diff --git a/.editorconfig b/.editorconfig index 879e6eebca..d506433ece 100644 --- a/.editorconfig +++ b/.editorconfig @@ -5,7 +5,7 @@ end_of_line = lf insert_final_newline = true trim_trailing_whitespace = true -[{*.py, *.pyx, *.pxd}] +[*.{py,pyx,pxd}] charset = utf-8 indent_style = space indent_size = 2 diff --git a/.github/labeler.yaml b/.github/labeler.yaml index db1f976da8..861c2efdbd 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -12,7 +12,7 @@ simulation: ui: - changed-files: - - any-glob-to-all-files: 'selfdrive/ui/**' + - any-glob-to-all-files: '{selfdrive/ui/**,system/ui/**}' tools: - changed-files: diff --git a/.gitignore b/.gitignore index 834b463083..40438f5fd0 100644 --- a/.gitignore +++ b/.gitignore @@ -47,10 +47,8 @@ selfdrive/pandad/pandad cereal/services.h cereal/gen cereal/messaging/bridge -selfdrive/logcatd/logcatd selfdrive/mapd/default_speeds_by_region.json system/proclogd/proclogd -selfdrive/ui/translations/alerts_generated.h selfdrive/ui/translations/tmp selfdrive/test/longitudinal_maneuvers/out selfdrive/car/tests/cars_dump diff --git a/Jenkinsfile b/Jenkinsfile index b1a0746ea3..a14bf59299 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -268,6 +268,8 @@ node { step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"), step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"), + // TODO: enable once new AGNOS is available + // step("test esim", "pytest system/hardware/tici/tests/test_esim.py"), step("test qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py", [diffPaths: ["system/qcomgpsd/"]]), ]) }, diff --git a/README.md b/README.md index 77002481d3..86cccafad9 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@

openpilot is an operating system for robotics.
- Currently, it upgrades the driver assistance system in 275+ supported cars. + Currently, it upgrades the driver assistance system in 300+ supported cars.

@@ -22,7 +22,7 @@ Quick start: `bash <(curl -fsSL openpilot.comma.ai)` -![openpilot tests](https://github.com/commaai/openpilot/actions/workflows/selfdrive_tests.yaml/badge.svg) +[![openpilot tests](https://github.com/commaai/openpilot/actions/workflows/selfdrive_tests.yaml/badge.svg)](https://github.com/commaai/openpilot/actions/workflows/selfdrive_tests.yaml) [![codecov](https://codecov.io/gh/commaai/openpilot/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/openpilot) [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](LICENSE) [![X Follow](https://img.shields.io/twitter/follow/comma_ai)](https://x.com/comma_ai) @@ -57,6 +57,7 @@ We have detailed instructions for [how to install the harness and device in a ca | `release3-staging` | openpilot-test.comma.ai | This is the staging branch for releases. Use it to get new releases slightly early. | | `nightly` | openpilot-nightly.comma.ai | This is the bleeding edge development branch. Do not expect this to be stable. | | `nightly-dev` | installer.comma.ai/commaai/nightly-dev | Same as nightly, but includes experimental development features for some cars. | +| `secretgoodopenpilot` | installer.comma.ai/commaai/secretgoodopenpilot | This is a preview branch from the autonomy team where new driving models get merged earlier than master. | To start developing openpilot ------ @@ -83,8 +84,8 @@ Safety and Testing * panda has additional hardware-in-the-loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). * We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. -Licensing ------- +
+MIT Licensed openpilot is released under the MIT license. Some parts of the software are released under other licenses as specified. @@ -93,9 +94,10 @@ Any user of this software shall indemnify and hold harmless Comma.ai, Inc. and i **THIS IS ALPHA QUALITY SOFTWARE FOR RESEARCH PURPOSES ONLY. THIS IS NOT A PRODUCT. YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. NO WARRANTY EXPRESSED OR IMPLIED.** +
-User Data and comma Account ------- +
+User Data and comma Account By default, openpilot uploads the driving data to our servers. You can also access your data through [comma connect](https://connect.comma.ai/). We use your data to train better models and improve openpilot for everyone. @@ -105,3 +107,4 @@ openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sen The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. By using openpilot, you agree to [our Privacy Policy](https://comma.ai/privacy). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma for the use of this data. +
diff --git a/RELEASES.md b/RELEASES.md index d16edf9860..5730877f94 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,14 @@ +Version 0.9.9 (2025-05-15) +======================== +* New driving model + * New training architecture supervised by MLSIM +* Steering actuator delay is now learned online +* Tesla Model 3 and Y support thanks to lukasloetkolben! +* Lexus RC 2023 support thanks to nelsonjchen! +* Coming soon + * New Honda models + * Bigger vision model + Version 0.9.8 (2025-02-28) ======================== * New driving model diff --git a/SConstruct b/SConstruct index c40f118985..d5597a70fe 100644 --- a/SConstruct +++ b/SConstruct @@ -55,11 +55,6 @@ AddOption('--external-sconscript', dest='external_sconscript', help='add an external SConscript to the build') -AddOption('--pc-thneed', - action='store_true', - dest='pc_thneed', - help='use thneed on pc') - AddOption('--mutation', action='store_true', help='generate mutation-ready code') @@ -288,12 +283,7 @@ else: elif arch != "Darwin": qt_libs += ["GL"] qt_env['QT3DIR'] = qt_env['QTDIR'] - -# compatibility for older SCons versions -try: - qt_env.Tool('qt3') -except SCons.Errors.UserError: - qt_env.Tool('qt') +qt_env.Tool('qt3') qt_env['CPPPATH'] += qt_dirs + ["#third_party/qrcode"] qt_flags = [ diff --git a/cereal/__init__.py b/cereal/__init__.py index 89c5cf38e3..93f4d77227 100644 --- a/cereal/__init__.py +++ b/cereal/__init__.py @@ -1,9 +1,11 @@ import os import capnp +from importlib.resources import as_file, files -CEREAL_PATH = os.path.dirname(os.path.abspath(__file__)) capnp.remove_import_hook() -log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) -car = capnp.load(os.path.join(CEREAL_PATH, "car.capnp")) -custom = capnp.load(os.path.join(CEREAL_PATH, "custom.capnp")) +with as_file(files("cereal")) as fspath: + CEREAL_PATH = fspath.as_posix() + log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) + car = capnp.load(os.path.join(CEREAL_PATH, "car.capnp")) + custom = capnp.load(os.path.join(CEREAL_PATH, "custom.capnp")) diff --git a/cereal/log.capnp b/cereal/log.capnp index 7b6076311f..9ab51e0b77 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -48,6 +48,7 @@ struct OnroadEvent @0xc4fa6047f024e718 { preEnableStandstill @12; # added during pre-enable state with brake gasPressedOverride @13; # added when user is pressing gas with no disengage on gas steerOverride @14; + steerDisengage @94; # exits active state cruiseDisabled @15; speedTooLow @16; outOfSpace @17; @@ -126,6 +127,7 @@ struct OnroadEvent @0xc4fa6047f024e718 { espActive @90; personalityChanged @91; aeb @92; + userFlag @95; soundsUnavailableDEPRECATED @47; } @@ -488,6 +490,7 @@ struct DeviceState @0xa4d8b5af2aa492eb { # device thermals cpuTempC @26 :List(Float32); gpuTempC @27 :List(Float32); + dspTempC @49 :Float32; memoryTempC @28 :Float32; nvmeTempC @35 :List(Float32); modemTempC @36 :List(Float32); @@ -1174,6 +1177,8 @@ struct ModelDataV2 { struct Action { desiredCurvature @0 :Float32; + desiredAcceleration @1 :Float32; + shouldStop @2 :Bool; } } @@ -1586,6 +1591,10 @@ struct UbloxGnss { svId @0 :UInt8; gnssId @1 :UInt8; flagsBitfield @2 :UInt32; + cno @3 :UInt8; + elevationDeg @4 :Int8; + azimuthDeg @5 :Int16; + pseudorangeResidual @6 :Float32; } } @@ -2274,6 +2283,22 @@ struct LiveTorqueParametersData { useParams @12 :Bool; } +struct LiveDelayData { + lateralDelay @0 :Float32; + validBlocks @1 :Int32; + status @2 :Status; + + lateralDelayEstimate @3 :Float32; + lateralDelayEstimateStd @5 :Float32; + points @4 :List(Float32); + + enum Status { + unestimated @0; + estimated @1; + invalid @2; + } +} + struct LiveMapDataDEPRECATED { speedLimitValid @0 :Bool; speedLimit @1 :Float32; @@ -2504,6 +2529,7 @@ struct Event { gnssMeasurements @91 :GnssMeasurements; liveParameters @61 :LiveParametersData; liveTorqueParameters @94 :LiveTorqueParametersData; + liveDelay @146 : LiveDelayData; cameraOdometry @63 :CameraOdometry; thumbnail @66: Thumbnail; onroadEvents @134: List(OnroadEvent); diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 8ad956b61b..b03285f80a 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -145,12 +145,16 @@ class SubMaster: self.updated = {s: False for s in services} self.recv_time = {s: 0. for s in services} self.recv_frame = {s: 0 for s in services} - self.alive = {s: False for s in services} - self.freq_ok = {s: False for s in services} self.sock = {} self.data = {} - self.valid = {} - self.logMonoTime = {} + self.logMonoTime = {s: 0 for s in services} + + # zero-frequency / on-demand services are always alive and presumed valid; all others must pass checks + on_demand = {s: SERVICE_LIST[s].frequency <= 1e-5 for s in services} + self.static_freq_services = set(s for s in services if not on_demand[s]) + self.alive = {s: on_demand[s] for s in services} + self.freq_ok = {s: on_demand[s] for s in services} + self.valid = {s: on_demand[s] for s in services} self.freq_tracker: Dict[str, FrequencyTracker] = {} self.poller = Poller() @@ -177,8 +181,6 @@ class SubMaster: data = new_message(s, 0) # lists self.data[s] = getattr(data.as_reader(), s) - self.logMonoTime[s] = 0 - self.valid[s] = False self.freq_tracker[s] = FrequencyTracker(SERVICE_LIST[s].frequency, self.update_freq, s == poll) def __getitem__(self, s: str) -> capnp.lib.capnp._DynamicStructReader: @@ -215,14 +217,10 @@ class SubMaster: self.logMonoTime[s] = msg.logMonoTime self.valid[s] = msg.valid - for s in self.services: - if SERVICE_LIST[s].frequency > 1e-5 and not self.simulation: - # alive if delay is within 10x the expected frequency - self.alive[s] = (cur_time - self.recv_time[s]) < (10. / SERVICE_LIST[s].frequency) - self.freq_ok[s] = self.freq_tracker[s].valid - else: - self.freq_ok[s] = True - self.alive[s] = self.seen[s] if self.simulation else True + for s in self.static_freq_services: + # alive if delay is within 10x the expected frequency; checks relaxed in simulator + self.alive[s] = (cur_time - self.recv_time[s]) < (10. / SERVICE_LIST[s].frequency) or (self.seen[s] and self.simulation) + self.freq_ok[s] = self.freq_tracker[s].valid or self.simulation def all_alive(self, service_list: Optional[List[str]] = None) -> bool: return all(self.alive[s] for s in (service_list or self.services) if s not in self.ignore_alive) diff --git a/cereal/messaging/tests/test_pub_sub_master.py b/cereal/messaging/tests/test_pub_sub_master.py index e9bc7a85cb..e47e713393 100644 --- a/cereal/messaging/tests/test_pub_sub_master.py +++ b/cereal/messaging/tests/test_pub_sub_master.py @@ -6,6 +6,7 @@ import cereal.messaging as messaging from cereal.messaging.tests.test_messaging import events, random_sock, random_socks, \ random_bytes, random_carstate, assert_carstate, \ zmq_sleep +from cereal.services import SERVICE_LIST class TestSubMaster: @@ -26,7 +27,9 @@ class TestSubMaster: sm = messaging.SubMaster(socks) assert sm.frame == -1 assert not any(sm.updated.values()) - assert not any(sm.alive.values()) + assert not any(sm.seen.values()) + on_demand = {s: SERVICE_LIST[s].frequency <= 1e-5 for s in sm.services} + assert all(sm.alive[s] == sm.valid[s] == sm.freq_ok[s] == on_demand[s] for s in sm.services) assert all(t == 0. for t in sm.recv_time.values()) assert all(f == 0 for f in sm.recv_frame.values()) assert all(t == 0 for t in sm.logMonoTime.values()) @@ -83,6 +86,7 @@ class TestSubMaster: "cameraOdometry": (20, 10), "liveCalibration": (4, 4), "carParams": (None, None), + "userFlag": (None, None), } for service, (max_freq, min_freq) in checks.items(): diff --git a/cereal/services.py b/cereal/services.py index aad83177bb..82fc04bd00 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -36,6 +36,7 @@ _services: dict[str, tuple] = { "errorLogMessage": (True, 0., 1), "liveCalibration": (True, 4., 4), "liveTorqueParameters": (True, 4., 1), + "liveDelay": (True, 4., 1), "androidLog": (True, 0.), "carState": (True, 100., 10), "carControl": (True, 100., 10), diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py deleted file mode 100644 index 01741c6f42..0000000000 --- a/common/ffi_wrapper.py +++ /dev/null @@ -1,8 +0,0 @@ -import platform - - -def suffix(): - if platform.system() == "Darwin": - return ".dylib" - else: - return ".so" diff --git a/common/filter_simple.py b/common/filter_simple.py index 0ec7a51562..9ea6fe3070 100644 --- a/common/filter_simple.py +++ b/common/filter_simple.py @@ -1,5 +1,4 @@ class FirstOrderFilter: - # first order filter def __init__(self, x0, rc, dt, initialized=True): self.x = x0 self.dt = dt diff --git a/common/params.cc b/common/params.cc index d1e5a36462..337be814b7 100644 --- a/common/params.cc +++ b/common/params.cc @@ -140,7 +140,7 @@ int Params::put(const char* key, const char* value, size_t value_size) { } // fsync to force persist the changes. - if ((result = fsync(tmp_fd)) < 0) break; + if ((result = HANDLE_EINTR(fsync(tmp_fd))) < 0) break; FileLock file_lock(params_path + "/.lock"); diff --git a/common/params_keys.h b/common/params_keys.h index 2b540b744c..ca779a5b5c 100644 --- a/common/params_keys.h +++ b/common/params_keys.h @@ -34,7 +34,7 @@ inline static std::unordered_map keys = { {"DoReboot", CLEAR_ON_MANAGER_START}, {"DoShutdown", CLEAR_ON_MANAGER_START}, {"DoUninstall", CLEAR_ON_MANAGER_START}, - {"ExperimentalLongitudinalEnabled", PERSISTENT | DEVELOPMENT_ONLY}, + {"AlphaLongitudinalEnabled", PERSISTENT | DEVELOPMENT_ONLY}, {"ExperimentalMode", PERSISTENT}, {"ExperimentalModeConfirmed", PERSISTENT}, {"FirmwareQueryDone", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, @@ -71,7 +71,9 @@ inline static std::unordered_map keys = { {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, {"LastUpdateException", CLEAR_ON_MANAGER_START}, {"LastUpdateTime", PERSISTENT}, + {"LiveDelay", PERSISTENT}, {"LiveParameters", PERSISTENT}, + {"LiveParametersV2", PERSISTENT}, {"LiveTorqueParameters", PERSISTENT | DONT_LOG}, {"LocationFilterInitialState", PERSISTENT}, {"LongitudinalManeuverMode", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, diff --git a/common/realtime.py b/common/realtime.py index 82176a00a6..57926b4c4f 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -1,6 +1,7 @@ """Utilities for reading real time clocks and keeping soft real time constraints.""" import gc import os +import sys import time from setproctitle import getproctitle @@ -28,13 +29,13 @@ class Priority: def set_core_affinity(cores: list[int]) -> None: - if not PC: + if sys.platform == 'linux' and not PC: os.sched_setaffinity(0, cores) def config_realtime_process(cores: int | list[int], priority: int) -> None: gc.disable() - if not PC: + if sys.platform == 'linux' and not PC: os.sched_setscheduler(0, os.SCHED_FIFO, os.sched_param(priority)) c = cores if isinstance(cores, list) else [cores, ] set_core_affinity(c) diff --git a/common/spinner.py b/common/spinner.py deleted file mode 100644 index dcf22641c4..0000000000 --- a/common/spinner.py +++ /dev/null @@ -1,52 +0,0 @@ -import os -import subprocess -from openpilot.common.basedir import BASEDIR - - -class Spinner: - def __init__(self): - try: - self.spinner_proc = subprocess.Popen(["./spinner"], - stdin=subprocess.PIPE, - cwd=os.path.join(BASEDIR, "selfdrive", "ui"), - close_fds=True) - except OSError: - self.spinner_proc = None - - def __enter__(self): - return self - - def update(self, spinner_text: str): - if self.spinner_proc is not None: - self.spinner_proc.stdin.write(spinner_text.encode('utf8') + b"\n") - try: - self.spinner_proc.stdin.flush() - except BrokenPipeError: - pass - - def update_progress(self, cur: float, total: float): - self.update(str(round(100 * cur / total))) - - def close(self): - if self.spinner_proc is not None: - self.spinner_proc.kill() - try: - self.spinner_proc.communicate(timeout=2.) - except subprocess.TimeoutExpired: - print("WARNING: failed to kill spinner") - self.spinner_proc = None - - def __del__(self): - self.close() - - def __exit__(self, exc_type, exc_value, traceback): - self.close() - - -if __name__ == "__main__": - import time - with Spinner() as s: - s.update("Spinner text") - time.sleep(5.0) - print("gone") - time.sleep(5.0) diff --git a/common/tests/test_simple_kalman.py b/common/tests/test_simple_kalman.py index f4a967e58a..e44ac2cc57 100644 --- a/common/tests/test_simple_kalman.py +++ b/common/tests/test_simple_kalman.py @@ -24,6 +24,6 @@ class TestSimpleKalman: self.kf.set_x([[1.0], [1.0]]) assert self.kf.x == [[1.0], [1.0]] - def update_returns_state(self): + def test_update_returns_state(self): x = self.kf.update(100) - assert x == self.kf.x + assert x == [i[0] for i in self.kf.x] diff --git a/common/text_window.py b/common/text_window.py deleted file mode 100755 index d2762ebf7d..0000000000 --- a/common/text_window.py +++ /dev/null @@ -1,63 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -import subprocess -from openpilot.common.basedir import BASEDIR - - -class TextWindow: - def __init__(self, text): - try: - self.text_proc = subprocess.Popen(["./text", text], - stdin=subprocess.PIPE, - cwd=os.path.join(BASEDIR, "selfdrive", "ui"), - close_fds=True) - except OSError: - self.text_proc = None - - def get_status(self): - if self.text_proc is not None: - self.text_proc.poll() - return self.text_proc.returncode - return None - - def __enter__(self): - return self - - def close(self): - if self.text_proc is not None: - self.text_proc.terminate() - self.text_proc = None - - def wait_for_exit(self): - if self.text_proc is not None: - while True: - if self.get_status() == 1: - return - time.sleep(0.1) - - def __del__(self): - self.close() - - def __exit__(self, exc_type, exc_value, traceback): - self.close() - - -if __name__ == "__main__": - text = """Traceback (most recent call last): - File "./controlsd.py", line 608, in - main() - File "./controlsd.py", line 604, in main - controlsd_thread(sm, pm, logcan) - File "./controlsd.py", line 455, in controlsd_thread - 1/0 -ZeroDivisionError: division by zero""" - print(text) - - with TextWindow(text) as s: - for _ in range(100): - if s.get_status() == 1: - print("Got exit button") - break - time.sleep(0.1) - print("gone") diff --git a/common/version.h b/common/version.h index 1f651fb392..6351a5b3ff 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.9.8" +#define COMMA_VERSION "0.9.9" diff --git a/docs/CARS.md b/docs/CARS.md index a3b1fe6351..cdaeb38890 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,328 +4,341 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 302 Supported Cars +# 312 Supported Cars -|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video| -|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| -|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|26 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Acura|RDX 2019-21|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chevrolet|Equinox 2019-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chevrolet|Trailblazer 2021-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica 2021-23|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica Hybrid 2019-24|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None|| -|CUPRA|Ateca 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Bronco Sport 2021-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Explorer 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Explorer Hybrid 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|F-150 2021-23|Co-Pilot360 Assist 2.0|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|F-150 Hybrid 2021-23|Co-Pilot360 Assist 2.0|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Focus 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Focus Hybrid 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick Hybrid 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick Hybrid 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Mustang Mach-E 2021-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Ranger 2024|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G70 2018|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G70 2019-21|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G70 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G80 2017|All|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G80 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|G90 2017-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV60 (Advanced Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV60 (Performance Trim) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV70 (2.5T Trim, without HDA II) 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV70 (3.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV70 Electrified (Australia Only) 2022[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV70 Electrified (with HDA II) 2023-24[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV80 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[4](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Civic 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Civic Hatchback 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|CR-V 2015-16|Touring Trim|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|CR-V Hybrid 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Fit 2018-20|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Freed 2020|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|HR-V 2019-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|HR-V 2023|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Insight 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Inspire 2018|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Odyssey 2018-20|Honda Sensing|openpilot|26 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Passport 2019-23|All|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Pilot 2016-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Ridgeline 2017-25|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Azera 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Azera Hybrid 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Azera Hybrid 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Custin 2023|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Elantra 2017-18|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Elantra 2019|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Elantra 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Elantra GT 2017-20|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq 5 (Southeast Asia and Europe only) 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq 5 (with HDA II) 2022-24[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq 5 (without HDA II) 2022-24[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq 6 (with HDA II) 2023-24[5](#footnotes)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Electric 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai O connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai O connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona Electric (with HDA II, Korea only) 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai R connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai I connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Nexo 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Cruz 2022-24[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Fe 2021-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Fe Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Fe Plug-in Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Sonata Hybrid 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Staria 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson 2022[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson 2023-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson Hybrid 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson Plug-in Hybrid 2024[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Carnival 2022-24[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Carnival (China only) 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Ceed 2019-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|EV6 (Southeast Asia only) 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|EV6 (with HDA II) 2022-24[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|EV6 (without HDA II) 2022-24[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Forte 2022-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|K5 2021-24|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|K5 Hybrid 2020-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|K8 Hybrid (with HDA II) 2023[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro EV 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro EV 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro EV 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Hybrid 2018|All|Stock|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Plug-in Hybrid 2018-19|All|Stock|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Plug-in Hybrid 2020|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Plug-in Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Plug-in Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Optima Hybrid 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sorento 2018|Advanced Smart Cruise Control & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sorento 2021-23[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sorento Hybrid 2021-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sorento Plug-in Hybrid 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sportage 2023-24[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sportage Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Stinger 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Telluride 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES Hybrid 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES Hybrid 2019-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|GS F 2016|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|IS 2022-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|LC 2024|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|NX 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|NX Hybrid 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RC 2018-20|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|UX Hybrid 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lincoln|Aviator 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lincoln|Aviator Plug-in Hybrid 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|eTGE 2020-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|TGE 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Mazda|CX-5 2022-25|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Nissan|Leaf 2018-23|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ram|1500 2019-24|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ram connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Rivian|R1S 2022-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Rivian A connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Rivian|R1T 2022-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Rivian A connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Ateca 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Ascent 2019-21|All[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Forester 2019-21|All[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Impreza 2017-19|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Impreza 2020-22|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Legacy 2020-22|All[6](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Outback 2020-22|All[6](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|XV 2018-19|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|XV 2020-21|EyeSight Driver Assistance[6](#footnotes)|openpilot available[1,7](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Škoda|Fabia 2022-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Škoda|Kamiq 2021-23[10,12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Škoda|Karoq 2019-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Kodiaq 2017-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia 2015-19[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia RS 2016[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia Scout 2017-19[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Scala 2020-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Škoda|Superb 2015-22[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Tesla|Model 3 (with HW3) 2019-23[8](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Tesla|Model 3 (with HW4) 2024[8](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Tesla|Model Y (with HW3) 2020-23[8](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Tesla|Model Y (with HW4) 2024[8](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon Hybrid 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR Hybrid 2021-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2018-20|All|Stock|0 mph[9](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2021-24|All|openpilot|0 mph[9](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry Hybrid 2021-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla Cross (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Corolla Hybrid (South America only) 2020-23|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Highlander 2020-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Highlander Hybrid 2020-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius Prime 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Prius v 2017|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2023-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2023-25|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon Shooting Brake 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas Cross Sport 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|California 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Crafter 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Crafter 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Grand California 2019-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta GLI 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat 2015-22[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| -|Volkswagen|T-Roc 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video|Setup Video| +|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:|:---:| +|Acura|ILX 2016-18|Technology Plus Package or AcuraWatch Plus|openpilot|26 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Acura|ILX 2019|All|openpilot|26 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Acura|RDX 2016-18|AcuraWatch Plus or Advance Package|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Acura|RDX 2019-21|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chevrolet|Equinox 2019-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chevrolet|Trailblazer 2021-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chrysler|Pacifica 2021-23|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Chrysler|Pacifica Hybrid 2019-24|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None||| +|CUPRA|Ateca 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Bronco Sport 2021-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Escape 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Escape 2023-24|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Escape Hybrid 2023-24|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Escape Plug-in Hybrid 2023-24|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Explorer 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Explorer Hybrid 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|F-150 2021-23|Co-Pilot360 Assist 2.0|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=MewJc9LYp9M| +|Ford|F-150 Hybrid 2021-23|Co-Pilot360 Assist 2.0|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=MewJc9LYp9M| +|Ford|Focus 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Focus Hybrid 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Kuga 2020-23|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Kuga Hybrid 2020-23|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Kuga Hybrid 2024|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Kuga Plug-in Hybrid 2020-23|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Kuga Plug-in Hybrid 2024|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Maverick 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Maverick 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Maverick Hybrid 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Maverick Hybrid 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ford|Mustang Mach-E 2021-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Ford|Ranger 2024|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q4 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://www.youtube.com/watch?v=uUGkH6C_EQU| +|Genesis|G70 2018|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G70 2019-21|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G70 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G80 2017|All|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G80 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|G90 2017-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV60 (Advanced Trim) 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV60 (Performance Trim) 2022-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV70 (2.5T Trim, without HDA II) 2022-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV70 (3.5T Trim, without HDA II) 2022-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV70 Electrified (Australia Only) 2022[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV70 Electrified (with HDA II) 2023-24[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Genesis|GV80 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[5](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback Hybrid 2023 (Europe only)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback Hybrid 2025|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|CR-V 2015-16|Touring Trim|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|CR-V Hybrid 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Fit 2018-20|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Freed 2020|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|HR-V 2019-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|HR-V 2023-25|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Insight 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Inspire 2018|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Odyssey 2018-20|Honda Sensing|openpilot|26 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Passport 2019-25|All|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Pilot 2016-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Ridgeline 2017-25|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Azera 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Azera Hybrid 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Azera Hybrid 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Custin 2023|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Elantra 2017-18|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Elantra 2019|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Elantra 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Elantra GT 2017-20|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq 5 (Southeast Asia and Europe only) 2022-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq 5 (with HDA II) 2022-24[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq 5 (without HDA II) 2022-24[6](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq 6 (with HDA II) 2023-24[6](#footnotes)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Electric 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai O connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai O connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona Electric (with HDA II, Korea only) 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai R connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai I connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Nexo 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Santa Cruz 2022-24[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Santa Fe 2021-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Santa Fe Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Santa Fe Plug-in Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Sonata Hybrid 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Staria 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson 2022[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson 2023-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson Hybrid 2022-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Tucson Plug-in Hybrid 2024[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Carnival 2022-24[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Carnival (China only) 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Ceed 2019-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|EV6 (Southeast Asia only) 2022-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|EV6 (with HDA II) 2022-24[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|EV6 (without HDA II) 2022-24[6](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Forte 2022-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|K5 2021-24|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|K5 Hybrid 2020-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|K8 Hybrid (with HDA II) 2023[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV (with HDA II) 2025[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai R connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro EV (without HDA II) 2023-25[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Hybrid 2018|All|Stock|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Hybrid 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Plug-in Hybrid 2018-19|All|Stock|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Plug-in Hybrid 2020|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Plug-in Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Niro Plug-in Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Optima Hybrid 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sorento 2018|Advanced Smart Cruise Control & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sorento 2021-23[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sorento Hybrid 2021-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sorento Plug-in Hybrid 2022-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sportage 2023-24[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Sportage Hybrid 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Stinger 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Kia|Telluride 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|ES 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|ES 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|ES Hybrid 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|ES Hybrid 2019-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|GS F 2016|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|IS 2022-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|LC 2024|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|NX 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|NX Hybrid 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RC 2018-20|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RC 2023|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lexus|UX Hybrid 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lincoln|Aviator 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Lincoln|Aviator Plug-in Hybrid 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|MAN|eTGE 2020-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|MAN|TGE 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Mazda|CX-5 2022-25|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Nissan[7](#footnotes)|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Nissan[7](#footnotes)|Leaf 2018-23|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Nissan[7](#footnotes)|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Nissan[7](#footnotes)|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Ram|1500 2019-24|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ram connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Rivian|R1S 2022-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Rivian A connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://youtu.be/uaISd1j7Z4U| +|Rivian|R1T 2022-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Rivian A connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||https://youtu.be/uaISd1j7Z4U| +|SEAT|Ateca 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Subaru|Ascent 2019-21|All[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Forester 2019-21|All[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Legacy 2020-22|All[8](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|Outback 2020-22|All[8](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|XV 2018-19|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Subaru|XV 2020-21|EyeSight Driver Assistance[8](#footnotes)|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
||| +|Škoda|Fabia 2022-23[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Škoda|Kamiq 2021-23[13,15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Škoda|Karoq 2019-23[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Škoda|Kodiaq 2017-23[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Škoda|Octavia 2015-19[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Škoda|Octavia RS 2016[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Škoda|Octavia Scout 2017-19[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Škoda|Scala 2020-23[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Škoda|Superb 2015-22[15](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Tesla[11](#footnotes)|Model 3 (with HW3) 2019-23[10](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Tesla[11](#footnotes)|Model 3 (with HW4) 2024-25[10](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Tesla[11](#footnotes)|Model Y (with HW3) 2020-23[10](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla A connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Tesla[11](#footnotes)|Model Y (with HW4) 2024[10](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Tesla B connector
- 1 USB-C coupler
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon Hybrid 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|C-HR 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|C-HR 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|C-HR Hybrid 2021-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Camry 2018-20|All|Stock|0 mph[12](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Camry 2021-24|All|openpilot|0 mph[12](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Camry Hybrid 2021-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla Cross (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Corolla Hybrid (South America only) 2020-23|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Highlander 2020-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Highlander Hybrid 2020-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius Prime 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Prius v 2017|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 2023-25|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 Hybrid 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|RAV4 Hybrid 2023-25|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Arteon Shooting Brake 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Atlas Cross Sport 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|California 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Crafter 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|e-Crafter 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Grand California 2019-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Jetta 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Jetta GLI 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Passat 2015-22[14](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[17](#footnotes)||| +|Volkswagen|T-Roc 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| ### Footnotes 1openpilot Longitudinal Control (Alpha) is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `nightly-dev`.
2By default, this car will use the stock Adaptive Cruise Control (ACC) for longitudinal control. If the Driver Support Unit (DSU) is disconnected, openpilot ACC will replace stock ACC. NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).
3Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in North and South America/Southeast Asia.
-42019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
-5Requires a CAN FD panda kit if not using comma 3X for this CAN FD car.
-6In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.
-7Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.
-8Some 2023 model years have HW4. To check which hardware type your vehicle has, look for Autopilot computer under Software -> Additional Vehicle Information on your vehicle's touchscreen. See this page for more information.
-9openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
-10Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
-11Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
-12Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma 3X functionality.
-13Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
-14Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
+4See more setup details for GM.
+52019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
+6Requires a CAN FD panda kit if not using comma 3X for this CAN FD car.
+7See more setup details for Nissan.
+8In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.
+9Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.
+10Some 2023 model years have HW4. To check which hardware type your vehicle has, look for Autopilot computer under Software -> Additional Vehicle Information on your vehicle's touchscreen. See this page for more information.
+11See more setup details for Tesla.
+12openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
+13Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
+14Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
+15Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma 3X functionality.
+16Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
+17Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
## Community Maintained Cars Although they're not upstream, the community has openpilot running on other makes and models. See the 'Community Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). diff --git a/docs/SAFETY.md b/docs/SAFETY.md index 4b568728a7..18a450a395 100644 --- a/docs/SAFETY.md +++ b/docs/SAFETY.md @@ -25,9 +25,9 @@ ensuring two main safety requirements. by stepping on the brake pedal or by pressing the cancel button. 2. The vehicle must not alter its trajectory too quickly for the driver to safely react. This means that while the system is engaged, the actuators are constrained - to operate within reasonable limits[^1]. + to operate within reasonable limits[^1]. -For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [panda/board/safety/](https://github.com/commaai/panda/tree/master/board/safety). +For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [opendbc/safety/safety](https://github.com/commaai/opendbc/tree/master/opendbc/safety/safety). **Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or not fully meeting the above requirements. diff --git a/docs/WORKFLOW.md b/docs/WORKFLOW.md index 477c7511ca..1c5bbe9a63 100644 --- a/docs/WORKFLOW.md +++ b/docs/WORKFLOW.md @@ -31,13 +31,3 @@ cd system/loggerd && pytest . # run the linter op lint ``` - -## Testing - -### Automated Testing - -All PRs and commits are automatically checked by GitHub Actions. Check out `.github/workflows/` for what GitHub Actions runs. Any new tests should be added to GitHub Actions. - -### Code Style and Linting - -Code is automatically checked for style by GitHub Actions as part of the automated tests. You can also run these tests yourself by running `pre-commit run --all`. diff --git a/docs/assets/three-back.svg b/docs/assets/three-back.svg new file mode 100644 index 0000000000..e5e8f9c1fc --- /dev/null +++ b/docs/assets/three-back.svg @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/docs/contributing/roadmap.md b/docs/contributing/roadmap.md index 7086d85b85..1262017a0b 100644 --- a/docs/contributing/roadmap.md +++ b/docs/contributing/roadmap.md @@ -12,7 +12,7 @@ This is the roadmap for the next major openpilot releases. Also check out openpilot 0.10 will be the first release with a driving policy trained in a [learned simulator](https://youtu.be/EqQNZXqzFSI). -* Driving model trained in a learned simlator +* Driving model trained in a learned simulator * Always-on driver monitoring (behind a toggle) * GPS removed from the driving stack * 100KB qlogs diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md index 469ef81672..cbaccaae6a 100644 --- a/docs/how-to/connect-to-comma.md +++ b/docs/how-to/connect-to-comma.md @@ -32,9 +32,13 @@ For doing development work on device, it's recommended to use [SSH agent forward ## ADB -In order to use ADB on your device, you'll need to enable it in the device's settings. +In order to use ADB on your device, you'll need to perform the following steps using the image below for reference: +![comma 3/3x back](../assets/three-back.svg) + +* Plug your device into constant power using port 2, letting the device boot up * Enable ADB in your device's settings +* Plug in your device to your PC using port 1 * Connect to your device * `adb shell` over USB * `adb connect` over WiFi diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md index e8b55ef81b..64f4475dfa 100644 --- a/docs/how-to/turn-the-speed-blue.md +++ b/docs/how-to/turn-the-speed-blue.md @@ -20,7 +20,7 @@ source .venv/bin/activate Then, compile openpilot: ```bash -scons -j8 +scons -j$(nproc) ``` ## 2. Run replay @@ -38,61 +38,77 @@ The openpilot UI should launch and show a replay of the demo route. If you have your own comma device, you can replace `--demo` with one of your own routes from comma connect. + ## 3. Make the speed blue -Search for “mph” with git grep in the `ui` folder. -```bash -$ git grep "mph" selfdrive/ui/ -paint.cc: ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular"); -``` +Now let’s update the speed display color in the UI. -The line right above contains the actual speed. Unfortunately, COLOR_BLUE isn’t defined, but a git grep of COLOR_WHITE shows it’s nvgRGBA(255, 255, 255, 255). Personally, I like a lighter blue, so I went with #8080FF. +Search for the function responsible for rendering UI text: ```bash -$ git diff -diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc -index 821d95115..cc996eaa1 100644 ---- a/selfdrive/ui/paint.cc -+++ b/selfdrive/ui/paint.cc -@@ -175,8 +175,8 @@ static void ui_draw_vision_speed(UIState *s) { - const float speed = std::max(0.0, (*s->sm)["carState"].getCarState().getVEgo() * (s->scene.is_metric ? 3.6 : 2.2369363)); - const std::string speed_str = std::to_string((int)std::nearbyint(speed)); - nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); -- ui_draw_text(s, s->fb_w/2, 210, speed_str.c_str(), 96 * 2.5, COLOR_WHITE, "sans-bold"); -- ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular"); -+ ui_draw_text(s, s->fb_w/2, 210, speed_str.c_str(), 96 * 2.5, nvgRGBA(128, 128, 255, 255), "sans-bold"); -+ ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, nvgRGBA(128, 128, 255, 200), "sans-regular"); - } - - static void ui_draw_vision_event(UIState *s) { +git grep "drawText" selfdrive/ui/qt/onroad/hud.cc ``` +You’ll find the relevant code inside `selfdrive/ui/qt/onroad/hud.cc`, in this function: -## 4. Rebuild UI, and admire your work +```cpp +void HudRenderer::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)); // <- this sets the speed text color + p.drawText(real_rect.x(), real_rect.bottom(), text); +} ``` -scons -j8 && selfdrive/ui/ui + +Change the `QColor(...)` line to make it **blue** instead of white. A nice soft blue is `#8080FF`, which translates to: + +```diff +- p.setPen(QColor(0xff, 0xff, 0xff, alpha)); ++ p.setPen(QColor(0x80, 0x80, 0xFF, alpha)); ``` +This change will tint all speed-related UI text to blue with the same transparency (`alpha`). + +--- + +## 4. Rebuild the UI + +After making changes, rebuild Openpilot so your new UI is compiled: +```bash +scons -j$(nproc) && selfdrive/ui/ui +``` ![](https://blog.comma.ai/img/blue_speed_ui.png) +You should now see the speed displayed in a nice blue shade during the demo replay. + +--- + ## 5. Push your fork to GitHub -Click fork on GitHub. Then, push with: +Click **"Fork"** on the [Openpilot GitHub repo](https://github.com/commaai/openpilot). Then push with: ```bash git remote rm origin git remote add origin git@github.com:/openpilot.git git add . -git commit -m "Make the speed blue." +git commit -m "Make the speed display blue" git push --set-upstream origin master ``` -## 6. Run your fork on device in your car! +--- -Uninstall openpilot from your device through the settings. Then, enter the URL for your very own installer: +## 6. Run your fork on your comma device + +Uninstall Openpilot through the settings on your device. + +Then reinstall using your own GitHub-hosted fork: ``` installer.comma.ai//master ``` -## 7. Admire your work IRL +--- + +## 7. Admire your work IRL 🚗💨 + +You’ve now successfully modified Openpilot’s UI and deployed it to your own car! ![](https://blog.comma.ai/img/c3_blue_ui.jpg) diff --git a/git_src_commit b/git_src_commit index d8af0b5cbe..a0f1c068d1 100644 --- a/git_src_commit +++ b/git_src_commit @@ -1 +1 @@ -fb7b9c0f9420d228f03362970ebcfb7237095cf3 \ No newline at end of file +312658756dbe16b802a90b2e9e9d8d8dcc868779 \ No newline at end of file diff --git a/git_src_commit_date b/git_src_commit_date index 99a769d9f9..1c4199c1ec 100644 --- a/git_src_commit_date +++ b/git_src_commit_date @@ -1 +1 @@ -1742072523 2025-03-15 14:02:03 -0700 \ No newline at end of file +1747964035 2025-05-23 01:33:55 +0000 \ No newline at end of file diff --git a/launch_env.sh b/launch_env.sh index 9bee47837a..6f31fcf776 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="11.11" + export AGNOS_VERSION="12.2" fi export STAGING_ROOT="/data/safe_staging" diff --git a/msgq_repo/msgq/tests/test_messaging.py b/msgq_repo/msgq/tests/test_messaging.py index 40dfd7f00e..b3fee36d85 100644 --- a/msgq_repo/msgq/tests/test_messaging.py +++ b/msgq_repo/msgq/tests/test_messaging.py @@ -52,9 +52,11 @@ class TestPubSubSockets: recvd_msgs = msgq.drain_sock_raw(sub_sock) if conflate: assert len(recvd_msgs) == 1 + assert recvd_msgs[0] == sent_msgs[-1] else: - # TODO: compare actual data assert len(recvd_msgs) == len(sent_msgs) + for rec_msg, sent_msg in zip(recvd_msgs, sent_msgs): + assert rec_msg == sent_msg def test_receive_timeout(self): sock = random_sock() diff --git a/opendbc_repo/.gitignore b/opendbc_repo/.gitignore index cb96f08721..96cb76aca6 100644 --- a/opendbc_repo/.gitignore +++ b/opendbc_repo/.gitignore @@ -15,8 +15,9 @@ *.html *.gcda *.gcno - +*.dump uv.lock +/dist/ opendbc/can/build/ opendbc/can/obj/ diff --git a/opendbc_repo/.pre-commit-config.yaml b/opendbc_repo/.pre-commit-config.yaml deleted file mode 100644 index 80bb697e4e..0000000000 --- a/opendbc_repo/.pre-commit-config.yaml +++ /dev/null @@ -1,37 +0,0 @@ -repos: -- repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.5.0 - hooks: - - id: check-ast - - id: check-yaml - - id: check-merge-conflict - - id: check-symlinks - - id: check-executables-have-shebangs - - id: check-shebang-scripts-are-executable -- repo: https://github.com/codespell-project/codespell - rev: v2.3.0 - hooks: - - id: codespell - exclude: '\.dbc$' -- repo: https://github.com/pre-commit/mirrors-mypy - rev: v1.11.1 - hooks: - - id: mypy -- repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.5.7 - hooks: - - id: ruff -- repo: https://github.com/MarcoGorelli/cython-lint - rev: v0.16.0 - hooks: - - id: cython-lint - - id: double-quote-cython-strings -- repo: https://github.com/cpplint/cpplint - rev: 1.6.1 - hooks: - - id: cpplint - args: - - --quiet - - --counting=detailed - - --linelength=240 - - --filter=-build,-legal,-readability,-runtime,-whitespace,+build/include_subdir,+build/forward_decl,+build/include_what_you_use,+build/deprecated,+whitespace/comma,+whitespace/line_length,+whitespace/empty_if_body,+whitespace/empty_loop_body,+whitespace/empty_conditional_body,+whitespace/forcolon,+whitespace/parens,+whitespace/semicolon,+whitespace/tab,+readability/braces diff --git a/opendbc_repo/MANIFEST.in b/opendbc_repo/MANIFEST.in index 288657b949..a8583dc97b 100644 --- a/opendbc_repo/MANIFEST.in +++ b/opendbc_repo/MANIFEST.in @@ -1,2 +1,3 @@ include opendbc/car/car.capnp include opendbc/car/include/c++.capnp +recursive-include opendbc/safety *.h diff --git a/opendbc_repo/README.md b/opendbc_repo/README.md index 8829a2e87a..5ce4591c18 100644 --- a/opendbc_repo/README.md +++ b/opendbc_repo/README.md @@ -47,7 +47,7 @@ cd opendbc pip3 install -e .[testing,docs] # install dependencies scons -j8 # build with 8 cores pytest . # run the tests -pre-commit run --all-files # run the linter +lefthook run lint # run the linter ``` [`examples/`](examples/) contains small example programs that can read state from the car and control the steering, gas, and brakes. @@ -75,9 +75,9 @@ If you're not so lucky, start with a "developer harness" from comma.ai/shop and ### Structure of a port -Depending on , most of this basic structure will already be in place. +Depending on the brand, most of this basic structure will already be in place. -The entirery of a car port lives in `opendbc/car//`: +The entirety of a car port lives in `opendbc/car//`: * `carstate.py`: parses out the relevant information from the CAN stream using the car's DBC file * `carcontroller.py`: outputs CAN messages to control the car * `can.py`: thin Python helpers around the DBC file to build CAN messages diff --git a/opendbc_repo/docs/CARS.md b/opendbc_repo/docs/CARS.md index d264c5ea95..93d325ab59 100644 --- a/opendbc_repo/docs/CARS.md +++ b/opendbc_repo/docs/CARS.md @@ -1,12 +1,13 @@ -# Support Information for 350 Known Cars +# Support Information for 361 Known Cars |Make|Model|Package|Support Level| |---|---|---|:---:| -|Acura|ILX 2016-19|AcuraWatch Plus|[Upstream](#upstream)| +|Acura|ILX 2016-18|Technology Plus Package or AcuraWatch Plus|[Upstream](#upstream)| +|Acura|ILX 2019|All|[Upstream](#upstream)| |Acura|Integra 2024|All|[Community](#community)| -|Acura|RDX 2016-18|AcuraWatch Plus|[Upstream](#upstream)| +|Acura|RDX 2016-18|AcuraWatch Plus or Advance Package|[Upstream](#upstream)| |Acura|RDX 2019-21|All|[Upstream](#upstream)| |Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| |Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| @@ -32,17 +33,22 @@ |Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| |Ford|Bronco Sport 2021-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|Escape 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape 2023-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape Hybrid 2023-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape Plug-in Hybrid 2023-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|Explorer 2020-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|Explorer Hybrid 2020-24|Co-Pilot360 Assist+|[Upstream](#upstream)| |Ford|F-150 2021-23|Co-Pilot360 Assist 2.0|[Upstream](#upstream)| |Ford|F-150 Hybrid 2021-23|Co-Pilot360 Assist 2.0|[Upstream](#upstream)| |Ford|Focus 2018|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| |Ford|Focus Hybrid 2018|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| -|Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| -|Ford|Kuga Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| -|Ford|Kuga Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga 2020-23|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga Hybrid 2020-23|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga Hybrid 2024|All|[Upstream](#upstream)| +|Ford|Kuga Plug-in Hybrid 2020-23|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga Plug-in Hybrid 2024|All|[Upstream](#upstream)| |Ford|Maverick 2022|LARIAT Luxury|[Upstream](#upstream)| |Ford|Maverick 2023-24|Co-Pilot360 Assist|[Upstream](#upstream)| |Ford|Maverick Hybrid 2022|LARIAT Luxury|[Upstream](#upstream)| @@ -73,6 +79,8 @@ |Honda|Civic 2022-24|All|[Upstream](#upstream)| |Honda|Civic Hatchback 2017-21|Honda Sensing|[Upstream](#upstream)| |Honda|Civic Hatchback 2022-24|All|[Upstream](#upstream)| +|Honda|Civic Hatchback Hybrid 2023 (Europe only)|All|[Upstream](#upstream)| +|Honda|Civic Hatchback Hybrid 2025|All|[Upstream](#upstream)| |Honda|Clarity 2018-21|All|[Community](#community)| |Honda|CR-V 2015-16|Touring Trim|[Upstream](#upstream)| |Honda|CR-V 2017-22|Honda Sensing|[Upstream](#upstream)| @@ -83,13 +91,14 @@ |Honda|Fit 2018-20|Honda Sensing|[Upstream](#upstream)| |Honda|Freed 2020|Honda Sensing|[Upstream](#upstream)| |Honda|HR-V 2019-22|Honda Sensing|[Upstream](#upstream)| -|Honda|HR-V 2023|All|[Upstream](#upstream)| +|Honda|HR-V 2023-25|All|[Upstream](#upstream)| |Honda|Insight 2019-22|All|[Upstream](#upstream)| |Honda|Inspire 2018|All|[Upstream](#upstream)| |Honda|Odyssey 2018-20|Honda Sensing|[Upstream](#upstream)| |Honda|Odyssey 2021-25|All|[Community](#community)| -|Honda|Passport 2019-23|All|[Upstream](#upstream)| +|Honda|Passport 2019-25|All|[Upstream](#upstream)| |Honda|Pilot 2016-22|Honda Sensing|[Upstream](#upstream)| +|Honda|Pilot 2023|All|[Dashcam mode](#dashcam)| |Honda|Pilot 2023-24|All|[Community](#community)| |Honda|Ridgeline 2017-25|Honda Sensing|[Upstream](#upstream)| |Hyundai|Azera 2022|All|[Upstream](#upstream)| @@ -155,7 +164,8 @@ |Kia|Niro EV 2020|All|[Upstream](#upstream)| |Kia|Niro EV 2021|All|[Upstream](#upstream)| |Kia|Niro EV 2022|All|[Upstream](#upstream)| -|Kia|Niro EV 2023|All|[Upstream](#upstream)| +|Kia|Niro EV (with HDA II) 2025|Highway Driving Assist II|[Upstream](#upstream)| +|Kia|Niro EV (without HDA II) 2023-25|All|[Upstream](#upstream)| |Kia|Niro Hybrid 2018|All|[Upstream](#upstream)| |Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|[Upstream](#upstream)| |Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|[Upstream](#upstream)| @@ -195,6 +205,7 @@ |Lexus|NX Hybrid 2018-19|All|[Upstream](#upstream)| |Lexus|NX Hybrid 2020-21|All|[Upstream](#upstream)| |Lexus|RC 2018-20|All|[Upstream](#upstream)| +|Lexus|RC 2023|All|[Upstream](#upstream)| |Lexus|RX 2016|Lexus Safety System+|[Upstream](#upstream)| |Lexus|RX 2017-19|All|[Upstream](#upstream)| |Lexus|RX 2020-22|All|[Upstream](#upstream)| @@ -254,7 +265,7 @@ |Škoda|Scala 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| |Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| |Tesla|Model 3 (with HW3) 2019-23|All|[Upstream](#upstream)| -|Tesla|Model 3 (with HW4) 2024|All|[Upstream](#upstream)| +|Tesla|Model 3 (with HW4) 2024-25|All|[Upstream](#upstream)| |Tesla|Model Y (with HW3) 2020-23|All|[Upstream](#upstream)| |Tesla|Model Y (with HW4) 2024|All|[Upstream](#upstream)| |Toyota|Alphard 2019-20|All|[Upstream](#upstream)| @@ -299,7 +310,7 @@ |Toyota|RAV4 2017-18|All|[Upstream](#upstream)| |Toyota|RAV4 2019-21|All|[Upstream](#upstream)| |Toyota|RAV4 2022|All|[Upstream](#upstream)| -|Toyota|RAV4 2023-24|All|[Upstream](#upstream)| +|Toyota|RAV4 2023-25|All|[Upstream](#upstream)| |Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|[Upstream](#upstream)| |Toyota|RAV4 Hybrid 2017-18|All|[Upstream](#upstream)| |Toyota|RAV4 Hybrid 2019-21|All|[Upstream](#upstream)| diff --git a/opendbc_repo/lefthook.yml b/opendbc_repo/lefthook.yml new file mode 100644 index 0000000000..ef01db0da2 --- /dev/null +++ b/opendbc_repo/lefthook.yml @@ -0,0 +1,30 @@ +output: + - meta # Print lefthook version + - summary # Print summary block (successful and failed steps) + - empty_summary # Print summary heading when there are no steps to run + - success # Print successful steps + - failure # Print failed steps printing + #- execution # Print any execution logs + #- execution_out # Print execution output + #- execution_info # Print `EXECUTE > ...` logging + - skips # Print "skip" (i.e. no files matched) + +test: + parallel: true + commands: + # *** static analysis + ruff: + run: ruff check . + cython-lint: + run: cython-lint opendbc/ + codespell: + run: codespell {files} -L tge,stdio -S *.dbc + files: git ls-tree -r HEAD --name-only + cpplint: + run: cpplint --exclude=opendbc/safety/tests/misra/cppcheck/ --exclude=opendbc/can/*_pyx.cpp --recursive --quiet --counting=detailed --linelength=240 --filter=-build,-legal,-readability,-runtime,-whitespace,+build/include_subdir,+build/forward_decl,+build/include_what_you_use,+build/deprecated,+whitespace/comma,+whitespace/line_length,+whitespace/empty_if_body,+whitespace/empty_loop_body,+whitespace/empty_conditional_body,+whitespace/forcolon,+whitespace/parens,+whitespace/semicolon,+whitespace/tab,+readability/braces opendbc/ + misra: + run: opendbc/safety/tests/misra/test_misra.sh + + # *** tests *** + pytest: + run: pytest -n8 diff --git a/opendbc_repo/opendbc/__init__.py b/opendbc_repo/opendbc/__init__.py index a40e5dbfa8..9f4ee6588b 100644 --- a/opendbc_repo/opendbc/__init__.py +++ b/opendbc_repo/opendbc/__init__.py @@ -1,3 +1,6 @@ import os DBC_PATH = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'dbc') + +# -I include path for e.g. "#include " +INCLUDE_PATH = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) diff --git a/opendbc_repo/opendbc/can/common.cc b/opendbc_repo/opendbc/can/common.cc index 9295db6930..7b5a5a8bc8 100644 --- a/opendbc_repo/opendbc/can/common.cc +++ b/opendbc_repo/opendbc/can/common.cc @@ -1,8 +1,30 @@ #include +#include +#include #include +#include #include "opendbc/can/common.h" +void pedal_setup_signal(Signal &sig, const std::string& dbc_name, int line_num) { + if (sig.name == "CHECKSUM_PEDAL") { + DBC_ASSERT(sig.size == 8, "INTERCEPTOR CHECKSUM is not 8 bits long"); + sig.type = PEDAL_CHECKSUM; + } else if (sig.name == "COUNTER_PEDAL") { + DBC_ASSERT(sig.size == 4, "INTERCEPTOR COUNTER is not 4 bits long"); + sig.type = COUNTER; + } +} + +void tesla_setup_signal(Signal &sig, const std::string& dbc_name, int line_num) { + if (endswith(sig.name, "Counter")) { + sig.type = COUNTER; + } else if (endswith(sig.name, "Checksum")) { + sig.type = TESLA_CHECKSUM; + sig.calc_checksum = &tesla_checksum; + } +} + unsigned int honda_checksum(uint32_t address, const Signal &sig, const std::vector &d) { int s = 0; bool extended = address > 0x7FF; @@ -257,3 +279,16 @@ unsigned int fca_giorgio_checksum(uint32_t address, const Signal &sig, const std } } + +unsigned int tesla_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + uint8_t checksum = (address & 0xFF) + ((address >> 8) & 0xFF); + int checksum_byte = sig.start_bit / 8; + + for (int i = 0; i < d.size(); i++) { + if (i != checksum_byte) { + checksum += d[i]; + } + } + + return checksum & 0xFF; +} diff --git a/opendbc_repo/opendbc/can/common.h b/opendbc_repo/opendbc/can/common.h index aa5f72d0a3..467e07f094 100644 --- a/opendbc_repo/opendbc/can/common.h +++ b/opendbc_repo/opendbc/can/common.h @@ -1,8 +1,10 @@ #pragma once +#include #include #include #include +#include #include #include #include @@ -19,6 +21,9 @@ #define CAN_INVALID_CNT 5 // Car specific functions +void pedal_setup_signal(Signal &sig, const std::string& dbc_name, int line_num); +void tesla_setup_signal(Signal &sig, const std::string& dbc_name, int line_num); + 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); @@ -28,6 +33,20 @@ unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d); unsigned int fca_giorgio_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); +unsigned int tesla_checksum(uint32_t address, const Signal &sig, const std::vector &d); + +#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 endswith(const std::string& str, const char* suffix) { + return str.find(suffix, str.length() - strlen(suffix)) != std::string::npos; +} struct CanFrame { long src; @@ -91,7 +110,7 @@ protected: class CANPacker { private: const DBC *dbc = NULL; - std::map, Signal> signal_lookup; + std::unordered_map> signal_lookup; std::map counters; public: diff --git a/opendbc_repo/opendbc/can/common.pxd b/opendbc_repo/opendbc/can/common.pxd index 0bfa436fd7..f8546c5f60 100644 --- a/opendbc_repo/opendbc/can/common.pxd +++ b/opendbc_repo/opendbc/can/common.pxd @@ -25,6 +25,7 @@ cdef extern from "common_dbc.h": CHRYSLER_CHECKSUM HKG_CAN_FD_CHECKSUM, FCA_GIORGIO_CHECKSUM, + TESLA_CHECKSUM, cdef struct Signal: string name @@ -85,5 +86,5 @@ cdef extern from "common.h": MessageState *getMessageState(uint32_t address) nogil cdef cppclass CANPacker: - CANPacker(string) - vector[uint8_t] pack(uint32_t, vector[SignalPackValue]&) + CANPacker(string) nogil + vector[uint8_t] pack(uint32_t, vector[SignalPackValue]&) nogil diff --git a/opendbc_repo/opendbc/can/common_dbc.h b/opendbc_repo/opendbc/can/common_dbc.h index 70a1b1f3fd..58ace65708 100644 --- a/opendbc_repo/opendbc/can/common_dbc.h +++ b/opendbc_repo/opendbc/can/common_dbc.h @@ -22,6 +22,7 @@ enum SignalType { CHRYSLER_CHECKSUM, HKG_CAN_FD_CHECKSUM, FCA_GIORGIO_CHECKSUM, + TESLA_CHECKSUM, }; struct Signal { @@ -64,6 +65,7 @@ typedef struct ChecksumState { bool little_endian; SignalType checksum_type; unsigned int (*calc_checksum)(uint32_t address, const Signal &sig, const std::vector &d); + void (*setup_signal)(Signal &sig, const std::string& dbc_name, int line_num); } ChecksumState; DBC* dbc_parse(const std::string& dbc_path); diff --git a/opendbc_repo/opendbc/can/dbc.cc b/opendbc_repo/opendbc/can/dbc.cc index 09c93b8924..e5ee6f2fae 100644 --- a/opendbc_repo/opendbc/can/dbc.cc +++ b/opendbc_repo/opendbc/can/dbc.cc @@ -2,9 +2,11 @@ #include #include #include +#include #include #include #include +#include #include #include #include @@ -20,15 +22,6 @@ std::regex sgm_regexp(R"(^SG_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9 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; } @@ -40,10 +33,6 @@ inline bool startswith(const std::string& str, std::initializer_listsetup_signal) { + chk->setup_signal(s, dbc_name, line_num); + } + + pedal_setup_signal(s, dbc_name, line_num); + 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; + if (s.type > COUNTER) { + DBC_ASSERT(chk->checksum_size == -1 || s.size == chk->checksum_size, s.name << " is not " << chk->checksum_size << " bits long"); + DBC_ASSERT(chk->checksum_start_bit == -1 || (s.start_bit % 8) == chk->checksum_start_bit, s.name << " starts at wrong bit"); + DBC_ASSERT(chk->little_endian == s.is_little_endian, s.name << " has wrong endianness"); + DBC_ASSERT(chk->calc_checksum != nullptr, "Checksum calculate function not supplied for " << s.name); + } else if (s.type == COUNTER) { + DBC_ASSERT(chk->counter_size == -1 || s.size == chk->counter_size, s.name << " is not " << chk->counter_size << " bits long"); + DBC_ASSERT(chk->counter_start_bit == -1 || (s.start_bit % 8) == chk->counter_start_bit, s.name << " starts at wrong bit"); + DBC_ASSERT(chk->little_endian == s.is_little_endian, s.name << " has wrong endianness"); + } } } diff --git a/opendbc_repo/opendbc/can/packer.cc b/opendbc_repo/opendbc/can/packer.cc index 15f49cf6b6..5e540e1282 100644 --- a/opendbc_repo/opendbc/can/packer.cc +++ b/opendbc_repo/opendbc/can/packer.cc @@ -3,7 +3,9 @@ #include #include #include +#include #include +#include #include "opendbc/can/common.h" @@ -34,7 +36,7 @@ CANPacker::CANPacker(const std::string& dbc_name) { for (const auto& msg : dbc->msgs) { for (const auto& sig : msg.sigs) { - signal_lookup[std::make_pair(msg.address, sig.name)] = sig; + signal_lookup[msg.address][sig.name] = sig; } } } @@ -51,8 +53,8 @@ std::vector CANPacker::pack(uint32_t address, const std::vector CANPacker::pack(uint32_t address, const std::vectorsecond; if (counters.find(address) == counters.end()) { @@ -84,8 +89,10 @@ std::vector CANPacker::pack(uint32_t address, const std::vector COUNTER; + }); + if (sig_it_checksum != signal_lookup[address].end()) { const auto &sig = sig_it_checksum->second; if (sig.calc_checksum != nullptr) { unsigned int checksum = sig.calc_checksum(address, sig, ret); diff --git a/opendbc_repo/opendbc/can/packer_pyx.pyx b/opendbc_repo/opendbc/can/packer_pyx.pyx index 4e8ae7d564..2d633deee9 100644 --- a/opendbc_repo/opendbc/can/packer_pyx.pyx +++ b/opendbc_repo/opendbc/can/packer_pyx.pyx @@ -2,6 +2,7 @@ # cython: c_string_encoding=ascii, language_level=3 from libc.stdint cimport uint8_t, uint32_t +from libcpp.string cimport string from libcpp.vector cimport vector from .common cimport CANPacker as cpp_CANPacker @@ -18,23 +19,37 @@ cdef class CANPacker: if not self.dbc: raise RuntimeError(f"Can't lookup {dbc_name}") - self.packer = new cpp_CANPacker(dbc_name) + cdef string cpp_dbc_name + if isinstance(dbc_name, str): + cpp_dbc_name = dbc_name.encode("utf-8") + else: + cpp_dbc_name = dbc_name + with nogil: + self.packer = new cpp_CANPacker(cpp_dbc_name) def __dealloc__(self): if self.packer: - del self.packer + with nogil: + del self.packer cdef vector[uint8_t] pack(self, addr, values): cdef vector[SignalPackValue] values_thing - values_thing.reserve(len(values)) - cdef SignalPackValue spv + cdef uint32_t value_len = len(values) + with nogil: + values_thing.reserve(value_len) + cdef SignalPackValue spv for name, value in values.iteritems(): spv.name = name.encode("utf8") spv.value = value - values_thing.push_back(spv) + with nogil: + values_thing.push_back(spv) - return self.packer.pack(addr, values_thing) + cdef vector[uint8_t] result + cdef uint32_t addr_cpp = addr + with nogil: + result = self.packer.pack(addr_cpp, values_thing) + return result cpdef make_can_msg(self, name_or_addr, bus, values): cdef uint32_t addr = 0 diff --git a/opendbc_repo/opendbc/can/parser.cc b/opendbc_repo/opendbc/can/parser.cc index 1607b09250..dedb584b75 100644 --- a/opendbc_repo/opendbc/can/parser.cc +++ b/opendbc_repo/opendbc/can/parser.cc @@ -2,8 +2,11 @@ #include #include #include +#include #include #include +#include +#include #include "opendbc/can/common.h" diff --git a/opendbc_repo/opendbc/can/parser_pyx.pyx b/opendbc_repo/opendbc/can/parser_pyx.pyx index 6815ad5154..ca8f475c29 100644 --- a/opendbc_repo/opendbc/can/parser_pyx.pyx +++ b/opendbc_repo/opendbc/can/parser_pyx.pyx @@ -63,7 +63,7 @@ cdef class CANParser: cdef string cpp_dbc_name if isinstance(dbc_name, str): - cpp_dbc_name = (dbc_name).encode('utf-8') + cpp_dbc_name = (dbc_name).encode("utf-8") else: cpp_dbc_name = dbc_name # Assume bytes cdef int cpp_bus = bus diff --git a/opendbc_repo/opendbc/can/tests/test_checksums.py b/opendbc_repo/opendbc/can/tests/test_checksums.py index b9a0a9ad6c..006bd12e23 100644 --- a/opendbc_repo/opendbc/can/tests/test_checksums.py +++ b/opendbc_repo/opendbc/can/tests/test_checksums.py @@ -93,7 +93,7 @@ class TestCanChecksums: def verify_volkswagen_mqb_crc(self, subtests, msg_name: str, msg_addr: int, test_messages: list[bytes], counter_field: str = 'COUNTER'): """Test AUTOSAR E2E Profile 2 CRCs""" assert len(test_messages) == 16 # All counter values must be tested - self.verify_checksum(subtests, "vw_mqb_2010", msg_name, msg_addr, test_messages, counter_field=counter_field) + self.verify_checksum(subtests, "vw_mqb", msg_name, msg_addr, test_messages, counter_field=counter_field) def test_volkswagen_mqb_crc_lwi_01(self, subtests): self.verify_volkswagen_mqb_crc(subtests, "LWI_01", 0x86, [ diff --git a/opendbc_repo/opendbc/can/tests/test_parser_performance.py b/opendbc_repo/opendbc/can/tests/test_parser_performance.py index c4ca5a3c82..678b74afd5 100644 --- a/opendbc_repo/opendbc/can/tests/test_parser_performance.py +++ b/opendbc_repo/opendbc/can/tests/test_parser_performance.py @@ -11,11 +11,14 @@ class TestParser: parser = CANParser('toyota_new_mc_pt_generated', checks, 0) packer = CANPacker('toyota_new_mc_pt_generated') + t1 = time.process_time_ns() can_msgs = [] for i in range(50000): values = {"ACC_CONTROL": {"ACC_TYPE": 1, "ALLOW_LONG_PRESS": 3}} msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] can_msgs.append([int(0.01 * i * 1e9), msgs]) + t2 = time.process_time_ns() + print(f'Pack time took {(t2 - t1) / 1e6} ms') ets = [] for _ in range(25): diff --git a/opendbc_repo/opendbc/car/__init__.py b/opendbc_repo/opendbc/car/__init__.py index dde58dd8cc..b830853297 100644 --- a/opendbc_repo/opendbc/car/__init__.py +++ b/opendbc_repo/opendbc/car/__init__.py @@ -98,13 +98,16 @@ class Bus(StrEnum): ap_party = auto() -def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): +def apply_driver_steer_torque_limits(apply_torque: int, apply_torque_last: int, driver_torque: float, LIMITS, steer_max: int = None): + # some safety modes utilize a dynamic max steer + if steer_max is None: + steer_max = LIMITS.STEER_MAX # limits due to driver torque - driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) - min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) + driver_max_torque = steer_max + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + driver_min_torque = -steer_max + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + max_steer_allowed = max(min(steer_max, driver_max_torque), 0) + min_steer_allowed = min(max(-steer_max, driver_min_torque), 0) apply_torque = np.clip(apply_torque, min_steer_allowed, max_steer_allowed) # slow rate if steer torque increases in magnitude diff --git a/opendbc_repo/opendbc/car/body/interface.py b/opendbc_repo/opendbc/car/body/interface.py index 007f679362..7c988c899c 100644 --- a/opendbc_repo/opendbc/car/body/interface.py +++ b/opendbc_repo/opendbc/car/body/interface.py @@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.notCar = True ret.brand = "body" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.body)] diff --git a/opendbc_repo/opendbc/car/car.capnp b/opendbc_repo/opendbc/car/car.capnp index 28d1dcea04..6df7f668ec 100644 --- a/opendbc_repo/opendbc/car/car.capnp +++ b/opendbc_repo/opendbc/car/car.capnp @@ -194,10 +194,12 @@ struct CarState { steeringTorque @8 :Float32; # TODO: standardize units steeringTorqueEps @27 :Float32; # TODO: standardize units steeringPressed @9 :Bool; # if the user is using the steering wheel + steeringDisengage @58 :Bool; # more force than steeringPressed, disengages for applicable brands steerFaultTemporary @35 :Bool; # temporary EPS fault steerFaultPermanent @36 :Bool; # permanent EPS fault invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) stockAeb @30 :Bool; + stockLkas @59 :Bool; stockFcw @31 :Bool; espDisabled @32 :Bool; accFaulted @42 :Bool; @@ -205,6 +207,7 @@ struct CarState { espActive @51 :Bool; vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed + blockPcmEnable @60 :Bool; # whether to allow PCM to enable this frame # cruise state cruiseState @10 :CruiseState; @@ -466,14 +469,15 @@ struct CarParams { enableDsu @5 :Bool; # driving support unit enableBsm @56 :Bool; # blind spot monitoring flags @64 :UInt32; # flags for car specific quirks - experimentalLongitudinalAvailable @71 :Bool; + alphaLongitudinalAvailable @71 :Bool; minEnableSpeed @7 :Float32; minSteerSpeed @8 :Float32; + steerAtStandstill @77 :Bool; # is steering available at standstill? just check if it faults safetyConfigs @62 :List(SafetyConfig); alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas - # Car docs fields + # Car docs fields, not used for control maxLateralAccel @68 :Float32; autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically diff --git a/opendbc_repo/opendbc/car/car_helpers.py b/opendbc_repo/opendbc/car/car_helpers.py index 64318bfbc6..c33a99489b 100644 --- a/opendbc_repo/opendbc/car/car_helpers.py +++ b/opendbc_repo/opendbc/car/car_helpers.py @@ -148,7 +148,7 @@ def fingerprint(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_mu return car_fingerprint, finger, vin, car_fw, source, exact_match -def get_car(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, experimental_long_allowed: bool, +def get_car(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, alpha_long_allowed: bool, num_pandas: int = 1, cached_params: CarParamsT | None = None): candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(can_recv, can_send, set_obd_multiplexing, num_pandas, cached_params) @@ -157,7 +157,7 @@ def get_car(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multip candidate = "MOCK" CarInterface = interfaces[candidate] - CP: CarParams = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) + CP: CarParams = CarInterface.get_params(candidate, fingerprints, car_fw, alpha_long_allowed, docs=False) CP.carVin = vin CP.carFw = car_fw CP.fingerprintSource = source diff --git a/opendbc_repo/opendbc/car/chrysler/interface.py b/opendbc_repo/opendbc/car/chrysler/interface.py index 065953a887..03246bed25 100755 --- a/opendbc_repo/opendbc/car/chrysler/interface.py +++ b/opendbc_repo/opendbc/car/chrysler/interface.py @@ -13,7 +13,7 @@ class CarInterface(CarInterfaceBase): RadarInterface = RadarInterface @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "chrysler" ret.dashcamOnly = candidate in RAM_HD diff --git a/opendbc_repo/opendbc/car/chrysler/values.py b/opendbc_repo/opendbc/car/chrysler/values.py index 50dffe984a..1a830ea5ac 100644 --- a/opendbc_repo/opendbc/car/chrysler/values.py +++ b/opendbc_repo/opendbc/car/chrysler/values.py @@ -67,12 +67,12 @@ class CAR(Platforms): # Jeep JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], + [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video="https://www.youtube.com/watch?v=eLR9o2JkuRk")], ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), ) JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], + [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video="https://www.youtube.com/watch?v=jBe4lWnRSu4")], JEEP_GRAND_CHEROKEE.specs, ) diff --git a/opendbc_repo/opendbc/car/docs.py b/opendbc_repo/opendbc/car/docs.py index 51f071b26a..a7e3952362 100755 --- a/opendbc_repo/opendbc/car/docs.py +++ b/opendbc_repo/opendbc/car/docs.py @@ -32,7 +32,7 @@ def get_params_for_docs(platform) -> CarParams: cp_platform = platform if platform in interfaces else MOCK.MOCK CP: CarParams = interfaces[cp_platform].get_params(cp_platform, fingerprint=gen_empty_fingerprint(), car_fw=[CarParams.CarFw(ecu=CarParams.Ecu.unknown)], - experimental_long=True, docs=True) + alpha_long=True, docs=True) return CP @@ -79,7 +79,7 @@ def group_by_make(all_car_docs: list[CarDocs]) -> dict[str, list[CarDocs]]: # CAUTION: This function is imported by shop.comma.ai and comma.ai/vehicles, test changes carefully -def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str) -> str: +def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str, **kwargs) -> str: with open(template_fn) as f: template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) @@ -87,7 +87,8 @@ def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str) -> str: cars_md: str = template.render(all_car_docs=all_car_docs, PartType=PartType, group_by_make=group_by_make, footnotes=footnotes, Device=Device, Column=Column, ExtraCarsColumn=ExtraCarsColumn, - BaseCarHarness=BaseCarHarness, SupportType=SupportType) + BaseCarHarness=BaseCarHarness, SupportType=SupportType, + **kwargs) return cars_md diff --git a/opendbc_repo/opendbc/car/docs_definitions.py b/opendbc_repo/opendbc/car/docs_definitions.py index bf44cd3d5a..9fce0b8a0c 100644 --- a/opendbc_repo/opendbc/car/docs_definitions.py +++ b/opendbc_repo/opendbc/car/docs_definitions.py @@ -22,6 +22,7 @@ class Column(Enum): AUTO_RESUME = "Resume from stop" HARDWARE = "Hardware Needed" VIDEO = "Video" + SETUP_VIDEO = "Setup Video" class ExtraCarsColumn(Enum): @@ -75,7 +76,7 @@ class Mount(EnumBase): class Cable(EnumBase): - long_obdc_cable = BasePart("long OBD-C cable") + long_obdc_cable = BasePart("long OBD-C cable (9.5 ft)") usb_a_2_a_cable = BasePart("USB A-A cable") usbc_otg_cable = BasePart("USB C OTG cable") usbc_coupler = BasePart("USB-C coupler") @@ -85,12 +86,12 @@ class Cable(EnumBase): class Accessory(EnumBase): harness_box = BasePart("harness box") - comma_power_v2 = BasePart("comma power v2") + comma_power = BasePart("comma power v3") @dataclass class BaseCarHarness(BasePart): - parts: list[Enum] = field(default_factory=lambda: [Accessory.harness_box, Accessory.comma_power_v2]) + parts: list[Enum] = field(default_factory=lambda: [Accessory.harness_box, Accessory.comma_power]) has_connector: bool = True # without are hidden on the harness connector page @@ -108,7 +109,7 @@ class CarHarness(EnumBase): fca = BaseCarHarness("FCA connector") ram = BaseCarHarness("Ram connector") vw_a = BaseCarHarness("VW A connector") - vw_j533 = BaseCarHarness("VW J533 connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler, Accessory.comma_power_v2]) + vw_j533 = BaseCarHarness("VW J533 connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) hyundai_a = BaseCarHarness("Hyundai A connector") hyundai_b = BaseCarHarness("Hyundai B connector") hyundai_c = BaseCarHarness("Hyundai C connector") @@ -128,17 +129,17 @@ class CarHarness(EnumBase): hyundai_q = BaseCarHarness("Hyundai Q connector") hyundai_r = BaseCarHarness("Hyundai R connector") custom = BaseCarHarness("Developer connector") - obd_ii = BaseCarHarness("OBD-II connector", parts=[Cable.long_obdc_cable], has_connector=False) + obd_ii = BaseCarHarness("OBD-II connector", parts=[Cable.long_obdc_cable, Cable.usbc_coupler], has_connector=False) gm = BaseCarHarness("GM connector", parts=[Accessory.harness_box]) - gmsdgm = BaseCarHarness("GM SDGM connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler, Accessory.comma_power_v2]) - nissan_a = BaseCarHarness("Nissan A connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) - nissan_b = BaseCarHarness("Nissan B connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) + gmsdgm = BaseCarHarness("GM SDGM connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + nissan_a = BaseCarHarness("Nissan A connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + nissan_b = BaseCarHarness("Nissan B connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) mazda = BaseCarHarness("Mazda connector") ford_q3 = BaseCarHarness("Ford Q3 connector") - ford_q4 = BaseCarHarness("Ford Q4 connector", parts=[Accessory.harness_box, Accessory.comma_power_v2, Cable.long_obdc_cable, Cable.usbc_coupler]) - rivian = BaseCarHarness("Rivian A connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) - tesla_a = BaseCarHarness("Tesla A connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) - tesla_b = BaseCarHarness("Tesla B connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) + ford_q4 = BaseCarHarness("Ford Q4 connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + rivian = BaseCarHarness("Rivian A connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + tesla_a = BaseCarHarness("Tesla A connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + tesla_b = BaseCarHarness("Tesla B connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) class Device(EnumBase): @@ -190,7 +191,7 @@ class CarParts: return self.parts + parts -CarFootnote = namedtuple("CarFootnote", ["text", "column", "docs_only", "shop_footnote"], defaults=(False, False)) +CarFootnote = namedtuple("CarFootnote", ["text", "column", "docs_only", "setup_note"], defaults=(False, False)) class CommonFootnote(Enum): @@ -254,7 +255,8 @@ class CarDocs: # of market. can be a package, trim, or list of features requirements: str | None = None - video_link: str | None = None + video: str | None = None + setup_video: str | None = None footnotes: list[Enum] = field(default_factory=list) min_steer_speed: float | None = None min_enable_speed: float | None = None @@ -284,7 +286,7 @@ class CarDocs: # longitudinal column op_long = "Stock" - if CP.experimentalLongitudinalAvailable or CP.enableDsu: + if CP.alphaLongitudinalAvailable or CP.enableDsu: op_long = "openpilot available" if CP.enableDsu: self.footnotes.append(CommonFootnote.EXP_LONG_DSU) @@ -333,7 +335,8 @@ class CarDocs: Column.STEERING_TORQUE: Star.EMPTY, Column.AUTO_RESUME: Star.FULL if self.auto_resume else Star.EMPTY, Column.HARDWARE: hardware_col, - Column.VIDEO: self.video_link if self.video_link is not None else "", # replaced with an image and link from template in get_column + Column.VIDEO: self.video or "", # replaced with an image and link from template in get_column + Column.SETUP_VIDEO: self.setup_video or "", # replaced with an image and link from template in get_column } if self.support_link is not None: @@ -382,7 +385,7 @@ class CarDocs: # experimental mode exp_link = "Experimental mode" - if CP.openpilotLongitudinalControl and not CP.experimentalLongitudinalAvailable: + if CP.openpilotLongitudinalControl and not CP.alphaLongitudinalAvailable: sentence_builder += f" Traffic light and stop sign handling is also available in {exp_link}." return sentence_builder.format(car_model=f"{self.make} {self.model}", alc=alc, acc=acc) diff --git a/opendbc_repo/opendbc/car/ford/carcontroller.py b/opendbc_repo/opendbc/car/ford/carcontroller.py index 1f5644cbe0..091c966dfb 100644 --- a/opendbc_repo/opendbc/car/ford/carcontroller.py +++ b/opendbc_repo/opendbc/car/ford/carcontroller.py @@ -4,18 +4,15 @@ from opendbc.can.packer import CANPacker from opendbc.car import ACCELERATION_DUE_TO_GRAVITY, Bus, DT_CTRL, apply_std_steer_angle_limits, structs from opendbc.car.ford import fordcan from opendbc.car.ford.values import CarControllerParams, FordFlags -from opendbc.car.interfaces import CarControllerBase, V_CRUISE_MAX +from opendbc.car.interfaces import CarControllerBase, ISO_LATERAL_ACCEL, V_CRUISE_MAX LongCtrlState = structs.CarControl.Actuators.LongControlState VisualAlert = structs.CarControl.HUDControl.VisualAlert -# ISO 11270 -ISO_LATERAL_ACCEL = 3.0 # m/s^2 # TODO: import from test lateral limits file? - +# CAN FD limits: # Limit to average banked road since safety doesn't have the roll -EARTH_G = 9.81 -AVERAGE_ROAD_ROLL = 0.06 # ~3.4 degrees, 6% superelevation -MAX_LATERAL_ACCEL = ISO_LATERAL_ACCEL - (EARTH_G * AVERAGE_ROAD_ROLL) # ~2.4 m/s^2 +AVERAGE_ROAD_ROLL = 0.06 # ~3.4 degrees, 6% superelevation. higher actual roll raises lateral acceleration +MAX_LATERAL_ACCEL = ISO_LATERAL_ACCEL - (ACCELERATION_DUE_TO_GRAVITY * AVERAGE_ROAD_ROLL) # ~2.4 m/s^2 def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw, steering_angle, lat_active, CP): diff --git a/opendbc_repo/opendbc/car/ford/fingerprints.py b/opendbc_repo/opendbc/car/ford/fingerprints.py index 03eedb1502..ab4c6d9d39 100644 --- a/opendbc_repo/opendbc/car/ford/fingerprints.py +++ b/opendbc_repo/opendbc/car/ford/fingerprints.py @@ -46,6 +46,20 @@ FW_VERSIONS = { b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, + CAR.FORD_ESCAPE_MK4_5: { + (Ecu.eps, 0x730, None): [ + b'PZ11-14D003-EA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PZ1C-2D053-EJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'PJ6T-14H102-ABL\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, CAR.FORD_EXPLORER_MK6: { (Ecu.eps, 0x730, None): [ b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -80,6 +94,7 @@ FW_VERSIONS = { b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ + b'NL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PL34-2D053-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PL3V-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -89,6 +104,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x706, None): [ b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'RJ6T-14H102-ACJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -96,6 +112,7 @@ FW_VERSIONS = { CAR.FORD_F_150_LIGHTNING_MK1: { (Ecu.abs, 0x760, None): [ b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'RL38-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/opendbc_repo/opendbc/car/ford/interface.py b/opendbc_repo/opendbc/car/ford/interface.py index f1e1bfe29c..ff5a0a6ee2 100644 --- a/opendbc_repo/opendbc/car/ford/interface.py +++ b/opendbc_repo/opendbc/car/ford/interface.py @@ -26,13 +26,14 @@ class CarInterface(CarInterfaceBase): return CarControllerParams.ACCEL_MIN, np.interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "ford" ret.radarUnavailable = Bus.radar not in DBC[candidate] ret.steerControlType = structs.CarParams.SteerControlType.angle ret.steerActuatorDelay = 0.2 ret.steerLimitTimer = 1.0 + ret.steerAtStandstill = True ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.5] @@ -48,8 +49,8 @@ class CarInterface(CarInterfaceBase): cfgs.insert(0, get_safety_config(structs.CarParams.SafetyModel.noOutput)) ret.safetyConfigs = cfgs - ret.experimentalLongitudinalAvailable = ret.radarUnavailable - if experimental_long or not ret.radarUnavailable: + ret.alphaLongitudinalAvailable = ret.radarUnavailable + if alpha_long or not ret.radarUnavailable: ret.safetyConfigs[-1].safetyParam |= FordSafetyFlags.LONG_CONTROL.value ret.openpilotLongitudinalControl = True diff --git a/opendbc_repo/opendbc/car/ford/values.py b/opendbc_repo/opendbc/car/ford/values.py index 57f41ca2a7..b752c88565 100644 --- a/opendbc_repo/opendbc/car/ford/values.py +++ b/opendbc_repo/opendbc/car/ford/values.py @@ -79,6 +79,11 @@ class FordCarDocs(CarDocs): else: self.car_parts = CarParts([Device.threex, harness]) + if harness == CarHarness.ford_q4: + self.setup_video = "https://www.youtube.com/watch?v=uUGkH6C_EQU" + + if CP.carFingerprint in (CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): + self.setup_video = "https://www.youtube.com/watch?v=MewJc9LYp9M" @dataclass class FordPlatformConfig(PlatformConfig): @@ -124,7 +129,15 @@ class CAR(Platforms): FORD_ESCAPE_MK4 = FordPlatformConfig( [ FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), - FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), + FordCarDocs("Ford Kuga 2020-23", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), + ], + CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), + ) + FORD_ESCAPE_MK4_5 = FordCANFDPlatformConfig( + [ + FordCarDocs("Ford Escape 2023-24", hybrid=True, plug_in_hybrid=True), + FordCarDocs("Ford Kuga Hybrid 2024", "All"), + FordCarDocs("Ford Kuga Plug-in Hybrid 2024", "All"), ], CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), ) @@ -155,11 +168,11 @@ class CAR(Platforms): CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), ) FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Mustang Mach-E 2021-23", "All")], + [FordCarDocs("Ford Mustang Mach-E 2021-23", "All", setup_video="https://www.youtube.com/watch?v=AR4_eTF3b_A")], CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio ) FORD_RANGER_MK2 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering")], + [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering", setup_video="https://www.youtube.com/watch?v=2oJlXCKYOy0")], CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), ) diff --git a/opendbc_repo/opendbc/car/fw_query_definitions.py b/opendbc_repo/opendbc/car/fw_query_definitions.py index 16e569b0b7..5c48fed6a1 100644 --- a/opendbc_repo/opendbc/car/fw_query_definitions.py +++ b/opendbc_repo/opendbc/car/fw_query_definitions.py @@ -56,6 +56,11 @@ class StdQueries: SUPPLIER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_VERSION_NUMBER) + MANUFACTURER_ECU_HARDWARE_NUMBER_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER) + MANUFACTURER_ECU_HARDWARE_NUMBER_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER) + UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ diff --git a/opendbc_repo/opendbc/car/gm/carcontroller.py b/opendbc_repo/opendbc/car/gm/carcontroller.py index bbfd7056db..ce5655c97d 100644 --- a/opendbc_repo/opendbc/car/gm/carcontroller.py +++ b/opendbc_repo/opendbc/car/gm/carcontroller.py @@ -89,7 +89,7 @@ class CarController(CarControllerBase): self.apply_gas = self.params.INACTIVE_REGEN self.apply_brake = 0 else: - self.apply_gas = int(round(np.interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) + self.apply_gas = float(np.interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V)) self.apply_brake = int(round(np.interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) # Don't allow any gas above inactive regen while stopping # FIXME: brakes aren't applied immediately when enabling at a stop diff --git a/opendbc_repo/opendbc/car/gm/gmcan.py b/opendbc_repo/opendbc/car/gm/gmcan.py index c9d1effc2e..cb74b609e4 100644 --- a/opendbc_repo/opendbc/car/gm/gmcan.py +++ b/opendbc_repo/opendbc/car/gm/gmcan.py @@ -56,16 +56,14 @@ def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): values = { "GasRegenCmdActive": enabled, "RollingCounter": idx, - "GasRegenCmdActiveInv": 1 - enabled, "GasRegenCmd": throttle, "GasRegenFullStopActive": at_full_stop, - "GasRegenAlwaysOne": 1, - "GasRegenAlwaysOne2": 1, - "GasRegenAlwaysOne3": 1, + "GasRegenAccType": 1, } dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[1] - values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ + values["GasRegenChecksum"] = ((1 - enabled) << 24) | \ + (((0xff - dat[1]) & 0xff) << 16) | \ (((0xff - dat[2]) & 0xff) << 8) | \ ((0x100 - dat[3] - idx) & 0xff) diff --git a/opendbc_repo/opendbc/car/gm/interface.py b/opendbc_repo/opendbc/car/gm/interface.py index 8059ab12df..a0b3a6bdb1 100755 --- a/opendbc_repo/opendbc/car/gm/interface.py +++ b/opendbc_repo/opendbc/car/gm/interface.py @@ -7,7 +7,7 @@ from opendbc.car.common.basedir import BASEDIR from opendbc.car.common.conversions import Conversions as CV from opendbc.car.gm.carcontroller import CarController from opendbc.car.gm.carstate import CarState -from opendbc.car.gm.radar_interface import RadarInterface, RADAR_HEADER_MSG +from opendbc.car.gm.radar_interface import RadarInterface, RADAR_HEADER_MSG, CAMERA_DATA_HEADER_MSG from opendbc.car.gm.values import CAR, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, SDGM_CAR, ALT_ACCS, CanBus, GMSafetyFlags from opendbc.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel @@ -85,7 +85,7 @@ class CarInterface(CarInterfaceBase): return self.torque_from_lateral_accel_linear @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "gm" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.gm)] ret.autoResumeSng = False @@ -100,7 +100,7 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiBP = [5., 35.] if candidate in (CAMERA_ACC_CAR | SDGM_CAR): - ret.experimentalLongitudinalAvailable = candidate not in SDGM_CAR + ret.alphaLongitudinalAvailable = candidate not in SDGM_CAR ret.networkLocation = NetworkLocation.fwdCamera ret.radarUnavailable = True # no radar ret.pcmCruise = True @@ -114,20 +114,21 @@ class CarInterface(CarInterfaceBase): ret.vEgoStopping = 0.25 ret.vEgoStarting = 0.25 - if experimental_long: + if alpha_long: ret.pcmCruise = False ret.openpilotLongitudinalControl = True ret.safetyConfigs[0].safetyParam |= GMSafetyFlags.HW_CAM_LONG.value if candidate in ALT_ACCS: - ret.experimentalLongitudinalAvailable = False + ret.alphaLongitudinalAvailable = False ret.openpilotLongitudinalControl = False ret.minEnableSpeed = -1. # engage speed is decided by PCM else: # ASCM, OBD-II harness ret.openpilotLongitudinalControl = True ret.networkLocation = NetworkLocation.gateway - ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs + # LRR messages can take up to a few seconds to start sending after ignition, check camera data as well which starts earlier + ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and CAMERA_DATA_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs ret.pcmCruise = False # stock non-adaptive cruise control is kept off # supports stop and go, but initial engage must (conservatively) be above 18mph ret.minEnableSpeed = 18 * CV.MPH_TO_MS diff --git a/opendbc_repo/opendbc/car/gm/radar_interface.py b/opendbc_repo/opendbc/car/gm/radar_interface.py index 2daffb8532..3bbfc9ca83 100755 --- a/opendbc_repo/opendbc/car/gm/radar_interface.py +++ b/opendbc_repo/opendbc/car/gm/radar_interface.py @@ -6,7 +6,8 @@ from opendbc.car.common.conversions import Conversions as CV from opendbc.car.gm.values import DBC, CanBus from opendbc.car.interfaces import RadarInterfaceBase -RADAR_HEADER_MSG = 1120 +RADAR_HEADER_MSG = 1120 # F_LRR_Obj_Header +CAMERA_DATA_HEADER_MSG = 1056 # F_Vision_Obj_Header SLOT_1_MSG = RADAR_HEADER_MSG + 1 NUM_SLOTS = 20 diff --git a/opendbc_repo/opendbc/car/gm/values.py b/opendbc_repo/opendbc/car/gm/values.py index b2b4e53886..8cb6179dab 100644 --- a/opendbc_repo/opendbc/car/gm/values.py +++ b/opendbc_repo/opendbc/car/gm/values.py @@ -1,9 +1,9 @@ from dataclasses import dataclass, field -from enum import IntFlag +from enum import Enum, IntFlag from opendbc.car import Bus, PlatformConfig, DbcDict, Platforms, CarSpecs from opendbc.car.structs import CarParams -from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts +from opendbc.car.docs_definitions import CarDocs, CarFootnote, CarHarness, CarParts, Column from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = CarParams.Ecu @@ -34,27 +34,26 @@ class CarControllerParams: def __init__(self, CP): # Gas/brake lookups - self.ZERO_GAS = 2048 # Coasting self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen if CP.carFingerprint in (CAMERA_ACC_CAR | SDGM_CAR): - self.MAX_GAS = 3400 - self.MAX_ACC_REGEN = 1514 - self.INACTIVE_REGEN = 1554 + self.MAX_GAS = 1346.0 + self.MAX_ACC_REGEN = -540.0 + self.INACTIVE_REGEN = -500.0 # Camera ACC vehicles have no regen while enabled. - # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly + # Camera transitions to MAX_ACC_REGEN from zero gas and uses friction brakes instantly max_regen_acceleration = 0. else: - self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. - self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen - self.INACTIVE_REGEN = 1404 + self.MAX_GAS = 1018.0 # Safety limit, not ACC max. Stock ACC >2042 from standstill. + self.MAX_ACC_REGEN = -650.0 # Max ACC regen is slightly less than max paddle regen + self.INACTIVE_REGEN = -650.0 # ICE has much less engine braking force compared to regen in EVs, # lower threshold removes some braking deadzone max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] - self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, 0., self.MAX_GAS] self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] @@ -66,6 +65,12 @@ class GMSafetyFlags(IntFlag): EV = 4 +class Footnote(Enum): + SETUP = CarFootnote( + "See more setup details for GM.", + Column.MAKE, setup_note=True) + + @dataclass class GMCarDocs(CarDocs): package: str = "Adaptive Cruise Control (ACC)" @@ -77,6 +82,7 @@ class GMCarDocs(CarDocs): else: self.car_parts = CarParts.common([CarHarness.gm]) else: + self.footnotes.insert(0, Footnote.SETUP) self.car_parts = CarParts.common([CarHarness.obd_ii]) @@ -113,7 +119,7 @@ class CAR(Platforms): GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), ) CHEVROLET_VOLT = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], + [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video="https://youtu.be/QeMCN_4TFfQ")], GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), ) CADILLAC_ATS = GMASCMPlatformConfig( @@ -125,7 +131,7 @@ class CAR(Platforms): GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), ) GMC_ACADIA = GMASCMPlatformConfig( - [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], + [GMCarDocs("GMC Acadia 2018", video="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), ) BUICK_LACROSSE = GMASCMPlatformConfig( @@ -150,7 +156,7 @@ class CAR(Platforms): ) CHEVROLET_BOLT_EUV = GMPlatformConfig( [ - GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), + GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video="https://youtu.be/xvwzGMUA210"), GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), ], GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), @@ -158,7 +164,7 @@ class CAR(Platforms): CHEVROLET_SILVERADO = GMPlatformConfig( [ GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), - GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), + GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video="https://youtu.be/5HbNoBLzRwE"), ], GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), ) diff --git a/opendbc_repo/opendbc/car/honda/carstate.py b/opendbc_repo/opendbc/car/honda/carstate.py index b70a9a394b..7fb19b3b8f 100644 --- a/opendbc_repo/opendbc/car/honda/carstate.py +++ b/opendbc_repo/opendbc/car/honda/carstate.py @@ -6,7 +6,7 @@ from opendbc.can.parser import CANParser from opendbc.car import Bus, create_button_events, structs from opendbc.car.common.conversions import Conversions as CV from opendbc.car.honda.hondacan import CanBus, get_cruise_speed_conversion -from opendbc.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ +from opendbc.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, HONDA_BOSCH_CANFD, \ HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ HondaFlags, CruiseButtons, CruiseSettings, GearShifter from opendbc.car.interfaces import CarStateBase @@ -68,13 +68,9 @@ def get_can_messages(CP, gearbox_msg): else: messages.append(("CRUISE_PARAMS", 50)) - # TODO: clean this up - if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - pass - elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - pass - else: + if CP.carFingerprint not in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, + CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV, *HONDA_BOSCH_RADARLESS, + *HONDA_BOSCH_CANFD): messages.append(("DOORS_STATUS", 3)) if CP.carFingerprint in HONDA_BOSCH_RADARLESS: @@ -92,6 +88,8 @@ class CarState(CarStateBase): self.gearbox_msg = "GEARBOX" if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: self.gearbox_msg = "GEARBOX_15T" + elif CP.carFingerprint == CAR.HONDA_CIVIC_2022 and CP.transmissionType == TransmissionType.cvt: + self.gearbox_msg = "GEARBOX_ALT" elif CP.transmissionType == TransmissionType.manual: self.gearbox_msg = "GEARBOX_ALT_2" @@ -139,7 +137,7 @@ class CarState(CarStateBase): ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 # TODO: find a common signal across all cars if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): + CAR.ACURA_RDX_3G, CAR.HONDA_E, *HONDA_BOSCH_RADARLESS, *HONDA_BOSCH_CANFD): ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) diff --git a/opendbc_repo/opendbc/car/honda/fingerprints.py b/opendbc_repo/opendbc/car/honda/fingerprints.py index 83a085bea0..36efa36597 100644 --- a/opendbc_repo/opendbc/car/honda/fingerprints.py +++ b/opendbc_repo/opendbc/car/honda/fingerprints.py @@ -866,7 +866,10 @@ FW_VERSIONS = { b'39990-T38-A040\x00\x00', b'39990-T39-A130\x00\x00', b'39990-T43-J020\x00\x00', + b'39990-T43-J030\x00\x00', b'39990-T60-J030\x00\x00', + b'39990-T56-A040\x00\x00', + b'39990-T50-J030\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-T20-A020\x00\x00', @@ -876,7 +879,10 @@ FW_VERSIONS = { b'38897-T21-A010\x00\x00', b'38897-T22-A110\x00\x00', b'38897-T24-Z120\x00\x00', + b'38897-T47-AA20\x00\x00', b'38897-T60-A110\x00\x00', + b'38897-T61-A320\x00\x00', + b'38897-T50-E310\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-T20-A970\x00\x00', @@ -886,6 +892,9 @@ FW_VERSIONS = { b'77959-T47-A940\x00\x00', b'77959-T47-A950\x00\x00', b'77959-T60-A920\x00\x00', + b'77959-T61-A920\x00\x00', + b'77959-T50-G930\x00\x00', + b'77959-T65-A920\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-T20-A060\x00\x00', @@ -895,16 +904,23 @@ FW_VERSIONS = { b'36161-T38-A060\x00\x00', b'36161-T47-A050\x00\x00', b'36161-T47-A070\x00\x00', + b'8S102-T47-AA20\x00\x00', b'8S102-T20-AA10\x00\x00', b'8S102-T47-AA10\x00\x00', b'8S102-T60-AA10\x00\x00', + b'8S102-T56-A060\x00\x00', + b'8S102-T50-EA10\x00\x00', + b'8S102-T64-A040\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ b'57114-T20-AB40\x00\x00', b'57114-T24-TB30\x00\x00', b'57114-T38-AA20\x00\x00', + b'57114-T43-JA30\x00\x00', b'57114-T43-JB30\x00\x00', b'57114-T60-AA20\x00\x00', + b'57114-T61-AJ30\x00\x00', + b'57114-T50-JC20\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28101-65D-A020\x00\x00', @@ -914,4 +930,12 @@ FW_VERSIONS = { b'28101-65J-N010\x00\x00', ], }, + CAR.HONDA_PILOT_4G: { + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'8S102-T90-A050\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'8S302-T90-A040\x00\x00', + ], + }, } diff --git a/opendbc_repo/opendbc/car/honda/hondacan.py b/opendbc_repo/opendbc/car/honda/hondacan.py index 878bdcb62b..ec2c5d25ae 100644 --- a/opendbc_repo/opendbc/car/honda/hondacan.py +++ b/opendbc_repo/opendbc/car/honda/hondacan.py @@ -1,6 +1,6 @@ from opendbc.car import CanBusBase from opendbc.car.common.conversions import Conversions as CV -from opendbc.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams +from opendbc.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_BOSCH_CANFD, CAR, CarControllerParams # CAN bus layout with relay # 0 = ACC-CAN - radar side @@ -14,7 +14,8 @@ class CanBus(CanBusBase): # use fingerprint if specified super().__init__(CP if fingerprint is None else None, fingerprint) - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS): + # powertrain bus is split instead of radar on radarless and CAN FD Bosch + if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS - HONDA_BOSCH_CANFD): self._pt, self._radar = self.offset + 1, self.offset # normally steering commands are sent to radar, which forwards them to powertrain bus # when radar is disabled, steering commands are sent directly to powertrain bus @@ -46,7 +47,7 @@ class CanBus(CanBusBase): def get_cruise_speed_conversion(car_fingerprint: str, is_metric: bool) -> float: # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting - return CV.MPH_TO_MS if car_fingerprint in HONDA_BOSCH_RADARLESS and not is_metric else CV.KPH_TO_MS + return CV.MPH_TO_MS if car_fingerprint in (HONDA_BOSCH_RADARLESS | HONDA_BOSCH_CANFD) and not is_metric else CV.KPH_TO_MS def create_brake_command(packer, CAN, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, car_fingerprint, stock_brake): @@ -173,11 +174,14 @@ def create_ui_commands(packer, CAN, CP, enabled, pcm_speed, hud, is_metric, acc_ 'BEEP': 0, } - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + if CP.carFingerprint in (HONDA_BOSCH_RADARLESS | HONDA_BOSCH_CANFD): lkas_hud_values['LANE_LINES'] = 3 lkas_hud_values['DASHED_LANES'] = hud.lanes_visible + # car likely needs to see LKAS_PROBLEM fall within a specific time frame, so forward from camera - lkas_hud_values['LKAS_PROBLEM'] = lkas_hud['LKAS_PROBLEM'] + # TODO: needed for Bosch CAN FD? + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + lkas_hud_values['LKAS_PROBLEM'] = lkas_hud['LKAS_PROBLEM'] if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): lkas_hud_values['SET_ME_X48'] = 0x48 @@ -206,6 +210,6 @@ def spam_buttons_command(packer, CAN, button_val, car_fingerprint): 'CRUISE_BUTTONS': button_val, 'CRUISE_SETTING': 0, } - # send buttons to camera on radarless cars + # send buttons to camera on radarless (camera does ACC) cars bus = CAN.camera if car_fingerprint in HONDA_BOSCH_RADARLESS else CAN.pt return packer.make_can_msg("SCM_BUTTONS", bus, values) diff --git a/opendbc_repo/opendbc/car/honda/interface.py b/opendbc_repo/opendbc/car/honda/interface.py index e1943e03e1..571ddcdbe7 100755 --- a/opendbc_repo/opendbc/car/honda/interface.py +++ b/opendbc_repo/opendbc/car/honda/interface.py @@ -4,7 +4,7 @@ from opendbc.car import get_safety_config, structs from opendbc.car.common.conversions import Conversions as CV from opendbc.car.disable_ecu import disable_ecu from opendbc.car.honda.hondacan import CanBus -from opendbc.car.honda.values import CarControllerParams, HondaFlags, CAR, HONDA_BOSCH, \ +from opendbc.car.honda.values import CarControllerParams, HondaFlags, CAR, HONDA_BOSCH, HONDA_BOSCH_CANFD, \ HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, HondaSafetyFlags from opendbc.car.honda.carcontroller import CarController from opendbc.car.honda.carstate import CarState @@ -31,19 +31,27 @@ class CarInterface(CarInterfaceBase): return CarControllerParams.NIDEC_ACCEL_MIN, np.interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "honda" CAN = CanBus(ret, fingerprint) + # Recent test route is needed to undashcam these cars + ret.dashcamOnly = candidate in HONDA_BOSCH_CANFD + if candidate in HONDA_BOSCH: - ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hondaBosch)] + cfgs = [get_safety_config(structs.CarParams.SafetyModel.hondaBosch)] + if candidate in HONDA_BOSCH_CANFD and CAN.pt >= 4: + cfgs.insert(0, get_safety_config(structs.CarParams.SafetyModel.noOutput)) + ret.safetyConfigs = cfgs + ret.radarUnavailable = True # Disable the radar and let openpilot control longitudinal # WARNING: THIS DISABLES AEB! # If Bosch radarless, this blocks ACC messages from the camera - ret.experimentalLongitudinalAvailable = True - ret.openpilotLongitudinalControl = experimental_long + # TODO: get radar disable working on Bosch CANFD + ret.alphaLongitudinalAvailable = candidate not in HONDA_BOSCH_CANFD + ret.openpilotLongitudinalControl = alpha_long ret.pcmCruise = not ret.openpilotLongitudinalControl else: ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hondaNidec)] @@ -61,9 +69,12 @@ class CarInterface(CarInterfaceBase): # Accord ICE 1.5T CVT has different gearbox message if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: ret.transmissionType = TransmissionType.cvt - # New Civics can have manual transmission - elif candidate == CAR.HONDA_CIVIC_2022 and 0x191 not in fingerprint[CAN.pt]: + # Civic Type R is missing 0x191 and 0x1A3 + elif candidate == CAR.HONDA_CIVIC_2022 and all(msg not in fingerprint[CAN.pt] for msg in (0x191, 0x1A3)): ret.transmissionType = TransmissionType.manual + # New Civics don't have 0x191, but do have 0x1A3 + elif candidate == CAR.HONDA_CIVIC_2022 and 0x1A3 in fingerprint[CAN.pt]: + ret.transmissionType = TransmissionType.cvt # Certain Hondas have an extra steering sensor at the bottom of the steering rack, # which improves controls quality as it removes the steering column torsion from feedback. @@ -101,10 +112,15 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] - elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): + elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + elif candidate == CAR.HONDA_CIVIC_2022: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kpV = [[0, 10], [0.05, 0.5]] + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kiV = [[0, 10], [0.0125, 0.125]] + elif candidate == CAR.HONDA_ACCORD: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end @@ -170,7 +186,7 @@ class CarInterface(CarInterfaceBase): else: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - elif candidate == CAR.HONDA_PILOT: + elif candidate in (CAR.HONDA_PILOT, CAR.HONDA_PILOT_4G): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] @@ -195,17 +211,17 @@ class CarInterface(CarInterfaceBase): ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.safetyConfigs[0].safetyParam |= HondaSafetyFlags.ALT_BRAKE.value + ret.safetyConfigs[-1].safetyParam |= HondaSafetyFlags.ALT_BRAKE.value # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: - ret.safetyConfigs[0].safetyParam |= HondaSafetyFlags.NIDEC_ALT.value + ret.safetyConfigs[-1].safetyParam |= HondaSafetyFlags.NIDEC_ALT.value if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: - ret.safetyConfigs[0].safetyParam |= HondaSafetyFlags.BOSCH_LONG.value + ret.safetyConfigs[-1].safetyParam |= HondaSafetyFlags.BOSCH_LONG.value if candidate in HONDA_BOSCH_RADARLESS: - ret.safetyConfigs[0].safetyParam |= HondaSafetyFlags.RADARLESS.value + ret.safetyConfigs[-1].safetyParam |= HondaSafetyFlags.RADARLESS.value # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not diff --git a/opendbc_repo/opendbc/car/honda/values.py b/opendbc_repo/opendbc/car/honda/values.py index 9233f75067..4e8ad3ee54 100644 --- a/opendbc_repo/opendbc/car/honda/values.py +++ b/opendbc_repo/opendbc/car/honda/values.py @@ -3,7 +3,7 @@ from enum import Enum, IntFlag from opendbc.car import Bus, CarSpecs, PlatformConfig, Platforms, structs, uds from opendbc.car.common.conversions import Conversions as CV -from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, Device from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 Ecu = structs.CarParams.Ecu @@ -40,9 +40,10 @@ class CarControllerParams: def __init__(self, CP): self.STEER_MAX = CP.lateralParams.torqueBP[-1] - # mirror of list (assuming first item is zero) for interp of signed request values - assert(CP.lateralParams.torqueBP[0] == 0) - assert(CP.lateralParams.torqueBP[0] == 0) + # mirror of list (assuming first item is zero) for interp of signed request + # values and verify that both arrays begin at zero + assert CP.lateralParams.torqueBP[0] == 0 + assert CP.lateralParams.torqueV[0] == 0 self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) @@ -68,6 +69,7 @@ class HondaFlags(IntFlag): NIDEC_ALT_PCM_ACCEL = 32 NIDEC_ALT_SCM_MESSAGES = 64 + BOSCH_CANFD = 128 # Car button codes class CruiseButtons: @@ -101,9 +103,19 @@ class HondaCarDocs(CarDocs): def init_make(self, CP: structs.CarParams): if CP.flags & HondaFlags.BOSCH: - self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) + if CP.flags & HondaFlags.BOSCH_CANFD: + harness = CarHarness.bosch_c + elif CP.flags & HondaFlags.BOSCH_RADARLESS: + harness = CarHarness.bosch_b + else: + harness = CarHarness.bosch_a else: - self.car_parts = CarParts.common([CarHarness.nidec]) + harness = CarHarness.nidec + + if CP.carFingerprint in (CAR.HONDA_PILOT_4G,): + self.car_parts = CarParts([Device.threex_angled_mount, harness]) + else: + self.car_parts = CarParts.common([harness]) class Footnote(Enum): @@ -130,7 +142,7 @@ class CAR(Platforms): # Bosch Cars HONDA_ACCORD = HondaBoschPlatformConfig( [ - HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarDocs("Honda Accord 2018-22", "All", video="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), ], @@ -140,7 +152,7 @@ class CAR(Platforms): ) HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( [ - HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", + HondaCarDocs("Honda Civic 2019-21", "All", video="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), ], @@ -154,8 +166,11 @@ class CAR(Platforms): ) HONDA_CIVIC_2022 = HondaBoschPlatformConfig( [ - HondaCarDocs("Honda Civic 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - HondaCarDocs("Honda Civic Hatchback 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + HondaCarDocs("Honda Civic 2022-24", "All", video="https://youtu.be/ytiOT5lcp6Q"), + HondaCarDocs("Honda Civic Hatchback 2022-24", "All", video="https://youtu.be/ytiOT5lcp6Q"), + HondaCarDocs("Honda Civic Hatchback Hybrid 2023 (Europe only)", "All"), + # TODO: Confirm 2024 + HondaCarDocs("Honda Civic Hatchback Hybrid 2025", "All"), ], HONDA_CIVIC_BOSCH.specs, {Bus.pt: 'honda_civic_ex_2022_can_generated'}, @@ -175,7 +190,7 @@ class CAR(Platforms): {Bus.pt: 'honda_accord_2018_can_generated'}, ) HONDA_HRV_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda HR-V 2023", "All")], + [HondaCarDocs("Honda HR-V 2023-25", "All")], CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), {Bus.pt: 'honda_civic_ex_2022_can_generated'}, flags=HondaFlags.BOSCH_RADARLESS, @@ -196,10 +211,19 @@ class CAR(Platforms): CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), {Bus.pt: 'acura_rdx_2020_can_generated'}, ) + HONDA_PILOT_4G = HondaBoschPlatformConfig( + [HondaCarDocs("Honda Pilot 2023", "All")], + CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec + {Bus.pt: 'honda_pilot_2023_can_generated'}, + flags=HondaFlags.BOSCH_CANFD | HondaFlags.BOSCH_ALT_BRAKE, + ) # Nidec Cars ACURA_ILX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], + [ + HondaCarDocs("Acura ILX 2016-18", "Technology Plus Package or AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS), + HondaCarDocs("Acura ILX 2019", "All", min_steer_speed=25. * CV.MPH_TO_MS), + ], CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end radar_dbc_dict('acura_ilx_2016_can_generated'), flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, @@ -247,7 +271,7 @@ class CAR(Platforms): flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, ) ACURA_RDX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], + [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus or Advance Package", min_steer_speed=12. * CV.MPH_TO_MS)], CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec radar_dbc_dict('acura_rdx_2018_can_generated'), flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, @@ -255,9 +279,9 @@ class CAR(Platforms): HONDA_PILOT = HondaNidecPlatformConfig( [ HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), - HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), + HondaCarDocs("Honda Passport 2019-25", "All", min_steer_speed=12. * CV.MPH_TO_MS), ], - CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec + HONDA_PILOT_4G.specs, radar_dbc_dict('acura_ilx_2016_can_generated'), flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, ) @@ -268,7 +292,7 @@ class CAR(Platforms): flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, ) HONDA_CIVIC = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], + [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video="https://youtu.be/-IkImTe1NYE")], CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec radar_dbc_dict('honda_civic_touring_2016_can_generated'), ) @@ -339,6 +363,7 @@ HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) +HONDA_BOSCH_CANFD = CAR.with_flags(HondaFlags.BOSCH_CANFD) DBC = CAR.create_dbc_map() diff --git a/opendbc_repo/opendbc/car/hyundai/carstate.py b/opendbc_repo/opendbc/car/hyundai/carstate.py index cb58d3d5c2..ae8ae1bf5e 100644 --- a/opendbc_repo/opendbc/car/hyundai/carstate.py +++ b/opendbc_repo/opendbc/car/hyundai/carstate.py @@ -16,6 +16,8 @@ PREV_BUTTON_SAMPLES = 8 CLUSTER_SAMPLE_RATE = 20 # frames STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS +# Cancel button can sometimes be ACC pause/resume button, main button can also enable on some cars +ENABLE_BUTTONS = (Buttons.RES_ACCEL, Buttons.SET_DECEL, Buttons.CANCEL) BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} @@ -53,6 +55,7 @@ class CarState(CarStateBase): "CRUISE_BUTTONS" self.is_metric = False self.buttons_counter = 0 + self.low_speed_alert = False self.cruise_info = {} @@ -62,6 +65,12 @@ class CarState(CarStateBase): self.params = CarControllerParams(CP) + def recent_button_interaction(self) -> bool: + # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state + # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons + # Main button also can trigger an engagement on these cars + return any(btn in ENABLE_BUTTONS for btn in self.cruise_buttons) or any(self.main_buttons) + def update(self, can_parsers) -> structs.CarState: cp = can_parsers[Bus.pt] cp_cam = can_parsers[Bus.cam] @@ -191,6 +200,15 @@ class CarState(CarStateBase): *create_button_events(self.main_buttons[-1], prev_main_buttons, {1: ButtonType.mainCruise}), *create_button_events(self.lda_button, prev_lda_button, {1: ButtonType.lkas})] + ret.blockPcmEnable = not self.recent_button_interaction() + + # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) + if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + self.low_speed_alert = True + if ret.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + ret.lowSpeedAlert = self.low_speed_alert + return ret def update_canfd(self, can_parsers) -> structs.CarState: @@ -284,6 +302,8 @@ class CarState(CarStateBase): *create_button_events(self.main_buttons[-1], prev_main_buttons, {1: ButtonType.mainCruise}), *create_button_events(self.lda_button, prev_lda_button, {1: ButtonType.lkas})] + ret.blockPcmEnable = not self.recent_button_interaction() + return ret def get_can_parsers_canfd(self, CP): diff --git a/opendbc_repo/opendbc/car/hyundai/fingerprints.py b/opendbc_repo/opendbc/car/hyundai/fingerprints.py index 9d7c783146..31f3bb3b36 100644 --- a/opendbc_repo/opendbc/car/hyundai/fingerprints.py +++ b/opendbc_repo/opendbc/car/hyundai/fingerprints.py @@ -53,11 +53,13 @@ FW_VERSIONS = { b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEH MFC AT EUR RHD 1.00 1.00 95740-G2400 180222', ], }, CAR.HYUNDAI_IONIQ_PHEV_2019: { @@ -277,12 +279,14 @@ FW_VERSIONS = { b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', + b'\xf1\x00TM ESC \x1b 102 \x08\x08 58910-S1DA0', b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', + b'\xf1\x00TM MDPS R 1.00 1.05 57700-S1500 4TSDP105', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', @@ -728,11 +732,14 @@ FW_VERSIONS = { }, CAR.KIA_NIRO_EV_2ND_GEN: { (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG__ RDR ----- 1.00 1.00 99110-AT200 ', b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', ], (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2EMFC AT EUR LHD 1.00 1.00 99211-AT200 240315', b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + b'\xf1\x00SG2EMFC AT USA LHD 1.00 1.00 99211-AT200 240401', ], }, CAR.KIA_NIRO_PHEV: { @@ -1043,6 +1050,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9220 14K', b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', diff --git a/opendbc_repo/opendbc/car/hyundai/interface.py b/opendbc_repo/opendbc/car/hyundai/interface.py index 0cdf71c6a5..eb51469f90 100644 --- a/opendbc_repo/opendbc/car/hyundai/interface.py +++ b/opendbc_repo/opendbc/car/hyundai/interface.py @@ -23,7 +23,7 @@ class CarInterface(CarInterfaceBase): RadarInterface = RadarInterface @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "hyundai" cam_can = CanBus(None, fingerprint).CAM @@ -32,10 +32,10 @@ class CarInterface(CarInterfaceBase): if ret.flags & HyundaiFlags.CANFD: # Shared configuration for CAN-FD cars - ret.experimentalLongitudinalAvailable = candidate not in CANFD_UNSUPPORTED_LONGITUDINAL_CAR + ret.alphaLongitudinalAvailable = candidate not in CANFD_UNSUPPORTED_LONGITUDINAL_CAR if lka_steering and Ecu.adas not in [fw.ecu for fw in car_fw]: # this needs to be figured out for cars without an ADAS ECU - ret.experimentalLongitudinalAvailable = False + ret.alphaLongitudinalAvailable = False ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] @@ -79,7 +79,7 @@ class CarInterface(CarInterfaceBase): else: # Shared configuration for non CAN-FD cars - ret.experimentalLongitudinalAvailable = candidate not in UNSUPPORTED_LONGITUDINAL_CAR + ret.alphaLongitudinalAvailable = candidate not in UNSUPPORTED_LONGITUDINAL_CAR ret.enableBsm = 0x58b in fingerprint[0] # Send LFA message on cars with HDA @@ -122,7 +122,7 @@ class CarInterface(CarInterfaceBase): # Common longitudinal control setup ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or Bus.radar not in DBC[ret.carFingerprint] - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + ret.openpilotLongitudinalControl = alpha_long and ret.alphaLongitudinalAvailable ret.pcmCruise = not ret.openpilotLongitudinalControl ret.startingState = True ret.vEgoStarting = 0.1 diff --git a/opendbc_repo/opendbc/car/hyundai/values.py b/opendbc_repo/opendbc/car/hyundai/values.py index 8772fb4aa4..1e30b363cc 100644 --- a/opendbc_repo/opendbc/car/hyundai/values.py +++ b/opendbc_repo/opendbc/car/hyundai/values.py @@ -196,12 +196,12 @@ class CAR(Platforms): flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, ) HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], + [HyundaiCarDocs("Hyundai Elantra 2021-23", video="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), flags=HyundaiFlags.CHECKSUM_CRC8, ) HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", + [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, @@ -253,7 +253,7 @@ class CAR(Platforms): HYUNDAI_KONA_2022 = HyundaiPlatformConfig( [HyundaiCarDocs("Hyundai Kona 2022", car_parts=CarParts.common([CarHarness.hyundai_o]))], CarSpecs(mass=1491, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CAMERA_SCC, + flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.ALT_LIMITS_2, ) HYUNDAI_KONA_EV = HyundaiPlatformConfig( [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], @@ -266,7 +266,7 @@ class CAR(Platforms): flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV | HyundaiFlags.ALT_LIMITS, ) HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", + [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video="https://www.youtube.com/watch?v=U2fOCmcQ8hw", car_parts=CarParts.common([CarHarness.hyundai_r]))], CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, @@ -282,13 +282,13 @@ class CAR(Platforms): flags=HyundaiFlags.FCEV, ) HYUNDAI_SANTA_FE = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", + [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video="https://youtu.be/bjDR0YjM__s", car_parts=CarParts.common([CarHarness.hyundai_d]))], CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, ) HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", + [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video="https://youtu.be/VnHzSTygTS4", car_parts=CarParts.common([CarHarness.hyundai_l]))], HYUNDAI_SANTA_FE.specs, flags=HyundaiFlags.CHECKSUM_CRC8, @@ -304,7 +304,7 @@ class CAR(Platforms): flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, ) HYUNDAI_SONATA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", + [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video="https://www.youtube.com/watch?v=ix63r9kE3Fw", car_parts=CarParts.common([CarHarness.hyundai_a]))], CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, @@ -312,7 +312,6 @@ class CAR(Platforms): HYUNDAI_SONATA_LF = HyundaiPlatformConfig( [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, ) HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( @@ -329,7 +328,7 @@ class CAR(Platforms): ) HYUNDAI_PALISADE = HyundaiPlatformConfig( [ - HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), ], CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), @@ -404,16 +403,19 @@ class CAR(Platforms): ) KIA_NIRO_EV = HyundaiPlatformConfig( [ - HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), - HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Niro EV 2019", "All", video="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Niro EV 2020", "All", video="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), + HyundaiCarDocs("Kia Niro EV 2021", "All", video="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro EV 2022", "All", video="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), ], CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, ) KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], + [ + HyundaiCarDocs("Kia Niro EV (without HDA II) 2023-25", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Kia Niro EV (with HDA II) 2025", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_r])), + ], KIA_NIRO_EV.specs, flags=HyundaiFlags.EV, ) @@ -483,9 +485,9 @@ class CAR(Platforms): ) KIA_SORENTO = HyundaiPlatformConfig( [ - HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", + HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), + HyundaiCarDocs("Kia Sorento 2019", video="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), ], CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, @@ -504,7 +506,7 @@ class CAR(Platforms): flags=HyundaiFlags.RADAR_SCC, ) KIA_STINGER = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", + [HyundaiCarDocs("Kia Stinger 2018-20", video="https://www.youtube.com/watch?v=MJ94qoofYw0", car_parts=CarParts.common([CarHarness.hyundai_c]))], CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable ) diff --git a/opendbc_repo/opendbc/car/interfaces.py b/opendbc_repo/opendbc/car/interfaces.py index 84509490e5..65cbc24b5b 100644 --- a/opendbc_repo/opendbc/car/interfaces.py +++ b/opendbc_repo/opendbc/car/interfaces.py @@ -27,6 +27,10 @@ ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 FRICTION_THRESHOLD = 0.3 +# ISO 11270 +ISO_LATERAL_ACCEL = 3.0 # m/s^2 +ISO_LATERAL_JERK = 5.0 # m/s^3 + TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'torque_data/params.toml') TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'torque_data/override.toml') TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'torque_data/substitute.toml') @@ -135,7 +139,7 @@ class CarInterfaceBase(ABC): @classmethod def get_params(cls, candidate: str, fingerprint: dict[int, dict[int, int]], car_fw: list[structs.CarParams.CarFw], - experimental_long: bool, docs: bool) -> structs.CarParams: + alpha_long: bool, docs: bool) -> structs.CarParams: ret = CarInterfaceBase.get_std_params(candidate) platform = PLATFORMS[candidate] @@ -148,7 +152,7 @@ class CarInterfaceBase(ABC): ret.tireStiffnessFactor = platform.config.specs.tireStiffnessFactor ret.flags |= int(platform.config.flags) - ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs) + ret = cls._get_params(ret, candidate, fingerprint, car_fw, alpha_long, docs) # Vehicle mass is published curb weight plus assumed payload such as a human driver; notCars have no assumed payload if not ret.notCar: @@ -163,7 +167,7 @@ class CarInterfaceBase(ABC): @staticmethod @abstractmethod def _get_params(ret: structs.CarParams, candidate, fingerprint: dict[int, dict[int, int]], - car_fw: list[structs.CarParams.CarFw], experimental_long: bool, docs: bool) -> structs.CarParams: + car_fw: list[structs.CarParams.CarFw], alpha_long: bool, docs: bool) -> structs.CarParams: raise NotImplementedError @staticmethod @@ -235,9 +239,6 @@ class CarInterfaceBase(ABC): tune.torque.latAccelOffset = 0.0 tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg - def _update(self) -> structs.CarState: - return self.CS.update(self.can_parsers) - def update(self, can_packets: list[tuple[int, list[CanData]]]) -> structs.CarState: # parse can for cp in self.can_parsers.values(): @@ -245,7 +246,7 @@ class CarInterfaceBase(ABC): cp.update_strings(can_packets) # get CarState - ret = self._update() + ret = self.CS.update(self.can_parsers) ret.canValid = all(cp.can_valid for cp in self.can_parsers.values()) ret.canTimeout = any(cp.bus_timeout for cp in self.can_parsers.values()) diff --git a/opendbc_repo/opendbc/car/isotp_parallel_query.py b/opendbc_repo/opendbc/car/isotp_parallel_query.py index 2ab569c7b7..57925e4239 100644 --- a/opendbc_repo/opendbc/car/isotp_parallel_query.py +++ b/opendbc_repo/opendbc/car/isotp_parallel_query.py @@ -42,13 +42,13 @@ class IsoTpParallelQuery: self.can_send([msg]) def _can_rx(self, addr, sub_addr=None): - """Helper function to retrieve message with specified address and subadress from buffer""" + """Helper function to retrieve message with specified address and subaddress from buffer""" keep_msgs = [] if sub_addr is None: msgs = self.msg_buffer[addr] else: - # Filter based on subadress + # Filter based on subaddress msgs = [] for m in self.msg_buffer[addr]: first_byte = m[1][0] diff --git a/opendbc_repo/opendbc/car/mazda/fingerprints.py b/opendbc_repo/opendbc/car/mazda/fingerprints.py index 1704954595..fa49f9b80f 100644 --- a/opendbc_repo/opendbc/car/mazda/fingerprints.py +++ b/opendbc_repo/opendbc/car/mazda/fingerprints.py @@ -6,6 +6,7 @@ Ecu = CarParams.Ecu FW_VERSIONS = { CAR.MAZDA_CX5_2022: { (Ecu.eps, 0x730, None): [ + b'KBST-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ @@ -20,12 +21,14 @@ FW_VERSIONS = { b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXGC-188K2-\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ + b'KBSV-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -41,6 +44,7 @@ FW_VERSIONS = { b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYA4-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/opendbc_repo/opendbc/car/mazda/interface.py b/opendbc_repo/opendbc/car/mazda/interface.py index 72fcd84475..ff2869ccfb 100755 --- a/opendbc_repo/opendbc/car/mazda/interface.py +++ b/opendbc_repo/opendbc/car/mazda/interface.py @@ -12,7 +12,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "mazda" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.mazda)] ret.radarUnavailable = True diff --git a/opendbc_repo/opendbc/car/mazda/values.py b/opendbc_repo/opendbc/car/mazda/values.py index 876557ab50..e85b352b85 100644 --- a/opendbc_repo/opendbc/car/mazda/values.py +++ b/opendbc_repo/opendbc/car/mazda/values.py @@ -67,7 +67,7 @@ class CAR(Platforms): MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) ) MAZDA_CX9_2021 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], + [MazdaCarDocs("Mazda CX-9 2021-23", video="https://youtu.be/dA3duO4a0O4")], MAZDA_CX9.specs ) MAZDA_CX5_2022 = MazdaPlatformConfig( diff --git a/opendbc_repo/opendbc/car/mock/interface.py b/opendbc_repo/opendbc/car/mock/interface.py index d825e54e1b..0a58f6ed28 100755 --- a/opendbc_repo/opendbc/car/mock/interface.py +++ b/opendbc_repo/opendbc/car/mock/interface.py @@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "mock" ret.mass = 1700. ret.wheelbase = 2.70 diff --git a/opendbc_repo/opendbc/car/nissan/interface.py b/opendbc_repo/opendbc/car/nissan/interface.py index 6f2eb021a4..6216291673 100644 --- a/opendbc_repo/opendbc/car/nissan/interface.py +++ b/opendbc_repo/opendbc/car/nissan/interface.py @@ -10,7 +10,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "nissan" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.nissan)] ret.autoResumeSng = False diff --git a/opendbc_repo/opendbc/car/nissan/values.py b/opendbc_repo/opendbc/car/nissan/values.py index f16cd442e9..a2c93f8fe3 100644 --- a/opendbc_repo/opendbc/car/nissan/values.py +++ b/opendbc_repo/opendbc/car/nissan/values.py @@ -1,9 +1,9 @@ from dataclasses import dataclass, field -from enum import IntFlag +from enum import Enum, IntFlag from opendbc.car import AngleSteeringLimits, Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, uds from opendbc.car.structs import CarParams -from opendbc.car.docs_definitions import CarDocs, CarHarness, CarParts +from opendbc.car.docs_definitions import CarDocs, CarFootnote, CarHarness, CarParts, Column from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = CarParams.Ecu @@ -29,10 +29,17 @@ class NissanSafetyFlags(IntFlag): ALT_EPS_BUS = 1 +class Footnote(Enum): + SETUP = CarFootnote( + "See more setup details for Nissan.", + Column.MAKE, setup_note=True) + + @dataclass class NissanCarDocs(CarDocs): package: str = "ProPILOT Assist" car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) + footnotes: list[Enum] = field(default_factory=lambda: [Footnote.SETUP]) @dataclass(frozen=True) @@ -52,7 +59,7 @@ class CAR(Platforms): NissanCarSpecs(mass=1610, wheelbase=2.705) ) NISSAN_LEAF = NissanPlatformConfig( - [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], + [NissanCarDocs("Nissan Leaf 2018-23", video="https://youtu.be/vaMbtAh_0cY")], NissanCarSpecs(mass=1610, wheelbase=2.705), {Bus.pt: 'nissan_leaf_2018_generated'}, ) diff --git a/opendbc_repo/opendbc/car/rivian/carcontroller.py b/opendbc_repo/opendbc/car/rivian/carcontroller.py index 8828958271..c1d0d308eb 100644 --- a/opendbc_repo/opendbc/car/rivian/carcontroller.py +++ b/opendbc_repo/opendbc/car/rivian/carcontroller.py @@ -1,3 +1,4 @@ +import numpy as np from opendbc.can.packer import CANPacker from opendbc.car import Bus, apply_driver_steer_torque_limits from opendbc.car.interfaces import CarControllerBase @@ -18,21 +19,24 @@ class CarController(CarControllerBase): can_sends = [] apply_torque = 0 + steer_max = round(float(np.interp(CS.out.vEgoRaw, CarControllerParams.STEER_MAX_LOOKUP[0], + CarControllerParams.STEER_MAX_LOOKUP[1]))) if CC.latActive: - new_torque = int(round(CC.actuators.torque * CarControllerParams.STEER_MAX)) + new_torque = int(round(CC.actuators.torque * steer_max)) apply_torque = apply_driver_steer_torque_limits(new_torque, self.apply_torque_last, - CS.out.steeringTorque, CarControllerParams) + CS.out.steeringTorque, CarControllerParams, steer_max) # send steering command self.apply_torque_last = apply_torque - can_sends.append(create_lka_steering(self.packer, CS.acm_lka_hba_cmd, apply_torque, CC.latActive)) + can_sends.append(create_lka_steering(self.packer, self.frame, CS.acm_lka_hba_cmd, apply_torque, CC.enabled, CC.latActive)) if self.frame % 5 == 0: can_sends.append(create_wheel_touch(self.packer, CS.sccm_wheel_touch, CC.enabled)) # Longitudinal control if self.CP.openpilotLongitudinalControl: - can_sends.append(create_longitudinal(self.packer, self.frame % 15, actuators.accel, CC.enabled)) + accel = float(np.clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)) + can_sends.append(create_longitudinal(self.packer, self.frame, accel, CC.enabled)) else: interface_status = None if CC.cruiseControl.cancel: @@ -46,7 +50,7 @@ class CarController(CarControllerBase): can_sends.append(create_adas_status(self.packer, CS.vdm_adas_status, interface_status)) new_actuators = actuators.as_builder() - new_actuators.torque = apply_torque / CarControllerParams.STEER_MAX + new_actuators.torque = apply_torque / steer_max new_actuators.torqueOutputCan = apply_torque self.frame += 1 diff --git a/opendbc_repo/opendbc/car/rivian/carstate.py b/opendbc_repo/opendbc/car/rivian/carstate.py index e47e811700..c2ccaaeef1 100644 --- a/opendbc_repo/opendbc/car/rivian/carstate.py +++ b/opendbc_repo/opendbc/car/rivian/carstate.py @@ -68,10 +68,7 @@ class CarState(CarStateBase): ret.gearShifter = GEAR_MAP.get(int(cp.vl["VDM_PropStatus"]["VDM_Prndl_Status"]), GearShifter.unknown) # Doors - ret.doorOpen = (cp_adas.vl["IndicatorLights"]["RearDriverDoor"] != 2 or - cp_adas.vl["IndicatorLights"]["FrontPassengerDoor"] != 2 or - cp_adas.vl["IndicatorLights"]["DriverDoor"] != 2 or - cp_adas.vl["IndicatorLights"]["RearPassengerDoor"] != 2) + ret.doorOpen = any(cp_adas.vl["IndicatorLights"][door] != 2 for door in ("RearDriverDoor", "FrontPassengerDoor", "DriverDoor", "RearPassengerDoor")) # Blinkers ret.leftBlinker = cp_adas.vl["IndicatorLights"]["TurnLightLeft"] in (1, 2) diff --git a/opendbc_repo/opendbc/car/rivian/interface.py b/opendbc_repo/opendbc/car/rivian/interface.py index bc6f66e53f..07b69ce0ae 100644 --- a/opendbc_repo/opendbc/car/rivian/interface.py +++ b/opendbc_repo/opendbc/car/rivian/interface.py @@ -3,6 +3,7 @@ from opendbc.car.interfaces import CarInterfaceBase from opendbc.car.rivian.carcontroller import CarController from opendbc.car.rivian.carstate import CarState from opendbc.car.rivian.radar_interface import RadarInterface +from opendbc.car.rivian.values import RivianSafetyFlags class CarInterface(CarInterfaceBase): @@ -11,12 +12,12 @@ class CarInterface(CarInterfaceBase): RadarInterface = RadarInterface @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "rivian" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.rivian)] - ret.steerActuatorDelay = 0.25 + ret.steerActuatorDelay = 0.15 ret.steerLimitTimer = 0.4 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) @@ -24,10 +25,10 @@ class CarInterface(CarInterfaceBase): ret.radarUnavailable = True # TODO: pending finding/handling missing set speed and fixing up radar parser - ret.experimentalLongitudinalAvailable = False - if experimental_long: + ret.alphaLongitudinalAvailable = False + if alpha_long: ret.openpilotLongitudinalControl = True - #ret.safetyConfigs[0].safetyParam |= Panda.FLAG_RIVIAN_LONG_CONTROL + ret.safetyConfigs[0].safetyParam |= RivianSafetyFlags.LONG_CONTROL.value ret.longitudinalActuatorDelay = 0.35 ret.vEgoStopping = 0.25 diff --git a/opendbc_repo/opendbc/car/rivian/riviancan.py b/opendbc_repo/opendbc/car/rivian/riviancan.py index 9961306c7e..d51b15c90e 100644 --- a/opendbc_repo/opendbc/car/rivian/riviancan.py +++ b/opendbc_repo/opendbc/car/rivian/riviancan.py @@ -11,40 +11,32 @@ def checksum(data, poly, xor_output): return crc ^ xor_output -def create_lka_steering(packer, acm_lka_hba_cmd, apply_torque, enabled): - values = {s: acm_lka_hba_cmd[s] for s in [ - "ACM_lkaHbaCmd_Counter", - "ACM_lkaHbaCmd_Checksum", - "ACM_HapticRequest", - "ACM_lkaStrToqReq", - "ACM_lkaSymbolState", - "ACM_lkaToiFlt", - "ACM_lkaActToi", +def create_lka_steering(packer, frame, acm_lka_hba_cmd, apply_torque, enabled, active): + # forward auto high beam and speed limit status and nothing else + values = {s: acm_lka_hba_cmd[s] for s in ( "ACM_hbaSysState", - "ACM_FailinfoAeb", - "ACM_lkaRHWarning", - "ACM_lkaLHWarning", - "ACM_lkaLaneRecogState", - "ACM_hbaOpt", "ACM_hbaLamp", - "ACM_lkaHandsoffSoundWarning", - "ACM_lkaHandsoffDisplayWarning", - "ACM_unkown1", - "ACM_unkown2", - "ACM_unkown3", - "ACM_unkown4", - "ACM_unkown6", - ]} + "ACM_hbaOnOffState", + "ACM_slifOnOffState", + )} - if enabled: - values["ACM_lkaActToi"] = 1 - values["ACM_lkaSymbolState"] = 3 - values["ACM_lkaLaneRecogState"] = 3 - values["ACM_lkaStrToqReq"] = apply_torque - values["ACM_unkown2"] = 1 - values["ACM_unkown3"] = 4 - values["ACM_unkown4"] = 160 - values["ACM_unkown6"] = 1 + values |= { + "ACM_lkaHbaCmd_Counter": frame % 15, + "ACM_lkaStrToqReq": apply_torque, + "ACM_lkaActToi": active, + + "ACM_lkaLaneRecogState": 3 if enabled else 0, + "ACM_lkaSymbolState": 3 if enabled else 0, + + # static values + "ACM_lkaElkRequest": 0, + "ACM_ldwlkaOnOffState": 2, # 2=LKAS+LDW on + "ACM_elkOnOffState": 1, # 1=LKAS on + # TODO: what are these used for? + "ACM_ldwWarnTypeState": 2, # always 2 + "ACM_ldwWarnTimingState": 1, # always 1 + #"ACM_lkaHandsoffDisplayWarning": 1, # TODO: we can send this when openpilot wants you to pay attention + } data = packer.make_can_msg("ACM_lkaHbaCmd", 0, values)[1] values["ACM_lkaHbaCmd_Checksum"] = checksum(data[1:], 0x1D, 0x63) @@ -74,10 +66,9 @@ def create_longitudinal(packer, frame, accel, enabled): values = { "ACM_longitudinalRequest_Counter": frame % 15, "ACM_AccelerationRequest": accel if enabled else 0, - "ACM_VehicleHoldRequired": 0, - "ACM_PrndRequired": 0, + "ACM_PrndRequest": 0, "ACM_longInterfaceEnable": 1 if enabled else 0, - "ACM_AccelerationRequestType": 0, + "ACM_VehicleHoldRequest": 0, } data = packer.make_can_msg("ACM_longitudinalRequest", 0, values)[1] diff --git a/opendbc_repo/opendbc/car/rivian/values.py b/opendbc_repo/opendbc/car/rivian/values.py index c0fdb8bb20..bd50e622e8 100644 --- a/opendbc_repo/opendbc/car/rivian/values.py +++ b/opendbc_repo/opendbc/car/rivian/values.py @@ -1,9 +1,9 @@ from dataclasses import dataclass, field from enum import StrEnum, IntFlag -from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, structs +from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, structs, uds from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts, Device -from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 from opendbc.car.vin import Vin @@ -28,6 +28,7 @@ class ModelYear(StrEnum): class RivianCarDocs(CarDocs): package: str = "All" car_parts: CarParts = field(default_factory=CarParts([Device.threex_angled_mount, CarHarness.rivian])) + setup_video: str = "https://youtu.be/uaISd1j7Z4U" @dataclass @@ -66,6 +67,10 @@ def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str return {str(c) for c in candidates} +RIVIAN_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf1a0) +RIVIAN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + FW_QUERY_CONFIG = FwQueryConfig( requests=[ Request( @@ -73,7 +78,21 @@ FW_QUERY_CONFIG = FwQueryConfig( [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], rx_offset=0x40, bus=0, - ) + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_ECU_HARDWARE_NUMBER_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_ECU_HARDWARE_NUMBER_RESPONSE], + rx_offset=0x40, + bus=0, + logging=True, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, RIVIAN_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, RIVIAN_VERSION_RESPONSE], + rx_offset=0x40, + bus=0, + logging=True, + ), ], match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, ) @@ -88,10 +107,16 @@ GEAR_MAP = { class CarControllerParams: - # The Rivian R1T we tested on achieves slightly more lateral acceleration going left vs. right - # and lateral acceleration rises as speed increases. This value is set conservatively to - # reach a maximum of 2.5-3.0 m/s^2 turning left at 80 mph, but is less at lower speeds - STEER_MAX = 250 # ~2.5 m/s^2 + # The R1T 2023 and R1S 2023 we tested on achieves slightly more lateral acceleration going left vs. right + # and lateral acceleration falls linearly as speed decreases from 38 mph to 20 mph. These values are set + # conservatively to reach a maximum of 3.0 m/s^2 turning left at 80 mph + + # These refer to turning left: + # 250 is ~2.8 m/s^2 above 17 m/s, then linearly ramps to ~1.6 m/s^2 from 17 m/s to 9 m/s + # TODO: it is theorized older models have different steering racks and achieve down to half the + # lateral acceleration referenced here at all speeds. detect this and ship a torque increase for those models + STEER_MAX = 250 # 350 is intended to maintain lateral accel, not increase it + STEER_MAX_LOOKUP = [9, 17], [350, 250] STEER_STEP = 1 STEER_DELTA_UP = 3 # torque increase per refresh STEER_DELTA_DOWN = 5 # torque decrease per refresh diff --git a/opendbc_repo/opendbc/car/subaru/fingerprints.py b/opendbc_repo/opendbc/car/subaru/fingerprints.py index 53f1e6f0b9..51c01e1030 100644 --- a/opendbc_repo/opendbc/car/subaru/fingerprints.py +++ b/opendbc_repo/opendbc/car/subaru/fingerprints.py @@ -54,6 +54,7 @@ FW_VERSIONS = { (Ecu.abs, 0x7b0, None): [ b'\xa1 \x02\x01', b'\xa1 \x02\x02', + b'\xa1 \x03\x02', b'\xa1 \x03\x03', b'\xa1 \x04\x01', ], @@ -67,6 +68,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7e0, None): [ b'\xde"a0\x07', + b'\xe2"a0\x07', b'\xde,\xa0@\x07', b'\xe2"aq\x07', b'\xe2,\xa0@\x07', @@ -463,6 +465,7 @@ FW_VERSIONS = { b'\xa1 \x06\x00', b'\xa1 \x06\x01', b'\xa1 \x06\x02', + b'\xa1 \x06\x03', b'\xa1 \x07\x00', b'\xa1 \x07\x02', b'\xa1 \x07\x03', @@ -496,6 +499,7 @@ FW_VERSIONS = { b'\xe2"`p\x07', b'\xe2"`q\x07', b'\xe3,\xa0@\x07', + b'\xe2,\xa0p\x07', ], (Ecu.transmission, 0x7e1, None): [ b'\xa5\xf6D@\x00', @@ -505,6 +509,7 @@ FW_VERSIONS = { b'\xa7\x8e\xf40\x00', b'\xa7\xf6D@\x00', b'\xa7\xfe\xf4@\x00', + b'\xa7\xfe\xf6@\x00', ], }, CAR.SUBARU_FORESTER_2022: { diff --git a/opendbc_repo/opendbc/car/subaru/interface.py b/opendbc_repo/opendbc/car/subaru/interface.py index 4fe4f2dd98..6d940fde7a 100644 --- a/opendbc_repo/opendbc/car/subaru/interface.py +++ b/opendbc_repo/opendbc/car/subaru/interface.py @@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "subaru" ret.radarUnavailable = True # for HYBRID CARS to be upstreamed, we need: @@ -86,9 +86,9 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"unknown car: {candidate}") - ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | - SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + ret.alphaLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | + SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) + ret.openpilotLongitudinalControl = alpha_long and ret.alphaLongitudinalAvailable if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value diff --git a/opendbc_repo/opendbc/car/subaru/values.py b/opendbc_repo/opendbc/car/subaru/values.py index 68171c5dd5..c65f38eced 100644 --- a/opendbc_repo/opendbc/car/subaru/values.py +++ b/opendbc_repo/opendbc/car/subaru/values.py @@ -103,7 +103,7 @@ class SubaruCarDocs(CarDocs): def init_make(self, CP: CarParams): self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) - if CP.experimentalLongitudinalAvailable: + if CP.alphaLongitudinalAvailable: self.footnotes.append(Footnote.EXP_LONG) @@ -142,8 +142,8 @@ class CAR(Platforms): SUBARU_IMPREZA = SubaruPlatformConfig( [ SubaruCarDocs("Subaru Impreza 2017-19"), - SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + SubaruCarDocs("Subaru Crosstrek 2018-19", video="https://youtu.be/Agww7oE1k-s?t=26"), + SubaruCarDocs("Subaru XV 2018-19", video="https://youtu.be/Agww7oE1k-s?t=26"), ], CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), ) diff --git a/opendbc_repo/opendbc/car/tesla/carcontroller.py b/opendbc_repo/opendbc/car/tesla/carcontroller.py index 9a16b102b4..89c69863f9 100644 --- a/opendbc_repo/opendbc/car/tesla/carcontroller.py +++ b/opendbc_repo/opendbc/car/tesla/carcontroller.py @@ -1,9 +1,58 @@ import numpy as np +import math from opendbc.can.packer import CANPacker -from opendbc.car import Bus, apply_std_steer_angle_limits -from opendbc.car.interfaces import CarControllerBase +from opendbc.car import ACCELERATION_DUE_TO_GRAVITY, Bus, AngleSteeringLimits, DT_CTRL, rate_limit +from opendbc.car.interfaces import CarControllerBase, ISO_LATERAL_ACCEL from opendbc.car.tesla.teslacan import TeslaCAN from opendbc.car.tesla.values import CarControllerParams +from opendbc.car.vehicle_model import VehicleModel + +# limit angle rate to both prevent a fault and for low speed comfort (~12 mph rate down to 0 mph) +MAX_ANGLE_RATE = 5 # deg/20ms frame, EPS faults at 12 at a standstill + +# Add extra tolerance for average banked road since safety doesn't have the roll +AVERAGE_ROAD_ROLL = 0.06 # ~3.4 degrees, 6% superelevation. higher actual roll lowers lateral acceleration +MAX_LATERAL_ACCEL = ISO_LATERAL_ACCEL + (ACCELERATION_DUE_TO_GRAVITY * AVERAGE_ROAD_ROLL) # ~3.6 m/s^2 +MAX_LATERAL_JERK = 3.0 + (ACCELERATION_DUE_TO_GRAVITY * AVERAGE_ROAD_ROLL) # ~3.6 m/s^3 + + +def get_max_angle_delta(v_ego_raw: float, VM: VehicleModel): + max_curvature_rate_sec = MAX_LATERAL_JERK / (max(v_ego_raw, 1) ** 2) # (1/m)/s + max_angle_rate_sec = math.degrees(VM.get_steer_from_curvature(max_curvature_rate_sec, v_ego_raw, 0)) # deg/s + return max_angle_rate_sec * (DT_CTRL * CarControllerParams.STEER_STEP) + + +def get_max_angle(v_ego_raw: float, VM: VehicleModel): + max_curvature = MAX_LATERAL_ACCEL / (max(v_ego_raw, 1) ** 2) # 1/m + return math.degrees(VM.get_steer_from_curvature(max_curvature, v_ego_raw, 0)) # deg + + +def apply_tesla_steer_angle_limits(apply_angle: float, apply_angle_last: float, v_ego_raw: float, steering_angle: float, + lat_active: bool, limits: AngleSteeringLimits, VM: VehicleModel) -> float: + # *** max lateral jerk limit *** + max_angle_delta = get_max_angle_delta(v_ego_raw, VM) + + # prevent fault + max_angle_delta = min(max_angle_delta, MAX_ANGLE_RATE) + new_apply_angle = rate_limit(apply_angle, apply_angle_last, -max_angle_delta, max_angle_delta) + + # *** max lateral accel limit *** + max_angle = get_max_angle(v_ego_raw, VM) + new_apply_angle = np.clip(new_apply_angle, -max_angle, max_angle) + + # angle is current angle when inactive + if not lat_active: + new_apply_angle = steering_angle + + # prevent fault + return float(np.clip(new_apply_angle, -limits.STEER_ANGLE_MAX, limits.STEER_ANGLE_MAX)) + + +def get_safety_CP(): + # We use the TESLA_MODEL_Y platform for lateral limiting to match safety + # A Model 3 at 40 m/s using the Model Y limits sees a <0.3% difference in max angle (from curvature factor) + from opendbc.car.tesla.interface import CarInterface + return CarInterface.get_non_essential_params("TESLA_MODEL_Y") class CarController(CarControllerBase): @@ -13,37 +62,40 @@ class CarController(CarControllerBase): self.packer = CANPacker(dbc_names[Bus.party]) self.tesla_can = TeslaCAN(self.packer) + # Vehicle model used for lateral limiting + self.VM = VehicleModel(get_safety_CP()) + def update(self, CC, CS, now_nanos): actuators = CC.actuators can_sends = [] - # Disengage and allow for user override on high torque inputs - # TODO: move this to a generic disengageRequested carState field and set CC.cruiseControl.cancel based on it - hands_on_fault = CS.hands_on_level >= 3 - cruise_cancel = CC.cruiseControl.cancel or hands_on_fault - lat_active = CC.latActive and not hands_on_fault + # Tesla EPS enforces disabling steering on heavy lateral override force. + # When enabling in a tight curve, we wait until user reduces steering force to start steering. + # Canceling is done on rising edge and is handled generically with CC.cruiseControl.cancel + lat_active = CC.latActive and CS.hands_on_level < 3 if self.frame % 2 == 0: # Angular rate limit based on speed - self.apply_angle_last = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, - CS.out.steeringAngleDeg, CC.latActive, CarControllerParams.ANGLE_LIMITS) + self.apply_angle_last = apply_tesla_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, + CS.out.steeringAngleDeg, lat_active, + CarControllerParams.ANGLE_LIMITS, self.VM) - can_sends.append(self.tesla_can.create_steering_control(self.apply_angle_last, lat_active, (self.frame // 2) % 16)) + can_sends.append(self.tesla_can.create_steering_control(self.apply_angle_last, lat_active)) if self.frame % 10 == 0: - can_sends.append(self.tesla_can.create_steering_allowed((self.frame // 10) % 16)) + can_sends.append(self.tesla_can.create_steering_allowed()) # Longitudinal control if self.CP.openpilotLongitudinalControl: if self.frame % 4 == 0: - state = 13 if cruise_cancel else 4 # 4=ACC_ON, 13=ACC_CANCEL_GENERIC_SILENT + state = 13 if CC.cruiseControl.cancel else 4 # 4=ACC_ON, 13=ACC_CANCEL_GENERIC_SILENT accel = float(np.clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)) cntr = (self.frame // 4) % 8 can_sends.append(self.tesla_can.create_longitudinal_command(state, accel, cntr, CS.out.vEgo, CC.longActive)) else: # Increment counter so cancel is prioritized even without openpilot longitudinal - if cruise_cancel: + if CC.cruiseControl.cancel: cntr = (CS.das_control["DAS_controlCounter"] + 1) % 8 can_sends.append(self.tesla_can.create_longitudinal_command(13, 0, cntr, CS.out.vEgo, False)) diff --git a/opendbc_repo/opendbc/car/tesla/carstate.py b/opendbc_repo/opendbc/car/tesla/carstate.py index a374090dcb..0a240e659e 100644 --- a/opendbc_repo/opendbc/car/tesla/carstate.py +++ b/opendbc_repo/opendbc/car/tesla/carstate.py @@ -15,9 +15,22 @@ class CarState(CarStateBase): self.can_define = CANDefine(DBC[CP.carFingerprint][Bus.party]) self.shifter_values = self.can_define.dv["DI_systemStatus"]["DI_gear"] + self.autopark = False + self.autopark_prev = False + self.cruise_enabled_prev = False + self.hands_on_level = 0 self.das_control = None + def update_autopark_state(self, autopark_state: str, cruise_enabled: bool): + autopark_now = autopark_state in ("ACTIVE", "COMPLETE", "SELFPARK_STARTED") + if autopark_now and not self.autopark_prev and not self.cruise_enabled_prev: + self.autopark = True + if not autopark_now: + self.autopark = False + self.autopark_prev = autopark_now + self.cruise_enabled_prev = cruise_enabled + def update(self, can_parsers) -> structs.CarState: cp_party = can_parsers[Bus.party] cp_ap_party = can_parsers[Bus.ap_party] @@ -43,18 +56,28 @@ class CarState(CarStateBase): ret.steeringRateDeg = -cp_ap_party.vl["SCCM_steeringAngleSensor"]["SCCM_steeringAngleSpeed"] ret.steeringTorque = -epas_status["EPAS3S_torsionBarTorque"] - # This matches stock logic, but with halved minimum frames (0.25-0.3s) - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > STEER_THRESHOLD, 15) + # stock handsOnLevel uses >0.5 for 0.25s, but is too slow + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > STEER_THRESHOLD, 5) eac_status = self.can_define.dv["EPAS3S_sysStatus"]["EPAS3S_eacStatus"].get(int(epas_status["EPAS3S_eacStatus"]), None) ret.steerFaultPermanent = eac_status == "EAC_FAULT" ret.steerFaultTemporary = eac_status == "EAC_INHIBITED" + # FSD disengages using union of handsOnLevel (slow overrides) and high angle rate faults (fast overrides, high speed) + eac_error_code = self.can_define.dv["EPAS3S_sysStatus"]["EPAS3S_eacErrorCode"].get(int(epas_status["EPAS3S_eacErrorCode"]), None) + ret.steeringDisengage = self.hands_on_level >= 3 or (eac_status == "EAC_INHIBITED" and + eac_error_code == "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY") + # Cruise state cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp_party.vl["DI_state"]["DI_cruiseState"]), None) speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp_party.vl["DI_state"]["DI_speedUnits"]), None) - ret.cruiseState.enabled = cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL") + autopark_state = self.can_define.dv["DI_state"]["DI_autoparkState"].get(int(cp_party.vl["DI_state"]["DI_autoparkState"]), None) + cruise_enabled = cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL") + self.update_autopark_state(autopark_state, cruise_enabled) + + # Match panda safety cruise engaged logic + ret.cruiseState.enabled = cruise_enabled and not self.autopark if speed_units == "KPH": ret.cruiseState.speed = max(cp_party.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS, 1e-3) elif speed_units == "MPH": @@ -71,8 +94,8 @@ class CarState(CarStateBase): ret.doorOpen = cp_party.vl["UI_warning"]["anyDoorOpen"] == 1 # Blinkers - ret.leftBlinker = cp_party.vl["UI_warning"]["leftBlinkerOn"] != 0 - ret.rightBlinker = cp_party.vl["UI_warning"]["rightBlinkerOn"] != 0 + ret.leftBlinker = cp_party.vl["UI_warning"]["leftBlinkerBlinking"] in (1, 2) + ret.rightBlinker = cp_party.vl["UI_warning"]["rightBlinkerBlinking"] in (1, 2) # Seatbelt ret.seatbeltUnlatched = cp_party.vl["UI_warning"]["buckleStatus"] != 1 @@ -84,6 +107,12 @@ class CarState(CarStateBase): # AEB ret.stockAeb = cp_ap_party.vl["DAS_control"]["DAS_aebEvent"] == 1 + # LKAS + ret.stockLkas = cp_ap_party.vl["DAS_steeringControl"]["DAS_steeringControlType"] == 2 # LANE_KEEP_ASSIST + + # Stock Autosteer should be off (includes FSD) + ret.invalidLkasSetting = cp_ap_party.vl["DAS_settings"]["DAS_autosteerEnabled"] != 0 + # Buttons # ToDo: add Gap adjust button # Messages needed by carcontroller @@ -105,7 +134,9 @@ class CarState(CarStateBase): ap_party_messages = [ ("DAS_control", 25), + ("DAS_steeringControl", 50), ("DAS_status", 2), + ("DAS_settings", 2), ("SCCM_steeringAngleSensor", 100), ] diff --git a/opendbc_repo/opendbc/car/tesla/fingerprints.py b/opendbc_repo/opendbc/car/tesla/fingerprints.py index b39c3f6339..978897f33c 100644 --- a/opendbc_repo/opendbc/car/tesla/fingerprints.py +++ b/opendbc_repo/opendbc/car/tesla/fingerprints.py @@ -8,10 +8,14 @@ FW_VERSIONS = { (Ecu.eps, 0x730, None): [ b'TeM3_E014p10_0.0.0 (16),E014.17.00', b'TeM3_E014p10_0.0.0 (16),EL014.17.00', + b'TeM3_ES014p11_0.0.0 (25),ES014.19.0', b'TeMYG4_DCS_Update_0.0.0 (13),E4014.28.1', b'TeMYG4_DCS_Update_0.0.0 (9),E4014.26.0', + b'TeMYG4_Legacy3Y_0.0.0 (2),E4015.02.0', + b'TeMYG4_Legacy3Y_0.0.0 (5),E4015.03.2', b'TeMYG4_Main_0.0.0 (59),E4H014.29.0', b'TeMYG4_Main_0.0.0 (65),E4H015.01.0', + b'TeMYG4_Main_0.0.0 (67),E4H015.02.1', b'TeMYG4_SingleECU_0.0.0 (33),E4S014.27', ], }, @@ -25,6 +29,7 @@ FW_VERSIONS = { b'TeMYG4_DCS_Update_0.0.0 (13),Y4P002.27.1', b'TeMYG4_DCS_Update_0.0.0 (9),Y4P002.25.0', b'TeMYG4_Legacy3Y_0.0.0 (2),Y4003.02.0', + b'TeMYG4_Legacy3Y_0.0.0 (5),Y4003.03.2', b'TeMYG4_Legacy3Y_0.0.0 (2),Y4P003.02.0', b'TeMYG4_SingleECU_0.0.0 (33),Y4S002.26', ], diff --git a/opendbc_repo/opendbc/car/tesla/interface.py b/opendbc_repo/opendbc/car/tesla/interface.py index 6b882806a2..e73e4dd107 100644 --- a/opendbc_repo/opendbc/car/tesla/interface.py +++ b/opendbc_repo/opendbc/car/tesla/interface.py @@ -10,20 +10,20 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "tesla" - ret.dashcamOnly = True ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.tesla)] - ret.steerLimitTimer = 1.0 + ret.steerLimitTimer = 0.4 ret.steerActuatorDelay = 0.1 + ret.steerAtStandstill = True ret.steerControlType = structs.CarParams.SteerControlType.angle ret.radarUnavailable = True - ret.experimentalLongitudinalAvailable = True - if experimental_long: + ret.alphaLongitudinalAvailable = True + if alpha_long: ret.openpilotLongitudinalControl = True ret.safetyConfigs[0].safetyParam |= TeslaSafetyFlags.LONG_CONTROL.value diff --git a/opendbc_repo/opendbc/car/tesla/teslacan.py b/opendbc_repo/opendbc/car/tesla/teslacan.py index a5c1de13b7..5592556b86 100644 --- a/opendbc_repo/opendbc/car/tesla/teslacan.py +++ b/opendbc_repo/opendbc/car/tesla/teslacan.py @@ -7,25 +7,16 @@ class TeslaCAN: def __init__(self, packer): self.packer = packer - @staticmethod - def checksum(msg_id, dat): - ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) - ret += sum(dat) - return ret & 0xFF - - def create_steering_control(self, angle, enabled, counter): + def create_steering_control(self, angle, enabled): values = { "DAS_steeringAngleRequest": -angle, "DAS_steeringHapticRequest": 0, "DAS_steeringControlType": 1 if enabled else 0, - "DAS_steeringControlCounter": counter, } - data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.party, values)[1] - values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) return self.packer.make_can_msg("DAS_steeringControl", CANBUS.party, values) - def create_longitudinal_command(self, acc_state, accel, cntr, v_ego, active): + def create_longitudinal_command(self, acc_state, accel, counter, v_ego, active): set_speed = max(v_ego * CV.MS_TO_KPH, 0) if active: # TODO: this causes jerking after gas override when above set speed @@ -39,19 +30,13 @@ class TeslaCAN: "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, "DAS_accelMin": accel, "DAS_accelMax": max(accel, 0), - "DAS_controlCounter": cntr, - "DAS_controlChecksum": 0, + "DAS_controlCounter": counter, } - data = self.packer.make_can_msg("DAS_control", CANBUS.party, values)[1] - values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) return self.packer.make_can_msg("DAS_control", CANBUS.party, values) - def create_steering_allowed(self, counter): + def create_steering_allowed(self): values = { "APS_eacAllow": 1, - "APS_eacMonitorCounter": counter, } - data = self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values)[1] - values["APS_eacMonitorChecksum"] = self.checksum(0x27d, data[:2]) return self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values) diff --git a/opendbc_repo/opendbc/car/tesla/values.py b/opendbc_repo/opendbc/car/tesla/values.py index 8453a73f51..43aea4813f 100644 --- a/opendbc_repo/opendbc/car/tesla/values.py +++ b/opendbc_repo/opendbc/car/tesla/values.py @@ -15,19 +15,23 @@ class Footnote(Enum): "See this page for more information.", Column.MODEL) + SETUP = CarFootnote( + "See more setup details for Tesla.", + Column.MAKE, setup_note=True) + @dataclass class TeslaCarDocsHW3(CarDocs): package: str = "All" car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.tesla_a])) - footnotes: list[Enum] = field(default_factory=lambda: [Footnote.HW_TYPE]) + footnotes: list[Enum] = field(default_factory=lambda: [Footnote.HW_TYPE, Footnote.SETUP]) @dataclass class TeslaCarDocsHW4(CarDocs): package: str = "All" car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.tesla_b])) - footnotes: list[Enum] = field(default_factory=lambda: [Footnote.HW_TYPE]) + footnotes: list[Enum] = field(default_factory=lambda: [Footnote.HW_TYPE, Footnote.SETUP]) @dataclass @@ -39,9 +43,8 @@ class CAR(Platforms): TESLA_MODEL_3 = TeslaPlatformConfig( [ # TODO: do we support 2017? It's HW3 - # TODO: do we support 2025? It's HW4 TeslaCarDocsHW3("Tesla Model 3 (with HW3) 2019-23"), - TeslaCarDocsHW4("Tesla Model 3 (with HW4) 2024"), + TeslaCarDocsHW4("Tesla Model 3 (with HW4) 2024-25"), ], CarSpecs(mass=1899., wheelbase=2.875, steerRatio=12.0), ) @@ -109,4 +112,4 @@ class TeslaFlags(IntFlag): DBC = CAR.create_dbc_map() -STEER_THRESHOLD = 0.5 +STEER_THRESHOLD = 1 diff --git a/opendbc_repo/opendbc/car/tests/routes.py b/opendbc_repo/opendbc/car/tests/routes.py index d582ec6e35..ed73404702 100644 --- a/opendbc_repo/opendbc/car/tests/routes.py +++ b/opendbc_repo/opendbc/car/tests/routes.py @@ -27,7 +27,6 @@ non_tested_cars = [ VOLKSWAGEN.VOLKSWAGEN_CRAFTER_MK2, # need a route from an ACC-equipped Crafter SUBARU.SUBARU_FORESTER_HYBRID, TESLA.TESLA_MODEL_3, - TESLA.TESLA_MODEL_Y, ] @@ -53,6 +52,7 @@ routes = [ CarTestRoute("54827bf84c38b14f|2023-01-25--14-14-11", FORD.FORD_BRONCO_SPORT_MK1), CarTestRoute("f8eaaccd2a90aef8|2023-05-04--15-10-09", FORD.FORD_ESCAPE_MK4), + CarTestRoute("56574443e0c3783c/00000002--c00bd0fe69", FORD.FORD_ESCAPE_MK4_5), CarTestRoute("62241b0c7fea4589|2022-09-01--15-32-49", FORD.FORD_EXPLORER_MK6), CarTestRoute("e886087f430e7fe7|2023-06-16--23-06-36", FORD.FORD_FOCUS_MK4), CarTestRoute("bd37e43731e5964b|2023-04-30--10-42-26", FORD.FORD_MAVERICK_MK1), @@ -106,7 +106,9 @@ routes = [ CarTestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.HONDA_RIDGELINE), CarTestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), CarTestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.HONDA_CIVIC_2022), - CarTestRoute("1f032f5173c8ad99/00000006--573b3fcaf5", HONDA.HONDA_CIVIC_2022), # Civic Type R with manual transmission + CarTestRoute("1f032f5173c8ad99/00000006--573b3fcaf5", HONDA.HONDA_CIVIC_2022), # Civic Type R with manual transmission + CarTestRoute("b1c832ad56b6bc9d/00000010--debfcf5867", HONDA.HONDA_CIVIC_2022), # 2025 Civic Hatch Hybrid with new eCVT transmission + CarTestRoute("f9c43864cf057d05|2024-01-15--23-01-20", HONDA.HONDA_PILOT_4G), # TODO: Replace with a newer route CarTestRoute("87d7f06ade479c2e|2023-09-11--23-30-11", HYUNDAI.HYUNDAI_AZERA_6TH_GEN), CarTestRoute("66189dd8ec7b50e6|2023-09-20--07-02-12", HYUNDAI.HYUNDAI_AZERA_HEV_6TH_GEN), @@ -214,12 +216,14 @@ routes = [ CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.TOYOTA_RAV4_TSS2_2022), # hybrid CarTestRoute("20ba9ade056a8c7b|2021-02-08--21-57-35", TOYOTA.TOYOTA_RAV4_PRIME), # SecOC CarTestRoute("8bfb000e03b2a257/00000004--f9eee5f52e", TOYOTA.TOYOTA_SIENNA_4TH_GEN), # SecOC + CarTestRoute("0b54d0594d924cd9/00000057--b6206a3205", TOYOTA.TOYOTA_YARIS), # SecOC CarTestRoute("7a31f030957b9c85|2023-04-01--14-12-51", TOYOTA.LEXUS_ES), CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ES), # hybrid CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), CarTestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ES_TSS2), # hybrid CarTestRoute("da23c367491f53e2|2021-05-21--09-09-11", TOYOTA.LEXUS_CTH, segment=3), CarTestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), + CarTestRoute("7f8f479cfa6f392a/00000001--9a84b69c9d", TOYOTA.LEXUS_RC_TSS2), CarTestRoute("ab9b64a5e5960cba|2023-10-24--17-32-08", TOYOTA.LEXUS_GS_F), CarTestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), CarTestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RX), # hybrid @@ -309,7 +313,8 @@ routes = [ CarTestRoute("bc095dc92e101734/000000db--ee9fe46e57", RIVIAN.RIVIAN_R1_GEN1), - #CarTestRoute("46cdc864ec865f4b/00000007--42f94db730", TESLA.TESLA_MODEL_Y), + CarTestRoute("46cdc864ec865f4b/00000007--42f94db730", TESLA.TESLA_MODEL_Y), + CarTestRoute("2c912ca5de3b1ee9/0000025d--6eb6bcbca4", TESLA.TESLA_MODEL_Y, segment=4), # Segments that test specific issues # Controls mismatch due to standstill threshold diff --git a/opendbc_repo/opendbc/car/tests/test_car_interfaces.py b/opendbc_repo/opendbc/car/tests/test_car_interfaces.py index 50f3b4df20..f33deed6ed 100644 --- a/opendbc_repo/opendbc/car/tests/test_car_interfaces.py +++ b/opendbc_repo/opendbc/car/tests/test_car_interfaces.py @@ -36,7 +36,7 @@ def get_fuzzy_car_interface_args(draw: DrawType) -> dict: params_strategy = st.fixed_dictionaries({ 'fingerprints': fingerprint_strategy, 'car_fw': car_fw_strategy, - 'experimental_long': st.booleans(), + 'alpha_long': st.booleans(), }) params: dict = draw(params_strategy) @@ -59,7 +59,7 @@ class TestCarInterfaces: args = get_fuzzy_car_interface_args(data.draw) car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], - experimental_long=args['experimental_long'], docs=False) + alpha_long=args['alpha_long'], docs=False) car_interface = CarInterface(car_params) assert car_params assert car_interface diff --git a/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py b/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py index 417ce3d205..58d2ba65d0 100644 --- a/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py +++ b/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py @@ -260,7 +260,7 @@ class TestFwFingerprintTiming: print(f'get_vin {name} case, query time={self.total_time / self.N} seconds') def test_fw_query_timing(self, subtests, mocker): - total_ref_time = {1: 7.1, 2: 7.7} + total_ref_time = {1: 7.3, 2: 7.9} brand_ref_times = { 1: { 'gm': 1.0, @@ -275,7 +275,7 @@ class TestFwFingerprintTiming: 'tesla': 0.1, 'toyota': 0.7, 'volkswagen': 0.65, - 'rivian': 0.1, + 'rivian': 0.3, }, 2: { 'ford': 1.6, diff --git a/opendbc_repo/opendbc/car/tests/test_lateral_limits.py b/opendbc_repo/opendbc/car/tests/test_lateral_limits.py index 7104086cf9..8fc06595d6 100755 --- a/opendbc_repo/opendbc/car/tests/test_lateral_limits.py +++ b/opendbc_repo/opendbc/car/tests/test_lateral_limits.py @@ -7,11 +7,10 @@ import sys from opendbc.car import DT_CTRL from opendbc.car.car_helpers import interfaces -from opendbc.car.interfaces import get_torque_params +from opendbc.car.interfaces import ISO_LATERAL_ACCEL, get_torque_params from opendbc.car.values import PLATFORMS # ISO 11270 - allowed up jerk is strictly lower than recommended limits -MAX_LAT_ACCEL = 3.0 # m/s^2 MAX_LAT_JERK_UP = 2.5 # m/s^3 MAX_LAT_JERK_DOWN = 5.0 # m/s^3 MAX_LAT_JERK_UP_TOLERANCE = 0.5 # m/s^3 @@ -65,7 +64,7 @@ class TestLateralLimits: assert down_jerk <= MAX_LAT_JERK_DOWN def test_max_lateral_accel(self): - assert self.torque_params["MAX_LAT_ACCEL_MEASURED"] <= MAX_LAT_ACCEL + assert self.torque_params["MAX_LAT_ACCEL_MEASURED"] <= ISO_LATERAL_ACCEL class LatAccelReport: diff --git a/opendbc_repo/opendbc/car/torque_data/override.toml b/opendbc_repo/opendbc/car/torque_data/override.toml index 16e07c2a46..af2ef323db 100644 --- a/opendbc_repo/opendbc/car/torque_data/override.toml +++ b/opendbc_repo/opendbc/car/torque_data/override.toml @@ -22,6 +22,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] # Guess "FORD_BRONCO_SPORT_MK1" = [nan, 1.5, nan] "FORD_ESCAPE_MK4" = [nan, 1.5, nan] +"FORD_ESCAPE_MK4_5" = [nan, 1.5, nan] "FORD_EXPLORER_MK6" = [nan, 1.5, nan] "FORD_F_150_MK14" = [nan, 1.5, nan] "FORD_FOCUS_MK4" = [nan, 1.5, nan] @@ -41,7 +42,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "CADILLAC_ESCALADE" = [1.899999976158142, 1.842270016670227, 0.1120000034570694] "CADILLAC_ESCALADE_ESV_2019" = [1.15, 1.3, 0.2] "CADILLAC_XT4" = [1.45, 1.6, 0.2] -"CHEVROLET_BOLT_EUV" = [2.0, 2.0, 0.05] +"CHEVROLET_BOLT_EUV" = [1.0, 2.0, 0.175] "CHEVROLET_SILVERADO" = [1.9, 1.9, 0.112] "CHEVROLET_TRAILBLAZER" = [1.33, 1.9, 0.16] "CHEVROLET_TRAVERSE" = [1.33, 1.33, 0.18] @@ -73,6 +74,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "HYUNDAI_STARIA_4TH_GEN" = [1.8, 2.0, 0.15] "GENESIS_GV70_ELECTRIFIED_1ST_GEN" = [1.9, 1.9, 0.09] "GENESIS_G80_2ND_GEN_FL" = [2.5819356441497803, 2.5, 0.11244568973779678] +# Note that some Rivians achieve significantly less lateral acceleration than this "RIVIAN_R1_GEN1" = [2.8, 2.5, 0.07] "HYUNDAI_NEXO_1ST_GEN" = [2.5, 2.5, 0.1] @@ -82,3 +84,4 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] # Manually checked "HONDA_CIVIC_2022" = [2.5, 1.2, 0.15] "HONDA_HRV_3G" = [2.5, 1.2, 0.2] +"HONDA_PILOT_4G" = [1.0, 1.0, 0.2] diff --git a/opendbc_repo/opendbc/car/torque_data/params.toml b/opendbc_repo/opendbc/car/torque_data/params.toml index 4bb8d45c53..fde2ca221d 100644 --- a/opendbc_repo/opendbc/car/torque_data/params.toml +++ b/opendbc_repo/opendbc/car/torque_data/params.toml @@ -73,6 +73,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "TOYOTA_RAV4H" = [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] "TOYOTA_RAV4_TSS2_2022" = [2.241883248393209, 1.9304407208090029, 0.112174] "TOYOTA_SIENNA" = [1.689726, 1.3208264576110418, 0.140456] +"TOYOTA_YARIS" = [2.22984, 1.86145, 0.168189] "VOLKSWAGEN_ARTEON_MK1" = [1.45136518053819, 1.3639364049316804, 0.23806361745695032] "VOLKSWAGEN_ATLAS_MK1" = [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] "VOLKSWAGEN_GOLF_MK7" = [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] diff --git a/opendbc_repo/opendbc/car/torque_data/substitute.toml b/opendbc_repo/opendbc/car/torque_data/substitute.toml index a91ac35895..1a433fa9eb 100644 --- a/opendbc_repo/opendbc/car/torque_data/substitute.toml +++ b/opendbc_repo/opendbc/car/torque_data/substitute.toml @@ -15,6 +15,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "LEXUS_CTH" = "LEXUS_NX" "LEXUS_ES" = "TOYOTA_CAMRY" "LEXUS_RC" = "LEXUS_NX_TSS2" +"LEXUS_RC_TSS2" = "LEXUS_NX_TSS2" "LEXUS_LC_TSS2" = "LEXUS_NX_TSS2" "KIA_OPTIMA_G4" = "HYUNDAI_SONATA" diff --git a/opendbc_repo/opendbc/car/toyota/carcontroller.py b/opendbc_repo/opendbc/car/toyota/carcontroller.py index 8c8dfa1b31..cb6ef47d29 100644 --- a/opendbc_repo/opendbc/car/toyota/carcontroller.py +++ b/opendbc_repo/opendbc/car/toyota/carcontroller.py @@ -272,9 +272,10 @@ class CarController(CarControllerBase): can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert)) # *** static msgs *** - for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: - if self.frame % fr_step == 0 and self.CP.enableDsu and self.CP.carFingerprint in cars: - can_sends.append(CanData(addr, vl, bus)) + if self.CP.enableDsu: + for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: + if self.frame % fr_step == 0 and self.CP.carFingerprint in cars: + can_sends.append(CanData(addr, vl, bus)) # keep radar disabled if self.frame % 20 == 0 and self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: diff --git a/opendbc_repo/opendbc/car/toyota/carstate.py b/opendbc_repo/opendbc/car/toyota/carstate.py index 53f30709d5..ce1b508846 100644 --- a/opendbc_repo/opendbc/car/toyota/carstate.py +++ b/opendbc_repo/opendbc/car/toyota/carstate.py @@ -141,6 +141,7 @@ class CarState(CarStateBase): cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] else: ret.accFaulted = cp.vl["PCM_CRUISE_2"]["ACC_FAULTED"] != 0 + ret.carFaultedNonCritical = cp.vl["PCM_CRUISE_SM"]["TEMP_ACC_FAULTED"] != 0 ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] diff --git a/opendbc_repo/opendbc/car/toyota/fingerprints.py b/opendbc_repo/opendbc/car/toyota/fingerprints.py index 3452c4cbcd..758b984f0a 100644 --- a/opendbc_repo/opendbc/car/toyota/fingerprints.py +++ b/opendbc_repo/opendbc/car/toyota/fingerprints.py @@ -1564,6 +1564,23 @@ FW_VERSIONS = { b'8646F2402200\x00\x00\x00\x00', ], }, + CAR.LEXUS_RC_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966324C8000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15262426000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B24481\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F2403100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ b'\x01896630E36100\x00\x00\x00\x00', @@ -1783,4 +1800,21 @@ FW_VERSIONS = { b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, + CAR.TOYOTA_YARIS: { + (Ecu.engine, 0x700, None): [ + b'\x0189663K015300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965BK003200\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F1526K007500\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0D05300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F5205200\x00\x00\x00\x008646G5202200\x00\x00\x00\x00', + ], + }, } diff --git a/opendbc_repo/opendbc/car/toyota/interface.py b/opendbc_repo/opendbc/car/toyota/interface.py index 4fa1eeea76..21403aa90c 100644 --- a/opendbc_repo/opendbc/car/toyota/interface.py +++ b/opendbc_repo/opendbc/car/toyota/interface.py @@ -21,7 +21,7 @@ class CarInterface(CarInterfaceBase): return CarControllerParams(CP).ACCEL_MIN, CarControllerParams(CP).ACCEL_MAX @staticmethod - def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "toyota" ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.toyota)] ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] @@ -31,7 +31,6 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs[0].safetyParam |= ToyotaSafetyFlags.ALT_BRAKE.value if ret.flags & ToyotaFlags.SECOC.value: - ret.dashcamOnly = True ret.secOcRequired = True ret.safetyConfigs[0].safetyParam |= ToyotaSafetyFlags.SECOC.value @@ -112,10 +111,10 @@ class CarInterface(CarInterfaceBase): # since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle if candidate in (RADAR_ACC_CAR | NO_DSU_CAR): - ret.experimentalLongitudinalAvailable = candidate in RADAR_ACC_CAR + ret.alphaLongitudinalAvailable = candidate in RADAR_ACC_CAR # Disabling radar is only supported on TSS2 radar-ACC cars - if experimental_long and candidate in RADAR_ACC_CAR: + if alpha_long and candidate in RADAR_ACC_CAR: ret.flags |= ToyotaFlags.DISABLE_RADAR.value # openpilot longitudinal enabled by default: diff --git a/opendbc_repo/opendbc/car/toyota/values.py b/opendbc_repo/opendbc/car/toyota/values.py index 889b9d0cb4..59dee497ad 100644 --- a/opendbc_repo/opendbc/car/toyota/values.py +++ b/opendbc_repo/opendbc/car/toyota/values.py @@ -148,8 +148,8 @@ class CAR(Platforms): ) TOYOTA_CAMRY = PlatformConfig( [ - ToyotaCarDocs("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), - ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), + ToyotaCarDocs("Toyota Camry 2018-20", video="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), + ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), ], CarSpecs(mass=3400. * CV.LB_TO_KG, wheelbase=2.82448, steerRatio=13.7, tireStiffnessFactor=0.7933), dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), @@ -187,9 +187,9 @@ class CAR(Platforms): # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid TOYOTA_COROLLA_TSS2 = ToyotaTSS2PlatformConfig( [ - ToyotaCarDocs("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + ToyotaCarDocs("Toyota Corolla 2020-22", video="https://www.youtube.com/watch?v=_66pXk0CBYA"), ToyotaCarDocs("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5), - ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video="https://www.youtube.com/watch?v=_66pXk0CBYA"), # Hybrid platforms ToyotaCarDocs("Toyota Corolla Hybrid 2020-22"), ToyotaCarDocs("Toyota Corolla Hybrid (South America only) 2020-23", min_enable_speed=7.5), @@ -200,7 +200,7 @@ class CAR(Platforms): ) TOYOTA_HIGHLANDER = PlatformConfig( [ - ToyotaCarDocs("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), + ToyotaCarDocs("Toyota Highlander 2017-19", video="https://www.youtube.com/watch?v=0wS0wXSLzoo"), ToyotaCarDocs("Toyota Highlander Hybrid 2017-19"), ], CarSpecs(mass=4516. * CV.LB_TO_KG, wheelbase=2.8194, steerRatio=16.0, tireStiffnessFactor=0.8), @@ -216,9 +216,9 @@ class CAR(Platforms): ) TOYOTA_PRIUS = PlatformConfig( [ - ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius 2017-20", video="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius Prime 2017-20", video="https://www.youtube.com/watch?v=8zopPJI8XQ0"), ], CarSpecs(mass=3045. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.74, tireStiffnessFactor=0.6371), dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), @@ -231,8 +231,8 @@ class CAR(Platforms): ) TOYOTA_PRIUS_TSS2 = ToyotaTSS2PlatformConfig( [ - ToyotaCarDocs("Toyota Prius 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), - ToyotaCarDocs("Toyota Prius Prime 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ToyotaCarDocs("Toyota Prius 2021-22", video="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ToyotaCarDocs("Toyota Prius Prime 2021-22", video="https://www.youtube.com/watch?v=J58TvCpUd4U"), ], CarSpecs(mass=3115. * CV.LB_TO_KG, wheelbase=2.70002, steerRatio=13.4, tireStiffnessFactor=0.6371), ) @@ -246,8 +246,8 @@ class CAR(Platforms): ) TOYOTA_RAV4H = PlatformConfig( [ - ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") + ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video="https://youtu.be/LhT5VzJVfNI?t=26"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video="https://youtu.be/LhT5VzJVfNI?t=26") ], TOYOTA_RAV4.specs, dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), @@ -256,7 +256,7 @@ class CAR(Platforms): ) TOYOTA_RAV4_TSS2 = ToyotaTSS2PlatformConfig( [ - ToyotaCarDocs("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), + ToyotaCarDocs("Toyota RAV4 2019-21", video="https://www.youtube.com/watch?v=wJxjDd42gGA"), ToyotaCarDocs("Toyota RAV4 Hybrid 2019-21"), ], CarSpecs(mass=3585. * CV.LB_TO_KG, wheelbase=2.68986, steerRatio=14.3, tireStiffnessFactor=0.7933), @@ -264,15 +264,15 @@ class CAR(Platforms): TOYOTA_RAV4_TSS2_2022 = ToyotaTSS2PlatformConfig( [ ToyotaCarDocs("Toyota RAV4 2022"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video="https://youtu.be/U0nH9cnrFB0"), ], TOYOTA_RAV4_TSS2.specs, flags=ToyotaFlags.RADAR_ACC, ) TOYOTA_RAV4_TSS2_2023 = ToyotaTSS2PlatformConfig( [ - ToyotaCarDocs("Toyota RAV4 2023-24"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2023-25", video_link="https://youtu.be/4eIsEq4L4Ng"), + ToyotaCarDocs("Toyota RAV4 2023-25"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2023-25", video="https://youtu.be/4eIsEq4L4Ng"), ], TOYOTA_RAV4_TSS2.specs, flags=ToyotaFlags.RADAR_ACC | ToyotaFlags.ANGLE_CONTROL, @@ -281,12 +281,17 @@ class CAR(Platforms): [ToyotaCarDocs("Toyota RAV4 Prime 2021-23", min_enable_speed=MIN_ACC_SPEED)], CarSpecs(mass=4372. * CV.LB_TO_KG, wheelbase=2.68, steerRatio=16.88, tireStiffnessFactor=0.5533), ) + TOYOTA_YARIS = ToyotaSecOCPlatformConfig( + [ToyotaCarDocs("Toyota Yaris 2023 (Non-US only)", min_enable_speed=MIN_ACC_SPEED)], + CarSpecs(mass=1170, wheelbase=2.55, steerRatio=14.80, tireStiffnessFactor=0.5533), + flags=ToyotaFlags.RADAR_ACC, + ) TOYOTA_MIRAI = ToyotaTSS2PlatformConfig( # TSS 2.5 [ToyotaCarDocs("Toyota Mirai 2021")], CarSpecs(mass=4300. * CV.LB_TO_KG, wheelbase=2.91, steerRatio=14.8, tireStiffnessFactor=0.8), ) TOYOTA_SIENNA = PlatformConfig( - [ToyotaCarDocs("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], + [ToyotaCarDocs("Toyota Sienna 2018-20", video="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], CarSpecs(mass=4590. * CV.LB_TO_KG, wheelbase=3.03, steerRatio=15.5, tireStiffnessFactor=0.444), dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), flags=ToyotaFlags.NO_STOP_TIMER, @@ -313,7 +318,7 @@ class CAR(Platforms): LEXUS_ES_TSS2 = ToyotaTSS2PlatformConfig( [ ToyotaCarDocs("Lexus ES 2019-24"), - ToyotaCarDocs("Lexus ES Hybrid 2019-25", video_link="https://youtu.be/BZ29osRVJeg?t=12"), + ToyotaCarDocs("Lexus ES Hybrid 2019-25", video="https://youtu.be/BZ29osRVJeg?t=12"), ], LEXUS_ES.specs, ) @@ -352,6 +357,12 @@ class CAR(Platforms): dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), flags=ToyotaFlags.UNSUPPORTED_DSU, ) + LEXUS_RC_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus RC 2023"), + ], + CarSpecs(mass=3986. * CV.LB_TO_KG, wheelbase=2.73, steerRatio=13.9, tireStiffnessFactor=0.444), + ) LEXUS_RX = PlatformConfig( [ ToyotaCarDocs("Lexus RX 2016", "Lexus Safety System+"), diff --git a/opendbc_repo/opendbc/car/volkswagen/interface.py b/opendbc_repo/opendbc/car/volkswagen/interface.py index 70a67857c8..1a07ba1e1d 100644 --- a/opendbc_repo/opendbc/car/volkswagen/interface.py +++ b/opendbc_repo/opendbc/car/volkswagen/interface.py @@ -10,7 +10,7 @@ class CarInterface(CarInterfaceBase): CarController = CarController @staticmethod - def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, alpha_long, docs) -> structs.CarParams: ret.brand = "volkswagen" ret.radarUnavailable = True @@ -73,8 +73,8 @@ class CarInterface(CarInterfaceBase): # Global longitudinal tuning defaults, can be overridden per-vehicle - ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs - if experimental_long: + ret.alphaLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs + if alpha_long: # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. ret.openpilotLongitudinalControl = True ret.safetyConfigs[0].safetyParam |= VolkswagenSafetyFlags.LONG_CONTROL.value diff --git a/opendbc_repo/opendbc/car/volkswagen/values.py b/opendbc_repo/opendbc/car/volkswagen/values.py index 750a99e1c6..7b4e5a74c5 100644 --- a/opendbc_repo/opendbc/car/volkswagen/values.py +++ b/opendbc_repo/opendbc/car/volkswagen/values.py @@ -147,7 +147,7 @@ class VolkswagenFlags(IntFlag): @dataclass class VolkswagenMQBPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: {Bus.pt: 'vw_mqb_2010'}) + dbc_dict: DbcDict = field(default_factory=lambda: {Bus.pt: 'vw_mqb'}) # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle chassis_codes: set[str] = field(default_factory=set) @@ -156,7 +156,7 @@ class VolkswagenMQBPlatformConfig(PlatformConfig): @dataclass class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: {Bus.pt: 'vw_golf_mk4'}) + dbc_dict: DbcDict = field(default_factory=lambda: {Bus.pt: 'vw_pq'}) def init(self): self.flags |= VolkswagenFlags.PQ @@ -216,11 +216,11 @@ class CAR(Platforms): VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( [ - VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon 2018-23", video="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon R 2020-23", video="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen CC 2018-22", video="https://youtu.be/FAomFKPFlDA"), ], VolkswagenCarSpecs(mass=1733, wheelbase=2.84), chassis_codes={"AN", "3H"}, @@ -249,11 +249,11 @@ class CAR(Platforms): ) VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( [ - VWCarDocs("Volkswagen Crafter 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen e-Crafter 2018-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen Grand California 2019-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN TGE 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN eTGE 2020-24", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen Crafter 2017-24", video="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen e-Crafter 2018-24", video="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen Grand California 2019-24", video="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN TGE 2017-24", video="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN eTGE 2020-24", video="https://youtu.be/4100gLeabmo"), ], VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), chassis_codes={"SY", "SZ", "UY", "UZ"}, diff --git a/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc b/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc index 2dd72d3690..e9a469e090 100644 --- a/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc +++ b/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc @@ -194,15 +194,12 @@ BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM - SG_ GasRegenAlwaysOne2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ GasRegenAlwaysOne : 14|1@0+ (1,0) [0|1] "" NEO - SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO - SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenAccType : 15|2@0+ (1,0) [0|3] "" NEO + SG_ GasRegenChecksum : 32|25@0+ (1,0) [0|0] "" NEO SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO - SG_ GasRegenAlwaysOne3 : 23|1@0+ (1,0) [0|1] "" NEO - SG_ GasRegenCmd : 22|12@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmd : 10|19@0+ (0.125,-22534) [-22534|43001.875] "Nm" NEO BO_ 717 ASCM_2CD: 5 K124_ASCM @@ -310,7 +307,7 @@ CM_ SG_ 481 ACCAlwaysOne "Usually 1 if the car is equipped with ACC"; CM_ SG_ 562 FrictionBrakeUnavailable "1 when ACC brake control is unavailable. Stays high if brake command messages are blocked for a period of time"; CM_ SG_ 497 SystemPowerMode "Describes ignition"; CM_ SG_ 497 SystemBackUpPowerMode "Describes ignition + preconditioning mode, noisy"; -CM_ SG_ 501 PRNDL2 "When ManualMode is Active, Value is 13=L1 12=L2 11=L3 ... 4=L10"; +CM_ SG_ 501 PRNDL2 "When ManualMode is Active, Value is 13=L1 12=L2 11=L3 ... 5=Full 70kW Paddle Regen Unlocked for Gen2 Bolts 4=L10"; CM_ SG_ 532 UserBrakePressure "can be lower than other brake position signals when the brakes are pre-filled from ACC braking and the user presses on the brakes. user-only pressure?"; CM_ SG_ 608 ClusterSpeed "Cluster speed signal seems to match dash on newer cars, but is a lower rate and can be noisier."; CM_ SG_ 761 UserBrakePressure2 "Similar to BRAKE_RELATED->UserBrakePressure"; @@ -350,6 +347,6 @@ VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; VAL_ 320 Intellibeam 1 "Active" 0 "Inactive" ; VAL_ 320 HighBeamsActive 1 "Active" 0 "Inactive" ; VAL_ 320 HighBeamsTemporary 1 "Active" 0 "Inactive" ; -VAL_ 501 PRNDL2 6 "L" 4 "D" 3 "N" 2 "R" 1 "P" 0 "Shifting"; +VAL_ 501 PRNDL2 7 "L3" 6 "L" 5 "L2" 4 "D" 3 "N" 2 "R" 1 "P" 0 "Shifting"; VAL_ 501 TransmissionState 11 "Shifting" 10 "Reverse" 9 "Forward" 8 "Disengaged"; VAL_ 501 ManualMode 1 "Active" 0 "Inactive" diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc index b5e8c14d6c..9da5c1e030 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc @@ -125,17 +125,6 @@ BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON @@ -229,4 +218,4 @@ CM_ SG_ 577 LINE_SOLID "1 = line is solid"; VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; -VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; \ No newline at end of file +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc index dc8def55cb..ec7c41ceec 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc @@ -28,16 +28,17 @@ BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ CAMERA_OVERHEAT : 15|1@0+ (1,0) [0|1] "" BDY SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ LANE_DEPARTURE_ALERT : 9|1@0+ (1,0) [0|1] "" BDY SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_ICON : 22|1@0+ (1,0) [0|1] "" BDY SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 18|3@0+ (1,0) [0|7] "" BDY SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY @@ -50,5 +51,7 @@ CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; +CM_ SG_ 829 CAM_TEMP_HIGH "Some Driver Assist Systems Cannot Operate: Camera Temperature Too High"; +CM_ SG_ 829 CAMERA_OVERHEAT "Lane Keeping Assist Cannot Operate: Camera Too Hot"; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 829 BEEP 5 "solid_beep" 4 "double_beep" 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc index 44a2ce4bcc..6983249e78 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc @@ -61,6 +61,17 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "kph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "kph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "kph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + BO_ 773 SEATBELT_STATUS: 7 BDY SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON @@ -146,6 +157,11 @@ BO_ 1029 DOORS_STATUS: 8 BDY SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + CM_ SG_ 304 "Seems to be platform-agnostic"; CM_ SG_ 316 "Should exist on Nidec"; CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc index 36611eebcf..d219a295e5 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc @@ -46,20 +46,9 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY SG_ CAMERA_OVERHEAT : 15|1@0+ (1,0) [0|1] "" BDY SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_a.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_a.dbc new file mode 100644 index 0000000000..81c03829b2 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_a.dbc @@ -0,0 +1,7 @@ +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_b.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_b.dbc new file mode 100644 index 0000000000..5314ed2dd6 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_steering_control_b.dbc @@ -0,0 +1,7 @@ +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00_2 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc index 5a60a9c9e1..7f9c716d29 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc @@ -1,13 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc index 06327f928f..9697989645 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc @@ -1,6 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; +CM_ "IMPORT _steering_control_b.dbc"; BO_ 392 GEARBOX: 6 XXX SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX @@ -16,13 +17,6 @@ BO_ 399 STEER_STATUS: 6 EPS SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON -BO_ 404 STEERING_CONTROL: 4 EON - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS - BO_ 422 SCM_BUTTONS: 8 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc index 38a312c311..44c5473513 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc @@ -20,11 +20,6 @@ BO_ 446 BRAKE_MODULE: 3 VSA SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc index e9f2fb41aa..a2a07fed9c 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc @@ -40,11 +40,6 @@ BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P"; VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P"; VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc index 89b6ceae35..af24990a68 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc @@ -1,14 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_a.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON @@ -76,11 +69,6 @@ BO_ 927 RADAR_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc index edeaa29993..9c88c725af 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc @@ -1,14 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_a.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 388 BRAKE_ERROR: 8 XXX SG_ BRAKE_ERROR_1 : 32|1@0+ (1,0) [0|1] "" EON @@ -95,11 +88,6 @@ BO_ 927 RADAR_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY -BO_ 1302 XXX_27: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc index fe2ae8f940..a65497d1f2 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc @@ -24,11 +24,6 @@ BO_ 446 BRAKE_MODULE: 3 VSA SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc index 7d0af49217..017c5b15ef 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc @@ -1,5 +1,6 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_control_b.dbc"; BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON @@ -21,14 +22,6 @@ BO_ 419 GEARBOX: 8 PCM SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON -BO_ 404 STEERING_CONTROL: 4 EON - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00_2 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS - BO_ 422 SCM_BUTTONS: 8 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc index 75fd63f3b0..39ebdf49ea 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc @@ -1,6 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; +CM_ "IMPORT _steering_control_b.dbc"; BO_ 399 STEER_STATUS: 6 EPS SG_ STEER_TORQUE_SENSOR : 7|12@0- (-1,0) [-2047.5|2047.5] "tbd" EON @@ -16,14 +17,6 @@ BO_ 401 GEARBOX: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 404 STEERING_CONTROL: 4 EON - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00_2 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS - BO_ 422 SCM_BUTTONS: 8 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc index 371ddd19a8..7a7e76648f 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc @@ -1,14 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc index fa445b3496..3d690b2661 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc @@ -1,13 +1,6 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc index 7a37e0124f..131c723e0e 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc @@ -1,13 +1,7 @@ CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS +CM_ "IMPORT _steering_control_a.dbc"; BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON @@ -67,11 +61,6 @@ BO_ 927 RADAR_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc index fed29d0664..af6d11954a 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc @@ -60,11 +60,6 @@ BO_ 862 HIGHBEAM_CONTROL: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc index 646245b74c..9256347f7e 100644 --- a/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc @@ -73,11 +73,6 @@ BO_ 829 LKAS_HUD: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; diff --git a/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_canfd.dbc b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_canfd.dbc index 31f5a662e2..cc5452d349 100644 --- a/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_canfd.dbc +++ b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_canfd.dbc @@ -209,27 +209,30 @@ BO_ 354 CCNC_0x162: 32 CCNC SG_ ZEROS_2 : 56|8@1+ (1,0) [0|255] "" XXX SG_ LEAD : 64|5@1+ (1,0) [0|31] "" XXX SG_ LEAD_DISTANCE : 69|11@1+ (0.1,0) [0|204.7] "m" XXX - SG_ LEAD_LATERAL : 80|7@1+ (1,0) [0|127] "" XXX + SG_ LEAD_LATERAL : 80|7@1+ (0.1,0) [0|127] "m" XXX SG_ ZEROS_3 : 87|1@0+ (1,0) [0|1] "" XXX SG_ LEAD_ALT : 88|5@1+ (1,0) [0|31] "" XXX SG_ LEAD_ALT_DISTANCE : 93|11@1+ (0.1,0) [0|204.7] "m" XXX - SG_ LEAD_ALT_LATERAL : 104|7@1+ (1,0) [0|127] "" XXX + SG_ LEAD_ALT_LATERAL : 104|7@1+ (0.1,0) [0|127] "m" XXX SG_ ZEROS_4 : 111|1@0+ (1,0) [0|1] "" XXX SG_ LEAD_LEFT : 112|5@1+ (1,0) [0|31] "" XXX SG_ LEAD_LEFT_DISTANCE : 117|11@1+ (0.1,0) [0|204.7] "m" XXX - SG_ LEAD_LEFT_LATERAL : 128|7@1+ (1,0) [0|127] "" XXX + SG_ LEAD_LEFT_LATERAL : 128|7@1+ (0.1,0) [0|127] "m" XXX SG_ ZEROS_5 : 135|1@0+ (1,0) [0|1] "" XXX SG_ LEAD_RIGHT : 136|5@1+ (1,0) [0|31] "" XXX SG_ LEAD_RIGHT_DISTANCE : 141|11@1+ (0.1,0) [0|204.7] "m" XXX - SG_ LEAD_RIGHT_LATERAL : 152|7@1+ (1,0) [0|127] "" XXX + SG_ LEAD_RIGHT_LATERAL : 152|7@1+ (0.1,0) [0|127] "m" XXX SG_ ZEROS_6 : 159|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_7 : 160|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_8 : 168|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_9 : 176|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_10 : 184|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_11 : 192|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_12 : 200|8@1+ (1,0) [0|255] "" XXX - SG_ ZEROS_13 : 208|5@1+ (1,0) [0|31] "" XXX + SG_ ZEROS_7 : 162|3@0+ (1,0) [0|7] "" XXX + SG_ LEAD_LEFT_REAR_STATUS : 167|5@0+ (1,0) [0|31] "" XXX + SG_ LEAD_LEFT_REAR_DISTANCE : 175|8@0+ (0.1,0) [0|255] "m" XXX + SG_ LEAD_LEFT_REAR_LATERAL : 182|7@0+ (0.1,0) [0|127] "m" XXX + SG_ ZEROS_8 : 183|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_9 : 191|8@0+ (1,0) [0|255] "" XXX + SG_ LEAD_RIGHT_REAR_STATUS : 196|5@0+ (1,0) [0|31] "" XXX + SG_ LEAD_RIGHT_REAR_DISTANCE : 197|8@1+ (0.1,0) [0|255] "m" XXX + SG_ LEAD_RIGHT_REAR_LATERAL : 205|7@1+ (0.1,0) [0|127] "m" XXX + SG_ ZEROS_10 : 212|1@0+ (1,0) [0|1] "" XXX SG_ FAULT_FSS : 213|3@1+ (1,0) [0|7] "" XXX SG_ FAULT_FCA : 216|3@1+ (1,0) [0|7] "" XXX SG_ FAULT_LSS : 219|3@1+ (1,0) [0|7] "" XXX @@ -243,7 +246,7 @@ BO_ 354 CCNC_0x162: 32 CCNC SG_ FAULT_HDP : 243|3@1+ (1,0) [0|7] "" XXX SG_ FAULT_DAS : 246|3@1+ (1,0) [0|7] "" XXX SG_ FAULT_ESS : 249|3@1+ (1,0) [0|7] "" XXX - SG_ ZEROS_14 : 252|4@1+ (1,0) [0|15] "" XXX + SG_ ZEROS_11 : 252|4@1+ (1,0) [0|15] "" XXX BO_ 357 SPAS1: 24 APRK SG_ CHECKSUM : 0|16@1+ (1,0) [0|65535] "" XXX diff --git a/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc b/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc index 6300ea9425..46a65a7b7e 100644 --- a/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc +++ b/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc @@ -58,6 +58,10 @@ BO_ 689 PROPILOT_HUD: 8 XXX SG_ unknown55 : 55|8@0+ (1,0) [0|63] "" XXX SG_ unknown59 : 59|4@0+ (1,0) [0|15] "" XXX +BO_ 451 PROPILOT_BRAKE: 8 XXX + SG_ BRAKE_PRESSURE : 5|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_ACTIVE : 47|1@0+ (1,0) [0|1] "" XXX + BO_ 783 CRUISE_STATE: 3 XXX SG_ CRUISE_ENABLED : 3|1@0+ (1,0) [0|1] "" XXX @@ -107,7 +111,7 @@ BO_ 1227 LKAS_SETTINGS: 8 XXX VAL_ 1228 PROPILOT_NA_MSGS 0 "NO_MSG" 1 "NA_FRONT_CAMERA_IMPARED" 2 "STEERING_ASSIST_ON_STANDBY" 3 "NA_PARKING_ASSIST_ENABLED" 4 "STEER_ASSIST_CURRENTLY_NA" 5 "NA_BAD_WEATHER" 6 "NA_PARK_BRAKE_ON" 7 "NA_SEATBELT_NOT_FASTENED" ; VAL_ 1228 BOTTOM_MSG 0 "OK_STEER_ASSIST_SETTINGS" 1 "NO_MSG" 2 "PRESS_SET_TO_SET_SPEED" 3 "PRESS_RES_SET_TO_CHANGE_SPEED" 4 "PRESS_RES_TO_RESTART" 5 "NO_MSG" 6 "CRUISE_NOT_AVAIL" 7 "NO_MSG" ; -VAL_ 689 FOLLOW_DISTANCE 0 "NO_FOLLOW_DISTANCE" 1 "FOLLOW_DISTANCE_1" 2 "FOLLOW_DISTANCE_2" 3 "FOLLOW_DISANCE_3" ; +VAL_ 689 FOLLOW_DISTANCE 0 "NO_FOLLOW_DISTANCE" 1 "FOLLOW_DISTANCE_1" 2 "FOLLOW_DISTANCE_2" 3 "FOLLOW_DISTANCE_3" ; VAL_ 689 AUDIBLE_TONE 0 "NO_TONE" 1 "CONT" 2 "FAST_BEEP_CONT" 3 "TRIPLE_FAST_BEEP_CONT" 4 "SLOW_BEEP_CONT" 5 "QUAD_SLOW_BEEP_CONT" 6 "SINGLE_BEEP_ONCE" 7 "DOUBLE_BEEP_ONCE" ; VAL_ 689 SMALL_STEERING_WHEEL_ICON 0 "NO_ICON" 1 "GRAY_ICON" 2 "GRAY_ICON_FLASHING" 3 "GREEN_ICON" 4 "GREEN_ICON_FLASHING" 5 "RED_ICON" 6 "RED_ICON_FLASHING" 7 "YELLOW_ICON" ; VAL_ 689 LARGE_STEERING_WHEEL_ICON 0 "NO_STEERINGWHEEL" 1 "GRAY_STEERINGWHEEL" 2 "GREEN_STEERINGWHEEL" 3 "GREEN_STEERINGWHEEL_FLASHING" ; diff --git a/opendbc_repo/opendbc/dbc/rivian_park_assist_can.dbc b/opendbc_repo/opendbc/dbc/rivian_park_assist_can.dbc new file mode 100644 index 0000000000..b18f0a53d8 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/rivian_park_assist_can.dbc @@ -0,0 +1,55 @@ +VERSION "ParkAssistCAN" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: ACM CGM EPAS_P ESP IBM OCS RCM SAS TestTool VDM Vector_XXX + +BO_ 794 WheelButtons: 7 XXX + SG_ LeftButton_ScrollClick : 19|2@0+ (1,0) [0|3] "" XXX + SG_ LeftButton_RightClick : 21|2@0+ (1,0) [0|3] "" XXX + SG_ LeftButton_LeftClick : 22|2@1+ (1,0) [0|3] "" XXX + SG_ LeftButton_Scroll : 31|8@0+ (1,0) [0|255] "" XXX + SG_ RightButton_ScrollClick : 35|2@0+ (1,0) [0|3] "" XXX + SG_ RightButton_RightClick : 37|2@0+ (1,0) [0|3] "" XXX + SG_ RightButton_LeftClick : 38|2@1+ (1,0) [0|3] "" XXX + SG_ RightButton_Scroll : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 848 BSM_BlindSpotIndicator: 4 XXX + SG_ BSM_BlindSpotIndicator_Checksum : 0|8@1+ (1,0) [0|255] "" XXX + SG_ BSM_BlindSpotIndicator_Counter : 11|4@0+ (1,0) [0|15] "" XXX + SG_ BSM_BlindSpotIndicator_Left : 29|2@0+ (1,0) [0|3] "" XXX + SG_ BSM_BlindSpotIndicator_Right : 30|2@1+ (1,0) [0|3] "" XXX + +VAL_ 848 BSM_BlindSpotIndicator_Left 0 "OFF" 1 "OBJECT_DETECTED" 2 "ACTIVE_WARNING" ; +VAL_ 848 BSM_BlindSpotIndicator_Right 0 "OFF" 1 "OBJECT_DETECTED" 2 "ACTIVE_WARNING" ; \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/rivian_primary_actuator.dbc b/opendbc_repo/opendbc/dbc/rivian_primary_actuator.dbc index 686ec6fe32..fb25e871ce 100644 --- a/opendbc_repo/opendbc/dbc/rivian_primary_actuator.dbc +++ b/opendbc_repo/opendbc/dbc/rivian_primary_actuator.dbc @@ -85,28 +85,27 @@ BO_ 272 ACM_SteeringControl: 8 ACM SG_ ACM_SteeringAngleRequest : 23|15@0+ (0.1,-1638.4) [-1638.4|1638.3] "deg" EPAS_P BO_ 288 ACM_lkaHbaCmd: 8 ACM - SG_ ACM_lkaHbaCmd_Checksum : 7|8@0+ (1,0) [0|0] "" EPAS_P - SG_ ACM_lkaHbaCmd_Counter : 11|4@0+ (1,0) [0|0] "" EPAS_P - SG_ ACM_unkown1 : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACM_unkown6 : 13|1@0+ (1,0) [0|1] "" XXX - SG_ ACM_unkown5 : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ACM_lkaHbaCmd_Checksum : 7|8@0+ (1,0) [0|255] "" EPAS_P + SG_ ACM_lkaHbaCmd_Counter : 11|4@0+ (1,0) [0|15] "" EPAS_P + SG_ ACM_lkaElkRequest : 14|3@0+ (1,0) [0|7] "" EPAS_P SG_ ACM_HapticRequest : 15|1@0+ (1,0) [0|1] "" EPAS_P SG_ ACM_lkaStrToqReq : 23|11@0+ (1,-1024) [-1024|1024] "" EPAS_P SG_ ACM_lkaSymbolState : 26|3@0+ (1,0) [0|7] "" EPAS_P SG_ ACM_lkaToiFlt : 27|1@0+ (1,0) [0|1] "" EPAS_P SG_ ACM_lkaActToi : 28|1@0+ (1,0) [0|1] "" EPAS_P SG_ ACM_hbaSysState : 34|3@0+ (1,0) [0|7] "" EPAS_P - SG_ ACM_FailinfoAeb : 37|3@0+ (1,0) [0|7] "" EPAS_P - SG_ ACM_unkown2 : 38|2@1+ (1,0) [0|3] "" XXX - SG_ ACM_lkaRHWarning : 41|2@0+ (1,0) [0|3] "" EPAS_P - SG_ ACM_lkaLHWarning : 43|2@0+ (1,0) [0|3] "" EPAS_P + SG_ ACM_hbaLamp : 35|1@0+ (1,0) [0|1] "" EPAS_P + SG_ ACM_slifOnOffState : 37|2@0+ (1,0) [0|3] "" EPAS_P + SG_ ACM_elkOnOffState : 39|2@0+ (1,0) [0|3] "" EPAS_P + SG_ ACM_ldwLHWarning : 43|3@0+ (1,0) [0|7] "" EPAS_P SG_ ACM_lkaLaneRecogState : 45|2@0+ (1,0) [0|3] "" EPAS_P - SG_ ACM_hbaOpt : 46|1@0+ (1,0) [0|1] "" EPAS_P - SG_ ACM_hbaLamp : 47|1@0+ (1,0) [0|1] "" EPAS_P - SG_ ACM_unkown3 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ ACM_hbaOnOffState : 47|2@0+ (1,0) [0|3] "" EPAS_P + SG_ ACM_ldwlkaOnOffState : 48|3@0+ (1,0) [0|7] "" EPAS_P + SG_ ACM_ldwWarnTimingState : 51|3@0+ (1,0) [0|7] "" EPAS_P SG_ ACM_lkaHandsoffSoundWarning : 53|2@0+ (1,0) [0|3] "" EPAS_P SG_ ACM_lkaHandsoffDisplayWarning : 55|2@0+ (1,0) [0|3] "" EPAS_P - SG_ ACM_unkown4 : 56|8@1+ (1,0) [0|255] "" XXX + SG_ ACM_ldwRHWarning : 58|3@0+ (1,0) [0|7] "" EPAS_P + SG_ ACM_ldwWarnTypeState : 61|3@0+ (1,0) [0|7] "" EPAS_P BO_ 304 RCM_IMU_LatAccYaw: 8 RCM SG_ RCM_LateralAccelYaw_Checksum : 7|8@0+ (1,0) [0|25] "" ACM,ESP,VDM @@ -176,10 +175,9 @@ BO_ 352 ACM_longitudinalRequest: 5 ACM SG_ ACM_longitudinalRequest_Checksum : 7|8@0+ (1,0) [0|255] "-" VDM SG_ ACM_longitudinalRequest_Counter : 11|4@0+ (1,0) [0|15] "-" VDM SG_ ACM_AccelerationRequest : 23|11@0+ (0.01,-10.24) [-10.24|10.23] "m/s^2" VDM - SG_ ACM_VehicleHoldRequired : 24|1@0+ (1,0) [0|1] "" VDM - SG_ ACM_PrndRequired : 27|3@0+ (1,0) [0|7] "" VDM + SG_ ACM_PrndRequest : 27|4@0+ (1,0) [0|7] "" VDM SG_ ACM_longInterfaceEnable : 37|2@0+ (1,0) [0|3] "" VDM - SG_ ACM_AccelerationRequestType : 39|2@0+ (1,0) [0|3] "" VDM + SG_ ACM_VehicleHoldRequest : 39|2@0+ (1,0) [0|3] "" VDM BO_ 354 VDM_AdasSts: 8 VDM SG_ VDM_AdasStatus_Checksum : 7|8@0+ (1,0) [0|0] "" ACM @@ -328,6 +326,7 @@ BO_ 565 IndicatorLights: 8 XXX SG_ DriverDoor : 28|2@0+ (1,0) [0|3] "" XXX SG_ RearPassengerDoor : 38|2@0+ (1,0) [0|3] "" XXX SG_ TurnLightLeft : 40|2@0+ (1,0) [0|3] "" XXX + SG_ IgnitionOn : 48|1@0+ (1,0) [0|1] "" XXX SG_ TurnLightRight : 54|2@0+ (1,0) [0|3] "" XXX BO_ 592 VDM_EcasStatus: 8 VDM @@ -609,9 +608,9 @@ CM_ SG_ 352 ACM_longitudinalRequest_Checksum "Checksum signal for frame"; CM_ SG_ 352 ACM_longitudinalRequest_Counter "Message counter signal for frame"; CM_ SG_ 352 ACM_AccelerationRequest "Acceleration Request command from the ACM"; CM_ SG_ 352 ACM_VehicleHoldRequired "Vehicle hold request flag"; -CM_ SG_ 352 ACM_PrndRequired "Drive state Request command from the ACM"; +CM_ SG_ 352 ACM_PrndRequest "Gear state Request command from the ACM"; CM_ SG_ 352 ACM_longInterfaceEnable "Acceleration Interface Enable Request from the ACM"; -CM_ SG_ 352 ACM_AccelerationRequestType "Acceleration Request type(positive/negative) from the ACM"; +CM_ SG_ 352 ACM_VehicleHoldRequest "Vehicle hold request from ACM"; CM_ SG_ 354 VDM_AdasStatus_Checksum "VDM_AdasSts message j1850 checksum."; CM_ SG_ 354 VDM_AdasStatus_Counter "VDM_AdasSts message counter."; CM_ SG_ 354 VDM_AdasFaultStatus "Fault status of ADAS requests from VDM."; @@ -828,14 +827,15 @@ VAL_ 288 ACM_lkaSymbolState 0 "ACM_LKASYMBOLSTATE_OFF" 1 "ACM_LKASYMBOLSTATE_WHI VAL_ 288 ACM_lkaToiFlt 0 "ACM_LKATOIFLT_NO_FAULT" 1 "ACM_LKATOIFLT_FAULT_PRESENT"; VAL_ 288 ACM_lkaActToi 0 "ACM_LKAACTTOI_DE_ACTIVATE_TOI" 1 "ACM_LKAACTTOI_ACTIVATE_TOI"; VAL_ 288 ACM_hbaSysState 0 "ACM_HBASYSSTATE_DEFAULT_DISABLE" 1 "ACM_HBASYSSTATE_HBA_ENABLE_HIGH_BEAM_OFF" 2 "ACM_HBASYSSTATE_HBA_ENABLE_HIGH_BEAM_ON" 7 "ACM_HBASYSSTATE_SYSTEM_FAIL"; -VAL_ 288 ACM_FailinfoAeb 0 "ACM_FAILINFOAEB_NORMAL" 1 "ACM_FAILINFOAEB_CAMERA_FAILURE" 2 "ACM_FAILINFOAEB_FRONT_RADAR_COM_ERR" 3 "ACM_FAILINFOAEB_CAMERA_BLOCKAGE" 4 "ACM_FAILINFOAEB_RESERVED_4" 5 "ACM_FAILINFOAEB_RESERVED_5" 6 "ACM_FAILINFOAEB_RESERVED_6"; -VAL_ 288 ACM_lkaRHWarning 0 "ACM_LKARHWARNING_NO_WARNING" 1 "ACM_LKARHWARNING_HAPTIC_WARNING_AND_DISPLAY" 2 "ACM_LKARHWARNING_ACOUSTIC_WARNING_AND_DISPLAY" 3 "ACM_LKARHWARNING_HAPTIC_ACOUSTIC_AND_DISPLAY"; -VAL_ 288 ACM_lkaLHWarning 0 "ACM_LKALHWARNING_NO_WARNING" 1 "ACM_LKALHWARNING_HAPTIC_WARNING_AND_DISPLAY" 2 "ACM_LKALHWARNING_ACOUSTIC_WARNING_AND_DISPLAY" 3 "ACM_LKALHWARNING_HAPTIC_ACOUSTIC_AND_DISPLAY"; +VAL_ 288 ACM_ldwRHWarning 0 "ACM_LKARHWARNING_NO_WARNING" 1 "ACM_LKARHWARNING_HAPTIC_WARNING_AND_DISPLAY" 2 "ACM_LKARHWARNING_ACOUSTIC_WARNING_AND_DISPLAY" 3 "ACM_LKARHWARNING_HAPTIC_ACOUSTIC_AND_DISPLAY"; +VAL_ 288 ACM_ldwLHWarning 0 "ACM_LKALHWARNING_NO_WARNING" 1 "ACM_LKALHWARNING_HAPTIC_WARNING_AND_DISPLAY" 2 "ACM_LKALHWARNING_ACOUSTIC_WARNING_AND_DISPLAY" 3 "ACM_LKALHWARNING_HAPTIC_ACOUSTIC_AND_DISPLAY"; VAL_ 288 ACM_lkaLaneRecogState 0 "ACM_LKALANERECOGSTATE_NOT_RECOGNITION" 1 "ACM_LKALANERECOGSTATE_LEFT_LANE_RECOGNITION" 2 "ACM_LKALANERECOGSTATE_RIGHT_LANE_RECOGNITION" 3 "ACM_LKALANERECOGSTATE_FULL_LANE_RECOGNITION"; -VAL_ 288 ACM_hbaOpt 0 "ACM_HBAOPT_NONE_HBA_OPTION_DEFAULT" 1 "ACM_HBAOPT_HBA_SYSTEM_ENABLE"; VAL_ 288 ACM_hbaLamp 0 "ACM_HBALAMP_HBA_INDICATOR_LAMP_OFF" 1 "ACM_HBALAMP_HBA_INDICATOR_LAMP_ON"; VAL_ 288 ACM_lkaHandsoffSoundWarning 0 "ACM_LKAHANDSOFFSOUNDWARNING_NO_INFO" 1 "ACM_LKAHANDSOFFSOUNDWARNING_WARNING" 2 "ACM_LKAHANDSOFFSOUNDWARNING_RESERVED_2" 3 "ACM_LKAHANDSOFFSOUNDWARNING_RESERVED_3"; VAL_ 288 ACM_lkaHandsoffDisplayWarning 0 "ACM_LKAHANDSOFFDISPLAYWARNING_NO_INFO" 1 "ACM_LKAHANDSOFFDISPLAYWARNING_WARNING" 2 "ACM_LKAHANDSOFFDISPLAYWARNING_RESERVED_2" 3 "ACM_LKAHANDSOFFDISPLAYWARNING_RESERVED_3"; +VAL_ 288 ACM_lkaElkRequest 0 "off" 1 "applying torque right for left departure" 2 "applying torque left for right departure"; +VAL_ 288 ACM_ldwlkaOnOffState 1 "LDW on" 2 "LKAS+LDW on" 3 "all off"; +VAL_ 288 ACM_elkOnOffState 1 "LKAS toggled on" 2 "LKAS toggled off"; VAL_ 304 RCM_IMU_LatAcc_Stat_SensAvail 0 "RCM_IMU_LatAcc_Stat_SensAvail_InSpec" 1 "RCM_IMU_LatAcc_Stat_SensAvail_NotInSpec"; VAL_ 304 RCM_IMU_LatAcc_Stat_Fail 0 "RCM_IMU_LatAcc_Stat_Fail_NotFailed" 1 "RCM_IMU_LatAcc_Stat_Fail_Failed"; VAL_ 304 RCM_IMU_LatAcc_Stat_Init 0 "RCM_IMU_LatAcc_Stat_Init_Finished" 1 "RCM_IMU_LatAcc_Stat_Init_Running"; @@ -871,9 +871,9 @@ VAL_ 338 VDM_EspPartialModeRequest 0 "VDM_EspPartialModeRequest_Normal" 1 "VDM_E VAL_ 338 VDM_SteeringModeRequest 0 "VDM_SteeringModeRequest_Default" 1 "VDM_SteeringModeRequest_Normal" 2 "VDM_SteeringModeRequest_Sport" 3 "VDM_SteeringModeRequest_Comfort"; VAL_ 338 VDM_EpasPowerMode 0 "VDM_EpasPowerMode_Drive_Off" 1 "VDM_EpasPowerMode_Drive_On" 2 "VDM_EpasPowerMode_Shutdown"; VAL_ 352 ACM_VehicleHoldRequired 0 "ACM_VEHICLEHOLDREQ_NO_REQUEST" 1 "ACM_VEHICLEHOLDREQ_VEHICLE_HOLD_REQUEST"; -VAL_ 352 ACM_PrndRequired 0 "ACM_PRNDREQ_PARK" 1 "ACM_PRNDREQ_REVERSE" 2 "ACM_PRNDREQ_NEUTRAL" 3 "ACM_PRNDREQ_DRIVE" 4 "ACM_PRNDREQ_NOT_USED"; +VAL_ 352 ACM_PrndRequest 0 "ACM_PRNDREQ_NO_REQUEST" 1 "ACM_PRNDREQ_PARK" 2 "ACM_PRNDREQ_REVERSE" 3 "ACM_PRNDREQ_NEUTRAL" 4 "ACM_PRNDREQ_DRIVE"; VAL_ 352 ACM_longInterfaceEnable 0 "ACM_LONGIFEN_INIT" 1 "ACM_LONGIFEN_LONGITUDINAL_INTERFACE_ENABLE" 2 "ACM_LONGIFEN_LONGITUDINAL_INTERFACE_DISABLE" 3 "ACM_LONGIFEN_SNA"; -VAL_ 352 ACM_AccelerationRequestType 0 "ACM_ACCELREQTYPE_INIT" 1 "ACM_ACCELREQTYPE_ACCEL_NEGATIVE" 2 "ACM_ACCELREQTYPE_ACCEL_POSITIVE" 3 "ACM_ACCELREQTYPE_SNA"; +VAL_ 352 ACM_VehicleHoldRequest 0 "NO_REQUEST" 1 "HOLD_REQUEST"; VAL_ 354 VDM_AdasDriverAccelPriorityStatus 0 "VDM_AdasDriverAccelPriorityStatus_Driver" 1 "VDM_AdasDriverAccelPriorityStatus_Adas"; VAL_ 354 VDM_AdasFaultStatus 0 "VDM_AdasFlaultStatus_No_Fault" 1 "VDM_AdasFaultStatus_Brk_Intv" 2 "VDM_AdasFlaultStatus_Cntr_Fault" 3 "VDM_AdasFlaultStatus_Imps_Cmd" 15 "VDM_AdasFlaultStatus_Sna"; VAL_ 354 VDM_AdasDriverModeStatus 0 "VDM_AdasDriverModeStatus_Human" 1 "VDM_AdasDriverModeStatus_Adas" 2 "VDM_AdasDriverModeStatus_Reserved" 3 "VDM_AdasDriverModeStatus_Sna"; diff --git a/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc b/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc index b8dcf0ff6c..72a831ad7c 100644 --- a/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc +++ b/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc @@ -111,6 +111,14 @@ BO_ 341 ESP_B: 8 PARTY SG_ ESP_wheelPulseCountFrR : 8|8@1+ (1,0) [0|254] "1" app SG_ ESP_wheelPulseCountFrL : 0|8@1+ (1,0) [0|254] "1" app +BO_ 373 ESP_wheelSpeeds: 8 CH + SG_ ESP_wheelSpeedsChecksum : 56|8@1+ (1,0) [0|255] "" das + SG_ ESP_wheelSpeedsCounter : 52|4@1+ (1,0) [0|15] "" das + SG_ ESP_wheelSpeedReR : 39|13@1+ (0.04,0) [0|327.64] "km/h" das + SG_ ESP_wheelSpeedReL : 26|13@1+ (0.04,0) [0|327.64] "km/h" das + SG_ ESP_wheelSpeedFrR : 13|13@1+ (0.04,0) [0|327.64] "km/h" das + SG_ ESP_wheelSpeedFrL : 0|13@1+ (0.04,0) [0|327.64] "km/h" das + BO_ 969 APS_status: 4 PARTY SG_ APS_statusCounter : 22|4@1+ (1,0) [0|15] "" X SG_ APS_apbGpioState : 20|2@1+ (1,0) [0|3] "" gtw @@ -131,8 +139,8 @@ BO_ 925 IBST_status: 5 PARTY SG_ IBST_statusChecksum : 0|8@1+ (1,0) [0|255] "" X BO_ 880 EPAS3S_sysStatus: 8 PARTY - SG_ EPAS3S_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" park - SG_ EPAS3S_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" gtw + SG_ EPAS3S_sysStatusChecksum : 56|8@1+ (1,0) [0|255] "" park + SG_ EPAS3S_sysStatusCounter : 48|4@1+ (1,0) [0|15] "" gtw SG_ EPAS3S_eacStatus : 55|3@0+ (1,0) [0|7] "" das SG_ EPAS3S_internalSAS : 37|14@0+ (0.1,-819.2) [-819.2|819] "deg" das SG_ EPAS3S_handsOnLevel : 39|2@0+ (1,0) [0|3] "" das @@ -189,9 +197,13 @@ BO_ 599 DI_speed: 8 PARTY SG_ DI_speedCounter : 8|4@1+ (1,0) [0|15] "" park SG_ DI_speedChecksum : 0|8@1+ (1,0) [0|255] "" park +BO_ 605 DAS_road: 6 XXX + SG_ DAS_stopLineDist : 16|8@1+ (0.5,0) [0|127.5] "m" XXX + SG_ DAS_trafficLightColor : 26|3@0+ (1,0) [0|7] "" XXX + BO_ 1160 DAS_steeringControl: 4 PARTY - SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|255] "" aps - SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|15] "" aps + SG_ DAS_steeringControlChecksum : 24|8@1+ (1,0) [0|255] "" aps + SG_ DAS_steeringControlCounter : 16|4@1+ (1,0) [0|15] "" aps SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|3] "" aps SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" aps SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|1] "" aps @@ -224,18 +236,33 @@ BO_ 646 DI_state: 8 ETH SG_ DI_locStatusChecksum : 0|8@1+ (1,0) [0|0] "" X BO_ 659 DAS_settings: 8 XXX - SG_ DAS_autopilotEnabled : 38|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_driverSteeringWeight : 1|2@0+ (1,0) [0|255] "" XXX + SG_ DAS_slipStart : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_offRoadAssist : 3|2@1+ (1,0) [0|63] "" XXX + SG_ DAS_distanceUnits : 13|1@1+ (1,0) [0|255] "" XXX + SG_ DAS_aebEnabled : 18|1@0+ (1,0) [0|255] "" XXX + SG_ DAS_adaptiveHeadlights : 22|1@1+ (1,0) [0|31] "" XXX + SG_ DAS_autosteerEnabled2 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_fcwEnabled : 34|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_fcwSensitivity : 37|2@0+ (1,0) [0|63] "" XXX + SG_ DAS_autosteerEnabled : 38|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_obstacleAwareAcceleration : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DAS_driverAccelerationMode : 44|1@1+ (1,0) [0|127] "" XXX SG_ DAS_settingCounter : 52|4@1+ (1,0) [0|15] "" XXX - SG_ DAS_settingChecksum : 63|8@0+ (1,0) [0|255] "" XXX + SG_ DAS_settingChecksum : 56|8@1+ (1,0) [0|255] "" XXX BO_ 785 UI_warning: 7 XXX SG_ buckleStatus : 13|1@0+ (1,0) [0|1] "" XXX - SG_ scrollWheelRightTilt : 21|1@0+ (1,0) [0|1] "" XXX + SG_ scrollWheelPressed : 21|1@0+ (1,0) [0|1] "" XXX SG_ leftBlinkerOn : 22|1@0+ (1,0) [0|1] "" XXX SG_ rightBlinkerOn : 23|1@0+ (1,0) [0|1] "" XXX + SG_ leftBlinkerBlinking : 25|2@0+ (1,0) [0|3] "" XXX + SG_ rightBlinkerBlinking : 26|2@1+ (1,0) [0|15] "" XXX SG_ anyDoorOpen : 28|1@0+ (1,0) [0|1] "" XXX SG_ wiperSettings : 39|8@0+ (1,0) [0|255] "" XXX SG_ highBeam : 50|1@0+ (1,0) [0|1] "" XXX + SG_ UI_warningCounter : 8|4@1+ (1,0) [0|15] "" XXX + SG_ UI_warningChecksum : 0|8@1+ (1,0) [0|255] "" XXX BO_ 923 DAS_status: 8 PARTY SG_ DAS_statusChecksum : 56|8@1+ (1,0) [0|255] "" aps @@ -266,11 +293,12 @@ BO_ 923 DAS_status: 8 PARTY SG_ DAS_autopilotState : 0|4@1+ (1,0) [0|15] "" aps +CM_ BO_ 605 "Bytes change when toggling between FSD and AP, as well as Traffic Light and Stop Sign Control in TACC"; - - - - +CM_ SG_ 659 DAS_autosteerEnabled "1 if Autosteer or FSD is enabled, 0 otherwise"; +CM_ SG_ 785 leftBlinkerOn "only describes stalk position if half pressed without auto-cancel blinkers. otherwise acts as expected"; +CM_ SG_ 785 rightBlinkerOn "only describes stalk position if half pressed without auto-cancel blinkers. otherwise acts as expected"; +CM_ SG_ 785 scrollWheelPressed "captures either scroll wheel left, right or down press"; VAL_ 545 VCFRONT_uiAudioLVState 1 "LV_ON" 2 "LV_GOING_DOWN" 3 "LV_FAULT" 0 "LV_OFF" ; VAL_ 545 VCFRONT_uiHiCurrentLVState 1 "LV_ON" 2 "LV_GOING_DOWN" 3 "LV_FAULT" 0 "LV_OFF" ; @@ -331,6 +359,7 @@ VAL_ 280 DI_immobilizerState 2 "DI_IMM_STATE_AUTHENTICATING" 0 "DI_IMM_STATE_INI VAL_ 280 DI_gear 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" 7 "DI_GEAR_SNA" 2 "DI_GEAR_R" 3 "DI_GEAR_N" 4 "DI_GEAR_D" ; VAL_ 280 DI_brakePedalState 2 "INVALID" 0 "OFF" 1 "ON" ; VAL_ 280 DI_systemState 5 "DI_SYS_ENABLE" 1 "DI_SYS_IDLE" 2 "DI_SYS_STANDBY" 0 "DI_SYS_UNAVAILABLE" 3 "DI_SYS_FAULT" 4 "DI_SYS_ABORT" ; +VAL_ 605 DAS_trafficLightColor 0 "NONE" 1 "RED" 2 "GREEN" 3 "YELLOW" ; VAL_ 697 DAS_accelMax 511 "SNA" ; VAL_ 697 DAS_accelMin 511 "SNA" ; VAL_ 697 DAS_jerkMax 255 "SNA" ; @@ -385,8 +414,15 @@ VAL_ 646 DI_parkBrakeState 0 "UNAVAILABLE" 1 "RELEASED" 2 "REQUESTED" 3 "APPLIED VAL_ 646 DI_autoparkState 0 "UNAVAILABLE" 1 "STANDBY" 2 "STARTED" 3 "ACTIVE" 4 "COMPLETE" 5 "PAUSED" 6 "ABORTED" 7 "RESUMED" 8 "UNPARK_COMPLETE" 9 "SELFPARK_STARTED" 15 "SNA" ; VAL_ 646 DI_speedUnits 0 "MPH" 1 "KPH" ; VAL_ 646 DI_cruiseState 0 "UNAVAILABLE" 1 "STANDBY" 2 "ENABLED" 3 "STANDSTILL" 4 "OVERRIDE" 5 "FAULT" 6 "PRE_FAULT" 7 "PRE_CANCEL" ; +VAL_ 659 DAS_driverSteeringWeight 0 "light" 1 "standard" 2 "heavy"; +VAL_ 659 DAS_offRoadAssist 0 "disabled" 3 "enabled"; +VAL_ 659 DAS_distanceUnits 1 "miles" 0 "kilometers"; +VAL_ 659 DAS_fcwSensitivity 0 "early" 1 "medium" 2 "late" 3 "off"; +VAL_ 659 DAS_driverAccelerationMode 0 "chill" 1 "standard"; VAL_ 785 buckleStatus 1 "LATCHED" 0 "UNLATCHED" ; VAL_ 785 anyDoorOpen 1 "OPEN" 0 "CLOSED" ; +VAL_ 785 leftBlinkerBlinking 0 "off" 1 "blinking, off" 2 "blinking, on"; +VAL_ 785 rightBlinkerBlinking 0 "off" 1 "blinking, off" 2 "blinking, on"; VAL_ 923 DAS_autoLaneChangeState 5 "ALC_UNAVAILABLE_VEHICLE_SPEED" 17 "ALC_ABORT_POOR_VIEW_RANGE" 23 "ALC_BLOCKED_VEH_TTC_AND_USS_L" 0 "ALC_UNAVAILABLE_DISABLED" 26 "ALC_BLOCKED_LANE_TYPE_L" 29 "ALC_ABORT_TIMEOUT" 9 "ALC_IN_PROGRESS_L" 4 "ALC_UNAVAILABLE_EXITING_HIGHWAY" 22 "ALC_BLOCKED_VEH_TTC_L" 12 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_R" 18 "ALC_ABORT_LC_HEALTH_BAD" 28 "ALC_WAITING_HANDS_ON" 8 "ALC_AVAILABLE_BOTH" 11 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_L" 3 "ALC_UNAVAILABLE_TP_FOLLOW" 2 "ALC_UNAVAILABLE_SONICS_INVALID" 21 "ALC_UNAVAILABLE_SOLID_LANE_LINE" 24 "ALC_BLOCKED_VEH_TTC_R" 1 "ALC_UNAVAILABLE_NO_LANES" 25 "ALC_BLOCKED_VEH_TTC_AND_USS_R" 30 "ALC_ABORT_MISSION_PLAN_INVALID" 27 "ALC_BLOCKED_LANE_TYPE_R" 19 "ALC_ABORT_BLINKER_TURNED_OFF" 31 "ALC_SNA" 13 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_L" 16 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_R" 6 "ALC_AVAILABLE_ONLY_L" 20 "ALC_ABORT_OTHER_REASON" 15 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_L" 7 "ALC_AVAILABLE_ONLY_R" 14 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_R" 10 "ALC_IN_PROGRESS_R" ; VAL_ 923 DAS_autopilotHandsOnState 8 "LC_HANDS_ON_SUSPENDED" 15 "LC_HANDS_ON_SNA" 7 "LC_HANDS_ON_REQD_STRUCK_OUT" 3 "LC_HANDS_ON_REQD_VISUAL" 4 "LC_HANDS_ON_REQD_CHIME_1" 6 "LC_HANDS_ON_REQD_SLOWING" 1 "LC_HANDS_ON_REQD_DETECTED" 2 "LC_HANDS_ON_REQD_NOT_DETECTED" 5 "LC_HANDS_ON_REQD_CHIME_2" 0 "LC_HANDS_ON_NOT_REQD" ; VAL_ 923 DAS_fleetSpeedState 0 "FLEETSPEED_UNAVAILABLE" 1 "FLEETSPEED_AVAILABLE" 2 "FLEETSPEED_ACTIVE" 3 "FLEETSPEED_HOLD" ; @@ -404,6 +440,3 @@ VAL_ 923 DAS_fusedSpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; VAL_ 923 DAS_blindSpotRearRight 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; VAL_ 923 DAS_blindSpotRearLeft 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; VAL_ 923 DAS_autopilotState 15 "SNA" 8 "ABORTING" 3 "ACTIVE_NOMINAL" 0 "DISABLED" 4 "ACTIVE_RESTRICTED" 5 "ACTIVE_NAV" 14 "FAULT" 1 "UNAVAILABLE" 9 "ABORTED" 2 "AVAILABLE" ; - - - diff --git a/opendbc_repo/opendbc/dbc/vw_mqb_2010.dbc b/opendbc_repo/opendbc/dbc/vw_mqb.dbc similarity index 100% rename from opendbc_repo/opendbc/dbc/vw_mqb_2010.dbc rename to opendbc_repo/opendbc/dbc/vw_mqb.dbc diff --git a/opendbc_repo/opendbc/dbc/vw_golf_mk4.dbc b/opendbc_repo/opendbc/dbc/vw_pq.dbc similarity index 100% rename from opendbc_repo/opendbc/dbc/vw_golf_mk4.dbc rename to opendbc_repo/opendbc/dbc/vw_pq.dbc diff --git a/opendbc_repo/opendbc/safety/__init__.py b/opendbc_repo/opendbc/safety/__init__.py index ef90de3c5c..4ce0cd5f03 100644 --- a/opendbc_repo/opendbc/safety/__init__.py +++ b/opendbc_repo/opendbc/safety/__init__.py @@ -5,7 +5,6 @@ LEN_TO_DLC = {length: dlc for (dlc, length) in enumerate(DLC_TO_LEN)} class ALTERNATIVE_EXPERIENCE: DEFAULT = 0 - DISABLE_DISENGAGE_ON_GAS = 1 DISABLE_STOCK_AEB = 2 RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX = 8 ALLOW_AEB = 16 diff --git a/opendbc_repo/opendbc/safety/board/can.h b/opendbc_repo/opendbc/safety/board/can.h index b2fe0ca39f..c2b8dfd17c 100644 --- a/opendbc_repo/opendbc/safety/board/can.h +++ b/opendbc_repo/opendbc/safety/board/can.h @@ -1,4 +1,10 @@ #pragma once -#include "can_declarations.h" + +// TODO: clean this up. it's for interop with the panda version +#ifndef CANPACKET_HEAD_SIZE + +#include "opendbc/safety/board/can_declarations.h" static const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; + +#endif diff --git a/opendbc_repo/opendbc/safety/board/can_declarations.h b/opendbc_repo/opendbc/safety/board/can_declarations.h index 186cba1fc2..e3524b7701 100644 --- a/opendbc_repo/opendbc/safety/board/can_declarations.h +++ b/opendbc_repo/opendbc/safety/board/can_declarations.h @@ -3,8 +3,7 @@ #define CANPACKET_HEAD_SIZE 6U // TODO: this is always CANFD -#if !defined(STM32F4) - #define CANFD +#ifdef CANFD #define CANPACKET_DATA_SIZE_MAX 64U #else #define CANPACKET_DATA_SIZE_MAX 8U diff --git a/opendbc_repo/opendbc/safety/board/drivers/can_common.h b/opendbc_repo/opendbc/safety/board/drivers/can_common.h index 52a980cf1d..523cca7371 100644 --- a/opendbc_repo/opendbc/safety/board/drivers/can_common.h +++ b/opendbc_repo/opendbc/safety/board/drivers/can_common.h @@ -1,4 +1,5 @@ -#include "can_common_declarations.h" +#pragma once +#include "opendbc/safety/board/drivers/can_common_declarations.h" uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) { uint8_t checksum = 0U; diff --git a/opendbc_repo/opendbc/safety/board/fake_stm.h b/opendbc_repo/opendbc/safety/board/fake_stm.h index 8f94e79edc..2d94bdb065 100644 --- a/opendbc_repo/opendbc/safety/board/fake_stm.h +++ b/opendbc_repo/opendbc/safety/board/fake_stm.h @@ -3,10 +3,9 @@ #include #include -#include "utils.h" +#include "opendbc/safety/board/utils.h" #define ALLOW_DEBUG -#define PANDA void print(const char *a) { printf("%s", a); diff --git a/opendbc_repo/opendbc/safety/board/faults.h b/opendbc_repo/opendbc/safety/board/faults.h index 0fc9d2c5cf..b1281955db 100644 --- a/opendbc_repo/opendbc/safety/board/faults.h +++ b/opendbc_repo/opendbc/safety/board/faults.h @@ -1,4 +1,4 @@ -#include "faults_declarations.h" +#include "opendbc/safety/board/faults_declarations.h" uint8_t fault_status = FAULT_STATUS_NONE; uint32_t faults = 0U; diff --git a/opendbc_repo/opendbc/safety/board/utils.h b/opendbc_repo/opendbc/safety/board/utils.h index f355ce8c2f..db011ddbe3 100644 --- a/opendbc_repo/opendbc/safety/board/utils.h +++ b/opendbc_repo/opendbc/safety/board/utils.h @@ -1,14 +1,14 @@ // cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension #define MIN(a, b) ({ \ - __typeof__ (a) _a = (a); \ - __typeof__ (b) _b = (b); \ + __typeof__(a) _a = (a); \ + __typeof__(b) _b = (b); \ (_a < _b) ? _a : _b; \ }) // cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension #define MAX(a, b) ({ \ - __typeof__ (a) _a = (a); \ - __typeof__ (b) _b = (b); \ + __typeof__(a) _a = (a); \ + __typeof__(b) _b = (b); \ (_a > _b) ? _a : _b; \ }) @@ -22,7 +22,7 @@ // cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension #define ABS(a) ({ \ - __typeof__ (a) _a = (a); \ + __typeof__(a) _a = (a); \ (_a > 0) ? _a : (-_a); \ }) @@ -42,6 +42,6 @@ // 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) { +static inline uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { return ts - ts_last; } diff --git a/opendbc_repo/opendbc/safety/main.c b/opendbc_repo/opendbc/safety/main.c index 3c873f84c2..7710d5f7aa 100644 --- a/opendbc_repo/opendbc/safety/main.c +++ b/opendbc_repo/opendbc/safety/main.c @@ -1,4 +1,4 @@ -#include "safety.h" +#include "opendbc/safety/safety.h" // this file is checked by cppcheck diff --git a/opendbc_repo/opendbc/safety/safety/safety_body.h b/opendbc_repo/opendbc/safety/modes/body.h similarity index 71% rename from opendbc_repo/opendbc/safety/safety/safety_body.h rename to opendbc_repo/opendbc/safety/modes/body.h index 9960d57bea..7ee9402806 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_body.h +++ b/opendbc_repo/opendbc/safety/modes/body.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" static void body_rx_hook(const CANPacket_t *to_push) { // body is never at standstill @@ -34,9 +34,9 @@ static safety_config body_init(uint16_t param) { {.msg = {{0x201, 0, 8, .ignore_checksum = true, .ignore_counter = true, .frequency = 100U}, { 0 }, { 0 }}}, }; - static const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8, false}, {0x250, 0, 6, false}, {0x251, 0, 5, false}, // body - {0x350, 0, 8, false}, {0x350, 0, 6, false}, {0x351, 0, 5, false}, // knee - {0x1, 0, 8, false}}; // CAN flasher + static const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8, .check_relay = false}, {0x250, 0, 6, .check_relay = false}, {0x251, 0, 5, .check_relay = false}, // body + {0x350, 0, 8, .check_relay = false}, {0x350, 0, 6, .check_relay = false}, {0x351, 0, 5, .check_relay = false}, // knee + {0x1, 0, 8, .check_relay = false}}; // CAN flasher UNUSED(param); safety_config ret = BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS); diff --git a/opendbc_repo/opendbc/safety/safety/safety_chrysler.h b/opendbc_repo/opendbc/safety/modes/chrysler.h similarity index 90% rename from opendbc_repo/opendbc/safety/safety/safety_chrysler.h rename to opendbc_repo/opendbc/safety/modes/chrysler.h index c581fce8b4..6370b517d7 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_chrysler.h +++ b/opendbc_repo/opendbc/safety/modes/chrysler.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" typedef struct { const int EPS_2; @@ -104,9 +104,8 @@ static void chrysler_rx_hook(const CANPacket_t *to_push) { static bool chrysler_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits CHRYSLER_STEERING_LIMITS = { - .max_steer = 261, + .max_torque = 261, .max_rt_delta = 112, - .max_rt_interval = 250000, .max_rate_up = 3, .max_rate_down = 3, .max_torque_error = 80, @@ -114,9 +113,8 @@ static bool chrysler_tx_hook(const CANPacket_t *to_send) { }; const TorqueSteeringLimits CHRYSLER_RAM_DT_STEERING_LIMITS = { - .max_steer = 350, + .max_torque = 350, .max_rt_delta = 112, - .max_rt_interval = 250000, .max_rate_up = 6, .max_rate_down = 6, .max_torque_error = 80, @@ -124,9 +122,8 @@ static bool chrysler_tx_hook(const CANPacket_t *to_send) { }; const TorqueSteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = { - .max_steer = 361, + .max_torque = 361, .max_rt_delta = 182, - .max_rt_interval = 250000, .max_rate_up = 14, .max_rate_down = 14, .max_torque_error = 80, @@ -164,18 +161,6 @@ static bool chrysler_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool chrysler_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - // 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){ - block_msg = true; - } - - return block_msg; -} - static safety_config chrysler_init(uint16_t param) { const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform @@ -222,15 +207,15 @@ static safety_config chrysler_init(uint16_t param) { }; static const CanMsg CHRYSLER_TX_MSGS[] = { - {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3, false}, - {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6, true}, - {CHRYSLER_ADDRS.DAS_6, 0, 8, false}, + {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3, .check_relay = false}, + {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6, .check_relay = true}, + {CHRYSLER_ADDRS.DAS_6, 0, 8, .check_relay = true}, }; static const CanMsg CHRYSLER_RAM_DT_TX_MSGS[] = { - {CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3, false}, - {CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8, true}, - {CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8, false}, + {CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3, .check_relay = false}, + {CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8, .check_relay = true}, + {CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8, .check_relay = true}, }; #ifdef ALLOW_DEBUG @@ -255,9 +240,9 @@ static safety_config chrysler_init(uint16_t param) { }; static const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = { - {CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3, false}, - {CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8, true}, - {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8, false}, + {CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3, .check_relay = false}, + {CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8, .check_relay = true}, + {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8, .check_relay = true}, }; const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform @@ -290,7 +275,6 @@ 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/opendbc_repo/opendbc/safety/safety/safety_defaults.h b/opendbc_repo/opendbc/safety/modes/defaults.h similarity index 88% rename from opendbc_repo/opendbc/safety/safety/safety_defaults.h rename to opendbc_repo/opendbc/safety/modes/defaults.h index 8c2a01de27..6266df9b84 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_defaults.h +++ b/opendbc_repo/opendbc/safety/modes/defaults.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // GCOV_EXCL_START // Unreachable by design (doesn't define any rx msgs) @@ -13,7 +13,7 @@ void default_rx_hook(const CANPacket_t *to_push) { static safety_config nooutput_init(uint16_t param) { UNUSED(param); - return (safety_config){NULL, 0, NULL, 0, true}; + return (safety_config){NULL, 0, NULL, 0, true}; // NOLINT(readability/braces) } // GCOV_EXCL_START @@ -36,7 +36,7 @@ static safety_config alloutput_init(uint16_t param) { const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1; controls_allowed = true; bool alloutput_passthrough = GET_FLAG(param, ALLOUTPUT_PARAM_PASSTHROUGH); - return (safety_config){NULL, 0, NULL, 0, !alloutput_passthrough}; + return (safety_config){NULL, 0, NULL, 0, !alloutput_passthrough}; // NOLINT(readability/braces) } static bool alloutput_tx_hook(const CANPacket_t *to_send) { diff --git a/opendbc_repo/opendbc/safety/safety/safety_elm327.h b/opendbc_repo/opendbc/safety/modes/elm327.h similarity index 92% rename from opendbc_repo/opendbc/safety/safety/safety_elm327.h rename to opendbc_repo/opendbc/safety/modes/elm327.h index 9a7277fcb9..673dee15d3 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_elm327.h +++ b/opendbc_repo/opendbc/safety/modes/elm327.h @@ -1,7 +1,7 @@ #pragma once -#include "safety_declarations.h" -#include "safety_defaults.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/modes/defaults.h" static bool elm327_tx_hook(const CANPacket_t *to_send) { const int GM_CAMERA_DIAG_ADDR = 0x24B; diff --git a/opendbc_repo/opendbc/safety/safety/safety_ford.h b/opendbc_repo/opendbc/safety/modes/ford.h similarity index 91% rename from opendbc_repo/opendbc/safety/safety/safety_ford.h rename to opendbc_repo/opendbc/safety/modes/ford.h index b4a4808ddf..71308a74d7 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_ford.h +++ b/opendbc_repo/opendbc/safety/modes/ford.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // Safety-relevant CAN messages for Ford vehicles. #define FORD_EngBrakeData 0x165 // RX from PCM, for driver brake pedal and cruise state @@ -69,7 +69,6 @@ static uint32_t ford_compute_checksum(const CANPacket_t *to_push) { chksum = 0xFFU - chksum; } else { } - return chksum; } @@ -88,9 +87,6 @@ static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) { return valid; } -static bool ford_canfd = false; -static bool ford_longitudinal = false; - #define FORD_INACTIVE_CURVATURE 1000U #define FORD_INACTIVE_CURVATURE_RATE 4096U #define FORD_INACTIVE_PATH_OFFSET 512U @@ -100,14 +96,6 @@ static bool ford_longitudinal = false; #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) && !ford_canfd) - || ((addr == FORD_LateralMotionControl2) && ford_canfd) - || (addr == FORD_IPMA_Data); -} - // Curvature rate limits #define FORD_LIMITS(limit_lateral_acceleration) { \ .max_angle = 1000, /* 0.02 curvature */ \ @@ -154,6 +142,7 @@ static void ford_rx_hook(const CANPacket_t *to_push) { // 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; + // TODO: this should generically cause rx valid to fall until re-enable if (is_invalid_speed) { controls_allowed = false; } @@ -311,29 +300,6 @@ static bool ford_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool ford_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - switch (bus_num) { - case FORD_CAM_BUS: { - if (ford_lkas_msg_check(addr)) { - // Block stock LKAS and UI messages - block_msg = true; - } else if (ford_longitudinal && (addr == FORD_ACCDATA)) { - // Block stock ACC message - block_msg = true; - } else { - } - break; - } - default: { - break; - } - } - - return block_msg; -} - static safety_config ford_init(uint16_t param) { // warning: quality flags are not yet checked in openpilot's CAN parser, // this may be the cause of blocked messages @@ -350,39 +316,39 @@ static safety_config ford_init(uint16_t param) { {.msg = {{FORD_DesiredTorqBrk, 0, 8, .ignore_checksum = true, .ignore_counter = true, .frequency = 50U}, { 0 }, { 0 }}}, }; - #define FORD_COMMON_TX_MSGS \ - {FORD_Steering_Data_FD1, 0, 8, false}, \ - {FORD_Steering_Data_FD1, 2, 8, false}, \ - {FORD_ACCDATA_3, 0, 8, true}, \ - {FORD_Lane_Assist_Data1, 0, 8, true}, \ - {FORD_IPMA_Data, 0, 8, true}, \ + #define FORD_COMMON_TX_MSGS \ + {FORD_Steering_Data_FD1, 0, 8, .check_relay = false}, \ + {FORD_Steering_Data_FD1, 2, 8, .check_relay = false}, \ + {FORD_ACCDATA_3, 0, 8, .check_relay = true}, \ + {FORD_Lane_Assist_Data1, 0, 8, .check_relay = true}, \ + {FORD_IPMA_Data, 0, 8, .check_relay = true}, \ static const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { FORD_COMMON_TX_MSGS - {FORD_ACCDATA, 0, 8, true}, - {FORD_LateralMotionControl2, 0, 8, true}, + {FORD_ACCDATA, 0, 8, .check_relay = true}, + {FORD_LateralMotionControl2, 0, 8, .check_relay = true}, }; static const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { FORD_COMMON_TX_MSGS - {FORD_LateralMotionControl2, 0, 8, true}, + {FORD_LateralMotionControl2, 0, 8, .check_relay = true}, }; static const CanMsg FORD_STOCK_TX_MSGS[] = { FORD_COMMON_TX_MSGS - {FORD_LateralMotionControl, 0, 8, true}, + {FORD_LateralMotionControl, 0, 8, .check_relay = true}, }; static const CanMsg FORD_LONG_TX_MSGS[] = { FORD_COMMON_TX_MSGS - {FORD_ACCDATA, 0, 8, true}, - {FORD_LateralMotionControl, 0, 8, true}, + {FORD_ACCDATA, 0, 8, .check_relay = true}, + {FORD_LateralMotionControl, 0, 8, .check_relay = true}, }; const uint16_t FORD_PARAM_CANFD = 2; - ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD); + const bool ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD); - ford_longitudinal = false; + bool ford_longitudinal = false; #ifdef ALLOW_DEBUG const uint16_t FORD_PARAM_LONGITUDINAL = 1; @@ -407,7 +373,6 @@ 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, diff --git a/opendbc_repo/opendbc/safety/safety/safety_gm.h b/opendbc_repo/opendbc/safety/modes/gm.h similarity index 78% rename from opendbc_repo/opendbc/safety/safety/safety_gm.h rename to opendbc_repo/opendbc/safety/modes/gm.h index fb12c49b52..8e4e7ce84d 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_gm.h +++ b/opendbc_repo/opendbc/safety/modes/gm.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. #define GM_COMMON_RX_CHECKS \ @@ -27,7 +27,6 @@ typedef enum { GM_CAM } GmHardware; static GmHardware gm_hw = GM_ASCM; -static bool gm_cam_long = false; static bool gm_pcm_cruise = false; static void gm_rx_hook(const CANPacket_t *to_push) { @@ -98,13 +97,12 @@ static void gm_rx_hook(const CANPacket_t *to_push) { static bool gm_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits GM_STEERING_LIMITS = { - .max_steer = 300, + .max_torque = 300, .max_rate_up = 10, .max_rate_down = 15, .driver_torque_allowance = 65, .driver_torque_multiplier = 4, .max_rt_delta = 128, - .max_rt_interval = 250000, .type = TorqueDriverLimited, }; @@ -135,7 +133,8 @@ static bool gm_tx_hook(const CANPacket_t *to_send) { // GAS/REGEN: safety check if (addr == 0x2CB) { bool apply = GET_BIT(to_send, 0U); - int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3); + // convert float CAN signal to an int for gas checks: 22534 / 0.125 = 180272 + int gas_regen = (((GET_BYTE(to_send, 1) & 0x7U) << 16) | (GET_BYTE(to_send, 2) << 8) | GET_BYTE(to_send, 3)) - 180272U; bool violation = false; // Allow apply bit in pre-enabled and overriding states @@ -160,56 +159,35 @@ static bool gm_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool gm_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (gm_hw == GM_CAM) { - 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) { - block_msg = true; - } - } - - 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); - block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long); - } - } else { - block_msg = true; - } - - return block_msg; -} - static safety_config gm_init(uint16_t param) { const uint16_t GM_PARAM_HW_CAM = 1; const uint16_t GM_PARAM_EV = 4; + // common safety checks assume unscaled integer values + static const int GM_GAS_TO_CAN = 8; // 1 / 0.125 + static const LongitudinalLimits GM_ASCM_LONG_LIMITS = { - .max_gas = 3072, - .min_gas = 1404, - .inactive_gas = 1404, + .max_gas = 1018 * GM_GAS_TO_CAN, + .min_gas = -650 * GM_GAS_TO_CAN, + .inactive_gas = -650 * GM_GAS_TO_CAN, .max_brake = 400, }; - static const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4, true}, {0x409, 0, 7, false}, {0x40A, 0, 7, false}, {0x2CB, 0, 8, true}, {0x370, 0, 6, false}, // pt bus - {0xA1, 1, 7, false}, {0x306, 1, 8, false}, {0x308, 1, 7, false}, {0x310, 1, 2, false}, // obs bus - {0x315, 2, 5, false}}; // ch bus + static const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4, .check_relay = true}, {0x409, 0, 7, .check_relay = false}, {0x40A, 0, 7, .check_relay = false}, {0x2CB, 0, 8, .check_relay = true}, {0x370, 0, 6, .check_relay = false}, // pt bus + {0xA1, 1, 7, .check_relay = false}, {0x306, 1, 8, .check_relay = false}, {0x308, 1, 7, .check_relay = false}, {0x310, 1, 2, .check_relay = false}, // obs bus + {0x315, 2, 5, .check_relay = false}}; // ch bus static const LongitudinalLimits GM_CAM_LONG_LIMITS = { - .max_gas = 3400, - .min_gas = 1514, - .inactive_gas = 1554, + .max_gas = 1346 * GM_GAS_TO_CAN, + .min_gas = -540 * GM_GAS_TO_CAN, + .inactive_gas = -500 * GM_GAS_TO_CAN, .max_brake = 400, }; - static const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4, true}, {0x315, 0, 5, false}, {0x2CB, 0, 8, true}, {0x370, 0, 6, false}, // pt bus - {0x184, 2, 8, false}}; // camera bus + // block PSCMStatus (0x184); forwarded through openpilot to hide an alert from the camera + static const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4, .check_relay = true}, {0x315, 0, 5, .check_relay = true}, {0x2CB, 0, 8, .check_relay = true}, {0x370, 0, 6, .check_relay = true}, // pt bus + {0x184, 2, 8, .check_relay = true}}; // camera bus static RxCheck gm_rx_checks[] = { @@ -221,8 +199,8 @@ static safety_config gm_init(uint16_t param) { {.msg = {{0xBD, 0, 7, .ignore_checksum = true, .ignore_counter = true, .frequency = 40U}, { 0 }, { 0 }}}, }; - static const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4, true}, // pt bus - {0x1E1, 2, 7, false}, {0x184, 2, 8, false}}; // camera bus + static const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4, .check_relay = true}, // pt bus + {0x1E1, 2, 7, .check_relay = false}, {0x184, 2, 8, .check_relay = true}}; // camera bus gm_hw = GET_FLAG(param, GM_PARAM_HW_CAM) ? GM_CAM : GM_ASCM; @@ -233,6 +211,8 @@ static safety_config gm_init(uint16_t param) { } else { } + bool gm_cam_long = false; + #ifdef ALLOW_DEBUG const uint16_t GM_PARAM_HW_CAM_LONG = 2; gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG); @@ -253,6 +233,11 @@ static safety_config gm_init(uint16_t param) { if (gm_ev) { SET_RX_CHECKS(gm_ev_rx_checks, ret); } + + // ASCM does not forward any messages + if (gm_hw == GM_ASCM) { + ret.disable_forwarding = true; + } return ret; } @@ -260,5 +245,4 @@ const safety_hooks gm_hooks = { .init = gm_init, .rx = gm_rx_hook, .tx = gm_tx_hook, - .fwd = gm_fwd_hook, }; diff --git a/opendbc_repo/opendbc/safety/safety/safety_honda.h b/opendbc_repo/opendbc/safety/modes/honda.h similarity index 86% rename from opendbc_repo/opendbc/safety/safety/safety_honda.h rename to opendbc_repo/opendbc/safety/modes/honda.h index 6361ba31f9..bed7017932 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_honda.h +++ b/opendbc_repo/opendbc/safety/modes/honda.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // 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) \ @@ -278,7 +278,11 @@ static bool honda_tx_hook(const CANPacket_t *to_send) { } static safety_config honda_nidec_init(uint16_t param) { - static CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5, true}, {0x194, 0, 4, true}, {0x1FA, 0, 8, false}, {0x30C, 0, 8, false}, {0x33D, 0, 5, false}}; + // 0x1FA is dynamically forwarded based on stock AEB + // 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 + static CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5, .check_relay = true}, {0x194, 0, 4, .check_relay = true}, {0x1FA, 0, 8, .check_relay = false}, + {0x30C, 0, 8, .check_relay = true}, {0x33D, 0, 5, .check_relay = true}}; const uint16_t HONDA_PARAM_NIDEC_ALT = 4; @@ -318,10 +322,21 @@ static safety_config honda_nidec_init(uint16_t param) { } static safety_config honda_bosch_init(uint16_t param) { - static CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5, true}, {0xE5, 0, 8, false}, {0x296, 1, 4, false}, {0x33D, 0, 5, false}, {0x33DA, 0, 5, false}, {0x33DB, 0, 8, false}}; // Bosch - static CanMsg HONDA_BOSCH_LONG_TX_MSGS[] = {{0xE4, 1, 5, true}, {0x1DF, 1, 8, true}, {0x1EF, 1, 8, false}, {0x1FA, 1, 8, false}, {0x30C, 1, 8, false}, {0x33D, 1, 5, false}, {0x33DA, 1, 5, false}, {0x33DB, 1, 8, false}, {0x39F, 1, 8, false}, {0x18DAB0F1, 1, 8, false}}; // Bosch w/ gas and brakes - static CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5, true}, {0x296, 2, 4, false}, {0x33D, 0, 8, false}}; // Bosch radarless - static CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5, true}, {0x33D, 0, 8, false}, {0x1C8, 0, 8, false}, {0x30C, 0, 8, false}}; // Bosch radarless w/ gas and brakes + // HONDA_BOSCH_TX_MSGS is used by Bosch and Bosch CAN FD + static CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5, .check_relay = true}, {0xE5, 0, 8, .check_relay = true}, + // Send buttons on powertrain bus: 0 for Bosch CAN FD, 1 for CAN + {0x296, 0, 4, .check_relay = false}, {0x296, 1, 4, .check_relay = false}, + {0x33D, 0, 5, .check_relay = true}, {0x33DA, 0, 5, .check_relay = true}, {0x33DB, 0, 8, .check_relay = true}}; // Bosch + + static CanMsg HONDA_BOSCH_LONG_TX_MSGS[] = {{0xE4, 1, 5, .check_relay = true}, {0x1DF, 1, 8, .check_relay = true}, {0x1EF, 1, 8, .check_relay = false}, + {0x1FA, 1, 8, .check_relay = false}, {0x30C, 1, 8, .check_relay = false}, {0x33D, 1, 5, .check_relay = true}, + {0x33DA, 1, 5, .check_relay = true}, {0x33DB, 1, 8, .check_relay = true}, {0x39F, 1, 8, .check_relay = false}, + {0x18DAB0F1, 1, 8, .check_relay = false}}; // Bosch w/ gas and brakes + + static CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5, .check_relay = true}, {0x296, 2, 4, .check_relay = false}, {0x33D, 0, 8, .check_relay = true}}; // Bosch radarless + + static CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5, .check_relay = true}, {0x33D, 0, 8, .check_relay = true}, {0x1C8, 0, 8, .check_relay = true}, + {0x30C, 0, 8, .check_relay = true}}; // Bosch radarless w/ gas and brakes const uint16_t HONDA_PARAM_ALT_BRAKE = 1; const uint16_t HONDA_PARAM_RADARLESS = 8; @@ -386,29 +401,12 @@ static safety_config honda_bosch_init(uint16_t param) { } static bool 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 bool block_msg = false; 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; + // forwarded if stock AEB is active bool is_brake_msg = addr == 0x1FA; - block_msg = is_lkas_msg || is_acc_hud_msg || (is_brake_msg && !honda_fwd_brake); - } - - return block_msg; -} - -static bool honda_bosch_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - 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; - block_msg = is_lkas_msg || is_acc_msg; + block_msg = is_brake_msg && !honda_fwd_brake; } return block_msg; @@ -428,7 +426,6 @@ 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/opendbc_repo/opendbc/safety/safety/safety_hyundai.h b/opendbc_repo/opendbc/safety/modes/hyundai.h similarity index 87% rename from opendbc_repo/opendbc/safety/safety/safety_hyundai.h rename to opendbc_repo/opendbc/safety/modes/hyundai.h index e56c123f95..077d155367 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_hyundai.h +++ b/opendbc_repo/opendbc/safety/modes/hyundai.h @@ -1,14 +1,13 @@ #pragma once -#include "safety_declarations.h" -#include "safety_hyundai_common.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/modes/hyundai_common.h" #define HYUNDAI_LIMITS(steer, rate_up, rate_down) { \ - .max_steer = (steer), \ + .max_torque = (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_multiplier = 2, \ .type = TorqueDriverLimited, \ @@ -27,17 +26,17 @@ const LongitudinalLimits HYUNDAI_LONG_LIMITS = { }; #define HYUNDAI_COMMON_TX_MSGS(scc_bus) \ - {0x340, 0, 8, true}, /* LKAS11 Bus 0 */ \ - {0x4F1, scc_bus, 4, false}, /* CLU11 Bus 0 (radar-SCC) or 2 (camera-SCC) */ \ - {0x485, 0, 4, false}, /* LFAHDA_MFC Bus 0 */ \ + {0x340, 0, 8, .check_relay = true}, /* LKAS11 Bus 0 */ \ + {0x4F1, scc_bus, 4, .check_relay = false}, /* CLU11 Bus 0 (radar-SCC) or 2 (camera-SCC) */ \ + {0x485, 0, 4, .check_relay = true}, /* LFAHDA_MFC Bus 0 */ \ #define HYUNDAI_LONG_COMMON_TX_MSGS(scc_bus) \ - HYUNDAI_COMMON_TX_MSGS(scc_bus) \ - {0x420, 0, 8, false}, /* SCC11 Bus 0 */ \ - {0x421, 0, 8, (scc_bus) == 0}, /* SCC12 Bus 0 */ \ - {0x50A, 0, 8, false}, /* SCC13 Bus 0 */ \ - {0x389, 0, 8, false}, /* SCC14 Bus 0 */ \ - {0x4A2, 0, 2, false}, /* FRT_RADAR11 Bus 0 */ \ + HYUNDAI_COMMON_TX_MSGS(scc_bus) \ + {0x420, 0, 8, .check_relay = true}, /* SCC11 Bus 0 */ \ + {0x421, 0, 8, .check_relay = true}, /* SCC12 Bus 0 */ \ + {0x50A, 0, 8, .check_relay = true}, /* SCC13 Bus 0 */ \ + {0x389, 0, 8, .check_relay = true}, /* SCC14 Bus 0 */ \ + {0x4A2, 0, 2, .check_relay = false}, /* FRT_RADAR11 Bus 0 */ \ #define HYUNDAI_COMMON_RX_CHECKS(legacy) \ {.msg = {{0x260, 0, 8, .max_counter = 3U, .frequency = 100U}, \ @@ -256,29 +255,12 @@ static bool hyundai_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool hyundai_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (bus_num == 2) { - // Stock LKAS11 messages - bool is_lkas_11 = (addr == 0x340); - // LFA and HDA cluster icons - bool is_lfahda_mfc = (addr == 0x485); - // Stock SCC messages, blocking when doing openpilot longitudinal on camera SCC cars - bool is_scc_msg = (addr == 0x420) || (addr == 0x421) || (addr == 0x50A) || (addr == 0x389); - - block_msg = is_lkas_11 || is_lfahda_mfc || (is_scc_msg && hyundai_longitudinal && hyundai_camera_scc); - } - - return block_msg; -} - static safety_config hyundai_init(uint16_t param) { static const CanMsg HYUNDAI_LONG_TX_MSGS[] = { HYUNDAI_LONG_COMMON_TX_MSGS(0) - {0x38D, 0, 8, false}, // FCA11 Bus 0 - {0x483, 0, 8, false}, // FCA12 Bus 0 - {0x7D0, 0, 8, false}, // radar UDS TX addr Bus 0 (for radar disable) + {0x38D, 0, 8, .check_relay = false}, // FCA11 Bus 0 + {0x483, 0, 8, .check_relay = false}, // FCA12 Bus 0 + {0x7D0, 0, 8, .check_relay = false}, // radar UDS TX addr Bus 0 (for radar disable) }; static const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { @@ -362,7 +344,6 @@ 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, @@ -372,7 +353,6 @@ 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/opendbc_repo/opendbc/safety/safety/safety_hyundai_canfd.h b/opendbc_repo/opendbc/safety/modes/hyundai_canfd.h similarity index 86% rename from opendbc_repo/opendbc/safety/safety/safety_hyundai_canfd.h rename to opendbc_repo/opendbc/safety/modes/hyundai_canfd.h index 7e0cdead6f..a64b56c12a 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_hyundai_canfd.h +++ b/opendbc_repo/opendbc/safety/modes/hyundai_canfd.h @@ -1,27 +1,27 @@ #pragma once -#include "safety_declarations.h" -#include "safety_hyundai_common.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/modes/hyundai_common.h" #define HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(bus) \ - {0x1CF, bus, 8, false}, /* CRUISE_BUTTON */ \ + {0x1CF, bus, 8, .check_relay = false}, /* CRUISE_BUTTON */ \ #define HYUNDAI_CANFD_LKA_STEERING_COMMON_TX_MSGS(a_can, e_can) \ - HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(e_can) \ - {0x50, a_can, 16, (a_can) == 0}, /* LKAS */ \ - {0x2A4, a_can, 24, false}, /* CAM_0x2A4 */ \ + HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(e_can) \ + {0x50, a_can, 16, .check_relay = (a_can) == 0}, /* LKAS */ \ + {0x2A4, a_can, 24, .check_relay = (a_can) == 0}, /* CAM_0x2A4 */ \ #define HYUNDAI_CANFD_LKA_STEERING_ALT_COMMON_TX_MSGS(a_can, e_can) \ HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(e_can) \ - {0x110, a_can, 32, (a_can) == 0}, /* LKAS_ALT */ \ - {0x362, a_can, 32, false}, /* CAM_0x362 */ \ + {0x110, a_can, 32, .check_relay = (a_can) == 0}, /* LKAS_ALT */ \ + {0x362, a_can, 32, .check_relay = (a_can) == 0}, /* CAM_0x362 */ \ #define HYUNDAI_CANFD_LFA_STEERING_COMMON_TX_MSGS(e_can) \ - {0x12A, e_can, 16, (e_can) == 0}, /* LFA */ \ - {0x1E0, e_can, 16, false}, /* LFAHDA_CLUSTER */ \ + {0x12A, e_can, 16, .check_relay = (e_can) == 0}, /* LFA */ \ + {0x1E0, e_can, 16, .check_relay = (e_can) == 0}, /* LFAHDA_CLUSTER */ \ -#define HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(e_can, longitudinal) \ - {0x1A0, e_can, 32, (longitudinal)}, /* SCC_CONTROL */ \ +#define HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(e_can, longitudinal) \ + {0x1A0, e_can, 32, .check_relay = (longitudinal)}, /* SCC_CONTROL */ \ // *** Addresses checked in rx hook *** // EV, ICE, HYBRID: ACCELERATOR (0x35), ACCELERATOR_BRAKE_ALT (0x100), ACCELERATOR_ALT (0x105) @@ -139,9 +139,8 @@ static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) { static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits HYUNDAI_CANFD_STEERING_LIMITS = { - .max_steer = 270, + .max_torque = 270, .max_rt_delta = 112, - .max_rt_interval = 250000, .max_rate_up = 2, .max_rate_down = 3, .driver_torque_allowance = 250, @@ -219,27 +218,6 @@ static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool hyundai_canfd_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (bus_num == 2) { - // LKAS for cars with LKAS and LFA messages, LFA for cars with no LKAS messages - int lfa_block_addr = hyundai_canfd_lka_steering_alt ? 0x362 : 0x2a4; - bool is_lka_msg = ((addr == hyundai_canfd_get_lka_addr()) || (addr == lfa_block_addr)) && hyundai_canfd_lka_steering; - bool is_lfa_msg = ((addr == 0x12a) && !hyundai_canfd_lka_steering); - - // HUD icons - bool is_lfahda_msg = ((addr == 0x1e0) && !hyundai_canfd_lka_steering); - - // SCC_CONTROL and ADRV_0x160 for camera SCC cars, we send our own longitudinal commands and to show FCA light - bool is_scc_msg = (((addr == 0x1a0) || (addr == 0x160)) && hyundai_longitudinal && !hyundai_canfd_lka_steering); - - block_msg = is_lka_msg || is_lfa_msg || is_lfahda_msg || is_scc_msg; - } - - return block_msg; -} - static safety_config hyundai_canfd_init(uint16_t param) { const int HYUNDAI_PARAM_CANFD_LKA_STEERING_ALT = 128; const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32; @@ -256,13 +234,13 @@ static safety_config hyundai_canfd_init(uint16_t param) { HYUNDAI_CANFD_LKA_STEERING_COMMON_TX_MSGS(0, 1) HYUNDAI_CANFD_LFA_STEERING_COMMON_TX_MSGS(1) HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(1, true) - {0x51, 0, 32, false}, // ADRV_0x51 - {0x730, 1, 8, false}, // tester present for ADAS ECU disable - {0x160, 1, 16, false}, // ADRV_0x160 - {0x1EA, 1, 32, false}, // ADRV_0x1ea - {0x200, 1, 8, false}, // ADRV_0x200 - {0x345, 1, 8, false}, // ADRV_0x345 - {0x1DA, 1, 32, false}, // ADRV_0x1da + {0x51, 0, 32, .check_relay = false}, // ADRV_0x51 + {0x730, 1, 8, .check_relay = false}, // tester present for ADAS ECU disable + {0x160, 1, 16, .check_relay = false}, // ADRV_0x160 + {0x1EA, 1, 32, .check_relay = false}, // ADRV_0x1ea + {0x200, 1, 8, .check_relay = false}, // ADRV_0x200 + {0x345, 1, 8, .check_relay = false}, // ADRV_0x345 + {0x1DA, 1, 32, .check_relay = false}, // ADRV_0x1da }; static const CanMsg HYUNDAI_CANFD_LFA_STEERING_TX_MSGS[] = { @@ -271,19 +249,21 @@ static safety_config hyundai_canfd_init(uint16_t param) { HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(0, false) }; + // ADRV_0x160 is checked for radar liveness static const CanMsg HYUNDAI_CANFD_LFA_STEERING_LONG_TX_MSGS[] = { HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(2) HYUNDAI_CANFD_LFA_STEERING_COMMON_TX_MSGS(0) HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(0, true) - {0x160, 0, 16, false}, // ADRV_0x160 - {0x7D0, 0, 8, false}, // tester present for radar ECU disable + {0x160, 0, 16, .check_relay = true}, // ADRV_0x160 + {0x7D0, 0, 8, .check_relay = false}, // tester present for radar ECU disable }; + // ADRV_0x160 is checked for relay malfunction #define HYUNDAI_CANFD_LFA_STEERING_CAMERA_SCC_TX_MSGS(longitudinal) \ HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(2) \ HYUNDAI_CANFD_LFA_STEERING_COMMON_TX_MSGS(0) \ HYUNDAI_CANFD_SCC_CONTROL_COMMON_TX_MSGS(0, (longitudinal)) \ - {0x160, 0, 16, false}, /* ADRV_0x160 */ \ + {0x160, 0, 16, .check_relay = (longitudinal)}, /* ADRV_0x160 */ \ hyundai_common_init(param); @@ -399,7 +379,6 @@ 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/opendbc_repo/opendbc/safety/safety/safety_hyundai_common.h b/opendbc_repo/opendbc/safety/modes/hyundai_common.h similarity index 98% rename from opendbc_repo/opendbc/safety/safety/safety_hyundai_common.h rename to opendbc_repo/opendbc/safety/modes/hyundai_common.h index afee974426..1905ae4a5b 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_hyundai_common.h +++ b/opendbc_repo/opendbc/safety/modes/hyundai_common.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" extern uint16_t hyundai_canfd_crc_lut[256]; uint16_t hyundai_canfd_crc_lut[256]; @@ -112,6 +112,7 @@ void hyundai_common_cruise_buttons_check(const int cruise_button, const bool mai } } +#ifdef CANFD 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); @@ -136,3 +137,4 @@ uint32_t hyundai_common_canfd_compute_checksum(const CANPacket_t *to_push) { return crc; } +#endif diff --git a/opendbc_repo/opendbc/safety/safety/safety_mazda.h b/opendbc_repo/opendbc/safety/modes/mazda.h similarity index 87% rename from opendbc_repo/opendbc/safety/safety/safety_mazda.h rename to opendbc_repo/opendbc/safety/modes/mazda.h index 7159729a3f..d5154602c1 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_mazda.h +++ b/opendbc_repo/opendbc/safety/modes/mazda.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // CAN msgs we care about #define MAZDA_LKAS 0x243 @@ -50,11 +50,10 @@ static void mazda_rx_hook(const CANPacket_t *to_push) { static bool mazda_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits MAZDA_STEERING_LIMITS = { - .max_steer = 800, + .max_torque = 800, .max_rate_up = 10, .max_rate_down = 25, .max_rt_delta = 300, - .max_rt_interval = 250000, .driver_torque_multiplier = 1, .driver_torque_allowance = 15, .type = TorqueDriverLimited, @@ -78,7 +77,7 @@ static bool mazda_tx_hook(const CANPacket_t *to_send) { // cruise buttons check if (addr == MAZDA_CRZ_BTNS) { // allow resume spamming while controls allowed, but - // only allow cancel while contrls not allowed + // only allow cancel while controls not allowed bool cancel_cmd = (GET_BYTE(to_send, 0) == 0x1U); if (!controls_allowed && !cancel_cmd) { tx = false; @@ -89,18 +88,8 @@ static bool mazda_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool mazda_fwd_hook(int bus, int addr) { - bool block_msg = false; - - if (bus == MAZDA_CAM) { - block_msg = (addr == MAZDA_LKAS) || (addr == MAZDA_LKAS_HUD); - } - - return block_msg; -} - static safety_config mazda_init(uint16_t param) { - static const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8, true}, {MAZDA_CRZ_BTNS, 0, 8, false}, {MAZDA_LKAS_HUD, 0, 8, false}}; + static const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8, .check_relay = true}, {MAZDA_CRZ_BTNS, 0, 8, .check_relay = false}, {MAZDA_LKAS_HUD, 0, 8, .check_relay = true}}; static RxCheck mazda_rx_checks[] = { {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .ignore_checksum = true, .ignore_counter = true, .frequency = 50U}, { 0 }, { 0 }}}, @@ -118,5 +107,4 @@ const safety_hooks mazda_hooks = { .init = mazda_init, .rx = mazda_rx_hook, .tx = mazda_tx_hook, - .fwd = mazda_fwd_hook, }; diff --git a/opendbc_repo/opendbc/safety/safety/safety_nissan.h b/opendbc_repo/opendbc/safety/modes/nissan.h similarity index 87% rename from opendbc_repo/opendbc/safety/safety/safety_nissan.h rename to opendbc_repo/opendbc/safety/modes/nissan.h index 30b971f22c..a1ac351401 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_nissan.h +++ b/opendbc_repo/opendbc/safety/modes/nissan.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" static bool nissan_alt_eps = false; @@ -100,29 +100,14 @@ static bool nissan_tx_hook(const CANPacket_t *to_send) { } -static bool nissan_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (bus_num == 0) { - block_msg = (addr == 0x280); // CANCEL_MSG - } - - if (bus_num == 2) { - // 0x169 is LKAS, 0x2b1 LKAS_HUD, 0x4cc LKAS_HUD_INFO_MSG - block_msg = ((addr == 0x169) || (addr == 0x2b1) || (addr == 0x4cc)); - } - - return block_msg; -} - static safety_config nissan_init(uint16_t param) { static const CanMsg NISSAN_TX_MSGS[] = { - {0x169, 0, 8, true}, // LKAS - {0x2b1, 0, 8, false}, // PROPILOT_HUD - {0x4cc, 0, 8, false}, // PROPILOT_HUD_INFO_MSG - {0x20b, 2, 6, false}, // CRUISE_THROTTLE (X-Trail) - {0x20b, 1, 6, false}, // CRUISE_THROTTLE (Altima) - {0x280, 2, 8, false} // CANCEL_MSG (Leaf) + {0x169, 0, 8, .check_relay = true}, // LKAS + {0x2b1, 0, 8, .check_relay = true}, // PROPILOT_HUD + {0x4cc, 0, 8, .check_relay = true}, // PROPILOT_HUD_INFO_MSG + {0x20b, 2, 6, .check_relay = false}, // CRUISE_THROTTLE (X-Trail) + {0x20b, 1, 6, .check_relay = false}, // CRUISE_THROTTLE (Altima) + {0x280, 2, 8, .check_relay = true} // CANCEL_MSG (Leaf) }; // Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. @@ -152,5 +137,4 @@ const safety_hooks nissan_hooks = { .init = nissan_init, .rx = nissan_rx_hook, .tx = nissan_tx_hook, - .fwd = nissan_fwd_hook, }; diff --git a/opendbc_repo/opendbc/safety/modes/rivian.h b/opendbc_repo/opendbc/safety/modes/rivian.h new file mode 100644 index 0000000000..85f2caaf2c --- /dev/null +++ b/opendbc_repo/opendbc/safety/modes/rivian.h @@ -0,0 +1,211 @@ +#pragma once + +#include "opendbc/safety/safety_declarations.h" + +#define RIVIAN_MAX_SPEED_DELTA 2.0 // m/s + +static uint8_t rivian_get_counter(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + uint8_t cnt = 0; + if ((addr == 0x208) || (addr == 0x150)) { + // Signal: ESP_Status_Counter, VDM_PropStatus_Counter + cnt = GET_BYTE(to_push, 1) & 0xFU; + } else { + } + return cnt; +} + +static uint32_t rivian_get_checksum(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + uint8_t chksum = 0; + if ((addr == 0x208) || (addr == 0x150)) { + // Signal: ESP_Status_Checksum, VDM_PropStatus_Checksum + chksum = GET_BYTE(to_push, 0); + } else { + } + return chksum; +} + +static uint8_t _rivian_compute_checksum(const CANPacket_t *to_push, uint8_t poly, uint8_t xor_output) { + int len = GET_LEN(to_push); + + uint8_t crc = 0; + // Skip the checksum byte + for (int i = 1; i < len; i++) { + crc ^= GET_BYTE(to_push, i); + for (int j = 0; j < 8; j++) { + if ((crc & 0x80U) != 0U) { + crc = (crc << 1) ^ poly; + } else { + crc <<= 1; + } + } + } + return crc ^ xor_output; +} + +static uint32_t rivian_compute_checksum(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + uint8_t chksum = 0; + if (addr == 0x208) { + chksum = _rivian_compute_checksum(to_push, 0x1D, 0xB1); + } else if (addr == 0x150) { + chksum = _rivian_compute_checksum(to_push, 0x1D, 0x9A); + } else { + } + return chksum; +} + +static bool rivian_get_quality_flag_valid(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + bool valid = false; + if (addr == 0x208) { + valid = ((GET_BYTE(to_push, 3) >> 3) & 0x3U) == 0x1U; // ESP_Vehicle_Speed_Q + } else if (addr == 0x150) { + valid = (GET_BYTE(to_push, 1) >> 6) == 0x1U; // VDM_VehicleSpeedQ + } else { + } + return valid; +} + +static void rivian_rx_hook(const CANPacket_t *to_push) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); + + if (bus == 0) { + // Vehicle speed + if (addr == 0x208) { + float speed = ((GET_BYTE(to_push, 6) << 8) | GET_BYTE(to_push, 7)) * 0.01; + vehicle_moving = speed > 0.0; + UPDATE_VEHICLE_SPEED(speed / 3.6); + } + + // Gas pressed and second speed source for variable torque limit + if (addr == 0x150) { + gas_pressed = GET_BYTE(to_push, 3) | (GET_BYTE(to_push, 4) & 0xC0U); + + // Disable controls if speeds from VDM and ESP ECUs are too far apart. + float vdm_speed = ((GET_BYTE(to_push, 5) << 8) | GET_BYTE(to_push, 6)) * 0.01 / 3.6; + bool is_invalid_speed = ABS(vdm_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > RIVIAN_MAX_SPEED_DELTA; + // TODO: this should generically cause rx valid to fall until re-enable + if (is_invalid_speed) { + controls_allowed = false; + } + } + + // Driver torque + if (addr == 0x380) { + int torque_driver_new = (((GET_BYTE(to_push, 2) << 4) | (GET_BYTE(to_push, 3) >> 4))) - 2050U; + update_sample(&torque_driver, torque_driver_new); + } + + // Brake pressed + if (addr == 0x38f) { + brake_pressed = GET_BIT(to_push, 23U); + } + } + + if (bus == 2) { + // Cruise state + if (addr == 0x100) { + const int feature_status = GET_BYTE(to_push, 2) >> 5U; + pcm_cruise_check(feature_status == 1); + } + } +} + +static bool rivian_tx_hook(const CANPacket_t *to_send) { + // Rivian utilizes more torque at low speed to maintain the same lateral accel + const TorqueSteeringLimits RIVIAN_STEERING_LIMITS = { + .max_torque = 350, + .dynamic_max_torque = true, + .max_torque_lookup = { + {9., 17., 17.}, + {350, 250, 250}, + }, + .max_rate_up = 3, + .max_rate_down = 5, + .max_rt_delta = 125, + .driver_torque_multiplier = 2, + .driver_torque_allowance = 100, + .type = TorqueDriverLimited, + }; + + const LongitudinalLimits RIVIAN_LONG_LIMITS = { + .max_accel = 200, + .min_accel = -350, + .inactive_accel = 0, + }; + + bool tx = true; + int bus = GET_BUS(to_send); + + if (bus == 0) { + int addr = GET_ADDR(to_send); + + // Steering control + if (addr == 0x120) { + int desired_torque = ((GET_BYTE(to_send, 2) << 3U) | (GET_BYTE(to_send, 3) >> 5U)) - 1024U; + bool steer_req = GET_BIT(to_send, 28U); + + if (steer_torque_cmd_checks(desired_torque, steer_req, RIVIAN_STEERING_LIMITS)) { + tx = false; + } + } + + // Longitudinal control + if (addr == 0x160) { + int raw_accel = ((GET_BYTE(to_send, 2) << 3) | (GET_BYTE(to_send, 3) >> 5)) - 1024U; + if (longitudinal_accel_checks(raw_accel, RIVIAN_LONG_LIMITS)) { + tx = false; + } + } + } + + return tx; +} + +static safety_config rivian_init(uint16_t param) { + // SCCM_WheelTouch: for hiding hold wheel alert + // VDM_AdasSts: for canceling stock ACC + // 0x120 = ACM_lkaHbaCmd, 0x321 = SCCM_WheelTouch, 0x162 = VDM_AdasSts + static const CanMsg RIVIAN_TX_MSGS[] = {{0x120, 0, 8, .check_relay = true}, {0x321, 2, 7, .check_relay = true}, {0x162, 2, 8, .check_relay = true}}; + // 0x160 = ACM_longitudinalRequest + static const CanMsg RIVIAN_LONG_TX_MSGS[] = {{0x120, 0, 8, .check_relay = true}, {0x321, 2, 7, .check_relay = true}, {0x160, 0, 5, .check_relay = true}}; + + static RxCheck rivian_rx_checks[] = { + {.msg = {{0x208, 0, 8, .frequency = 50U, .max_counter = 14U, .quality_flag = true}, { 0 }, { 0 }}}, // ESP_Status (speed) + {.msg = {{0x150, 0, 7, .frequency = 50U, .max_counter = 14U, .quality_flag = true}, { 0 }, { 0 }}}, // VDM_PropStatus (gas pedal & 2nd speed) + {.msg = {{0x380, 0, 5, .frequency = 100U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // EPAS_SystemStatus (driver torque) + {.msg = {{0x38f, 0, 6, .frequency = 50U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // iBESP2 (brakes) + {.msg = {{0x100, 2, 8, .frequency = 100U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // ACM_Status (cruise state) + }; + + bool rivian_longitudinal = false; + + UNUSED(param); + #ifdef ALLOW_DEBUG + const int FLAG_RIVIAN_LONG_CONTROL = 1; + rivian_longitudinal = GET_FLAG(param, FLAG_RIVIAN_LONG_CONTROL); + #endif + + // FIXME: cppcheck thinks that rivian_longitudinal is always false. This is not true + // if ALLOW_DEBUG is defined but cppcheck is run without ALLOW_DEBUG + // cppcheck-suppress knownConditionTrueFalse + return rivian_longitudinal ? BUILD_SAFETY_CFG(rivian_rx_checks, RIVIAN_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(rivian_rx_checks, RIVIAN_TX_MSGS); +} + +const safety_hooks rivian_hooks = { + .init = rivian_init, + .rx = rivian_rx_hook, + .tx = rivian_tx_hook, + .get_counter = rivian_get_counter, + .get_checksum = rivian_get_checksum, + .compute_checksum = rivian_compute_checksum, + .get_quality_flag_valid = rivian_get_quality_flag_valid, +}; diff --git a/opendbc_repo/opendbc/safety/safety/safety_subaru.h b/opendbc_repo/opendbc/safety/modes/subaru.h similarity index 82% rename from opendbc_repo/opendbc/safety/safety/safety_subaru.h rename to opendbc_repo/opendbc/safety/modes/subaru.h index 8c59776004..14413700da 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_subaru.h +++ b/opendbc_repo/opendbc/safety/modes/subaru.h @@ -1,12 +1,11 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" #define SUBARU_STEERING_LIMITS_GENERATOR(steer_max, rate_up, rate_down) \ { \ - .max_steer = (steer_max), \ + .max_torque = (steer_max), \ .max_rt_delta = 940, \ - .max_rt_interval = 250000, \ .max_rate_up = (rate_up), \ .max_rate_down = (rate_down), \ .driver_torque_multiplier = 50, \ @@ -44,22 +43,25 @@ #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, true}, \ - {MSG_SUBARU_ES_Distance, alt_bus, 8, false}, \ - {MSG_SUBARU_ES_DashStatus, SUBARU_MAIN_BUS, 8, false}, \ - {MSG_SUBARU_ES_LKAS_State, SUBARU_MAIN_BUS, 8, false}, \ - {MSG_SUBARU_ES_Infotainment, SUBARU_MAIN_BUS, 8, false}, \ +#define SUBARU_BASE_TX_MSGS(alt_bus, lkas_msg) \ + {lkas_msg, SUBARU_MAIN_BUS, 8, .check_relay = true}, \ + {MSG_SUBARU_ES_DashStatus, SUBARU_MAIN_BUS, 8, .check_relay = true}, \ + {MSG_SUBARU_ES_LKAS_State, SUBARU_MAIN_BUS, 8, .check_relay = true}, \ + {MSG_SUBARU_ES_Infotainment, SUBARU_MAIN_BUS, 8, .check_relay = true}, \ -#define SUBARU_COMMON_LONG_TX_MSGS(alt_bus) \ - {MSG_SUBARU_ES_Brake, alt_bus, 8, false}, \ - {MSG_SUBARU_ES_Status, alt_bus, 8, false}, \ +#define SUBARU_COMMON_TX_MSGS(alt_bus) \ + {MSG_SUBARU_ES_Distance, alt_bus, 8, .check_relay = false}, \ -#define SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() \ - {MSG_SUBARU_ES_UDS_Request, SUBARU_CAM_BUS, 8, false}, \ - {MSG_SUBARU_ES_HighBeamAssist, SUBARU_MAIN_BUS, 8, false}, \ - {MSG_SUBARU_ES_STATIC_1, SUBARU_MAIN_BUS, 8, false}, \ - {MSG_SUBARU_ES_STATIC_2, SUBARU_MAIN_BUS, 8, false}, \ +#define SUBARU_COMMON_LONG_TX_MSGS(alt_bus) \ + {MSG_SUBARU_ES_Distance, alt_bus, 8, .check_relay = true}, \ + {MSG_SUBARU_ES_Brake, alt_bus, 8, .check_relay = true}, \ + {MSG_SUBARU_ES_Status, alt_bus, 8, .check_relay = true}, \ + +#define SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() \ + {MSG_SUBARU_ES_UDS_Request, SUBARU_CAM_BUS, 8, .check_relay = false}, \ + {MSG_SUBARU_ES_HighBeamAssist, SUBARU_MAIN_BUS, 8, .check_relay = false}, \ + {MSG_SUBARU_ES_STATIC_1, SUBARU_MAIN_BUS, 8, .check_relay = false}, \ + {MSG_SUBARU_ES_STATIC_2, SUBARU_MAIN_BUS, 8, .check_relay = false}, \ #define SUBARU_COMMON_RX_CHECKS(alt_bus) \ {.msg = {{MSG_SUBARU_Throttle, SUBARU_MAIN_BUS, 8, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ @@ -205,42 +207,24 @@ static bool subaru_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool subaru_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - 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)); - - block_msg = block_lkas || (subaru_longitudinal && block_long); - } - - return block_msg; -} - static safety_config subaru_init(uint16_t param) { static const CanMsg SUBARU_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_BASE_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS) }; static const CanMsg SUBARU_LONG_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_BASE_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) SUBARU_COMMON_LONG_TX_MSGS(SUBARU_MAIN_BUS) }; static const CanMsg SUBARU_GEN2_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_BASE_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS) }; static const CanMsg SUBARU_GEN2_LONG_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) + SUBARU_BASE_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) SUBARU_COMMON_LONG_TX_MSGS(SUBARU_ALT_BUS) SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() }; @@ -277,7 +261,6 @@ 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/opendbc_repo/opendbc/safety/safety/safety_subaru_preglobal.h b/opendbc_repo/opendbc/safety/modes/subaru_preglobal.h similarity index 88% rename from opendbc_repo/opendbc/safety/safety/safety_subaru_preglobal.h rename to opendbc_repo/opendbc/safety/modes/subaru_preglobal.h index 8c229a0412..2252792eaf 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_subaru_preglobal.h +++ b/opendbc_repo/opendbc/safety/modes/subaru_preglobal.h @@ -1,6 +1,6 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // Preglobal platform // 0x161 is ES_CruiseThrottle @@ -55,9 +55,8 @@ static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits SUBARU_PG_STEERING_LIMITS = { - .max_steer = 2047, + .max_torque = 2047, .max_rt_delta = 940, - .max_rt_interval = 250000, .max_rate_up = 50, .max_rate_down = 70, .driver_torque_multiplier = 10, @@ -83,20 +82,10 @@ static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool subaru_preglobal_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (bus_num == SUBARU_PG_CAM_BUS) { - block_msg = ((addr == MSG_SUBARU_PG_ES_Distance) || (addr == MSG_SUBARU_PG_ES_LKAS)); - } - - return block_msg; -} - static safety_config subaru_preglobal_init(uint16_t param) { static const CanMsg SUBARU_PG_TX_MSGS[] = { - {MSG_SUBARU_PG_ES_Distance, SUBARU_PG_MAIN_BUS, 8, false}, - {MSG_SUBARU_PG_ES_LKAS, SUBARU_PG_MAIN_BUS, 8, true} + {MSG_SUBARU_PG_ES_Distance, SUBARU_PG_MAIN_BUS, 8, .check_relay = true}, + {MSG_SUBARU_PG_ES_LKAS, SUBARU_PG_MAIN_BUS, 8, .check_relay = true} }; // TODO: do checksum and counter checks after adding the signals to the outback dbc file @@ -118,5 +107,4 @@ 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/opendbc_repo/opendbc/safety/modes/tesla.h b/opendbc_repo/opendbc/safety/modes/tesla.h new file mode 100644 index 0000000000..9e3e63ab2f --- /dev/null +++ b/opendbc_repo/opendbc/safety/modes/tesla.h @@ -0,0 +1,450 @@ +#pragma once + +#include "opendbc/safety/safety_declarations.h" + +// parameters for lateral accel/jerk angle limiting using a simple vehicle model +typedef struct { + const float slip_factor; + const float steer_ratio; + const float wheelbase; +} AngleSteeringParams; + +#define TESLA_MAX_SPEED_DELTA 2.0 // m/s + +static bool tesla_longitudinal = false; +static bool tesla_stock_aeb = false; + +// Only rising edges while controls are not allowed are considered for these systems: +// TODO: Only LKAS (non-emergency) is currently supported since we've only seen it +static bool tesla_stock_lkas = false; +static bool tesla_stock_lkas_prev = false; + +// Only Summon is currently supported due to Autopark not setting Autopark state properly +static bool tesla_autopark = false; +static bool tesla_autopark_prev = false; + +static float tesla_curvature_factor(const float speed, const AngleSteeringParams params) { + return 1. / (1. - (params.slip_factor * (speed * speed))) / params.wheelbase; +} + +static bool tesla_steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const AngleSteeringLimits limits, + const AngleSteeringParams params) { + + static const float RAD_TO_DEG = 57.29577951308232; + static const float ISO_LATERAL_ACCEL = 3.0; // m/s^2 + + // Highway curves are rolled in the direction of the turn, add tolerance to compensate + static const float EARTH_G = 9.81; + static const float AVERAGE_ROAD_ROLL = 0.06; // ~3.4 degrees, 6% superelevation + + static const float MAX_LATERAL_ACCEL = ISO_LATERAL_ACCEL + (EARTH_G * AVERAGE_ROAD_ROLL); // ~3.6 m/s^2 + static const float MAX_LATERAL_JERK = 3.0 + (EARTH_G * AVERAGE_ROAD_ROLL); // ~3.6 m/s^3 + + const float fudged_speed = (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.; + const float curvature_factor = tesla_curvature_factor(fudged_speed, params); + + bool violation = false; + + if (controls_allowed && steer_control_enabled) { + // *** ISO lateral jerk limit *** + // calculate maximum angle rate per second + const float speed = MAX(fudged_speed, 1.0); + const float max_curvature_rate_sec = MAX_LATERAL_JERK / (speed * speed); + const float max_angle_rate_sec = max_curvature_rate_sec * params.steer_ratio / curvature_factor * RAD_TO_DEG; + + // finally get max angle delta per frame + const float max_angle_delta = max_angle_rate_sec * (0.01f * 2.0f); // 50 Hz + const int max_angle_delta_can = (max_angle_delta * limits.angle_deg_to_can) + 1.; + + // NOTE: symmetric up and down limits + const int highest_desired_angle = desired_angle_last + max_angle_delta_can; + const int lowest_desired_angle = desired_angle_last - max_angle_delta_can; + + violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + + // *** ISO lateral accel limit *** + const float max_curvature = MAX_LATERAL_ACCEL / (speed * speed); + const float max_angle = max_curvature * params.steer_ratio / curvature_factor * RAD_TO_DEG; + const int max_angle_can = (max_angle * limits.angle_deg_to_can) + 1.; + + violation |= max_limit_check(desired_angle, max_angle_can, -max_angle_can); + } + desired_angle_last = desired_angle; + + // Angle should either be 0 or same as current angle while not steering + if (!steer_control_enabled) { + const int max_inactive_angle = CLAMP(angle_meas.max, -limits.max_angle, limits.max_angle) + 1; + const int min_inactive_angle = CLAMP(angle_meas.min, -limits.max_angle, limits.max_angle) - 1; + violation |= (limits.inactive_angle_is_zero ? (desired_angle != 0) : + max_limit_check(desired_angle, max_inactive_angle, min_inactive_angle)); + } + + // No angle control allowed when controls are not allowed + violation |= !controls_allowed && steer_control_enabled; + + return violation; +} + +static uint8_t tesla_get_counter(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + uint8_t cnt = 0; + if (addr == 0x2b9) { + // Signal: DAS_controlCounter + cnt = GET_BYTE(to_push, 6) >> 5; + } else if (addr == 0x488) { + // Signal: DAS_steeringControlCounter + cnt = GET_BYTE(to_push, 2) & 0x0FU; + } else if ((addr == 0x257) || (addr == 0x118) || (addr == 0x39d) || (addr == 0x286) || (addr == 0x311)) { + // Signal: DI_speedCounter, DI_systemStatusCounter, IBST_statusCounter, DI_locStatusCounter, UI_warningCounter + cnt = GET_BYTE(to_push, 1) & 0x0FU; + } else if (addr == 0x155) { + // Signal: ESP_wheelRotationCounter + cnt = GET_BYTE(to_push, 6) >> 4; + } else if (addr == 0x370) { + // Signal: EPAS3S_sysStatusCounter + cnt = GET_BYTE(to_push, 6) & 0x0FU; + } else { + } + return cnt; +} + +static int _tesla_get_checksum_byte(const int addr) { + int checksum_byte = -1; + if ((addr == 0x370) || (addr == 0x2b9) || (addr == 0x155)) { + // Signal: EPAS3S_sysStatusChecksum, DAS_controlChecksum, ESP_wheelRotationChecksum + checksum_byte = 7; + } else if (addr == 0x488) { + // Signal: DAS_steeringControlChecksum + checksum_byte = 3; + } else if ((addr == 0x257) || (addr == 0x118) || (addr == 0x39d) || (addr == 0x286) || (addr == 0x311)) { + // Signal: DI_speedChecksum, DI_systemStatusChecksum, IBST_statusChecksum, DI_locStatusChecksum, UI_warningChecksum + checksum_byte = 0; + } else { + } + return checksum_byte; +} + +static uint32_t tesla_get_checksum(const CANPacket_t *to_push) { + uint8_t chksum = 0; + int checksum_byte = _tesla_get_checksum_byte(GET_ADDR(to_push)); + if (checksum_byte != -1) { + chksum = GET_BYTE(to_push, checksum_byte); + } + return chksum; +} + +static uint32_t tesla_compute_checksum(const CANPacket_t *to_push) { + unsigned int addr = GET_ADDR(to_push); + + uint8_t chksum = 0; + int checksum_byte = _tesla_get_checksum_byte(addr); + + if (checksum_byte != -1) { + chksum = (uint8_t)((addr & 0xFFU) + ((addr >> 8) & 0xFFU)); + int len = GET_LEN(to_push); + for (int i = 0; i < len; i++) { + if (i != checksum_byte) { + chksum += GET_BYTE(to_push, i); + } + } + } + return chksum; +} + +static bool tesla_get_quality_flag_valid(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + bool valid = false; + if (addr == 0x155) { + valid = (GET_BYTE(to_push, 5) & 0x1U) == 0x1U; // ESP_wheelSpeedsQF + } else { + } + return valid; +} + +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) { + // Steering angle: (0.1 * val) - 819.2 in deg. + if (addr == 0x370) { + // Store it 1/10 deg to match steering request + const int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U; + update_sample(&angle_meas, angle_meas_new); + + const int hands_on_level = GET_BYTE(to_push, 4) >> 6; // EPAS3S_handsOnLevel + const int eac_status = GET_BYTE(to_push, 6) >> 5; // EPAS3S_eacStatus + const int eac_error_code = GET_BYTE(to_push, 2) >> 4; // EPAS3S_eacErrorCode + + // Disengage on normal user override, or if high angle rate fault from user overriding extremely quickly + steering_disengage = (hands_on_level >= 3) || ((eac_status == 0) && (eac_error_code == 9)); + } + + // Vehicle speed (DI_speed) + if (addr == 0x257) { + // Vehicle speed: ((val * 0.08) - 40) / MS_TO_KPH + float speed = ((((GET_BYTE(to_push, 2) << 4) | (GET_BYTE(to_push, 1) >> 4)) * 0.08) - 40.) / 3.6; + UPDATE_VEHICLE_SPEED(speed); + } + + // 2nd vehicle speed (ESP_B) + if (addr == 0x155) { + // Disable controls if speeds from DI (Drive Inverter) and ESP ECUs are too far apart. + float esp_speed = (((GET_BYTE(to_push, 6) & 0x0FU) << 6) | GET_BYTE(to_push, 5) >> 2) * 0.5 / 3.6; + bool is_invalid_speed = ABS(esp_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > TESLA_MAX_SPEED_DELTA; + // TODO: this should generically cause rx valid to fall until re-enable + if (is_invalid_speed) { + controls_allowed = false; + } + } + + // Gas pressed + if (addr == 0x118) { + gas_pressed = (GET_BYTE(to_push, 4) != 0U); + } + + // Brake pressed + if (addr == 0x39d) { + brake_pressed = (GET_BYTE(to_push, 2) & 0x03U) == 2U; + } + + // Cruise and Autopark/Summon state + if (addr == 0x286) { + // Autopark state + int autopark_state = (GET_BYTE(to_push, 3) >> 1) & 0x0FU; // DI_autoparkState + bool tesla_autopark_now = (autopark_state == 3) || // ACTIVE + (autopark_state == 4) || // COMPLETE + (autopark_state == 9); // SELFPARK_STARTED + + // Only consider rising edges while controls are not allowed + if (tesla_autopark_now && !tesla_autopark_prev && !cruise_engaged_prev) { + tesla_autopark = true; + } + if (!tesla_autopark_now) { + tesla_autopark = false; + } + tesla_autopark_prev = tesla_autopark_now; + + // Cruise state + int cruise_state = (GET_BYTE(to_push, 1) >> 4) & 0x07U; + 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 + cruise_engaged = cruise_engaged && !tesla_autopark; + + vehicle_moving = cruise_state != 3; // STANDSTILL + pcm_cruise_check(cruise_engaged); + } + } + + if (bus == 2) { + // DAS_control + if (addr == 0x2b9) { + // "AEB_ACTIVE" + tesla_stock_aeb = (GET_BYTE(to_push, 2) & 0x03U) == 1U; + } + + // DAS_steeringControl + if (addr == 0x488) { + int steering_control_type = GET_BYTE(to_push, 2) >> 6; + bool tesla_stock_lkas_now = steering_control_type == 2; // "LANE_KEEP_ASSIST" + + // Only consider rising edges while controls are not allowed + if (tesla_stock_lkas_now && !tesla_stock_lkas_prev && !controls_allowed) { + tesla_stock_lkas = true; + } + if (!tesla_stock_lkas_now) { + tesla_stock_lkas = false; + } + tesla_stock_lkas_prev = tesla_stock_lkas_now; + } + } +} + + +static bool tesla_tx_hook(const CANPacket_t *to_send) { + const AngleSteeringLimits TESLA_STEERING_LIMITS = { + .max_angle = 3600, // 360 deg, EPAS faults above this + .angle_deg_to_can = 10, + }; + + // NOTE: based off TESLA_MODEL_Y to match openpilot + const AngleSteeringParams TESLA_STEERING_PARAMS = { + .slip_factor = -0.000580374383851451, // calc_slip_factor(VM) + .steer_ratio = 12., + .wheelbase = 2.89, + }; + + const LongitudinalLimits TESLA_LONG_LIMITS = { + .max_accel = 425, // 2 m/s^2 + .min_accel = 288, // -3.48 m/s^2 + .inactive_accel = 375, // 0. m/s^2 + }; + + bool tx = true; + int addr = GET_ADDR(to_send); + bool violation = false; + + // Don't send any messages when Autopark is active + if (tesla_autopark) { + violation = true; + } + + // Steering control: (0.1 * val) - 1638.35 in deg. + if (addr == 0x488) { + // 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 == 1; // ANGLE_CONTROL + + if (tesla_steer_angle_cmd_checks(desired_angle, steer_control_enabled, TESLA_STEERING_LIMITS, TESLA_STEERING_PARAMS)) { + violation = true; + } + + bool valid_steer_control_type = (steer_control_type == 0) || // NONE + (steer_control_type == 1); // ANGLE_CONTROL + if (!valid_steer_control_type) { + violation = true; + } + + if (tesla_stock_lkas) { + // Don't allow any steering commands when stock LKAS is active + violation = true; + } + } + + // DAS_control: longitudinal control message + if (addr == 0x2b9) { + // 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 long/cancel messages when the stock AEB system is active + if (tesla_stock_aeb) { + violation = true; + } + + 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); + int acc_state = GET_BYTE(to_send, 1) >> 4; + + if (tesla_longitudinal) { + // Prevent both acceleration from being negative, as this could cause the car to reverse after coming to standstill + if ((raw_accel_max < TESLA_LONG_LIMITS.inactive_accel) && (raw_accel_min < TESLA_LONG_LIMITS.inactive_accel)) { + violation = true; + } + + // Don't allow any acceleration limits above the safety limits + violation |= longitudinal_accel_checks(raw_accel_max, TESLA_LONG_LIMITS); + violation |= longitudinal_accel_checks(raw_accel_min, TESLA_LONG_LIMITS); + } else { + // Can only send cancel longitudinal messages when not controlling longitudinal + if (acc_state != 13) { // ACC_CANCEL_GENERIC_SILENT + violation = true; + } + + // No actuation is allowed when not controlling longitudinal + if ((raw_accel_max != TESLA_LONG_LIMITS.inactive_accel) || (raw_accel_min != TESLA_LONG_LIMITS.inactive_accel)) { + violation = true; + } + } + } + + if (violation) { + tx = false; + } + + return tx; +} + +static bool tesla_fwd_hook(int bus_num, int addr) { + bool block_msg = false; + + if (bus_num == 2) { + if (!tesla_autopark) { + // APS_eacMonitor + if (addr == 0x27d) { + block_msg = true; + } + + // DAS_steeringControl + if ((addr == 0x488) && !tesla_stock_lkas) { + block_msg = true; + } + + // DAS_control + if (tesla_longitudinal && (addr == 0x2b9) && !tesla_stock_aeb) { + block_msg = true; + } + } + } + + return block_msg; +} + +static safety_config tesla_init(uint16_t param) { + + static const CanMsg TESLA_M3_Y_TX_MSGS[] = { + {0x488, 0, 4, .check_relay = true, .disable_static_blocking = true}, // DAS_steeringControl + {0x2b9, 0, 8, .check_relay = false}, // DAS_control (for cancel) + {0x27D, 0, 3, .check_relay = true, .disable_static_blocking = true}, // APS_eacMonitor + }; + + static const CanMsg TESLA_M3_Y_LONG_TX_MSGS[] = { + {0x488, 0, 4, .check_relay = true, .disable_static_blocking = true}, // DAS_steeringControl + {0x2b9, 0, 8, .check_relay = true, .disable_static_blocking = true}, // DAS_control + {0x27D, 0, 3, .check_relay = true, .disable_static_blocking = true}, // APS_eacMonitor + }; + + UNUSED(param); +#ifdef ALLOW_DEBUG + const int TESLA_FLAG_LONGITUDINAL_CONTROL = 1; + tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); +#endif + + tesla_stock_aeb = false; + tesla_stock_lkas = false; + tesla_stock_lkas_prev = false; + // we need to assume Autopark/Summon on startup since DI_state is a low freq msg. + // this is so that we don't fault if starting while these systems are active + tesla_autopark = true; + tesla_autopark_prev = false; + + static RxCheck tesla_model3_y_rx_checks[] = { + {.msg = {{0x2b9, 2, 8, .max_counter = 7U, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control + {.msg = {{0x488, 2, 4, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, // DAS_steeringControl + {.msg = {{0x257, 0, 8, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, // DI_speed (speed in kph) + {.msg = {{0x155, 0, 8, .max_counter = 15U, .quality_flag = true, .frequency = 50U}, { 0 }, { 0 }}}, // ESP_B (2nd speed in kph) + {.msg = {{0x370, 0, 8, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, // EPAS3S_sysStatus (steering angle) + {.msg = {{0x118, 0, 8, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, // DI_systemStatus (gas pedal) + {.msg = {{0x39d, 0, 5, .max_counter = 15U, .frequency = 25U}, { 0 }, { 0 }}}, // IBST_status (brakes) + {.msg = {{0x286, 0, 8, .max_counter = 15U, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state (acc state) + {.msg = {{0x311, 0, 7, .max_counter = 15U, .frequency = 10U}, { 0 }, { 0 }}}, // UI_warning (blinkers, buckle switch & doors) + }; + + safety_config ret; + if (tesla_longitudinal) { + ret = BUILD_SAFETY_CFG(tesla_model3_y_rx_checks, TESLA_M3_Y_LONG_TX_MSGS); + } else { + ret = BUILD_SAFETY_CFG(tesla_model3_y_rx_checks, TESLA_M3_Y_TX_MSGS); + } + return ret; +} + +const safety_hooks tesla_hooks = { + .init = tesla_init, + .rx = tesla_rx_hook, + .tx = tesla_tx_hook, + .fwd = tesla_fwd_hook, + .get_counter = tesla_get_counter, + .get_checksum = tesla_get_checksum, + .compute_checksum = tesla_compute_checksum, + .get_quality_flag_valid = tesla_get_quality_flag_valid, +}; diff --git a/opendbc_repo/opendbc/safety/safety/safety_toyota.h b/opendbc_repo/opendbc/safety/modes/toyota.h similarity index 85% rename from opendbc_repo/opendbc/safety/safety/safety_toyota.h rename to opendbc_repo/opendbc/safety/modes/toyota.h index 7185001da1..4c969a150c 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_toyota.h +++ b/opendbc_repo/opendbc/safety/modes/toyota.h @@ -1,28 +1,35 @@ #pragma once -#include "safety_declarations.h" +#include "opendbc/safety/safety_declarations.h" // Stock longitudinal #define TOYOTA_BASE_TX_MSGS \ - {0x191, 0, 8, false}, {0x412, 0, 8, false}, {0x1D2, 0, 8, false}, /* LKAS + LTA + PCM cancel cmd */ \ + {0x191, 0, 8, .check_relay = true}, {0x412, 0, 8, .check_relay = true}, {0x1D2, 0, 8, .check_relay = false}, /* LKAS + LTA + PCM cancel cmd */ \ #define TOYOTA_COMMON_TX_MSGS \ TOYOTA_BASE_TX_MSGS \ - {0x2E4, 0, 5, true}, \ - {0x343, 0, 8, false}, /* ACC cancel cmd */ \ + {0x2E4, 0, 5, .check_relay = true}, \ + {0x343, 0, 8, .check_relay = false}, /* ACC cancel cmd */ \ #define TOYOTA_COMMON_SECOC_TX_MSGS \ TOYOTA_BASE_TX_MSGS \ - {0x2E4, 0, 8, true}, {0x131, 0, 8, false}, \ - {0x343, 0, 8, false}, /* ACC cancel cmd */ \ - -#define TOYOTA_COMMON_LONG_TX_MSGS \ - TOYOTA_COMMON_TX_MSGS \ - {0x283, 0, 7, false}, {0x2E6, 0, 8, false}, {0x2E7, 0, 8, false}, {0x33E, 0, 7, false}, {0x344, 0, 8, false}, {0x365, 0, 7, false}, {0x366, 0, 7, false}, {0x4CB, 0, 8, false}, /* DSU bus 0 */ \ - {0x128, 1, 6, false}, {0x141, 1, 4, false}, {0x160, 1, 8, false}, {0x161, 1, 7, false}, {0x470, 1, 4, false}, /* DSU bus 1 */ \ - {0x411, 0, 8, false}, /* PCS_HUD */ \ - {0x750, 0, 8, false}, /* radar diagnostic address */ \ - {0x343, 0, 8, true}, /* ACC */ \ + {0x2E4, 0, 8, .check_relay = true}, {0x131, 0, 8, .check_relay = true}, \ + {0x343, 0, 8, .check_relay = false}, /* ACC cancel cmd */ \ + +#define TOYOTA_COMMON_LONG_TX_MSGS \ + TOYOTA_COMMON_TX_MSGS \ + /* DSU bus 0 */ \ + {0x283, 0, 7, .check_relay = false}, {0x2E6, 0, 8, .check_relay = false}, {0x2E7, 0, 8, .check_relay = false}, {0x33E, 0, 7, .check_relay = false}, \ + {0x344, 0, 8, .check_relay = false}, {0x365, 0, 7, .check_relay = false}, {0x366, 0, 7, .check_relay = false}, {0x4CB, 0, 8, .check_relay = false}, \ + /* DSU bus 1 */ \ + {0x128, 1, 6, .check_relay = false}, {0x141, 1, 4, .check_relay = false}, {0x160, 1, 8, .check_relay = false}, {0x161, 1, 7, .check_relay = false}, \ + {0x470, 1, 4, .check_relay = false}, \ + /* PCS_HUD */ \ + {0x411, 0, 8, .check_relay = false}, \ + /* radar diagnostic address */ \ + {0x750, 0, 8, .check_relay = false}, \ + /* ACC */ \ + {0x343, 0, 8, .check_relay = true}, \ #define TOYOTA_COMMON_RX_CHECKS(lta) \ {.msg = {{ 0xaa, 0, 8, .ignore_checksum = true, .ignore_counter = true, .frequency = 83U}, { 0 }, { 0 }}}, \ @@ -155,19 +162,18 @@ static void toyota_rx_hook(const CANPacket_t *to_push) { static bool toyota_tx_hook(const CANPacket_t *to_send) { const TorqueSteeringLimits TOYOTA_TORQUE_STEERING_LIMITS = { - .max_steer = 1500, + .max_torque = 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 + .min_valid_request_rt_interval = 171000, // 171ms; a ~10% buffer on cutting every 19 frames .has_steer_req_tolerance = true, }; @@ -399,27 +405,10 @@ static safety_config toyota_init(uint16_t param) { return ret; } -static bool toyota_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - 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)); - // on SecOC cars 0x131 is also LTA - is_lkas_msg |= toyota_secoc && (addr == 0x131); - // in TSS2 the camera does ACC as well, so filter 0x343 - bool is_acc_msg = (addr == 0x343); - block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal); - } - - return block_msg; -} - 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_quality_flag_valid = toyota_get_quality_flag_valid, diff --git a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_common.h b/opendbc_repo/opendbc/safety/modes/volkswagen_common.h similarity index 80% rename from opendbc_repo/opendbc/safety/safety/safety_volkswagen_common.h rename to opendbc_repo/opendbc/safety/modes/volkswagen_common.h index 1285bb883e..72525dcced 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_common.h +++ b/opendbc_repo/opendbc/safety/modes/volkswagen_common.h @@ -53,15 +53,15 @@ static uint32_t volkswagen_mqb_meb_compute_crc(const CANPacket_t *to_push) { uint8_t counter = volkswagen_mqb_meb_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]; + 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]; + 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]; + 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]; + 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]; + 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 } diff --git a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_mqb.h b/opendbc_repo/opendbc/safety/modes/volkswagen_mqb.h similarity index 85% rename from opendbc_repo/opendbc/safety/safety/safety_volkswagen_mqb.h rename to opendbc_repo/opendbc/safety/modes/volkswagen_mqb.h index f3a1851650..beba367de3 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_mqb.h +++ b/opendbc_repo/opendbc/safety/modes/volkswagen_mqb.h @@ -1,7 +1,7 @@ #pragma once -#include "safety_declarations.h" -#include "safety_volkswagen_common.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/modes/volkswagen_common.h" static bool volkswagen_mqb_brake_pedal_switch = false; static bool volkswagen_mqb_brake_pressure_detected = false; @@ -9,11 +9,12 @@ static bool volkswagen_mqb_brake_pressure_detected = false; static safety_config volkswagen_mqb_init(uint16_t param) { // Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration - static const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8, true}, {MSG_GRA_ACC_01, 0, 8, false}, {MSG_GRA_ACC_01, 2, 8, false}, - {MSG_LDW_02, 0, 8, false}, {MSG_LH_EPS_03, 2, 8, false}}; + // MSG_LH_EPS_03: openpilot needs to replace apparent driver steering input torque to pacify VW Emergency Assist + static const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8, .check_relay = true}, {MSG_GRA_ACC_01, 0, 8, .check_relay = false}, {MSG_GRA_ACC_01, 2, 8, .check_relay = false}, + {MSG_LDW_02, 0, 8, .check_relay = true}, {MSG_LH_EPS_03, 2, 8, .check_relay = true}}; - static const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8, true}, {MSG_LDW_02, 0, 8, false}, {MSG_LH_EPS_03, 2, 8, false}, - {MSG_ACC_02, 0, 8, false}, {MSG_ACC_06, 0, 8, false}, {MSG_ACC_07, 0, 8, false}}; + static const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8, .check_relay = true}, {MSG_LDW_02, 0, 8, .check_relay = true}, {MSG_LH_EPS_03, 2, 8, .check_relay = true}, + {MSG_ACC_02, 0, 8, .check_relay = true}, {MSG_ACC_06, 0, 8, .check_relay = true}, {MSG_ACC_07, 0, 8, .check_relay = true}}; static RxCheck volkswagen_mqb_rx_checks[] = { {.msg = {{MSG_ESP_19, 0, 8, .ignore_checksum = true, .ignore_counter = true, .frequency = 100U}, { 0 }, { 0 }}}, @@ -127,9 +128,8 @@ static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) { static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { // lateral limits const TorqueSteeringLimits VOLKSWAGEN_MQB_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) + .max_torque = 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, @@ -201,38 +201,10 @@ static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool volkswagen_mqb_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - 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 - block_msg = true; - } - 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 - block_msg = true; - } 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 - block_msg = true; - } else { - } - break; - default: - break; - } - - return block_msg; -} - 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_meb_get_counter, .get_checksum = volkswagen_mqb_meb_get_checksum, .compute_checksum = volkswagen_mqb_meb_compute_crc, diff --git a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_pq.h b/opendbc_repo/opendbc/safety/modes/volkswagen_pq.h similarity index 89% rename from opendbc_repo/opendbc/safety/safety/safety_volkswagen_pq.h rename to opendbc_repo/opendbc/safety/modes/volkswagen_pq.h index 3f0d8269cb..e5e8f781c8 100644 --- a/opendbc_repo/opendbc/safety/safety/safety_volkswagen_pq.h +++ b/opendbc_repo/opendbc/safety/modes/volkswagen_pq.h @@ -1,7 +1,7 @@ #pragma once -#include "safety_declarations.h" -#include "safety_volkswagen_common.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/modes/volkswagen_common.h" #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 @@ -52,11 +52,11 @@ static uint32_t volkswagen_pq_compute_checksum(const CANPacket_t *to_push) { static safety_config volkswagen_pq_init(uint16_t param) { // Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration - static const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5, true}, {MSG_LDW_1, 0, 8, false}, - {MSG_GRA_NEU, 0, 4, false}, {MSG_GRA_NEU, 2, 4, false}}; + static const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5, .check_relay = true}, {MSG_LDW_1, 0, 8, .check_relay = true}, + {MSG_GRA_NEU, 0, 4, .check_relay = false}, {MSG_GRA_NEU, 2, 4, .check_relay = false}}; - static const CanMsg VOLKSWAGEN_PQ_LONG_TX_MSGS[] = {{MSG_HCA_1, 0, 5, true}, {MSG_LDW_1, 0, 8, false}, - {MSG_ACC_SYSTEM, 0, 8, false}, {MSG_ACC_GRA_ANZEIGE, 0, 8, false}}; + static const CanMsg VOLKSWAGEN_PQ_LONG_TX_MSGS[] = {{MSG_HCA_1, 0, 5, .check_relay = true}, {MSG_LDW_1, 0, 8, .check_relay = true}, + {MSG_ACC_SYSTEM, 0, 8, .check_relay = true}, {MSG_ACC_GRA_ANZEIGE, 0, 8, .check_relay = true}}; static RxCheck volkswagen_pq_rx_checks[] = { {.msg = {{MSG_LENKHILFE_3, 0, 6, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, @@ -154,9 +154,8 @@ static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) { static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { // lateral limits const TorqueSteeringLimits VOLKSWAGEN_PQ_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) + .max_torque = 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_multiplier = 3, @@ -218,32 +217,10 @@ static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { return tx; } -static bool volkswagen_pq_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - switch (bus_num) { - case 2: - if ((addr == MSG_HCA_1) || (addr == MSG_LDW_1)) { - // openpilot takes over LKAS steering control and related HUD messages from the camera - block_msg = true; - } 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 - block_msg = true; - } else { - } - break; - default: - break; - } - - return block_msg; -} - 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/opendbc_repo/opendbc/safety/safety.h b/opendbc_repo/opendbc/safety/safety.h index ced9f3b888..886a84fade 100644 --- a/opendbc_repo/opendbc/safety/safety.h +++ b/opendbc_repo/opendbc/safety/safety.h @@ -1,62 +1,32 @@ #pragma once -#include "safety_declarations.h" -#include "can.h" +#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/board/can.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_rivian.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" +#include "opendbc/safety/modes/defaults.h" +#include "opendbc/safety/modes/honda.h" +#include "opendbc/safety/modes/toyota.h" +#include "opendbc/safety/modes/tesla.h" +#include "opendbc/safety/modes/gm.h" +#include "opendbc/safety/modes/ford.h" +#include "opendbc/safety/modes/hyundai.h" +#include "opendbc/safety/modes/chrysler.h" +#include "opendbc/safety/modes/rivian.h" +#include "opendbc/safety/modes/subaru.h" +#include "opendbc/safety/modes/subaru_preglobal.h" +#include "opendbc/safety/modes/mazda.h" +#include "opendbc/safety/modes/nissan.h" +#include "opendbc/safety/modes/volkswagen_mqb.h" +#include "opendbc/safety/modes/volkswagen_pq.h" +#include "opendbc/safety/modes/elm327.h" +#include "opendbc/safety/modes/body.h" // CAN-FD only safety modes #ifdef CANFD -#include "safety/safety_hyundai_canfd.h" +#include "opendbc/safety/modes/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 -#define SAFETY_RIVIAN 33U -#define SAFETY_VOLKSWAGEN_MEB 34U - uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len) { uint32_t ret = 0U; for (int i = 0; i < len; i++) { @@ -77,6 +47,8 @@ bool brake_pressed = false; bool brake_pressed_prev = false; bool regen_braking = false; bool regen_braking_prev = false; +bool steering_disengage; +bool steering_disengage_prev; bool cruise_engaged_prev = false; struct sample_t vehicle_speed; bool vehicle_moving = false; @@ -114,6 +86,9 @@ uint16_t current_safety_param = 0; static const safety_hooks *current_hooks = &nooutput_hooks; safety_config current_safety_config; +static void generic_rx_checks(void); +static void stock_ecu_check(bool stock_ecu_detected); + static bool is_msg_valid(RxCheck addr_list[], int index) { bool valid = true; if (index != -1) { @@ -216,15 +191,18 @@ bool safety_rx_hook(const CANPacket_t *to_push) { current_hooks->rx(to_push); } + // Handles gas, brake, and regen paddle + generic_rx_checks(); + // the relay malfunction hook runs on all incoming rx messages. - // check all tx msgs for liveness on sending bus if specified. + // check all applicable tx msgs for liveness on sending bus. // used to detect a relay malfunction or control messages from disabled ECUs like the radar const int bus = GET_BUS(to_push); const int addr = GET_ADDR(to_push); for (int i = 0; i < current_safety_config.tx_msgs_len; i++) { const CanMsg *m = ¤t_safety_config.tx_msgs[i]; if (m->check_relay) { - generic_rx_checks((m->addr == addr) && (m->bus == bus)); + stock_ecu_check((m->addr == addr) && (m->bus == bus)); } } @@ -280,11 +258,24 @@ static int get_fwd_bus(int bus_num) { int safety_fwd_hook(int bus_num, int addr) { bool blocked = relay_malfunction || current_safety_config.disable_forwarding; + // Block messages that are being checked for relay malfunctions. Safety modes can opt out of this + // in the case of selective AEB forwarding + const int destination_bus = get_fwd_bus(bus_num); + if (!blocked) { + for (int i = 0; i < current_safety_config.tx_msgs_len; i++) { + const CanMsg *m = ¤t_safety_config.tx_msgs[i]; + if (m->check_relay && !m->disable_static_blocking && (m->addr == addr) && (m->bus == destination_bus)) { + blocked = true; + break; + } + } + } + if (!blocked && (current_hooks->fwd != NULL)) { blocked = current_hooks->fwd(bus_num, addr); } - return blocked ? -1 : get_fwd_bus(bus_num); + return blocked ? -1 : destination_bus; } bool get_longitudinal_allowed(void) { @@ -355,14 +346,7 @@ static void relay_malfunction_set(void) { fault_occurred(FAULT_RELAY_MALFUNCTION); } -static void generic_rx_checks(bool stock_ecu_detected) { - // allow 1s of transition timeout after relay changes state before assessing malfunctioning - const uint32_t RELAY_TRNS_TIMEOUT = 1U; - - // 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; - } +static void generic_rx_checks(void) { gas_pressed_prev = gas_pressed; // exit controls on rising edge of brake press @@ -377,6 +361,17 @@ static void generic_rx_checks(bool stock_ecu_detected) { } regen_braking_prev = regen_braking; + // exit controls on rising edge of steering override/disengage + if (steering_disengage && !steering_disengage_prev) { + controls_allowed = false; + } + steering_disengage_prev = steering_disengage; +} + +static void stock_ecu_check(bool stock_ecu_detected) { + // allow 1s of transition timeout after relay changes state before assessing malfunctioning + const uint32_t RELAY_TRNS_TIMEOUT = 1U; + // check if stock ECU is on bus broken by car harness if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && stock_ecu_detected) { relay_malfunction_set(); @@ -435,6 +430,8 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { brake_pressed_prev = false; regen_braking = false; regen_braking_prev = false; + steering_disengage = false; + steering_disengage_prev = false; cruise_engaged_prev = false; vehicle_moving = false; acc_main_on = false; @@ -519,7 +516,7 @@ void update_sample(struct sample_t *sample, int sample_new) { } } -static bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { +bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { return (val > MAX_VAL) || (val < MIN_VAL); } @@ -643,13 +640,21 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee uint32_t ts = microsecond_timer_get(); if (controls_allowed) { + // Some safety models support variable torque limit based on vehicle speed + int max_torque = limits.max_torque; + if (limits.dynamic_max_torque) { + const float fudged_speed = (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.; + max_torque = interpolate(limits.max_torque_lookup, fudged_speed) + 1; + max_torque = CLAMP(max_torque, -limits.max_torque, limits.max_torque); + } + // *** global torque limit check *** - violation |= max_limit_check(desired_torque, limits.max_steer, -limits.max_steer); + violation |= max_limit_check(desired_torque, max_torque, -max_torque); // *** 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, + max_torque, limits.max_rate_up, limits.max_rate_down, limits.driver_torque_allowance, limits.driver_torque_multiplier); } else { violation |= dist_to_meas_check(desired_torque, desired_torque_last, &torque_meas, @@ -662,7 +667,7 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee // 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) { + if (ts_elapsed > MAX_TORQUE_RT_INTERVAL) { rt_torque_last = desired_torque; ts_torque_check_last = ts; } diff --git a/opendbc_repo/opendbc/safety/safety/safety_rivian.h b/opendbc_repo/opendbc/safety/safety/safety_rivian.h deleted file mode 100644 index 0afb3090c6..0000000000 --- a/opendbc_repo/opendbc/safety/safety/safety_rivian.h +++ /dev/null @@ -1,153 +0,0 @@ -#pragma once - -#include "safety_declarations.h" - -static bool rivian_longitudinal = false; - -static void rivian_rx_hook(const CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if (bus == 0) { - // Vehicle speed - if (addr == 0x208) { - vehicle_moving = GET_BYTE(to_push, 6) | GET_BYTE(to_push, 7); - } - - // Driver torque - if (addr == 0x380) { - int torque_driver_new = (((GET_BYTE(to_push, 2) << 4) | (GET_BYTE(to_push, 3) >> 4))) - 2050U; - update_sample(&torque_driver, torque_driver_new); - } - - // Gas pressed - if (addr == 0x150) { - gas_pressed = GET_BYTE(to_push, 3) | (GET_BYTE(to_push, 4) & 0xC0U); - } - - // Brake pressed - if (addr == 0x38f) { - brake_pressed = GET_BIT(to_push, 23U); - } - } - - if (bus == 2) { - // Cruise state - if (addr == 0x100) { - const int feature_status = GET_BYTE(to_push, 2) >> 5U; - pcm_cruise_check(feature_status == 1); - } - } -} - -static bool rivian_tx_hook(const CANPacket_t *to_send) { - const TorqueSteeringLimits RIVIAN_STEERING_LIMITS = { - .max_steer = 250, - .max_rate_up = 3, - .max_rate_down = 5, - .max_rt_delta = 125, - .max_rt_interval = 250000, - .driver_torque_multiplier = 2, - .driver_torque_allowance = 100, - .type = TorqueDriverLimited, - }; - - const LongitudinalLimits RIVIAN_LONG_LIMITS = { - .max_accel = 200, - .min_accel = -350, - .inactive_accel = 0, - }; - - bool tx = true; - int bus = GET_BUS(to_send); - - if (bus == 0) { - int addr = GET_ADDR(to_send); - - // Steering control - if (addr == 0x120) { - int desired_torque = ((GET_BYTE(to_send, 2) << 3U) | (GET_BYTE(to_send, 3) >> 5U)) - 1024U; - bool steer_req = GET_BIT(to_send, 28U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, RIVIAN_STEERING_LIMITS)) { - tx = false; - } - } - - // Longitudinal control - if (addr == 0x160) { - int raw_accel = ((GET_BYTE(to_send, 2) << 3) | (GET_BYTE(to_send, 3) >> 5)) - 1024U; - if (longitudinal_accel_checks(raw_accel, RIVIAN_LONG_LIMITS)) { - tx = false; - } - } - } - - return tx; -} - -static bool rivian_fwd_hook(int bus, int addr) { - bool block_msg = false; - - if (bus == 0) { - // SCCM_WheelTouch: for hiding hold wheel alert - if (addr == 0x321) { - block_msg = true; - } - - // VDM_AdasSts: for canceling stock ACC - // cppcheck-suppress knownConditionTrueFalse - if ((addr == 0x162) && !rivian_longitudinal) { - block_msg = true; - } - } - - if (bus == 2) { - // ACM_lkaHbaCmd: lateral control message - if (addr == 0x120) { - block_msg = true; - } - - // ACM_longitudinalRequest: longitudinal control message - // cppcheck-suppress knownConditionTrueFalse - if (rivian_longitudinal && (addr == 0x160)) { - block_msg = true; - } - } - - return block_msg; -} - -static safety_config rivian_init(uint16_t param) { - // 0x120 = ACM_lkaHbaCmd, 0x321 = SCCM_WheelTouch, 0x162 = VDM_AdasSts - static const CanMsg RIVIAN_TX_MSGS[] = {{0x120, 0, 8, true}, {0x321, 2, 7, false}, {0x162, 2, 8, false}}; - // 0x160 = ACM_longitudinalRequest - static const CanMsg RIVIAN_LONG_TX_MSGS[] = {{0x120, 0, 8, true}, {0x321, 2, 7, false}, {0x160, 0, 5, true}}; - - static RxCheck rivian_rx_checks[] = { - {.msg = {{0x208, 0, 8, .frequency = 50U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // ESP_Status (speed) - {.msg = {{0x380, 0, 5, .frequency = 100U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // EPAS_SystemStatus (driver torque) - {.msg = {{0x150, 0, 7, .frequency = 50U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // VDM_PropStatus (gas pedal) - {.msg = {{0x38f, 0, 6, .frequency = 50U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // iBESP2 (brakes) - {.msg = {{0x100, 2, 8, .frequency = 100U, .ignore_checksum = true, .ignore_counter = true}, { 0 }, { 0 }}}, // ACM_Status (cruise state) - }; - - UNUSED(param); - #ifdef ALLOW_DEBUG - const int FLAG_RIVIAN_LONG_CONTROL = 1; - rivian_longitudinal = GET_FLAG(param, FLAG_RIVIAN_LONG_CONTROL); - #endif - - // FIXME: cppcheck thinks that rivian_longitudinal is always false. This is not true - // if ALLOW_DEBUG is defined but cppcheck is run without ALLOW_DEBUG - // cppcheck-suppress knownConditionTrueFalse - return rivian_longitudinal ? BUILD_SAFETY_CFG(rivian_rx_checks, RIVIAN_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(rivian_rx_checks, RIVIAN_TX_MSGS); -} - -const safety_hooks rivian_hooks = { - .init = rivian_init, - .rx = rivian_rx_hook, - .tx = rivian_tx_hook, - .fwd = rivian_fwd_hook, -}; diff --git a/opendbc_repo/opendbc/safety/safety/safety_tesla.h b/opendbc_repo/opendbc/safety/safety/safety_tesla.h deleted file mode 100644 index 26b7098adb..0000000000 --- a/opendbc_repo/opendbc/safety/safety/safety_tesla.h +++ /dev/null @@ -1,209 +0,0 @@ -#pragma once - -#include "safety_declarations.h" - -static bool tesla_longitudinal = false; -static 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) { - // Steering angle: (0.1 * val) - 819.2 in deg. - if (addr == 0x370) { - // 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); - } - - // Vehicle speed - if (addr == 0x257) { - // Vehicle speed: ((val * 0.08) - 40) / MS_TO_KPH - float speed = ((((GET_BYTE(to_push, 2) << 4) | (GET_BYTE(to_push, 1) >> 4)) * 0.08) - 40) / 3.6; - UPDATE_VEHICLE_SPEED(speed); - } - - // Gas pressed - if (addr == 0x118) { - gas_pressed = (GET_BYTE(to_push, 4) != 0U); - } - - // Brake pressed - if (addr == 0x39d) { - brake_pressed = (GET_BYTE(to_push, 2) & 0x03U) == 2U; - } - - // Cruise state - if (addr == 0x286) { - int cruise_state = (GET_BYTE(to_push, 1) >> 4) & 0x07U; - 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 - - vehicle_moving = cruise_state != 3; // STANDSTILL - pcm_cruise_check(cruise_engaged); - } - } - - if (bus == 2) { - if (tesla_longitudinal && (addr == 0x2b9)) { - // "AEB_ACTIVE" - tesla_stock_aeb = (GET_BYTE(to_push, 2) & 0x03U) == 1U; - } - } -} - - -static bool tesla_tx_hook(const CANPacket_t *to_send) { - const AngleSteeringLimits TESLA_STEERING_LIMITS = { - .max_angle = 3600, // 360 deg, EPAS faults above this - .angle_deg_to_can = 10, - .angle_rate_up_lookup = { - {0., 5., 25.}, - {2.5, 1.5, 0.2} - }, - .angle_rate_down_lookup = { - {0., 5., 25.}, - {5., 2.0, 0.3} - }, - }; - - const LongitudinalLimits TESLA_LONG_LIMITS = { - .max_accel = 425, // 2 m/s^2 - .min_accel = 288, // -3.48 m/s^2 - .inactive_accel = 375, // 0. m/s^2 - }; - - bool tx = true; - int addr = GET_ADDR(to_send); - bool violation = false; - - // Steering control: (0.1 * val) - 1638.35 in deg. - if (addr == 0x488) { - // 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; - } - } - - // DAS_control: longitudinal control message - if (addr == 0x2b9) { - // No AEB events may be sent by openpilot - int aeb_event = GET_BYTE(to_send, 2) & 0x03U; - if (aeb_event != 0) { - violation = true; - } - - 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); - int acc_state = GET_BYTE(to_send, 1) >> 4; - - if (tesla_longitudinal) { - // Don't send messages when the stock AEB system is active - if (tesla_stock_aeb) { - violation = true; - } - - // Prevent both acceleration from being negative, as this could cause the car to reverse after coming to standstill - if ((raw_accel_max < TESLA_LONG_LIMITS.inactive_accel) && (raw_accel_min < TESLA_LONG_LIMITS.inactive_accel)) { - violation = true; - } - - // Don't allow any acceleration limits above the safety limits - violation |= longitudinal_accel_checks(raw_accel_max, TESLA_LONG_LIMITS); - violation |= longitudinal_accel_checks(raw_accel_min, TESLA_LONG_LIMITS); - } else { - // does allowing cancel here disrupt stock AEB? TODO: find out and add safety or remove comment - // Can only send cancel longitudinal messages when not controlling longitudinal - if (acc_state != 13) { // ACC_CANCEL_GENERIC_SILENT - violation = true; - } - - // No actuation is allowed when not controlling longitudinal - if ((raw_accel_max != TESLA_LONG_LIMITS.inactive_accel) || (raw_accel_min != TESLA_LONG_LIMITS.inactive_accel)) { - violation = true; - } - } - } - - if (violation) { - tx = false; - } - - return tx; -} - -static bool tesla_fwd_hook(int bus_num, int addr) { - bool block_msg = false; - - if (bus_num == 2) { - // DAS_steeringControl, APS_eacMonitor - if ((addr == 0x488) || (addr == 0x27d)) { - block_msg = true; - } - - // DAS_control - if (tesla_longitudinal && (addr == 0x2b9) && !tesla_stock_aeb) { - block_msg = true; - } - } - - return block_msg; -} - -static safety_config tesla_init(uint16_t param) { - - static const CanMsg TESLA_M3_Y_TX_MSGS[] = { - {0x488, 0, 4, true}, // DAS_steeringControl - {0x2b9, 0, 8, false}, // DAS_control (for cancel) - {0x27D, 0, 3, true}, // APS_eacMonitor - }; - - static const CanMsg TESLA_M3_Y_LONG_TX_MSGS[] = { - {0x488, 0, 4, true}, // DAS_steeringControl - {0x2b9, 0, 8, true}, // DAS_control - {0x27D, 0, 3, true}, // APS_eacMonitor - }; - - UNUSED(param); -#ifdef ALLOW_DEBUG - const int TESLA_FLAG_LONGITUDINAL_CONTROL = 1; - tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); -#endif - - tesla_stock_aeb = false; - - static RxCheck tesla_model3_y_rx_checks[] = { - {.msg = {{0x2b9, 2, 8, .ignore_checksum = true, .ignore_counter = true,.frequency = 25U}, { 0 }, { 0 }}}, // DAS_control - {.msg = {{0x257, 0, 8, .ignore_checksum = true, .ignore_counter = true,.frequency = 50U}, { 0 }, { 0 }}}, // DI_speed (speed in kph) - {.msg = {{0x370, 0, 8, .ignore_checksum = true, .ignore_counter = true,.frequency = 100U}, { 0 }, { 0 }}}, // EPAS3S_internalSAS (steering angle) - {.msg = {{0x118, 0, 8, .ignore_checksum = true, .ignore_counter = true,.frequency = 100U}, { 0 }, { 0 }}}, // DI_systemStatus (gas pedal) - {.msg = {{0x39d, 0, 5, .ignore_checksum = true, .ignore_counter = true,.frequency = 25U}, { 0 }, { 0 }}}, // IBST_status (brakes) - {.msg = {{0x286, 0, 8, .ignore_checksum = true, .ignore_counter = true,.frequency = 10U}, { 0 }, { 0 }}}, // DI_state (acc state) - {.msg = {{0x311, 0, 7, .ignore_checksum = true, .ignore_counter = true,.frequency = 10U}, { 0 }, { 0 }}}, // UI_warning (blinkers, buckle switch & doors) - }; - - safety_config ret; - if (tesla_longitudinal) { - ret = BUILD_SAFETY_CFG(tesla_model3_y_rx_checks, TESLA_M3_Y_LONG_TX_MSGS); - } else { - ret = BUILD_SAFETY_CFG(tesla_model3_y_rx_checks, TESLA_M3_Y_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/opendbc_repo/opendbc/safety/safety_declarations.h b/opendbc_repo/opendbc/safety/safety_declarations.h index c9fe9131ad..d27ee3261d 100644 --- a/opendbc_repo/opendbc/safety/safety_declarations.h +++ b/opendbc_repo/opendbc/safety/safety_declarations.h @@ -3,6 +3,36 @@ #include #include +// 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 +#define SAFETY_RIVIAN 33U +#define SAFETY_VOLKSWAGEN_MEB 34U + #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)) // cppcheck-suppress misra-c2012-1.2; allow __typeof__ @@ -22,7 +52,7 @@ (config).tx_msgs = (tx); \ (config).tx_msgs_len = sizeof((tx)) / sizeof((tx)[0]); \ (config).disable_forwarding = false; \ - } while(0); + } while (0); #define UPDATE_VEHICLE_SPEED(val_ms) (update_sample(&vehicle_speed, ROUND((val_ms) * VEHICLE_SPEED_FACTOR))) @@ -33,6 +63,7 @@ extern const int MAX_WRONG_COUNTERS; #define MAX_SAMPLE_VALS 6 // used to represent floating point vehicle speed in a sample_t #define VEHICLE_SPEED_FACTOR 1000.0 +#define MAX_TORQUE_RT_INTERVAL 250000U // sample struct that keeps 6 samples in memory @@ -52,7 +83,8 @@ typedef struct { int addr; int bus; int len; - bool check_relay; + bool check_relay; // if true, trigger relay malfunction if existence on destination bus and block forwarding to destination bus + bool disable_static_blocking; // if true, static blocking is disabled so safety mode can dynamically handle it (e.g. selective AEB pass-through) } CanMsg; typedef enum { @@ -62,11 +94,13 @@ typedef enum { typedef struct { // torque cmd limits - const int max_steer; + const int max_torque; // this upper limit is always enforced + const bool dynamic_max_torque; // use max_torque_lookup to apply torque limit based on speed + const struct lookup_t max_torque_lookup; + const int max_rate_up; const int max_rate_down; - const int max_rt_delta; - const uint32_t max_rt_interval; + const int max_rt_delta; // max change in torque per 250ms interval (MAX_TORQUE_RT_INTERVAL) const SteeringControlType type; @@ -181,16 +215,15 @@ typedef struct { 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); +bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL); bool get_longitudinal_allowed(void); int ROUND(float val); void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]); #ifdef CANFD void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]); #endif -static void generic_rx_checks(bool stock_ecu_detected); bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueSteeringLimits limits); bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const AngleSteeringLimits limits); bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits); @@ -211,6 +244,8 @@ extern bool brake_pressed; extern bool brake_pressed_prev; extern bool regen_braking; extern bool regen_braking_prev; +extern bool steering_disengage; +extern bool steering_disengage_prev; extern bool cruise_engaged_prev; extern struct sample_t vehicle_speed; extern bool vehicle_moving; @@ -237,11 +272,11 @@ extern uint32_t ts_angle_last; extern int desired_angle_last; extern struct sample_t angle_meas; // last 6 steer angles/curvatures -// This can be set with a USB command +// Alt experiences 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 +//#define ALT_EXP_DISABLE_DISENGAGE_ON_GAS 1 // not used anymore, but reserved // 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 diff --git a/opendbc_repo/opendbc/safety/tests/common.py b/opendbc_repo/opendbc/safety/tests/common.py index f087fd528c..23943d6a11 100644 --- a/opendbc_repo/opendbc/safety/tests/common.py +++ b/opendbc_repo/opendbc/safety/tests/common.py @@ -1,5 +1,6 @@ import os import abc +import math import unittest import importlib import numpy as np @@ -11,13 +12,24 @@ from opendbc.safety.tests.libsafety import libsafety_py MAX_WRONG_COUNTERS = 5 MAX_SAMPLE_VALS = 6 +VEHICLE_SPEED_FACTOR = 1000 MessageFunction = Callable[[float], libsafety_py.CANPacket] + def sign_of(a): return 1 if a > 0 else -1 +def away_round(x): + # non-banker's/away from zero rounding, C++ CANParser uses this style + return math.floor(x + 0.5) if x >= 0 else math.ceil(x - 0.5) + + +def round_speed(v): + return round(v * VEHICLE_SPEED_FACTOR) / VEHICLE_SPEED_FACTOR + + def make_msg(bus, addr, length=8, dat=None): if dat is None: dat = b'\x00' * length @@ -166,6 +178,7 @@ class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC): MIN_GAS: int = 0 MAX_GAS: int | None = None INACTIVE_GAS = 0 + MIN_POSSIBLE_GAS: int = 0. MAX_POSSIBLE_GAS: int | None = None def test_gas_brake_limits_correct(self): @@ -187,16 +200,17 @@ class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC): 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) + self._generic_limit_safety_check(self._send_gas_msg, self.MIN_GAS, self.MAX_GAS, self.MIN_POSSIBLE_GAS, 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_TORQUE_LOOKUP: tuple[list[float], list[int]] = ([0], [0]) + DYNAMIC_MAX_TORQUE = False MAX_RT_DELTA = 0 - RT_INTERVAL = 0 + RT_INTERVAL = 250000 NO_STEER_REQ_BIT = False @@ -206,23 +220,53 @@ class TorqueSteeringSafetyTestBase(PandaSafetyTestBase, abc.ABC): cls.safety = None raise unittest.SkipTest + @property + def MAX_TORQUE(self): + return max(self.MAX_TORQUE_LOOKUP[1]) + + @property + def _torque_speed_range(self): + if not self.DYNAMIC_MAX_TORQUE: + return [0] + else: + # test with more precision inside breakpoint range + min_speed = min(self.MAX_TORQUE_LOOKUP[0]) + max_speed = max(self.MAX_TORQUE_LOOKUP[0]) + return np.concatenate([np.arange(0, min_speed, 5), np.arange(min_speed, max_speed, 0.5), np.arange(max_speed, 40, 5)]) + + def _get_max_torque(self, speed): + # matches safety fudge + torque = int(np.interp(speed - 1, self.MAX_TORQUE_LOOKUP[0], self.MAX_TORQUE_LOOKUP[1]) + 1) + return min(torque, self.MAX_TORQUE) + @abc.abstractmethod def _torque_cmd_msg(self, torque, steer_req=1): pass + @abc.abstractmethod + def _speed_msg(self, speed): + pass + + def _reset_speed_measurement(self, speed): + for _ in range(MAX_SAMPLE_VALS): + self._rx(self._speed_msg(speed)) + 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))) + for speed in self._torque_speed_range: + self._reset_speed_measurement(speed) + max_torque = self._get_max_torque(speed) + for enabled in [0, 1]: + for t in range(int(-max_torque * 1.5), int(max_torque * 1.5)): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > 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) @@ -266,7 +310,12 @@ class SteerRequestCutSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): # Safety around steering request bit mismatch tolerance MIN_VALID_STEERING_FRAMES: int MAX_INVALID_STEERING_FRAMES: int - MIN_VALID_STEERING_RT_INTERVAL: int + STEER_STEP: int = 1 + + @property + def MIN_VALID_STEERING_RT_INTERVAL(self): + # a ~10% buffer + return int((self.MIN_VALID_STEERING_FRAMES + 1) * self.STEER_STEP * 10000 * 0.9) def test_steer_req_bit_frames(self): """ @@ -389,40 +438,44 @@ class DriverTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): # 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))) + for speed in self._torque_speed_range: + self._reset_speed_measurement(speed) + max_torque = self._get_max_torque(speed) + + # 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(max_torque * sign) + should_tx = abs(driver_torque) <= self.DRIVER_TORQUE_ALLOWANCE + self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(max_torque * sign))) + + # arbitrary high driver torque to ensure max steer torque is allowed + max_driver_torque = int(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 = (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(max_torque * sign) + self._reset_torque_driver_measurement(-max_driver_torque * sign) + self.assertTrue(self._tx(self._torque_cmd_msg((max_torque - self.MAX_RATE_DOWN) * sign))) + self._set_prev_torque(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(max_torque * sign) + self._reset_torque_driver_measurement(-max_driver_torque * sign) + self.assertFalse(self._tx(self._torque_cmd_msg((max_torque - self.MAX_RATE_DOWN + 1) * sign))) def test_realtime_limits(self): self.safety.set_controls_allowed(True) @@ -479,34 +532,41 @@ class MotorTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): 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) + for speed in self._torque_speed_range: + self._reset_speed_measurement(speed) + max_torque = self._get_max_torque(speed) + for controls_allowed in [True, False]: + for torque in np.arange(-max_torque - 1000, 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 + if controls_allowed: + send = (-max_torque <= torque <= max_torque) + else: + send = torque == 0 - self.assertEqual(send, self._tx(self._torque_cmd_msg(torque))) + 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 + for speed in self._torque_speed_range: + self._reset_speed_measurement(speed) + max_torque = self._get_max_torque(speed) - 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))) + torque_meas = 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.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE - self.MAX_RATE_DOWN + 1))) + self.safety.set_rt_torque_last(max_torque) + self.safety.set_torque_meas(torque_meas, torque_meas) + self.safety.set_desired_torque_last(max_torque) + self.assertTrue(self._tx(self._torque_cmd_msg(max_torque - self.MAX_RATE_DOWN))) + + self.safety.set_rt_torque_last(max_torque) + self.safety.set_torque_meas(torque_meas, torque_meas) + self.safety.set_desired_torque_last(max_torque) + self.assertFalse(self._tx(self._torque_cmd_msg(max_torque - self.MAX_RATE_DOWN + 1))) def test_exceed_torque_sensor(self): self.safety.set_controls_allowed(True) @@ -577,7 +637,23 @@ class MotorTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): self.assertEqual(self.safety.get_torque_meas_max(), 0) -class AngleSteeringSafetyTest(PandaSafetyTestBase): +class VehicleSpeedSafetyTest(PandaSafetyTestBase): + @classmethod + def setUpClass(cls): + if cls.__name__ == "VehicleSpeedSafetyTest": + cls.safety = None + raise unittest.SkipTest + + @abc.abstractmethod + def _speed_msg(self, speed): + pass + + def test_vehicle_speed_measurements(self): + # TODO: lower tolerance on these tests + self._common_measurement_test(self._speed_msg, 0, 80, 1, self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max) + + +class AngleSteeringSafetyTest(VehicleSpeedSafetyTest): STEER_ANGLE_MAX: float = 300 DEG_TO_CAN: float @@ -591,10 +667,6 @@ class AngleSteeringSafetyTest(PandaSafetyTestBase): 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 @@ -615,10 +687,6 @@ class AngleSteeringSafetyTest(PandaSafetyTestBase): for _ in range(MAX_SAMPLE_VALS): self._rx(self._speed_msg(speed)) - def test_vehicle_speed_measurements(self): - # TODO: lower tolerance on these tests - self._common_measurement_test(self._speed_msg, 0, 80, 1, self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max) - def test_steering_angle_measurements(self): self._common_measurement_test(self._angle_meas_msg, -self.STEER_ANGLE_MAX, self.STEER_ANGLE_MAX, self.DEG_TO_CAN, self.safety.get_angle_meas_min, self.safety.get_angle_meas_max) @@ -888,16 +956,9 @@ class PandaCarSafetyTest(PandaSafetyTest): 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): + def test_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()) diff --git a/opendbc_repo/opendbc/safety/tests/libsafety/SConscript b/opendbc_repo/opendbc/safety/tests/libsafety/SConscript index 97464ecbbe..b936eac1ec 100644 --- a/opendbc_repo/opendbc/safety/tests/libsafety/SConscript +++ b/opendbc_repo/opendbc/safety/tests/libsafety/SConscript @@ -2,9 +2,13 @@ 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 +mac_ver = platform.mac_ver() + +# 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 +# clang works on macOS 15 and greater but has issues on earlier macOS versions. +# see: https://github.com/commaai/openpilot/issues/35093 +if system == 'Darwin' and mac_ver[0] and mac_ver[0] < '15': CC += '-13' env = Environment( @@ -18,8 +22,9 @@ env = Environment( '-std=gnu11', '-Wfatal-errors', '-Wno-pointer-to-int-cast', + '-DCANFD', ], - CPPPATH=[".", "../../board/", "../../"], + CPPPATH=["#", "../../board/"], ) if system == "Darwin": env.PrependENVPath('PATH', '/opt/homebrew/bin') diff --git a/opendbc_repo/opendbc/safety/tests/libsafety/safety.c b/opendbc_repo/opendbc/safety/tests/libsafety/safety.c index bdb63596b1..48190d8758 100644 --- a/opendbc_repo/opendbc/safety/tests/libsafety/safety.c +++ b/opendbc_repo/opendbc/safety/tests/libsafety/safety.c @@ -1,13 +1,13 @@ #include -#include "fake_stm.h" -#include "can.h" +#include "opendbc/safety/board/fake_stm.h" +#include "opendbc/safety/board/can.h" //int safety_tx_hook(CANPacket_t *to_send) { return 1; } -#include "faults.h" -#include "safety.h" -#include "drivers/can_common.h" +#include "opendbc/safety/board/faults.h" +#include "opendbc/safety/safety.h" +#include "opendbc/safety/board/drivers/can_common.h" // libsafety stuff -#include "safety_helpers.h" +#include "opendbc/safety/tests/libsafety/safety_helpers.h" diff --git a/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.h b/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.h index 84e7eb736b..1176e8ca76 100644 --- a/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.h +++ b/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.h @@ -1,3 +1,5 @@ +#include + void safety_tick_current_safety_config() { safety_tick(¤t_safety_config); } @@ -59,6 +61,10 @@ bool get_regen_braking_prev(void){ return regen_braking_prev; } +bool get_steering_disengage_prev(void){ + return steering_disengage_prev; +} + bool get_cruise_engaged_prev(void){ return cruise_engaged_prev; } @@ -180,4 +186,7 @@ void init_tests(void){ ts_steer_req_mismatch_last = 0; valid_steer_req_count = 0; invalid_steer_req_count = 0; + + // assumes autopark on safety mode init to avoid a fault. get rid of that for testing + tesla_autopark = false; } diff --git a/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.py b/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.py index cd116fb59a..984693e7a4 100644 --- a/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.py +++ b/opendbc_repo/opendbc/safety/tests/libsafety/safety_helpers.py @@ -14,6 +14,7 @@ def setup_safety_helpers(ffi): void set_gas_pressed_prev(bool); bool get_brake_pressed_prev(void); bool get_regen_braking_prev(void); + bool get_steering_disengage_prev(void); bool get_acc_main_on(void); float get_vehicle_speed_min(void); float get_vehicle_speed_max(void); @@ -63,6 +64,7 @@ class PandaSafety(Protocol): def set_gas_pressed_prev(self, c: bool) -> None: ... def get_brake_pressed_prev(self) -> bool: ... def get_regen_braking_prev(self) -> bool: ... + def get_steering_disengage_prev(self) -> bool: ... def get_acc_main_on(self) -> bool: ... def get_vehicle_speed_min(self) -> int: ... def get_vehicle_speed_max(self) -> int: ... diff --git a/opendbc_repo/opendbc/safety/tests/misra/checkers.txt b/opendbc_repo/opendbc/safety/tests/misra/checkers.txt index 4e6f517e8c..b3f1d5866d 100644 --- a/opendbc_repo/opendbc/safety/tests/misra/checkers.txt +++ b/opendbc_repo/opendbc/safety/tests/misra/checkers.txt @@ -5,7 +5,7 @@ Cppcheck checkers list from test_misra.sh: TEST variant options: ---enable=all --disable=unusedFunction -DPANDA --addon=misra -DSTM32F4 -DSTM32F413xx /opendbc/safety/main.c +--enable=all --enable=unusedFunction --addon=misra -DCANFD /opendbc/safety/main.c Critical errors @@ -31,7 +31,6 @@ No CheckBool::checkComparisonOfFuncReturningBool require:style,c++ Yes CheckBool::checkIncrementBoolean Yes CheckBool::pointerArithBool Yes CheckBool::returnValueOfFunctionReturningBool -No CheckBoost::checkBoostForeachModification Yes CheckBufferOverrun::analyseWholeProgram Yes CheckBufferOverrun::argumentSize Yes CheckBufferOverrun::arrayIndex @@ -192,464 +191,10 @@ Yes CheckType::checkIntegerOverflow Yes CheckType::checkLongCast Yes CheckType::checkSignConversion Yes CheckType::checkTooBigBitwiseShift +Yes CheckUninitVar::analyseWholeProgram Yes CheckUninitVar::check Yes CheckUninitVar::valueFlowUninit -No CheckUnusedFunctions::check require:unusedFunction -Yes CheckUnusedVar::checkFunctionVariableUsage -Yes CheckUnusedVar::checkStructMemberUsage -Yes CheckVaarg::va_list_usage -Yes CheckVaarg::va_start_argument - - -Premium checkers ----------------- -Not available, Cppcheck Premium is not used - - -Autosar -------- -Not available, Cppcheck Premium is not used - - -Cert C ------- -Not available, Cppcheck Premium is not used - - -Cert C++ --------- -Not available, Cppcheck Premium is not used - - -Misra C 2012 ------------- -No Misra C 2012: Dir 1.1 -No Misra C 2012: Dir 2.1 -No Misra C 2012: Dir 3.1 -No Misra C 2012: Dir 4.1 -No Misra C 2012: Dir 4.2 -No Misra C 2012: Dir 4.3 -No Misra C 2012: Dir 4.4 -No Misra C 2012: Dir 4.5 -No Misra C 2012: Dir 4.6 amendment:3 -No Misra C 2012: Dir 4.7 -No Misra C 2012: Dir 4.8 -No Misra C 2012: Dir 4.9 amendment:3 -No Misra C 2012: Dir 4.10 -No Misra C 2012: Dir 4.11 amendment:3 -No Misra C 2012: Dir 4.12 -No Misra C 2012: Dir 4.13 -No Misra C 2012: Dir 4.14 amendment:2 -No Misra C 2012: Dir 4.15 amendment:3 -No Misra C 2012: Dir 5.1 amendment:4 -No Misra C 2012: Dir 5.2 amendment:4 -No Misra C 2012: Dir 5.3 amendment:4 -Yes Misra C 2012: 1.1 -Yes Misra C 2012: 1.2 -Yes Misra C 2012: 1.3 -Yes Misra C 2012: 1.4 amendment:2 -No Misra C 2012: 1.5 amendment:3 require:premium -Yes Misra C 2012: 2.1 -Yes Misra C 2012: 2.2 -Yes Misra C 2012: 2.3 -Yes Misra C 2012: 2.4 -Yes Misra C 2012: 2.5 -Yes Misra C 2012: 2.6 -Yes Misra C 2012: 2.7 -Yes Misra C 2012: 2.8 -Yes Misra C 2012: 3.1 -Yes Misra C 2012: 3.2 -Yes Misra C 2012: 4.1 -Yes Misra C 2012: 4.2 -Yes Misra C 2012: 5.1 -Yes Misra C 2012: 5.2 -Yes Misra C 2012: 5.3 -Yes Misra C 2012: 5.4 -Yes Misra C 2012: 5.5 -Yes Misra C 2012: 5.6 -Yes Misra C 2012: 5.7 -Yes Misra C 2012: 5.8 -Yes Misra C 2012: 5.9 -Yes Misra C 2012: 6.1 -Yes Misra C 2012: 6.2 -No Misra C 2012: 6.3 -Yes Misra C 2012: 7.1 -Yes Misra C 2012: 7.2 -Yes Misra C 2012: 7.3 -Yes Misra C 2012: 7.4 -No Misra C 2012: 7.5 -No Misra C 2012: 7.6 -Yes Misra C 2012: 8.1 -Yes Misra C 2012: 8.2 -No Misra C 2012: 8.3 -Yes Misra C 2012: 8.4 -Yes Misra C 2012: 8.5 -Yes Misra C 2012: 8.6 -Yes Misra C 2012: 8.7 -Yes Misra C 2012: 8.8 -Yes Misra C 2012: 8.9 -Yes Misra C 2012: 8.10 -Yes Misra C 2012: 8.11 -Yes Misra C 2012: 8.12 -Yes Misra C 2012: 8.13 -Yes Misra C 2012: 8.14 -No Misra C 2012: 8.15 -No Misra C 2012: 8.16 -No Misra C 2012: 8.17 -Yes Misra C 2012: 9.1 -Yes Misra C 2012: 9.2 -Yes Misra C 2012: 9.3 -Yes Misra C 2012: 9.4 -Yes Misra C 2012: 9.5 -No Misra C 2012: 9.6 -No Misra C 2012: 9.7 -Yes Misra C 2012: 10.1 -Yes Misra C 2012: 10.2 -Yes Misra C 2012: 10.3 -Yes Misra C 2012: 10.4 -Yes Misra C 2012: 10.5 -Yes Misra C 2012: 10.6 -Yes Misra C 2012: 10.7 -Yes Misra C 2012: 10.8 -Yes Misra C 2012: 11.1 -Yes Misra C 2012: 11.2 -Yes Misra C 2012: 11.3 -Yes Misra C 2012: 11.4 -Yes Misra C 2012: 11.5 -Yes Misra C 2012: 11.6 -Yes Misra C 2012: 11.7 -Yes Misra C 2012: 11.8 -Yes Misra C 2012: 11.9 -No Misra C 2012: 11.10 -Yes Misra C 2012: 12.1 -Yes Misra C 2012: 12.2 -Yes Misra C 2012: 12.3 -Yes Misra C 2012: 12.4 -Yes Misra C 2012: 12.5 amendment:1 -No Misra C 2012: 12.6 amendment:4 require:premium -Yes Misra C 2012: 13.1 -No Misra C 2012: 13.2 -Yes Misra C 2012: 13.3 -Yes Misra C 2012: 13.4 -Yes Misra C 2012: 13.5 -Yes Misra C 2012: 13.6 -Yes Misra C 2012: 14.1 -Yes Misra C 2012: 14.2 -Yes Misra C 2012: 14.3 -Yes Misra C 2012: 14.4 -Yes Misra C 2012: 15.1 -Yes Misra C 2012: 15.2 -Yes Misra C 2012: 15.3 -Yes Misra C 2012: 15.4 -Yes Misra C 2012: 15.5 -Yes Misra C 2012: 15.6 -Yes Misra C 2012: 15.7 -Yes Misra C 2012: 16.1 -Yes Misra C 2012: 16.2 -Yes Misra C 2012: 16.3 -Yes Misra C 2012: 16.4 -Yes Misra C 2012: 16.5 -Yes Misra C 2012: 16.6 -Yes Misra C 2012: 16.7 -Yes Misra C 2012: 17.1 -Yes Misra C 2012: 17.2 -Yes Misra C 2012: 17.3 -No Misra C 2012: 17.4 -Yes Misra C 2012: 17.5 -Yes Misra C 2012: 17.6 -Yes Misra C 2012: 17.7 -Yes Misra C 2012: 17.8 -No Misra C 2012: 17.9 -No Misra C 2012: 17.10 -No Misra C 2012: 17.11 -No Misra C 2012: 17.12 -No Misra C 2012: 17.13 -Yes Misra C 2012: 18.1 -Yes Misra C 2012: 18.2 -Yes Misra C 2012: 18.3 -Yes Misra C 2012: 18.4 -Yes Misra C 2012: 18.5 -Yes Misra C 2012: 18.6 -Yes Misra C 2012: 18.7 -Yes Misra C 2012: 18.8 -No Misra C 2012: 18.9 -No Misra C 2012: 18.10 -Yes Misra C 2012: 19.1 -Yes Misra C 2012: 19.2 -Yes Misra C 2012: 20.1 -Yes Misra C 2012: 20.2 -Yes Misra C 2012: 20.3 -Yes Misra C 2012: 20.4 -Yes Misra C 2012: 20.5 -Yes Misra C 2012: 20.6 -Yes Misra C 2012: 20.7 -Yes Misra C 2012: 20.8 -Yes Misra C 2012: 20.9 -Yes Misra C 2012: 20.10 -Yes Misra C 2012: 20.11 -Yes Misra C 2012: 20.12 -Yes Misra C 2012: 20.13 -Yes Misra C 2012: 20.14 -Yes Misra C 2012: 21.1 -Yes Misra C 2012: 21.2 -Yes Misra C 2012: 21.3 -Yes Misra C 2012: 21.4 -Yes Misra C 2012: 21.5 -Yes Misra C 2012: 21.6 -Yes Misra C 2012: 21.7 -Yes Misra C 2012: 21.8 -Yes Misra C 2012: 21.9 -Yes Misra C 2012: 21.10 -Yes Misra C 2012: 21.11 -Yes Misra C 2012: 21.12 -Yes Misra C 2012: 21.13 amendment:1 -Yes Misra C 2012: 21.14 amendment:1 -Yes Misra C 2012: 21.15 amendment:1 -Yes Misra C 2012: 21.16 amendment:1 -Yes Misra C 2012: 21.17 amendment:1 -Yes Misra C 2012: 21.18 amendment:1 -Yes Misra C 2012: 21.19 amendment:1 -Yes Misra C 2012: 21.20 amendment:1 -Yes Misra C 2012: 21.21 amendment:3 -No Misra C 2012: 21.22 amendment:3 require:premium -No Misra C 2012: 21.23 amendment:3 require:premium -No Misra C 2012: 21.24 amendment:3 require:premium -No Misra C 2012: 21.25 amendment:4 require:premium -No Misra C 2012: 21.26 amendment:4 require:premium -Yes Misra C 2012: 22.1 -Yes Misra C 2012: 22.2 -Yes Misra C 2012: 22.3 -Yes Misra C 2012: 22.4 -Yes Misra C 2012: 22.5 -Yes Misra C 2012: 22.6 -Yes Misra C 2012: 22.7 amendment:1 -Yes Misra C 2012: 22.8 amendment:1 -Yes Misra C 2012: 22.9 amendment:1 -Yes Misra C 2012: 22.10 amendment:1 -No Misra C 2012: 22.11 amendment:4 require:premium -No Misra C 2012: 22.12 amendment:4 require:premium -No Misra C 2012: 22.13 amendment:4 require:premium -No Misra C 2012: 22.14 amendment:4 require:premium -No Misra C 2012: 22.15 amendment:4 require:premium -No Misra C 2012: 22.16 amendment:4 require:premium -No Misra C 2012: 22.17 amendment:4 require:premium -No Misra C 2012: 22.18 amendment:4 require:premium -No Misra C 2012: 22.19 amendment:4 require:premium -No Misra C 2012: 22.20 amendment:4 require:premium -No Misra C 2012: 23.1 amendment:3 require:premium -No Misra C 2012: 23.2 amendment:3 require:premium -No Misra C 2012: 23.3 amendment:3 require:premium -No Misra C 2012: 23.4 amendment:3 require:premium -No Misra C 2012: 23.5 amendment:3 require:premium -No Misra C 2012: 23.6 amendment:3 require:premium -No Misra C 2012: 23.7 amendment:3 require:premium -No Misra C 2012: 23.8 amendment:3 require:premium - - -Misra C++ 2008 --------------- -Not available, Cppcheck Premium is not used - - -Misra C++ 2023 --------------- -Not available, Cppcheck Premium is not used - - - - - -TEST variant options: ---enable=all --disable=unusedFunction -DPANDA --addon=misra -DSTM32H7 -DSTM32H725xx /opendbc/safety/main.c - - -Critical errors ---------------- -No critical errors encountered. -Note: There might still have been non-critical bailouts which might lead to false negatives. - - -Open source checkers --------------------- -Yes Check64BitPortability::pointerassignment -Yes CheckAssert::assertWithSideEffects -Yes CheckAutoVariables::assignFunctionArg -Yes CheckAutoVariables::autoVariables -Yes CheckAutoVariables::checkVarLifetime -No CheckBool::checkAssignBoolToFloat require:style,c++ -Yes CheckBool::checkAssignBoolToPointer -No CheckBool::checkBitwiseOnBoolean require:style,inconclusive -Yes CheckBool::checkComparisonOfBoolExpressionWithInt -No CheckBool::checkComparisonOfBoolWithBool require:style,c++ -No CheckBool::checkComparisonOfBoolWithInt require:warning,c++ -No CheckBool::checkComparisonOfFuncReturningBool require:style,c++ -Yes CheckBool::checkIncrementBoolean -Yes CheckBool::pointerArithBool -Yes CheckBool::returnValueOfFunctionReturningBool -No CheckBoost::checkBoostForeachModification -Yes CheckBufferOverrun::analyseWholeProgram -Yes CheckBufferOverrun::argumentSize -Yes CheckBufferOverrun::arrayIndex -Yes CheckBufferOverrun::arrayIndexThenCheck -Yes CheckBufferOverrun::bufferOverflow -Yes CheckBufferOverrun::negativeArraySize -Yes CheckBufferOverrun::objectIndex -Yes CheckBufferOverrun::pointerArithmetic -No CheckBufferOverrun::stringNotZeroTerminated require:warning,inconclusive -Yes CheckClass::analyseWholeProgram -No CheckClass::checkConst require:style,inconclusive -No CheckClass::checkConstructors require:style,warning -No CheckClass::checkCopyConstructors require:warning -No CheckClass::checkDuplInheritedMembers require:warning -No CheckClass::checkExplicitConstructors require:style -No CheckClass::checkMemset -No CheckClass::checkMissingOverride require:style,c++03 -No CheckClass::checkReturnByReference require:performance -No CheckClass::checkSelfInitialization -No CheckClass::checkThisUseAfterFree require:warning -No CheckClass::checkUnsafeClassRefMember require:warning,safeChecks -No CheckClass::checkUselessOverride require:style -No CheckClass::checkVirtualFunctionCallInConstructor require:warning -No CheckClass::initializationListUsage require:performance -No CheckClass::initializerListOrder require:style,inconclusive -No CheckClass::operatorEqRetRefThis require:style -No CheckClass::operatorEqToSelf require:warning -No CheckClass::privateFunctions require:style -No CheckClass::thisSubtraction require:warning -No CheckClass::virtualDestructor -Yes CheckCondition::alwaysTrueFalse -Yes CheckCondition::assignIf -Yes CheckCondition::checkAssignmentInCondition -Yes CheckCondition::checkBadBitmaskCheck -Yes CheckCondition::checkCompareValueOutOfTypeRange -Yes CheckCondition::checkDuplicateConditionalAssign -Yes CheckCondition::checkIncorrectLogicOperator -Yes CheckCondition::checkInvalidTestForOverflow -Yes CheckCondition::checkModuloAlwaysTrueFalse -Yes CheckCondition::checkPointerAdditionResultNotNull -Yes CheckCondition::clarifyCondition -Yes CheckCondition::comparison -Yes CheckCondition::duplicateCondition -Yes CheckCondition::multiCondition -Yes CheckCondition::multiCondition2 -No CheckExceptionSafety::checkCatchExceptionByValue require:style -No CheckExceptionSafety::checkRethrowCopy require:style -No CheckExceptionSafety::deallocThrow require:warning -No CheckExceptionSafety::destructors require:warning -No CheckExceptionSafety::nothrowThrows -No CheckExceptionSafety::rethrowNoCurrentException -No CheckExceptionSafety::unhandledExceptionSpecification require:style,inconclusive -Yes CheckFunctions::checkIgnoredReturnValue -Yes CheckFunctions::checkMathFunctions -Yes CheckFunctions::checkMissingReturn -Yes CheckFunctions::checkProhibitedFunctions -Yes CheckFunctions::invalidFunctionUsage -Yes CheckFunctions::memsetInvalid2ndParam -Yes CheckFunctions::memsetZeroBytes -No CheckFunctions::returnLocalStdMove require:performance,c++11 -Yes CheckFunctions::useStandardLibrary -No CheckIO::checkCoutCerrMisusage require:c -Yes CheckIO::checkFileUsage -Yes CheckIO::checkWrongPrintfScanfArguments -Yes CheckIO::invalidScanf -Yes CheckLeakAutoVar::check -No CheckMemoryLeakInClass::check -Yes CheckMemoryLeakInFunction::checkReallocUsage -Yes CheckMemoryLeakNoVar::check -No CheckMemoryLeakNoVar::checkForUnsafeArgAlloc -Yes CheckMemoryLeakStructMember::check -Yes CheckNullPointer::analyseWholeProgram -Yes CheckNullPointer::arithmetic -Yes CheckNullPointer::nullConstantDereference -Yes CheckNullPointer::nullPointer -No CheckOther::checkAccessOfMovedVariable require:c++11,warning -Yes CheckOther::checkCastIntToCharAndBack -Yes CheckOther::checkCharVariable -Yes CheckOther::checkComparePointers -Yes CheckOther::checkComparisonFunctionIsAlwaysTrueOrFalse -Yes CheckOther::checkConstPointer -No CheckOther::checkConstVariable require:style,c++ -No CheckOther::checkDuplicateBranch require:style,inconclusive -Yes CheckOther::checkDuplicateExpression -Yes CheckOther::checkEvaluationOrder -Yes CheckOther::checkFuncArgNamesDifferent -No CheckOther::checkIncompleteArrayFill require:warning,portability,inconclusive -Yes CheckOther::checkIncompleteStatement -No CheckOther::checkInterlockedDecrement require:windows-platform -Yes CheckOther::checkInvalidFree -Yes CheckOther::checkKnownArgument -Yes CheckOther::checkKnownPointerToBool -No CheckOther::checkMisusedScopedObject require:style,c++ -Yes CheckOther::checkModuloOfOne -Yes CheckOther::checkNanInArithmeticExpression -Yes CheckOther::checkNegativeBitwiseShift -Yes CheckOther::checkOverlappingWrite -No CheckOther::checkPassByReference require:performance,c++ -Yes CheckOther::checkRedundantAssignment -No CheckOther::checkRedundantCopy require:c++,performance,inconclusive -Yes CheckOther::checkRedundantPointerOp -Yes CheckOther::checkShadowVariables -Yes CheckOther::checkSignOfUnsignedVariable -No CheckOther::checkSuspiciousCaseInSwitch require:warning,inconclusive -No CheckOther::checkSuspiciousSemicolon require:warning,inconclusive -Yes CheckOther::checkUnreachableCode -Yes CheckOther::checkUnusedLabel -Yes CheckOther::checkVarFuncNullUB -Yes CheckOther::checkVariableScope -Yes CheckOther::checkZeroDivision -Yes CheckOther::clarifyCalculation -Yes CheckOther::clarifyStatement -Yes CheckOther::invalidPointerCast -Yes CheckOther::redundantBitwiseOperationInSwitch -Yes CheckOther::suspiciousFloatingPointCast -No CheckOther::warningOldStylePointerCast require:style,c++ -No CheckPostfixOperator::postfixOperator require:performance -Yes CheckSizeof::checkSizeofForArrayParameter -Yes CheckSizeof::checkSizeofForNumericParameter -Yes CheckSizeof::checkSizeofForPointerSize -Yes CheckSizeof::sizeofCalculation -Yes CheckSizeof::sizeofFunction -Yes CheckSizeof::sizeofVoid -Yes CheckSizeof::sizeofsizeof -No CheckSizeof::suspiciousSizeofCalculation require:warning,inconclusive -No CheckStl::checkDereferenceInvalidIterator require:warning -No CheckStl::checkDereferenceInvalidIterator2 -No CheckStl::checkFindInsert require:performance -No CheckStl::checkMutexes require:warning -No CheckStl::erase -No CheckStl::eraseIteratorOutOfBounds -No CheckStl::if_find require:warning,performance -No CheckStl::invalidContainer -No CheckStl::iterators -No CheckStl::knownEmptyContainer require:style -No CheckStl::misMatchingContainerIterator -No CheckStl::misMatchingContainers -No CheckStl::missingComparison require:warning -No CheckStl::negativeIndex -No CheckStl::outOfBounds -No CheckStl::outOfBoundsIndexExpression -No CheckStl::redundantCondition require:style -No CheckStl::size require:performance,c++03 -No CheckStl::stlBoundaries -No CheckStl::stlOutOfBounds -No CheckStl::string_c_str -No CheckStl::useStlAlgorithm require:style -No CheckStl::uselessCalls require:performance,warning -Yes CheckString::checkAlwaysTrueOrFalseStringCompare -Yes CheckString::checkIncorrectStringCompare -Yes CheckString::checkSuspiciousStringCompare -Yes CheckString::overlappingStrcmp -Yes CheckString::sprintfOverlappingData -Yes CheckString::strPlusChar -Yes CheckString::stringLiteralWrite -Yes CheckType::checkFloatToIntegerOverflow -Yes CheckType::checkIntegerOverflow -Yes CheckType::checkLongCast -Yes CheckType::checkSignConversion -Yes CheckType::checkTooBigBitwiseShift -Yes CheckUninitVar::check -Yes CheckUninitVar::valueFlowUninit -No CheckUnusedFunctions::check require:unusedFunction +Yes CheckUnusedFunctions::check Yes CheckUnusedVar::checkFunctionVariableUsage Yes CheckUnusedVar::checkStructMemberUsage Yes CheckVaarg::va_list_usage diff --git a/opendbc_repo/opendbc/safety/tests/misra/install.sh b/opendbc_repo/opendbc/safety/tests/misra/install.sh index 9c8fd385c8..c626b8fa6b 100755 --- a/opendbc_repo/opendbc/safety/tests/misra/install.sh +++ b/opendbc_repo/opendbc/safety/tests/misra/install.sh @@ -10,7 +10,7 @@ fi cd $CPPCHECK_DIR -VERS="2.16.0" +VERS="2.17.1" git fetch --all --tags --force git checkout $VERS diff --git a/opendbc_repo/opendbc/safety/tests/misra/test_misra.sh b/opendbc_repo/opendbc/safety/tests/misra/test_misra.sh index 0ff97d712f..0bd762a820 100755 --- a/opendbc_repo/opendbc/safety/tests/misra/test_misra.sh +++ b/opendbc_repo/opendbc/safety/tests/misra/test_misra.sh @@ -13,11 +13,6 @@ NC='\033[0m' : "${CPPCHECK_DIR:=$DIR/cppcheck/}" -# install cppcheck if missing -if [ -z "${SKIP_CPPCHECK_INSTALL}" ]; then - $DIR/install.sh -fi - # ensure checked in coverage table is up to date if [ -z "$SKIP_TABLES_DIFF" ]; then python3 $CPPCHECK_DIR/addons/misra.py -generate-table > coverage_table @@ -37,7 +32,7 @@ echo "Cppcheck checkers list from test_misra.sh:" > $CHECKLIST cppcheck() { # get all gcc defines: arm-none-eabi-gcc -dM -E - < /dev/null - COMMON_DEFINES="-D__GNUC__=9 -UCMSIS_NVIC_VIRTUAL -UCMSIS_VECTAB_VIRTUAL" + COMMON_DEFINES="-D__GNUC__=9" # note that cppcheck build cache results in inconsistent results as of v2.13.0 OUTPUT=$DIR/.output.log @@ -45,11 +40,10 @@ cppcheck() { echo -e "\n\n\n\n\nTEST variant options:" >> $CHECKLIST echo -e ""${@//$BASEDIR/}"\n\n" >> $CHECKLIST # (absolute path removed) - $CPPCHECK_DIR/cppcheck --inline-suppr -I $BASEDIR/opendbc/safety/ \ - -I $BASEDIR/opendbc/safety/safety/ -I $BASEDIR/opendbc/safety/board/ \ - -I "$(arm-none-eabi-gcc -print-file-name=include)" \ - --suppressions-list=$DIR/suppressions.txt --suppress=*:*inc/* \ - --suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive --safety \ + $CPPCHECK_DIR/cppcheck --inline-suppr -I $BASEDIR \ + -I "$(gcc -print-file-name=include)" --suppress=*:*gcc*include/* --suppress=*:*clang*include/* \ + --suppressions-list=$DIR/suppressions.txt \ + --error-exitcode=2 --check-level=exhaustive --safety \ --platform=arm32-wchar_t4 $COMMON_DEFINES --checkers-report=$CHECKLIST.tmp \ --std=c11 "$@" 2>&1 | tee $OUTPUT @@ -63,21 +57,13 @@ cppcheck() { fi } -PANDA_OPTS="--enable=all --disable=unusedFunction -DPANDA --addon=misra" - -printf "\n${GREEN}** PANDA F4 CODE **${NC}\n" -cppcheck $PANDA_OPTS -DSTM32F4 -DSTM32F413xx $BASEDIR/opendbc/safety/main.c +PANDA_OPTS=" --enable=all --enable=unusedFunction --addon=misra" -printf "\n${GREEN}** PANDA H7 CODE **${NC}\n" -cppcheck $PANDA_OPTS -DSTM32H7 -DSTM32H725xx $BASEDIR/opendbc/safety/main.c - -# unused needs to run globally -#printf "\n${GREEN}** UNUSED ALL CODE **${NC}\n" -#cppcheck --enable=unusedFunction --quiet $BASEDIR/opendbc/safety/board/ +printf "\n${GREEN}** Safety with CANFD **${NC}\n" +cppcheck $PANDA_OPTS -DCANFD $BASEDIR/opendbc/safety/main.c printf "\n${GREEN}Success!${NC} took $SECONDS seconds\n" - # ensure list of checkers is up to date cd $DIR if [ -z "$SKIP_TABLES_DIFF" ] && ! git diff --quiet $CHECKLIST; then diff --git a/opendbc_repo/opendbc/safety/tests/misra/test_mutation.py b/opendbc_repo/opendbc/safety/tests/misra/test_mutation.py index 1caf51a864..fe346699aa 100755 --- a/opendbc_repo/opendbc/safety/tests/misra/test_mutation.py +++ b/opendbc_repo/opendbc/safety/tests/misra/test_mutation.py @@ -19,7 +19,7 @@ mutations = [ # default (None, None, False), # general safety - ("opendbc/safety/safety/safety_toyota.h", "s/is_lkas_msg =.*;/is_lkas_msg = addr == 1 || addr == 2;/g", True), + ("opendbc/safety/modes/toyota.h", "s/if (addr == 0x260) {/if (addr == 1 || addr == 2) {/g", True), ] patterns = [ diff --git a/opendbc_repo/opendbc/safety/tests/safety_replay/helpers.py b/opendbc_repo/opendbc/safety/tests/safety_replay/helpers.py index d4d31de9aa..5e058296dd 100644 --- a/opendbc_repo/opendbc/safety/tests/safety_replay/helpers.py +++ b/opendbc_repo/opendbc/safety/tests/safety_replay/helpers.py @@ -18,7 +18,7 @@ def is_steering_msg(mode, param, addr): ret = addr == (0x191 if param & ToyotaSafetyFlags.LTA else 0x2E4) elif mode == CarParams.SafetyModel.gm: ret = addr == 384 - elif mode == CarParams.SafetyModel.hyundai: + elif mode in (CarParams.SafetyModel.hyundai, CarParams.SafetyModel.hyundaiLegacy): ret = addr == 832 elif mode == CarParams.SafetyModel.hyundaiCanfd: ret = addr == (0x110 if param & HyundaiSafetyFlags.CANFD_LKA_STEERING_ALT else @@ -34,6 +34,8 @@ def is_steering_msg(mode, param, addr): ret = addr == 0x169 elif mode == CarParams.SafetyModel.rivian: ret = addr == 0x120 + elif mode == CarParams.SafetyModel.tesla: + ret = addr == 0x488 return ret def get_steer_value(mode, param, to_send): @@ -52,7 +54,7 @@ def get_steer_value(mode, param, to_send): elif mode == CarParams.SafetyModel.gm: torque = ((to_send.data[0] & 0x7) << 8) | to_send.data[1] torque = to_signed(torque, 11) - elif mode == CarParams.SafetyModel.hyundai: + elif mode in (CarParams.SafetyModel.hyundai, CarParams.SafetyModel.hyundaiLegacy): torque = (((to_send.data[3] & 0x7) << 8) | to_send.data[2]) - 1024 elif mode == CarParams.SafetyModel.hyundaiCanfd: torque = ((to_send.data[5] >> 1) | (to_send.data[6] & 0xF) << 7) - 1024 @@ -71,6 +73,8 @@ def get_steer_value(mode, param, to_send): angle = -angle + (1310 * 100) elif mode == CarParams.SafetyModel.rivian: torque = ((to_send.data[2] << 3) | (to_send.data[3] >> 5)) - 1024 + elif mode == CarParams.SafetyModel.tesla: + angle = (((to_send.data[0] & 0x7F) << 8) | (to_send.data[1])) - 16384 # ceil(1638.35/0.1) return torque, angle def package_can_msg(msg): diff --git a/opendbc_repo/opendbc/safety/tests/safety_replay/replay_drive.py b/opendbc_repo/opendbc/safety/tests/safety_replay/replay_drive.py index 36e958c7a9..cbd8fe81a1 100755 --- a/opendbc_repo/opendbc/safety/tests/safety_replay/replay_drive.py +++ b/opendbc_repo/opendbc/safety/tests/safety_replay/replay_drive.py @@ -49,6 +49,7 @@ def replay_drive(msgs, safety_mode, param, alternative_experience): elif msg.which() == 'can': # ignore msgs we sent for canmsg in filter(lambda m: m.src < 128, msg.can): + safety.safety_fwd_hook(canmsg.src, canmsg.address) to_push = package_can_msg(canmsg) recv = safety.safety_rx_hook(to_push) if not recv: diff --git a/opendbc_repo/opendbc/safety/tests/test_chrysler.py b/opendbc_repo/opendbc/safety/tests/test_chrysler.py index 854c2f5f73..d8c9825664 100755 --- a/opendbc_repo/opendbc/safety/tests/test_chrysler.py +++ b/opendbc_repo/opendbc/safety/tests/test_chrysler.py @@ -10,14 +10,13 @@ from opendbc.safety.tests.common import CANPackerPanda class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSafetyTest): TX_MSGS = [[0x23B, 0], [0x292, 0], [0x2A6, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x292,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x292, 0x2A6)} FWD_BLACKLISTED_ADDRS = {2: [0x292, 0x2A6]} MAX_RATE_UP = 3 MAX_RATE_DOWN = 3 - MAX_TORQUE = 261 + MAX_TORQUE_LOOKUP = [0], [261] MAX_RT_DELTA = 112 - RT_INTERVAL = 250000 MAX_TORQUE_ERROR = 80 LKAS_ACTIVE_VALUE = 1 @@ -75,12 +74,12 @@ class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSa class TestChryslerRamDTSafety(TestChryslerSafety): TX_MSGS = [[0xB1, 2], [0xA6, 0], [0xFA, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0xA6,)} + RELAY_MALFUNCTION_ADDRS = {0: (0xA6, 0xFA)} FWD_BLACKLISTED_ADDRS = {2: [0xA6, 0xFA]} MAX_RATE_UP = 6 MAX_RATE_DOWN = 6 - MAX_TORQUE = 350 + MAX_TORQUE_LOOKUP = [0], [350] DAS_BUS = 2 @@ -98,10 +97,10 @@ class TestChryslerRamDTSafety(TestChryslerSafety): class TestChryslerRamHDSafety(TestChryslerSafety): TX_MSGS = [[0x275, 0], [0x276, 0], [0x23A, 2]] - RELAY_MALFUNCTION_ADDRS = {0: (0x276,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x276, 0x275)} FWD_BLACKLISTED_ADDRS = {2: [0x275, 0x276]} - MAX_TORQUE = 361 + MAX_TORQUE_LOOKUP = [0], [361] MAX_RATE_UP = 14 MAX_RATE_DOWN = 14 MAX_RT_DELTA = 182 diff --git a/opendbc_repo/opendbc/safety/tests/test_gm.py b/opendbc_repo/opendbc/safety/tests/test_gm.py index ab65247231..29a56d184d 100755 --- a/opendbc_repo/opendbc/safety/tests/test_gm.py +++ b/opendbc_repo/opendbc/safety/tests/test_gm.py @@ -18,12 +18,13 @@ class Buttons: class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeSafetyTest): # pylint: disable=no-member,abstract-method - RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB)} # ASCMLKASteeringCmd, ASCMGasRegenCmd + RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB), 2: (0x184,)} # ASCMLKASteeringCmd, ASCMGasRegenCmd, PSCMStatus MAX_POSSIBLE_BRAKE = 2 ** 12 MAX_BRAKE = 400 - MAX_POSSIBLE_GAS = 2 ** 12 + MAX_POSSIBLE_GAS = 4000 # reasonably excessive limits, not signal max + MIN_POSSIBLE_GAS = -4000 PCM_CRUISE = False # openpilot can control the PCM state if longitudinal @@ -74,15 +75,14 @@ class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeS 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 + RELAY_MALFUNCTION_ADDRS = {0: (0x180,), 2: (0x184,)} # ASCMLKASteeringCmd, PSCMStatus BUTTONS_BUS = 0 # rx or tx BRAKE_BUS = 0 # tx only MAX_RATE_UP = 10 MAX_RATE_DOWN = 15 - MAX_TORQUE = 300 + MAX_TORQUE_LOOKUP = [0], [300] MAX_RT_DELTA = 128 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 65 DRIVER_TORQUE_FACTOR = 4 @@ -148,12 +148,13 @@ class TestGmAscmSafety(GmLongitudinalBase, TestGmSafetyBase): [0xA1, 1], [0x306, 1], [0x308, 1], [0x310, 1], # obs bus [0x315, 2]] # ch bus FWD_BLACKLISTED_ADDRS: dict[int, list[int]] = {} + RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB)} # ASCMLKASteeringCmd, ASCMGasRegenCmd FWD_BUS_LOOKUP: dict[int, int] = {} BRAKE_BUS = 2 - MAX_GAS = 3072 - MIN_GAS = 1404 # maximum regen - INACTIVE_GAS = 1404 + MAX_GAS = 1018 + MIN_GAS = -650 # maximum regen + INACTIVE_GAS = -650 def setUp(self): self.packer = CANPackerPanda("gm_global_a_powertrain_generated") @@ -209,11 +210,12 @@ 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 + RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB, 0x370, 0x315), 2: (0x184,)} BUTTONS_BUS = 0 # rx only - MAX_GAS = 3400 - MIN_GAS = 1514 # maximum regen - INACTIVE_GAS = 1554 + MAX_GAS = 1346 + MIN_GAS = -540 # maximum regen + INACTIVE_GAS = -500 def setUp(self): self.packer = CANPackerPanda("gm_global_a_powertrain_generated") diff --git a/opendbc_repo/opendbc/safety/tests/test_honda.py b/opendbc_repo/opendbc/safety/tests/test_honda.py index 265842efe4..a9fc57dd28 100755 --- a/opendbc_repo/opendbc/safety/tests/test_honda.py +++ b/opendbc_repo/opendbc/safety/tests/test_honda.py @@ -249,6 +249,7 @@ class HondaBase(common.PandaCarSafetyTest): class TestHondaNidecSafetyBase(HondaBase): TX_MSGS = HONDA_N_COMMON_TX_MSGS FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x194, 0x33D, 0x30C]} + RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x194, 0x33D, 0x30C)} PT_BUS = 0 STEER_BUS = 0 @@ -374,7 +375,7 @@ class TestHondaBoschSafetyBase(HondaBase): TX_MSGS = [[0xE4, 0], [0xE5, 0], [0x296, 1], [0x33D, 0], [0x33DA, 0], [0x33DB, 0]] FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]} - RELAY_MALFUNCTION_ADDRS = {0: (0xE4,)} # STEERING_CONTROL + RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB)} # STEERING_CONTROL, BOSCH_SUPPLEMENTAL_1 def setUp(self): self.packer = CANPackerPanda("honda_accord_2018_can_generated") @@ -458,9 +459,9 @@ class TestHondaBoschLongSafety(HondaButtonEnableBase, TestHondaBoschSafetyBase): 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]} + FWD_BLACKLISTED_ADDRS = {} # 0x1DF is to test that radar is disabled - RELAY_MALFUNCTION_ADDRS = {1: (0xE4, 0x1DF)} # STEERING_CONTROL, ACC_CONTROL + RELAY_MALFUNCTION_ADDRS = {1: (0xE4, 0x1DF, 0x33D, 0x33DA, 0x33DB)} # STEERING_CONTROL, ACC_CONTROL def setUp(self): super().setUp() @@ -510,7 +511,8 @@ class TestHondaBoschRadarlessSafetyBase(TestHondaBoschSafetyBase): 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]} + FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x33D]} + RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x33D)} # STEERING_CONTROL def setUp(self): self.packer = CANPackerPanda("honda_civic_ex_2022_can_generated") @@ -545,7 +547,8 @@ class TestHondaBoschRadarlessLongSafety(common.LongitudinalAccelSafetyTest, Hond 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]} + FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x33D, 0x1C8, 0x30C]} + RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x1C8, 0x30C, 0x33D)} def setUp(self): super().setUp() diff --git a/opendbc_repo/opendbc/safety/tests/test_hyundai.py b/opendbc_repo/opendbc/safety/tests/test_hyundai.py index fa95fdca9d..c0c972caeb 100755 --- a/opendbc_repo/opendbc/safety/tests/test_hyundai.py +++ b/opendbc_repo/opendbc/safety/tests/test_hyundai.py @@ -48,21 +48,19 @@ def checksum(msg): 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 + RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x485)} # LKAS11 FWD_BLACKLISTED_ADDRS = {2: [0x340, 0x485]} MAX_RATE_UP = 3 MAX_RATE_DOWN = 7 - MAX_TORQUE = 384 + MAX_TORQUE_LOOKUP = [0], [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 @@ -117,7 +115,7 @@ class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.Dri class TestHyundaiSafetyAltLimits(TestHyundaiSafety): MAX_RATE_UP = 2 MAX_RATE_DOWN = 3 - MAX_TORQUE = 270 + MAX_TORQUE_LOOKUP = [0], [270] def setUp(self): self.packer = CANPackerPanda("hyundai_kia_generic") @@ -129,7 +127,7 @@ class TestHyundaiSafetyAltLimits(TestHyundaiSafety): class TestHyundaiSafetyAltLimits2(TestHyundaiSafety): MAX_RATE_UP = 2 MAX_RATE_DOWN = 3 - MAX_TORQUE = 170 + MAX_TORQUE_LOOKUP = [0], [170] def setUp(self): self.packer = CANPackerPanda("hyundai_kia_generic") @@ -195,7 +193,9 @@ class TestHyundaiLegacySafetyHEV(TestHyundaiSafety): 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 + FWD_BLACKLISTED_ADDRS = {2: [0x340, 0x485, 0x421, 0x420, 0x50A, 0x389]} + + RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x485, 0x421, 0x420, 0x50A, 0x389)} # LKAS11, LFAHDA_MFC, SCC12, SCC11, SCC13, SCC14 DISABLED_ECU_UDS_MSG = (0x7D0, 0) DISABLED_ECU_ACTUATION_MSG = (0x421, 0) @@ -241,6 +241,7 @@ class TestHyundaiLongitudinalSafetyCameraSCC(HyundaiLongitudinalBase, TestHyunda TX_MSGS = [[0x340, 0], [0x4F1, 2], [0x485, 0], [0x420, 0], [0x421, 0], [0x50A, 0], [0x389, 0], [0x4A2, 0]] FWD_BLACKLISTED_ADDRS = {2: [0x340, 0x485, 0x420, 0x421, 0x50A, 0x389]} + RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x485, 0x421, 0x420, 0x50A, 0x389)} # LKAS11, LFAHDA_MFC, SCC12, SCC11, SCC13, SCC14 def setUp(self): self.packer = CANPackerPanda("hyundai_kia_generic") diff --git a/opendbc_repo/opendbc/safety/tests/test_hyundai_canfd.py b/opendbc_repo/opendbc/safety/tests/test_hyundai_canfd.py index b31c8c3ef0..3fad83d3df 100755 --- a/opendbc_repo/opendbc/safety/tests/test_hyundai_canfd.py +++ b/opendbc_repo/opendbc/safety/tests/test_hyundai_canfd.py @@ -30,10 +30,9 @@ class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common. MAX_RATE_UP = 2 MAX_RATE_DOWN = 3 - MAX_TORQUE = 270 + MAX_TORQUE_LOOKUP = [0], [270] MAX_RT_DELTA = 112 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 250 DRIVER_TORQUE_FACTOR = 2 @@ -41,7 +40,6 @@ class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common. # 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 @@ -87,7 +85,7 @@ class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common. class TestHyundaiCanfdLFASteeringBase(TestHyundaiCanfdBase): TX_MSGS = [[0x12A, 0], [0x1A0, 1], [0x1CF, 0], [0x1E0, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x12A,)} # LFA + RELAY_MALFUNCTION_ADDRS = {0: (0x12A, 0x1E0)} # LFA, LFAHDA_CLUSTER FWD_BLACKLISTED_ADDRS = {2: [0x12A, 0x1E0]} STEER_MSG = "LFA" @@ -161,7 +159,7 @@ class TestHyundaiCanfdLFASteeringAltButtons(TestHyundaiCanfdLFASteeringAltButton class TestHyundaiCanfdLKASteeringEV(TestHyundaiCanfdBase): TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x50,)} # LKAS + RELAY_MALFUNCTION_ADDRS = {0: (0x50, 0x2a4)} # LKAS, CAM_0x2A4 FWD_BLACKLISTED_ADDRS = {2: [0x50, 0x2a4]} PT_BUS = 1 @@ -180,7 +178,7 @@ class TestHyundaiCanfdLKASteeringEV(TestHyundaiCanfdBase): class TestHyundaiCanfdLKASteeringAltEV(TestHyundaiCanfdBase): TX_MSGS = [[0x110, 0], [0x1CF, 1], [0x362, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x110,)} # LKAS_ALT + RELAY_MALFUNCTION_ADDRS = {0: (0x110, 0x362)} # LKAS_ALT, CAM_0x362 FWD_BLACKLISTED_ADDRS = {2: [0x110, 0x362]} PT_BUS = 1 @@ -201,7 +199,7 @@ class TestHyundaiCanfdLKASteeringLongEV(HyundaiLongitudinalBase, TestHyundaiCanf 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 + RELAY_MALFUNCTION_ADDRS = {0: (0x50, 0x2a4), 1: (0x1a0,)} # LKAS, CAM_0x2A4, SCC_CONTROL DISABLED_ECU_UDS_MSG = (0x730, 1) DISABLED_ECU_ACTUATION_MSG = (0x1a0, 1) @@ -230,7 +228,7 @@ class TestHyundaiCanfdLFASteeringLongBase(HyundaiLongitudinalBase, TestHyundaiCa FWD_BLACKLISTED_ADDRS = {2: [0x12a, 0x1e0, 0x1a0, 0x160]} - RELAY_MALFUNCTION_ADDRS = {0: (0x12A, 0x1a0)} # LFA, SCC_CONTROL + RELAY_MALFUNCTION_ADDRS = {0: (0x12A, 0x1E0, 0x1a0, 0x160)} # LFA, LFAHDA_CLUSTER, SCC_CONTROL, ADRV_0x160 DISABLED_ECU_UDS_MSG = (0x7D0, 0) DISABLED_ECU_ACTUATION_MSG = (0x1a0, 0) diff --git a/opendbc_repo/opendbc/safety/tests/test_mazda.py b/opendbc_repo/opendbc/safety/tests/test_mazda.py index e60248d2d1..a39b25b4aa 100755 --- a/opendbc_repo/opendbc/safety/tests/test_mazda.py +++ b/opendbc_repo/opendbc/safety/tests/test_mazda.py @@ -11,15 +11,14 @@ class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafe TX_MSGS = [[0x243, 0], [0x09d, 0], [0x440, 0]] STANDSTILL_THRESHOLD = .1 - RELAY_MALFUNCTION_ADDRS = {0: (0x243,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x243, 0x440)} FWD_BLACKLISTED_ADDRS = {2: [0x243, 0x440]} MAX_RATE_UP = 10 MAX_RATE_DOWN = 25 - MAX_TORQUE = 800 + MAX_TORQUE_LOOKUP = [0], [800] MAX_RT_DELTA = 300 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 15 DRIVER_TORQUE_FACTOR = 1 diff --git a/opendbc_repo/opendbc/safety/tests/test_nissan.py b/opendbc_repo/opendbc/safety/tests/test_nissan.py index 22f556f4dc..588bc9612c 100755 --- a/opendbc_repo/opendbc/safety/tests/test_nissan.py +++ b/opendbc_repo/opendbc/safety/tests/test_nissan.py @@ -12,7 +12,7 @@ class TestNissanSafety(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest TX_MSGS = [[0x169, 0], [0x2b1, 0], [0x4cc, 0], [0x20b, 2], [0x280, 2]] GAS_PRESSED_THRESHOLD = 3 - RELAY_MALFUNCTION_ADDRS = {0: (0x169,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x169, 0x2b1, 0x4cc), 2: (0x280,)} FWD_BLACKLISTED_ADDRS = {0: [0x280], 2: [0x169, 0x2b1, 0x4cc]} EPS_BUS = 0 diff --git a/opendbc_repo/opendbc/safety/tests/test_rivian.py b/opendbc_repo/opendbc/safety/tests/test_rivian.py index a1b6b3e8a1..8867c94a78 100755 --- a/opendbc_repo/opendbc/safety/tests/test_rivian.py +++ b/opendbc_repo/opendbc/safety/tests/test_rivian.py @@ -1,29 +1,51 @@ #!/usr/bin/env python3 import unittest +import numpy as np from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common from opendbc.safety.tests.common import CANPackerPanda from opendbc.car.rivian.values import RivianSafetyFlags +from opendbc.car.rivian.riviancan import checksum as _checksum -class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.LongitudinalAccelSafetyTest): +def checksum(msg): + addr, dat, bus = msg + ret = bytearray(dat) + + # ESP_Status + if addr == 0x208: + ret[0] = _checksum(ret[1:], 0x1D, 0xB1) + elif addr == 0x150: + ret[0] = _checksum(ret[1:], 0x1D, 0x9A) + + return addr, ret, bus + + +class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.LongitudinalAccelSafetyTest, + common.VehicleSpeedSafetyTest): TX_MSGS = [[0x120, 0], [0x321, 2], [0x162, 2]] - RELAY_MALFUNCTION_ADDRS = {0: (0x120,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x120,), 2: (0x321, 0x162)} FWD_BLACKLISTED_ADDRS = {0: [0x321, 0x162], 2: [0x120]} - MAX_TORQUE = 250 + MAX_TORQUE_LOOKUP = [9, 17], [350, 250] + DYNAMIC_MAX_TORQUE = True MAX_RATE_UP = 3 MAX_RATE_DOWN = 5 MAX_RT_DELTA = 125 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 100 DRIVER_TORQUE_FACTOR = 2 + # Max allowed delta between car speeds + MAX_SPEED_DELTA = 2.0 # m/s + + cnt_speed = 0 + cnt_speed_2 = 0 + def _torque_driver_msg(self, torque): values = {"EPAS_TorsionBarTorque": torque / 100.0} return self.packer.make_can_msg_panda("EPAS_SystemStatus", 0, values) @@ -32,26 +54,29 @@ class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteerin values = {"ACM_lkaStrToqReq": torque, "ACM_lkaActToi": steer_req} return self.packer.make_can_msg_panda("ACM_lkaHbaCmd", 0, values) - def _speed_msg(self, speed): - values = {"ESP_Status": speed * 3.6} - return self.packer.make_can_msg_panda("ESP_Vehicle_Speed", 0, values) + def _speed_msg(self, speed, quality_flag=True): + values = {"ESP_Vehicle_Speed": speed * 3.6, "ESP_Status_Counter": self.cnt_speed % 15, + "ESP_Vehicle_Speed_Q": 1 if quality_flag else 0} + self.__class__.cnt_speed += 1 + return self.packer.make_can_msg_panda("ESP_Status", 0, values, fix_checksum=checksum) + + def _speed_msg_2(self, speed, quality_flag=True): + return self._user_gas_msg(0, speed, quality_flag) def _user_brake_msg(self, brake): values = {"iBESP2_BrakePedalApplied": brake} return self.packer.make_can_msg_panda("iBESP2", 0, values) - def _user_gas_msg(self, gas): - values = {"VDM_AcceleratorPedalPosition": gas} - return self.packer.make_can_msg_panda("VDM_PropStatus", 0, values) + def _user_gas_msg(self, gas, speed=0, quality_flag=True): + values = {"VDM_AcceleratorPedalPosition": gas, "VDM_VehicleSpeed": speed * 3.6, + "VDM_PropStatus_Counter": self.cnt_speed_2 % 15, "VDM_VehicleSpeedQ": 1 if quality_flag else 0} + self.__class__.cnt_speed_2 += 1 + return self.packer.make_can_msg_panda("VDM_PropStatus", 0, values, fix_checksum=checksum) def _pcm_status_msg(self, enable): values = {"ACM_FeatureStatus": enable, "ACM_Unkown1": 1} return self.packer.make_can_msg_panda("ACM_Status", 2, values) - def _vehicle_moving_msg(self, speed: float): - values = {"ESP_Vehicle_Speed": speed} - return self.packer.make_can_msg_panda("ESP_Status", 0, values) - def _accel_msg(self, accel: float): values = {"ACM_AccelerationRequest": accel} return self.packer.make_can_msg_panda("ACM_longitudinalRequest", 0, values) @@ -67,6 +92,40 @@ class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteerin } self.assertTrue(self._tx(self.packer.make_can_msg_panda("SCCM_WheelTouch", 2, values))) + def test_rx_hook(self): + # checksum, counter, and quality flag checks + for quality_flag in (True, False): + for msg in ("speed", "speed_2"): + 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) + + self.assertEqual(quality_flag, self._rx(to_push)) + self.assertEqual(quality_flag, self.safety.get_controls_allowed()) + + # Mess with checksum to make it fail + to_push[0].data[0] = 0xff + self.assertFalse(self._rx(to_push)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_rx_hook_speed_mismatch(self): + # TODO: this can be a common test w/ Ford + # Rivian has a dynamic max torque limit based on speed, 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) + class TestRivianStockSafety(TestRivianSafetyBase): @@ -90,7 +149,7 @@ class TestRivianStockSafety(TestRivianSafetyBase): class TestRivianLongitudinalSafety(TestRivianSafetyBase): TX_MSGS = [[0x120, 0], [0x321, 2], [0x160, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x120, 0x160)} + RELAY_MALFUNCTION_ADDRS = {0: (0x120, 0x160), 2: (0x321,)} FWD_BLACKLISTED_ADDRS = {0: [0x321], 2: [0x120, 0x160]} def setUp(self): diff --git a/opendbc_repo/opendbc/safety/tests/test_subaru.py b/opendbc_repo/opendbc/safety/tests/test_subaru.py index 8727732400..f31a8df5c9 100755 --- a/opendbc_repo/opendbc/safety/tests/test_subaru.py +++ b/opendbc_repo/opendbc/safety/tests/test_subaru.py @@ -56,11 +56,11 @@ def fwd_blacklisted_addr(lkas_msg=SubaruMsg.ES_LKAS): class TestSubaruSafetyBase(common.PandaCarSafetyTest): FLAGS = 0 - RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS,)} + RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, + SubaruMsg.ES_Infotainment)} FWD_BLACKLISTED_ADDRS = fwd_blacklisted_addr() MAX_RT_DELTA = 940 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 60 DRIVER_TORQUE_FACTOR = 50 @@ -155,12 +155,12 @@ class TestSubaruLongitudinalSafetyBase(TestSubaruSafetyBase, common.Longitudinal class TestSubaruTorqueSafetyBase(TestSubaruSafetyBase, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): MAX_RATE_UP = 50 MAX_RATE_DOWN = 70 - MAX_TORQUE = 2047 + MAX_TORQUE_LOOKUP = [0], [2047] # Safety around steering req bit MIN_VALID_STEERING_FRAMES = 7 MAX_INVALID_STEERING_FRAMES = 1 - MIN_VALID_STEERING_RT_INTERVAL = 144000 + STEER_STEP = 2 def _torque_cmd_msg(self, torque, steer_req=1): values = {"LKAS_Output": torque, "LKAS_Request": steer_req} @@ -178,7 +178,7 @@ class TestSubaruGen2TorqueSafetyBase(TestSubaruTorqueSafetyBase): MAX_RATE_UP = 40 MAX_RATE_DOWN = 40 - MAX_TORQUE = 1000 + MAX_TORQUE_LOOKUP = [0], [1000] class TestSubaruGen2TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase): @@ -189,11 +189,19 @@ class TestSubaruGen2TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSaf class TestSubaruGen1LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruTorqueSafetyBase): FLAGS = SubaruSafetyFlags.LONG TX_MSGS = lkas_tx_msgs(SUBARU_MAIN_BUS) + long_tx_msgs(SUBARU_MAIN_BUS) + RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, + SubaruMsg.ES_Infotainment, SubaruMsg.ES_Brake, SubaruMsg.ES_Status, + SubaruMsg.ES_Distance)} class TestSubaruGen2LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase): FLAGS = SubaruSafetyFlags.LONG | SubaruSafetyFlags.GEN2 TX_MSGS = lkas_tx_msgs(SUBARU_ALT_BUS) + long_tx_msgs(SUBARU_ALT_BUS) + gen2_long_additional_tx_msgs() + FWD_BLACKLISTED_ADDRS = {2: [SubaruMsg.ES_LKAS, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, + SubaruMsg.ES_Infotainment]} + RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, + SubaruMsg.ES_Infotainment), + SUBARU_ALT_BUS: (SubaruMsg.ES_Brake, SubaruMsg.ES_Status, SubaruMsg.ES_Distance)} def _rdbi_msg(self, did: int): return b'\x03\x22' + did.to_bytes(2) + b'\x00\x00\x00\x00' diff --git a/opendbc_repo/opendbc/safety/tests/test_subaru_preglobal.py b/opendbc_repo/opendbc/safety/tests/test_subaru_preglobal.py index b2f482bf57..44aef0812e 100755 --- a/opendbc_repo/opendbc/safety/tests/test_subaru_preglobal.py +++ b/opendbc_repo/opendbc/safety/tests/test_subaru_preglobal.py @@ -12,15 +12,14 @@ class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSt FLAGS = 0 DBC = "subaru_outback_2015_generated" TX_MSGS = [[0x161, 0], [0x164, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x164,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x164, 0x161)} FWD_BLACKLISTED_ADDRS = {2: [0x161, 0x164]} MAX_RATE_UP = 50 MAX_RATE_DOWN = 70 - MAX_TORQUE = 2047 + MAX_TORQUE_LOOKUP = [0], [2047] MAX_RT_DELTA = 940 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 75 DRIVER_TORQUE_FACTOR = 10 diff --git a/opendbc_repo/opendbc/safety/tests/test_tesla.py b/opendbc_repo/opendbc/safety/tests/test_tesla.py index a75e35392d..4ed9b0f714 100755 --- a/opendbc_repo/opendbc/safety/tests/test_tesla.py +++ b/opendbc_repo/opendbc/safety/tests/test_tesla.py @@ -1,18 +1,28 @@ #!/usr/bin/env python3 import unittest +import numpy as np from opendbc.car.tesla.values import TeslaSafetyFlags +from opendbc.car.tesla.carcontroller import get_max_angle_delta, get_max_angle, get_safety_CP from opendbc.car.structs import CarParams +from opendbc.car.vehicle_model import VehicleModel from opendbc.can.can_define import CANDefine from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerPanda, MAX_WRONG_COUNTERS, away_round, round_speed MSG_DAS_steeringControl = 0x488 MSG_APS_eacMonitor = 0x27d MSG_DAS_Control = 0x2b9 +def round_angle(apply_angle, can_offset=0): + apply_angle_can = (apply_angle + 1638.35) / 0.1 + can_offset + # 0.49999_ == 0.5 + rnd_offset = 1e-5 if apply_angle >= 0 else -1e-5 + return away_round(apply_angle_can + rnd_offset) * 0.1 - 1638.35 + + class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest, common.LongitudinalAccelSafetyTest): RELAY_MALFUNCTION_ADDRS = {0: (MSG_DAS_steeringControl, MSG_APS_eacMonitor)} FWD_BLACKLISTED_ADDRS = {2: [MSG_DAS_steeringControl, MSG_APS_eacMonitor]} @@ -25,28 +35,43 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT STEER_ANGLE_MAX = 360 # deg DEG_TO_CAN = 10 - ANGLE_RATE_BP = [0., 5., 25.] - ANGLE_RATE_UP = [2.5, 1.5, 0.2] # windup limit - ANGLE_RATE_DOWN = [5., 2.0, 0.3] # unwind limit + # Tesla uses get_max_angle_delta and get_max_angle for real lateral accel and jerk limits + # TODO: integrate this into AngleSteeringSafetyTest + ANGLE_RATE_BP = None + ANGLE_RATE_UP = None + ANGLE_RATE_DOWN = None # Long control limits MAX_ACCEL = 2.0 MIN_ACCEL = -3.48 INACTIVE_ACCEL = 0.0 + # Max allowed delta between car speeds + MAX_SPEED_DELTA = 2.0 # m/s + + cnt_epas = 0 + packer: CANPackerPanda def setUp(self): + self.VM = VehicleModel(get_safety_CP()) self.packer = CANPackerPanda("tesla_model3_party") self.define = CANDefine("tesla_model3_party") self.acc_states = {d: v for v, d in self.define.dv["DAS_control"]["DAS_accState"].items()} + self.autopark_states = {d: v for v, d in self.define.dv["DI_state"]["DI_autoparkState"].items()} + self.active_autopark_states = [self.autopark_states[s] for s in ('ACTIVE', 'COMPLETE', 'SELFPARK_STARTED')] + + self.steer_control_types = {d: v for v, d in self.define.dv["DAS_steeringControl"]["DAS_steeringControlType"].items()} - 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_cmd_msg(self, angle: float, state: bool | int, bus: int = 0): + values = {"DAS_steeringAngleRequest": angle, "DAS_steeringControlType": state} + return self.packer.make_can_msg_panda("DAS_steeringControl", bus, values) - def _angle_meas_msg(self, angle: float): - values = {"EPAS3S_internalSAS": angle} + def _angle_meas_msg(self, angle: float, hands_on_level: int = 0, eac_status: int = 1, eac_error_code: int = 0): + values = {"EPAS3S_internalSAS": angle, "EPAS3S_handsOnLevel": hands_on_level, + "EPAS3S_eacStatus": eac_status, "EPAS3S_eacErrorCode": eac_error_code, + "EPAS3S_sysStatusCounter": self.cnt_epas % 16} + self.__class__.cnt_epas += 1 return self.packer.make_can_msg_panda("EPAS3S_sysStatus", 0, values) def _user_brake_msg(self, brake): @@ -57,6 +82,10 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT values = {"DI_vehicleSpeed": speed * 3.6} return self.packer.make_can_msg_panda("DI_speed", 0, values) + def _speed_msg_2(self, speed, quality_flag=True): + values = {"ESP_vehicleSpeed": speed * 3.6, "ESP_wheelSpeedsQF": quality_flag} + return self.packer.make_can_msg_panda("ESP_B", 0, values) + def _vehicle_moving_msg(self, speed: float): values = {"DI_cruiseState": 3 if speed <= self.STANDSTILL_THRESHOLD else 2} return self.packer.make_can_msg_panda("DI_state", 0, values) @@ -65,8 +94,11 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT values = {"DI_accelPedalPos": gas} return self.packer.make_can_msg_panda("DI_systemStatus", 0, values) - def _pcm_status_msg(self, enable): - values = {"DI_cruiseState": 2 if enable else 0} + def _pcm_status_msg(self, enable, autopark_state=0): + values = { + "DI_cruiseState": 2 if enable else 0, + "DI_autoparkState": autopark_state, + } return self.packer.make_can_msg_panda("DI_state", 0, values) def _long_control_msg(self, set_speed, acc_state=0, jerk_limits=(0, 0), accel_limits=(0, 0), aeb_event=0, bus=0): @@ -85,11 +117,222 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT # For common.LongitudinalAccelSafetyTest return self._long_control_msg(10, accel_limits=(accel, max(accel, 0))) + def test_rx_hook(self): + # counter check + for msg in ("angle", "long", "speed", "speed_2"): + # send multiple times to verify counter checks + for i in range(10): + if msg == "angle": + to_push = self._angle_cmd_msg(0, True, bus=2) + elif msg == "long": + to_push = self._long_control_msg(0, bus=2) + elif msg == "speed": + to_push = self._speed_msg(0) + elif msg == "speed_2": + to_push = self._speed_msg_2(0) + + should_rx = i >= 5 + if not should_rx: + # mess with checksums + if msg == "angle": + to_push[0].data[3] = 0 + elif msg == "long": + to_push[0].data[7] = 0 + elif msg == "speed": + to_push[0].data[0] = 0 + elif msg == "speed_2": + to_push[0].data[7] = 0 + + self.safety.set_controls_allowed(True) + self.assertEqual(should_rx, self._rx(to_push)) + self.assertEqual(should_rx, self.safety.get_controls_allowed()) + + # Send static counters + for i in range(MAX_WRONG_COUNTERS + 1): + should_rx = i + 1 < MAX_WRONG_COUNTERS + self.assertEqual(should_rx, self._rx(to_push)) + self.assertEqual(should_rx, self.safety.get_controls_allowed()) + def test_vehicle_speed_measurements(self): # OVERRIDDEN: 79.1667 is the max speed in m/s self._common_measurement_test(self._speed_msg, 0, 285 / 3.6, 1, self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max) + def test_rx_hook_speed_mismatch(self): + # TODO: this can be a common test w/ Ford + # Tesla relies on speed for lateral limits close to ISO 11270, so it checks two sources + for speed in np.arange(0, 40, 0.5): + # match signal rounding on CAN + speed = away_round(speed / 0.08 * 3.6) * 0.08 / 3.6 + for speed_delta in np.arange(-5, 5, 0.1): + speed_2 = max(speed + speed_delta, 0) + speed_2 = away_round(speed_2 * 2 * 3.6) / 2 / 3.6 + + # Set controls allowed in between rx since first message can reset it + self.assertTrue(self._rx(self._speed_msg(speed))) + self.safety.set_controls_allowed(True) + self.assertTrue(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) + + # Test ESP_B quality flag + for quality_flag in (True, False): + self.safety.set_controls_allowed(True) + self.assertTrue(self._rx(self._speed_msg(0))) + self.assertEqual(quality_flag, self._rx(self._speed_msg_2(0, quality_flag=quality_flag))) + self.assertEqual(quality_flag, self.safety.get_controls_allowed()) + + def test_steering_wheel_disengage(self): + # Tesla disengages when the user forcibly overrides the locked-in angle steering control + # Either when the hands on level is high, or if there is a high angle rate fault + for hands_on_level in range(4): + for eac_status in range(8): + for eac_error_code in range(16): + self.safety.set_controls_allowed(True) + + should_disengage = hands_on_level >= 3 or (eac_status == 0 and eac_error_code == 9) + self.assertTrue(self._rx(self._angle_meas_msg(0, hands_on_level=hands_on_level, eac_status=eac_status, + eac_error_code=eac_error_code))) + self.assertNotEqual(should_disengage, self.safety.get_controls_allowed()) + self.assertEqual(should_disengage, self.safety.get_steering_disengage_prev()) + + # Should not recover + self.assertTrue(self._rx(self._angle_meas_msg(0, hands_on_level=0, eac_status=1, eac_error_code=0))) + self.assertNotEqual(should_disengage, self.safety.get_controls_allowed()) + self.assertFalse(self.safety.get_steering_disengage_prev()) + + def test_autopark_summon_while_enabled(self): + # We should not respect Autopark that activates while controls are allowed + self._rx(self._pcm_status_msg(True, 0)) + + self._rx(self._pcm_status_msg(True, self.autopark_states["SELFPARK_STARTED"])) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertTrue(self._tx(self._angle_cmd_msg(0, True))) + self.assertTrue(self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"]))) + + # We should still not respect Autopark if we disengage cruise + self._rx(self._pcm_status_msg(False, self.autopark_states["SELFPARK_STARTED"])) + self.assertFalse(self.safety.get_controls_allowed()) + self.assertTrue(self._tx(self._angle_cmd_msg(0, False))) + self.assertTrue(self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"]))) + + def test_autopark_summon_behavior(self): + for autopark_state in range(16): + self._rx(self._pcm_status_msg(False, 0)) + + # We shouldn't allow controls if Autopark is an active state + autopark_active = autopark_state in self.active_autopark_states + self._rx(self._pcm_status_msg(False, autopark_state)) + self._rx(self._pcm_status_msg(True, autopark_state)) + self.assertNotEqual(autopark_active, self.safety.get_controls_allowed()) + + # We should also start blocking all inactive/active openpilot msgs + self.assertNotEqual(autopark_active, self._tx(self._angle_cmd_msg(0, False))) + self.assertNotEqual(autopark_active, self._tx(self._angle_cmd_msg(0, True))) + self.assertNotEqual(autopark_active, self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"]))) + self.assertNotEqual(autopark_active or not self.LONGITUDINAL, self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_ON"]))) + + # Regain controls when Autopark disables + self._rx(self._pcm_status_msg(True, 0)) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertTrue(self._tx(self._angle_cmd_msg(0, False))) + self.assertTrue(self._tx(self._angle_cmd_msg(0, True))) + self.assertTrue(self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"]))) + self.assertEqual(self.LONGITUDINAL, self._tx(self._long_control_msg(0, acc_state=self.acc_states["ACC_ON"]))) + + def test_steering_control_type(self): + # Only angle control is allowed (no LANE_KEEP_ASSIST or EMERGENCY_LANE_KEEP) + self.safety.set_controls_allowed(True) + for steer_control_type in range(4): + should_tx = steer_control_type in (self.steer_control_types["NONE"], + self.steer_control_types["ANGLE_CONTROL"]) + self.assertEqual(should_tx, self._tx(self._angle_cmd_msg(0, state=steer_control_type))) + + def test_stock_lkas_passthrough(self): + # TODO: make these generic passthrough tests + no_lkas_msg = self._angle_cmd_msg(0, state=False) + no_lkas_msg_cam = self._angle_cmd_msg(0, state=True, bus=2) + lkas_msg_cam = self._angle_cmd_msg(0, state=self.steer_control_types['LANE_KEEP_ASSIST'], bus=2) + + # stock system sends no LKAS -> no forwarding, and OP is allowed to TX + self.assertEqual(1, self._rx(no_lkas_msg_cam)) + self.assertEqual(-1, self.safety.safety_fwd_hook(2, no_lkas_msg_cam.addr)) + self.assertTrue(self._tx(no_lkas_msg)) + + # stock system sends LKAS -> forwarding, and OP is not allowed to TX + self.assertEqual(1, self._rx(lkas_msg_cam)) + self.assertEqual(0, self.safety.safety_fwd_hook(2, lkas_msg_cam.addr)) + self.assertFalse(self._tx(no_lkas_msg)) + + def test_angle_cmd_when_enabled(self): + # We properly test lateral acceleration and jerk below + pass + + def test_lateral_accel_limit(self): + for speed in np.linspace(0, 40, 100): + # match DI_vehicleSpeed rounding on CAN + speed = round_speed(away_round(speed / 0.08 * 3.6) * 0.08 / 3.6) + for sign in (-1, 1): + self.safety.set_controls_allowed(True) + self._reset_speed_measurement(speed + 1) # safety fudges the speed + + # angle signal can't represent 0, so it biases one unit down + angle_unit_offset = -1 if sign == -1 else 0 + + # at limit (safety tolerance adds 1) + max_angle = round_angle(get_max_angle(speed, self.VM), angle_unit_offset + 1) * sign + max_angle = np.clip(max_angle, -self.STEER_ANGLE_MAX, self.STEER_ANGLE_MAX) + self._tx(self._angle_cmd_msg(max_angle, True)) + + self.assertTrue(self._tx(self._angle_cmd_msg(max_angle, True))) + + # 1 unit above limit + max_angle_raw = round_angle(get_max_angle(speed, self.VM), angle_unit_offset + 2) * sign + max_angle = np.clip(max_angle_raw, -self.STEER_ANGLE_MAX, self.STEER_ANGLE_MAX) + self._tx(self._angle_cmd_msg(max_angle, True)) + + # at low speeds max angle is above 360, so adding 1 has no effect + should_tx = abs(max_angle_raw) >= self.STEER_ANGLE_MAX + self.assertEqual(should_tx, self._tx(self._angle_cmd_msg(max_angle, True))) + + def test_lateral_jerk_limit(self): + for speed in np.linspace(0, 40, 100): + # match DI_vehicleSpeed rounding on CAN + speed = round_speed(away_round(speed / 0.08 * 3.6) * 0.08 / 3.6) + for sign in (-1, 1): # (-1, 1): + self.safety.set_controls_allowed(True) + self._reset_speed_measurement(speed + 1) # safety fudges the speed + self._tx(self._angle_cmd_msg(0, True)) + + # angle signal can't represent 0, so it biases one unit down + angle_unit_offset = 1 if sign == -1 else 0 + + # Stay within limits + # Up + max_angle_delta = round_angle(get_max_angle_delta(speed, self.VM), angle_unit_offset) * sign + self.assertTrue(self._tx(self._angle_cmd_msg(max_angle_delta, True))) + + # Don't change + self.assertTrue(self._tx(self._angle_cmd_msg(max_angle_delta, True))) + + # Down + self.assertTrue(self._tx(self._angle_cmd_msg(0, True))) + + # Inject too high rates + # Up + max_angle_delta = round_angle(get_max_angle_delta(speed, self.VM), angle_unit_offset + 1) * sign + self.assertFalse(self._tx(self._angle_cmd_msg(max_angle_delta, True))) + + # Don't change + self.assertTrue(self._tx(self._angle_cmd_msg(max_angle_delta, True))) + + # Down + self.assertFalse(self._tx(self._angle_cmd_msg(0, True))) + + # Recover + self.assertTrue(self._tx(self._angle_cmd_msg(0, True))) + class TestTeslaStockSafety(TestTeslaSafetyBase): @@ -110,7 +353,26 @@ class TestTeslaStockSafety(TestTeslaSafetyBase): def test_no_aeb(self): for aeb_event in range(4): - self.assertEqual(self._tx(self._long_control_msg(10, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"], aeb_event=aeb_event)), aeb_event == 0) + should_tx = aeb_event == 0 + ret = self._tx(self._long_control_msg(10, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"], aeb_event=aeb_event)) + self.assertEqual(ret, should_tx) + + def test_stock_aeb_no_cancel(self): + # No passthrough logic since we always forward DAS_control, + # but ensure we can't send cancel cmd while stock AEB is active + no_aeb_msg = self._long_control_msg(10, acc_state=self.acc_states["ACC_CANCEL_GENERIC_SILENT"], 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(0, self.safety.safety_fwd_hook(2, no_aeb_msg_cam.addr)) + self.assertTrue(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.assertFalse(self._tx(no_aeb_msg)) class TestTeslaLongitudinalSafety(TestTeslaSafetyBase): diff --git a/opendbc_repo/opendbc/safety/tests/test_toyota.py b/opendbc_repo/opendbc/safety/tests/test_toyota.py index dcca1eb856..3edbe1ebf4 100755 --- a/opendbc_repo/opendbc/safety/tests/test_toyota.py +++ b/opendbc_repo/opendbc/safety/tests/test_toyota.py @@ -21,7 +21,7 @@ TOYOTA_COMMON_LONG_TX_MSGS = [[0x283, 0], [0x2E6, 0], [0x2E7, 0], [0x33E, 0], [0 class TestToyotaSafetyBase(common.PandaCarSafetyTest, common.LongitudinalAccelSafetyTest): TX_MSGS = TOYOTA_COMMON_TX_MSGS + TOYOTA_COMMON_LONG_TX_MSGS - RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x343)} + RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x191, 0x412, 0x343)} FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191, 0x343]} EPS_SCALE = 73 @@ -124,16 +124,14 @@ class TestToyotaSafetyTorque(TestToyotaSafetyBase, common.MotorTorqueSteeringSaf MAX_RATE_UP = 15 MAX_RATE_DOWN = 25 - MAX_TORQUE = 1500 + MAX_TORQUE_LOOKUP = [0], [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") @@ -269,7 +267,7 @@ class TestToyotaStockLongitudinalBase(TestToyotaSafetyBase): TX_MSGS = TOYOTA_COMMON_TX_MSGS # Base addresses minus ACC_CONTROL (0x343) - RELAY_MALFUNCTION_ADDRS = {0: (0x2E4,)} + RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x191, 0x412)} FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191]} LONGITUDINAL = False @@ -314,8 +312,8 @@ class TestToyotaStockLongitudinalAngle(TestToyotaStockLongitudinalBase, TestToyo class TestToyotaSecOcSafety(TestToyotaStockLongitudinalBase): TX_MSGS = TOYOTA_SECOC_TX_MSGS - RELAY_MALFUNCTION_ADDRS = {0: (0x2E4,)} - FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191, 0x131]} + RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x191, 0x412, 0x131)} + FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x191, 0x412, 0x131]} def setUp(self): self.packer = CANPackerPanda("toyota_secoc_pt_generated") diff --git a/opendbc_repo/opendbc/safety/tests/test_volkswagen_mqb.py b/opendbc_repo/opendbc/safety/tests/test_volkswagen_mqb.py index de47b5eab0..92d659f4ce 100755 --- a/opendbc_repo/opendbc/safety/tests/test_volkswagen_mqb.py +++ b/opendbc_repo/opendbc/safety/tests/test_volkswagen_mqb.py @@ -24,13 +24,12 @@ MSG_LDW_02 = 0x397 # TX by OP, Lane line recognition and text alerts class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01,)} + RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01, MSG_LDW_02), 2: (MSG_LH_EPS_03,)} MAX_RATE_UP = 4 MAX_RATE_DOWN = 10 - MAX_TORQUE = 300 + MAX_TORQUE_LOOKUP = [0], [300] MAX_RT_DELTA = 75 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 80 DRIVER_TORQUE_FACTOR = 3 @@ -133,7 +132,7 @@ class TestVolkswagenMqbStockSafety(TestVolkswagenMqbSafetyBase): FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02]} def setUp(self): - self.packer = CANPackerPanda("vw_mqb_2010") + self.packer = CANPackerPanda("vw_mqb") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagen, 0) self.safety.init_tests() @@ -151,10 +150,11 @@ class TestVolkswagenMqbStockSafety(TestVolkswagenMqbSafetyBase): class TestVolkswagenMqbLongSafety(TestVolkswagenMqbSafetyBase): 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]} + RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01, MSG_LDW_02, MSG_ACC_02, MSG_ACC_06, MSG_ACC_07), 2: (MSG_LH_EPS_03,)} INACTIVE_ACCEL = 3.01 def setUp(self): - self.packer = CANPackerPanda("vw_mqb_2010") + self.packer = CANPackerPanda("vw_mqb") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagen, VolkswagenSafetyFlags.LONG_CONTROL) self.safety.init_tests() diff --git a/opendbc_repo/opendbc/safety/tests/test_volkswagen_pq.py b/opendbc_repo/opendbc/safety/tests/test_volkswagen_pq.py index cc9e87df49..22b897d9a0 100755 --- a/opendbc_repo/opendbc/safety/tests/test_volkswagen_pq.py +++ b/opendbc_repo/opendbc/safety/tests/test_volkswagen_pq.py @@ -22,13 +22,12 @@ MSG_LDW_1 = 0x5BE # TX by OP, Lane line recognition and text alerts class TestVolkswagenPqSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): cruise_engaged = False - RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1,)} + RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1, MSG_LDW_1)} MAX_RATE_UP = 6 MAX_RATE_DOWN = 10 - MAX_TORQUE = 300 + MAX_TORQUE_LOOKUP = [0], [300] MAX_RT_DELTA = 113 - RT_INTERVAL = 250000 DRIVER_TORQUE_ALLOWANCE = 80 DRIVER_TORQUE_FACTOR = 3 @@ -116,7 +115,7 @@ class TestVolkswagenPqStockSafety(TestVolkswagenPqSafetyBase): FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1]} def setUp(self): - self.packer = CANPackerPanda("vw_golf_mk4") + self.packer = CANPackerPanda("vw_pq") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagenPq, 0) self.safety.init_tests() @@ -134,10 +133,11 @@ class TestVolkswagenPqStockSafety(TestVolkswagenPqSafetyBase): class TestVolkswagenPqLongSafety(TestVolkswagenPqSafetyBase, 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]} + RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1, MSG_LDW_1, MSG_ACC_SYSTEM, MSG_ACC_GRA_ANZEIGE)} INACTIVE_ACCEL = 3.01 def setUp(self): - self.packer = CANPackerPanda("vw_golf_mk4") + self.packer = CANPackerPanda("vw_pq") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagenPq, VolkswagenSafetyFlags.LONG_CONTROL) self.safety.init_tests() diff --git a/opendbc_repo/pyproject.toml b/opendbc_repo/pyproject.toml index 8d561ab167..d923f39fdd 100644 --- a/opendbc_repo/pyproject.toml +++ b/opendbc_repo/pyproject.toml @@ -9,7 +9,7 @@ requires-python = ">=3.9,<3.13" # pycapnp doesn't work with 3.13 urls = { "homepage" = "https://github.com/commaai/opendbc" } -# setuptools includes distutils which is needed by Cython and pre-commit. +# setuptools includes distutils which is needed by Cython. # distutils was removed in python3.12 from the standard library. dependencies = [ "scons", @@ -25,7 +25,6 @@ dependencies = [ [project.optional-dependencies] testing = [ "cffi", - "ruff", "gcovr", "pytest", "pytest-coverage", @@ -35,7 +34,14 @@ testing = [ "pytest-subtests", "hypothesis==6.47.*", "parameterized>=0.8,<0.9", - "pre-commit", + + # static analysis + "ruff", + "ty", + "lefthook", + "cpplint", + "cython-lint", + "codespell", ] docs = [ "Jinja2", @@ -119,3 +125,9 @@ flake8-implicit-str-concat.allow-multiline=false "pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" # TODO: re-enable when all tests are converted to pytest #"unittest".msg = "Use pytest" + +[tool.setuptools] +include-package-data = true + +[tool.setuptools.package-data] +"opendbc.safety" = ["*.h", "board/*.h", "board/drivers/*.h", "modes/*.h"] diff --git a/opendbc_repo/setup.sh b/opendbc_repo/setup.sh index 732a118183..29c5bf2cd1 100755 --- a/opendbc_repo/setup.sh +++ b/opendbc_repo/setup.sh @@ -15,3 +15,5 @@ fi export UV_PROJECT_ENVIRONMENT="$BASEDIR/.venv" uv sync --all-extras source "$PYTHONPATH/.venv/bin/activate" + +$BASEDIR/opendbc/safety/tests/misra/install.sh diff --git a/opendbc_repo/test.sh b/opendbc_repo/test.sh index da9377134a..d91afb0356 100755 --- a/opendbc_repo/test.sh +++ b/opendbc_repo/test.sh @@ -9,13 +9,8 @@ source ./setup.sh # *** build *** scons -j8 -# *** lint *** -# TODO: pre-commit is slow; replace it with openpilot's "op lint" -#pre-commit run --all-files -ruff check . - -# *** test *** -pytest -n8 --ignore opendbc/safety +# *** lint + test *** +lefthook run test # *** all done *** GREEN='\033[0;32m' diff --git a/panda/.gitignore b/panda/.gitignore index 89eed6e4c5..378d327f62 100644 --- a/panda/.gitignore +++ b/panda/.gitignore @@ -1,3 +1,4 @@ +.venv *.tmp *.pyc .*.swp @@ -20,6 +21,7 @@ examples/output.csv nosetests.xml .mypy_cache/ .sconsign.dblite +uv.lock # CTU info files generated by Cppcheck *.*.ctu-info diff --git a/panda/.pre-commit-config.yaml b/panda/.pre-commit-config.yaml deleted file mode 100644 index 31ebf6ecfb..0000000000 --- a/panda/.pre-commit-config.yaml +++ /dev/null @@ -1,20 +0,0 @@ -repos: -- repo: https://github.com/pre-commit/pre-commit-hooks - rev: v5.0.0 - hooks: - - id: check-ast - - id: check-yaml - - id: check-merge-conflict - - id: check-symlinks - - id: check-executables-have-shebangs - - id: check-shebang-scripts-are-executable -- repo: https://github.com/pre-commit/mirrors-mypy - rev: v1.15.0 - hooks: - - id: mypy - additional_dependencies: ['numpy', 'types-requests', 'types-atomicwrites', - 'types-pycurl'] -- repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.9.9 - hooks: - - id: ruff diff --git a/panda/Dockerfile b/panda/Dockerfile index 816a9b80e3..88190b084c 100644 --- a/panda/Dockerfile +++ b/panda/Dockerfile @@ -3,47 +3,17 @@ FROM ubuntu:24.04 ENV PYTHONUNBUFFERED=1 ENV PYTHONPATH=/tmp/pythonpath +# deps install +COPY pyproject.toml __init__.py setup.sh /tmp/ +COPY python/__init__.py /tmp/python/ ENV DEBIAN_FRONTEND=noninteractive -RUN apt-get update && apt-get install -y --no-install-recommends \ - make \ - g++ \ - gcc-arm-none-eabi libnewlib-arm-none-eabi \ - git \ - libffi-dev \ - libusb-1.0-0 \ - python3 \ - python3-dev \ - python3-pip \ - && rm -rf /var/lib/apt/lists/* && \ - apt clean && \ - cd /usr/lib/gcc/arm-none-eabi/* && \ - rm -rf arm/ && \ - rm -rf thumb/nofp thumb/v6* thumb/v8* thumb/v7+fp thumb/v7-r+fp.sp && \ - apt-get update && apt-get install -y clang-17 && \ - ln -s $(which clang-17) /usr/bin/clang +RUN apt-get update && apt-get install -y --no-install-recommends sudo && /tmp/setup.sh -RUN apt-get update && apt-get install -y curl && \ - curl -1sLf 'https://dl.cloudsmith.io/public/mull-project/mull-stable/setup.deb.sh' | bash && \ - apt-get update && apt-get install -y mull-17 - -ENV CPPCHECK_DIR=/tmp/cppcheck -COPY tests/misra/install.sh /tmp/ -RUN /tmp/install.sh && rm -rf $CPPCHECK_DIR/.git/ -ENV SKIP_CPPCHECK_INSTALL=1 - -COPY setup.py __init__.py $PYTHONPATH/panda/ +COPY pyproject.toml __init__.py $PYTHONPATH/panda/ COPY python/__init__.py $PYTHONPATH/panda/python/ RUN pip3 install --break-system-packages --no-cache-dir $PYTHONPATH/panda/[dev] -# TODO: this should be a "pip install" or not even in this repo at all RUN git config --global --add safe.directory $PYTHONPATH/panda -ENV OPENDBC_REF="da0a5e3d2b3984b56ebf5e25d9769f5c77807e4d" -RUN cd /tmp/ && \ - git clone --depth 1 https://github.com/commaai/opendbc opendbc_repo && \ - cd opendbc_repo && git fetch origin $OPENDBC_REF && git checkout FETCH_HEAD && rm -rf .git/ && \ - pip3 install --break-system-packages --no-cache-dir Cython numpy pycapnp && \ - ln -s $PWD/opendbc $PYTHONPATH/opendbc && \ - scons -j8 --minimal opendbc/ # for Jenkins COPY README.md panda.tar.* /tmp/ diff --git a/panda/Jenkinsfile b/panda/Jenkinsfile index 64429b7756..a771ff53bd 100644 --- a/panda/Jenkinsfile +++ b/panda/Jenkinsfile @@ -106,7 +106,7 @@ pipeline { steps { phone_steps("panda-tres", [ ["build", "scons -j4"], - ["flash", "cd tests/ && ./reflash_internal_panda.py"], + ["flash", "cd scripts/ && ./reflash_internal_panda.py"], ["flash jungle", "cd board/jungle && ./flash.py --all"], ["test", "cd tests/hitl && HW_TYPES=9 pytest -n0 --durations=0 2*.py [5-9]*.py"], ]) @@ -118,7 +118,7 @@ pipeline { steps { phone_steps("panda-dos", [ ["build", "scons -j4"], - ["flash", "cd tests/ && ./reflash_internal_panda.py"], + ["flash", "cd scripts/ && ./reflash_internal_panda.py"], ["flash jungle", "cd board/jungle && ./flash.py --all"], ["test", "cd tests/hitl && HW_TYPES=6 pytest -n0 --durations=0 [2-9]*.py -k 'not test_send_recv'"], ]) diff --git a/panda/README.md b/panda/README.md index 8952175677..7b0a66f1fa 100644 --- a/panda/README.md +++ b/panda/README.md @@ -1,8 +1,5 @@ # Welcome to panda -![panda tests](https://github.com/commaai/panda/workflows/tests/badge.svg) -![panda drivers](https://github.com/commaai/panda/workflows/drivers/badge.svg) - panda speaks CAN and CAN FD, and it runs on [STM32F413](https://www.st.com/resource/en/reference_manual/rm0430-stm32f413423-advanced-armbased-32bit-mcus-stmicroelectronics.pdf) and [STM32H725](https://www.st.com/resource/en/reference_manual/rm0468-stm32h723733-stm32h725735-and-stm32h730-value-line-advanced-armbased-32bit-mcus-stmicroelectronics.pdf). ## Directory structure @@ -12,7 +9,9 @@ panda speaks CAN and CAN FD, and it runs on [STM32F413](https://www.st.com/resou ├── board # Code that runs on the STM32 ├── drivers # Drivers (not needed for use with Python) ├── python # Python userspace library for interfacing with the panda -├── tests # Tests and helper programs for panda +├── tests # Tests for panda +├── scripts # Miscellaneous used for panda development and debugging +├── examples # Example scripts for using a panda in a car ``` ## Safety Model @@ -43,26 +42,15 @@ In addition, we run the [ruff linter](https://github.com/astral-sh/ruff) and [my ## Usage -Setup dependencies: ```bash -# Ubuntu -sudo apt-get install dfu-util gcc-arm-none-eabi python3-pip libffi-dev git clang-17 - -# macOS -brew install --cask gcc-arm-embedded -brew install python3 dfu-util gcc@13 -``` - -Clone panda repository and install: -``` bash git clone https://github.com/commaai/panda.git cd panda -# install dependencies -pip install -e .[dev] +# setup your environment +./setup.sh -# install panda -python setup.py install +# build fw + run the tests +./test.sh ``` See [the Panda class](https://github.com/commaai/panda/blob/master/python/__init__.py) for how to interact with the panda. @@ -95,11 +83,8 @@ The panda jungle uses different udev rules. See [the repo](https://github.com/co ## Software interface support -As a universal car interface, it should support every reasonable software interface. - - [Python library](https://github.com/commaai/panda/tree/master/python) - [C++ library](https://github.com/commaai/openpilot/tree/master/selfdrive/pandad) -- [socketcan in kernel](https://github.com/commaai/panda/tree/master/drivers/linux) (alpha) ## Licensing diff --git a/panda/SConscript b/panda/SConscript index f617410b43..1a4c875b2b 100644 --- a/panda/SConscript +++ b/panda/SConscript @@ -1,7 +1,7 @@ import os +import opendbc import subprocess - PREFIX = "arm-none-eabi-" BUILDER = "DEV" @@ -84,7 +84,7 @@ def build_project(project_name, project, extra_flags): '..', panda_root, f"{panda_root}/board/", - f"{panda_root}/../opendbc/safety/", + opendbc.INCLUDE_PATH, ] env = Environment( diff --git a/panda/SConstruct b/panda/SConstruct index 11ff21738e..f8a089b6a9 100644 --- a/panda/SConstruct +++ b/panda/SConstruct @@ -8,25 +8,17 @@ AddOption('--ubsan', action='store_true', help='turn on UBSan') -AddOption('--coverage', - action='store_true', - help='build with test coverage options') - AddOption('--compile_db', action='store_true', help='build clang compilation database') -AddOption('--mutation', - action='store_true', - help='generate mutation-ready code') - env = Environment( COMPILATIONDB_USE_ABSPATH=True, tools=["default", "compilation_db"], ) - + if GetOption('compile_db'): - env.CompilationDatabase("compile_commands.json") + env.CompilationDatabase("compile_commands.json") # panda fw & test files SConscript('SConscript') diff --git a/panda/__init__.py b/panda/__init__.py index f5a00d9ae5..12fbe3a7c5 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -6,6 +6,5 @@ from .python import (Panda, PandaDFU, # noqa: F401 pack_can_buffer, unpack_can_buffer, calculate_checksum, DLC_TO_LEN, LEN_TO_DLC, CANPACKET_HEAD_SIZE) - # panda jungle from .board.jungle import PandaJungle, PandaJungleDFU # noqa: F401 diff --git a/panda/board/README.md b/panda/board/README.md index ab3d59d3e8..558beae78f 100644 --- a/panda/board/README.md +++ b/panda/board/README.md @@ -17,4 +17,4 @@ If panda is blinking fast with green LED, use `flash.py`. Otherwise if LED is off and panda can't be seen with `lsusb` command, use [panda paw](https://comma.ai/shop/products/panda-paw) to go into DFU mode. -If your device has an internal panda and none of the above works, try running `../tests/reflash_internal_panda.py`. +If your device has an internal panda and none of the above works, try running `../scripts/reflash_internal_panda.py`. diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index 133c11fb2d..3f198179e0 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -26,33 +26,6 @@ static void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -static 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); - } - } -} - -static 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; - } -} - static void black_set_usb_load_switch(bool enabled) { set_gpio_output(GPIOB, 1, !enabled); } @@ -102,41 +75,12 @@ static void black_init(void) { 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(); - - - // 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); } static void black_init_bootloader(void) { @@ -162,7 +106,6 @@ static harness_configuration black_harness_config = { board board_black = { .set_bootkick = unused_set_bootkick, .harness_config = &black_harness_config, - .has_obd = true, .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, @@ -173,8 +116,8 @@ board board_black = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .set_can_mode = black_set_can_mode, .check_ignition = black_check_ignition, .read_voltage_mV = white_read_voltage_mV, diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h index 61e9ce2d8e..f96812e9ba 100644 --- a/panda/board/boards/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -13,8 +13,6 @@ typedef enum { 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); @@ -28,7 +26,8 @@ typedef void (*board_set_amp_enabled)(bool enabled); struct board { harness_configuration *harness_config; - const bool has_obd; + GPIO_TypeDef * const led_GPIO[3]; + const uint8_t led_pin[3]; const bool has_spi; const bool has_canfd; const uint16_t fan_max_rpm; @@ -39,8 +38,6 @@ struct board { 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; @@ -67,11 +64,6 @@ struct board { #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 diff --git a/panda/board/boards/cuatro.h b/panda/board/boards/cuatro.h index 3d630f022e..d9e219c020 100644 --- a/panda/board/boards/cuatro.h +++ b/panda/board/boards/cuatro.h @@ -6,22 +6,6 @@ // Cuatro (STM32H7) + Harness // // ////////////////////////// // -static void cuatro_set_led(uint8_t color, bool enabled) { - switch (color) { - case LED_RED: - set_gpio_output(GPIOC, 6, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 9, !enabled); - break; - default: - break; - } -} - static void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { case 1U: @@ -41,18 +25,6 @@ static void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -static 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); - } - } -} - static uint32_t cuatro_read_voltage_mV(void) { return adc_get_mV(8) * 11U; } @@ -68,7 +40,7 @@ static void cuatro_set_fan_enabled(bool enabled) { static void cuatro_set_bootkick(BootState state) { set_gpio_output(GPIOA, 0, state != BOOT_BOOTKICK); // TODO: confirm we need this - set_gpio_output(GPIOC, 12, state != BOOT_RESET); + //set_gpio_output(GPIOC, 12, state != BOOT_RESET); } static void cuatro_set_amp_enabled(bool enabled){ @@ -76,14 +48,9 @@ static void cuatro_set_amp_enabled(bool enabled){ } static void cuatro_init(void) { - red_chiplet_init(); - - // init LEDs as open drain - set_gpio_output_type(GPIOC, 6, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output_type(GPIOC, 7, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output_type(GPIOC, 9, OUTPUT_TYPE_OPEN_DRAIN); + common_init_gpio(); - // more open drain + // open drain set_gpio_output_type(GPIOD, 3, OUTPUT_TYPE_OPEN_DRAIN); // FAN_EN set_gpio_output_type(GPIOC, 12, OUTPUT_TYPE_OPEN_DRAIN); // VBAT_EN @@ -114,9 +81,6 @@ static void cuatro_init(void) { 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); register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT8); // open drain @@ -127,7 +91,7 @@ static void cuatro_init(void) { tres_set_ir_power(0U); // Clock source - clock_source_init(); + clock_source_init(true); // Sound codec cuatro_set_amp_enabled(false); @@ -141,9 +105,22 @@ static void cuatro_init(void) { sound_init(); } +static harness_configuration cuatro_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 = 9, + .pin_relay_SBU2 = 3, + .adc_channel_SBU1 = 4, // ADC12_INP4 + .adc_channel_SBU2 = 17 // ADC1_INP17 +}; + board board_cuatro = { - .harness_config = &red_chiplet_harness_config, - .has_obd = true, + .harness_config = &cuatro_harness_config, .has_spi = true, .has_canfd = true, .fan_max_rpm = 12500U, @@ -154,9 +131,9 @@ board board_cuatro = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {6, 7, 9}, + .set_can_mode = tres_set_can_mode, .check_ignition = red_check_ignition, .read_voltage_mV = cuatro_read_voltage_mV, .read_current_mA = cuatro_read_current_mA, diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index d96cee4ca4..661f91fb75 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -26,33 +26,6 @@ static void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -static 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); - } - } -} - -static 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; - } -} - static void dos_set_bootkick(BootState state) { set_gpio_output(GPIOC, 4, state != BOOT_BOOTKICK); } @@ -117,25 +90,6 @@ static void dos_init(void) { 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); @@ -148,26 +102,11 @@ static void dos_init(void) { pwm_init(TIM4, 2); dos_set_ir_power(0U); - // Initialize harness - harness_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); - // Init clock source (camera strobe) using PWM - clock_source_init(); + clock_source_init(false); } static harness_configuration dos_harness_config = { @@ -186,7 +125,6 @@ static harness_configuration dos_harness_config = { board board_dos = { .harness_config = &dos_harness_config, - .has_obd = true, #ifdef ENABLE_SPI .has_spi = true, #else @@ -201,8 +139,8 @@ board board_dos = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .set_can_mode = dos_set_can_mode, .check_ignition = dos_check_ignition, .read_voltage_mV = white_read_voltage_mV, diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index b3e40bc6fe..6ba07b4d0d 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -11,7 +11,6 @@ board board_grey = { .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, - .has_obd = false, .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, @@ -22,8 +21,8 @@ board board_grey = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .set_can_mode = white_set_can_mode, .check_ignition = white_check_ignition, .read_voltage_mV = white_read_voltage_mV, diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h index f1d8d9c44b..9871f959d8 100644 --- a/panda/board/boards/red.h +++ b/panda/board/boards/red.h @@ -25,34 +25,6 @@ static void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -static 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); - } - } -} - -static 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; - } -} - static void red_set_can_mode(uint8_t mode) { red_enable_can_transceiver(2U, false); red_enable_can_transceiver(4U, false); @@ -107,17 +79,6 @@ static uint32_t red_read_voltage_mV(void){ static 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); @@ -140,21 +101,6 @@ static void red_init(void) { set_gpio_pullup(GPIOB, 14, PULL_UP); set_gpio_mode(GPIOB, 14, MODE_OUTPUT); set_gpio_output(GPIOB, 14, 1); - - // Initialize harness - harness_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); } static harness_configuration red_harness_config = { @@ -174,7 +120,6 @@ static harness_configuration red_harness_config = { board board_red = { .set_bootkick = unused_set_bootkick, .harness_config = &red_harness_config, - .has_obd = true, .has_spi = false, .has_canfd = true, .fan_max_rpm = 0U, @@ -185,8 +130,8 @@ board board_red = { .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, + .led_GPIO = {GPIOE, GPIOE, GPIOE}, + .led_pin = {4, 3, 2}, .set_can_mode = red_set_can_mode, .check_ignition = red_check_ignition, .read_voltage_mV = red_read_voltage_mV, diff --git a/panda/board/boards/red_chiplet.h b/panda/board/boards/red_chiplet.h deleted file mode 100644 index e5d1aa097f..0000000000 --- a/panda/board/boards/red_chiplet.h +++ /dev/null @@ -1,151 +0,0 @@ -#pragma once - -#include "board_declarations.h" - -// ///////////////////////////////////// // -// Red Panda chiplet (STM32H7) + Harness // -// ///////////////////////////////////// // - -// Most hardware functionality is similar to red panda - -static 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; - } -} - -static 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); - } - } -} - -static 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; - } -} - -static void red_chiplet_set_fan_or_usb_load_switch(bool enabled) { - set_gpio_output(GPIOD, 3, enabled); -} - -static 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(); - - - // 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); -} - -static 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 index f0602ae60b..811314a5bb 100644 --- a/panda/board/boards/tres.h +++ b/panda/board/boards/tres.h @@ -9,7 +9,7 @@ static bool tres_ir_enabled; static bool tres_fan_enabled; static void tres_update_fan_ir_power(void) { - red_chiplet_set_fan_or_usb_load_switch(tres_ir_enabled || tres_fan_enabled); + set_gpio_output(GPIOD, 3, tres_ir_enabled || tres_fan_enabled); } static void tres_set_ir_power(uint8_t percentage){ @@ -29,6 +29,67 @@ static void tres_set_fan_enabled(bool enabled) { tres_update_fan_ir_power(); } +static void tres_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; + } +} + +static void tres_set_can_mode(uint8_t mode) { + current_board->enable_can_transceiver(2U, false); + current_board->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); + current_board->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); + current_board->enable_can_transceiver(4U, true); + } + break; + default: + break; + } +} + static bool tres_read_som_gpio (void) { return (get_gpio_input(GPIOC, 2) != 0); } @@ -39,7 +100,7 @@ static void tres_init(void) { register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); while ((PWR->CR3 & PWR_CR3_USB33RDY) == 0U); - red_chiplet_init(); + common_init_gpio(); // C2: SOM GPIO used as input (fan control at boot) set_gpio_mode(GPIOC, 2, MODE_INPUT); @@ -54,9 +115,6 @@ static void tres_init(void) { 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); @@ -71,12 +129,25 @@ static void tres_init(void) { register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT10 | GPIO_OTYPER_OT11); // open drain // Clock source - clock_source_init(); + clock_source_init(false); } +static harness_configuration tres_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 +}; + board board_tres = { - .harness_config = &red_chiplet_harness_config, - .has_obd = true, + .harness_config = &tres_harness_config, .has_spi = true, .has_canfd = true, .fan_max_rpm = 6600U, @@ -86,10 +157,10 @@ board board_tres = { .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, + .enable_can_transceiver = tres_enable_can_transceiver, + .led_GPIO = {GPIOE, GPIOE, GPIOE}, + .led_pin = {4, 3, 2}, + .set_can_mode = tres_set_can_mode, .check_ignition = red_check_ignition, .read_voltage_mV = red_read_voltage_mV, .read_current_mA = unused_read_current, diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index d1728f1f9f..fd71460a6e 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -26,33 +26,6 @@ static void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -static 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); - } - } -} - -static 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; - } -} - static void uno_set_bootkick(BootState state) { if (state == BOOT_BOOTKICK) { set_gpio_output(GPIOB, 14, false); @@ -118,25 +91,11 @@ static void uno_init(void) { 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); @@ -148,21 +107,6 @@ static void uno_init(void) { pwm_init(TIM4, 2); uno_set_ir_power(0U); - // Initialize harness - harness_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); - // 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); @@ -197,7 +141,6 @@ static harness_configuration uno_harness_config = { board board_uno = { .harness_config = &uno_harness_config, - .has_obd = true, .has_spi = false, .has_canfd = false, .fan_max_rpm = 5100U, @@ -208,8 +151,8 @@ board board_uno = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .set_can_mode = uno_set_can_mode, .check_ignition = uno_check_ignition, .read_voltage_mV = white_read_voltage_mV, diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index c4a2559353..5f43dda6d3 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -17,30 +17,6 @@ static void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { case 3U: set_gpio_output(GPIOA, 0, !enabled); break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -static 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); - } -} - -static 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; } @@ -152,18 +128,6 @@ static void white_grey_init(void) { set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); set_gpio_pullup(GPIOC, 11, PULL_UP); - - // 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 @@ -191,7 +155,6 @@ static harness_configuration white_harness_config = { board board_white = { .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, - .has_obd = false, .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, @@ -202,8 +165,8 @@ board board_white = { .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, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .set_can_mode = white_set_can_mode, .check_ignition = white_check_ignition, .read_voltage_mV = white_read_voltage_mV, diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c index aee665e7e0..5e05fa66d7 100644 --- a/panda/board/bootstub.c +++ b/panda/board/bootstub.c @@ -6,6 +6,7 @@ // ********************* Includes ********************* #include "config.h" +#include "drivers/led.h" #include "drivers/pwm.h" #include "drivers/usb.h" diff --git a/panda/board/crc.h b/panda/board/crc.h index 3e20fb0981..a3caf785de 100644 --- a/panda/board/crc.h +++ b/panda/board/crc.h @@ -1,5 +1,6 @@ #pragma once +#if defined(ENABLE_SPI) || defined(BOOTSTUB) uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) { uint8_t crc = 0xFFU; int i; @@ -17,3 +18,4 @@ uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) { } return crc; } +#endif diff --git a/panda/board/drivers/bxcan.h b/panda/board/drivers/bxcan.h index 721a7ee492..75bd05d50c 100644 --- a/panda/board/drivers/bxcan.h +++ b/panda/board/drivers/bxcan.h @@ -178,7 +178,7 @@ void can_rx(uint8_t can_number) { safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U; ignition_can_hook(&to_push); - current_board->set_led(LED_BLUE, true); + led_set(LED_BLUE, true); rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U; // next diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h index eeaf87384e..fd2cfad465 100644 --- a/panda/board/drivers/can_common.h +++ b/panda/board/drivers/can_common.h @@ -166,9 +166,6 @@ void ignition_can_hook(CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); - // Check counter position on cars with overlap - static int prev_counter = -1; - // GM exception if ((addr == 0x1F1) && (len == 8)) { // SystemPowerMode (2=Run, 3=Crank Request) @@ -181,12 +178,13 @@ void ignition_can_hook(CANPacket_t *to_push) { // 0x152 overlaps with Subaru pre-global which has this bit as the high beam int counter = GET_BYTE(to_push, 1) & 0xFU; // max is only 14 - if ((counter == ((prev_counter + 1) % 15)) && (prev_counter != -1)) { + static int prev_counter_rivian = -1; + if ((counter == ((prev_counter_rivian + 1) % 15)) && (prev_counter_rivian != -1)) { // VDM_OutputSignals->VDM_EpasPowerMode ignition_can = ((GET_BYTE(to_push, 7) >> 4U) & 0x3U) == 1U; // VDM_EpasPowerMode_Drive_On=1 ignition_can_cnt = 0U; } - prev_counter = counter; + prev_counter_rivian = counter; } // Tesla Model 3/Y exception @@ -194,13 +192,14 @@ void ignition_can_hook(CANPacket_t *to_push) { // 0x221 overlaps with Rivian which has random data on byte 0 int counter = GET_BYTE(to_push, 6) >> 4; - if ((counter == ((prev_counter + 1) % 16)) && (prev_counter != -1)) { + static int prev_counter_tesla = -1; + if ((counter == ((prev_counter_tesla + 1) % 16)) && (prev_counter_tesla != -1)) { // VCFRONT_LVPowerState->VCFRONT_vehiclePowerState int power_state = (GET_BYTE(to_push, 0) >> 5U) & 0x3U; ignition_can = power_state == 0x3; // VEHICLE_POWER_STATE_DRIVE=3 ignition_can_cnt = 0U; } - prev_counter = counter; + prev_counter_tesla = counter; } // Mazda exception diff --git a/panda/board/drivers/clock_source.h b/panda/board/drivers/clock_source.h index 18d12d579a..9fb818aade 100644 --- a/panda/board/drivers/clock_source.h +++ b/panda/board/drivers/clock_source.h @@ -4,7 +4,7 @@ void clock_source_set_period(uint8_t period) { register_set(&(TIM1->ARR), ((period*10U) - 1U), 0xFFFFU); } -void clock_source_init(void) { +void clock_source_init(bool enable_channel1) { // 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 @@ -21,11 +21,14 @@ void clock_source_init(void) { NVIC_DisableIRQ(TIM1_CC_IRQn); // Set GPIO as timer channels + if (enable_channel1) { + set_gpio_alternate(GPIOA, 8, GPIO_AF1_TIM1); + } set_gpio_alternate(GPIOB, 14, GPIO_AF1_TIM1); set_gpio_alternate(GPIOB, 15, GPIO_AF1_TIM1); // Set PWM mode - register_set(&(TIM1->CCMR1), (0b110UL << TIM_CCMR1_OC2M_Pos), 0xFFFFU); + register_set(&(TIM1->CCMR1), (0b110UL << TIM_CCMR1_OC1M_Pos) | (0b110UL << TIM_CCMR1_OC2M_Pos), 0xFFFFU); register_set(&(TIM1->CCMR2), (0b110UL << TIM_CCMR2_OC3M_Pos), 0xFFFFU); // Enable output diff --git a/panda/board/drivers/clock_source_declarations.h b/panda/board/drivers/clock_source_declarations.h index 013f75303a..b230b4d665 100644 --- a/panda/board/drivers/clock_source_declarations.h +++ b/panda/board/drivers/clock_source_declarations.h @@ -4,4 +4,4 @@ #define CLOCK_SOURCE_PULSE_LEN_MS 2U void clock_source_set_period(uint8_t period); -void clock_source_init(void); +void clock_source_init(bool enable_channel1); diff --git a/panda/board/drivers/fan.h b/panda/board/drivers/fan.h index daadd23833..ec0e1be5fa 100644 --- a/panda/board/drivers/fan.h +++ b/panda/board/drivers/fan.h @@ -19,7 +19,7 @@ void fan_init(void) { // Call this at FAN_TICK_FREQ void fan_tick(void) { - const float FAN_I = 0.001f; + const float FAN_I = 6.5f; const uint8_t FAN_STALL_THRESHOLD_MAX = 8U; if (current_board->fan_max_rpm > 0U) { @@ -33,7 +33,7 @@ void fan_tick(void) { 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); + fan_state.stall_counter = MIN(fan_state.stall_counter + 1U, 254U); } else { fan_state.stall_counter = 0U; } @@ -74,10 +74,11 @@ void fan_tick(void) { if (fan_state.target_rpm == 0U) { fan_state.error_integral = 0.0f; } else { - float error = fan_state.target_rpm - fan_rpm_fast; + float error = (fan_state.target_rpm - fan_rpm_fast) / ((float) current_board->fan_max_rpm); fan_state.error_integral += FAN_I * error; } - fan_state.power = CLAMP(fan_state.error_integral, 0U, current_board->fan_max_pwm); + fan_state.error_integral = CLAMP(fan_state.error_integral, 0U, current_board->fan_max_pwm); + fan_state.power = fan_state.error_integral; // Set PWM and enable line pwm_set(TIM3, 3, fan_state.power); diff --git a/panda/board/drivers/fdcan.h b/panda/board/drivers/fdcan.h index 2f032d03bd..f3f8d99723 100644 --- a/panda/board/drivers/fdcan.h +++ b/panda/board/drivers/fdcan.h @@ -223,7 +223,7 @@ void can_rx(uint8_t can_number) { safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U; ignition_can_hook(&to_push); - current_board->set_led(LED_BLUE, true); + led_set(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 diff --git a/panda/board/drivers/gpio.h b/panda/board/drivers/gpio.h index 0b8fc091b1..aea604254e 100644 --- a/panda/board/drivers/gpio.h +++ b/panda/board/drivers/gpio.h @@ -10,11 +10,6 @@ #define OUTPUT_TYPE_PUSH_PULL 0U #define OUTPUT_TYPE_OPEN_DRAIN 1U -typedef struct { - GPIO_TypeDef * const 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; @@ -68,6 +63,12 @@ int get_gpio_input(const GPIO_TypeDef *GPIO, unsigned int pin) { return (GPIO->IDR & (1UL << pin)) == (1UL << pin); } +#ifdef PANDA_JUNGLE +typedef struct { + GPIO_TypeDef * const bank; + uint8_t pin; +} gpio_t; + void gpio_set_all_output(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); @@ -79,6 +80,7 @@ void gpio_set_bitmask(gpio_t *pins, uint8_t num_pins, uint32_t bitmask) { set_gpio_output(pins[i].bank, pins[i].pin, (bitmask >> i) & 1U); } } +#endif // Detection with internal pullup #define PULL_EFFECTIVE_DELAY 4096 diff --git a/panda/board/drivers/harness.h b/panda/board/drivers/harness.h index cfb6965c03..1d8c580664 100644 --- a/panda/board/drivers/harness.h +++ b/panda/board/drivers/harness.h @@ -94,13 +94,14 @@ void harness_tick(void) { } void harness_init(void) { - // try to detect orientation + // init OBD_SBUx_RELAY + set_gpio_output_type(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output_type(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, 1); + set_gpio_output(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, 1); + + // detect initial 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/led.h b/panda/board/drivers/led.h new file mode 100644 index 0000000000..f67e4f9870 --- /dev/null +++ b/panda/board/drivers/led.h @@ -0,0 +1,20 @@ + +#define LED_RED 0U +#define LED_GREEN 1U +#define LED_BLUE 2U + +void led_set(uint8_t color, bool enabled) { + if (color < 3U) { + set_gpio_output(current_board->led_GPIO[color], current_board->led_pin[color], !enabled); + } +} + +void led_init(void) { + for (uint8_t i = 0U; i<3U; i++){ + set_gpio_pullup(current_board->led_GPIO[i], current_board->led_pin[i], PULL_NONE); + set_gpio_mode(current_board->led_GPIO[i], current_board->led_pin[i], MODE_OUTPUT); + set_gpio_output_type(current_board->led_GPIO[i], current_board->led_pin[i], OUTPUT_TYPE_OPEN_DRAIN); + + led_set(i, false); + } +} diff --git a/panda/board/drivers/registers.h b/panda/board/drivers/registers.h index 92b6b0faa2..ce4be14a92 100644 --- a/panda/board/drivers/registers.h +++ b/panda/board/drivers/registers.h @@ -49,13 +49,10 @@ void check_registers(void){ if((uint32_t) register_map[i].address != 0U){ ENTER_CRITICAL() if((*(register_map[i].address) & register_map[i].check_mask) != (register_map[i].value & register_map[i].check_mask)){ - #ifdef DEBUG_FAULTS - print("Register at address 0x"); puth((uint32_t) register_map[i].address); print(" is divergent!"); - print(" Map: 0x"); puth(register_map[i].value); - print(" Register: 0x"); puth(*(register_map[i].address)); - print(" Mask: 0x"); puth(register_map[i].check_mask); - print("\n"); - #endif + if(!register_map[i].logged_fault){ + print("Register 0x"); puth((uint32_t) register_map[i].address); print(" divergent! Map: 0x"); puth(register_map[i].value); print(" Reg: 0x"); puth(*(register_map[i].address)); print("\n"); + register_map[i].logged_fault = true; + } fault_occurred(FAULT_REGISTER_DIVERGENT); } EXIT_CRITICAL() diff --git a/panda/board/drivers/registers_declarations.h b/panda/board/drivers/registers_declarations.h index 13180117b4..90ee66df0d 100644 --- a/panda/board/drivers/registers_declarations.h +++ b/panda/board/drivers/registers_declarations.h @@ -4,6 +4,7 @@ typedef struct reg { volatile uint32_t *address; uint32_t value; uint32_t check_mask; + bool logged_fault; } reg; // 10 bit hash with 23 as a prime diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h index 36f4dd29aa..469243db2f 100644 --- a/panda/board/drivers/spi.h +++ b/panda/board/drivers/spi.h @@ -108,7 +108,9 @@ void spi_rx_done(void) { response_len = 1U; } else { // response: NACK and reset state machine - print("- incorrect header sync or checksum "); hexdump(spi_buf_rx, SPI_HEADER_SIZE); + #ifdef DEBUG_SPI + print("- incorrect header sync or checksum "); hexdump(spi_buf_rx, SPI_HEADER_SIZE); + #endif spi_buf_tx[0] = SPI_NACK; next_rx_state = SPI_STATE_HEADER_NACK; response_len = 1U; @@ -160,12 +162,14 @@ void spi_rx_done(void) { } 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"); + #ifdef DEBUG_SPI + 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"); + #endif } if (!response_ack) { diff --git a/panda/board/drivers/timers.h b/panda/board/drivers/timers.h index 49d9f5c4d1..4c046a2b49 100644 --- a/panda/board/drivers/timers.h +++ b/panda/board/drivers/timers.h @@ -17,7 +17,7 @@ uint32_t microsecond_timer_get(void) { void interrupt_timer_init(void) { enable_interrupt_timer(); - REGISTER_INTERRUPT(INTERRUPT_TIMER_IRQ, interrupt_timer_handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS) + REGISTER_INTERRUPT(INTERRUPT_TIMER_IRQ, interrupt_timer_handler, 2U, 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); diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index 737539c955..ee15999a86 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -145,10 +145,6 @@ void puth(unsigned int i) { puthx(i, 8U); } -void puth2(unsigned int i) { - puthx(i, 2U); -} - #if defined(ENABLE_SPI) || defined(BOOTSTUB) || defined(DEBUG) void puth4(unsigned int i) { puthx(i, 4U); @@ -160,7 +156,7 @@ 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]); + puthx(((const unsigned char*)a)[i], 2U); print(" "); } } diff --git a/panda/board/drivers/uart_declarations.h b/panda/board/drivers/uart_declarations.h index 041fd377c3..f2775d3f55 100644 --- a/panda/board/drivers/uart_declarations.h +++ b/panda/board/drivers/uart_declarations.h @@ -33,7 +33,6 @@ void putch(const char a); void print(const char *a); void puthx(uint32_t i, uint8_t len); void puth(unsigned int i); -void puth2(unsigned int i); #if defined(ENABLE_SPI) || defined(BOOTSTUB) || defined(DEBUG) void puth4(unsigned int i); #endif diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index 8fd3d8c41e..1f715feef0 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -538,21 +538,26 @@ void usb_irqhandler(void) { } if ((gintsts & USB_OTG_GINTSTS_USBRST) != 0U) { - print("USB reset\n"); + #ifdef DEBUG_USB + print("USB reset\n"); + #endif usb_reset(); } if ((gintsts & USB_OTG_GINTSTS_ENUMDNE) != 0U) { - print("enumeration done"); + #ifdef DEBUG_USB + print("enumeration done\n"); + #endif // Full speed, ENUMSPD //puth(USBx_DEVICE->DSTS); - print("\n"); } if ((gintsts & USB_OTG_GINTSTS_OTGINT) != 0U) { - print("OTG int:"); - puth(USBx->GOTGINT); - print("\n"); + #ifdef DEBUG_USB + print("OTG int:"); + puth(USBx->GOTGINT); + print("\n"); + #endif // getting ADTOCHG //USBx->GOTGINT = USBx->GOTGINT; diff --git a/panda/board/drivers/watchdog.h b/panda/board/drivers/watchdog.h deleted file mode 100644 index 51337ba6ef..0000000000 --- a/panda/board/drivers/watchdog.h +++ /dev/null @@ -1,24 +0,0 @@ -typedef enum { - WATCHDOG_50_MS = (400U - 1U), - WATCHDOG_500_MS = 4000U, -} WatchdogTimeout; - -static 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 index 1837019d09..e48a80637a 100644 --- a/panda/board/early_init.h +++ b/panda/board/early_init.h @@ -56,10 +56,11 @@ void early_initialization(void) { detect_board_type(); if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { + led_init(); #ifdef PANDA current_board->init_bootloader(); #endif - current_board->set_led(LED_GREEN, 1); + led_set(LED_GREEN, 1); jump_to_bootloader(); } } diff --git a/panda/board/fake_stm.h b/panda/board/fake_stm.h index b73a4e8985..984fde14f1 100644 --- a/panda/board/fake_stm.h +++ b/panda/board/fake_stm.h @@ -31,3 +31,5 @@ uint32_t microsecond_timer_get(void); uint32_t microsecond_timer_get(void) { return MICROSECOND_TIMER->CNT; } + +typedef uint32_t GPIO_TypeDef; diff --git a/panda/board/flasher.h b/panda/board/flasher.h index 9a046a25d0..9cf21542d6 100644 --- a/panda/board/flasher.h +++ b/panda/board/flasher.h @@ -35,7 +35,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { flash_unlock(); resp[1] = 0xff; } - current_board->set_led(LED_GREEN, 1); + led_set(LED_GREEN, 1); unlocked = true; prog_ptr = (uint32_t *)APP_START_ADDRESS; break; @@ -112,14 +112,14 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { 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); + led_set(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); + led_set(LED_RED, 1); } @@ -132,26 +132,28 @@ void soft_flasher_start(void) { gpio_usart2_init(); gpio_usb_init(); + led_init(); // enable USB usb_init(); - // enable SPI +#ifdef ENABLE_SPI if (current_board->has_spi) { gpio_spi_init(); spi_init(); } +#endif // green LED on for flashing - current_board->set_led(LED_GREEN, 1); + led_set(LED_GREEN, 1); enable_interrupts(); for (;;) { // blink the green LED fast - current_board->set_led(LED_GREEN, 0); + led_set(LED_GREEN, 0); delay(500000); - current_board->set_led(LED_GREEN, 1); + led_set(LED_GREEN, 1); delay(500000); } } diff --git a/panda/board/jungle/boards/board_declarations.h b/panda/board/jungle/boards/board_declarations.h index 26b093fa80..e6c6601b0c 100644 --- a/panda/board/jungle/boards/board_declarations.h +++ b/panda/board/jungle/boards/board_declarations.h @@ -1,6 +1,5 @@ // ******************** 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); @@ -15,11 +14,12 @@ typedef float (*board_get_channel_power)(uint8_t channel); typedef uint16_t (*board_get_sbu_mV)(uint8_t channel, uint8_t sbu); struct board { + GPIO_TypeDef * const led_GPIO[3]; + const uint8_t led_pin[3]; 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; @@ -42,11 +42,6 @@ struct board { #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_OBD_CAN2 3U diff --git a/panda/board/jungle/boards/board_v1.h b/panda/board/jungle/boards/board_v1.h index 833f49f9cf..44e90b8fa6 100644 --- a/panda/board/jungle/boards/board_v1.h +++ b/panda/board/jungle/boards/board_v1.h @@ -2,22 +2,6 @@ // 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_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { case 1U: @@ -140,11 +124,6 @@ void board_v1_init(void) { board_v1_enable_can_transceiver(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); @@ -162,7 +141,8 @@ board board_v1 = { .has_sbu_sense = false, .avdd_mV = 3300U, .init = &board_v1_init, - .set_led = &board_v1_set_led, + .led_GPIO = {GPIOC, GPIOC, GPIOC}, + .led_pin = {9, 7, 6}, .board_tick = &board_v1_tick, .get_button = &board_v1_get_button, .set_panda_power = &board_v1_set_panda_power, diff --git a/panda/board/jungle/boards/board_v2.h b/panda/board/jungle/boards/board_v2.h index bfd3796996..ea0a099d91 100644 --- a/panda/board/jungle/boards/board_v2.h +++ b/panda/board/jungle/boards/board_v2.h @@ -65,22 +65,6 @@ adc_channel_t sbu2_channels[] = { {.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: @@ -252,11 +236,6 @@ uint16_t board_v2_get_sbu_mV(uint8_t channel, uint8_t sbu) { 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); @@ -312,7 +291,8 @@ board board_v2 = { .has_sbu_sense = true, .avdd_mV = 3300U, .init = &board_v2_init, - .set_led = &board_v2_set_led, + .led_GPIO = {GPIOE, GPIOE, GPIOE}, + .led_pin = {4, 3, 2}, .board_tick = &board_v2_tick, .get_button = &board_v2_get_button, .set_panda_power = &board_v2_set_panda_power, diff --git a/panda/board/jungle/main.c b/panda/board/jungle/main.c index 6b660f6c50..664351c150 100644 --- a/panda/board/jungle/main.c +++ b/panda/board/jungle/main.c @@ -1,8 +1,9 @@ // ********************* Includes ********************* #include "board/config.h" -#include "safety.h" +#include "opendbc/safety/safety.h" +#include "board/drivers/led.h" #include "board/drivers/pwm.h" #include "board/drivers/usb.h" @@ -76,7 +77,7 @@ void tick_handler(void) { check_registers(); // turn off the blue LED, turned on by CAN - current_board->set_led(LED_BLUE, false); + led_set(LED_BLUE, false); // Blink and OBD CAN #ifdef FINAL_PROVISIONING @@ -87,7 +88,7 @@ void tick_handler(void) { uptime_cnt += 1U; } - current_board->set_led(LED_GREEN, green_led_enabled); + led_set(LED_GREEN, green_led_enabled); // Check on button bool current_button_status = current_board->get_button(); @@ -146,8 +147,8 @@ int main(void) { peripherals_init(); detect_board_type(); // red+green leds enabled until succesful USB init, as a debug indicator - current_board->set_led(LED_RED, true); - current_board->set_led(LED_GREEN, true); + led_set(LED_RED, true); + led_set(LED_GREEN, true); // print hello print("\n\n\n************************ MAIN START ************************\n"); @@ -176,8 +177,8 @@ int main(void) { // enable USB (right before interrupts or enum can fail!) usb_init(); - current_board->set_led(LED_RED, false); - current_board->set_led(LED_GREEN, false); + led_set(LED_RED, false); + led_set(LED_GREEN, false); print("**** INTERRUPTS ON ****\n"); enable_interrupts(); @@ -223,16 +224,16 @@ int main(void) { // useful for debugging, fade breaks = panda is overloaded for (uint32_t fade = 0U; fade < MAX_LED_FADE; fade += 1U) { - current_board->set_led(LED_RED, true); + led_set(LED_RED, true); delay(fade >> 4); - current_board->set_led(LED_RED, false); + led_set(LED_RED, false); delay((MAX_LED_FADE - fade) >> 4); } for (uint32_t fade = MAX_LED_FADE; fade > 0U; fade -= 1U) { - current_board->set_led(LED_RED, true); + led_set(LED_RED, true); delay(fade >> 4); - current_board->set_led(LED_RED, false); + led_set(LED_RED, false); delay((MAX_LED_FADE - fade) >> 4); } } diff --git a/panda/board/main.c b/panda/board/main.c index 7183b26f98..458db9670c 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -1,6 +1,7 @@ // ********************* Includes ********************* #include "config.h" +#include "drivers/led.h" #include "drivers/pwm.h" #include "drivers/usb.h" #include "drivers/simple_watchdog.h" @@ -9,7 +10,7 @@ #include "early_init.h" #include "provision.h" -#include "safety.h" +#include "opendbc/safety/safety.h" #include "health.h" @@ -76,14 +77,14 @@ void set_safety_mode(uint16_t mode, uint16_t param) { switch (mode_copy) { case SAFETY_SILENT: set_intercept_relay(false, false); - if (current_board->has_obd) { + if (current_board->harness_config->has_harness) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_SILENT; break; case SAFETY_NOOUTPUT: set_intercept_relay(false, false); - if (current_board->has_obd) { + if (current_board->harness_config->has_harness) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; @@ -92,7 +93,7 @@ void set_safety_mode(uint16_t mode, uint16_t param) { set_intercept_relay(false, false); heartbeat_counter = 0U; heartbeat_lost = false; - if (current_board->has_obd) { + if (current_board->harness_config->has_harness) { // Clear any pending messages in the can core (i.e. sending while comma power is unplugged) // TODO: rewrite using hardware queues rather than fifo to cancel specific messages can_clear_send(CANIF_FROM_CAN_NUM(1), 1); @@ -108,7 +109,7 @@ void set_safety_mode(uint16_t mode, uint16_t param) { set_intercept_relay(true, false); heartbeat_counter = 0U; heartbeat_lost = false; - if (current_board->has_obd) { + if (current_board->harness_config->has_harness) { current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; @@ -189,11 +190,11 @@ static void tick_handler(void) { #endif // set green LED to be controls allowed - current_board->set_led(LED_GREEN, controls_allowed | green_led_enabled); + led_set(LED_GREEN, controls_allowed | green_led_enabled); // turn off the blue LED, turned on by CAN // unless we are in power saving mode - current_board->set_led(LED_BLUE, (uptime_cnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED)); + led_set(LED_BLUE, (uptime_cnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED)); const bool recent_heartbeat = heartbeat_counter == 0U; @@ -303,9 +304,10 @@ int main(void) { clock_init(); peripherals_init(); detect_board_type(); + led_init(); // red+green leds enabled until succesful USB/SPI init, as a debug indicator - current_board->set_led(LED_RED, true); - current_board->set_led(LED_GREEN, true); + led_set(LED_RED, true); + led_set(LED_GREEN, true); adc_init(); // print hello @@ -319,6 +321,10 @@ int main(void) { // init board current_board->init(); + current_board->set_can_mode(CAN_MODE_NORMAL); + if (current_board->harness_config->has_harness) { + harness_init(); + } // panda has an FPU, let's use it! enable_fpu(); @@ -334,7 +340,7 @@ int main(void) { set_safety_mode(SAFETY_SILENT, 0U); // enable CAN TXs - current_board->enable_can_transceivers(true); + enable_can_transceivers(true); // init watchdog for heartbeat loop, fed at 8Hz simple_watchdog_init(FAULT_HEARTBEAT_LOOP_WATCHDOG, (3U * 1000000U / 8U)); @@ -351,12 +357,14 @@ int main(void) { #ifdef ENABLE_SPI if (current_board->has_spi) { + gpio_spi_init(); spi_init(); } #endif - current_board->set_led(LED_RED, false); - current_board->set_led(LED_GREEN, false); + led_set(LED_RED, false); + led_set(LED_GREEN, false); + led_set(LED_BLUE, false); print("**** INTERRUPTS ON ****\n"); enable_interrupts(); @@ -369,24 +377,24 @@ int main(void) { #endif // useful for debugging, fade breaks = panda is overloaded for (uint32_t fade = 0U; fade < MAX_LED_FADE; fade += 1U) { - current_board->set_led(LED_RED, true); + led_set(LED_RED, true); delay(fade >> 4); - current_board->set_led(LED_RED, false); + led_set(LED_RED, false); delay((MAX_LED_FADE - fade) >> 4); } for (uint32_t fade = MAX_LED_FADE; fade > 0U; fade -= 1U) { - current_board->set_led(LED_RED, true); + led_set(LED_RED, true); delay(fade >> 4); - current_board->set_led(LED_RED, false); + led_set(LED_RED, false); delay((MAX_LED_FADE - fade) >> 4); } #ifdef DEBUG_FAULTS } else { - current_board->set_led(LED_RED, 1); + led_set(LED_RED, 1); delay(512000U); - current_board->set_led(LED_RED, 0); + led_set(LED_RED, 0); delay(512000U); } #endif diff --git a/panda/board/main_comms.h b/panda/board/main_comms.h index e366b19a09..90056869f1 100644 --- a/panda/board/main_comms.h +++ b/panda/board/main_comms.h @@ -212,7 +212,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { break; // **** 0xdb: set OBD CAN multiplexing mode case 0xdb: - if (current_board->has_obd) { + if (current_board->harness_config->has_harness) { if (req->param1 == 1U) { // Enable OBD CAN current_board->set_can_mode(CAN_MODE_OBD_CAN2); diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h index 2704a01a03..3b4a807dc2 100644 --- a/panda/board/main_declarations.h +++ b/panda/board/main_declarations.h @@ -3,7 +3,6 @@ // ******************** 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; diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h index 7fcc181ea9..dea46491b2 100644 --- a/panda/board/power_saving.h +++ b/panda/board/power_saving.h @@ -5,8 +5,15 @@ int power_save_status = POWER_SAVE_STATUS_DISABLED; -void set_power_save_state(int state) { +void enable_can_transceivers(bool enabled) { + // Leave main CAN always on for CAN-based ignition detection + uint8_t main_bus = (current_board->harness_config->has_harness && (harness.status == HARNESS_STATUS_FLIPPED)) ? 3U : 1U; + for(uint8_t i=1U; i<=4U; i++){ + current_board->enable_can_transceiver(i, (i == main_bus) || enabled); + } +} +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; @@ -33,7 +40,7 @@ void set_power_save_state(int state) { enable = true; } - current_board->enable_can_transceivers(enable); + enable_can_transceivers(enable); // Switch off IR when in power saving if(!enable){ diff --git a/panda/board/stm32f4/board.h b/panda/board/stm32f4/board.h index 0cbaae6025..cd10c173bf 100644 --- a/panda/board/stm32f4/board.h +++ b/panda/board/stm32f4/board.h @@ -39,4 +39,7 @@ void detect_board_type(void) { hw_type = HW_TYPE_BLACK_PANDA; current_board = &board_black; } + + // Return A13 to the alt mode to fix SWD + set_gpio_alternate(GPIOA, 13, GPIO_AF0_SWJ); } diff --git a/panda/board/stm32f4/lluart.h b/panda/board/stm32f4/lluart.h index f4b1a5f1db..660c1ce199 100644 --- a/panda/board/stm32f4/lluart.h +++ b/panda/board/stm32f4/lluart.h @@ -20,61 +20,9 @@ void uart_tx_ring(uart_ring *q){ EXIT_CRITICAL(); } -static 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(); -} - // 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); -static 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_))) diff --git a/panda/board/stm32f4/peripherals.h b/panda/board/stm32f4/peripherals.h index 9c0b8ee650..fc97409112 100644 --- a/panda/board/stm32f4/peripherals.h +++ b/panda/board/stm32f4/peripherals.h @@ -9,6 +9,7 @@ static void gpio_usb_init(void) { GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; } +#ifdef ENABLE_SPI void gpio_spi_init(void) { // A4-A7: SPI set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); @@ -17,12 +18,15 @@ void gpio_spi_init(void) { 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); } +#endif +#ifdef BOOTSTUB 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); } +#endif // Common GPIO initialization void common_init_gpio(void) { @@ -45,12 +49,14 @@ void common_init_gpio(void) { set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); } +#ifdef BOOTSTUB 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; } +#endif // Peripheral initialization void peripherals_init(void) { diff --git a/panda/board/stm32f4/stm32f4_config.h b/panda/board/stm32f4/stm32f4_config.h index eae9222a9d..b3fc2a8907 100644 --- a/panda/board/stm32f4/stm32f4_config.h +++ b/panda/board/stm32f4/stm32f4_config.h @@ -52,7 +52,6 @@ #include "drivers/timers.h" #include "stm32f4/board.h" #include "stm32f4/clock.h" -#include "drivers/watchdog.h" #include "drivers/spi.h" #include "stm32f4/llspi.h" @@ -73,7 +72,7 @@ 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; + 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 index 6ab75f55d8..0507ca3fb6 100644 --- a/panda/board/stm32h7/board.h +++ b/panda/board/stm32h7/board.h @@ -9,12 +9,10 @@ #include "drivers/harness.h" #include "drivers/fan.h" #include "stm32h7/llfan.h" -#include "stm32h7/lldac.h" #include "drivers/fake_siren.h" #include "stm32h7/sound.h" #include "drivers/clock_source.h" #include "boards/red.h" -#include "boards/red_chiplet.h" #include "boards/tres.h" #include "boards/cuatro.h" diff --git a/panda/board/stm32h7/lldac.h b/panda/board/stm32h7/lldac.h deleted file mode 100644 index 5726f62413..0000000000 --- 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/peripherals.h b/panda/board/stm32h7/peripherals.h index cae04652a4..2cdbea6daf 100644 --- a/panda/board/stm32h7/peripherals.h +++ b/panda/board/stm32h7/peripherals.h @@ -9,6 +9,7 @@ static void gpio_usb_init(void) { GPIOA->OSPEEDR = GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12; } +#ifdef ENABLE_SPI void gpio_spi_init(void) { set_gpio_alternate(GPIOE, 11, GPIO_AF5_SPI4); set_gpio_alternate(GPIOE, 12, GPIO_AF5_SPI4); @@ -16,12 +17,15 @@ void gpio_spi_init(void) { 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); } +#endif +#ifdef BOOTSTUB 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); } +#endif void gpio_uart7_init(void) { // E7,E8: UART 7 for debugging @@ -31,26 +35,6 @@ void gpio_uart7_init(void) { // 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); @@ -82,6 +66,7 @@ void common_init_gpio(void) { set_gpio_alternate(GPIOG, 10, GPIO_AF2_FDCAN3); } +#ifdef BOOTSTUB void flasher_peripherals_init(void) { RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; @@ -89,6 +74,7 @@ void flasher_peripherals_init(void) { RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; } +#endif // Peripheral initialization void peripherals_init(void) { diff --git a/panda/board/stm32h7/sound.h b/panda/board/stm32h7/sound.h index de35a1230d..467c356737 100644 --- a/panda/board/stm32h7/sound.h +++ b/panda/board/stm32h7/sound.h @@ -84,7 +84,7 @@ static void BDMA_Channel0_IRQ_Handler(void) { sound_tx_buf[1U - playback_buf][i] = (1UL << 11); } register_clear_bits(&DMA1_Stream1->CR, DMA_SxCR_EN); - register_set(&DMA1_Stream1->CR, (1UL - playback_buf) << DMA_SxCR_CT_Pos, DMA_SxCR_CT_Msk); + DMA1_Stream1->CR = (DMA1_Stream1->CR & ~DMA_SxCR_CT_Msk) | ((1UL - playback_buf) << DMA_SxCR_CT_Pos); register_set_bits(&DMA1_Stream1->CR, DMA_SxCR_EN); } sound_idle_count = SOUND_IDLE_TIMEOUT; @@ -105,6 +105,7 @@ void sound_init(void) { REGISTER_INTERRUPT(DMA1_Stream0_IRQn, DMA1_Stream0_IRQ_Handler, 128U, FAULT_INTERRUPT_RATE_SOUND_DMA) // Init DAC + DAC1->DHR12R1 = (1UL << 11); register_set(&DAC1->MCR, 0U, 0xFFFFFFFFU); register_set(&DAC1->CR, DAC_CR_TEN1 | (4U << DAC_CR_TSEL1_Pos) | DAC_CR_DMAEN1, 0xFFFFFFFFU); register_set_bits(&DAC1->CR, DAC_CR_EN1); @@ -131,7 +132,6 @@ void sound_init(void) { // sync both SAIs register_set(&SAI4->GCR, (0b10UL << SAI_GCR_SYNCOUT_Pos), SAI_GCR_SYNCIN_Msk | SAI_GCR_SYNCOUT_Msk); - register_set(&SAI1->GCR, (3U << SAI_GCR_SYNCIN_Pos), SAI_GCR_SYNCIN_Msk | SAI_GCR_SYNCOUT_Msk); // stereo audio in register_set(&SAI4_Block_B->CR1, SAI_xCR1_DMAEN | (0b00UL << SAI_xCR1_SYNCEN_Pos) | (0b100U << SAI_xCR1_DS_Pos) | (0b11U << SAI_xCR1_MODE_Pos), 0x0FFB3FEFU); @@ -157,7 +157,6 @@ void sound_init(void) { // init DFSDM for PDM mic register_set(&DFSDM1_Channel0->CHCFGR1, (76UL << DFSDM_CHCFGR1_CKOUTDIV_Pos) | DFSDM_CHCFGR1_CHEN, 0xC0FFF1EFU); // CH0 controls the clock register_set(&DFSDM1_Channel3->CHCFGR1, (0b01UL << DFSDM_CHCFGR1_SPICKSEL_Pos) | (0b00U << DFSDM_CHCFGR1_SITP_Pos) | DFSDM_CHCFGR1_CHEN, 0x0000F1EFU); // SITP determines sample edge - register_set(&DFSDM1_Channel3->CHCFGR2, (2U << DFSDM_CHCFGR2_DTRBS_Pos), 0xFFFFFFF7U); register_set(&DFSDM1_Filter0->FLTFCR, (0U << DFSDM_FLTFCR_IOSR_Pos) | (64UL << DFSDM_FLTFCR_FOSR_Pos) | (4UL << DFSDM_FLTFCR_FORD_Pos), 0xE3FF00FFU); register_set(&DFSDM1_Filter0->FLTCR1, DFSDM_FLTCR1_FAST | (3UL << DFSDM_FLTCR1_RCH_Pos) | DFSDM_FLTCR1_RDMAEN | DFSDM_FLTCR1_RCONT | DFSDM_FLTCR1_DFEN, 0x672E7F3BU); @@ -166,7 +165,7 @@ void sound_init(void) { register_set(&DMA1_Stream0->M0AR, (uint32_t)mic_rx_buf[0], 0xFFFFFFFFU); register_set(&DMA1_Stream0->M1AR, (uint32_t)mic_rx_buf[1], 0xFFFFFFFFU); DMA1_Stream0->NDTR = MIC_RX_BUF_SIZE; - register_set(&DMA1_Stream0->CR, DMA_SxCR_DBM | (0b10UL << DMA_SxCR_MSIZE_Pos) | (0b10UL << DMA_SxCR_PSIZE_Pos) | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_TCIE, 0x01FFFFFFU); + register_set(&DMA1_Stream0->CR, DMA_SxCR_DBM | (0b10UL << DMA_SxCR_MSIZE_Pos) | (0b10UL << DMA_SxCR_PSIZE_Pos) | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_TCIE, 0x01F7FFFFU); register_set(&DMAMUX1_Channel0->CCR, 101U, DMAMUX_CxCR_DMAREQ_ID_Msk); // DFSDM1_DMA0 register_set_bits(&DMA1_Stream0->CR, DMA_SxCR_EN); DMA1->LIFCR |= 0x7D; // clear flags diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h index bfc12e8c3a..4355fe8e08 100644 --- a/panda/board/stm32h7/stm32h7_config.h +++ b/panda/board/stm32h7/stm32h7_config.h @@ -63,7 +63,6 @@ separate IRQs for RX and TX. #include "stm32h7/peripherals.h" #include "stm32h7/interrupt_handlers.h" #include "drivers/timers.h" -#include "drivers/watchdog.h" #if !defined(BOOTSTUB) #include "drivers/uart.h" diff --git a/panda/drivers/linux/.gitignore b/panda/drivers/linux/.gitignore deleted file mode 100644 index 93a6cde763..0000000000 --- a/panda/drivers/linux/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -.*.cmd -*.ko -.tmp_versions -Module.symvers -modules.order -*.mod.c diff --git a/panda/drivers/linux/Makefile b/panda/drivers/linux/Makefile deleted file mode 100644 index 5ccc4bd08c..0000000000 --- a/panda/drivers/linux/Makefile +++ /dev/null @@ -1,24 +0,0 @@ -VERSION=0.0.1 -obj-m+=panda.o - -all: build install - -build: - sudo dkms build panda/$(VERSION) - -install: - sudo dkms install panda/$(VERSION) - -remove: - sudo dkms remove panda/$(VERSION) --all - -uninstall: - sudo dkms uninstall panda/$(VERSION) - -clean: remove - -link: - sudo dkms add `pwd` - -unload: - sudo rmmod panda diff --git a/panda/drivers/linux/README.md b/panda/drivers/linux/README.md deleted file mode 100644 index 677b566ca5..0000000000 --- a/panda/drivers/linux/README.md +++ /dev/null @@ -1,28 +0,0 @@ -# Linux driver -Installs the panda linux kernel driver using DKMS. - -This will allow the panda to work with tools such as `can-utils` - -## Prerequisites - - `apt-get install dkms gcc linux-headers-$(uname -r) make sudo` - -## Installation - - `make all` - - `make link` (optional, setup to build/install when kernel is updated) - -## Uninstall - - `make clean` - -## Usage - -You will need to bring it up using `sudo ifconfig can0 up` or -`sudo ip link set dev can0 up`, depending on your platform. - -Note that you may have to setup udev rules for Linux -``` bash -sudo tee /etc/udev/rules.d/11-panda.rules < -#include -#include -#include // Macros used to mark up functions e.g., __init __exit -#include // Contains types, macros, functions for the kernel -#include // Core header for loading LKMs into the kernel -#include -#include -#include - -/* vendor and product id */ -#define PANDA_MODULE_NAME "panda" -#define PANDA_VENDOR_ID 0X3801 -#define PANDA_PRODUCT_ID 0XDDCC - -#define PANDA_MAX_TX_URBS 20 -#define PANDA_CTX_FREE PANDA_MAX_TX_URBS - -#define PANDA_USB_RX_BUFF_SIZE 0x40 -#define PANDA_USB_TX_BUFF_SIZE (sizeof(struct panda_usb_can_msg)) - -#define PANDA_NUM_CAN_INTERFACES 3 - -#define PANDA_CAN_TRANSMIT 1 -#define PANDA_CAN_EXTENDED 4 - -#define PANDA_BITRATE 500000 - -#define PANDA_DLC_MASK 0x0F - -#define SAFETY_ALLOUTPUT 17 -#define SAFETY_SILENT 0 - -struct panda_usb_ctx { - struct panda_inf_priv *priv; - u32 ndx; - u8 dlc; -}; - -struct panda_dev_priv; - -struct panda_inf_priv { - struct can_priv can; - struct panda_usb_ctx tx_context[PANDA_MAX_TX_URBS]; - struct net_device *netdev; - struct usb_anchor tx_submitted; - atomic_t free_ctx_cnt; - u8 interface_num; - u8 mcu_can_ifnum; - struct panda_dev_priv *priv_dev; -}; - -struct panda_dev_priv { - struct usb_device *udev; - struct device *dev; - struct usb_anchor rx_submitted; - struct panda_inf_priv *interfaces[PANDA_NUM_CAN_INTERFACES]; -}; - -struct __packed panda_usb_can_msg { - u32 rir; - u32 bus_dat_len; - u8 data[8]; -}; - -static const struct usb_device_id panda_usb_table[] = { - { USB_DEVICE(PANDA_VENDOR_ID, PANDA_PRODUCT_ID) }, - {} /* Terminating entry */ -}; - -MODULE_DEVICE_TABLE(usb, panda_usb_table); - - -// panda: CAN1 = 0 CAN2 = 1 CAN3 = 2 -const int can_numbering[] = {0,1,2}; - -struct panda_inf_priv * -panda_get_inf_from_bus_id(struct panda_dev_priv *priv_dev, int bus_id) { - int inf_num; - for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) - if(can_numbering[inf_num] == bus_id) - return priv_dev->interfaces[inf_num]; - return NULL; -} - -// CTX handling shamlessly ripped from mcba_usb.c linux driver -static inline void panda_init_ctx(struct panda_inf_priv *priv) -{ - int i = 0; - - for (i = 0; i < PANDA_MAX_TX_URBS; i++) { - priv->tx_context[i].ndx = PANDA_CTX_FREE; - priv->tx_context[i].priv = priv; - } - - atomic_set(&priv->free_ctx_cnt, ARRAY_SIZE(priv->tx_context)); -} - -static inline struct panda_usb_ctx *panda_usb_get_free_ctx(struct panda_inf_priv *priv, struct can_frame *cf) -{ - int i = 0; - struct panda_usb_ctx *ctx = NULL; - - for (i = 0; i < PANDA_MAX_TX_URBS; i++) { - if (priv->tx_context[i].ndx == PANDA_CTX_FREE) { - ctx = &priv->tx_context[i]; - ctx->ndx = i; - ctx->dlc = cf->can_dlc; - - atomic_dec(&priv->free_ctx_cnt); - break; - } - } - - //printk("CTX num %d\n", atomic_read(&priv->free_ctx_cnt)); - if (!atomic_read(&priv->free_ctx_cnt)) { - /* That was the last free ctx. Slow down tx path */ - printk("SENDING TOO FAST\n"); - netif_stop_queue(priv->netdev); - } - - return ctx; -} - -/* panda_usb_free_ctx and panda_usb_get_free_ctx are executed by different - * threads. The order of execution in below function is important. - */ -static inline void panda_usb_free_ctx(struct panda_usb_ctx *ctx) -{ - /* Increase number of free ctxs before freeing ctx */ - atomic_inc(&ctx->priv->free_ctx_cnt); - - ctx->ndx = PANDA_CTX_FREE; - - /* Wake up the queue once ctx is marked free */ - netif_wake_queue(ctx->priv->netdev); -} - -static void panda_urb_unlink(struct panda_inf_priv *priv) -{ - usb_kill_anchored_urbs(&priv->priv_dev->rx_submitted); - usb_kill_anchored_urbs(&priv->tx_submitted); -} - -static int panda_set_output_enable(struct panda_inf_priv* priv, bool enable) { - return usb_control_msg(priv->priv_dev->udev, - usb_sndctrlpipe(priv->priv_dev->udev, 0), - 0xDC, USB_TYPE_VENDOR | USB_RECIP_DEVICE, - enable ? SAFETY_ALLOUTPUT : SAFETY_SILENT, 0, NULL, 0, USB_CTRL_SET_TIMEOUT); -} - -static void panda_usb_write_bulk_callback(struct urb *urb) -{ - struct panda_usb_ctx *ctx = urb->context; - struct net_device *netdev; - - WARN_ON(!ctx); - - netdev = ctx->priv->netdev; - - /* free up our allocated buffer */ - usb_free_coherent(urb->dev, urb->transfer_buffer_length, urb->transfer_buffer, urb->transfer_dma); - - if (!netif_device_present(netdev)) - return; - - netdev->stats.tx_packets++; - netdev->stats.tx_bytes += ctx->dlc; - - can_get_echo_skb(netdev, ctx->ndx, NULL); - - if (urb->status) - netdev_info(netdev, "Tx URB aborted (%d)\n", urb->status); - - /* Release the context */ - panda_usb_free_ctx(ctx); -} - -static netdev_tx_t panda_usb_xmit(struct panda_inf_priv *priv, struct panda_usb_can_msg *usb_msg, struct panda_usb_ctx *ctx) -{ - struct urb *urb; - u8 *buf; - int err; - - /* create a URB, and a buffer for it, and copy the data to the URB */ - urb = usb_alloc_urb(0, GFP_ATOMIC); - if (!urb) - return -ENOMEM; - - buf = usb_alloc_coherent(priv->priv_dev->udev, PANDA_USB_TX_BUFF_SIZE, GFP_ATOMIC, &urb->transfer_dma); - if (!buf) { - err = -ENOMEM; - goto nomembuf; - } - - memcpy(buf, usb_msg, PANDA_USB_TX_BUFF_SIZE); - - usb_fill_bulk_urb(urb, priv->priv_dev->udev, - usb_sndbulkpipe(priv->priv_dev->udev, 3), buf, - PANDA_USB_TX_BUFF_SIZE, panda_usb_write_bulk_callback, - ctx); - - urb->transfer_flags |= URB_NO_TRANSFER_DMA_MAP; - usb_anchor_urb(urb, &priv->tx_submitted); - - err = usb_submit_urb(urb, GFP_ATOMIC); - if (unlikely(err)) - goto failed; - - /* Release our reference to this URB, the USB core will eventually free it entirely. */ - usb_free_urb(urb); - - return 0; - - failed: - usb_unanchor_urb(urb); - usb_free_coherent(priv->priv_dev->udev, PANDA_USB_TX_BUFF_SIZE, buf, urb->transfer_dma); - - if (err == -ENODEV) - netif_device_detach(priv->netdev); - else - netdev_warn(priv->netdev, "failed tx_urb %d\n", err); - - nomembuf: - usb_free_urb(urb); - - return err; -} - -static void panda_usb_process_can_rx(struct panda_dev_priv *priv_dev, struct panda_usb_can_msg *msg) -{ - struct can_frame *cf; - struct sk_buff *skb; - int bus_num; - struct panda_inf_priv *priv_inf; - struct net_device_stats *stats; - - bus_num = (msg->bus_dat_len >> 4) & 0xf; - priv_inf = panda_get_inf_from_bus_id(priv_dev, bus_num); - if (!priv_inf) { - printk("Got something on an unused interface %d\n", bus_num); - return; - } - //printk("Recv bus %d\n", bus_num); - - stats = &priv_inf->netdev->stats; - //u16 sid; - - if (!netif_device_present(priv_inf->netdev)) - return; - - skb = alloc_can_skb(priv_inf->netdev, &cf); - if (!skb) - return; - - if (msg->rir & PANDA_CAN_EXTENDED) { - cf->can_id = (msg->rir >> 3) | CAN_EFF_FLAG; - } else { - cf->can_id = (msg->rir >> 21); - } - - // TODO: Handle Remote Frames - //if (msg->dlc & MCBA_DLC_RTR_MASK) - // cf->can_id |= CAN_RTR_FLAG; - -#if LINUX_VERSION_CODE < KERNEL_VERSION(5, 11, 0) - cf->can_dlc = get_can_dlc(msg->bus_dat_len & PANDA_DLC_MASK); -#else - cf->can_dlc = can_cc_dlc2len(msg->bus_dat_len & PANDA_DLC_MASK); -#endif - - memcpy(cf->data, msg->data, cf->can_dlc); - - stats->rx_packets++; - stats->rx_bytes += cf->can_dlc; - - netif_rx(skb); -} - -static void panda_usb_read_bulk_callback(struct urb *urb) -{ - struct panda_dev_priv *priv_dev = urb->context; - int retval; - int pos = 0; - int inf_num; - - switch (urb->status) { - case 0: /* success */ - break; - case -ENOENT: - case -ESHUTDOWN: - return; - default: - dev_info(priv_dev->dev, "Rx URB aborted (%d)\n", urb->status); - goto resubmit_urb; - } - - while (pos < urb->actual_length) { - struct panda_usb_can_msg *msg; - - if (pos + sizeof(struct panda_usb_can_msg) > urb->actual_length) { - dev_err(priv_dev->dev, "format error\n"); - break; - } - - msg = (struct panda_usb_can_msg *)(urb->transfer_buffer + pos); - - panda_usb_process_can_rx(priv_dev, msg); - - pos += sizeof(struct panda_usb_can_msg); - } - - resubmit_urb: - usb_fill_bulk_urb(urb, priv_dev->udev, - usb_rcvbulkpipe(priv_dev->udev, 1), - urb->transfer_buffer, PANDA_USB_RX_BUFF_SIZE, - panda_usb_read_bulk_callback, priv_dev); - - retval = usb_submit_urb(urb, GFP_ATOMIC); - - if (retval == -ENODEV) { - for (inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) - if (priv_dev->interfaces[inf_num]) - netif_device_detach(priv_dev->interfaces[inf_num]->netdev); - } else if (retval) { - dev_err(priv_dev->dev, "failed resubmitting read bulk urb: %d\n", retval); - } -} - - -static int panda_usb_start(struct panda_dev_priv *priv_dev) -{ - int err; - struct urb *urb = NULL; - u8 *buf; - int inf_num; - - for (inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) - panda_init_ctx(priv_dev->interfaces[inf_num]); - - err = usb_set_interface(priv_dev->udev, 0, 0); - if (err) { - dev_err(priv_dev->dev, "Can not set alternate setting to 0, error: %i", err); - return err; - } - - /* create a URB, and a buffer for it */ - urb = usb_alloc_urb(0, GFP_KERNEL); - if (!urb) { - return -ENOMEM; - } - - buf = usb_alloc_coherent(priv_dev->udev, PANDA_USB_RX_BUFF_SIZE, GFP_KERNEL, &urb->transfer_dma); - if (!buf) { - dev_err(priv_dev->dev, "No memory left for USB buffer\n"); - usb_free_urb(urb); - return -ENOMEM; - } - - usb_fill_bulk_urb(urb, priv_dev->udev, - usb_rcvbulkpipe(priv_dev->udev, 1), - buf, PANDA_USB_RX_BUFF_SIZE, - panda_usb_read_bulk_callback, priv_dev); - urb->transfer_flags |= URB_NO_TRANSFER_DMA_MAP; - - usb_anchor_urb(urb, &priv_dev->rx_submitted); - - err = usb_submit_urb(urb, GFP_KERNEL); - if (err) { - usb_unanchor_urb(urb); - usb_free_coherent(priv_dev->udev, PANDA_USB_RX_BUFF_SIZE, buf, urb->transfer_dma); - usb_free_urb(urb); - dev_err(priv_dev->dev, "Failed in start, while submitting urb.\n"); - return err; - } - - /* Drop reference, USB core will take care of freeing it */ - usb_free_urb(urb); - - - return 0; -} - -/* Open USB device */ -static int panda_usb_open(struct net_device *netdev) -{ - struct panda_inf_priv *priv = netdev_priv(netdev); - int err; - - /* common open */ - err = open_candev(netdev); - if (err) - return err; - - //priv->can_speed_check = true; - priv->can.state = CAN_STATE_ERROR_ACTIVE; - - netif_start_queue(netdev); - - return 0; -} - -/* Close USB device */ -static int panda_usb_close(struct net_device *netdev) -{ - struct panda_inf_priv *priv = netdev_priv(netdev); - - priv->can.state = CAN_STATE_STOPPED; - - netif_stop_queue(netdev); - - /* Stop polling */ - panda_urb_unlink(priv); - - close_candev(netdev); - - return 0; -} - -static netdev_tx_t panda_usb_start_xmit(struct sk_buff *skb, struct net_device *netdev) -{ - struct panda_inf_priv *priv_inf = netdev_priv(netdev); - struct can_frame *cf = (struct can_frame *)skb->data; - struct panda_usb_ctx *ctx = NULL; - struct net_device_stats *stats = &priv_inf->netdev->stats; - int err; - struct panda_usb_can_msg usb_msg = {}; - int bus = priv_inf->mcu_can_ifnum; - - if (can_dropped_invalid_skb(netdev, skb)) { - printk("Invalid CAN packet"); - return NETDEV_TX_OK; - } - - ctx = panda_usb_get_free_ctx(priv_inf, cf); - - //Warning: cargo cult. Can't tell what this is for, but it is - //everywhere and encouraged in the documentation. - can_put_echo_skb(skb, priv_inf->netdev, ctx->ndx, NULL); - - if (cf->can_id & CAN_EFF_FLAG) { - usb_msg.rir = cpu_to_le32(((cf->can_id & 0x1FFFFFFF) << 3) | PANDA_CAN_TRANSMIT | PANDA_CAN_EXTENDED); - } else { - usb_msg.rir = cpu_to_le32(((cf->can_id & 0x7FF) << 21) | PANDA_CAN_TRANSMIT); - } - usb_msg.bus_dat_len = cpu_to_le32((cf->can_dlc & 0x0F) | (bus << 4)); - - memcpy(usb_msg.data, cf->data, cf->can_dlc); - - //TODO Handle Remote Frames - //if (cf->can_id & CAN_RTR_FLAG) - // usb_msg.dlc |= PANDA_DLC_RTR_MASK; - - // printk("Received data from socket. bus: %x; canid: %x; len: %d\n", priv_inf->mcu_can_ifnum, cf->can_id, cf->can_dlc); - - err = panda_usb_xmit(priv_inf, &usb_msg, ctx); - if (err) - goto xmit_failed; - - return NETDEV_TX_OK; - - xmit_failed: - can_free_echo_skb(priv_inf->netdev, ctx->ndx, NULL); - panda_usb_free_ctx(ctx); - dev_kfree_skb_any(skb); - stats->tx_dropped++; - - return NETDEV_TX_OK; -} - -static const struct net_device_ops panda_netdev_ops = { - .ndo_open = panda_usb_open, - .ndo_stop = panda_usb_close, - .ndo_start_xmit = panda_usb_start_xmit, -}; - -static int panda_usb_probe(struct usb_interface *intf, const struct usb_device_id *id) -{ - struct net_device *netdev; - struct panda_inf_priv *priv_inf; - int err = -ENOMEM; - int inf_num; - struct panda_dev_priv *priv_dev; - struct usb_device *usbdev = interface_to_usbdev(intf); - - priv_dev = kzalloc(sizeof(struct panda_dev_priv), GFP_KERNEL); - if (!priv_dev) { - dev_err(&intf->dev, "Couldn't alloc priv_dev\n"); - return -ENOMEM; - } - priv_dev->udev = usbdev; - priv_dev->dev = &intf->dev; - usb_set_intfdata(intf, priv_dev); - - ////// Interface privs - for (inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) { - netdev = alloc_candev(sizeof(struct panda_inf_priv), PANDA_MAX_TX_URBS); - if (!netdev) { - dev_err(&intf->dev, "Couldn't alloc candev\n"); - goto cleanup_candev; - } - netdev->netdev_ops = &panda_netdev_ops; - netdev->flags |= IFF_ECHO; /* we support local echo */ - - priv_inf = netdev_priv(netdev); - priv_inf->netdev = netdev; - priv_inf->priv_dev = priv_dev; - priv_inf->interface_num = inf_num; - priv_inf->mcu_can_ifnum = can_numbering[inf_num]; - - init_usb_anchor(&priv_dev->rx_submitted); - init_usb_anchor(&priv_inf->tx_submitted); - - /* Init CAN device */ - priv_inf->can.state = CAN_STATE_STOPPED; - priv_inf->can.bittiming.bitrate = PANDA_BITRATE; - - SET_NETDEV_DEV(netdev, &intf->dev); - - err = register_candev(netdev); - if (err) { - netdev_err(netdev, "couldn't register PANDA CAN device: %d\n", err); - free_candev(priv_inf->netdev); - goto cleanup_candev; - } - - priv_dev->interfaces[inf_num] = priv_inf; - } - - err = panda_usb_start(priv_dev); - if (err) { - dev_err(&intf->dev, "Failed to initialize Comma.ai Panda CAN controller\n"); - goto cleanup_candev; - } - - err = panda_set_output_enable(priv_inf, true); - if (err) { - dev_info(&intf->dev, "Failed to initialize send enable message to Panda.\n"); - goto cleanup_candev; - } - - dev_info(&intf->dev, "Comma.ai Panda CAN controller connected\n"); - - return 0; - - cleanup_candev: - for (inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) { - priv_inf = priv_dev->interfaces[inf_num]; - if (priv_inf) { - unregister_candev(priv_inf->netdev); - free_candev(priv_inf->netdev); - } else { - break; - } - } - - kfree(priv_dev); - - return err; -} - -/* Called by the usb core when driver is unloaded or device is removed */ -static void panda_usb_disconnect(struct usb_interface *intf) -{ - struct panda_dev_priv *priv_dev = usb_get_intfdata(intf); - struct panda_inf_priv *priv_inf; - int inf_num; - - usb_set_intfdata(intf, NULL); - - for (inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) { - priv_inf = priv_dev->interfaces[inf_num]; - if (priv_inf) { - netdev_info(priv_inf->netdev, "device disconnected\n"); - unregister_candev(priv_inf->netdev); - free_candev(priv_inf->netdev); - } else { - break; - } - } - - panda_urb_unlink(priv_inf); - kfree(priv_dev); -} - -static struct usb_driver panda_usb_driver = { - .name = PANDA_MODULE_NAME, - .probe = panda_usb_probe, - .disconnect = panda_usb_disconnect, - .id_table = panda_usb_table, -}; - -module_usb_driver(panda_usb_driver); - -MODULE_LICENSE("GPL"); -MODULE_AUTHOR("Jessy Diamond Exum "); -MODULE_DESCRIPTION("SocketCAN driver for Comma.ai's Panda Adapter."); -MODULE_VERSION("0.1"); diff --git a/panda/drivers/linux/test/Makefile b/panda/drivers/linux/test/Makefile deleted file mode 100644 index c73945e4cd..0000000000 --- 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 1f44efc76e..0000000000 --- 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 100755 index 5301719b49..0000000000 --- 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/mypy.ini b/panda/mypy.ini deleted file mode 100644 index 0b6de30d80..0000000000 --- a/panda/mypy.ini +++ /dev/null @@ -1,11 +0,0 @@ -[mypy] -; third-party packages -ignore_missing_imports = True - -; helpful warnings -warn_redundant_casts = True -warn_unreachable = True -warn_unused_ignores = True - -; restrict dynamic typing -warn_return_any = True diff --git a/panda/panda.png b/panda/panda.png deleted file mode 100644 index e18137d872..0000000000 Binary files a/panda/panda.png and /dev/null differ diff --git a/panda/pyproject.toml b/panda/pyproject.toml index 5b0697d67b..8f29ec6634 100644 --- a/panda/pyproject.toml +++ b/panda/pyproject.toml @@ -1,3 +1,60 @@ +[project] +name = "pandacan" +version = "0.0.10" +description = "Code powering the comma.ai panda" +readme = "README.md" +requires-python = ">=3.11,<3.13" +license = {text = "MIT"} +authors = [{name = "comma.ai"}] +classifiers = [ + "Natural Language :: English", + "Programming Language :: Python :: 3", + "Topic :: System :: Hardware", +] +dependencies = [ + "libusb1", +] + +[project.optional-dependencies] +dev = [ + "scons", + "pycryptodome >= 3.9.8", + "cffi", + "flaky", + "pytest", + "pytest-mock", + "pytest-xdist", + "pytest-timeout", + "pytest-randomly", + "ruff", + "mypy", + "spidev", + "setuptools", + "opendbc @ git+https://github.com/commaai/opendbc.git@45bf6c8f548473dece52f780f60bd8e20c32bd65#egg=opendbc", +] + +[build-system] +requires = ["setuptools>=61", "wheel"] +build-backend = "setuptools.build_meta" + +[tool.setuptools] +packages = ["panda"] + +[tool.setuptools.package-dir] +panda = "." + +[tool.mypy] +# third-party packages +ignore_missing_imports = true + +# helpful warnings +warn_redundant_casts = true +warn_unreachable = true +warn_unused_ignores = true + +# restrict dynamic typing +warn_return_any = true + # https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml [tool.ruff] line-length = 160 @@ -12,4 +69,8 @@ flake8-implicit-str-concat.allow-multiline=false "pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" [tool.pytest.ini_options] -addopts = "-n auto --ignore-glob='*.sh'" +addopts = "-n0 -Werror --strict-config --strict-markers --durations=10 --ignore-glob='*.sh' --ignore=tests/misra --ignore=tests/som --ignore=tests/hitl" +python_files = "test_*.py" +testpaths = [ + "tests/" +] \ No newline at end of file diff --git a/panda/release/.gitignore b/panda/release/.gitignore deleted file mode 100644 index c4c4ffc6aa..0000000000 --- a/panda/release/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*.zip diff --git a/panda/tests/benchmark.py b/panda/scripts/benchmark.py similarity index 100% rename from panda/tests/benchmark.py rename to panda/scripts/benchmark.py diff --git a/panda/tests/black_white_loopback_test.py b/panda/scripts/black_white_loopback_test.py similarity index 100% rename from panda/tests/black_white_loopback_test.py rename to panda/scripts/black_white_loopback_test.py diff --git a/panda/tests/black_white_relay_endurance.py b/panda/scripts/black_white_relay_endurance.py similarity index 100% rename from panda/tests/black_white_relay_endurance.py rename to panda/scripts/black_white_relay_endurance.py diff --git a/panda/tests/black_white_relay_test.py b/panda/scripts/black_white_relay_test.py similarity index 100% rename from panda/tests/black_white_relay_test.py rename to panda/scripts/black_white_relay_test.py diff --git a/panda/tests/bulk_write_test.py b/panda/scripts/bulk_write_test.py similarity index 100% rename from panda/tests/bulk_write_test.py rename to panda/scripts/bulk_write_test.py diff --git a/panda/tests/can_health.py b/panda/scripts/can_health.py similarity index 100% rename from panda/tests/can_health.py rename to panda/scripts/can_health.py diff --git a/panda/tests/can_printer.py b/panda/scripts/can_printer.py similarity index 100% rename from panda/tests/can_printer.py rename to panda/scripts/can_printer.py diff --git a/panda/tests/check_fw_size.py b/panda/scripts/check_fw_size.py similarity index 100% rename from panda/tests/check_fw_size.py rename to panda/scripts/check_fw_size.py diff --git a/panda/tests/debug_console.py b/panda/scripts/debug_console.py similarity index 100% rename from panda/tests/debug_console.py rename to panda/scripts/debug_console.py diff --git a/panda/tests/development/register_hashmap_spread.py b/panda/scripts/development/register_hashmap_spread.py similarity index 100% rename from panda/tests/development/register_hashmap_spread.py rename to panda/scripts/development/register_hashmap_spread.py diff --git a/panda/tests/echo.py b/panda/scripts/echo.py similarity index 100% rename from panda/tests/echo.py rename to panda/scripts/echo.py diff --git a/panda/tests/fan/fan_test.py b/panda/scripts/fan/fan_test.py similarity index 100% rename from panda/tests/fan/fan_test.py rename to panda/scripts/fan/fan_test.py diff --git a/panda/tests/fan/fan_tuning.py b/panda/scripts/fan/fan_tuning.py similarity index 100% rename from panda/tests/fan/fan_tuning.py rename to panda/scripts/fan/fan_tuning.py diff --git a/panda/tests/get_version.py b/panda/scripts/get_version.py similarity index 100% rename from panda/tests/get_version.py rename to panda/scripts/get_version.py diff --git a/panda/tests/health_test.py b/panda/scripts/health_test.py similarity index 100% rename from panda/tests/health_test.py rename to panda/scripts/health_test.py diff --git a/panda/tests/ir_test.py b/panda/scripts/ir_test.py similarity index 100% rename from panda/tests/ir_test.py rename to panda/scripts/ir_test.py diff --git a/panda/tests/loopback_test.py b/panda/scripts/loopback_test.py similarity index 100% rename from panda/tests/loopback_test.py rename to panda/scripts/loopback_test.py diff --git a/panda/release/make_release.sh b/panda/scripts/make_release.sh similarity index 100% rename from panda/release/make_release.sh rename to panda/scripts/make_release.sh diff --git a/panda/tests/message_drop_test.py b/panda/scripts/message_drop_test.py similarity index 100% rename from panda/tests/message_drop_test.py rename to panda/scripts/message_drop_test.py diff --git a/panda/tests/read_flash_spi.py b/panda/scripts/read_flash_spi.py similarity index 100% rename from panda/tests/read_flash_spi.py rename to panda/scripts/read_flash_spi.py diff --git a/panda/tests/read_st_flash.sh b/panda/scripts/read_st_flash.sh similarity index 100% rename from panda/tests/read_st_flash.sh rename to panda/scripts/read_st_flash.sh diff --git a/panda/tests/reflash_internal_panda.py b/panda/scripts/reflash_internal_panda.py similarity index 100% rename from panda/tests/reflash_internal_panda.py rename to panda/scripts/reflash_internal_panda.py diff --git a/panda/tests/relay_test.py b/panda/scripts/relay_test.py similarity index 100% rename from panda/tests/relay_test.py rename to panda/scripts/relay_test.py diff --git a/panda/tests/restore_flash_spi.py b/panda/scripts/restore_flash_spi.py similarity index 100% rename from panda/tests/restore_flash_spi.py rename to panda/scripts/restore_flash_spi.py diff --git a/panda/tests/som_debug.sh b/panda/scripts/som_debug.sh similarity index 100% rename from panda/tests/som_debug.sh rename to panda/scripts/som_debug.sh diff --git a/panda/tests/spam_can.py b/panda/scripts/spam_can.py similarity index 100% rename from panda/tests/spam_can.py rename to panda/scripts/spam_can.py diff --git a/panda/tests/standalone_test.py b/panda/scripts/standalone_test.py similarity index 100% rename from panda/tests/standalone_test.py rename to panda/scripts/standalone_test.py diff --git a/panda/tests/canfd/test_canfd.py b/panda/scripts/test_canfd.py similarity index 100% rename from panda/tests/canfd/test_canfd.py rename to panda/scripts/test_canfd.py diff --git a/panda/setup.cfg b/panda/setup.cfg deleted file mode 100644 index 3480374bc2..0000000000 --- a/panda/setup.cfg +++ /dev/null @@ -1,2 +0,0 @@ -[bdist_wheel] -universal=1 \ No newline at end of file diff --git a/panda/setup.py b/panda/setup.py deleted file mode 100644 index a7729cc6f8..0000000000 --- a/panda/setup.py +++ /dev/null @@ -1,78 +0,0 @@ -""" - Panda CAN Controller Dongle - ~~~~~ - - Setup - ````` - - $ pip install . # or python setup.py install -""" - -import codecs -import os -import re -from setuptools import setup - -here = os.path.abspath(os.path.dirname(__file__)) - -def read(*parts): - """Taken from pypa pip setup.py: - intentionally *not* adding an encoding option to open, See: - https://github.com/pypa/virtualenv/issues/201#issuecomment-3145690 - """ - return codecs.open(os.path.join(here, *parts), 'r').read() - - -def find_version(*file_paths): - version_file = read(*file_paths) - version_match = re.search(r"^__version__ = ['\"]([^'\"]*)['\"]", - version_file, re.M) - if version_match: - return version_match.group(1) - raise RuntimeError("Unable to find version string.") - -setup( - name='pandacan', - version=find_version("python", "__init__.py"), - url='https://github.com/commaai/panda', - author='comma.ai', - author_email='', - packages=[ - 'panda', - ], - package_dir={'panda': 'python'}, - platforms='any', - license='MIT', - install_requires=[ - 'libusb1', - ], - extras_require = { - 'dev': [ - "scons", - "pycryptodome >= 3.9.8", - "cffi", - "flaky", - "pytest", - "pytest-mock", - "pytest-xdist", - "pytest-timeout", - "pytest-randomly", - "parameterized", - "pre-commit", - "numpy", - "ruff", - "spidev", - "setuptools", # for setup.py - ], - }, - ext_modules=[], - description="Code powering the comma.ai panda", - long_description='See https://github.com/commaai/panda', - classifiers=[ - 'Development Status :: 2 - Pre-Alpha', - "Natural Language :: English", - "Programming Language :: Python :: 2", - "Programming Language :: Python :: 3", - "Topic :: System :: Hardware", - ], -) diff --git a/panda/setup.sh b/panda/setup.sh new file mode 100755 index 0000000000..647bcd22d6 --- /dev/null +++ b/panda/setup.sh @@ -0,0 +1,31 @@ +#!/usr/bin/env bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +PLATFORM=$(uname -s) + +echo "installing dependencies" +if [[ $PLATFORM == "Darwin" ]]; then + brew install --cask gcc-arm-embedded + brew install python3 gcc@13 +elif [[ $PLATFORM == "Linux" ]]; then + sudo apt-get install -y --no-install-recommends \ + curl \ + make g++ git libnewlib-arm-none-eabi \ + libusb-1.0-0 \ + gcc-arm-none-eabi python3-pip python3-venv python3-dev +else + echo "WARNING: unsupported platform. skipping apt/brew install." +fi + +if ! command -v uv &>/dev/null; then + echo "'uv' is not installed. Installing 'uv'..." + curl -LsSf https://astral.sh/uv/install.sh | sh + source $HOME/.local/bin/env || true +fi + +export UV_PROJECT_ENVIRONMENT="$DIR/.venv" +uv sync --all-extras +source "$DIR/.venv/bin/activate" diff --git a/panda/test.sh b/panda/test.sh new file mode 100755 index 0000000000..7287977124 --- /dev/null +++ b/panda/test.sh @@ -0,0 +1,21 @@ +#!/usr/bin/env bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +# *** env setup *** +source ./setup.sh + +# *** build *** +scons -j8 + +# *** lint *** +ruff check . +mypy python/ + + +# *** test *** + +# TODO: make xdist and randomly work +pytest -n0 --randomly-dont-reorganize tests/ diff --git a/panda/tests/ci_shell.sh b/panda/tests/ci_shell.sh deleted file mode 100755 index ab87f36cae..0000000000 --- a/panda/tests/ci_shell.sh +++ /dev/null @@ -1,21 +0,0 @@ -#!/usr/bin/env bash -set -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/elm_car_simulator.py b/panda/tests/elm_car_simulator.py deleted file mode 100755 index e297eb045e..0000000000 --- a/panda/tests/elm_car_simulator.py +++ /dev/null @@ -1,233 +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 opendbc.car.structs import CarParams -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(CarParams.SafetyModel.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, 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, 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, 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 100755 index 983d4a1416..0000000000 --- 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/hitl/2_health.py b/panda/tests/hitl/2_health.py index d44633c6ef..d6c602737b 100644 --- a/panda/tests/hitl/2_health.py +++ b/panda/tests/hitl/2_health.py @@ -38,10 +38,10 @@ def test_hw_type(p): 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=CarParams.SafetyModel.hyundai, param=HyundaiSafetyFlags.FLAG_HYUNDAI_LONG) + p.set_safety_mode(mode=CarParams.SafetyModel.hyundai, param=HyundaiSafetyFlags.LONG) p.send_heartbeat() assert p.health()['safety_mode'] == CarParams.SafetyModel.hyundai - assert p.health()['safety_param'] == HyundaiSafetyFlags.FLAG_HYUNDAI_LONG + assert p.health()['safety_param'] == HyundaiSafetyFlags.LONG # shouldn't do anything once we're in a car safety mode p.set_heartbeat_disabled() diff --git a/panda/tests/libpanda/SConscript b/panda/tests/libpanda/SConscript index a690ba7577..fc6807236b 100644 --- a/panda/tests/libpanda/SConscript +++ b/panda/tests/libpanda/SConscript @@ -1,10 +1,15 @@ +import opendbc 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 +mac_ver = platform.mac_ver() + +# 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 +# clang works on macOS 15 and greater but has issues on earlier macOS versions. +# see: https://github.com/commaai/openpilot/issues/35093 +if system == 'Darwin' and mac_ver[0] and mac_ver[0] < '15': CC += '-13' env = Environment( @@ -16,23 +21,11 @@ env = Environment( '-Wfatal-errors', '-Wno-pointer-to-int-cast', ], - CPPPATH=[".", "../../board/", "../../../opendbc/safety/"], + CPPPATH=[".", "../../board/", opendbc.INCLUDE_PATH], ) if system == "Darwin": env.PrependENVPath('PATH', '/opt/homebrew/bin') -if GetOption('mutation'): - env['CC'] = 'clang-17' - flags = [ - '-fprofile-instr-generate', - '-fcoverage-mapping', - '-fpass-plugin=/usr/lib/mull-ir-frontend-17', - '-g', - '-grecord-command-line', - ] - env['CFLAGS'] += flags - env['LINKFLAGS'] += flags - if GetOption('ubsan'): flags = [ "-fsanitize=undefined", @@ -43,12 +36,3 @@ if GetOption('ubsan'): 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/panda.c b/panda/tests/libpanda/panda.c index 303d72e7d0..2d17d64e34 100644 --- a/panda/tests/libpanda/panda.c +++ b/panda/tests/libpanda/panda.c @@ -15,7 +15,7 @@ void can_tx_comms_resume_spi(void) { }; #include "faults.h" #include "libc.h" #include "boards/board_declarations.h" -#include "safety.h" +#include "opendbc/safety/safety.h" #include "main_definitions.h" #include "drivers/can_common.h" diff --git a/panda/tests/misra/test_misra.sh b/panda/tests/misra/test_misra.sh index aaa7b0c365..3b16863bf3 100755 --- a/panda/tests/misra/test_misra.sh +++ b/panda/tests/misra/test_misra.sh @@ -3,6 +3,7 @@ set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" PANDA_DIR=$(realpath $DIR/../../) +OPENDBC_ROOT=$(python3 -c "import opendbc; print(opendbc.INCLUDE_PATH)") GREEN="\e[1;32m" YELLOW="\e[1;33m" @@ -47,7 +48,7 @@ cppcheck() { $CPPCHECK_DIR/cppcheck --inline-suppr -I $PANDA_DIR/board/ \ -I "$(arm-none-eabi-gcc -print-file-name=include)" \ -I $PANDA_DIR/board/stm32f4/inc/ -I $PANDA_DIR/board/stm32h7/inc/ \ - -I $PANDA_DIR/../opendbc/safety/ \ + -I $OPENDBC_ROOT \ --suppressions-list=$DIR/suppressions.txt --suppress=*:*inc/* \ --suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive --safety \ --platform=arm32-wchar_t4 $COMMON_DEFINES --checkers-report=$CHECKLIST.tmp \ diff --git a/panda/tests/misra/test_mutation.py b/panda/tests/misra/test_mutation.py index db955a8f44..8996d8aeda 100755 --- a/panda/tests/misra/test_mutation.py +++ b/panda/tests/misra/test_mutation.py @@ -64,11 +64,13 @@ assert len(files) > 70, all(d in files for d in ('board/main.c', 'board/stm32f4/ for p in patterns: mutations.append((random.choice(files), p, True)) +# TODO: remove sampling once test_misra.sh is faster +mutations = random.sample(mutations, 2) + @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 + "/panda", dirs_exist_ok=True) - shutil.copytree(ROOT + "../opendbc", tmp + "/opendbc", dirs_exist_ok=True) # apply patch if fn is not None: diff --git a/panda/tests/read_winusb_descriptors.py b/panda/tests/read_winusb_descriptors.py deleted file mode 100755 index 5d311c9ea9..0000000000 --- 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/test_rsa.c b/panda/tests/test_rsa.c deleted file mode 100644 index 5c784e23a4..0000000000 --- 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/usbprotocol/test.sh b/panda/tests/usbprotocol/test.sh deleted file mode 100755 index b4c32166b9..0000000000 --- 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 python3 -m unittest discover . -done diff --git a/pyproject.toml b/pyproject.toml index 1fb751e2d5..b9a9fcab55 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -26,7 +26,7 @@ dependencies = [ "pycapnp", "Cython", "setuptools", - "numpy < 2.0.0", + "numpy >=2.0, <2.2", # Linting issues with mypy in 2.2 # body / webrtcd "aiohttp", @@ -47,6 +47,7 @@ dependencies = [ # logging "pyzmq", "sentry-sdk", + "xattr", # used in place of 'os.getxattr' for macos compatibility # athena "PyJWT", @@ -122,7 +123,7 @@ tools = [ ] [project.urls] -Homepage = "https://comma.ai" +Homepage = "https://github.com/commaai/openpilot" [build-system] requires = ["hatchling"] @@ -168,9 +169,9 @@ testpaths = [ [tool.codespell] quiet-level = 3 # if you've got a short variable name that's getting flagged, add it here -ignore-words-list = "bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup,bumb,nd,sie,preints,whit,indexIn,ws,uint,grey,deque,stdio,amin,BA,LITE,atEnd,UIs,errorString,arange,FocusIn,od,tim,relA,hist,copyable,jupyter,thead,TGE,abl" +ignore-words-list = "bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup,bumb,nd,sie,preints,whit,indexIn,ws,uint,grey,deque,stdio,amin,BA,LITE,atEnd,UIs,errorString,arange,FocusIn,od,tim,relA,hist,copyable,jupyter,thead,TGE,abl,lite" builtin = "clear,rare,informal,code,names,en-GB_to_en-US" -skip = "./third_party/*, ./tinygrad/*, ./tinygrad_repo/*, ./msgq/*, ./panda/*, ./opendbc/*, ./opendbc_repo/*, ./rednose/*, ./rednose_repo/*, ./teleoprtc/*, ./teleoprtc_repo/*, *.ts, uv.lock, *.onnx, ./cereal/gen/*, */c_generated_code/*" +skip = "./third_party/*, ./tinygrad/*, ./tinygrad_repo/*, ./msgq/*, ./panda/*, ./opendbc/*, ./opendbc_repo/*, ./rednose/*, ./rednose_repo/*, ./teleoprtc/*, ./teleoprtc_repo/*, *.ts, uv.lock, *.onnx, ./cereal/gen/*, */c_generated_code/*, docs/assets/*" [tool.mypy] python_version = "3.11" diff --git a/release/build_release.sh b/release/build_release.sh index 735ef5e043..220da05c17 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -40,8 +40,6 @@ 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" diff --git a/release/pack.py b/release/pack.py new file mode 100755 index 0000000000..1cb1a47a48 --- /dev/null +++ b/release/pack.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python3 + +import importlib +import shutil +import sys +import tempfile +import zipapp +from argparse import ArgumentParser +from pathlib import Path + +from openpilot.common.basedir import BASEDIR + + +DIRS = ['cereal', 'openpilot'] +EXTS = ['.png', '.py', '.ttf', '.capnp'] +INTERPRETER = '/usr/bin/env python3' + + +def copy(src, dest): + if any(src.endswith(ext) for ext in EXTS): + shutil.copy2(src, dest, follow_symlinks=True) + + +if __name__ == '__main__': + parser = ArgumentParser(prog='pack.py', description="package script into a portable executable", epilog='comma.ai') + parser.add_argument('-e', '--entrypoint', help="function to call in module, default is 'main'", default='main') + parser.add_argument('-o', '--output', help='output file') + parser.add_argument('module', help="the module to target, e.g. 'openpilot.system.ui.spinner'") + args = parser.parse_args() + + if not args.output: + args.output = args.module + + try: + mod = importlib.import_module(args.module) + except ModuleNotFoundError: + print(f'{args.module} not found, typo?') + sys.exit(1) + + if not hasattr(mod, args.entrypoint): + print(f'{args.module} does not have a {args.entrypoint}() function, typo?') + sys.exit(1) + + with tempfile.TemporaryDirectory() as tmp: + for directory in DIRS: + shutil.copytree(BASEDIR + '/' + directory, tmp + '/' + directory, symlinks=False, dirs_exist_ok=True, copy_function=copy) + entry = f'{args.module}:{args.entrypoint}' + zipapp.create_archive(tmp, target=args.output, interpreter=INTERPRETER, main=entry) + + print(f'created executable {Path(args.output).resolve()}') diff --git a/scripts/jenkins_loop_test.sh b/scripts/jenkins_loop_test.sh index 0b242e98dc..8073f4668c 100755 --- a/scripts/jenkins_loop_test.sh +++ b/scripts/jenkins_loop_test.sh @@ -16,7 +16,7 @@ CRUMB=$(curl -s --cookie-jar $COOKIE_JAR 'https://jenkins.comma.life/crumbIssuer FIRST_LOOP=1 function loop() { - JENKINS_BRANCH="__jenkins_loop_${BRANCH}" + JENKINS_BRANCH="__jenkins_loop_${BRANCH}_$(date +%s)" API_ROUTE="https://jenkins.comma.life/job/openpilot/job/$JENKINS_BRANCH" for run in $(seq 1 $((RUNS / 2))); do diff --git a/scripts/reporter.py b/scripts/reporter.py new file mode 100755 index 0000000000..903fcc8911 --- /dev/null +++ b/scripts/reporter.py @@ -0,0 +1,31 @@ +#!/usr/bin/env python3 +import os +import glob +import onnx + +BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) +MASTER_PATH = os.getenv("MASTER_PATH", BASEDIR) +MODEL_PATH = "/selfdrive/modeld/models/" + +def get_checkpoint(f): + model = onnx.load(f) + metadata = {prop.key: prop.value for prop in model.metadata_props} + return metadata['model_checkpoint'].split('/')[0] + +if __name__ == "__main__": + print("| | master | PR branch |") + print("|-| ----- | --------- |") + + for f in glob.glob(BASEDIR + MODEL_PATH + "/*.onnx"): + # TODO: add checkpoint to DM + if "dmonitoring" in f: + continue + + fn = os.path.basename(f) + master = get_checkpoint(MASTER_PATH + MODEL_PATH + fn) + pr = get_checkpoint(BASEDIR + MODEL_PATH + fn) + print( + "|", fn, "|", + f"[{master}](https://reporter.comma.life/experiment/{master})", "|", + f"[{pr}](https://reporter.comma.life/experiment/{pr})", "|" + ) diff --git a/selfdrive/assets/assets.qrc b/selfdrive/assets/assets.qrc index 6d8d8df334..26a7d998ed 100644 --- a/selfdrive/assets/assets.qrc +++ b/selfdrive/assets/assets.qrc @@ -1,19 +1,19 @@ ../../third_party/bootstrap/bootstrap-icons.svg - img_continue_triangle.svg - img_circled_check.svg - img_circled_slash.svg - img_eye_open.svg - img_eye_closed.svg + images/button_continue_triangle.svg + icons/circled_check.svg + icons/circled_slash.svg + icons/eye_open.svg + icons/eye_closed.svg icons/close.svg - offroad/icon_lock_closed.svg - offroad/icon_checkmark.svg - offroad/icon_warning.png - offroad/icon_wifi_strength_low.svg - offroad/icon_wifi_strength_medium.svg - offroad/icon_wifi_strength_high.svg - offroad/icon_wifi_strength_full.svg + icons/lock_closed.svg + icons/checkmark.svg + icons/warning.png + icons/wifi_strength_low.svg + icons/wifi_strength_medium.svg + icons/wifi_strength_high.svg + icons/wifi_strength_full.svg ../ui/translations/languages.json diff --git a/selfdrive/assets/icons/arrow-right.png b/selfdrive/assets/icons/arrow-right.png new file mode 100644 index 0000000000..7040293836 Binary files /dev/null and b/selfdrive/assets/icons/arrow-right.png differ diff --git a/selfdrive/assets/icons/backspace.png b/selfdrive/assets/icons/backspace.png new file mode 100644 index 0000000000..0de132aab5 Binary files /dev/null and b/selfdrive/assets/icons/backspace.png differ diff --git a/selfdrive/assets/offroad/icon_calibration.png b/selfdrive/assets/icons/calibration.png similarity index 100% rename from selfdrive/assets/offroad/icon_calibration.png rename to selfdrive/assets/icons/calibration.png diff --git a/selfdrive/assets/icons/capslock-fill.png b/selfdrive/assets/icons/capslock-fill.png new file mode 100644 index 0000000000..e52f3ec2f0 Binary files /dev/null and b/selfdrive/assets/icons/capslock-fill.png differ diff --git a/selfdrive/assets/icons/checkmark.png b/selfdrive/assets/icons/checkmark.png new file mode 100644 index 0000000000..c1886defdc Binary files /dev/null and b/selfdrive/assets/icons/checkmark.png differ diff --git a/selfdrive/assets/icons/checkmark.svg b/selfdrive/assets/icons/checkmark.svg new file mode 100644 index 0000000000..bb04a2b12e --- /dev/null +++ b/selfdrive/assets/icons/checkmark.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/offroad/icon_chevron_right.png b/selfdrive/assets/icons/chevron_right.png similarity index 100% rename from selfdrive/assets/offroad/icon_chevron_right.png rename to selfdrive/assets/icons/chevron_right.png diff --git a/selfdrive/assets/img_chffr_wheel.png b/selfdrive/assets/icons/chffr_wheel.png similarity index 100% rename from selfdrive/assets/img_chffr_wheel.png rename to selfdrive/assets/icons/chffr_wheel.png diff --git a/selfdrive/assets/icons/circled_check.png b/selfdrive/assets/icons/circled_check.png new file mode 100644 index 0000000000..a29a613bff Binary files /dev/null and b/selfdrive/assets/icons/circled_check.png differ diff --git a/selfdrive/assets/icons/circled_check.svg b/selfdrive/assets/icons/circled_check.svg new file mode 100644 index 0000000000..03cc81109b --- /dev/null +++ b/selfdrive/assets/icons/circled_check.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/icons/circled_slash.png b/selfdrive/assets/icons/circled_slash.png new file mode 100644 index 0000000000..cf22b9c192 Binary files /dev/null and b/selfdrive/assets/icons/circled_slash.png differ diff --git a/selfdrive/assets/icons/circled_slash.svg b/selfdrive/assets/icons/circled_slash.svg new file mode 100644 index 0000000000..5f22233ef6 --- /dev/null +++ b/selfdrive/assets/icons/circled_slash.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/icons/close.png b/selfdrive/assets/icons/close.png new file mode 100644 index 0000000000..9c39fce89d Binary files /dev/null and b/selfdrive/assets/icons/close.png differ diff --git a/selfdrive/assets/icons/close.svg b/selfdrive/assets/icons/close.svg index b1e6d3b867..6927cede05 100644 --- a/selfdrive/assets/icons/close.svg +++ b/selfdrive/assets/icons/close.svg @@ -1,4 +1,3 @@ - - - + + diff --git a/selfdrive/assets/icons/close2.png b/selfdrive/assets/icons/close2.png new file mode 100644 index 0000000000..055a2970ff Binary files /dev/null and b/selfdrive/assets/icons/close2.png differ diff --git a/selfdrive/assets/icons/close2.svg b/selfdrive/assets/icons/close2.svg new file mode 100644 index 0000000000..be1385848f --- /dev/null +++ b/selfdrive/assets/icons/close2.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/icons/couch.png b/selfdrive/assets/icons/couch.png new file mode 100644 index 0000000000..bde02c0b7e Binary files /dev/null and b/selfdrive/assets/icons/couch.png differ diff --git a/selfdrive/assets/icons/couch.svg b/selfdrive/assets/icons/couch.svg new file mode 100644 index 0000000000..6317cf92f3 --- /dev/null +++ b/selfdrive/assets/icons/couch.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/icons/disengage_on_accelerator.png b/selfdrive/assets/icons/disengage_on_accelerator.png new file mode 100644 index 0000000000..181491c05d Binary files /dev/null and b/selfdrive/assets/icons/disengage_on_accelerator.png differ diff --git a/selfdrive/assets/icons/disengage_on_accelerator.svg b/selfdrive/assets/icons/disengage_on_accelerator.svg new file mode 100644 index 0000000000..d90ba8ca5f --- /dev/null +++ b/selfdrive/assets/icons/disengage_on_accelerator.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/icons/driver_face.png similarity index 100% rename from selfdrive/assets/img_driver_face.png rename to selfdrive/assets/icons/driver_face.png diff --git a/selfdrive/assets/icons/experimental.png b/selfdrive/assets/icons/experimental.png new file mode 100644 index 0000000000..fcb1e086ab Binary files /dev/null and b/selfdrive/assets/icons/experimental.png differ diff --git a/selfdrive/assets/icons/experimental.svg b/selfdrive/assets/icons/experimental.svg new file mode 100644 index 0000000000..2be14b8084 --- /dev/null +++ b/selfdrive/assets/icons/experimental.svg @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/selfdrive/assets/icons/experimental_grey.png b/selfdrive/assets/icons/experimental_grey.png new file mode 100644 index 0000000000..9be4bd720b Binary files /dev/null and b/selfdrive/assets/icons/experimental_grey.png differ diff --git a/selfdrive/assets/icons/experimental_grey.svg b/selfdrive/assets/icons/experimental_grey.svg new file mode 100644 index 0000000000..0f77bb008e --- /dev/null +++ b/selfdrive/assets/icons/experimental_grey.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/icons/experimental_white.png b/selfdrive/assets/icons/experimental_white.png new file mode 100644 index 0000000000..4751ee5276 Binary files /dev/null and b/selfdrive/assets/icons/experimental_white.png differ diff --git a/selfdrive/assets/icons/experimental_white.svg b/selfdrive/assets/icons/experimental_white.svg new file mode 100644 index 0000000000..d5052e9d20 --- /dev/null +++ b/selfdrive/assets/icons/experimental_white.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/icons/eye_closed.png b/selfdrive/assets/icons/eye_closed.png new file mode 100644 index 0000000000..910363f752 Binary files /dev/null and b/selfdrive/assets/icons/eye_closed.png differ diff --git a/selfdrive/assets/icons/eye_closed.svg b/selfdrive/assets/icons/eye_closed.svg new file mode 100644 index 0000000000..47410a035c --- /dev/null +++ b/selfdrive/assets/icons/eye_closed.svg @@ -0,0 +1,5 @@ + + + + + diff --git a/selfdrive/assets/icons/eye_open.png b/selfdrive/assets/icons/eye_open.png new file mode 100644 index 0000000000..55b5056586 Binary files /dev/null and b/selfdrive/assets/icons/eye_open.png differ diff --git a/selfdrive/assets/icons/eye_open.svg b/selfdrive/assets/icons/eye_open.svg new file mode 100644 index 0000000000..16d34f0802 --- /dev/null +++ b/selfdrive/assets/icons/eye_open.svg @@ -0,0 +1,4 @@ + + + + diff --git a/selfdrive/assets/icons/lock_closed.png b/selfdrive/assets/icons/lock_closed.png new file mode 100644 index 0000000000..05afcaef97 Binary files /dev/null and b/selfdrive/assets/icons/lock_closed.png differ diff --git a/selfdrive/assets/icons/lock_closed.svg b/selfdrive/assets/icons/lock_closed.svg new file mode 100644 index 0000000000..923344f758 --- /dev/null +++ b/selfdrive/assets/icons/lock_closed.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/offroad/icon_menu.png b/selfdrive/assets/icons/menu.png similarity index 100% rename from selfdrive/assets/offroad/icon_menu.png rename to selfdrive/assets/icons/menu.png diff --git a/selfdrive/assets/offroad/icon_metric.png b/selfdrive/assets/icons/metric.png similarity index 100% rename from selfdrive/assets/offroad/icon_metric.png rename to selfdrive/assets/icons/metric.png diff --git a/selfdrive/assets/offroad/icon_minus.png b/selfdrive/assets/icons/minus.png similarity index 100% rename from selfdrive/assets/offroad/icon_minus.png rename to selfdrive/assets/icons/minus.png diff --git a/selfdrive/assets/offroad/icon_monitoring.png b/selfdrive/assets/icons/monitoring.png similarity index 100% rename from selfdrive/assets/offroad/icon_monitoring.png rename to selfdrive/assets/icons/monitoring.png diff --git a/selfdrive/assets/offroad/icon_network.png b/selfdrive/assets/icons/network.png similarity index 100% rename from selfdrive/assets/offroad/icon_network.png rename to selfdrive/assets/icons/network.png diff --git a/selfdrive/assets/offroad/icon_road.png b/selfdrive/assets/icons/road.png similarity index 100% rename from selfdrive/assets/offroad/icon_road.png rename to selfdrive/assets/icons/road.png diff --git a/selfdrive/assets/offroad/icon_settings.png b/selfdrive/assets/icons/settings.png similarity index 100% rename from selfdrive/assets/offroad/icon_settings.png rename to selfdrive/assets/icons/settings.png diff --git a/selfdrive/assets/offroad/icon_shell.png b/selfdrive/assets/icons/shell.png similarity index 100% rename from selfdrive/assets/offroad/icon_shell.png rename to selfdrive/assets/icons/shell.png diff --git a/selfdrive/assets/icons/shift-fill.png b/selfdrive/assets/icons/shift-fill.png new file mode 100644 index 0000000000..7cf0d25274 Binary files /dev/null and b/selfdrive/assets/icons/shift-fill.png differ diff --git a/selfdrive/assets/icons/shift.png b/selfdrive/assets/icons/shift.png new file mode 100644 index 0000000000..5847339e68 Binary files /dev/null and b/selfdrive/assets/icons/shift.png differ diff --git a/selfdrive/assets/offroad/icon_speed_limit.png b/selfdrive/assets/icons/speed_limit.png similarity index 100% rename from selfdrive/assets/offroad/icon_speed_limit.png rename to selfdrive/assets/icons/speed_limit.png diff --git a/selfdrive/assets/icons/triangle.png b/selfdrive/assets/icons/triangle.png new file mode 100644 index 0000000000..86f9156ce4 Binary files /dev/null and b/selfdrive/assets/icons/triangle.png differ diff --git a/selfdrive/assets/icons/triangle.svg b/selfdrive/assets/icons/triangle.svg new file mode 100644 index 0000000000..ef10e16e29 --- /dev/null +++ b/selfdrive/assets/icons/triangle.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/offroad/icon_warning.png b/selfdrive/assets/icons/warning.png similarity index 100% rename from selfdrive/assets/offroad/icon_warning.png rename to selfdrive/assets/icons/warning.png diff --git a/selfdrive/assets/icons/wifi_strength_full.png b/selfdrive/assets/icons/wifi_strength_full.png new file mode 100644 index 0000000000..58d3feedc6 Binary files /dev/null and b/selfdrive/assets/icons/wifi_strength_full.png differ diff --git a/selfdrive/assets/icons/wifi_strength_full.svg b/selfdrive/assets/icons/wifi_strength_full.svg new file mode 100644 index 0000000000..96af037992 --- /dev/null +++ b/selfdrive/assets/icons/wifi_strength_full.svg @@ -0,0 +1,5 @@ + + + + + diff --git a/selfdrive/assets/icons/wifi_strength_high.png b/selfdrive/assets/icons/wifi_strength_high.png new file mode 100644 index 0000000000..327a75b2a3 Binary files /dev/null and b/selfdrive/assets/icons/wifi_strength_high.png differ diff --git a/selfdrive/assets/icons/wifi_strength_high.svg b/selfdrive/assets/icons/wifi_strength_high.svg new file mode 100644 index 0000000000..63fc8bc0bc --- /dev/null +++ b/selfdrive/assets/icons/wifi_strength_high.svg @@ -0,0 +1,5 @@ + + + + + diff --git a/selfdrive/assets/icons/wifi_strength_low.png b/selfdrive/assets/icons/wifi_strength_low.png new file mode 100644 index 0000000000..5464acfd2b Binary files /dev/null and b/selfdrive/assets/icons/wifi_strength_low.png differ diff --git a/selfdrive/assets/icons/wifi_strength_low.svg b/selfdrive/assets/icons/wifi_strength_low.svg new file mode 100644 index 0000000000..5bc67bed5c --- /dev/null +++ b/selfdrive/assets/icons/wifi_strength_low.svg @@ -0,0 +1,6 @@ + + + + + + diff --git a/selfdrive/assets/icons/wifi_strength_medium.png b/selfdrive/assets/icons/wifi_strength_medium.png new file mode 100644 index 0000000000..5340423e58 Binary files /dev/null and b/selfdrive/assets/icons/wifi_strength_medium.png differ diff --git a/selfdrive/assets/icons/wifi_strength_medium.svg b/selfdrive/assets/icons/wifi_strength_medium.svg new file mode 100644 index 0000000000..9030dbc568 --- /dev/null +++ b/selfdrive/assets/icons/wifi_strength_medium.svg @@ -0,0 +1,5 @@ + + + + + diff --git a/selfdrive/assets/icons/wifi_uploading.png b/selfdrive/assets/icons/wifi_uploading.png new file mode 100644 index 0000000000..e0aa598fba Binary files /dev/null and b/selfdrive/assets/icons/wifi_uploading.png differ diff --git a/selfdrive/assets/icons/wifi_uploading.svg b/selfdrive/assets/icons/wifi_uploading.svg new file mode 100644 index 0000000000..1c1c9af45e --- /dev/null +++ b/selfdrive/assets/icons/wifi_uploading.svg @@ -0,0 +1,5 @@ + + + + + diff --git a/selfdrive/assets/images/button_continue_triangle.png b/selfdrive/assets/images/button_continue_triangle.png new file mode 100644 index 0000000000..eeacfeb830 Binary files /dev/null and b/selfdrive/assets/images/button_continue_triangle.png differ diff --git a/selfdrive/assets/images/button_continue_triangle.svg b/selfdrive/assets/images/button_continue_triangle.svg new file mode 100644 index 0000000000..814b36c4b0 --- /dev/null +++ b/selfdrive/assets/images/button_continue_triangle.svg @@ -0,0 +1,3 @@ + + + diff --git a/selfdrive/assets/img_spinner_comma.png b/selfdrive/assets/images/spinner_comma.png similarity index 100% rename from selfdrive/assets/img_spinner_comma.png rename to selfdrive/assets/images/spinner_comma.png diff --git a/selfdrive/assets/img_spinner_track.png b/selfdrive/assets/images/spinner_track.png similarity index 100% rename from selfdrive/assets/img_spinner_track.png rename to selfdrive/assets/images/spinner_track.png diff --git a/selfdrive/assets/images/triangle.svg b/selfdrive/assets/images/triangle.svg deleted file mode 100644 index 9320269bde..0000000000 --- a/selfdrive/assets/images/triangle.svg +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - diff --git a/selfdrive/assets/img_circled_check.svg b/selfdrive/assets/img_circled_check.svg deleted file mode 100644 index 27c37395b2..0000000000 --- a/selfdrive/assets/img_circled_check.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/img_circled_slash.svg b/selfdrive/assets/img_circled_slash.svg deleted file mode 100644 index b10a3938d5..0000000000 --- a/selfdrive/assets/img_circled_slash.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/img_continue_triangle.svg b/selfdrive/assets/img_continue_triangle.svg deleted file mode 100644 index 20f9e45dcf..0000000000 --- a/selfdrive/assets/img_continue_triangle.svg +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/selfdrive/assets/img_couch.svg b/selfdrive/assets/img_couch.svg deleted file mode 100644 index 2e86012809..0000000000 --- a/selfdrive/assets/img_couch.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/img_experimental.svg b/selfdrive/assets/img_experimental.svg deleted file mode 100644 index 0eaec3b3cd..0000000000 --- a/selfdrive/assets/img_experimental.svg +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/selfdrive/assets/img_experimental_grey.svg b/selfdrive/assets/img_experimental_grey.svg deleted file mode 100644 index dc87105ac5..0000000000 --- a/selfdrive/assets/img_experimental_grey.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/img_experimental_white.svg b/selfdrive/assets/img_experimental_white.svg deleted file mode 100644 index ae4f18fde2..0000000000 --- a/selfdrive/assets/img_experimental_white.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/img_eye_closed.svg b/selfdrive/assets/img_eye_closed.svg deleted file mode 100644 index 91b229e911..0000000000 --- a/selfdrive/assets/img_eye_closed.svg +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/selfdrive/assets/img_eye_open.svg b/selfdrive/assets/img_eye_open.svg deleted file mode 100644 index ea6e41ac54..0000000000 --- a/selfdrive/assets/img_eye_open.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/offroad/icon_checkmark.svg b/selfdrive/assets/offroad/icon_checkmark.svg deleted file mode 100644 index b024eccd9e..0000000000 --- a/selfdrive/assets/offroad/icon_checkmark.svg +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/selfdrive/assets/offroad/icon_close.svg b/selfdrive/assets/offroad/icon_close.svg deleted file mode 100644 index 4c063371af..0000000000 --- a/selfdrive/assets/offroad/icon_close.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/offroad/icon_disengage_on_accelerator.svg b/selfdrive/assets/offroad/icon_disengage_on_accelerator.svg deleted file mode 100644 index 0175e672c6..0000000000 --- a/selfdrive/assets/offroad/icon_disengage_on_accelerator.svg +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/selfdrive/assets/offroad/icon_lock_closed.svg b/selfdrive/assets/offroad/icon_lock_closed.svg deleted file mode 100644 index 7dc9283c81..0000000000 --- a/selfdrive/assets/offroad/icon_lock_closed.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/selfdrive/assets/offroad/icon_wifi_strength_full.svg b/selfdrive/assets/offroad/icon_wifi_strength_full.svg deleted file mode 100644 index 758198e97f..0000000000 --- a/selfdrive/assets/offroad/icon_wifi_strength_full.svg +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/selfdrive/assets/offroad/icon_wifi_strength_high.svg b/selfdrive/assets/offroad/icon_wifi_strength_high.svg deleted file mode 100644 index a8db07f91e..0000000000 --- a/selfdrive/assets/offroad/icon_wifi_strength_high.svg +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/selfdrive/assets/offroad/icon_wifi_strength_low.svg b/selfdrive/assets/offroad/icon_wifi_strength_low.svg deleted file mode 100644 index 8963c3dbc1..0000000000 --- a/selfdrive/assets/offroad/icon_wifi_strength_low.svg +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/selfdrive/assets/offroad/icon_wifi_strength_medium.svg b/selfdrive/assets/offroad/icon_wifi_strength_medium.svg deleted file mode 100644 index 8f8d503260..0000000000 --- a/selfdrive/assets/offroad/icon_wifi_strength_medium.svg +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/selfdrive/assets/offroad/icon_wifi_uploading.svg b/selfdrive/assets/offroad/icon_wifi_uploading.svg deleted file mode 100644 index 95cb0e283e..0000000000 --- a/selfdrive/assets/offroad/icon_wifi_uploading.svg +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/selfdrive/assets/prep-svg.sh b/selfdrive/assets/prep-svg.sh new file mode 100755 index 0000000000..2332cd25c5 --- /dev/null +++ b/selfdrive/assets/prep-svg.sh @@ -0,0 +1,46 @@ +#!/usr/bin/env bash +set -e + +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +ICONS_DIR="$DIR/icons" +BOOTSTRAP_SVG="$DIR/../../third_party/bootstrap/bootstrap-icons.svg" + +ICON_IDS=( + arrow-right + backspace + capslock-fill + shift + shift-fill +) +ICON_FILL_COLOR="#fff" + +# extract bootstrap icons +for id in "${ICON_IDS[@]}"; do + svg="${ICONS_DIR}/${id}.svg" + perl -0777 -ne "print \$& if /]*id=\"$id\"[^>]*>.*?<\/symbol>/s" "$BOOTSTRAP_SVG" \ + | sed "s//<\/svg>/" > "$svg" +done + +# sudo apt install inkscape + +for svg in $(find $DIR -type f | grep svg$); do + bunx svgo $svg --multipass --pretty --indent 2 + + # convert to PNG + png="${svg%.svg}.png" + width=$(inkscape --query-width "$svg") + height=$(inkscape --query-height "$svg") + if (( $(echo "$width > $height" | bc -l) )); then + export_dim="--export-width=512" + else + export_dim="--export-height=512" + fi + inkscape "$svg" --export-filename="$png" "$export_dim" + + optipng -o7 -strip all "$png" +done + +# cleanup bootstrap SVGs +for id in "${ICON_IDS[@]}"; do + rm "${ICONS_DIR}/${id}.svg" +done diff --git a/selfdrive/assets/strip-svg-metadata.sh b/selfdrive/assets/strip-svg-metadata.sh deleted file mode 100755 index e51dc9481d..0000000000 --- a/selfdrive/assets/strip-svg-metadata.sh +++ /dev/null @@ -1,9 +0,0 @@ -#!/usr/bin/env bash - -# sudo apt install scour - -for svg in $(find icons/ -type f | grep svg$); do - # scour doesn't support overwriting input file - scour $svg --remove-metadata $svg.tmp - mv $svg.tmp $svg -done diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 2d69d3d590..c5edb484af 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -1,11 +1,8 @@ -from collections import deque from cereal import car, log import cereal.messaging as messaging from opendbc.car import DT_CTRL, structs from opendbc.car.interfaces import MAX_CTRL_SPEED from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams -from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS -from opendbc.car.hyundai.carstate import PREV_BUTTON_SAMPLES as HYUNDAI_PREV_BUTTON_SAMPLES from openpilot.selfdrive.selfdrived.events import Events @@ -39,14 +36,12 @@ class CarSpecificEvents: self.no_steer_warning = False self.silent_steer_warning = True - self.cruise_buttons: deque = deque([], maxlen=HYUNDAI_PREV_BUTTON_SAMPLES) - def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl): if self.CP.brand in ('body', 'mock'): events = Events() elif self.CP.brand == 'ford': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.manumatic]) + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.low, GearShifter.manumatic]) elif self.CP.brand == 'nissan': events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.brake]) @@ -136,20 +131,8 @@ class CarSpecificEvents: # events.add(EventName.steerTimeLimit) elif self.CP.brand == 'hyundai': - # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state - # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons - # Main button also can trigger an engagement on these cars - self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.buttonEvents)) events = self.create_common_events(CS, CS_prev, extra_gears=(GearShifter.sport, GearShifter.manumatic), - pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons), allow_button_cancel=False) - - # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) - if CS.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: - self.low_speed_alert = True - if CS.vEgo > (self.CP.minSteerSpeed + 4.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(EventName.belowSteerSpeed) + pcm_enable=self.CP.pcmCruise, allow_button_cancel=False) else: events = self.create_common_events(CS, CS_prev) @@ -157,7 +140,7 @@ class CarSpecificEvents: return events def create_common_events(self, CS: structs.CarState, CS_prev: car.CarState, extra_gears=None, pcm_enable=True, - allow_enable=True, allow_button_cancel=True): + allow_button_cancel=True): events = Events() if CS.doorOpen: @@ -191,6 +174,8 @@ class CarSpecificEvents: events.add(EventName.accFaulted) if CS.steeringPressed: events.add(EventName.steerOverride) + if CS.steeringDisengage and not CS_prev.steeringDisengage: + events.add(EventName.steerDisengage) if CS.brakePressed and CS.standstill: events.add(EventName.preEnableStandstill) if CS.gasPressed: @@ -234,7 +219,7 @@ class CarSpecificEvents: # we engage when pcm is active (rising edge) # enabling can optionally be blocked by the car interface if pcm_enable: - if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled and allow_enable: + if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled and not CS.blockPcmEnable: events.add(EventName.pcmEnable) elif not CS.cruiseState.enabled: events.add(EventName.pcmDisable) diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 607f5590c4..502daaa015 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -17,7 +17,6 @@ from opendbc.car.carlog import carlog from opendbc.car.fw_versions import ObdCallback from opendbc.car.car_helpers import get_car, interfaces from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase -from opendbc.safety import ALTERNATIVE_EXPERIENCE from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import MockCarState @@ -89,7 +88,7 @@ class Car: if len(can.can) > 0: break - experimental_long_allowed = self.params.get_bool("ExperimentalLongitudinalEnabled") + alpha_long_allowed = self.params.get_bool("AlphaLongitudinalEnabled") num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates) cached_params = None @@ -98,7 +97,7 @@ class Car: with car.CarParams.from_bytes(cached_params_raw) as _cached_params: cached_params = _cached_params - self.CI = get_car(*self.can_callbacks, obd_callback(self.params), experimental_long_allowed, num_pandas, cached_params) + self.CI = get_car(*self.can_callbacks, obd_callback(self.params), alpha_long_allowed, num_pandas, cached_params) self.RI = interfaces[self.CI.CP.carFingerprint].RadarInterface(self.CI.CP) self.CP = self.CI.CP @@ -108,16 +107,9 @@ class Car: self.CI, self.CP = CI, CI.CP self.RI = RI - # set alternative experiences from parameters - disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.CP.alternativeExperience = 0 - if not disengage_on_accelerator: - self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") - controller_available = self.CI.CC is not None and openpilot_enabled_toggle and not self.CP.dashcamOnly - self.CP.passive = not controller_available or self.CP.dashcamOnly if self.CP.passive: safety_config = structs.CarParams.SafetyConfig() diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index e0cd5a1e91..92c7ff8f1c 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -39,7 +39,7 @@ class TestCarInterfaces: args = get_fuzzy_car_interface_args(data.draw) car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], - experimental_long=args['experimental_long'], docs=False) + alpha_long=args['alpha_long'], docs=False) car_params = car_params.as_reader() car_interface = CarInterface(car_params) assert car_params diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index 43c30eb64d..6e13d55b29 100644 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -4,7 +4,7 @@ from openpilot.common.basedir import BASEDIR from opendbc.car.docs import generate_cars_md, get_all_car_docs from openpilot.selfdrive.debug.dump_car_docs import dump_car_docs from openpilot.selfdrive.debug.print_docs_diff import print_car_docs_diff -from openpilot.selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE +from openpilot.selfdrive.car.docs import CARS_MD_TEMPLATE class TestCarDocs: @@ -13,11 +13,7 @@ class TestCarDocs: cls.all_cars = get_all_car_docs() def test_generator(self): - generated_cars_md = generate_cars_md(self.all_cars, CARS_MD_TEMPLATE) - with open(CARS_MD_OUT) as f: - current_cars_md = f.read() - - assert generated_cars_md == current_cars_md, "Run selfdrive/car/docs.py to update the compatibility documentation" + generate_cars_md(self.all_cars, CARS_MD_TEMPLATE) def test_docs_diff(self): dump_path = os.path.join(BASEDIR, "selfdrive", "car", "tests", "cars_dump") diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 906fa99320..0a4784aca8 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -78,7 +78,7 @@ class TestCarModelBase(unittest.TestCase): cls.elm_frame = None cls.car_safety_mode_frame = None cls.fingerprint = gen_empty_fingerprint() - experimental_long = False + alpha_long = False for msg in lr: if msg.which() == "can": can = can_capnp_to_list((msg.as_builder().to_bytes(),))[0] @@ -91,7 +91,7 @@ class TestCarModelBase(unittest.TestCase): elif msg.which() == "carParams": car_fw = msg.carParams.carFw if msg.carParams.openpilotLongitudinalControl: - experimental_long = True + alpha_long = True if cls.platform is None: live_fingerprint = msg.carParams.carFingerprint cls.platform = MIGRATION.get(live_fingerprint, live_fingerprint) @@ -113,7 +113,7 @@ class TestCarModelBase(unittest.TestCase): cls.car_safety_mode_frame = len(can_msgs) assert len(can_msgs) > int(50 / DT_CTRL), "no can data found" - return car_fw, can_msgs, experimental_long + return car_fw, can_msgs, alpha_long @classmethod def get_testing_data(cls): @@ -146,13 +146,13 @@ class TestCarModelBase(unittest.TestCase): raise unittest.SkipTest raise Exception(f"missing test route for {cls.platform}") - car_fw, cls.can_msgs, experimental_long = cls.get_testing_data() + car_fw, cls.can_msgs, alpha_long = cls.get_testing_data() # if relay is expected to be open in the route cls.openpilot_enabled = cls.car_safety_mode_frame is not None cls.CarInterface = interfaces[cls.platform] - cls.CP = cls.CarInterface.get_params(cls.platform, cls.fingerprint, car_fw, experimental_long, docs=False) + cls.CP = cls.CarInterface.get_params(cls.platform, cls.fingerprint, car_fw, alpha_long, docs=False) assert cls.CP assert cls.CP.carFingerprint == cls.platform @@ -330,6 +330,7 @@ class TestCarModelBase(unittest.TestCase): prev_panda_gas = self.safety.get_gas_pressed_prev() prev_panda_brake = self.safety.get_brake_pressed_prev() prev_panda_regen_braking = self.safety.get_regen_braking_prev() + prev_panda_steering_disengage = self.safety.get_steering_disengage_prev() prev_panda_vehicle_moving = self.safety.get_vehicle_moving() prev_panda_vehicle_speed_min = self.safety.get_vehicle_speed_min() prev_panda_vehicle_speed_max = self.safety.get_vehicle_speed_max() @@ -357,6 +358,9 @@ class TestCarModelBase(unittest.TestCase): if self.safety.get_regen_braking_prev() != prev_panda_regen_braking: self.assertEqual(CS.regenBraking, self.safety.get_regen_braking_prev()) + if self.safety.get_steering_disengage_prev() != prev_panda_steering_disengage: + self.assertEqual(CS.steeringDisengage, self.safety.get_steering_disengage_prev()) + if self.safety.get_vehicle_moving() != prev_panda_vehicle_moving: self.assertEqual(not CS.standstill, self.safety.get_vehicle_moving()) @@ -432,6 +436,7 @@ class TestCarModelBase(unittest.TestCase): brake_pressed = False checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev() checks['regenBraking'] += CS.regenBraking != self.safety.get_regen_braking_prev() + checks['steeringDisengage'] += CS.steeringDisengage != self.safety.get_steering_disengage_prev() if self.CP.pcmCruise: # On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state. diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index f6fabfc421..5ecff1ccdf 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -12,7 +12,7 @@ from openpilot.common.swaglog import cloudlog from opendbc.car.car_helpers import interfaces from opendbc.car.vehicle_model import VehicleModel from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature -from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED +from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -41,6 +41,7 @@ class Controls: self.pm = messaging.PubMaster(['carControl', 'controlsState']) self.steer_limited_by_controls = False + self.curvature = 0.0 self.desired_curvature = 0.0 self.pose_calibrator = PoseCalibrator() @@ -73,6 +74,9 @@ class Controls: sr = max(lp.steerRatio, 0.1) self.VM.update_params(x, sr) + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) + self.curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) + # Update Torque Params if self.CP.lateralTuning.which() == 'torque': torque_params = self.sm['liveTorqueParameters'] @@ -87,8 +91,9 @@ class Controls: CC.enabled = self.sm['selfdriveState'].enabled # Check which actuators can be enabled - standstill = abs(CS.vEgo) <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill - CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and not standstill + standstill = abs(CS.vEgo) <= max(self.CP.minSteerSpeed, 0.3) or CS.standstill + CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ + (not standstill or self.CP.steerAtStandstill) CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in self.sm['onroadEvents']) and self.CP.openpilotLongitudinalControl actuators = CC.actuators @@ -109,7 +114,10 @@ class Controls: actuators.accel = float(self.LoC.update(CC.longActive, CS, long_plan.aTarget, long_plan.shouldStop, pid_accel_limits)) # Steering PID loop and lateral MPC - self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature, lp.roll) + # Reset desired curvature to current to avoid violating the limits on engage + new_desired_curvature = model_v2.action.desiredCurvature if CC.latActive else self.curvature + self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, new_desired_curvature, lp.roll) + actuators.curvature = self.desired_curvature steer, steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, self.steer_limited_by_controls, self.desired_curvature, @@ -133,6 +141,7 @@ class Controls: # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller + CC.currentCurvature = self.curvature if self.calibrated_pose is not None: CC.orientationNED = self.calibrated_pose.orientation.xyz.tolist() CC.angularVelocity = self.calibrated_pose.angular_velocity.xyz.tolist() @@ -174,10 +183,7 @@ class Controls: dat.valid = CS.canValid cs = dat.controlsState - lp = self.sm['liveParameters'] - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) - cs.curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) - + cs.curvature = self.curvature cs.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] cs.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] cs.desiredCurvature = self.desired_curvature diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 41384abae8..56eeac3bdf 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,7 +1,7 @@ import numpy as np from cereal import log from opendbc.car.vehicle_model import ACCELERATION_DUE_TO_GRAVITY -from openpilot.common.realtime import DT_CTRL +from openpilot.common.realtime import DT_CTRL, DT_MDL MIN_SPEED = 1.0 CONTROL_N = 17 @@ -19,6 +19,9 @@ def clamp(val, min_val, max_val): clamped_val = float(np.clip(val, min_val, max_val)) return clamped_val, clamped_val != val +def smooth_value(val, prev_val, tau, dt=DT_MDL): + alpha = 1 - np.exp(-dt/tau) if tau > 0 else 1 + return alpha * val + (1 - alpha) * prev_val def clip_curvature(v_ego, prev_curvature, new_curvature, roll): # This function respects ISO lateral jerk and acceleration limits + a max curvature @@ -43,3 +46,29 @@ def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: vel_err = np.clip(modelV2.temporalPose.trans[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) return float(vel_err) return 0.0 + + +def get_accel_from_plan(speeds, accels, t_idxs, action_t=DT_MDL, vEgoStopping=0.05): + if len(speeds) == len(t_idxs): + v_now = speeds[0] + a_now = accels[0] + v_target = np.interp(action_t, t_idxs, speeds) + a_target = 2 * (v_target - v_now) / (action_t) - a_now + v_target_1sec = np.interp(action_t + 1.0, t_idxs, speeds) + else: + v_target = 0.0 + v_target_1sec = 0.0 + a_target = 0.0 + should_stop = (v_target < vEgoStopping and + v_target_1sec < vEgoStopping) + return a_target, should_stop + +def curv_from_psis(psi_target, psi_rate, vego, action_t): + vego = np.clip(vego, MIN_SPEED, np.inf) + curv_from_psi = psi_target / (vego * action_t) + return 2*curv_from_psi - psi_rate / vego + +def get_curvature_from_plan(yaws, yaw_rates, t_idxs, vego, action_t): + psi_target = np.interp(action_t, t_idxs, yaws) + psi_rate = yaw_rates[0] + return curv_from_psis(psi_target, psi_rate, vego, action_t) diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index dcf0003430..d67a4aa959 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -3,8 +3,6 @@ from abc import abstractmethod, ABC from openpilot.common.realtime import DT_CTRL -MIN_LATERAL_CONTROL_SPEED = 0.3 # m/s - class LatControl(ABC): def __init__(self, CP, CI): diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index 1b249a3d1a..f3f1bc5acf 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -10,6 +10,7 @@ class LatControlAngle(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) self.sat_check_min_speed = 5. + self.use_steer_limited_by_controls = CP.brand == "tesla" def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited): angle_log = log.ControlsState.LateralAngleState.new_message() @@ -22,7 +23,13 @@ class LatControlAngle(LatControl): angle_steers_des = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) angle_steers_des += params.angleOffsetDeg - angle_control_saturated = abs(angle_steers_des - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD + if self.use_steer_limited_by_controls: + # these cars' carcontrollers calculate max lateral accel and jerk, so we can rely on carOutput for saturation + angle_control_saturated = steer_limited_by_controls + else: + # for cars which use a method of limiting torque such as a torque signal (Nissan and Toyota) + # or relying on EPS (Ford Q3), carOutput does not capture maxing out torque # TODO: this can be improved + angle_control_saturated = abs(angle_steers_des - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD angle_log.saturated = bool(self._check_saturation(angle_control_saturated, CS, False, curvature_limited)) angle_log.steeringAngleDeg = float(CS.steeringAngleDeg) angle_log.steeringAngleDesiredDeg = angle_steers_des diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index c7a2295a5f..9d71faeca2 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -11,7 +11,7 @@ from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC -from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_speed_error +from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_speed_error, get_accel_from_plan from openpilot.selfdrive.car.cruise import V_CRUISE_MAX, V_CRUISE_UNSET from openpilot.common.swaglog import cloudlog @@ -48,27 +48,11 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): return [a_target[0], min(a_target[1], a_x_allowed)] -def get_accel_from_plan(speeds, accels, action_t=DT_MDL, vEgoStopping=0.05): - if len(speeds) == CONTROL_N: - v_now = speeds[0] - a_now = accels[0] - - v_target = np.interp(action_t, CONTROL_N_T_IDX, speeds) - a_target = 2 * (v_target - v_now) / (action_t) - a_now - v_target_1sec = np.interp(action_t + 1.0, CONTROL_N_T_IDX, speeds) - else: - v_target = 0.0 - v_target_1sec = 0.0 - a_target = 0.0 - should_stop = (v_target < vEgoStopping and - v_target_1sec < vEgoStopping) - return a_target, should_stop - - class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0, dt=DT_MDL): self.CP = CP self.mpc = LongitudinalMpc(dt=dt) + self.mpc.mode = 'acc' self.fcw = False self.dt = dt self.allow_throttle = True @@ -176,7 +160,7 @@ class LongitudinalPlanner: self.v_desired_filter.x = self.v_desired_filter.x + self.dt * (self.a_desired + a_prev) / 2.0 action_t = self.CP.longitudinalActuatorDelay + DT_MDL - output_a_target, self.output_should_stop = get_accel_from_plan(self.v_desired_trajectory, self.a_desired_trajectory, + output_a_target, self.output_should_stop = get_accel_from_plan(self.v_desired_trajectory, self.a_desired_trajectory, CONTROL_N_T_IDX, action_t=action_t, vEgoStopping=self.CP.vEgoStopping) for idx in range(2): diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 84420e3584..98fce1cb26 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -6,6 +6,7 @@ from typing import Any import capnp from cereal import messaging, log, car +from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params from openpilot.common.realtime import DT_MDL, Priority, config_realtime_process from openpilot.common.swaglog import cloudlog @@ -51,7 +52,7 @@ class Track: def __init__(self, identifier: int, v_lead: float, kalman_params: KalmanParams): self.identifier = identifier self.cnt = 0 - self.aLeadTau = _LEAD_ACCEL_TAU + self.aLeadTau = FirstOrderFilter(_LEAD_ACCEL_TAU, 0.45, DT_MDL) self.K_A = kalman_params.A self.K_C = kalman_params.C self.K_K = kalman_params.K @@ -74,17 +75,12 @@ class Track: # Learn if constant acceleration if abs(self.aLeadK) < 0.5: - self.aLeadTau = _LEAD_ACCEL_TAU + self.aLeadTau.x = _LEAD_ACCEL_TAU else: - self.aLeadTau *= 0.9 + self.aLeadTau.update(0.0) self.cnt += 1 - def reset_a_lead(self, aLeadK: float, aLeadTau: float): - self.kf = KF1D([[self.vLead], [aLeadK]], self.K_A, self.K_C, self.K_K) - self.aLeadK = aLeadK - self.aLeadTau = aLeadTau - def get_RadarState(self, model_prob: float = 0.0): return { "dRel": float(self.dRel), @@ -93,7 +89,7 @@ class Track: "vLead": float(self.vLead), "vLeadK": float(self.vLeadK), "aLeadK": float(self.aLeadK), - "aLeadTau": float(self.aLeadTau), + "aLeadTau": float(self.aLeadTau.x), "status": True, "fcw": self.is_potential_fcw(model_prob), "modelProb": model_prob, diff --git a/selfdrive/debug/clear_dtc.py b/selfdrive/debug/car/clear_dtc.py similarity index 100% rename from selfdrive/debug/clear_dtc.py rename to selfdrive/debug/car/clear_dtc.py diff --git a/selfdrive/debug/hyundai_enable_radar_points.py b/selfdrive/debug/car/hyundai_enable_radar_points.py similarity index 100% rename from selfdrive/debug/hyundai_enable_radar_points.py rename to selfdrive/debug/car/hyundai_enable_radar_points.py diff --git a/selfdrive/debug/toyota_eps_factor.py b/selfdrive/debug/car/toyota_eps_factor.py similarity index 100% rename from selfdrive/debug/toyota_eps_factor.py rename to selfdrive/debug/car/toyota_eps_factor.py diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/car/vw_mqb_config.py similarity index 100% rename from selfdrive/debug/vw_mqb_config.py rename to selfdrive/debug/car/vw_mqb_config.py diff --git a/selfdrive/debug/max_lat_accel.py b/selfdrive/debug/max_lat_accel.py index 2369d99d86..dc44e8ac40 100755 --- a/selfdrive/debug/max_lat_accel.py +++ b/selfdrive/debug/max_lat_accel.py @@ -2,6 +2,8 @@ import argparse import numpy as np import matplotlib.pyplot as plt +from functools import partial +from tqdm import tqdm from typing import NamedTuple from openpilot.tools.lib.logreader import LogReader from openpilot.selfdrive.locationd.models.pose_kf import EARTH_G @@ -20,14 +22,15 @@ class Event(NamedTuple): timestamp: float # relative to start of route (s) -def find_events(lr: LogReader, qlog: bool = False) -> list[Event]: +def find_events(lr: LogReader, extrapolate: bool = False, qlog: bool = False) -> list[Event]: min_lat_active = RLOG_MIN_LAT_ACTIVE // QLOG_DECIMATION if qlog else RLOG_MIN_LAT_ACTIVE min_steering_unpressed = RLOG_MIN_STEERING_UNPRESSED // QLOG_DECIMATION if qlog else RLOG_MIN_STEERING_UNPRESSED min_requesting_max = RLOG_MIN_REQUESTING_MAX // QLOG_DECIMATION if qlog else RLOG_MIN_REQUESTING_MAX - events = [] + # if we test with driver torque safety, max torque can be slightly noisy + steer_threshold = 0.7 if extrapolate else 0.95 - start_ts = 0 + events = [] # state tracking steering_unpressed = 0 # frames @@ -38,7 +41,9 @@ def find_events(lr: LogReader, qlog: bool = False) -> list[Event]: curvature = 0 v_ego = 0 roll = 0 + out_torque = 0 + start_ts = 0 for msg in lr: if msg.which() == 'carControl': if start_ts == 0: @@ -47,8 +52,8 @@ def find_events(lr: LogReader, qlog: bool = False) -> list[Event]: lat_active = lat_active + 1 if msg.carControl.latActive else 0 elif msg.which() == 'carOutput': - # if we test with driver torque safety, max torque can be slightly noisy - requesting_max = requesting_max + 1 if abs(msg.carOutput.actuatorsOutput.torque) > 0.95 else 0 + out_torque = msg.carOutput.actuatorsOutput.torque + requesting_max = requesting_max + 1 if abs(out_torque) > steer_threshold else 0 elif msg.which() == 'carState': steering_unpressed = steering_unpressed + 1 if not msg.carState.steeringPressed else 0 @@ -64,7 +69,8 @@ def find_events(lr: LogReader, qlog: bool = False) -> list[Event]: # TODO: record max lat accel at the end of the event, need to use the past lat accel as overriding can happen before we detect it requesting_max = 0 - current_lateral_accel = curvature * v_ego ** 2 - roll * EARTH_G + factor = 1 / abs(out_torque) + current_lateral_accel = (curvature * v_ego ** 2 * factor) - roll * EARTH_G events.append(Event(current_lateral_accel, v_ego, roll, round((msg.logMonoTime - start_ts) * 1e-9, 2))) print(events[-1]) @@ -75,29 +81,38 @@ if __name__ == '__main__': parser = argparse.ArgumentParser(description="Find max lateral acceleration events", formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("route") + parser.add_argument("route", nargs='+') + parser.add_argument("-e", "--extrapolate", action="store_true", help="Extrapolates max lateral acceleration events linearly. " + + "This option can be far less accurate.") args = parser.parse_args() - lr = LogReader(args.route, sort_by_time=True) - qlog = args.route.endswith('/q') - if qlog: - print('WARNING: Treating route as qlog!') + events = [] + for route in tqdm(args.route): + try: + lr = LogReader(route, sort_by_time=True) + except Exception: + print(f'Skipping {route}') + continue + + qlog = route.endswith('/q') + if qlog: + print('WARNING: Treating route as qlog!') - print('Finding events...') - events = find_events(lr, qlog=qlog) + print('Finding events...') + events += lr.run_across_segments(8, partial(find_events, extrapolate=args.extrapolate, qlog=qlog), disable_tqdm=True) print() print(f'Found {len(events)} events') - perc_left_accel = -np.percentile([-ev.lateral_accel for ev in events if ev.lateral_accel < 0], 90) - perc_right_accel = np.percentile([ev.lateral_accel for ev in events if ev.lateral_accel > 0], 90) + perc_left_accel = -np.percentile([-ev.lateral_accel for ev in events if ev.lateral_accel < 0] or [0], 90) + perc_right_accel = np.percentile([ev.lateral_accel for ev in events if ev.lateral_accel > 0] or [0], 90) CP = lr.first('carParams') plt.ion() plt.clf() plt.suptitle(f'{CP.carFingerprint} - Max lateral acceleration events') - plt.title(args.route) + plt.title(', '.join(args.route)) plt.scatter([ev.speed for ev in events], [ev.lateral_accel for ev in events], label='max lateral accel events') plt.plot([0, 35], [3, 3], c='r', label='ISO 11270 - 3 m/s^2') diff --git a/selfdrive/debug/measure_modeld_packet_drop.py b/selfdrive/debug/measure_modeld_packet_drop.py deleted file mode 100755 index 9814942ce2..0000000000 --- a/selfdrive/debug/measure_modeld_packet_drop.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 -import cereal.messaging as messaging - -if __name__ == "__main__": - modeld_sock = messaging.sub_sock("modelV2") - - last_frame_id = None - start_t: int | None = None - frame_cnt = 0 - dropped = 0 - - while True: - m = messaging.recv_one(modeld_sock) - if m is None: - continue - - frame_id = m.modelV2.frameId - t = m.logMonoTime / 1e9 - frame_cnt += 1 - - if start_t is None: - start_t = t - last_frame_id = frame_id - continue - - d_frame = frame_id - last_frame_id - dropped += d_frame - 1 - - expected_num_frames = int((t - start_t) * 20) - frame_drop = 100 * (1 - (expected_num_frames / frame_cnt)) - print(f"Num dropped {dropped}, Drop compared to 20Hz: {frame_drop:.2f}%") - - last_frame_id = frame_id diff --git a/selfdrive/debug/set_car_params.py b/selfdrive/debug/set_car_params.py index 6060dfbc36..aec30b4d74 100755 --- a/selfdrive/debug/set_car_params.py +++ b/selfdrive/debug/set_car_params.py @@ -15,7 +15,7 @@ if __name__ == "__main__": else: CP = car.CarParams.new_message() CP.openpilotLongitudinalControl = True - CP.experimentalLongitudinalAvailable = False + CP.alphaLongitudinalAvailable = False cp_bytes = CP.to_bytes() for p in ("CarParams", "CarParamsCache", "CarParamsPersistent"): diff --git a/selfdrive/debug/show_matching_cars.py b/selfdrive/debug/show_matching_cars.py deleted file mode 100755 index bc13772977..0000000000 --- a/selfdrive/debug/show_matching_cars.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars -import cereal.messaging as messaging - - -# rav4 2019 and corolla tss2 -fingerprint = {896: 8, 898: 8, 900: 6, 976: 1, 1541: 8, 902: 6, 905: 8, 810: 2, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1552: 8, 1553: 8, 1556: 8, 1571: 8, 921: 8, 1056: 8, 544: 4, 1570: 8, 1059: 1, 36: 8, 37: 8, 550: 8, 935: 8, 552: 4, 170: 8, 812: 8, 944: 8, 945: 8, 562: 6, 180: 8, 1077: 8, 951: 8, 1592: 8, 1076: 8, 186: 4, 955: 8, 956: 8, 1001: 8, 705: 8, 452: 8, 1788: 8, 464: 8, 824: 8, 466: 8, 467: 8, 761: 8, 728: 8, 1572: 8, 1114: 8, 933: 8, 800: 8, 608: 8, 865: 8, 610: 8, 1595: 8, 934: 8, 998: 5, 1745: 8, 1000: 8, 764: 8, 1002: 8, 999: 7, 1789: 8, 1649: 8, 1779: 8, 1568: 8, 1017: 8, 1786: 8, 1787: 8, 1020: 8, 426: 6, 1279: 8} # noqa: E501 - -candidate_cars = all_legacy_fingerprint_cars() - - -for addr, l in fingerprint.items(): - dat = messaging.new_message('can', 1) - - msg = dat.can[0] - msg.address = addr - msg.dat = " " * l - - candidate_cars = eliminate_incompatible_cars(msg, candidate_cars) - print(candidate_cars) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 8ce884ae4f..e265b70f1a 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -11,7 +11,7 @@ import capnp import numpy as np from typing import NoReturn -from cereal import log +from cereal import log, car import cereal.messaging as messaging from openpilot.common.conversions import Conversions as CV from openpilot.common.params import Params @@ -258,16 +258,18 @@ def main() -> NoReturn: config_realtime_process([0, 1, 2, 3], 5) pm = messaging.PubMaster(['liveCalibration']) - sm = messaging.SubMaster(['cameraOdometry', 'carState', 'carParams'], poll='cameraOdometry') + sm = messaging.SubMaster(['cameraOdometry', 'carState'], poll='cameraOdometry') + + params_reader = Params() + CP = messaging.log_from_bytes(params_reader.get("CarParams", block=True), car.CarParams) calibrator = Calibrator(param_put=True) + calibrator.not_car = CP.notCar while 1: timeout = 0 if sm.frame == -1 else 100 sm.update(timeout) - calibrator.not_car = sm['carParams'].notCar - if sm.updated['cameraOdometry']: calibrator.handle_v_ego(sm['carState'].vEgo) new_rpy = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, diff --git a/selfdrive/locationd/helpers.py b/selfdrive/locationd/helpers.py index af307b0336..a3e3ae4a8c 100644 --- a/selfdrive/locationd/helpers.py +++ b/selfdrive/locationd/helpers.py @@ -1,10 +1,48 @@ import numpy as np from typing import Any +from functools import cache from cereal import log from openpilot.common.transformations.orientation import rot_from_euler, euler_from_rot +@cache +def fft_next_good_size(n: int) -> int: + """ + smallest composite of 2, 3, 5, 7, 11 that is >= n + inspired by pocketfft + """ + if n <= 6: + return n + best, f2 = 2 * n, 1 + while f2 < best: + f23 = f2 + while f23 < best: + f235 = f23 + while f235 < best: + f2357 = f235 + while f2357 < best: + f235711 = f2357 + while f235711 < best: + best = f235711 if f235711 >= n else best + f235711 *= 11 + f2357 *= 7 + f235 *= 5 + f23 *= 3 + f2 *= 2 + return best + + +def parabolic_peak_interp(R, max_index): + if max_index == 0 or max_index == len(R) - 1: + return max_index + + y_m1, y_0, y_p1 = R[max_index - 1], R[max_index], R[max_index + 1] + offset = 0.5 * (y_p1 - y_m1) / (2 * y_0 - y_p1 - y_m1) + + return max_index + offset + + def rotate_cov(rot_matrix, cov_in): return rot_matrix @ cov_in @ rot_matrix.T diff --git a/selfdrive/locationd/lagd.py b/selfdrive/locationd/lagd.py new file mode 100755 index 0000000000..4e207b4882 --- /dev/null +++ b/selfdrive/locationd/lagd.py @@ -0,0 +1,391 @@ +#!/usr/bin/env python3 +import os +import numpy as np +import capnp +from collections import deque +from functools import partial + +import cereal.messaging as messaging +from cereal import car, log +from cereal.services import SERVICE_LIST +from openpilot.common.params import Params +from openpilot.common.realtime import config_realtime_process +from openpilot.common.swaglog import cloudlog +from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose, fft_next_good_size, parabolic_peak_interp + +BLOCK_SIZE = 100 +BLOCK_NUM = 50 +BLOCK_NUM_NEEDED = 5 +MOVING_WINDOW_SEC = 60.0 +MIN_OKAY_WINDOW_SEC = 25.0 +MIN_RECOVERY_BUFFER_SEC = 2.0 +MIN_VEGO = 15.0 +MIN_ABS_YAW_RATE = 0.0 +MAX_YAW_RATE_SANITY_CHECK = 1.0 +MIN_NCC = 0.95 +MAX_LAG = 1.0 +MAX_LAG_STD = 0.1 +MAX_LAT_ACCEL = 2.0 +MAX_LAT_ACCEL_DIFF = 0.6 +MIN_CONFIDENCE = 0.7 +CORR_BORDER_OFFSET = 5 +LAG_CANDIDATE_CORR_THRESHOLD = 0.9 + + +def masked_normalized_cross_correlation(expected_sig: np.ndarray, actual_sig: np.ndarray, mask: np.ndarray, n: int): + """ + References: + D. Padfield. "Masked FFT registration". In Proc. Computer Vision and + Pattern Recognition, pp. 2918-2925 (2010). + :DOI:`10.1109/CVPR.2010.5540032` + """ + + eps = np.finfo(np.float64).eps + expected_sig = np.asarray(expected_sig, dtype=np.float64) + actual_sig = np.asarray(actual_sig, dtype=np.float64) + + expected_sig[~mask] = 0.0 + actual_sig[~mask] = 0.0 + + rotated_expected_sig = expected_sig[::-1] + rotated_mask = mask[::-1] + + fft = partial(np.fft.fft, n=n) + + actual_sig_fft = fft(actual_sig) + rotated_expected_sig_fft = fft(rotated_expected_sig) + actual_mask_fft = fft(mask.astype(np.float64)) + rotated_mask_fft = fft(rotated_mask.astype(np.float64)) + + number_overlap_masked_samples = np.fft.ifft(rotated_mask_fft * actual_mask_fft).real + number_overlap_masked_samples[:] = np.round(number_overlap_masked_samples) + number_overlap_masked_samples[:] = np.fmax(number_overlap_masked_samples, eps) + masked_correlated_actual_fft = np.fft.ifft(rotated_mask_fft * actual_sig_fft).real + masked_correlated_expected_fft = np.fft.ifft(actual_mask_fft * rotated_expected_sig_fft).real + + numerator = np.fft.ifft(rotated_expected_sig_fft * actual_sig_fft).real + numerator -= masked_correlated_actual_fft * masked_correlated_expected_fft / number_overlap_masked_samples + + actual_squared_fft = fft(actual_sig ** 2) + actual_sig_denom = np.fft.ifft(rotated_mask_fft * actual_squared_fft).real + actual_sig_denom -= masked_correlated_actual_fft ** 2 / number_overlap_masked_samples + actual_sig_denom[:] = np.fmax(actual_sig_denom, 0.0) + + rotated_expected_squared_fft = fft(rotated_expected_sig ** 2) + expected_sig_denom = np.fft.ifft(actual_mask_fft * rotated_expected_squared_fft).real + expected_sig_denom -= masked_correlated_expected_fft ** 2 / number_overlap_masked_samples + expected_sig_denom[:] = np.fmax(expected_sig_denom, 0.0) + + denom = np.sqrt(actual_sig_denom * expected_sig_denom) + + # zero-out samples with very small denominators + tol = 1e3 * eps * np.max(np.abs(denom), keepdims=True) + nonzero_indices = denom > tol + + ncc = np.zeros_like(denom, dtype=np.float64) + ncc[nonzero_indices] = numerator[nonzero_indices] / denom[nonzero_indices] + np.clip(ncc, -1, 1, out=ncc) + + return ncc + + +class Points: + def __init__(self, num_points: int): + self.times = deque[float]([0.0] * num_points, maxlen=num_points) + self.okay = deque[bool]([False] * num_points, maxlen=num_points) + self.desired = deque[float]([0.0] * num_points, maxlen=num_points) + self.actual = deque[float]([0.0] * num_points, maxlen=num_points) + + @property + def num_points(self): + return len(self.desired) + + @property + def num_okay(self): + return np.count_nonzero(self.okay) + + def update(self, t: float, desired: float, actual: float, okay: bool): + self.times.append(t) + self.okay.append(okay) + self.desired.append(desired) + self.actual.append(actual) + + def get(self) -> tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarray]: + return np.array(self.times), np.array(self.desired), np.array(self.actual), np.array(self.okay) + + +class BlockAverage: + def __init__(self, num_blocks: int, block_size: int, valid_blocks: int, initial_value: float): + self.num_blocks = num_blocks + self.block_size = block_size + self.block_idx = valid_blocks % num_blocks + self.idx = 0 + + self.values = np.tile(initial_value, (num_blocks, 1)) + self.valid_blocks = valid_blocks + + def update(self, value: float): + self.values[self.block_idx] = (self.idx * self.values[self.block_idx] + value) / (self.idx + 1) + self.idx = (self.idx + 1) % self.block_size + if self.idx == 0: + self.block_idx = (self.block_idx + 1) % self.num_blocks + self.valid_blocks = min(self.valid_blocks + 1, self.num_blocks) + + def get(self) -> tuple[float, float, float, float]: + valid_block_idx = [i for i in range(self.valid_blocks) if i != self.block_idx] + valid_and_current_idx = valid_block_idx + ([self.block_idx] if self.idx > 0 else []) + + if len(valid_block_idx) > 0: + valid_mean = float(np.mean(self.values[valid_block_idx], axis=0).item()) + valid_std = float(np.std(self.values[valid_block_idx], axis=0).item()) + else: + valid_mean, valid_std = float('nan'), float('nan') + + if len(valid_and_current_idx) > 0: + current_mean = float(np.mean(self.values[valid_and_current_idx], axis=0).item()) + current_std = float(np.std(self.values[valid_and_current_idx], axis=0).item()) + else: + current_mean, current_std = float('nan'), float('nan') + + return valid_mean, valid_std, current_mean, current_std + + +class LateralLagEstimator: + inputs = {"carControl", "carState", "controlsState", "liveCalibration", "livePose"} + + def __init__(self, CP: car.CarParams, dt: float, + block_count: int = BLOCK_NUM, min_valid_block_count: int = BLOCK_NUM_NEEDED, block_size: int = BLOCK_SIZE, + window_sec: float = MOVING_WINDOW_SEC, okay_window_sec: float = MIN_OKAY_WINDOW_SEC, min_recovery_buffer_sec: float = MIN_RECOVERY_BUFFER_SEC, + min_vego: float = MIN_VEGO, min_yr: float = MIN_ABS_YAW_RATE, min_ncc: float = MIN_NCC, + max_lat_accel: float = MAX_LAT_ACCEL, max_lat_accel_diff: float = MAX_LAT_ACCEL_DIFF, min_confidence: float = MIN_CONFIDENCE): + self.dt = dt + self.window_sec = window_sec + self.okay_window_sec = okay_window_sec + self.min_recovery_buffer_sec = min_recovery_buffer_sec + self.initial_lag = CP.steerActuatorDelay + 0.2 + self.block_size = block_size + self.block_count = block_count + self.min_valid_block_count = min_valid_block_count + self.min_vego = min_vego + self.min_yr = min_yr + self.min_ncc = min_ncc + self.min_confidence = min_confidence + self.max_lat_accel = max_lat_accel + self.max_lat_accel_diff = max_lat_accel_diff + + self.t = 0.0 + self.lat_active = False + self.steering_pressed = False + self.steering_saturated = False + self.desired_curvature = 0.0 + self.v_ego = 0.0 + self.yaw_rate = 0.0 + self.yaw_rate_std = 0.0 + self.pose_valid = False + + self.last_lat_inactive_t = 0.0 + self.last_steering_pressed_t = 0.0 + self.last_steering_saturated_t = 0.0 + self.last_pose_invalid_t = 0.0 + self.last_estimate_t = 0.0 + + self.calibrator = PoseCalibrator() + + self.reset(self.initial_lag, 0) + + def reset(self, initial_lag: float, valid_blocks: int): + window_len = int(self.window_sec / self.dt) + self.points = Points(window_len) + self.block_avg = BlockAverage(self.block_count, self.block_size, valid_blocks, initial_lag) + + def get_msg(self, valid: bool, debug: bool = False) -> capnp._DynamicStructBuilder: + msg = messaging.new_message('liveDelay') + + msg.valid = valid + + liveDelay = msg.liveDelay + + valid_mean_lag, valid_std, current_mean_lag, current_std = self.block_avg.get() + if self.block_avg.valid_blocks >= self.min_valid_block_count and not np.isnan(valid_mean_lag) and not np.isnan(valid_std): + if valid_std > MAX_LAG_STD: + liveDelay.status = log.LiveDelayData.Status.invalid + else: + liveDelay.status = log.LiveDelayData.Status.estimated + else: + liveDelay.status = log.LiveDelayData.Status.unestimated + + if liveDelay.status == log.LiveDelayData.Status.estimated: + liveDelay.lateralDelay = valid_mean_lag + else: + liveDelay.lateralDelay = self.initial_lag + + if not np.isnan(current_mean_lag) and not np.isnan(current_std): + liveDelay.lateralDelayEstimate = current_mean_lag + liveDelay.lateralDelayEstimateStd = current_std + else: + liveDelay.lateralDelayEstimate = self.initial_lag + liveDelay.lateralDelayEstimateStd = 0.0 + + liveDelay.validBlocks = self.block_avg.valid_blocks + if debug: + liveDelay.points = self.block_avg.values.flatten().tolist() + + return msg + + def handle_log(self, t: float, which: str, msg: capnp._DynamicStructReader): + if which == "carControl": + self.lat_active = msg.latActive + elif which == "carState": + self.steering_pressed = msg.steeringPressed + self.v_ego = msg.vEgo + elif which == "controlsState": + self.steering_saturated = getattr(msg.lateralControlState, msg.lateralControlState.which()).saturated + self.desired_curvature = msg.desiredCurvature + elif which == "liveCalibration": + self.calibrator.feed_live_calib(msg) + elif which == "livePose": + device_pose = Pose.from_live_pose(msg) + calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + self.yaw_rate = calibrated_pose.angular_velocity.yaw + self.yaw_rate_std = calibrated_pose.angular_velocity.yaw_std + self.pose_valid = msg.angularVelocityDevice.valid and msg.posenetOK and msg.inputsOK + self.t = t + + def points_enough(self): + return self.points.num_points >= int(self.okay_window_sec / self.dt) + + def points_valid(self): + return self.points.num_okay >= int(self.okay_window_sec / self.dt) + + def update_points(self): + la_desired = self.desired_curvature * self.v_ego * self.v_ego + la_actual_pose = self.yaw_rate * self.v_ego + + fast = self.v_ego > self.min_vego + turning = np.abs(self.yaw_rate) >= self.min_yr + sensors_valid = self.pose_valid and np.abs(self.yaw_rate) < MAX_YAW_RATE_SANITY_CHECK and self.yaw_rate_std < MAX_YAW_RATE_SANITY_CHECK + la_valid = np.abs(la_actual_pose) <= self.max_lat_accel and np.abs(la_desired - la_actual_pose) <= self.max_lat_accel_diff + calib_valid = self.calibrator.calib_valid + + if not self.lat_active: + self.last_lat_inactive_t = self.t + if self.steering_pressed: + self.last_steering_pressed_t = self.t + if self.steering_saturated: + self.last_steering_saturated_t = self.t + if not sensors_valid or not la_valid: + self.last_pose_invalid_t = self.t + + has_recovered = all( # wait for recovery after !lat_active, steering_pressed, steering_saturated, !sensors/la_valid + self.t - last_t >= self.min_recovery_buffer_sec + for last_t in [self.last_lat_inactive_t, self.last_steering_pressed_t, self.last_steering_saturated_t, self.last_pose_invalid_t] + ) + okay = self.lat_active and not self.steering_pressed and not self.steering_saturated and \ + fast and turning and has_recovered and calib_valid and sensors_valid and la_valid + + self.points.update(self.t, la_desired, la_actual_pose, okay) + + def update_estimate(self): + if not self.points_enough(): + return + + times, desired, actual, okay = self.points.get() + # check if there are any new valid data points since the last update + is_valid = self.points_valid() + if self.last_estimate_t != 0 and times[0] <= self.last_estimate_t: + new_values_start_idx = next(-i for i, t in enumerate(reversed(times)) if t <= self.last_estimate_t) + is_valid = is_valid and not (new_values_start_idx == 0 or not np.any(okay[new_values_start_idx:])) + + delay, corr, confidence = self.actuator_delay(desired, actual, okay, self.dt, MAX_LAG) + if corr < self.min_ncc or confidence < self.min_confidence or not is_valid: + return + + self.block_avg.update(delay) + self.last_estimate_t = self.t + + def actuator_delay(self, expected_sig: np.ndarray, actual_sig: np.ndarray, mask: np.ndarray, dt: float, max_lag: float) -> tuple[float, float, float]: + assert len(expected_sig) == len(actual_sig) + max_lag_samples = int(max_lag / dt) + padded_size = fft_next_good_size(len(expected_sig) + max_lag_samples) + + ncc = masked_normalized_cross_correlation(expected_sig, actual_sig, mask, padded_size) + + # only consider lags from 0 to max_lag + roi = np.s_[len(expected_sig) - 1: len(expected_sig) - 1 + max_lag_samples] + extended_roi = np.s_[roi.start - CORR_BORDER_OFFSET: roi.stop + CORR_BORDER_OFFSET] + roi_ncc = ncc[roi] + extended_roi_ncc = ncc[extended_roi] + + max_corr_index = np.argmax(roi_ncc) + corr = roi_ncc[max_corr_index] + lag = parabolic_peak_interp(roi_ncc, max_corr_index) * dt + + # to estimate lag confidence, gather all high-correlation candidates and see how spread they are + # if e.g. 0.8 and 0.4 are both viable, this is an ambiguous case + ncc_thresh = (roi_ncc.max() - roi_ncc.min()) * LAG_CANDIDATE_CORR_THRESHOLD + roi_ncc.min() + good_lag_candidate_mask = extended_roi_ncc >= ncc_thresh + good_lag_candidate_edges = np.diff(good_lag_candidate_mask.astype(int), prepend=0, append=0) + starts, ends = np.where(good_lag_candidate_edges == 1)[0], np.where(good_lag_candidate_edges == -1)[0] - 1 + run_idx = np.searchsorted(starts, max_corr_index + CORR_BORDER_OFFSET, side='right') - 1 + width = ends[run_idx] - starts[run_idx] + 1 + confidence = np.clip(1 - width * dt, 0, 1) + + return lag, corr, confidence + + +def retrieve_initial_lag(params: Params, CP: car.CarParams): + last_lag_data = params.get("LiveDelay") + last_carparams_data = params.get("CarParamsPrevRoute") + + if last_lag_data is not None: + try: + with log.Event.from_bytes(last_lag_data) as last_lag_msg, car.CarParams.from_bytes(last_carparams_data) as last_CP: + ld = last_lag_msg.liveDelay + if last_CP.carFingerprint != CP.carFingerprint: + raise Exception("Car model mismatch") + + lag, valid_blocks, status = ld.lateralDelayEstimate, ld.validBlocks, ld.status + assert valid_blocks <= BLOCK_NUM, "Invalid number of valid blocks" + assert status != log.LiveDelayData.Status.invalid, "Lag estimate is invalid" + return lag, valid_blocks + except Exception as e: + cloudlog.error(f"Failed to retrieve initial lag: {e}") + params.remove("LiveDelay") + + return None + + +def main(): + config_realtime_process([0, 1, 2, 3], 5) + + DEBUG = bool(int(os.getenv("DEBUG", "0"))) + + pm = messaging.PubMaster(['liveDelay']) + sm = messaging.SubMaster(['livePose', 'liveCalibration', 'carState', 'controlsState', 'carControl'], poll='livePose') + + params = Params() + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + + lag_learner = LateralLagEstimator(CP, 1. / SERVICE_LIST['livePose'].frequency) + if (initial_lag_params := retrieve_initial_lag(params, CP)) is not None: + lag, valid_blocks = initial_lag_params + lag_learner.reset(lag, valid_blocks) + + while True: + sm.update() + if sm.all_checks(): + for which in sorted(sm.updated.keys(), key=lambda x: sm.logMonoTime[x]): + if sm.updated[which]: + t = sm.logMonoTime[which] * 1e-9 + lag_learner.handle_log(t, which, sm[which]) + lag_learner.update_points() + + # 4Hz driven by livePose + if sm.frame % 5 == 0: + lag_learner.update_estimate() + lag_msg = lag_learner.get_msg(sm.all_checks(), DEBUG) + lag_msg_dat = lag_msg.to_bytes() + pm.send('liveDelay', lag_msg_dat) + + if sm.frame % 1200 == 0: # cache every 60 seconds + params.put_nonblocking("LiveDelay", lag_msg_dat) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 80789b8886..f6a0935ed9 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import json import time import capnp import numpy as np @@ -65,7 +64,7 @@ class LocationEstimator: self.observation_errors = {kind: np.zeros(3, dtype=np.float32) for kind in obs_kinds} def reset(self, t: float, x_initial: np.ndarray = PoseKalman.initial_x, P_initial: np.ndarray = PoseKalman.initial_P): - self.kf.reset(t, x_initial, P_initial) + self.kf.init_state(x_initial, covs=P_initial, filter_time=t) def _validate_sensor_source(self, source: log.SensorEventData.SensorSource): # some segments have two IMUs, ignore the second one @@ -186,8 +185,8 @@ class LocationEstimator: rot_device_noise = rot_device_std ** 2 trans_device_noise = trans_device_std ** 2 - cam_odo_rot_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_ROTATION, rot_device, rot_device_noise) - cam_odo_trans_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_TRANSLATION, trans_device, trans_device_noise) + cam_odo_rot_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_ROTATION, rot_device, np.array([np.diag(rot_device_noise)])) + cam_odo_trans_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_TRANSLATION, trans_device, np.array([np.diag(trans_device_noise)])) self.camodo_yawrate_distribution = np.array([rot_device[2], rot_device_std[2]]) if cam_odo_rot_res is not None: _, new_x, _, new_P, _, _, (cam_odo_rot_err,), _, _ = cam_odo_rot_res @@ -278,12 +277,13 @@ def main(): input_invalid_threshold = {s: input_invalid_limit[s] - 0.5 for s in critcal_services} input_invalid_decay = {s: calculate_invalid_input_decay(input_invalid_limit[s], INPUT_INVALID_RECOVERY, SERVICE_LIST[s].frequency) for s in critcal_services} - initial_pose = params.get("LocationFilterInitialState") - if initial_pose is not None: - initial_pose = json.loads(initial_pose) - x_initial = np.array(initial_pose["x"], dtype=np.float64) - P_initial = np.diag(np.array(initial_pose["P"], dtype=np.float64)) - estimator.reset(None, x_initial, P_initial) + initial_pose_data = params.get("LocationFilterInitialState") + if initial_pose_data is not None: + with log.Event.from_bytes(initial_pose_data) as lp_msg: + filter_state = lp_msg.livePose.debugFilterState + x_initial = np.array(filter_state.value, dtype=np.float64) if len(filter_state.value) != 0 else PoseKalman.initial_x + P_initial = np.diag(np.array(filter_state.std, dtype=np.float64)) if len(filter_state.std) != 0 else PoseKalman.initial_P + estimator.reset(None, x_initial, P_initial) while True: sm.update() diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index 5f40f19e46..349897f371 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -160,19 +160,18 @@ class CarKalman(KalmanFilter): gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, global_vars=global_vars) - def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0, P_initial=None): - dim_state = self.initial_x.shape[0] - dim_state_err = self.P_initial.shape[0] - x_init = self.initial_x - x_init[States.STEER_RATIO] = steer_ratio - x_init[States.STIFFNESS] = stiffness_factor - x_init[States.ANGLE_OFFSET] = angle_offset - - if P_initial is not None: - self.P_initial = P_initial - # init filter - self.filter = EKF_sym_pyx(generated_dir, self.name, self.Q, self.initial_x, self.P_initial, - dim_state, dim_state_err, global_vars=self.global_vars, logger=cloudlog) + def __init__(self, generated_dir): + dim_state, dim_state_err = CarKalman.initial_x.shape[0], CarKalman.P_initial.shape[0] + self.filter = EKF_sym_pyx(generated_dir, CarKalman.name, CarKalman.Q, CarKalman.initial_x, CarKalman.P_initial, + dim_state, dim_state_err, global_vars=CarKalman.global_vars, logger=cloudlog) + + def set_globals(self, mass, rotational_inertia, center_to_front, center_to_rear, stiffness_front, stiffness_rear): + self.filter.set_global("mass", mass) + self.filter.set_global("rotational_inertia", rotational_inertia) + self.filter.set_global("center_to_front", center_to_front) + self.filter.set_global("center_to_rear", center_to_rear) + self.filter.set_global("stiffness_front", stiffness_front) + self.filter.set_global("stiffness_rear", stiffness_rear) if __name__ == "__main__": diff --git a/selfdrive/locationd/models/pose_kf.py b/selfdrive/locationd/models/pose_kf.py index df63518441..020e51ad6e 100755 --- a/selfdrive/locationd/models/pose_kf.py +++ b/selfdrive/locationd/models/pose_kf.py @@ -5,6 +5,8 @@ import numpy as np from openpilot.selfdrive.locationd.models.constants import ObservationKind +from rednose.helpers.kalmanfilter import KalmanFilter + if __name__=="__main__": import sympy as sp from rednose.helpers.ekf_sym import gen_code @@ -24,7 +26,7 @@ class States: ACCEL_BIAS = slice(15, 18) # Acceletometer bias in m/s**2 -class PoseKalman: +class PoseKalman(KalmanFilter): name = "pose" # state @@ -50,10 +52,10 @@ class PoseKalman: 3**2, 3**2, 3**2, 0.005**2, 0.005**2, 0.005**2]) - obs_noise = {ObservationKind.PHONE_GYRO: np.array([0.025**2, 0.025**2, 0.025**2]), - ObservationKind.PHONE_ACCEL: np.array([.5**2, .5**2, .5**2]), - ObservationKind.CAMERA_ODO_TRANSLATION: np.array([0.5**2, 0.5**2, 0.5**2]), - ObservationKind.CAMERA_ODO_ROTATION: np.array([0.05**2, 0.05**2, 0.05**2])} + obs_noise = {ObservationKind.PHONE_GYRO: np.diag([0.025**2, 0.025**2, 0.025**2]), + ObservationKind.PHONE_ACCEL: np.diag([.5**2, .5**2, .5**2]), + ObservationKind.CAMERA_ODO_TRANSLATION: np.diag([0.5**2, 0.5**2, 0.5**2]), + ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2])} @staticmethod def generate_code(generated_dir): @@ -103,35 +105,6 @@ class PoseKalman: self.filter = EKF_sym_pyx(generated_dir, self.name, PoseKalman.Q, PoseKalman.initial_x, PoseKalman.initial_P, dim_state, dim_state_err, max_rewind_age=max_rewind_age) - @property - def x(self): - return self.filter.state() - - @property - def P(self): - return self.filter.covs() - - @property - def t(self): - return self.filter.get_filter_time() - - def predict_and_observe(self, t, kind, data, obs_noise=None): - data = np.atleast_2d(data) - if obs_noise is None: - obs_noise = self.obs_noise[kind] - R = self._get_R(len(data), obs_noise) - return self.filter.predict_and_update_batch(t, kind, data, R) - - def reset(self, t, x_init, P_init): - self.filter.init_state(x_init, P_init, t) - - def _get_R(self, n, obs_noise): - dim = obs_noise.shape[0] - R = np.zeros((n, dim, dim)) - for i in range(n): - R[i, :, :] = np.diag(obs_noise) - return R - if __name__ == "__main__": generated_dir = sys.argv[2] diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 3819fba080..ec15f501ae 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -1,8 +1,8 @@ #!/usr/bin/env python3 import os -import math import json import numpy as np +import capnp import cereal.messaging as messaging from cereal import car, log @@ -13,12 +13,11 @@ from openpilot.selfdrive.locationd.models.constants import GENERATED_DIR from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.common.swaglog import cloudlog - MAX_ANGLE_OFFSET_DELTA = 20 * DT_MDL # Max 20 deg/s -ROLL_MAX_DELTA = math.radians(20.0) * DT_MDL # 20deg in 1 second is well within curvature limits -ROLL_MIN, ROLL_MAX = math.radians(-10), math.radians(10) -ROLL_LOWERED_MAX = math.radians(8) -ROLL_STD_MAX = math.radians(1.5) +ROLL_MAX_DELTA = np.radians(20.0) * DT_MDL # 20deg in 1 second is well within curvature limits +ROLL_MIN, ROLL_MAX = np.radians(-10), np.radians(10) +ROLL_LOWERED_MAX = np.radians(8) +ROLL_STD_MAX = np.radians(1.5) LATERAL_ACC_SENSOR_THRESHOLD = 4.0 OFFSET_MAX = 10.0 OFFSET_LOWERED_MAX = 8.0 @@ -26,40 +25,58 @@ MIN_ACTIVE_SPEED = 1.0 LOW_ACTIVE_SPEED = 10.0 -class ParamsLearner: - def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=None): - self.kf = CarKalman(GENERATED_DIR, steer_ratio, stiffness_factor, angle_offset, P_initial) +class VehicleParamsLearner: + def __init__(self, CP: car.CarParams, steer_ratio: float, stiffness_factor: float, angle_offset: float, P_initial: np.ndarray | None = None): + self.kf = CarKalman(GENERATED_DIR) + + self.x_initial = CarKalman.initial_x.copy() + self.x_initial[States.STEER_RATIO] = steer_ratio + self.x_initial[States.STIFFNESS] = stiffness_factor + self.x_initial[States.ANGLE_OFFSET] = angle_offset + self.P_initial = P_initial if P_initial is not None else CarKalman.P_initial - self.kf.filter.set_global("mass", CP.mass) - self.kf.filter.set_global("rotational_inertia", CP.rotationalInertia) - self.kf.filter.set_global("center_to_front", CP.centerToFront) - self.kf.filter.set_global("center_to_rear", CP.wheelbase - CP.centerToFront) - self.kf.filter.set_global("stiffness_front", CP.tireStiffnessFront) - self.kf.filter.set_global("stiffness_rear", CP.tireStiffnessRear) + self.kf.set_globals( + mass=CP.mass, + rotational_inertia=CP.rotationalInertia, + center_to_front=CP.centerToFront, + center_to_rear=CP.wheelbase - CP.centerToFront, + stiffness_front=CP.tireStiffnessFront, + stiffness_rear=CP.tireStiffnessRear + ) - self.active = False + self.min_sr, self.max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio self.calibrator = PoseCalibrator() - self.speed = 0.0 - self.yaw_rate = 0.0 - self.yaw_rate_std = 0.0 - self.roll = 0.0 - self.steering_angle = 0.0 + self.observed_speed = 0.0 + self.observed_yaw_rate = 0.0 + self.observed_roll = 0.0 + + self.avg_offset_valid = True + self.total_offset_valid = True + self.roll_valid = True + + self.reset(None) - def handle_log(self, t, which, msg): + def reset(self, t: float | None): + self.kf.init_state(self.x_initial, covs=self.P_initial, filter_time=t) + + self.angle_offset, self.roll, self.active = np.degrees(self.x_initial[States.ANGLE_OFFSET].item()), 0.0, False + self.avg_angle_offset = self.angle_offset + + def handle_log(self, t: float, which: str, msg: capnp._DynamicStructReader): if which == 'livePose': device_pose = Pose.from_live_pose(msg) calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + yaw_rate, yaw_rate_std = calibrated_pose.angular_velocity.z, calibrated_pose.angular_velocity.z_std yaw_rate_valid = msg.angularVelocityDevice.valid - yaw_rate_valid = yaw_rate_valid and 0 < self.yaw_rate_std < 10 # rad/s - yaw_rate_valid = yaw_rate_valid and abs(self.yaw_rate) < 1 # rad/s - if yaw_rate_valid: - self.yaw_rate, self.yaw_rate_std = calibrated_pose.angular_velocity.z, calibrated_pose.angular_velocity.z_std - else: + yaw_rate_valid = yaw_rate_valid and 0 < yaw_rate_std < 10 # rad/s + yaw_rate_valid = yaw_rate_valid and abs(yaw_rate) < 1 # rad/s + if not yaw_rate_valid: # This is done to bound the yaw rate estimate when localizer values are invalid or calibrating - self.yaw_rate, self.yaw_rate_std = 0.0, np.radians(10.0) + yaw_rate, yaw_rate_std = 0.0, np.radians(10.0) + self.observed_yaw_rate = yaw_rate localizer_roll, localizer_roll_std = device_pose.orientation.x, device_pose.orientation.x_std localizer_roll_std = np.radians(1) if np.isnan(localizer_roll_std) else localizer_roll_std @@ -72,18 +89,18 @@ class ParamsLearner: # This is done to bound the road roll estimate when localizer values are invalid roll = 0.0 roll_std = np.radians(10.0) - self.roll = np.clip(roll, self.roll - ROLL_MAX_DELTA, self.roll + ROLL_MAX_DELTA) + self.observed_roll = np.clip(roll, self.observed_roll - ROLL_MAX_DELTA, self.observed_roll + ROLL_MAX_DELTA) if self.active: if msg.posenetOK: self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_YAW_RATE, - np.array([[-self.yaw_rate]]), - np.array([np.atleast_2d(self.yaw_rate_std**2)])) + np.array([[-self.observed_yaw_rate]]), + np.array([np.atleast_2d(yaw_rate_std**2)])) self.kf.predict_and_observe(t, ObservationKind.ROAD_ROLL, - np.array([[self.roll]]), + np.array([[self.observed_roll]]), np.array([np.atleast_2d(roll_std**2)])) self.kf.predict_and_observe(t, ObservationKind.ANGLE_OFFSET_FAST, np.array([[0]])) @@ -99,20 +116,79 @@ class ParamsLearner: self.calibrator.feed_live_calib(msg) elif which == 'carState': - self.steering_angle = msg.steeringAngleDeg - self.speed = msg.vEgo + steering_angle = msg.steeringAngleDeg - in_linear_region = abs(self.steering_angle) < 45 - self.active = self.speed > MIN_ACTIVE_SPEED and in_linear_region + in_linear_region = abs(steering_angle) < 45 + self.observed_speed = msg.vEgo + self.active = self.observed_speed > MIN_ACTIVE_SPEED and in_linear_region if self.active: - self.kf.predict_and_observe(t, ObservationKind.STEER_ANGLE, np.array([[math.radians(msg.steeringAngleDeg)]])) - self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_X_SPEED, np.array([[self.speed]])) + self.kf.predict_and_observe(t, ObservationKind.STEER_ANGLE, np.array([[np.radians(steering_angle)]])) + self.kf.predict_and_observe(t, ObservationKind.ROAD_FRAME_X_SPEED, np.array([[self.observed_speed]])) if not self.active: # Reset time when stopped so uncertainty doesn't grow - self.kf.filter.set_filter_time(t) - self.kf.filter.reset_rewind() + self.kf.filter.set_filter_time(t) # type: ignore + self.kf.filter.reset_rewind() # type: ignore + + def get_msg(self, valid: bool, debug: bool = False) -> capnp._DynamicStructBuilder: + x = self.kf.x + P = np.sqrt(self.kf.P.diagonal()) + if not np.all(np.isfinite(x)): + cloudlog.error("NaN in liveParameters estimate. Resetting to default values") + self.reset(self.kf.t) + x = self.kf.x + + self.avg_angle_offset = np.clip(np.degrees(x[States.ANGLE_OFFSET].item()), + self.avg_angle_offset - MAX_ANGLE_OFFSET_DELTA, self.avg_angle_offset + MAX_ANGLE_OFFSET_DELTA) + self.angle_offset = np.clip(np.degrees(x[States.ANGLE_OFFSET].item() + x[States.ANGLE_OFFSET_FAST].item()), + self.angle_offset - MAX_ANGLE_OFFSET_DELTA, self.angle_offset + MAX_ANGLE_OFFSET_DELTA) + self.roll = np.clip(float(x[States.ROAD_ROLL].item()), self.roll - ROLL_MAX_DELTA, self.roll + ROLL_MAX_DELTA) + roll_std = float(P[States.ROAD_ROLL].item()) + if self.active and self.observed_speed > LOW_ACTIVE_SPEED: + # Account for the opposite signs of the yaw rates + # At low speeds, bumping into a curb can cause the yaw rate to be very high + sensors_valid = bool(abs(self.observed_speed * (x[States.YAW_RATE].item() + self.observed_yaw_rate)) < LATERAL_ACC_SENSOR_THRESHOLD) + else: + sensors_valid = True + self.avg_offset_valid = check_valid_with_hysteresis(self.avg_offset_valid, self.avg_angle_offset, OFFSET_MAX, OFFSET_LOWERED_MAX) + self.total_offset_valid = check_valid_with_hysteresis(self.total_offset_valid, self.angle_offset, OFFSET_MAX, OFFSET_LOWERED_MAX) + self.roll_valid = check_valid_with_hysteresis(self.roll_valid, self.roll, ROLL_MAX, ROLL_LOWERED_MAX) + + msg = messaging.new_message('liveParameters') + + msg.valid = valid + + liveParameters = msg.liveParameters + liveParameters.posenetValid = True + liveParameters.sensorValid = sensors_valid + liveParameters.steerRatio = float(x[States.STEER_RATIO].item()) + liveParameters.stiffnessFactor = float(x[States.STIFFNESS].item()) + liveParameters.roll = float(self.roll) + liveParameters.angleOffsetAverageDeg = float(self.avg_angle_offset) + liveParameters.angleOffsetDeg = float(self.angle_offset) + liveParameters.steerRatioValid = self.min_sr <= liveParameters.steerRatio <= self.max_sr + liveParameters.stiffnessFactorValid = 0.2 <= liveParameters.stiffnessFactor <= 5.0 + liveParameters.angleOffsetAverageValid = bool(self.avg_offset_valid) + liveParameters.angleOffsetValid = bool(self.total_offset_valid) + liveParameters.valid = all(( + liveParameters.angleOffsetAverageValid, + liveParameters.angleOffsetValid , + self.roll_valid, + roll_std < ROLL_STD_MAX, + liveParameters.stiffnessFactorValid, + liveParameters.steerRatioValid, + )) + liveParameters.steerRatioStd = float(P[States.STEER_RATIO].item()) + liveParameters.stiffnessFactorStd = float(P[States.STIFFNESS].item()) + liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET].item()) + liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST].item()) + if debug: + liveParameters.debugFilterState = log.LiveParametersData.FilterState.new_message() + liveParameters.debugFilterState.value = x.tolist() + liveParameters.debugFilterState.std = P.tolist() + + return msg def check_valid_with_hysteresis(current_valid: bool, val: float, threshold: float, lowered_threshold: float): @@ -123,69 +199,84 @@ def check_valid_with_hysteresis(current_valid: bool, val: float, threshold: floa return current_valid -def main(): - config_realtime_process([0, 1, 2, 3], 5) - - DEBUG = bool(int(os.getenv("DEBUG", "0"))) - REPLAY = bool(int(os.getenv("REPLAY", "0"))) - - pm = messaging.PubMaster(['liveParameters']) - sm = messaging.SubMaster(['livePose', 'liveCalibration', 'carState'], poll='livePose') +# TODO: Remove this function after few releases (added in 0.9.9) +def migrate_cached_vehicle_params_if_needed(params: Params): + last_parameters_data_old = params.get("LiveParameters") + last_parameters_data = params.get("LiveParametersV2") + if last_parameters_data_old is None or last_parameters_data is not None: + return - params_reader = Params() - # wait for stats about the car to come in from controls - cloudlog.info("paramsd is waiting for CarParams") - CP = messaging.log_from_bytes(params_reader.get("CarParams", block=True), car.CarParams) - cloudlog.info("paramsd got CarParams") + try: + last_parameters_dict = json.loads(last_parameters_data_old) + last_parameters_msg = messaging.new_message('liveParameters') + last_parameters_msg.liveParameters.valid = True + last_parameters_msg.liveParameters.steerRatio = last_parameters_dict['steerRatio'] + last_parameters_msg.liveParameters.stiffnessFactor = last_parameters_dict['stiffnessFactor'] + last_parameters_msg.liveParameters.angleOffsetAverageDeg = last_parameters_dict['angleOffsetAverageDeg'] + params.put("LiveParametersV2", last_parameters_msg.to_bytes()) + except Exception as e: + cloudlog.error(f"Failed to perform parameter migration: {e}") + params.remove("LiveParameters") - min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio - params = params_reader.get("LiveParameters") +def retrieve_initial_vehicle_params(params: Params, CP: car.CarParams, replay: bool, debug: bool): + last_parameters_data = params.get("LiveParametersV2") + last_carparams_data = params.get("CarParamsPrevRoute") - # Check if car model matches - if params is not None: - params = json.loads(params) - if params.get('carFingerprint', None) != CP.carFingerprint: - cloudlog.info("Parameter learner found parameters for wrong car.") - params = None + steer_ratio, stiffness_factor, angle_offset_deg, p_initial = CP.steerRatio, 1.0, 0.0, None - # Check if starting values are sane - if params is not None: + retrieve_success = False + if last_parameters_data is not None and last_carparams_data is not None: try: - steer_ratio_sane = min_sr <= params['steerRatio'] <= max_sr - if not steer_ratio_sane: - cloudlog.info(f"Invalid starting values found {params}") - params = None + with log.Event.from_bytes(last_parameters_data) as last_lp_msg, car.CarParams.from_bytes(last_carparams_data) as last_CP: + lp = last_lp_msg.liveParameters + # Check if car model matches + if last_CP.carFingerprint != CP.carFingerprint: + raise Exception("Car model mismatch") + + # Check if starting values are sane + min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio + steer_ratio_sane = min_sr <= lp.steerRatio <= max_sr + if not steer_ratio_sane: + raise Exception(f"Invalid starting values found {lp}") + + initial_filter_std = np.array(lp.debugFilterState.std) + if debug and len(initial_filter_std) != 0: + p_initial = np.diag(initial_filter_std) + + steer_ratio, stiffness_factor, angle_offset_deg = lp.steerRatio, lp.stiffnessFactor, lp.angleOffsetAverageDeg + retrieve_success = True except Exception as e: - cloudlog.info(f"Error reading params {params}: {str(e)}") - params = None - - # TODO: cache the params with the capnp struct - if params is None: - params = { - 'carFingerprint': CP.carFingerprint, - 'steerRatio': CP.steerRatio, - 'stiffnessFactor': 1.0, - 'angleOffsetAverageDeg': 0.0, - } - cloudlog.info("Parameter learner resetting to default values") + cloudlog.error(f"Failed to retrieve initial values: {e}") + params.remove("LiveParametersV2") - if not REPLAY: + if not replay: # When driving in wet conditions the stiffness can go down, and then be too low on the next drive # Without a way to detect this we have to reset the stiffness every drive - params['stiffnessFactor'] = 1.0 + stiffness_factor = 1.0 - pInitial = None - if DEBUG: - pInitial = np.array(params['debugFilterState']['std']) if 'debugFilterState' in params else None + if not retrieve_success: + cloudlog.info("Parameter learner resetting to default values") + + return steer_ratio, stiffness_factor, angle_offset_deg, p_initial + + +def main(): + config_realtime_process([0, 1, 2, 3], 5) + + DEBUG = bool(int(os.getenv("DEBUG", "0"))) + REPLAY = bool(int(os.getenv("REPLAY", "0"))) + + pm = messaging.PubMaster(['liveParameters']) + sm = messaging.SubMaster(['livePose', 'liveCalibration', 'carState'], poll='livePose') - learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverageDeg']), pInitial) - angle_offset_average = params['angleOffsetAverageDeg'] - angle_offset = angle_offset_average - roll = 0.0 - avg_offset_valid = True - total_offset_valid = True - roll_valid = True + params = Params() + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + + migrate_cached_vehicle_params_if_needed(params) + + steer_ratio, stiffness_factor, angle_offset_deg, pInitial = retrieve_initial_vehicle_params(params, CP, REPLAY, DEBUG) + learner = VehicleParamsLearner(CP, steer_ratio, stiffness_factor, np.radians(angle_offset_deg), pInitial) while True: sm.update() @@ -196,72 +287,13 @@ def main(): learner.handle_log(t, which, sm[which]) if sm.updated['livePose']: - x = learner.kf.x - P = np.sqrt(learner.kf.P.diagonal()) - if not all(map(math.isfinite, x)): - cloudlog.error("NaN in liveParameters estimate. Resetting to default values") - learner = ParamsLearner(CP, CP.steerRatio, 1.0, 0.0) - x = learner.kf.x - - angle_offset_average = np.clip(math.degrees(x[States.ANGLE_OFFSET].item()), - angle_offset_average - MAX_ANGLE_OFFSET_DELTA, angle_offset_average + MAX_ANGLE_OFFSET_DELTA) - angle_offset = np.clip(math.degrees(x[States.ANGLE_OFFSET].item() + x[States.ANGLE_OFFSET_FAST].item()), - angle_offset - MAX_ANGLE_OFFSET_DELTA, angle_offset + MAX_ANGLE_OFFSET_DELTA) - roll = np.clip(float(x[States.ROAD_ROLL].item()), roll - ROLL_MAX_DELTA, roll + ROLL_MAX_DELTA) - roll_std = float(P[States.ROAD_ROLL].item()) - if learner.active and learner.speed > LOW_ACTIVE_SPEED: - # Account for the opposite signs of the yaw rates - # At low speeds, bumping into a curb can cause the yaw rate to be very high - sensors_valid = bool(abs(learner.speed * (x[States.YAW_RATE].item() + learner.yaw_rate)) < LATERAL_ACC_SENSOR_THRESHOLD) - else: - sensors_valid = True - avg_offset_valid = check_valid_with_hysteresis(avg_offset_valid, angle_offset_average, OFFSET_MAX, OFFSET_LOWERED_MAX) - total_offset_valid = check_valid_with_hysteresis(total_offset_valid, angle_offset, OFFSET_MAX, OFFSET_LOWERED_MAX) - roll_valid = check_valid_with_hysteresis(roll_valid, roll, ROLL_MAX, ROLL_LOWERED_MAX) - - msg = messaging.new_message('liveParameters') - - liveParameters = msg.liveParameters - liveParameters.posenetValid = True - liveParameters.sensorValid = sensors_valid - liveParameters.steerRatio = float(x[States.STEER_RATIO].item()) - liveParameters.stiffnessFactor = float(x[States.STIFFNESS].item()) - liveParameters.roll = float(roll) - liveParameters.angleOffsetAverageDeg = float(angle_offset_average) - liveParameters.angleOffsetDeg = float(angle_offset) - liveParameters.steerRatioValid = min_sr <= liveParameters.steerRatio <= max_sr - liveParameters.stiffnessFactorValid = 0.2 <= liveParameters.stiffnessFactor <= 5.0 - liveParameters.angleOffsetAverageValid = bool(avg_offset_valid) - liveParameters.angleOffsetValid = bool(total_offset_valid) - liveParameters.valid = all(( - liveParameters.angleOffsetAverageValid, - liveParameters.angleOffsetValid , - roll_valid, - roll_std < ROLL_STD_MAX, - liveParameters.stiffnessFactorValid, - liveParameters.steerRatioValid, - )) - liveParameters.steerRatioStd = float(P[States.STEER_RATIO].item()) - liveParameters.stiffnessFactorStd = float(P[States.STIFFNESS].item()) - liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET].item()) - liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST].item()) - if DEBUG: - liveParameters.debugFilterState = log.LiveParametersData.FilterState.new_message() - liveParameters.debugFilterState.value = x.tolist() - liveParameters.debugFilterState.std = P.tolist() - - msg.valid = sm.all_checks() + msg = learner.get_msg(sm.all_checks(), debug=DEBUG) + msg_dat = msg.to_bytes() if sm.frame % 1200 == 0: # once a minute - params = { - 'carFingerprint': CP.carFingerprint, - 'steerRatio': liveParameters.steerRatio, - 'stiffnessFactor': liveParameters.stiffnessFactor, - 'angleOffsetAverageDeg': liveParameters.angleOffsetAverageDeg, - } - params_reader.put_nonblocking("LiveParameters", json.dumps(params)) - - pm.send('liveParameters', msg) + params.put_nonblocking("LiveParametersV2", msg_dat) + + pm.send('liveParameters', msg_dat) if __name__ == "__main__": diff --git a/selfdrive/locationd/test/test_lagd.py b/selfdrive/locationd/test/test_lagd.py new file mode 100644 index 0000000000..b805f1759d --- /dev/null +++ b/selfdrive/locationd/test/test_lagd.py @@ -0,0 +1,141 @@ +import random +import numpy as np +import time +import pytest + +from cereal import messaging, log +from openpilot.selfdrive.locationd.lagd import LateralLagEstimator, retrieve_initial_lag, masked_normalized_cross_correlation, \ + BLOCK_NUM_NEEDED, BLOCK_SIZE, MIN_OKAY_WINDOW_SEC +from openpilot.selfdrive.test.process_replay.migration import migrate, migrate_carParams +from openpilot.selfdrive.locationd.test.test_locationd_scenarios import TEST_ROUTE +from openpilot.common.params import Params +from openpilot.tools.lib.logreader import LogReader +from openpilot.system.hardware import PC + +MAX_ERR_FRAMES = 1 +DT = 0.05 + + +def process_messages(mocker, estimator, lag_frames, n_frames, vego=20.0, rejection_threshold=0.0): + class ZeroMock(mocker.Mock): + def __getattr__(self, *args): + return 0 + + for i in range(n_frames): + t = i * estimator.dt + desired_la = np.cos(10 * t) * 0.1 + actual_la = np.cos(10 * (t - lag_frames * estimator.dt)) * 0.1 + + # if sample is masked out, set it to desired value (no lag) + rejected = random.uniform(0, 1) < rejection_threshold + if rejected: + actual_la = desired_la + + desired_cuvature = desired_la / (vego ** 2) + actual_yr = actual_la / vego + msgs = [ + (t, "carControl", mocker.Mock(latActive=not rejected)), + (t, "carState", mocker.Mock(vEgo=vego, steeringPressed=False)), + (t, "controlsState", mocker.Mock(desiredCurvature=desired_cuvature, + lateralControlState=mocker.Mock(which=mocker.Mock(return_value='debugControlState'), debugControlState=ZeroMock()))), + (t, "livePose", mocker.Mock(orientationNED=ZeroMock(), + velocityDevice=ZeroMock(), + accelerationDevice=ZeroMock(), + angularVelocityDevice=ZeroMock(z=actual_yr, valid=True), + posenetOK=True, inputsOK=True)), + (t, "liveCalibration", mocker.Mock(rpyCalib=[0, 0, 0], calStatus=log.LiveCalibrationData.Status.calibrated)), + ] + for t, w, m in msgs: + estimator.handle_log(t, w, m) + estimator.update_points() + estimator.update_estimate() + + +class TestLagd: + def test_read_saved_params(self): + params = Params() + + lr = migrate(LogReader(TEST_ROUTE), [migrate_carParams]) + CP = next(m for m in lr if m.which() == "carParams").carParams + + msg = messaging.new_message('liveDelay') + msg.liveDelay.lateralDelayEstimate = random.random() + msg.liveDelay.validBlocks = random.randint(1, 10) + params.put("LiveDelay", msg.to_bytes()) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes()) + + saved_lag_params = retrieve_initial_lag(params, CP) + assert saved_lag_params is not None + + lag, valid_blocks = saved_lag_params + assert lag == msg.liveDelay.lateralDelayEstimate + assert valid_blocks == msg.liveDelay.validBlocks + + def test_ncc(self): + lag_frames = random.randint(1, 19) + + desired_sig = np.sin(np.arange(0.0, 10.0, 0.1)) + actual_sig = np.sin(np.arange(0.0, 10.0, 0.1) - lag_frames * 0.1) + mask = np.ones(len(desired_sig), dtype=bool) + + corr = masked_normalized_cross_correlation(desired_sig, actual_sig, mask, 200)[len(desired_sig) - 1:len(desired_sig) + 20] + assert np.argmax(corr) == lag_frames + + # add some noise + desired_sig += np.random.normal(0, 0.05, len(desired_sig)) + actual_sig += np.random.normal(0, 0.05, len(actual_sig)) + corr = masked_normalized_cross_correlation(desired_sig, actual_sig, mask, 200)[len(desired_sig) - 1:len(desired_sig) + 20] + assert np.argmax(corr) in range(lag_frames - MAX_ERR_FRAMES, lag_frames + MAX_ERR_FRAMES + 1) + + # mask out 40% of the values, and make them noise + mask = np.random.choice([True, False], size=len(desired_sig), p=[0.6, 0.4]) + desired_sig[~mask] = np.random.normal(0, 1, size=np.sum(~mask)) + actual_sig[~mask] = np.random.normal(0, 1, size=np.sum(~mask)) + corr = masked_normalized_cross_correlation(desired_sig, actual_sig, mask, 200)[len(desired_sig) - 1:len(desired_sig) + 20] + assert np.argmax(corr) in range(lag_frames - MAX_ERR_FRAMES, lag_frames + MAX_ERR_FRAMES + 1) + + def test_empty_estimator(self, mocker): + mocked_CP = mocker.Mock(steerActuatorDelay=0.8) + estimator = LateralLagEstimator(mocked_CP, DT) + msg = estimator.get_msg(True) + assert msg.liveDelay.status == 'unestimated' + assert np.allclose(msg.liveDelay.lateralDelay, estimator.initial_lag) + assert np.allclose(msg.liveDelay.lateralDelayEstimate, estimator.initial_lag) + assert msg.liveDelay.validBlocks == 0 + + def test_estimator_basics(self, mocker, subtests): + for lag_frames in range(5): + with subtests.test(msg=f"lag_frames={lag_frames}"): + mocked_CP = mocker.Mock(steerActuatorDelay=0.8) + estimator = LateralLagEstimator(mocked_CP, DT, min_recovery_buffer_sec=0.0, min_yr=0.0) + process_messages(mocker, estimator, lag_frames, int(MIN_OKAY_WINDOW_SEC / DT) + BLOCK_NUM_NEEDED * BLOCK_SIZE) + msg = estimator.get_msg(True) + assert msg.liveDelay.status == 'estimated' + assert np.allclose(msg.liveDelay.lateralDelay, lag_frames * DT, atol=0.01) + assert np.allclose(msg.liveDelay.lateralDelayEstimate, lag_frames * DT, atol=0.01) + assert np.allclose(msg.liveDelay.lateralDelayEstimateStd, 0.0, atol=0.01) + assert msg.liveDelay.validBlocks == BLOCK_NUM_NEEDED + + def test_estimator_masking(self, mocker): + mocked_CP, lag_frames = mocker.Mock(steerActuatorDelay=0.8), random.randint(1, 19) + estimator = LateralLagEstimator(mocked_CP, DT, min_recovery_buffer_sec=0.0, min_yr=0.0, min_valid_block_count=1) + process_messages(mocker, estimator, lag_frames, (int(MIN_OKAY_WINDOW_SEC / DT) + BLOCK_SIZE) * 2, rejection_threshold=0.4) + msg = estimator.get_msg(True) + assert np.allclose(msg.liveDelay.lateralDelayEstimate, lag_frames * DT, atol=0.01) + assert np.allclose(msg.liveDelay.lateralDelayEstimateStd, 0.0, atol=0.01) + + @pytest.mark.skipif(PC, reason="only on device") + @pytest.mark.timeout(60) + def test_estimator_performance(self, mocker): + mocked_CP = mocker.Mock(steerActuatorDelay=0.8) + estimator = LateralLagEstimator(mocked_CP, DT) + + ds = [] + for _ in range(1000): + st = time.perf_counter() + estimator.update_points() + estimator.update_estimate() + d = time.perf_counter() - st + ds.append(d) + + assert np.mean(ds) < DT diff --git a/selfdrive/locationd/test/test_paramsd.py b/selfdrive/locationd/test/test_paramsd.py new file mode 100644 index 0000000000..2129bf4386 --- /dev/null +++ b/selfdrive/locationd/test/test_paramsd.py @@ -0,0 +1,68 @@ +import random +import numpy as np +import json + +from cereal import messaging +from openpilot.selfdrive.locationd.paramsd import retrieve_initial_vehicle_params, migrate_cached_vehicle_params_if_needed +from openpilot.selfdrive.locationd.models.car_kf import CarKalman +from openpilot.selfdrive.locationd.test.test_locationd_scenarios import TEST_ROUTE +from openpilot.selfdrive.test.process_replay.migration import migrate, migrate_carParams +from openpilot.common.params import Params +from openpilot.tools.lib.logreader import LogReader + + +def get_random_live_parameters(CP): + msg = messaging.new_message("liveParameters") + msg.liveParameters.steerRatio = (random.random() + 0.5) * CP.steerRatio + msg.liveParameters.stiffnessFactor = random.random() + msg.liveParameters.angleOffsetAverageDeg = random.random() + msg.liveParameters.debugFilterState.std = [random.random() for _ in range(CarKalman.P_initial.shape[0])] + return msg + + +class TestParamsd: + def test_read_saved_params(self): + params = Params() + + lr = migrate(LogReader(TEST_ROUTE), [migrate_carParams]) + CP = next(m for m in lr if m.which() == "carParams").carParams + + msg = get_random_live_parameters(CP) + params.put("LiveParametersV2", msg.to_bytes()) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes()) + + migrate_cached_vehicle_params_if_needed(params) # this is not tested here but should not mess anything up or throw an error + sr, sf, offset, p_init = retrieve_initial_vehicle_params(params, CP, replay=True, debug=True) + np.testing.assert_allclose(sr, msg.liveParameters.steerRatio) + np.testing.assert_allclose(sf, msg.liveParameters.stiffnessFactor) + np.testing.assert_allclose(offset, msg.liveParameters.angleOffsetAverageDeg) + np.testing.assert_equal(p_init.shape, CarKalman.P_initial.shape) + np.testing.assert_allclose(np.diagonal(p_init), msg.liveParameters.debugFilterState.std) + + # TODO Remove this test after the support for old format is removed + def test_read_saved_params_old_format(self): + params = Params() + + lr = migrate(LogReader(TEST_ROUTE), [migrate_carParams]) + CP = next(m for m in lr if m.which() == "carParams").carParams + + msg = get_random_live_parameters(CP) + params.put("LiveParameters", json.dumps(msg.liveParameters.to_dict())) + params.put("CarParamsPrevRoute", CP.as_builder().to_bytes()) + params.remove("LiveParametersV2") + + migrate_cached_vehicle_params_if_needed(params) + sr, sf, offset, _ = retrieve_initial_vehicle_params(params, CP, replay=True, debug=True) + np.testing.assert_allclose(sr, msg.liveParameters.steerRatio) + np.testing.assert_allclose(sf, msg.liveParameters.stiffnessFactor) + np.testing.assert_allclose(offset, msg.liveParameters.angleOffsetAverageDeg) + assert params.get("LiveParametersV2") is not None + + def test_read_saved_params_corrupted_old_format(self): + params = Params() + params.put("LiveParameters", b'\x00\x00\x02\x00\x01\x00:F\xde\xed\xae;') + params.remove("LiveParametersV2") + + migrate_cached_vehicle_params_if_needed(params) + assert params.get("LiveParameters") is None + assert params.get("LiveParametersV2") is None diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 590b6cc6f7..fcaa19df73 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -32,7 +32,7 @@ MIN_BUCKET_POINTS = np.array([100, 300, 500, 500, 500, 500, 300, 100]) MIN_ENGAGE_BUFFER = 2 # secs VERSION = 1 # bump this to invalidate old parameter caches -ALLOWED_CARS = ['toyota', 'hyundai'] +ALLOWED_CARS = ['toyota', 'hyundai', 'rivian'] def slope2rot(slope): diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index cecebfa18b..10f3876190 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -1,3 +1,4 @@ +import os import glob Import('env', 'envCython', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'transformations') @@ -13,7 +14,6 @@ common_src = [ "transforms/transform.cc", ] - # OpenCL is a framework on Mac if arch == "Darwin": frameworks += ['OpenCL'] @@ -38,17 +38,35 @@ for model_name in ['driving_vision', 'driving_policy']: cmd = f'python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.onnx' lenv.Command(fn + "_metadata.pkl", [fn + ".onnx"] + tinygrad_files + script_files, cmd) -# Compile tinygrad model -pythonpath_string = 'PYTHONPATH="${PYTHONPATH}:' + env.Dir("#tinygrad_repo").abspath + '"' -if arch == 'larch64': - device_string = 'QCOM=1' -elif arch == 'Darwin': - device_string = 'CLANG=1 IMAGE=0' -else: - device_string = 'LLVM=1 LLVMOPT=1 BEAM=0 IMAGE=0' +def tg_compile(flags, model_name): + pythonpath_string = 'PYTHONPATH="${PYTHONPATH}:' + env.Dir("#tinygrad_repo").abspath + '"' + fn = File(f"models/{model_name}").abspath + return lenv.Command( + fn + "_tinygrad.pkl", + [fn + ".onnx"] + tinygrad_files, + f'{pythonpath_string} {flags} python3 {Dir("#tinygrad_repo").abspath}/examples/openpilot/compile3.py {fn}.onnx {fn}_tinygrad.pkl' + ) +# Compile small models for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']: - fn = File(f"models/{model_name}").abspath - cmd = f'{pythonpath_string} {device_string} python3 {Dir("#tinygrad_repo").abspath}/examples/openpilot/compile3.py {fn}.onnx {fn}_tinygrad.pkl' - lenv.Command(fn + "_tinygrad.pkl", [fn + ".onnx"] + tinygrad_files, cmd) + flags = { + 'larch64': 'QCOM=1', + 'Darwin': 'CPU=1 IMAGE=0 JIT=2', + }.get(arch, 'LLVM=1 LLVMOPT=1 BEAM=0 IMAGE=0 JIT=2') + tg_compile(flags, model_name) + +# Compile BIG model if USB GPU is available +import subprocess +from tinygrad import Device +# because tg doesn't support multi-process +devs = subprocess.check_output('python3 -c "from tinygrad import Device; print(list(Device.get_available_devices()))"', shell=True) +if b"AMD" in devs: + del Device + print("USB GPU detected... building") + flags = "AMD=1 AMD_IFACE=USB AMD_LLVM=1 NOLOCALS=0 IMAGE=0" + bp = tg_compile(flags, "big_driving_policy") + bv = tg_compile(flags, "big_driving_vision") + lenv.SideEffect('lock', [bp, bv]) # tg doesn't support multi-process so build serially +else: + print("USB GPU not detected... skipping") diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 2bb7b8100c..5ca0a86bc8 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -14,8 +14,14 @@ class ModelConstants: # model inputs constants MODEL_FREQ = 20 + HISTORY_FREQ = 5 + HISTORY_LEN_SECONDS = 5 + TEMPORAL_SKIP = MODEL_FREQ // HISTORY_FREQ + FULL_HISTORY_BUFFER_LEN = MODEL_FREQ * HISTORY_LEN_SECONDS + INPUT_HISTORY_BUFFER_LEN = HISTORY_FREQ * HISTORY_LEN_SECONDS + FEATURE_LEN = 512 - FULL_HISTORY_BUFFER_LEN = 100 + DESIRE_LEN = 8 TRAFFIC_CONVENTION_LEN = 2 LAT_PLANNER_STATE_LEN = 4 diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index 9ebdea4c75..2a3df3f652 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -134,7 +134,7 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: def main(): setproctitle(PROCESS_NAME) - config_realtime_process([0, 1, 2, 3], 5) + config_realtime_process(7, 5) sentry.set_tag("daemon", PROCESS_NAME) cloudlog.bind(daemon=PROCESS_NAME) diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 0ea88f9bc1..a91c6395c7 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -56,7 +56,7 @@ def fill_lane_line_meta(builder, lane_lines, lane_line_probs): builder.rightProb = lane_line_probs[2] def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._DynamicStructBuilder, - net_output_data: dict[str, np.ndarray], v_ego: float, delay: float, + net_output_data: dict[str, np.ndarray], action: log.ModelDataV2.Action, publish_state: PublishState, vipc_frame_id: int, vipc_frame_id_extra: int, frame_id: int, frame_drop: float, timestamp_eof: int, model_execution_time: float, valid: bool) -> None: @@ -71,7 +71,8 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D driving_model_data.frameIdExtra = vipc_frame_id_extra driving_model_data.frameDropPerc = frame_drop_perc driving_model_data.modelExecutionTime = model_execution_time - driving_model_data.action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) + + driving_model_data.action = action modelV2 = extended_msg.modelV2 modelV2.frameId = vipc_frame_id @@ -98,33 +99,17 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D # poly path fill_xyz_poly(driving_model_data.path, ModelConstants.POLY_PATH_DEGREE, *net_output_data['plan'][0,:,Plan.POSITION].T) - # lateral planning - modelV2.action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) - - # times at X_IDXS according to model plan - PLAN_T_IDXS = [np.nan] * ModelConstants.IDX_N - PLAN_T_IDXS[0] = 0.0 - plan_x = net_output_data['plan'][0,:,Plan.POSITION][:,0].tolist() - for xidx in range(1, ModelConstants.IDX_N): - tidx = 0 - # increment tidx until we find an element that's further away than the current xidx - while tidx < ModelConstants.IDX_N - 1 and plan_x[tidx+1] < ModelConstants.X_IDXS[xidx]: - tidx += 1 - if tidx == ModelConstants.IDX_N - 1: - # if the Plan doesn't extend far enough, set plan_t to the max value (10s), then break - PLAN_T_IDXS[xidx] = ModelConstants.T_IDXS[ModelConstants.IDX_N - 1] - break - # interpolate to find `t` for the current xidx - current_x_val = plan_x[tidx] - next_x_val = plan_x[tidx+1] - p = (ModelConstants.X_IDXS[xidx] - current_x_val) / (next_x_val - current_x_val) if abs(next_x_val - current_x_val) > 1e-9 else float('nan') - PLAN_T_IDXS[xidx] = p * ModelConstants.T_IDXS[tidx+1] + (1 - p) * ModelConstants.T_IDXS[tidx] + # action + modelV2.action = action + + # times at X_IDXS of edges and lines aren't used + LINE_T_IDXS: list[float] = [] # lane lines modelV2.init('laneLines', 4) for i in range(4): lane_line = modelV2.laneLines[i] - fill_xyzt(lane_line, PLAN_T_IDXS, np.array(ModelConstants.X_IDXS), net_output_data['lane_lines'][0,i,:,0], net_output_data['lane_lines'][0,i,:,1]) + fill_xyzt(lane_line, LINE_T_IDXS, np.array(ModelConstants.X_IDXS), net_output_data['lane_lines'][0,i,:,0], net_output_data['lane_lines'][0,i,:,1]) modelV2.laneLineStds = net_output_data['lane_lines_stds'][0,:,0,0].tolist() modelV2.laneLineProbs = net_output_data['lane_lines_prob'][0,1::2].tolist() @@ -134,7 +119,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D modelV2.init('roadEdges', 2) for i in range(2): road_edge = modelV2.roadEdges[i] - fill_xyzt(road_edge, PLAN_T_IDXS, np.array(ModelConstants.X_IDXS), net_output_data['road_edges'][0,i,:,0], net_output_data['road_edges'][0,i,:,1]) + fill_xyzt(road_edge, LINE_T_IDXS, np.array(ModelConstants.X_IDXS), net_output_data['road_edges'][0,i,:,0], net_output_data['road_edges'][0,i,:,1]) modelV2.roadEdgeStds = net_output_data['road_edges_stds'][0,:,0,0].tolist() # leads diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index ee825d158f..96520a4b15 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -1,13 +1,18 @@ #!/usr/bin/env python3 import os from openpilot.system.hardware import TICI -from tinygrad.tensor import Tensor -from tinygrad.dtype import dtypes -if TICI: +USBGPU = "USBGPU" in os.environ +if USBGPU: + os.environ['AMD'] = '1' + os.environ['AMD_IFACE'] = 'USB' +elif TICI: from openpilot.selfdrive.modeld.runners.tinygrad_helpers import qcom_tensor_from_opencl_address os.environ['QCOM'] = '1' else: os.environ['LLVM'] = '1' + os.environ['JIT'] = '2' +from tinygrad.tensor import Tensor +from tinygrad.dtype import dtypes import time import pickle import numpy as np @@ -21,14 +26,15 @@ from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.filter_simple import FirstOrderFilter -from openpilot.common.realtime import config_realtime_process +from openpilot.common.realtime import config_realtime_process, DT_MDL from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper +from openpilot.selfdrive.controls.lib.drive_helpers import get_accel_from_plan, smooth_value from openpilot.selfdrive.modeld.parse_model_outputs import Parser from openpilot.selfdrive.modeld.fill_model_msg import fill_model_msg, fill_pose_msg, PublishState -from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.selfdrive.modeld.constants import ModelConstants, Plan from openpilot.selfdrive.modeld.models.commonmodel_pyx import DrivingModelFrame, CLContext @@ -40,6 +46,30 @@ POLICY_PKL_PATH = Path(__file__).parent / 'models/driving_policy_tinygrad.pkl' VISION_METADATA_PATH = Path(__file__).parent / 'models/driving_vision_metadata.pkl' POLICY_METADATA_PATH = Path(__file__).parent / 'models/driving_policy_metadata.pkl' +LAT_SMOOTH_SECONDS = 0.0 +LONG_SMOOTH_SECONDS = 0.0 +MIN_LAT_CONTROL_SPEED = 0.3 + + +def get_action_from_model(model_output: dict[str, np.ndarray], prev_action: log.ModelDataV2.Action, + lat_action_t: float, long_action_t: float, v_ego: float) -> log.ModelDataV2.Action: + plan = model_output['plan'][0] + desired_accel, should_stop = get_accel_from_plan(plan[:,Plan.VELOCITY][:,0], + plan[:,Plan.ACCELERATION][:,0], + ModelConstants.T_IDXS, + action_t=long_action_t) + desired_accel = smooth_value(desired_accel, prev_action.desiredAcceleration, LONG_SMOOTH_SECONDS) + + desired_curvature = model_output['desired_curvature'][0, 0] + if v_ego > MIN_LAT_CONTROL_SPEED: + desired_curvature = smooth_value(desired_curvature, prev_action.desiredCurvature, LAT_SMOOTH_SECONDS) + else: + desired_curvature = prev_action.desiredCurvature + + return log.ModelDataV2.Action(desiredCurvature=float(desired_curvature), + desiredAcceleration=float(desired_accel), + shouldStop=bool(should_stop)) + class FrameMeta: frame_id: int = 0 timestamp_sof: int = 0 @@ -56,16 +86,24 @@ class ModelState: prev_desire: np.ndarray # for tracking the rising edge of the pulse def __init__(self, context: CLContext): - self.frames = {'input_imgs': DrivingModelFrame(context), 'big_input_imgs': DrivingModelFrame(context)} + self.frames = { + 'input_imgs': DrivingModelFrame(context, ModelConstants.TEMPORAL_SKIP), + 'big_input_imgs': DrivingModelFrame(context, ModelConstants.TEMPORAL_SKIP) + } self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) + self.full_features_buffer = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32) + self.full_desire = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32) + self.full_prev_desired_curv = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32) + self.temporal_idxs = slice(-1-(ModelConstants.TEMPORAL_SKIP*(ModelConstants.INPUT_HISTORY_BUFFER_LEN-1)), None, ModelConstants.TEMPORAL_SKIP) + # policy inputs self.numpy_inputs = { - 'desire': np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32), + 'desire': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32), 'traffic_convention': np.zeros((1, ModelConstants.TRAFFIC_CONVENTION_LEN), dtype=np.float32), 'lateral_control_params': np.zeros((1, ModelConstants.LATERAL_CONTROL_PARAMS_LEN), dtype=np.float32), - 'prev_desired_curv': np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32), - 'features_buffer': np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32), + 'prev_desired_curv': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32), + 'features_buffer': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32), } with open(VISION_METADATA_PATH, 'rb') as f: @@ -104,15 +142,16 @@ class ModelState: new_desire = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) self.prev_desire[:] = inputs['desire'] - self.numpy_inputs['desire'][0,:-1] = self.numpy_inputs['desire'][0,1:] - self.numpy_inputs['desire'][0,-1] = new_desire + self.full_desire[0,:-1] = self.full_desire[0,1:] + self.full_desire[0,-1] = new_desire + self.numpy_inputs['desire'][:] = self.full_desire.reshape((1,ModelConstants.INPUT_HISTORY_BUFFER_LEN,ModelConstants.TEMPORAL_SKIP,-1)).max(axis=2) self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention'] self.numpy_inputs['lateral_control_params'][:] = inputs['lateral_control_params'] imgs_cl = {'input_imgs': self.frames['input_imgs'].prepare(buf, transform.flatten()), 'big_input_imgs': self.frames['big_input_imgs'].prepare(wbuf, transform_wide.flatten())} - if TICI: + if TICI and not USBGPU: # The imgs tensors are backed by opencl memory, only need init once for key in imgs_cl: if key not in self.vision_inputs: @@ -128,15 +167,17 @@ class ModelState: self.vision_output = self.vision_run(**self.vision_inputs).numpy().flatten() vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(self.vision_output, self.vision_output_slices)) - self.numpy_inputs['features_buffer'][0,:-1] = self.numpy_inputs['features_buffer'][0,1:] - self.numpy_inputs['features_buffer'][0,-1] = vision_outputs_dict['hidden_state'][0, :] + self.full_features_buffer[0,:-1] = self.full_features_buffer[0,1:] + self.full_features_buffer[0,-1] = vision_outputs_dict['hidden_state'][0, :] + self.numpy_inputs['features_buffer'][:] = self.full_features_buffer[0, self.temporal_idxs] self.policy_output = self.policy_run(**self.policy_inputs).numpy().flatten() policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices)) # TODO model only uses last value now - self.numpy_inputs['prev_desired_curv'][0,:-1] = self.numpy_inputs['prev_desired_curv'][0,1:] - self.numpy_inputs['prev_desired_curv'][0,-1,:] = policy_outputs_dict['desired_curvature'][0, :] + self.full_prev_desired_curv[0,:-1] = self.full_prev_desired_curv[0,1:] + self.full_prev_desired_curv[0,-1,:] = policy_outputs_dict['desired_curvature'][0, :] + self.numpy_inputs['prev_desired_curv'][:] = self.full_prev_desired_curv[0, self.temporal_idxs] combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict} if SEND_RAW_PRED: @@ -151,13 +192,17 @@ def main(demo=False): sentry.set_tag("daemon", PROCESS_NAME) cloudlog.bind(daemon=PROCESS_NAME) setproctitle(PROCESS_NAME) - config_realtime_process(7, 54) + if not USBGPU: + # USB GPU currently saturates a core so can't do this yet, + # also need to move the aux USB interrupts for good timings + config_realtime_process(7, 54) + st = time.monotonic() cloudlog.warning("setting up CL context") cl_context = CLContext() cloudlog.warning("CL context ready; loading model") model = ModelState(cl_context) - cloudlog.warning("models loaded, modeld starting") + cloudlog.warning(f"models loaded in {time.monotonic() - st:.1f}s, modeld starting") # visionipc clients while True: @@ -210,7 +255,10 @@ def main(demo=False): cloudlog.info("modeld got CarParams: %s", CP.brand) # TODO this needs more thought, use .2s extra for now to estimate other delays - steer_delay = CP.steerActuatorDelay + .2 + # TODO Move smooth seconds to action function + lat_delay = CP.steerActuatorDelay + .2 + LAT_SMOOTH_SECONDS + long_delay = CP.longitudinalActuatorDelay + LONG_SMOOTH_SECONDS + prev_action = log.ModelDataV2.Action() DH = DesireHelper() @@ -252,7 +300,7 @@ def main(demo=False): is_rhd = sm["driverMonitoringState"].isRHD frame_id = sm["roadCameraState"].frameId v_ego = max(sm["carState"].vEgo, 0.) - lateral_control_params = np.array([v_ego, steer_delay], dtype=np.float32) + lateral_control_params = np.array([v_ego, lat_delay], dtype=np.float32) if sm.updated["liveCalibration"] and sm.seen['roadCameraState'] and sm.seen['deviceState']: device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32) dc = DEVICE_CAMERAS[(str(sm['deviceState'].deviceType), str(sm['roadCameraState'].sensor))] @@ -295,7 +343,10 @@ def main(demo=False): modelv2_send = messaging.new_message('modelV2') drivingdata_send = messaging.new_message('drivingModelData') posenet_send = messaging.new_message('cameraOdometry') - fill_model_msg(drivingdata_send, modelv2_send, model_output, v_ego, steer_delay, + + action = get_action_from_model(model_output, prev_action, lat_delay + DT_MDL, long_delay + DT_MDL, v_ego) + prev_action = action + fill_model_msg(drivingdata_send, modelv2_send, model_output, action, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, frame_drop_ratio, meta_main.timestamp_eof, model_execution_time, live_calib_seen) diff --git a/selfdrive/modeld/models/big_driving_policy.onnx b/selfdrive/modeld/models/big_driving_policy.onnx new file mode 120000 index 0000000000..e1b653a14a --- /dev/null +++ b/selfdrive/modeld/models/big_driving_policy.onnx @@ -0,0 +1 @@ +driving_policy.onnx \ No newline at end of file diff --git a/selfdrive/modeld/models/big_driving_vision.onnx b/selfdrive/modeld/models/big_driving_vision.onnx new file mode 120000 index 0000000000..28ee71dd74 --- /dev/null +++ b/selfdrive/modeld/models/big_driving_vision.onnx @@ -0,0 +1 @@ +driving_vision.onnx \ No newline at end of file diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index 9973d18588..d3341e76ec 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -5,11 +5,12 @@ #include "common/clutil.h" -DrivingModelFrame::DrivingModelFrame(cl_device_id device_id, cl_context context) : ModelFrame(device_id, context) { +DrivingModelFrame::DrivingModelFrame(cl_device_id device_id, cl_context context, int _temporal_skip) : ModelFrame(device_id, context) { input_frames = std::make_unique(buf_size); + temporal_skip = _temporal_skip; input_frames_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, buf_size, NULL, &err)); - img_buffer_20hz_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, 2*frame_size_bytes, NULL, &err)); - region.origin = 1 * frame_size_bytes; + img_buffer_20hz_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (temporal_skip+1)*frame_size_bytes, NULL, &err)); + region.origin = temporal_skip * frame_size_bytes; region.size = frame_size_bytes; last_img_cl = CL_CHECK_ERR(clCreateSubBuffer(img_buffer_20hz_cl, CL_MEM_READ_WRITE, CL_BUFFER_CREATE_TYPE_REGION, ®ion, &err)); @@ -20,7 +21,7 @@ DrivingModelFrame::DrivingModelFrame(cl_device_id device_id, cl_context context) cl_mem* DrivingModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection) { run_transform(yuv_cl, MODEL_WIDTH, MODEL_HEIGHT, frame_width, frame_height, frame_stride, frame_uv_offset, projection); - for (int i = 0; i < 1; i++) { + for (int i = 0; i < temporal_skip; i++) { CL_CHECK(clEnqueueCopyBuffer(q, img_buffer_20hz_cl, img_buffer_20hz_cl, (i+1)*frame_size_bytes, i*frame_size_bytes, frame_size_bytes, 0, nullptr, nullptr)); } loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, last_img_cl); @@ -36,6 +37,7 @@ cl_mem* DrivingModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_hei DrivingModelFrame::~DrivingModelFrame() { deinit_transform(); loadyuv_destroy(&loadyuv); + CL_CHECK(clReleaseMemObject(input_frames_cl)); CL_CHECK(clReleaseMemObject(img_buffer_20hz_cl)); CL_CHECK(clReleaseMemObject(last_img_cl)); CL_CHECK(clReleaseCommandQueue(q)); @@ -57,5 +59,6 @@ cl_mem* MonitoringModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_ MonitoringModelFrame::~MonitoringModelFrame() { deinit_transform(); + CL_CHECK(clReleaseMemObject(input_frame_cl)); CL_CHECK(clReleaseCommandQueue(q)); } diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 14409943e4..176d7eb6dc 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -64,20 +64,21 @@ protected: class DrivingModelFrame : public ModelFrame { public: - DrivingModelFrame(cl_device_id device_id, cl_context context); + DrivingModelFrame(cl_device_id device_id, cl_context context, int _temporal_skip); ~DrivingModelFrame(); cl_mem* prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection); 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; + const int buf_size = MODEL_FRAME_SIZE * 2; // 2 frames are temporal_skip frames apart const size_t frame_size_bytes = MODEL_FRAME_SIZE * sizeof(uint8_t); private: LoadYUVState loadyuv; cl_mem img_buffer_20hz_cl, last_img_cl, input_frames_cl; cl_buffer_region region; + int temporal_skip; }; class MonitoringModelFrame : public ModelFrame { diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd index b4f08b12aa..4ac64d9172 100644 --- a/selfdrive/modeld/models/commonmodel.pxd +++ b/selfdrive/modeld/models/commonmodel.pxd @@ -20,7 +20,7 @@ cdef extern from "selfdrive/modeld/models/commonmodel.h": cppclass DrivingModelFrame: int buf_size - DrivingModelFrame(cl_device_id, cl_context) + DrivingModelFrame(cl_device_id, cl_context, int) cppclass MonitoringModelFrame: int buf_size diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx index 7b3a5bb342..5b7d11bc71 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pyx +++ b/selfdrive/modeld/models/commonmodel_pyx.pyx @@ -59,8 +59,8 @@ cdef class ModelFrame: cdef class DrivingModelFrame(ModelFrame): cdef cppDrivingModelFrame * _frame - def __cinit__(self, CLContext context): - self._frame = new cppDrivingModelFrame(context.device_id, context.context) + def __cinit__(self, CLContext context, int temporal_skip): + self._frame = new cppDrivingModelFrame(context.device_id, context.context, temporal_skip) self.frame = (self._frame) self.buf_size = self._frame.buf_size diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx index ad84edd639..122a041524 100644 Binary files a/selfdrive/modeld/models/driving_policy.onnx and b/selfdrive/modeld/models/driving_policy.onnx differ diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index bb7f9b7bab..e432570d73 100644 Binary files a/selfdrive/modeld/models/driving_vision.onnx and b/selfdrive/modeld/models/driving_vision.onnx differ diff --git a/selfdrive/pandad/panda.cc b/selfdrive/pandad/panda.cc index 7b5fc9a999..93e139f0ec 100644 --- a/selfdrive/pandad/panda.cc +++ b/selfdrive/pandad/panda.cc @@ -66,6 +66,25 @@ void Panda::set_alternative_experience(uint16_t alternative_experience) { handle->control_write(0xdf, alternative_experience, 0); } +std::string Panda::serial_read(int port_number) { + std::string ret; + char buffer[USBPACKET_MAX_SIZE] = {}; + + while (true) { + int bytes_read = handle->control_read(0xe0, port_number, 0, (unsigned char *)buffer, USBPACKET_MAX_SIZE); + if (bytes_read <= 0) { + break; + } + ret.append(buffer, bytes_read); + } + + return ret; +} + +void Panda::set_uart_baud(int uart, int rate) { + handle->control_write(0xe4, uart, int(rate / 300)); +} + cereal::PandaState::PandaType Panda::get_hw_type() { unsigned char hw_query[1] = {0}; diff --git a/selfdrive/pandad/panda.h b/selfdrive/pandad/panda.h index 6ae2c77755..5cbce44f28 100644 --- a/selfdrive/pandad/panda.h +++ b/selfdrive/pandad/panda.h @@ -64,6 +64,8 @@ public: 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); + std::string serial_read(int port_number = 0); + void set_uart_baud(int uart, int rate); void set_fan_speed(uint16_t fan_speed); uint16_t get_fan_speed(); void set_ir_pwr(uint16_t ir_pwr); diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc index e6ef4a4072..1666c6229f 100644 --- a/selfdrive/pandad/pandad.cc +++ b/selfdrive/pandad/pandad.cc @@ -25,7 +25,7 @@ // - If a panda connection is dropped, pandad 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 +// - Each panda will have its 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 @@ -452,6 +452,19 @@ void pandad_run(std::vector &pandas) { send_peripheral_state(peripheral_panda, &pm); } + // Forward logs from pandas to cloudlog if available + for (auto *panda : pandas) { + std::string log = panda->serial_read(); + if (!log.empty()) { + if (log.find("Register 0x") != std::string::npos) { + // Log register divergent faults as errors + LOGE("%s", log.c_str()); + } else { + LOGD("%s", log.c_str()); + } + } + } + rk.keepTime(); } diff --git a/selfdrive/pandad/pandad.py b/selfdrive/pandad/pandad.py index fd6668feba..b33ffb6473 100755 --- a/selfdrive/pandad/pandad.py +++ b/selfdrive/pandad/pandad.py @@ -87,7 +87,7 @@ def main() -> None: # TODO: remove this in the next AGNOS # wait until USB is up before counting - if time.monotonic() < 25.: + if time.monotonic() < 35.: no_internal_panda_count = 0 # Handle missing internal panda diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index ee2c418b6e..6293deb2af 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -670,6 +670,11 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { visual_alert=VisualAlert.brakePressed), }, + EventName.steerDisengage: { + ET.USER_DISABLE: EngagementAlert(AudibleAlert.disengage), + ET.NO_ENTRY: NoEntryAlert("Steering Pressed"), + }, + EventName.preEnableStandstill: { ET.PRE_ENABLE: Alert( "Release Brake to Engage", @@ -889,7 +894,7 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { # causing the connection to the panda to be lost EventName.usbError: { ET.SOFT_DISABLE: soft_disable_alert("USB Error: Reboot Your Device"), - ET.PERMANENT: NormalPermanentAlert("USB Error: Reboot Your Device", ""), + ET.PERMANENT: NormalPermanentAlert("USB Error: Reboot Your Device"), ET.NO_ENTRY: NoEntryAlert("USB Error: Reboot Your Device"), }, @@ -977,6 +982,9 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.WARNING: personality_changed_alert, }, + EventName.userFlag: { + ET.PERMANENT: NormalPermanentAlert("Bookmark Saved", duration=1.5), + }, } diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index fdf1b77871..98c03acf1e 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -7,7 +7,6 @@ import cereal.messaging as messaging from cereal import car, log from msgq.visionipc import VisionIpcClient, VisionStreamType -from opendbc.safety import ALTERNATIVE_EXPERIENCE from openpilot.common.params import Params @@ -19,14 +18,13 @@ from openpilot.selfdrive.car.car_specific import CarSpecificEvents from openpilot.selfdrive.selfdrived.events import Events, ET from openpilot.selfdrive.selfdrived.state import StateMachine from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert -from openpilot.selfdrive.controls.lib.latcontrol import MIN_LATERAL_CONTROL_SPEED +from openpilot.system.hardware import HARDWARE from openpilot.system.version import get_build_metadata REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ TESTING_CLOSET = "TESTING_CLOSET" in os.environ -IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} LONGITUDINAL_PERSONALITY_MAP = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()} ThermalStatus = log.DeviceState.ThermalStatus @@ -56,7 +54,6 @@ class SelfdriveD: self.CP = CP self.car_events = CarSpecificEvents(self.CP) - self.disengage_on_accelerator = not (self.CP.alternativeExperience & ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS) # Setup sockets self.pm = messaging.PubMaster(['selfdriveState', 'onroadEvents']) @@ -76,9 +73,9 @@ class SelfdriveD: # no vipc in replay will make them ignored anyways ignore += ['roadCameraState', 'wideRoadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', - 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', + 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'liveDelay', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'controlsState', 'carControl', 'driverAssistance', 'alertDebug'] + \ + 'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userFlag'] + \ self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore, ignore_valid=ignore, frequency=int(1/DT_CTRL)) @@ -86,12 +83,13 @@ class SelfdriveD: # read params self.is_metric = self.params.get_bool("IsMetric") self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") + self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") car_recognized = self.CP.brand != 'mock' # cleanup old params - if not self.CP.experimentalLongitudinalAvailable: - self.params.remove("ExperimentalLongitudinalEnabled") + if not self.CP.alphaLongitudinalAvailable: + self.params.remove("AlphaLongitudinalEnabled") if not self.CP.openpilotLongitudinalControl: self.params.remove("ExperimentalMode") @@ -116,6 +114,12 @@ class SelfdriveD: self.state_machine = StateMachine() self.rk = Ratekeeper(100, print_delay_threshold=None) + # some comma three with NVMe experience NVMe dropouts mid-drive that + # cause loggerd to crash on write, so ignore it only on that platform + self.ignored_processes = set() + if HARDWARE.get_device_type() == 'tici' and os.path.exists('/dev/nvme0'): + self.ignored_processes = {'loggerd', } + # Determine startup event self.startup_event = EventName.startup if build_metadata.openpilot.comma_remote and build_metadata.tested_channel else EventName.startupMaster if not car_recognized: @@ -154,7 +158,11 @@ class SelfdriveD: self.events.add(EventName.selfdriveInitializing) return - # no more events while in dashcam mode + # Check for user flag (bookmark) press + if self.sm.updated['userFlag']: + self.events.add(EventName.userFlag) + + # Don't add any more events while in dashcam mode if self.CP.passive: return @@ -259,7 +267,7 @@ class SelfdriveD: if not_running != self.not_running_prev: cloudlog.event("process_not_running", not_running=not_running, error=True) self.not_running_prev = not_running - if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): + if self.sm.recv_frame['managerState'] and (not_running - self.ignored_processes): self.events.add(EventName.processNotRunning) else: if not SIMULATION and not self.rk.lagging: @@ -270,11 +278,12 @@ class SelfdriveD: if not REPLAY and self.rk.lagging: self.events.add(EventName.selfdrivedLagging) if not self.sm.valid['radarState']: - if self.sm['radarState'].radarErrors.radarUnavailableTemporary: + if self.sm['radarState'].radarErrors.canError: + self.events.add(EventName.canError) + elif self.sm['radarState'].radarErrors.radarUnavailableTemporary: self.events.add(EventName.radarTempUnavailable) else: self.events.add(EventName.radarFault) - self.events.add(EventName.radarFault) if not self.sm.valid['pandaStates']: self.events.add(EventName.usbError) if CS.canTimeout: @@ -330,7 +339,7 @@ class SelfdriveD: controlstate = self.sm['controlsState'] lac = getattr(controlstate.lateralControlState, controlstate.lateralControlState.which()) if lac.active and not recent_steer_pressed and not self.CP.notCar: - clipped_speed = max(CS.vEgo, MIN_LATERAL_CONTROL_SPEED) + clipped_speed = max(CS.vEgo, 0.3) actual_lateral_accel = controlstate.curvature * (clipped_speed**2) desired_lateral_accel = self.sm['modelV2'].action.desiredCurvature * (clipped_speed**2) undershooting = abs(desired_lateral_accel) / abs(1e-3 + actual_lateral_accel) > 1.2 @@ -359,7 +368,7 @@ class SelfdriveD: if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) - # decrement personality on distance button press + # Decrement personality on distance button press if self.CP.openpilotLongitudinalControl: if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): self.personality = (self.personality - 1) % 3 @@ -476,6 +485,7 @@ class SelfdriveD: def params_thread(self, evt): while not evt.is_set(): self.is_metric = self.params.get_bool("IsMetric") + self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl self.personality = self.read_personality_param() time.sleep(0.1) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 989b84dee3..b8c6adb436 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -107,6 +107,7 @@ class Plant: 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 + model.modelV2.action.desiredAcceleration = float(self.acceleration + 0.1) velocity = log.XYZTData.new_message() velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)] velocity.x[0] = float(self.speed) # always start at current speed diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index 381e4dcb7f..dc801e4285 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -38,7 +38,7 @@ optional arguments: ## Forks -openpilot forks can use this test with their own reference logs, by default `test_proccess.py` saves logs locally. +openpilot forks can use this test with their own reference logs, by default `test_proccesses.py` saves logs locally. To generate new logs: @@ -48,13 +48,13 @@ Then, check in the new logs using git-lfs. Make sure to also update the `ref_com ## API -Process replay test suite exposes programmatic APIs for simultaneously running processes or groups of processes on provided logs. +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, + 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]: ``` @@ -73,14 +73,14 @@ output_logs = replay_process_with_name('locationd', lr) output_logs = replay_process_with_name(['ubloxd', 'locationd'], lr) ``` -Supported processes: +Supported processes: * controlsd * radard * plannerd * calibrationd * dmonitoringd * locationd -* paramsd +* paramsd * ubloxd * torqued * modeld diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index fd13c4f239..33b363cfd9 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -9,10 +9,11 @@ from opendbc.car.fingerprints import MIGRATION from opendbc.car.toyota.values import EPS_SCALE, ToyotaSafetyFlags from opendbc.car.ford.values import CAR as FORD, FordFlags, FordSafetyFlags from opendbc.car.hyundai.values import HyundaiSafetyFlags +from opendbc.car.gm.values import GMSafetyFlags from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index -from openpilot.selfdrive.controls.lib.longitudinal_planner import get_accel_from_plan +from openpilot.selfdrive.controls.lib.longitudinal_planner import get_accel_from_plan, CONTROL_N_T_IDX from openpilot.system.manager.process_config import managed_processes from openpilot.tools.lib.logreader import LogIterable @@ -21,12 +22,12 @@ MigrationOps = tuple[list[tuple[int, capnp.lib.capnp._DynamicStructReader]], lis MigrationFunc = Callable[[list[MessageWithIndex]], MigrationOps] -## rules for migration functions -## 1. must use the decorator @migration(inputs=[...], product="...") and MigrationFunc signature -## 2. it only gets the messages that are in the inputs list -## 3. product is the message type created by the migration function, and the function will be skipped if product type already exists in lr -## 4. it must return a list of operations to be applied to the logreader (replace, add, delete) -## 5. all migration functions must be independent of each other +# rules for migration functions +# 1. must use the decorator @migration(inputs=[...], product="...") and MigrationFunc signature +# 2. it only gets the messages that are in the inputs list +# 3. product is the message type created by the migration function, and the function will be skipped if product type already exists in lr +# 4. it must return a list of operations to be applied to the logreader (replace, add, delete) +# 5. all migration functions must be independent of each other def migrate_all(lr: LogIterable, manager_states: bool = False, panda_states: bool = False, camera_states: bool = False): migrations = [ migrate_sensorEvents, @@ -108,7 +109,7 @@ def migrate_longitudinalPlan(msgs): if msg.which() != 'longitudinalPlan': continue new_msg = msg.as_builder() - a_target, should_stop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels) + a_target, should_stop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels, CONTROL_N_T_IDX) new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = float(a_target), bool(should_stop) ops.append((index, new_msg.as_reader())) return ops, [], [] @@ -274,9 +275,11 @@ def migrate_pandaStates(msgs): "TOYOTA_PRIUS": EPS_SCALE["TOYOTA_PRIUS"] | ToyotaSafetyFlags.STOCK_LONGITUDINAL, "TOYOTA_RAV4": EPS_SCALE["TOYOTA_RAV4"] | ToyotaSafetyFlags.ALT_BRAKE, "KIA_EV6": HyundaiSafetyFlags.EV_GAS | HyundaiSafetyFlags.CANFD_LKA_STEERING, + "CHEVROLET_VOLT": GMSafetyFlags.EV, + "CHEVROLET_BOLT_EUV": GMSafetyFlags.EV | GMSafetyFlags.HW_CAM, } # TODO: get new Ford route - safety_param_migration |= {car: FordSafetyFlags.LONG_CONTROL for car in (set(FORD) - FORD.with_flags(FordFlags.CANFD))} + safety_param_migration |= dict.fromkeys((set(FORD) - FORD.with_flags(FordFlags.CANFD)), FordSafetyFlags.LONG_CONTROL) # Migrate safety param base on carParams CP = next((m.carParams for _, m in msgs if m.which() == 'carParams'), None) @@ -303,6 +306,8 @@ def migrate_pandaStates(msgs): elif msg.which() == 'pandaStates': new_msg = msg.as_builder() new_msg.pandaStates[-1].safetyParam = safety_param + # Clear DISABLE_DISENGAGE_ON_GAS bit to fix controls mismatch + new_msg.pandaStates[-1].alternativeExperience &= ~1 ops.append((index, new_msg.as_reader())) return ops, [], [] diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 36398af8ca..0578a61588 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -64,6 +64,7 @@ def generate_report(proposed, master, tmp, commit): ModelV2_Plots = zl([ (lambda x: get_idx_if_non_empty(x.velocity.x, 0), "velocity.x"), (lambda x: get_idx_if_non_empty(x.action.desiredCurvature), "desiredCurvature"), + (lambda x: get_idx_if_non_empty(x.action.desiredAcceleration), "desiredAcceleration"), (lambda x: get_idx_if_non_empty(x.leadsV3[0].x, 0), "leadsV3.x"), (lambda x: get_idx_if_non_empty(x.laneLines[1].y, 0), "laneLines.y"), (lambda x: get_idx_if_non_empty(x.meta.desireState, 3), "desireState.laneChangeLeft"), @@ -122,7 +123,7 @@ def comment_replay_report(proposed, master, full_logs): diff_plots = create_table("Model Replay Differences", diff_files, link, open_table=True) all_plots = create_table("All Model Replay Plots", files, link) comment = f"ref for commit {commit}: {link}/{log_name}" + diff_plots + all_plots - GITHUB.comment_on_pr(comment, PR_BRANCH) + GITHUB.comment_on_pr(comment, PR_BRANCH, "commaci-public", True) def trim_logs_to_max_frames(logs, max_frames, frs_types, include_all_types): all_msgs = [] diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 16761225d3..d87a330fdd 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -2,7 +2,6 @@ import os import time import copy -import json import heapq import signal from collections import Counter, OrderedDict @@ -18,7 +17,6 @@ from cereal import car from cereal.services import SERVICE_LIST from msgq.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name from opendbc.car.car_helpers import get_car, interfaces -from opendbc.safety import ALTERNATIVE_EXPERIENCE from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout @@ -364,10 +362,7 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): with car.CarParams.from_bytes(cached_params_raw) as _cached_params: cached_params = _cached_params - CP = get_car(*can_callbacks, lambda obd: None, Params().get_bool("ExperimentalLongitudinalEnabled"), cached_params=cached_params).CP - - if not params.get_bool("DisengageOnAccelerator"): - CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS + CP = get_car(*can_callbacks, lambda obd: None, Params().get_bool("AlphaLongitudinalEnabled"), cached_params=cached_params).CP params.put("CarParams", CP.to_bytes()) @@ -463,7 +458,7 @@ CONFIGS = [ proc_name="selfdrived", pubs=[ "carState", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", - "longitudinalPlan", "livePose", "liveParameters", "radarState", + "longitudinalPlan", "livePose", "liveDelay", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", "alertDebug", @@ -517,9 +512,10 @@ CONFIGS = [ ), ProcessConfig( proc_name="calibrationd", - pubs=["carState", "cameraOdometry", "carParams"], + pubs=["carState", "cameraOdometry"], subs=["liveCalibration"], ignore=["logMonoTime"], + init_callback=get_car_params_callback, should_recv_callback=calibration_rcv_callback, ), ProcessConfig( @@ -551,6 +547,15 @@ CONFIGS = [ tolerance=NUMPY_TOLERANCE, processing_time=0.004, ), + ProcessConfig( + proc_name="lagd", + pubs=["livePose", "liveCalibration", "carState", "carControl", "controlsState"], + subs=["liveDelay"], + ignore=["logMonoTime"], + init_callback=get_car_params_callback, + should_recv_callback=MessageBasedRcvCallback("livePose"), + tolerance=NUMPY_TOLERANCE, + ), ProcessConfig( proc_name="ubloxd", pubs=["ubloxRaw"], @@ -628,9 +633,7 @@ def get_custom_params_from_lr(lr: LogIterable, initial_state: str = "first") -> 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) + custom_params["LiveParameters"] = live_parameters[msg_index].as_builder().to_bytes() if len(live_torque_parameters) > 0: custom_params["LiveTorqueParameters"] = live_torque_parameters[msg_index].as_builder().to_bytes() @@ -762,15 +765,12 @@ def generate_params_config(lr=None, CP=None, fingerprint=None, custom_params=Non 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 + params_dict["AlphaLongitudinalEnabled"] = True if CP.notCar: params_dict["JoystickDebugMode"] = True diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 353b8fa7ce..0ca95ec5fa 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e9d57157494480637a8ffb52257d2b660a48be67 \ No newline at end of file +280cd05fe44e47474d04f2cf7435fb0000a562e5 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 927f54c0c3..a82eab27dd 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -22,47 +22,48 @@ source_segments = [ ("HYUNDAI2", "d545129f3ca90f28|2022-11-07--20-43-08--3"), # HYUNDAI.HYUNDAI_KIA_EV6 (+ QCOM GPS) ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.TOYOTA_PRIUS ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.TOYOTA_RAV4 - ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.TOYOTA_COROLLA_TSS2 + ("TOYOTA3", "8011d605be1cbb77|000000cc--8e8d8ec716--6"), # TOYOTA.TOYOTA_COROLLA_TSS2 ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.HONDA_CIVIC (NIDEC) ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.HONDA_ACCORD (BOSCH) ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID ("RAM", "17fc16d840fe9d21|2023-04-26--13-28-44--5"), # CHRYSLER.RAM_1500_5TH_GEN ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.SUBARU_OUTBACK - ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.CHEVROLET_VOLT - ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.CHEVROLET_BOLT_EUV + ("GM", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.CHEVROLET_BOLT_EUV ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.NISSAN_XTRAIL ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.VOLKSWAGEN_GOLF + # FIXME the sensor timings are bad in mazda segment, we're not fully testing it, but it should be replaced ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.MAZDA_CX9_2021 ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.FORD_BRONCO_SPORT_MK1 ("RIVIAN", "bc095dc92e101734|000000db--ee9fe46e57--1"), # RIVIAN.RIVIAN_R1_GEN1 + ("TESLA", "2c912ca5de3b1ee9|0000025d--6eb6bcbca4--4"), # TESLA.TESLA_MODEL_Y # Enable when port is tested and dashcamOnly is no longer set #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.VOLKSWAGEN_PASSAT_NMS ] segments = [ - ("BODY", "regenA67A128BCD8|2024-08-30--02-36-22--0"), - ("HYUNDAI", "regenCCD47FEBC0C|2025-03-04--03-21-48--0"), - ("HYUNDAI2", "regen306779F6870|2024-10-03--04-03-23--0"), - ("TOYOTA", "regen4A5115B248D|2025-03-04--03-21-43--0"), - ("TOYOTA2", "regen6E484EDAB96|2024-08-30--02-47-37--0"), - ("TOYOTA3", "regen4CE950B0267|2024-08-30--02-51-30--0"), - ("HONDA", "regenB8CABEC09CC|2025-03-04--03-32-55--0"), - ("HONDA2", "regen4B38A7428CD|2024-08-30--02-56-31--0"), - ("CHRYSLER", "regenF3DBBA9E8DF|2024-08-30--02-59-03--0"), - ("RAM", "regenDB02684E00A|2024-08-30--03-02-54--0"), - ("SUBARU", "regen5E3347D0A0F|2025-03-04--03-23-55--0"), - ("GM", "regen720F2BA4CF6|2024-08-30--03-09-15--0"), - ("GM2", "regen9ADBECBCD1C|2024-08-30--03-13-04--0"), - ("NISSAN", "regen58464878D07|2024-08-30--03-15-31--0"), - ("VOLKSWAGEN", "regenED976DEB757|2024-08-30--03-18-02--0"), + ("BODY", "regen2F3C7259F1B|2025-04-08--23-00-23--0"), + ("HYUNDAI", "regenAA0FC4ED71E|2025-04-08--22-57-50--0"), + ("HYUNDAI2", "regenAFB9780D823|2025-04-08--23-00-34--0"), + ("TOYOTA", "regen218A4DCFAA1|2025-04-08--22-57-51--0"), + ("TOYOTA2", "regen107352E20EB|2025-04-08--22-57-46--0"), + ("TOYOTA3", "regen1455E3B4BDF|2025-04-09--03-26-06--0"), + ("HONDA", "regenB328FF8BA0A|2025-04-08--22-57-45--0"), + ("HONDA2", "regen6170C8C9A35|2025-04-08--22-57-46--0"), + ("CHRYSLER", "regen5B28FC2A437|2025-04-08--23-04-24--0"), + ("RAM", "regenBF81EA96E08|2025-04-08--23-06-54--0"), + ("SUBARU", "regen7366F13F6A1|2025-04-08--23-07-07--0"), + ("GM", "regen1271097D038|2025-04-09--03-26-00--0"), + ("NISSAN", "regen15D60604EAB|2025-04-08--23-06-59--0"), + ("VOLKSWAGEN", "regen0F2F06C9539|2025-04-08--23-06-56--0"), ("MAZDA", "regenACF84CCF482|2024-08-30--03-21-55--0"), - ("FORD", "regenA75209BD115|2025-03-04--03-23-53--0"), - ("RIVIAN", "bc095dc92e101734|000000db--ee9fe46e57--1"), + ("FORD", "regen755D8CB1E1F|2025-04-08--23-13-43--0"), + ("RIVIAN", "regen5FCAC896BBE|2025-04-08--23-13-35--0"), + ("TESLA", "2c912ca5de3b1ee9|0000025d--6eb6bcbca4--4"), ] # dashcamOnly makes don't need to be tested until a full port is done -excluded_interfaces = ["mock", "tesla", "rivian"] +excluded_interfaces = ["mock", "tesla"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") @@ -196,7 +197,7 @@ if __name__ == "__main__": continue # to speed things up, we only test all segments on card - if cfg.proc_name != 'card' and car_brand not in ('HYUNDAI', 'TOYOTA', 'HONDA', 'SUBARU', 'FORD'): + if cfg.proc_name != 'card' and car_brand not in ('HYUNDAI', 'TOYOTA', 'HONDA', 'SUBARU', 'FORD', 'RIVIAN', 'TESLA'): continue cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{cur_commit}.zst") diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 69555b19f7..d717698514 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -18,6 +18,9 @@ if [ -z "$TEST_DIR" ]; then exit 1 fi +# prevent storage from filling up +rm -rf /data/media/0/realdata/* + rm -rf /data/safe_staging/ || true if [ -d /data/safe_staging/ ]; then sudo umount /data/safe_staging/merged/ || true diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 1ea59c4856..d0c725cacb 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -44,7 +44,6 @@ PROCS = { "./camerad": 10.0, "selfdrive.controls.plannerd": 9.0, "./ui": 18.0, - "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, "selfdrive.controls.radard": 2.0, "selfdrive.modeld.modeld": 22.0, @@ -53,6 +52,8 @@ PROCS = { "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, "selfdrive.locationd.locationd": 25.0, + "selfdrive.locationd.paramsd": 9.0, + "selfdrive.locationd.lagd": 11.0, "selfdrive.ui.soundd": 3.0, "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 2.0, @@ -95,6 +96,7 @@ TIMINGS = { "modelV2": [2.5, 0.35], "driverStateV2": [2.5, 0.40], "livePose": [2.5, 0.35], + "liveParameters": [2.5, 0.35], "wideRoadCameraState": [1.5, 0.35], } @@ -187,7 +189,7 @@ class TestOnroad: def test_manager_starting_time(self): st = self.ts['managerState']['t'][0] - assert (st - self.manager_st) < 10, f"manager.py took {st - self.manager_st}s to publish the first 'managerState' msg" + assert (st - self.manager_st) < 12.5, f"manager.py took {st - self.manager_st}s to publish the first 'managerState' msg" def test_cloudlog_size(self): msgs = self.msgs['logMessage'] @@ -391,8 +393,12 @@ class TestOnroad: result += "----------------- Model Timing -----------------\n" result += "------------------------------------------------\n" cfgs = [ - ("modelV2", 0.045, 0.040), # TODO: this should be stricter but it's hard to measure exactly - ("driverStateV2", 0.045, 0.035), + # since multiple processes use the GPU and can preempt each other, + # these numbers are not fully self-contained. + ("modelV2", 0.06, 0.040), + + # can miss cycles here and there, just important the avg frequency is 20Hz + ("driverStateV2", 0.3, 0.05), ] for (s, instant_max, avg_max) in cfgs: ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s]] diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index f9724816da..7e9eaf932f 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -3,9 +3,6 @@ moc_* translations/main_test_en.* -_text -_spinner - ui mui watch3 diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 8fa4b55ea7..e63359da05 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -66,10 +66,6 @@ if GetOption('extras'): 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) - # 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], diff --git a/selfdrive/ui/qt/network/networking.cc b/selfdrive/ui/qt/network/networking.cc index 066dc3ca7e..bb914b6449 100644 --- a/selfdrive/ui/qt/network/networking.cc +++ b/selfdrive/ui/qt/network/networking.cc @@ -173,14 +173,36 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid }); list->addItem(editApnButton); - // Metered toggle + // Cellular metered toggle (prime lite or none) 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) { + cellularMeteredToggle = new ToggleControl(tr("Cellular Metered"), tr("Prevent large data uploads when on a metered cellular connection"), "", metered); + QObject::connect(cellularMeteredToggle, &SshToggle::toggleFlipped, [=](bool state) { params.putBool("GsmMetered", state); wifi->updateGsmSettings(params.getBool("GsmRoaming"), QString::fromStdString(params.get("GsmApn")), state); }); - list->addItem(meteredToggle); + list->addItem(cellularMeteredToggle); + + // Wi-Fi metered toggle + std::vector metered_button_texts{tr("default"), tr("metered"), tr("unmetered")}; + wifiMeteredToggle = new MultiButtonControl(tr("Wi-Fi Network Metered"), tr("Prevent large data uploads when on a metered Wi-FI connection"), "", metered_button_texts); + QObject::connect(wifiMeteredToggle, &MultiButtonControl::buttonClicked, [=](int id) { + wifiMeteredToggle->setEnabled(false); + MeteredType metered = MeteredType::UNKNOWN; + if (id == NM_METERED_YES) { + metered = MeteredType::YES; + } else if (id == NM_METERED_NO) { + metered = MeteredType::NO; + } + auto pending_call = wifi->setCurrentNetworkMetered(metered); + if (pending_call) { + QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(*pending_call); + QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, [=]() { + refresh(); + watcher->deleteLater(); + }); + } + }); + list->addItem(wifiMeteredToggle); // Hidden Network hiddenNetworkButton = new ButtonControl(tr("Hidden Network"), tr("CONNECT")); @@ -211,18 +233,32 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid void AdvancedNetworking::setGsmVisible(bool visible) { roamingToggle->setVisible(visible); editApnButton->setVisible(visible); - meteredToggle->setVisible(visible); + cellularMeteredToggle->setVisible(visible); } void AdvancedNetworking::refresh() { ipLabel->setText(wifi->ipv4_address); tetheringToggle->setEnabled(true); + + if (wifi->isTetheringEnabled() || wifi->ipv4_address == "") { + wifiMeteredToggle->setEnabled(false); + wifiMeteredToggle->setCheckedButton(0); + } else if (wifi->ipv4_address != "") { + MeteredType metered = wifi->currentNetworkMetered(); + wifiMeteredToggle->setEnabled(true); + wifiMeteredToggle->setCheckedButton(static_cast(metered)); + } + update(); } void AdvancedNetworking::toggleTethering(bool enabled) { wifi->setTetheringEnabled(enabled); tetheringToggle->setEnabled(false); + if (enabled) { + wifiMeteredToggle->setEnabled(false); + wifiMeteredToggle->setCheckedButton(0); + } } // WifiUI functions @@ -234,12 +270,12 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) // load imgs for (const auto &s : {"low", "medium", "high", "full"}) { - QPixmap pix(ASSET_PATH + "/offroad/icon_wifi_strength_" + s + ".svg"); + QPixmap pix(ASSET_PATH + "/icons/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); + lock = QPixmap(ASSET_PATH + "icons/lock_closed.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); + checkmark = QPixmap(ASSET_PATH + "icons/checkmark.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); + circled_slash = QPixmap(ASSET_PATH + "icons/circled_slash.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); scanningLabel = new QLabel(tr("Scanning for networks...")); scanningLabel->setStyleSheet("font-size: 65px;"); diff --git a/selfdrive/ui/qt/network/networking.h b/selfdrive/ui/qt/network/networking.h index 4fd604039b..0bdf64e459 100644 --- a/selfdrive/ui/qt/network/networking.h +++ b/selfdrive/ui/qt/network/networking.h @@ -65,7 +65,8 @@ private: ToggleControl* roamingToggle; ButtonControl* editApnButton; ButtonControl* hiddenNetworkButton; - ToggleControl* meteredToggle; + ToggleControl* cellularMeteredToggle; + MultiButtonControl* wifiMeteredToggle; WifiManager* wifi = nullptr; Params params; diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc index 1717210634..d4ad8974b0 100644 --- a/selfdrive/ui/qt/network/wifi_manager.cc +++ b/selfdrive/ui/qt/network/wifi_manager.cc @@ -353,6 +353,7 @@ void WifiManager::activateModemConnection(const QDBusObjectPath &path) { } // function matches tici/hardware.py +// FIXME: it can mistakenly show CELL when connected to WIFI 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"); @@ -372,6 +373,44 @@ NetworkType WifiManager::currentNetworkType() { return NetworkType::NONE; } +MeteredType WifiManager::currentNetworkMetered() { + MeteredType metered = MeteredType::UNKNOWN; + for (const auto &active_conn : getActiveConnections()) { + QString type = call(active_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); + if (type == "802-11-wireless") { + QDBusObjectPath conn = call(active_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Connection"); + if (!conn.path().isEmpty()) { + Connection settings = getConnectionSettings(conn); + int metered_prop = settings.value("connection").value("metered").toInt(); + if (metered_prop == NM_METERED_YES) { + metered = MeteredType::YES; + } else if (metered_prop == NM_METERED_NO) { + metered = MeteredType::NO; + } + } + break; + } + } + return metered; +} + +std::optional WifiManager::setCurrentNetworkMetered(MeteredType metered) { + for (const auto &active_conn : getActiveConnections()) { + QString type = call(active_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); + if (type == "802-11-wireless") { + if (!isTetheringEnabled()) { + QDBusObjectPath conn = call(active_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Connection"); + if (!conn.path().isEmpty()) { + Connection settings = getConnectionSettings(conn); + settings["connection"]["metered"] = static_cast(metered); + return asyncCall(conn.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "Update", QVariant::fromValue(settings)); + } + } + } + } + return std::nullopt; +} + void WifiManager::updateGsmSettings(bool roaming, QString apn, bool metered) { if (!lteConnectionPath.path().isEmpty()) { bool changes = false; @@ -439,7 +478,7 @@ void WifiManager::addTetheringConnection() { address["prefix"] = 24u; connection["ipv4"]["address-data"] = QVariant::fromValue(IpConfig() << address); connection["ipv4"]["gateway"] = "192.168.43.1"; - connection["ipv4"]["route-metric"] = 1100; + connection["ipv4"]["never-default"] = true; connection["ipv6"]["method"] = "ignore"; asyncCall(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection)); diff --git a/selfdrive/ui/qt/network/wifi_manager.h b/selfdrive/ui/qt/network/wifi_manager.h index e5f79c5149..cab932a388 100644 --- a/selfdrive/ui/qt/network/wifi_manager.h +++ b/selfdrive/ui/qt/network/wifi_manager.h @@ -22,6 +22,11 @@ enum class NetworkType { CELL, ETHERNET }; +enum class MeteredType { + UNKNOWN, + YES, + NO +}; typedef QMap Connection; typedef QVector IpConfig; @@ -53,6 +58,8 @@ public: bool isKnownConnection(const QString &ssid); std::optional activateWifiConnection(const QString &ssid); NetworkType currentNetworkType(); + MeteredType currentNetworkMetered(); + std::optional setCurrentNetworkMetered(MeteredType metered); void updateGsmSettings(bool roaming, QString apn, bool metered); void connect(const Network &ssid, const bool is_hidden = false, const QString &password = {}, const QString &username = {}); diff --git a/selfdrive/ui/qt/offroad/developer_panel.cc b/selfdrive/ui/qt/offroad/developer_panel.cc index 365aec09c4..a095228da2 100644 --- a/selfdrive/ui/qt/offroad/developer_panel.cc +++ b/selfdrive/ui/qt/offroad/developer_panel.cc @@ -26,7 +26,7 @@ DeveloperPanel::DeveloperPanel(SettingsWindow *parent) : ListWidget(parent) { addItem(longManeuverToggle); experimentalLongitudinalToggle = new ParamControl( - "ExperimentalLongitudinalEnabled", + "AlphaLongitudinalEnabled", 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).")) @@ -68,8 +68,8 @@ void DeveloperPanel::updateToggles(bool _offroad) { 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"); + if (!CP.getAlphaLongitudinalAvailable() || is_release) { + params.remove("AlphaLongitudinalEnabled"); experimentalLongitudinalToggle->setEnabled(false); } @@ -78,7 +78,7 @@ void DeveloperPanel::updateToggles(bool _offroad) { * - is not a release branch, and * - the car supports experimental longitudinal control (alpha) */ - experimentalLongitudinalToggle->setVisible(CP.getExperimentalLongitudinalAvailable() && !is_release); + experimentalLongitudinalToggle->setVisible(CP.getAlphaLongitudinalAvailable() && !is_release); longManeuverToggle->setEnabled(hasLongitudinalControl(CP) && _offroad); } else { diff --git a/selfdrive/ui/qt/offroad/experimental_mode.cc b/selfdrive/ui/qt/offroad/experimental_mode.cc index b99220c1d1..e255073f39 100644 --- a/selfdrive/ui/qt/offroad/experimental_mode.cc +++ b/selfdrive/ui/qt/offroad/experimental_mode.cc @@ -9,8 +9,8 @@ #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); + chill_pixmap = QPixmap("../assets/icons/couch.svg").scaledToWidth(img_width, Qt::SmoothTransformation); + experimental_pixmap = QPixmap("../assets/icons/experimental_grey.svg").scaledToWidth(img_width, Qt::SmoothTransformation); // go to toggles and expand experimental mode description connect(this, &QPushButton::clicked, [=]() { emit openSettings(2, "ExperimentalMode"); }); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 4d0516bda1..ed06734f0f 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -23,43 +23,43 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "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/img_chffr_wheel.png", + "../assets/icons/chffr_wheel.png", }, { "ExperimentalMode", tr("Experimental Mode"), "", - "../assets/img_experimental_white.svg", + "../assets/icons/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", + "../assets/icons/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", + "../assets/icons/warning.png", }, { "AlwaysOnDM", tr("Always-On Driver Monitoring"), tr("Enable driver monitoring even when openpilot is not engaged."), - "../assets/offroad/icon_monitoring.png", + "../assets/icons/monitoring.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", + "../assets/icons/monitoring.png", }, { "IsMetric", tr("Use Metric System"), tr("Display speed in km/h instead of mph."), - "../assets/offroad/icon_metric.png", + "../assets/icons/metric.png", }, }; @@ -69,7 +69,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { 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. On supported cars, you can cycle through these personalities with " "your steering wheel distance button."), - "../assets/offroad/icon_speed_limit.png", + "../assets/icons/speed_limit.png", longi_button_texts); // set up uiState update for personality setting @@ -91,7 +91,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { } // Toggles with confirmation dialogs - toggles["ExperimentalMode"]->setActiveIcon("../assets/img_experimental.svg"); + toggles["ExperimentalMode"]->setActiveIcon("../assets/icons/experimental.svg"); toggles["ExperimentalMode"]->setConfirmation(true, true); } @@ -152,7 +152,7 @@ void TogglesPanel::updateToggles() { QString long_desc = unavailable + " " + \ tr("openpilot longitudinal control may come in a future update."); - if (CP.getExperimentalLongitudinalAvailable()) { + if (CP.getAlphaLongitudinalAvailable()) { 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 { @@ -194,6 +194,9 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), tr("Reset"), this)) { params.remove("CalibrationParams"); params.remove("LiveTorqueParameters"); + params.remove("LiveParameters"); + params.remove("LiveParametersV2"); + params.remove("LiveDelay"); } }); addItem(resetCalibBtn); @@ -326,7 +329,7 @@ void SettingsWindow::setCurrentPanel(int index, const QString ¶m) { if (param.endsWith("Panel")) { QString panelName = param; panelName.chop(5); // Remove "Panel" suffix - + // Find the panel by name for (int i = 0; i < nav_btns->buttons().size(); i++) { if (nav_btns->buttons()[i]->text() == tr(panelName.toStdString().c_str())) { @@ -338,7 +341,7 @@ void SettingsWindow::setCurrentPanel(int index, const QString ¶m) { emit expandToggleDescription(param); } } - + panel_widget->setCurrentIndex(index); nav_btns->buttons()[index]->setChecked(true); } diff --git a/selfdrive/ui/qt/onroad/buttons.cc b/selfdrive/ui/qt/onroad/buttons.cc index 2c2cc672b9..32e58c9dba 100644 --- a/selfdrive/ui/qt/onroad/buttons.cc +++ b/selfdrive/ui/qt/onroad/buttons.cc @@ -19,8 +19,8 @@ void drawIcon(QPainter &p, const QPoint ¢er, const QPixmap &img, const QBrus ExperimentalButton::ExperimentalButton(QWidget *parent) : experimental_mode(false), engageable(false), QPushButton(parent) { setFixedSize(btn_size, btn_size); - engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); - experimental_img = loadPixmap("../assets/img_experimental.svg", {img_size, img_size}); + engage_img = loadPixmap("../assets/icons/chffr_wheel.png", {img_size, img_size}); + experimental_img = loadPixmap("../assets/icons/experimental.svg", {img_size, img_size}); QObject::connect(this, &QPushButton::clicked, this, &ExperimentalButton::changeMode); } diff --git a/selfdrive/ui/qt/onroad/driver_monitoring.cc b/selfdrive/ui/qt/onroad/driver_monitoring.cc index afd003cf8f..49f2c950b4 100644 --- a/selfdrive/ui/qt/onroad/driver_monitoring.cc +++ b/selfdrive/ui/qt/onroad/driver_monitoring.cc @@ -21,7 +21,7 @@ static const QColor DMON_ENGAGED_COLOR = QColor::fromRgbF(0.1, 0.945, 0.26); static const QColor DMON_DISENGAGED_COLOR = QColor::fromRgbF(0.545, 0.545, 0.545); DriverMonitorRenderer::DriverMonitorRenderer() : face_kpts_draw(std::size(DEFAULT_FACE_KPTS_3D)) { - dm_img = loadPixmap("../assets/img_driver_face.png", {img_size + 5, img_size + 5}); + dm_img = loadPixmap("../assets/icons/driver_face.png", {img_size + 5, img_size + 5}); } void DriverMonitorRenderer::updateState(const UIState &s) { diff --git a/selfdrive/ui/qt/python_helpers.py b/selfdrive/ui/qt/python_helpers.py index 88c36290d9..1f6d43f309 100644 --- a/selfdrive/ui/qt/python_helpers.py +++ b/selfdrive/ui/qt/python_helpers.py @@ -1,11 +1,14 @@ import os +import platform from cffi import FFI import sip -from openpilot.common.ffi_wrapper import suffix from openpilot.common.basedir import BASEDIR +def suffix(): + return ".dylib" if platform.system() == "Darwin" else ".so" + def get_ffi(): lib = os.path.join(BASEDIR, "selfdrive", "ui", "qt", "libpython_helpers" + suffix()) diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index dfa9e12b4e..8a06c9fda0 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -98,7 +98,7 @@ QWidget * Setup::low_voltage() { main_layout->addLayout(inner_layout); QLabel *triangle = new QLabel(); - triangle->setPixmap(QPixmap(ASSET_PATH + "offroad/icon_warning.png")); + triangle->setPixmap(QPixmap(ASSET_PATH + "icons/warning.png")); inner_layout->addWidget(triangle, 0, Qt::AlignTop | Qt::AlignLeft); inner_layout->addSpacing(80); @@ -159,7 +159,7 @@ QWidget * Setup::getting_started() { vlayout->addStretch(); QPushButton *btn = new QPushButton(); - btn->setIcon(QIcon(":/img_continue_triangle.svg")); + btn->setIcon(QIcon(":/images/button_continue_triangle.svg")); btn->setIconSize(QSize(54, 106)); btn->setFixedSize(310, 1080); btn->setProperty("primary", true); @@ -251,7 +251,7 @@ QWidget * radio_button(QString title, QButtonGroup *group) { )"); // checkmark icon - QPixmap pix(":/img_circled_check.svg"); + QPixmap pix(":/icons/circled_check.svg"); btn->setIcon(pix); btn->setIconSize(QSize(0, 0)); btn->setLayoutDirection(Qt::RightToLeft); diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc deleted file mode 100644 index 2404efa668..0000000000 --- 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: white; - } - )"); - - 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 43d90a75b0..0000000000 --- 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/spinner_larch64 b/selfdrive/ui/qt/spinner_larch64 deleted file mode 100755 index 1b59cd532e..0000000000 Binary files a/selfdrive/ui/qt/spinner_larch64 and /dev/null differ diff --git a/selfdrive/ui/qt/text.cc b/selfdrive/ui/qt/text.cc deleted file mode 100644 index 21ec5eedcf..0000000000 --- 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/text_larch64 b/selfdrive/ui/qt/text_larch64 deleted file mode 100755 index 915e5f9014..0000000000 Binary files a/selfdrive/ui/qt/text_larch64 and /dev/null differ diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 399a1a98d7..ff381fe39c 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -193,8 +193,8 @@ QPixmap bootstrapPixmap(const QString &id) { 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") + return car_params.getAlphaLongitudinalAvailable() + ? Params().getBool("AlphaLongitudinalEnabled") : car_params.getOpenpilotLongitudinalControl(); } diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index aebf934f2a..3342de5324 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -183,10 +183,10 @@ private: bool store_confirm = false; }; -class ButtonParamControl : public AbstractControl { +class MultiButtonControl : public AbstractControl { Q_OBJECT public: - ButtonParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, + MultiButtonControl(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 { @@ -204,28 +204,27 @@ public: QPushButton:checked:enabled { background-color: #33Ab4C; } + QPushButton:checked:disabled { + background-color: #9933Ab4C; + } 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->setChecked(i == 0); button->setStyleSheet(style); button->setMinimumWidth(minimum_button_width); hlayout->addWidget(button); button_group->addButton(button, i); } - QObject::connect(button_group, QOverload::of(&QButtonGroup::buttonClicked), [=](int id) { - params.put(key, std::to_string(id)); - }); + QObject::connect(button_group, QOverload::of(&QButtonGroup::buttonClicked), this, &MultiButtonControl::buttonClicked); } void setEnabled(bool enable) { @@ -238,6 +237,31 @@ public: button_group->button(id)->setChecked(true); } +signals: + void buttonClicked(int id); + +protected: + QButtonGroup *button_group; +}; + +class ButtonParamControl : public MultiButtonControl { + 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) : MultiButtonControl(title, desc, icon, + button_texts, minimum_button_width) { + key = param.toStdString(); + int value = atoi(params.get(key).c_str()); + + if (value > 0 && value < button_group->buttons().size()) { + button_group->button(value)->setChecked(true); + } + + QObject::connect(this, QOverload::of(&MultiButtonControl::buttonClicked), [=](int id) { + params.put(key, std::to_string(id)); + }); + } + void refresh() { int value = atoi(params.get(key).c_str()); button_group->button(value)->setChecked(true); @@ -250,7 +274,6 @@ public: private: std::string key; Params params; - QButtonGroup *button_group; }; class ListWidget : public QWidget { diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index b0b6b4c23b..0cbf14931b 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -120,11 +120,11 @@ InputDialog::InputDialog(const QString &title, QWidget *parent, const QString &s 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->setIcon(QIcon(ASSET_PATH + "icons/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->setIcon(QIcon(ASSET_PATH + "icons/eye_open.svg")); eye_btn->setIconSize(QSize(81, 44)); line->setEchoMode(QLineEdit::Normal); } diff --git a/selfdrive/ui/spinner b/selfdrive/ui/spinner deleted file mode 100755 index 965c8f581a..0000000000 --- a/selfdrive/ui/spinner +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/sh - -if [ -f /TICI ] && [ ! -f _spinner ]; then - cp qt/spinner_larch64 _spinner -fi - -exec ./_spinner "$1" diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index 09dd7c5d8b..2ae3356bb8 100644 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -96,8 +96,15 @@ class TestTranslations: 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() + try: + 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() + except requests.exceptions.HTTPError as e: + if e.response is not None and e.response.status_code == 429: + pytest.skip("word list rate limited") + raise banned_words = {line.strip() for line in response.text.splitlines()} diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 35323cf000..c830680aa6 100755 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -56,7 +56,7 @@ def setup_settings_firehose(click, pm: PubMaster): def setup_settings_developer(click, pm: PubMaster): CP = car.CarParams() - CP.experimentalLongitudinalAvailable = True + CP.alphaLongitudinalAvailable = True Params().put("CarParamsPersistent", CP.to_bytes()) setup_settings_device(click, pm) diff --git a/selfdrive/ui/text b/selfdrive/ui/text deleted file mode 100755 index b12235f4e6..0000000000 --- a/selfdrive/ui/text +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/sh - -if [ -f /TICI ] && [ ! -f _text ]; then - cp qt/text_larch64 _text -fi - -exec ./_text "$1" diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 8f43e64e8a..fa3b2d69e7 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -327,10 +327,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp ACTIVE نشط - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>غير نشط</span>: اتصل بشبكة غير محسوبة - For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. للحصول على أقصى فعالية، أحضر جهازك إلى الداخل واتصل بمحول USB-C جيد وشبكة Wi-Fi أسبوعياً.<br><br>يمكن أن يعمل وضع خرطوم الحريق أيضاً أثناء القيادة إذا كنت متصلاً بنقطة اتصال أو ببطاقة SIM غير محدودة.<br><br><br><b>الأسئلة المتكررة</b><br><br><i>هل يهم كيف أو أين أقود؟</i> لا، فقط قد كما تفعل عادة.<br><br><i>هل يتم سحب كل مقاطع رحلاتي في وضع خرطوم الحريق؟</i> لا، نقوم بسحب مجموعة مختارة من مقاطع رحلاتك.<br><br><i>ما هو محول USB-C الجيد؟</i> أي شاحن سريع للهاتف أو اللابتوب يجب أن يكون مناسباً.<br><br><i>هل يهم أي برنامج أستخدم؟</i> نعم، فقط النسخة الأصلية من openpilot (وأفرع معينة) يمكن استخدامها للتدريب. @@ -346,6 +342,10 @@ Firehose Mode allows you to maximize your training data uploads to improve openp حتى الآن، يوجد </b>%n مقطع<b>%n من قيادتك في مجموعة بيانات التدريب. + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + + HudRenderer @@ -582,14 +582,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - إعادة التشغيل - - - Exit - إغلاق - openpilot openpilot diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index d440e790fc..3123e52578 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -68,23 +68,23 @@ Hidden Network - + Verborgenes Netzwerk CONNECT - CONNECT + VERBINDEN Enter SSID - SSID eingeben + SSID eingeben Enter password - Passwort eingeben + Passwort eingeben for "%1" - für "%1" + für "%1" @@ -117,31 +117,31 @@ DeveloperPanel Joystick Debug Mode - + Joystick Debug-Modus Longitudinal Maneuver Mode - + Längsmanöver-Modus openpilot Longitudinal Control (Alpha) - + openpilot Längsregelung (Alpha) WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB). - + WARNUNG: Die openpilot Längsregelung befindet sich für dieses Fahrzeug im Alpha-Stadium und deaktiviert das automatische Notbremsen (AEB). 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. - + Bei diesem Fahrzeug verwendet openpilot standardmäßig den eingebauten Tempomaten anstelle der openpilot Längsregelung. Aktiviere diese Option, um auf die openpilot Längsregelung umzuschalten. Es wird empfohlen, den experimentellen Modus zu aktivieren, wenn die openpilot Längsregelung (Alpha) aktiviert wird. Enable ADB - + ADB aktivieren ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. See https://docs.comma.ai/how-to/connect-to-comma for more info. - + ADB (Android Debug Bridge) ermöglicht die Verbindung zu deinem Gerät über USB oder Netzwerk. Siehe https://docs.comma.ai/how-to/connect-to-comma für weitere Informationen. @@ -280,11 +280,11 @@ Pair Device - + Gerät koppeln PAIR - + KOPPELN @@ -309,37 +309,39 @@ FirehosePanel 🔥 Firehose Mode 🔥 - + 🔥 Firehose-Modus 🔥 openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilot lernt das Fahren, indem es Menschen wie dir beim Fahren zuschaut. + +Der Firehose-Modus ermöglicht es dir, deine Trainingsdaten-Uploads zu maximieren, um die Fahrmodelle von openpilot zu verbessern. Mehr Daten bedeuten größere Modelle, was zu einem besseren Experimentellen Modus führt. Firehose Mode: ACTIVE - + Firehose-Modus: AKTIV ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + AKTIV For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + Für maximale Effektivität bring dein Gerät jede Woche nach drinnen und verbinde es mit einem guten USB-C-Adapter und WLAN.<br><br>Der Firehose-Modus funktioniert auch während der Fahrt, wenn das Gerät mit einem Hotspot oder einer ungedrosselten SIM-Karte verbunden ist.<br><br><br><b>Häufig gestellte Fragen</b><br><br><i>Spielt es eine Rolle, wie oder wo ich fahre?</i> Nein, fahre einfach wie gewohnt.<br><br><i>Werden im Firehose-Modus alle meine Segmente hochgeladen?</i> Nein, wir wählen selektiv nur einen Teil deiner Segmente aus.<br><br><i>Welcher USB-C-Adapter ist gut?</i> Jedes Schnellladegerät für Handy oder Laptop sollte ausreichen.<br><br><i>Spielt es eine Rolle, welche Software ich nutze?</i> Ja, nur das offizielle Upstream‑openpilot (und bestimmte Forks) kann für das Training verwendet werden. <b>%n segment(s)</b> of your driving is in the training dataset so far. - - - + + <b>%n Segment</b> deiner Fahrten ist bisher im Trainingsdatensatz. + <b>%n Segmente</b> deiner Fahrten sind bisher im Trainingsdatensatz. + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INAKTIV</span>: Verbinde dich mit einem ungedrosselten Netzwerk + HudRenderer @@ -411,48 +413,49 @@ Firehose Mode allows you to maximize your training data uploads to improve openp OffroadAlert Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won't engage in %1 - + Stelle sofort eine Internetverbindung her, um nach Updates zu suchen. Wenn du keine Verbindung herstellst, kann openpilot in %1 nicht mehr aktiviert werden. Connect to internet to check for updates. openpilot won't automatically start until it connects to internet to check for updates. - + Verbinde dich mit dem Internet, um nach Updates zu suchen. openpilot startet nicht automatisch, bis eine Internetverbindung besteht und nach Updates gesucht wurde. Unable to download updates %1 - + Updates konnten nicht heruntergeladen werden +%1 Taking camera snapshots. System won't start until finished. - + Kamera-Snapshots werden aufgenommen. Das System startet erst, wenn dies abgeschlossen ist. An update to your device's operating system is downloading in the background. You will be prompted to update when it's ready to install. - + Ein Update für das Betriebssystem deines Geräts wird im Hintergrund heruntergeladen. Du wirst aufgefordert, das Update zu installieren, sobald es bereit ist. Device failed to register. It will not connect to or upload to comma.ai servers, and receives no support from comma.ai. If this is an official device, visit https://comma.ai/support. - + Gerät konnte nicht registriert werden. Es wird keine Verbindung zu den comma.ai-Servern herstellen oder Daten hochladen und erhält keinen Support von comma.ai. Wenn dies ein offizielles Gerät ist, besuche https://comma.ai/support. NVMe drive not mounted. - + NVMe-Laufwerk nicht gemounted. Unsupported NVMe drive detected. Device may draw significantly more power and overheat due to the unsupported NVMe. - + Nicht unterstütztes NVMe-Laufwerk erkannt. Das Gerät kann dadurch deutlich mehr Strom verbrauchen und überhitzen. openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - + openpilot konnte dein Auto nicht identifizieren. Dein Auto wird entweder nicht unterstützt oder die Steuergeräte (ECUs) werden nicht erkannt. Bitte reiche einen Pull Request ein, um die Firmware-Versionen für das richtige Fahrzeug hinzuzufügen. Hilfe findest du auf discord.comma.ai. openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. - + openpilot hat eine Änderung der Montageposition des Geräts erkannt. Stelle sicher, dass das Gerät vollständig in der Halterung sitzt und die Halterung fest an der Windschutzscheibe befestigt ist. Device temperature too high. System cooling down before starting. Current internal component temperature: %1 - + Gerätetemperatur zu hoch. Das System kühlt ab, bevor es startet. Aktuelle interne Komponententemperatur: %1 @@ -474,23 +477,23 @@ Firehose Mode allows you to maximize your training data uploads to improve openp OnroadAlerts openpilot Unavailable - + openpilot nicht verfügbar TAKE CONTROL IMMEDIATELY - + ÜBERNIMM SOFORT DIE KONTROLLE Reboot Device - + Gerät neu starten Waiting to start - + Warten auf Start System Unresponsive - + System reagiert nicht @@ -513,7 +516,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Please connect to Wi-Fi to complete initial pairing - + Bitte verbinde dich mit WLAN, um die Koppelung abzuschließen. @@ -547,15 +550,15 @@ Firehose Mode allows you to maximize your training data uploads to improve openp 24/7 LTE connectivity - + 24/7 LTE-Verbindung 1 year of drive storage - + Fahrdaten-Speicherung für 1 Jahr Remote snapshots - + Remote-Snapshots @@ -571,14 +574,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - Neustart - - - Exit - Verlassen - openpilot openpilot @@ -606,7 +601,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp now - + jetzt @@ -637,16 +632,17 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. - + Datenpartition konnte nicht gemounted werden. Die Partition ist möglicherweise beschädigt. Drücke Bestätigen, um das Gerät zu löschen und zurückzusetzen. Resetting device... This may take up to a minute. - + Gerät wird zurückgesetzt... +Dies kann bis zu einer Minute dauern. System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. - + System-Reset ausgelöst. Drücke Bestätigen, um alle Inhalte und Einstellungen zu löschen. Drücke Abbrechen, um den Startvorgang fortzusetzen. @@ -673,11 +669,11 @@ This may take up to a minute. Developer - + Entwickler Firehose - + Firehose @@ -752,11 +748,11 @@ This may take up to a minute. No custom software found at this URL. - + Keine benutzerdefinierte Software unter dieser URL gefunden. Something went wrong. Reboot the device. - + Etwas ist schiefgelaufen. Starte das Gerät neu. Select a language @@ -764,15 +760,15 @@ This may take up to a minute. Choose Software to Install - + Wähle die zu installierende Software openpilot - openpilot + openpilot Custom Software - + Benutzerdefinierte Software @@ -923,23 +919,23 @@ This may take up to a minute. failed to check for update - + Update-Prüfung fehlgeschlagen up to date, last checked %1 - + Auf dem neuesten Stand, zuletzt geprüft am %1 DOWNLOAD - + HERUNTERLADEN update available - + Update verfügbar never - + nie @@ -1000,11 +996,11 @@ This may take up to a minute. Welcome to openpilot - + Willkommen bei openpilot You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + Du musst die Nutzungsbedingungen akzeptieren, um openpilot zu verwenden. Lies die aktuellen Bedingungen unter <span style='color: #465BEA;'>https://comma.ai/terms</span>, bevor du fortfährst. @@ -1071,51 +1067,51 @@ This may take up to a minute. Aggressive - + Aggressiv Standard - + Standard Relaxed - + Entspannt Driving Personality - + Fahrstil End-to-End Longitudinal Control - + Ende-zu-Ende Längsregelung openpilot longitudinal control may come in a future update. - + Die openpilot Längsregelung könnte in einem zukünftigen Update verfügbar sein. An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches. - + Eine Alpha-Version der openpilot Längsregelung kann zusammen mit dem Experimentellen Modus auf non-stable Branches getestet werden. Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode. - + Aktiviere den Schalter für openpilot Längsregelung (Alpha), um den Experimentellen Modus zu erlauben. 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. On supported cars, you can cycle through these personalities with your steering wheel distance button. - + Standard wird empfohlen. Im aggressiven Modus folgt openpilot vorausfahrenden Fahrzeugen enger und ist beim Gasgeben und Bremsen aggressiver. Im entspannten Modus hält openpilot mehr Abstand zu vorausfahrenden Fahrzeugen. Bei unterstützten Fahrzeugen kannst du mit der Abstandstaste am Lenkrad zwischen diesen Fahrstilen wechseln. 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. - + Die Fahrvisualisierung wechselt bei niedrigen Geschwindigkeiten auf die nach vorne gerichtete Weitwinkelkamera, um Kurven besser darzustellen. Das Logo des Experimentellen Modus wird außerdem oben rechts angezeigt. Always-On Driver Monitoring - + Dauerhaft aktive Fahrerüberwachung Enable driver monitoring even when openpilot is not engaged. - + Fahrerüberwachung auch aktivieren, wenn openpilot nicht aktiv ist. @@ -1157,15 +1153,15 @@ This may take up to a minute. WiFiPromptWidget Open - + Öffnen Maximize your training data uploads to improve openpilot's driving models. - + Maximiere deine Trainingsdaten-Uploads, um die Fahrmodelle von openpilot zu verbessern. <span style='font-family: "Noto Color Emoji";'>🔥</span> Firehose Mode <span style='font-family: Noto Color Emoji;'>🔥</span> - + <span style='font-family: "Noto Color Emoji";'>🔥</span> Firehose-Modus <span style='font-family: Noto Color Emoji;'>🔥</span> diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 235051bb73..3d9be63caf 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -137,11 +137,11 @@ Enable ADB - + Activar ADB ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. See https://docs.comma.ai/how-to/connect-to-comma for more info. - + ADB (Android Debug Bridge) permite conectar a su dispositivo por USB o por red. Visite https://docs.comma.ai/how-to/connect-to-comma para más información. @@ -309,37 +309,39 @@ FirehosePanel 🔥 Firehose Mode 🔥 - + 🔥 Modo Firehose 🔥 openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilot aprende a conducir observando a humanos, como tú, conducir. + +El Modo Firehose te permite maximizar las subidas de datos de entrenamiento para mejorar los modelos de conducción de openpilot. Más datos significan modelos más grandes, lo que significa un mejor Modo Experimental. Firehose Mode: ACTIVE - + Modo Firehose: ACTIVO ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + ACTIVO For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + Para máxima efectividad, traiga su dispositivo adentro y conéctelo a un buen adaptador USB-C y Wi-Fi semanalmente.<br><br>El Modo Firehose también puede funcionar mientras conduce si está conectado a un punto de acceso o tarjeta SIM ilimitada.<br><br><br><b>Preguntas Frecuentes</b><br><br><i>¿Importa cómo o dónde conduzco?</i> No, solo conduzca como lo haría normalmente.<br><br><i>¿Se extraen todos mis segmentos en el Modo Firehose?</i> No, seleccionamos selectivamente un subconjunto de sus segmentos.<br><br><i>¿Qué es un buen adaptador USB-C?</i> Cualquier cargador rápido de teléfono o portátil debería funcionar.<br><br><i>¿Importa qué software ejecuto?</i> Sí, solo el openpilot original (y forks específicos) pueden usarse para el entrenamiento. <b>%n segment(s)</b> of your driving is in the training dataset so far. - - - + + <b>%n segmento</b> de tu conducción está en el conjunto de datos de entrenamiento hasta ahora. + <b>%n segmentos</b> de tu conducción están en el conjunto de datos de entrenamiento hasta ahora. + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVO</span>: conéctate a una red sin límite de datos + HudRenderer @@ -572,14 +574,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - Reiniciar - - - Exit - Salir - openpilot openpilot @@ -679,7 +673,7 @@ Esto puede tardar un minuto. Firehose - + Firehose @@ -1000,11 +994,11 @@ Esto puede tardar un minuto. Welcome to openpilot - + Bienvenido a openpilot You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + Debe aceptar los Términos y Condiciones para usar openpilot. Lea los términos más recientes en <span style='color: #465BEA;'>https://comma.ai/terms</span> antes de continuar. @@ -1157,15 +1151,15 @@ Esto puede tardar un minuto. WiFiPromptWidget Open - + Abrir Maximize your training data uploads to improve openpilot's driving models. - + Maximice sus cargas de datos de entrenamiento para mejorar los modelos de conducción de openpilot. <span style='font-family: "Noto Color Emoji";'>🔥</span> Firehose Mode <span style='font-family: Noto Color Emoji;'>🔥</span> - + <span style='font-family: "Noto Color Emoji";'>🔥</span> Modo Firehose <span style='font-family: Noto Color Emoji;'>🔥</span> diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index 4ed97e2338..69652510df 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -325,10 +325,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp ACTIVE - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - - For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. @@ -340,6 +336,10 @@ Firehose Mode allows you to maximize your training data uploads to improve openp + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + + HudRenderer @@ -572,14 +572,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - Redémarrer - - - Exit - Quitter - openpilot openpilot diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 7c67d83020..4cce79757f 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -315,30 +315,32 @@ openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilotは人間であるあなたの運転から学び、AI学習します。 + +Firehoseモードを有効にすると、学習データを最大限アップロードし、openpilotの運転モデルを向上させることができます。より多くのデータはより大きなモデルとなり、Experimentalモードの精度を向上させます。 Firehose Mode: ACTIVE - + Firehoseモード: 作動中 ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + 動作中 For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + 最大の効果を得るためにはデバイスを屋内に持ち込み、大容量のUSB-C充電器とWi-Fiに毎週接続してください。<br><br>Firehoseモードは公衆無線LANや大容量契約のSIMカードに接続していれば、運転中でも動作します。<br><br><br><b>よくある質問(FAQ)</b><br><br><i>運転のやり方や走る場所は重要ですか?</i> いいえ、普段どおりに運転するだけで大丈夫です。<br><br><i>Firehoseモードでは全てのデータがアップロードされますか?</i> いいえ、アップロードするデータを選ぶことができます。<br><br><i>大容量のUSB-C充電器とは何ですか?</i> スマートフォンやノートパソコンを高速に充電できるものを使って下さい。<br><br><i>どのフォークを使うかは重要ですか?</i>はい、トレーニングには公式のopenpilot(および特定のフォーク)のみが使用できます。 <b>%n segment(s)</b> of your driving is in the training dataset so far. - - + + あなたの運転の<b>%nセグメント</b>がこれまでのトレーニングデータに含まれています。 + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>動作停止</span>: 大容量のネットワークに接続してください + HudRenderer @@ -570,14 +572,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - 再起動 - - - Exit - 閉じる - openpilot openpilot @@ -945,7 +939,7 @@ This may take up to a minute. 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. - 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。commaのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 + 警告: これはGitHubの設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外のGitHubユーザー名を入力しないでください。commaのスタッフがGitHubのユーザー名を追加するようお願いすることはありません。 ADD @@ -953,7 +947,7 @@ This may take up to a minute. Enter your GitHub username - GitHub のユーザー名を入力してください + GitHubのユーザー名を入力してください LOADING @@ -995,18 +989,18 @@ This may take up to a minute. Welcome to openpilot - + openpilotへようこそ You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + openpilotを使用するには利用規約に同意する必要があります。続行する前に最新の規約を以下でご確認ください: <span style='color: #465BEA;'>https://comma.ai/terms</span> TogglesPanel Enable openpilot - openpilot を有効化 + openpilotを有効化 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. @@ -1014,7 +1008,7 @@ This may take up to a minute. Enable Lane Departure Warnings - 車線逸脱警報機能の有効化 + 車線逸脱警報の有効化 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). diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 5abc6ce9b2..3be96846a7 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -102,7 +102,7 @@ DeclinePage You must accept the Terms and Conditions in order to use openpilot. - openpilot을 사용하려면 이용약관에 동의해야 합니다. + 오픈파일럿을 사용하려면 이용약관에 동의해야 합니다. Back @@ -121,19 +121,19 @@ Longitudinal Maneuver Mode - 롱컨 제어 모드 + 가감속 제어 조작 모드 openpilot Longitudinal Control (Alpha) - openpilot 가감속 제어 (알파) + 오픈파일럿 가감속 제어 (알파) WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB). - 경고: openpilot 가감속 제어는 알파 기능으로 차량의 자동긴급제동(AEB)기능이 작동하지 않습니다. + 경고: 오픈파일럿 가감속 제어는 알파 기능으로 차량의 자동긴급제동(AEB)기능이 작동하지 않습니다. 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. - 이 차량에서 openpilot은 openpilot 가감속 제어 대신 기본적으로 차량의 ACC로 가감속을 제어합니다. openpilot 가감속 제어로 전환하려면 이 기능을 활성화하세요. openpilot 가감속 제어 알파 기능을 활성화하는 경우 실험 모드 활성화를 권장합니다. + 이 차량에서 오픈파일럿은 오픈파일럿 가감속 제어 대신 기본적으로 차량의 ACC로 가감속을 제어합니다. 오픈파일럿 가감속 제어로 전환하려면 이 기능을 활성화하세요. 오픈파일럿 가감속 제어 알파 기능을 활성화하는 경우 실험 모드 활성화를 권장합니다. Enable ADB @@ -192,7 +192,7 @@ Review the rules, features, and limitations of openpilot - openpilot의 규칙, 기능 및 제한 다시 확인 + 오픈파일럿의 규칙, 기능 및 제한 다시 확인 Are you sure you want to review the training guide? @@ -228,7 +228,7 @@ 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. - openpilot 장치는 좌우 4°, 위로 5°, 아래로 9° 이내 각도로 장착되어야 합니다. openpilot은 지속적으로 자동 보정되며 재설정은 거의 필요하지 않습니다. + 오픈파일럿 장치는 좌우 4°, 위로 5°, 아래로 9° 이내 각도로 장착되어야 합니다. 오픈파일럿은 지속적으로 자동 보정되며 재설정은 거의 필요하지 않습니다. Your device is pointed %1° %2 and %3° %4. @@ -317,7 +317,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. 오픈파일럿은 여러분과 같은 사람이 운전하는 모습을 보면서 운전하는 법을 배웁니다. -파이어호스 모드를 사용하면 훈련 데이터 업로드를 최대화하여 오픈파일럿의 주행 모델을 개선할 수 있습니다. 더 많은 데이터는 더 큰 모델을 의미하며, 이는 더 나은 실험 모드를 의미합니다. +파이어호스 모드를 사용하면 학습 데이터 업로드를 최대화하여 오픈파일럿의 주행 모델을 개선할 수 있습니다. 더 많은 데이터는 더 큰 모델을 의미하며, 이는 더 나은 실험 모드를 의미합니다. Firehose Mode: ACTIVE @@ -325,22 +325,22 @@ Firehose Mode allows you to maximize your training data uploads to improve openp ACTIVE - 활성화 - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>비활성</span>: 무제한 네트워크에 연결 + 활성 상태 For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - 최대한의 효과를 얻으려면 매주 장치를 실내로 가져와 좋은 USB-C 케이블에 연결하고 Wi-Fi에 연결하세요.<br><br>파이어호스 모드는 핫스팟 또는 무제한 SIM 카드에 연결된 경우에는 운전 중에도 작동할 수 있습니다.<br><br><br><b>자주 묻는 질문</b><br><br><i>운전 방법이나 장소가 중요한가요?</i> 아니요, 평소처럼 운전하시면 됩니다.<br><br><i>파이어호스 모드에서 제 모든 구간을 가져오나요?.<br><br><i> 아니요, 저희는 여러분의 구간 중 일부를 선별적으로 가져옵니다.<br><br><i>좋은 USB-C 케이블은 무엇인가요?</i> 휴대폰이나 노트북 고속 충전기가 있으면 됩니다.<br><br><i>어떤 소프트웨어를 실행하는지가 중요한가요?</i> 예, 오직 공식 openpilot의 특정 포크만 트레이닝에 사용할 수 있습니다. + 최대한의 효과를 얻으려면 매주 장치를 실내로 가져와 좋은 USB-C 충전기와 Wi-Fi에 연결하세요.<br><br>파이어호스 모드는 핫스팟 또는 무제한 네트워크에 연결된 경우 주행 중에도 작동할 수 있습니다.<br><br><br><b>자주 묻는 질문</b><br><br><i>운전 방법이나 장소가 중요한가요?</i> 아니요, 평소처럼 운전하시면 됩니다.<br><br><i>파이어호스 모드에서 제 모든 구간을 가져오나요?<br><br><i> 아니요, 저희는 여러분의 구간 중 일부를 선별적으로 가져옵니다.<br><br><i>좋은 USB-C 충전기는 무엇인가요?</i> 휴대폰이나 노트북충전이 가능한 고속 충전기이면 괜찮습니다.<br><br><i>어떤 소프트웨어를 실행하는지가 중요한가요?</i> 예, 오직 공식 오픈파일럿의 특정 포크만 트레이닝에 사용할 수 있습니다. <b>%n segment(s)</b> of your driving is in the training dataset so far. - - + + <b>%n 구간</b> 의 운전이 지금까지의 학습 데이터셋에 포함되어 있습니다. + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>비활성 상태</span>: 무제한 네트워크에 연결 하세요 + HudRenderer @@ -411,11 +411,11 @@ Firehose Mode allows you to maximize your training data uploads to improve openp OffroadAlert Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won't engage in %1 - 즉시 인터넷에 연결하여 업데이트를 확인하세요. 인터넷에 연결되어 있지 않으면 %1 이후에는 openpilot이 활성화되지 않습니다. + 즉시 인터넷에 연결하여 업데이트를 확인하세요. 인터넷에 연결되어 있지 않으면 %1 이후에는 오픈파일럿이 활성화되지 않습니다. Connect to internet to check for updates. openpilot won't automatically start until it connects to internet to check for updates. - 업데이트를 확인하려면 인터넷에 연결하세요. openpilot은 업데이트를 확인하기 위해 인터넷에 연결할 때까지 자동으로 시작되지 않습니다. + 업데이트 확인을 위해 인터넷 연결이 필요합니다. 오픈파일럿은 업데이트 확인을 위해 인터넷에 연결될 때까지 자동으로 시작되지 않습니다. Unable to download updates @@ -445,15 +445,15 @@ Firehose Mode allows you to maximize your training data uploads to improve openp openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - openpilot이 차량을 식별할 수 없습니다. 지원되지 않는 차량이거나 ECU가 인식되지 않습니다. 해당 차량에 맞는 펌웨어 버전을 추가하려면 PR을 제출하세요. 도움이 필요하시면 discord.comma.ai에 가입하세요. + 오픈파일럿이 차량을 식별할 수 없습니다. 지원되지 않는 차량이거나 ECU가 인식되지 않습니다. 해당 차량에 맞는 펌웨어 버전을 추가하려면 PR을 제출하세요. 도움이 필요하시면 discord.comma.ai에 참여하세요. openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. - openpilot 장치의 장착 위치가 변경되었습니다. 장치가 마운트에 완전히 장착되고 마운트가 앞유리에 단단히 고정되었는지 확인하세요. + 오픈파일럿 장치의 장착 위치가 변경되었습니다. 장치가 마운트에 완전히 장착되고 마운트가 앞유리에 단단히 고정되었는지 확인하세요. Device temperature too high. System cooling down before starting. Current internal component temperature: %1 - 장치의 온도가 너무 높습니다. 시작 전에 온도를 낮춰주세요. 현재 내부 구성 요소 온도: %1 + 장치 온도가 너무 높습니다. 시작하기 전에 시스템을 냉각하고 있습니다. 현재 내부 구성 요소 온도: %1 @@ -536,7 +536,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Become a comma prime member at connect.comma.ai - connect.comma.ai에 접속하여 comma prime 회원으로 등록하세요 + connect.comma.ai에서 comma prime 사용자로 등록하세요 PRIME FEATURES: @@ -552,7 +552,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp 1 year of drive storage - 1년간 드라이브 로그 저장 + 1년간 주행 로그 저장 Remote snapshots @@ -572,17 +572,9 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - 재부팅 - - - Exit - 종료 - openpilot - openpilot + 오픈파일럿 %n minute(s) ago @@ -767,7 +759,7 @@ This may take up to a minute. openpilot - openpilot + 오픈파일럿 Custom Software @@ -997,7 +989,7 @@ This may take up to a minute. Welcome to openpilot - 오픈 파일럿에 오신 것을 환영합니다. + 오픈파일럿에 오신 것을 환영합니다. You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. @@ -1008,11 +1000,11 @@ This may take up to a minute. TogglesPanel Enable openpilot - openpilot 사용 + 오픈파일럿 사용 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. - 어댑티브 크루즈 컨트롤 및 차로 유지 보조를 위해 openpilot 시스템을 사용할 수 있습니다. 이 기능을 사용할 때에는 언제나 주의를 기울여야 합니다. 설정을 변경하면 차량 시동이 꺼졌을 때 적용됩니다. + 오픈파일럿 시스템을 사용하여 어댑티브 크루즈 컨트롤과 차로 유지 보조 기능을 활용하십시오. 이 기능을 사용할 때에는 항상 주의를 기울여야 합니다. 설정 변경은 차량을 재시동해야 적용됩니다. Enable Lane Departure Warnings @@ -1044,7 +1036,7 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. - 활성화된 경우 가속 페달을 밟으면 openpilot이 해제됩니다. + 활성화된 경우 가속 페달을 밟으면 오픈파일럿이 해제됩니다. Experimental Mode @@ -1052,11 +1044,11 @@ This may take up to a minute. openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: - openpilot은 기본적으로 <b>안정 모드</b>로 주행합니다. 실험 모드는 안정화되지 않은 <b>알파 수준의 기능</b>을 활성화합니다. 실험 모드의 기능은 아래와 같습니다: + 오픈파일럿은 기본적으로 <b>안정 모드</b>로 주행합니다. 실험 모드는 안정화되지 않은 <b>알파 수준의 기능</b>을 활성화합니다. 실험 모드의 기능은 아래와 같습니다: 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. - openpilot의 주행모델이 가감속을 제어합니다. openpilot은 신호등과 정지 표지판을 보고 멈추는 것을 포함하여 인간이 운전하는 것처럼 생각하고 주행합니다. 주행 모델이 주행할 속도를 결정하므로 설정된 속도는 최대 주행 속도로만 기능합니다. 이 기능은 알파 수준이므로 사용에 각별히 주의해야 합니다. + 주행모델이 가감속을 제어하도록 합니다. 오픈파일럿은 빨간불과 정지신호를 보고 정지하는것을 포함하여 사람이 운전하는 방식대로 작동하며 주행 모델이 속도를 결정하므로 설정 속도는 최대 제한 속도로만 작동합니다. 이는 알파 수준의 기능이며 오류가 발생할수있으니 사용에 주의해야 합니다. New Driving Visualization @@ -1064,11 +1056,11 @@ This may take up to a minute. Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control. - 차량에 장착된 ACC로 가감속을 제어하기 때문에 현재 이 차량에서는 실험 모드를 사용할 수 없습니다. + 차량의 ACC가 가감속 제어에 사용되기 때문에, 이 차량에서는 실험 모드를 사용할 수 없습니다. openpilot longitudinal control may come in a future update. - openpilot 가감속 제어는 향후 업데이트에서 지원될 수 있습니다. + 오픈파일럿 가감속 제어는 향후 업데이트에서 지원될 수 있습니다. Aggressive @@ -1088,11 +1080,11 @@ This may take up to a minute. An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches. - openpilot 가감속 제어 알파 버전은 비 릴리즈 브랜치에서 실험 모드와 함께 테스트할 수 있습니다. + 오픈파일럿 가감속 제어 알파 버전은 비 릴리즈 브랜치에서 실험 모드와 함께 테스트할 수 있습니다. Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode. - 실험 모드를 사용하려면 openpilot E2E 가감속 제어 (알파) 토글을 활성화하세요. + 실험 모드를 사용하려면 오픈파일럿 E2E 가감속 제어 (알파) 토글을 활성화하세요. End-to-End Longitudinal Control @@ -1100,7 +1092,7 @@ This may take up to a minute. 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. On supported cars, you can cycle through these personalities with your steering wheel distance button. - 표준 모드를 권장합니다. 공격적 모드의 openpilot은 선두 차량을 더 가까이 따라가고 가감속제어를 사용하여 더욱 공격적으로 움직입니다. 편안한 모드의 openpilot은 선두 차량으로부터 더 멀리 떨어져 있습니다. 지원되는 차량에서는 스티어링 휠 거리 버튼을 사용하여 이러한 특성을 순환할 수 있습니다. + 표준 모드를 권장합니다. 공격적 모드의 오픈파일럿은 선두 차량을 더 가까이 따라가고 가감속제어를 사용하여 더욱 공격적으로 움직입니다. 편안한 모드의 오픈파일럿은 선두 차량으로부터 더 멀리 떨어져 있습니다. 지원되는 차량에서는 차간거리 버튼을 사용하여 이러한 특성을 순환할 수 있습니다. 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. @@ -1112,7 +1104,7 @@ This may take up to a minute. Enable driver monitoring even when openpilot is not engaged. - openpilot이 활성화되지 않은 경우에도 드라이버 모니터링을 활성화합니다. + 오픈파일럿이 활성화되지 않은 경우에도 드라이버 모니터링을 활성화합니다. @@ -1158,7 +1150,7 @@ This may take up to a minute. Maximize your training data uploads to improve openpilot's driving models. - 훈련 데이터 업로드를 최대화하여 오픈파일럿의 주행 모델을 개선하세요. + 오픈파일럿의 주행 모델 개선을 위해 학습 데이터 업로드를 최대화하세요. <span style='font-family: "Noto Color Emoji";'>🔥</span> Firehose Mode <span style='font-family: Noto Color Emoji;'>🔥</span> diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 57b5b4ffa5..a6a473bc92 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -327,10 +327,6 @@ O Modo Firehose permite maximizar o envio de dados de treinamento para melhorar ACTIVE ATIVO - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INATIVO</span>: conecte-se a uma rede sem restrição <br> de dados - For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. Para maior eficácia, leve seu dispositivo para dentro de casa e conecte-o a um bom adaptador USB-C e Wi-Fi semanalmente.<br><br>O Modo Firehose também pode funcionar enquanto você dirige, se estiver conectado a um hotspot ou a um chip SIM com dados ilimitados.<br><br><br><b>Perguntas Frequentes</b><br><br><i>Importa como ou onde eu dirijo?</i> Não, basta dirigir normalmente.<br><br><i>Todos os meus segmentos são enviados no Modo Firehose?</i> Não, selecionamos apenas um subconjunto dos seus segmentos.<br><br><i>Qual é um bom adaptador USB-C?</i> Qualquer carregador rápido de telefone ou laptop deve ser suficiente.<br><br><i>Importa qual software eu uso?</i> Sim, apenas o openpilot oficial (e alguns forks específicos) podem ser usados para treinamento. @@ -342,6 +338,10 @@ O Modo Firehose permite maximizar o envio de dados de treinamento para melhorar <b>%n segmentos</b> da sua direção estão no conjunto de dados de treinamento até agora. + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INATIVO</span>: conecte-se a uma rede sem limite <br> de dados + HudRenderer @@ -574,14 +574,6 @@ O Modo Firehose permite maximizar o envio de dados de treinamento para melhorar QObject - - Reboot - Reiniciar - - - Exit - Sair - openpilot openpilot diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 6db0085567..c7521082c3 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -117,31 +117,31 @@ DeveloperPanel Joystick Debug Mode - + โหมดดีบักจอยสติ๊ก Longitudinal Maneuver Mode - + โหมดการควบคุมการเร่ง/เบรค openpilot Longitudinal Control (Alpha) - ระบบควบคุมการเร่ง/เบรคโดย openpilot (Alpha) + ระบบควบคุมการเร่ง/เบรคโดย openpilot (Alpha) WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB). - คำเตือน: การควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ยังอยู่ในสถานะ alpha และระบบเบรคฉุกเฉินอัตโนมัติ (AEB) จะถูกปิด + คำเตือน: การควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ยังอยู่ในสถานะ alpha และระบบเบรคฉุกเฉินอัตโนมัติ (AEB) จะถูกปิด 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. - โดยปกติสำหรับรถคันนี้ openpilot จะควบคุมการเร่ง/เบรคด้วยระบบ ACC จากโรงงาน แทนการควยคุมโดย openpilot เปิดสวิตซ์นี้เพื่อให้ openpilot ควบคุมการเร่ง/เบรค แนะนำให้เปิดโหมดทดลองเมื่อต้องการให้ openpilot ควบคุมการเร่ง/เบรค ซึ่งอยู่ในสถานะ alpha + โดยปกติสำหรับรถคันนี้ openpilot จะควบคุมการเร่ง/เบรคด้วยระบบ ACC จากโรงงาน แทนการควยคุมโดย openpilot เปิดสวิตซ์นี้เพื่อให้ openpilot ควบคุมการเร่ง/เบรค แนะนำให้เปิดโหมดทดลองเมื่อต้องการให้ openpilot ควบคุมการเร่ง/เบรค ซึ่งอยู่ในสถานะ alpha Enable ADB - + เปิด ADB ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. See https://docs.comma.ai/how-to/connect-to-comma for more info. - + ADB (Android Debug Bridge) อนุญาตให้เชื่อมต่ออุปกรณ์ของคุณผ่าน USB หรือผ่านเครือข่าย ดูข้อมูลเพิ่มเติมที่ https://docs.comma.ai/how-to/connect-to-comma @@ -309,36 +309,38 @@ FirehosePanel 🔥 Firehose Mode 🔥 - + 🔥 โหมดสายยางดับเพลิง 🔥 openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilot เรียนรู้วิธีขับรถจากการเฝ้าดูการขับขี่ของมนุษย์เช่นคุณ + +โหมดสายยางดับเพลิงช่วยให้คุณอัปโหลดข้อมูลการฝึกฝนได้มากที่สุด เพื่อนำไปพัฒนาโมเดลการขับขี่ของ openpilot ข้อมูลที่มากขึ้นหมายถึงโมเดลที่ใหญ่ขึ้น และนั่นหมายถึงโหมดทดลองที่ดีขึ้น Firehose Mode: ACTIVE - + โหมดสายยางดับเพลิง: เปิดใช้งาน ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + เปิดใช้งาน For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + เพื่อประสิทธิภาพสูงสุด ควรนำอุปกรณ์เข้ามาข้างใน เชื่อมต่อกับอะแดปเตอร์ USB-C คุณภาพดี และ Wi-Fi สัปดาห์ละครั้ง<br><br>โหมดสายยางดับเพลิงยังสามารถทำงานระหว่างขับรถได้ หากเชื่อมต่อกับฮอตสปอตหรือซิมการ์ดที่มีเน็ตไม่จำกัด<br><br><br><b>คำถามที่พบบ่อย</b><br><br><i>วิธีการขับหรือสถานที่ขับขี่มีผลหรือไม่?</i>ไม่มีผล แค่ขับขี่ตามปกติของคุณ<br><br><i>เซกเมนต์ทั้งหมดของฉันจะถูกดึงข้อมูลในโหมดสายยางดับเพลิงหรือไม่?</i>ไม่ใช่ เราจะเลือกดึงข้อมูลเพียงบางส่วนจากเซกเมนต์ของคุณ<br><br><i>อะแดปเตอร์ USB-C แบบไหนดี?</i>ที่ชาร์จเร็วของโทรศัพท์หรือแล็ปท็อปแบบใดก็ได้ สามารถใช้ได้<br><br><i>ซอฟต์แวร์ที่ใช้มีผลหรือไม่?</i>มีผล เฉพาะ openpilot ตัวหลัก (และ fork เฉพาะบางตัว) เท่านั้น ที่สามารถนำข้อมูลไปใช้ฝึกฝนโมเดลได้ <b>%n segment(s)</b> of your driving is in the training dataset so far. - - + + มีการขับขี่ของคุณ <b>%n เซกเมนต์</b> อยู่ในชุดข้อมูลการฝึกฝนแล้วในขณะนี้ + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>ไม่เปิดใช้งาน</span>: เชื่อมต่อกับเครือข่ายที่ไม่จำกัดข้อมูล + HudRenderer @@ -485,11 +487,11 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Waiting to start - + รอเริ่มทำงาน System Unresponsive - + ระบบไม่ตอบสนอง @@ -512,7 +514,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Please connect to Wi-Fi to complete initial pairing - + กรุณาเชื่อมต่อ Wi-Fi เพื่อทำการจับคู่ครั้งแรกให้เสร็จสิ้น @@ -554,7 +556,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Remote snapshots - + ภาพถ่ายระยะไกล @@ -570,14 +572,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - รีบูต - - - Exit - ปิด - openpilot openpilot @@ -670,11 +664,11 @@ This may take up to a minute. Developer - + นักพัฒนา Firehose - + สายยางดับเพลิง @@ -995,11 +989,11 @@ This may take up to a minute. Welcome to openpilot - + ยินดีต้อนรับสู่ openpilot You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + คุณต้องยอมรับข้อกำหนดและเงื่อนไขเพื่อใช้งาน openpilot อ่านข้อกำหนดล่าสุดได้ที่ <span style='color: #465BEA;'>https://comma.ai/terms</span> ก่อนดำเนินการต่อ @@ -1106,11 +1100,11 @@ This may take up to a minute. Always-On Driver Monitoring - + การเฝ้าระวังผู้ขับขี่ตลอดเวลา Enable driver monitoring even when openpilot is not engaged. - + เปิดใช้งานการเฝ้าระวังผู้ขับขี่แม้เมื่อ openpilot ไม่ได้เข้าควบคุมอยู่ @@ -1152,15 +1146,15 @@ This may take up to a minute. WiFiPromptWidget Open - + เปิด Maximize your training data uploads to improve openpilot's driving models. - + อัปโหลดข้อมูลการฝึกฝนให้ได้มากที่สุด เพื่อพัฒนาโมเดลการขับขี่ของ openpilot <span style='font-family: "Noto Color Emoji";'>🔥</span> Firehose Mode <span style='font-family: Noto Color Emoji;'>🔥</span> - + <span style='font-family: "Noto Color Emoji";'>🔥</span> โหมดสายยางดับเพลิง <span style='font-family: Noto Color Emoji;'>🔥</span> diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index e640eeab4d..b8b7202898 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -325,10 +325,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp ACTIVE - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - - For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. @@ -339,6 +335,10 @@ Firehose Mode allows you to maximize your training data uploads to improve openp + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + + HudRenderer @@ -569,14 +569,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - Yeniden başlat - - - Exit - Çık - openpilot openpilot diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index f78d8dcdff..c310265a1c 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -121,7 +121,7 @@ Longitudinal Maneuver Mode - 纵向机动模式 + 纵向操控测试模式 openpilot Longitudinal Control (Alpha) @@ -315,30 +315,32 @@ openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilot 通过观察人类驾驶(包括您)来学习如何驾驶。 + +“训练数据上传模式”允许您最大化上传训练数据,以改进 openpilot 的驾驶模型。更多数据意味着更强大的模型,也就意味着更优秀的“实验模式”。 Firehose Mode: ACTIVE - + 训练数据上传模式:激活中 ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + 激活中 For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + 为了达到最佳效果,请每周将您的设备带回室内,并连接到优质的 USB-C 充电器和 Wi-Fi。<br><br>Firehose 模式在行驶时也能运行,但需连接到移动热点或使用不限流量的 SIM 卡。<br><br><br><b>常见问题</b><br><br><i>我开车的方式或地点有影响吗?</i>不会,请像平常一样驾驶即可。<br><br><i>Firehose 模式会上传所有的驾驶片段吗?</i>不会,我们会选择性地上传部分片段。<br><br><i>什么是好的 USB-C 充电器?</i>任何快速手机或笔记本电脑充电器都应该适用。<br><br><i>我使用的软件版本有影响吗?</i>有的,只有官方 openpilot(以及特定的分支)可以用于训练。 <b>%n segment(s)</b> of your driving is in the training dataset so far. - - + + <b>目前已有 %n 段</b> 您的驾驶数据被纳入训练数据集。 + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>闲置</span>:请连接到不限流量的网络 + HudRenderer @@ -570,14 +572,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - 重启 - - - Exit - 退出 - openpilot openpilot @@ -995,11 +989,11 @@ This may take up to a minute. Welcome to openpilot - + 欢迎使用 openpilot You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + 您必须接受《条款与条件》才能使用 openpilot。在继续之前,请先阅读最新条款:<span style='color: #465BEA;'>https://comma.ai/terms</span>。 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 8547c90410..5f81cc2c53 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -121,7 +121,7 @@ Longitudinal Maneuver Mode - 縱向機動模式 + 縱向操控測試模式 openpilot Longitudinal Control (Alpha) @@ -315,30 +315,32 @@ openpilot learns to drive by watching humans, like you, drive. Firehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode. - + openpilot 透過觀察人類駕駛(包括您)來學習如何駕駛。 + +「訓練資料上傳模式」可讓您最大化上傳訓練數據,以改進 openpilot 的駕駛模型。更多數據代表更強大的模型,也就意味著更優秀的「實驗模式」。 Firehose Mode: ACTIVE - + 訓練資料上傳模式:啟用中 ACTIVE - - - - <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network - + 啟用中 For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br><br>Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br><br><br><b>Frequently Asked Questions</b><br><br><i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br><i>Do all of my segments get pulled in Firehose Mode?</i> No, we selectively pull a subset of your segments.<br><br><i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br><i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training. - + 為了達到最佳效果,請每週將您的裝置帶回室內,並連接至優質的 USB-C 充電器與 Wi-Fi。<br><br>訓練資料上傳模式在行駛時也能運作,但需連接至行動熱點或使用不限流量的 SIM 卡。<br><br><br><b>常見問題</b><br><br><i>我開車的方式或地點有影響嗎?</i> 不會,請像平常一樣駕駛即可。<br><br><i>訓練資料上傳模式會上傳所有的駕駛片段嗎?</i>不會,我們會選擇性地上傳部分片段。<br><br><i>什麼是好的 USB-C 充電器?</i>任何快速手機或筆電充電器都應該適用。<br><br><i>我使用的軟體版本有影響嗎?</i>有的,只有官方 openpilot(以及特定的分支)可以用於訓練。 <b>%n segment(s)</b> of your driving is in the training dataset so far. - - + + <b>目前已有 %n 段</b> 您的駕駛數據被納入訓練資料集。 + + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to an unmetered network + <span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>閒置中</span>:請連接到不按流量計費的網絡 + HudRenderer @@ -570,14 +572,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp QObject - - Reboot - 重新啟動 - - - Exit - 離開 - openpilot openpilot @@ -995,11 +989,11 @@ This may take up to a minute. Welcome to openpilot - + 歡迎使用 openpilot You must accept the Terms and Conditions to use openpilot. Read the latest terms at <span style='color: #465BEA;'>https://comma.ai/terms</span> before continuing. - + 您必須接受《條款與條件》才能使用 openpilot。在繼續之前,請先閱讀最新條款:<span style='color: #465BEA;'>https://comma.ai/terms</span>。 diff --git a/system/athena/athenad.py b/system/athena/athenad.py index b36bdb103d..5a02d45c43 100755 --- a/system/athena/athenad.py +++ b/system/athena/athenad.py @@ -16,7 +16,7 @@ import threading import time from dataclasses import asdict, dataclass, replace from datetime import datetime -from functools import partial +from functools import partial, total_ordering from queue import Queue from typing import cast from collections.abc import Callable @@ -53,6 +53,7 @@ MAX_RETRY_COUNT = 30 # Try for at most 5 minutes if upload fails immediately MAX_AGE = 31 * 24 * 3600 # seconds WS_FRAME_SIZE = 4096 DEVICE_STATE_UPDATE_INTERVAL = 1.0 # in seconds +DEFAULT_UPLOAD_PRIORITY = 99 # higher number = lower priority NetworkType = log.DeviceState.NetworkType @@ -68,13 +69,15 @@ class UploadFile: url: str headers: dict[str, str] allow_cellular: bool + priority: int = DEFAULT_UPLOAD_PRIORITY @classmethod def from_dict(cls, d: dict) -> UploadFile: - return cls(d.get("fn", ""), d.get("url", ""), d.get("headers", {}), d.get("allow_cellular", False)) + return cls(d.get("fn", ""), d.get("url", ""), d.get("headers", {}), d.get("allow_cellular", False), d.get("priority", DEFAULT_UPLOAD_PRIORITY)) @dataclass +@total_ordering class UploadItem: path: str url: str @@ -85,17 +88,28 @@ class UploadItem: current: bool = False progress: float = 0 allow_cellular: bool = False + priority: int = DEFAULT_UPLOAD_PRIORITY @classmethod def from_dict(cls, d: dict) -> UploadItem: return cls(d["path"], d["url"], d["headers"], d["created_at"], d["id"], d["retry_count"], d["current"], - d["progress"], d["allow_cellular"]) + d["progress"], d["allow_cellular"], d["priority"]) + + def __lt__(self, other): + if not isinstance(other, UploadItem): + return NotImplemented + return self.priority < other.priority + + def __eq__(self, other): + if not isinstance(other, UploadItem): + return NotImplemented + return self.priority == other.priority dispatcher["echo"] = lambda s: s recv_queue: Queue[str] = queue.Queue() send_queue: Queue[str] = queue.Queue() -upload_queue: Queue[UploadItem] = queue.Queue() +upload_queue: Queue[UploadItem] = queue.PriorityQueue() low_priority_send_queue: Queue[str] = queue.Queue() log_recv_queue: Queue[str] = queue.Queue() cancelled_uploads: set[str] = set() @@ -398,6 +412,7 @@ def uploadFilesToUrls(files_data: list[UploadFileDict]) -> UploadFilesToUrlRespo created_at=int(time.time() * 1000), id=None, allow_cellular=file.allow_cellular, + priority=file.priority, ) upload_id = hashlib.sha1(str(item).encode()).hexdigest() item = replace(item, id=upload_id) @@ -531,7 +546,7 @@ def getNetworks(): @dispatcher.add_method def takeSnapshot() -> str | dict[str, str] | None: - from openpilot.system.camerad.snapshot.snapshot import jpeg_write, snapshot + from openpilot.system.camerad.snapshot import jpeg_write, snapshot ret = snapshot() if ret is not None: def b64jpeg(x): @@ -761,8 +776,11 @@ def ws_manage(ws: WebSocket, end_event: threading.Event) -> None: # While not sending data, onroad, we can expect to time out in 7 + (7 * 2) = 21s # offroad, we can expect to time out in 30 + (10 * 3) = 60s # FIXME: TCP_USER_TIMEOUT is effectively 2x for some reason (32s), so it's mostly unused - sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_USER_TIMEOUT, 16000 if onroad else 0) - sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30) + if sys.platform == 'linux': + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_USER_TIMEOUT, 16000 if onroad else 0) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30) + elif sys.platform == 'darwin': + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPALIVE, 7 if onroad else 30) sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPINTVL, 7 if onroad else 10) sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPCNT, 2 if onroad else 3) diff --git a/system/athena/registration.py b/system/athena/registration.py index 964fbff51e..ce7fcea89f 100755 --- a/system/athena/registration.py +++ b/system/athena/registration.py @@ -7,7 +7,6 @@ from pathlib import Path from datetime import datetime, timedelta, UTC from openpilot.common.api import api_get from openpilot.common.params import Params -from openpilot.common.spinner import Spinner from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, PC from openpilot.system.hardware.hw import Paths @@ -45,6 +44,7 @@ def register(show_spinner=False) -> str | None: cloudlog.warning(f"missing public key: {pubkey}") elif dongle_id is None: if show_spinner: + from openpilot.system.ui.spinner import Spinner spinner = Spinner() spinner.update("registering device") diff --git a/system/athena/tests/test_athenad.py b/system/athena/tests/test_athenad.py index e16e73a7ea..dd82325815 100644 --- a/system/athena/tests/test_athenad.py +++ b/system/athena/tests/test_athenad.py @@ -76,7 +76,7 @@ class TestAthenadMethods: self.params.put(k, v) self.params.put_bool("GsmMetered", True) - athenad.upload_queue = queue.Queue() + athenad.upload_queue = queue.PriorityQueue() athenad.cur_upload_items.clear() athenad.cancelled_uploads.clear() @@ -321,6 +321,26 @@ class TestAthenadMethods: assert len(items) == 1 assert items[0]['current'] + def test_list_upload_queue_priority(self): + priorities = (25, 50, 99, 75, 0) + + for i in priorities: + fn = f'qlog_{i}.zst' + fp = self._create_file(fn) + item = athenad.UploadItem( + path=fp, + url=f"http://localhost:44444/{fn}", + headers={}, + created_at=int(time.time()*1000), + id='', + allow_cellular=True, + priority=i + ) + athenad.upload_queue.put_nowait(item) + + for i in sorted(priorities): + assert athenad.upload_queue.get_nowait().priority == i + def test_list_upload_queue(self): item = athenad.UploadItem(path="qlog.zst", url="http://localhost:44444/qlog.zst", headers={}, created_at=int(time.time()*1000), id='id', allow_cellular=True) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index f6c2681dea..1f6ad9b4be 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -26,9 +26,6 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, SpectraCamera * LOGD("allocated %d CL buffers", frame_buf_count); } - out_img_width = sensor->frame_width; - out_img_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height; - // the encoder HW tells us the size it wants after setting it up. // TODO: VENUS_BUFFER_SIZE should give the size, but it's too small. dependent on encoder settings? size_t nv12_size = (out_img_width <= 1344 ? 2900 : 2346)*cam->stride; diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index c0426678b6..c26859cbc4 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -32,7 +32,7 @@ public: VisionBuf *cur_yuv_buf; VisionBuf *cur_camera_buf; std::unique_ptr camera_bufs_raw; - int out_img_width, out_img_height; + uint32_t out_img_width, out_img_height; CameraBuf() = default; ~CameraBuf(); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 18a42f05d8..8c4602bb31 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -73,7 +73,7 @@ void CameraState::init(VisionIpcServer *v, cl_device_id device_id, cl_context ct if (!camera.enabled) return; - fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm; + fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm / camera.sensor->out_scale; set_exposure_rect(); dc_gain_weight = camera.sensor->dc_gain_min_weight; @@ -107,10 +107,10 @@ void CameraState::set_exposure_rect() { float fl_ref = ae_target.second; ae_xywh = (Rect){ - std::max(0, camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::max(0, camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), - std::min((int)(fl_pix / fl_ref * xywh_ref.w), camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::min((int)(fl_pix / fl_ref * xywh_ref.h), camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) + std::max(0, (int)camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::max(0, (int)camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), + std::min((int)(fl_pix / fl_ref * xywh_ref.w), (int)camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::min((int)(fl_pix / fl_ref * xywh_ref.h), (int)camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) }; } diff --git a/system/camerad/cameras/ife.h b/system/camerad/cameras/ife.h index 49737f2db7..fd87d2baa4 100644 --- a/system/camerad/cameras/ife.h +++ b/system/camerad/cameras/ife.h @@ -105,7 +105,7 @@ int build_update(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std: } -int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std::vector &patches) { +int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std::vector &patches, uint32_t out_width, uint32_t out_height) { uint8_t *start = dst; // start with the every frame config @@ -185,12 +185,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo // output size/scaling dst += write_cont(dst, 0xa3c, { 0x00000003, - ((s->frame_width - 1) << 16) | (s->frame_width - 1), + ((out_width - 1) << 16) | (s->frame_width - 1), 0x30036666, 0x00000000, 0x00000000, s->frame_width - 1, - ((s->frame_height - 1) << 16) | (s->frame_height - 1), + ((out_height - 1) << 16) | (s->frame_height - 1), 0x30036666, 0x00000000, 0x00000000, @@ -198,12 +198,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo }); dst += write_cont(dst, 0xa68, { 0x00000003, - ((s->frame_width/2 - 1) << 16) | (s->frame_width - 1), + ((out_width / 2 - 1) << 16) | (s->frame_width - 1), 0x3006cccc, 0x00000000, 0x00000000, s->frame_width - 1, - ((s->frame_height/2 - 1) << 16) | (s->frame_height - 1), + ((out_height / 2 - 1) << 16) | (s->frame_height - 1), 0x3006cccc, 0x00000000, 0x00000000, @@ -212,12 +212,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo // cropping dst += write_cont(dst, 0xe10, { - s->frame_height - 1, - s->frame_width - 1, + out_height - 1, + out_width - 1, }); dst += write_cont(dst, 0xe30, { - s->frame_height/2 - 1, - s->frame_width - 1, + out_height / 2 - 1, + out_width - 1, }); dst += write_cont(dst, 0xe18, { 0x0ff00000, diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index d12dbb2444..47ae9061f4 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -19,7 +19,6 @@ #include "system/camerad/cameras/ife.h" #include "system/camerad/cameras/spectra.h" #include "system/camerad/cameras/bps_blobs.h" -#include "third_party/linux/include/msm_media_info.h" // ************** low level camera helpers **************** @@ -282,18 +281,21 @@ void SpectraCamera::camera_open(VisionIpcServer *v, cl_device_id device_id, cl_c if (!enabled) return; + buf.out_img_width = sensor->frame_width / sensor->out_scale; + buf.out_img_height = (sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height) / sensor->out_scale; + // size is driven by all the HW that handles frames, // the video encoder has certain alignment requirements in this case - stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, sensor->frame_width); - y_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); - uv_height = VENUS_UV_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); + stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, buf.out_img_width); + y_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, buf.out_img_height); + uv_height = VENUS_UV_SCANLINES(COLOR_FMT_NV12, buf.out_img_height); uv_offset = stride*y_height; yuv_size = uv_offset + stride*uv_height; if (cc.output_type != ISP_RAW_OUTPUT) { uv_offset = ALIGNED_SIZE(uv_offset, 0x1000); yuv_size = uv_offset + ALIGNED_SIZE(stride*uv_height, 0x1000); } - assert(stride == VENUS_UV_STRIDE(COLOR_FMT_NV12, sensor->frame_width)); + assert(stride == VENUS_UV_STRIDE(COLOR_FMT_NV12, buf.out_img_width)); assert(y_height/2 == uv_height); open = true; @@ -646,14 +648,14 @@ void SpectraCamera::config_bps(int idx, int request_id) { io_cfg[1].mem_handle[0] = buf_handle_yuv[idx]; io_cfg[1].mem_handle[1] = buf_handle_yuv[idx]; io_cfg[1].planes[0] = (struct cam_plane_cfg){ - .width = sensor->frame_width, - .height = sensor->frame_height, + .width = buf.out_img_width, + .height = buf.out_img_height, .plane_stride = stride, .slice_height = y_height, }; io_cfg[1].planes[1] = (struct cam_plane_cfg){ - .width = sensor->frame_width, - .height = sensor->frame_height/2, + .width = buf.out_img_width, + .height = buf.out_img_height / 2, .plane_stride = stride, .slice_height = uv_height, }; @@ -738,7 +740,7 @@ void SpectraCamera::config_ife(int idx, int request_id, bool init) { bool is_raw = cc.output_type != ISP_IFE_PROCESSED; if (!is_raw) { if (init) { - buf_desc[0].length = build_initial_config((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches); + buf_desc[0].length = build_initial_config((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches, buf.out_img_width, buf.out_img_height); } else { buf_desc[0].length = build_update((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches); } @@ -845,14 +847,14 @@ void SpectraCamera::config_ife(int idx, int request_id, bool init) { io_cfg[0].mem_handle[0] = buf_handle_yuv[idx]; io_cfg[0].mem_handle[1] = buf_handle_yuv[idx]; io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = sensor->frame_width, - .height = sensor->frame_height, + .width = buf.out_img_width, + .height = buf.out_img_height, .plane_stride = stride, .slice_height = y_height, }; io_cfg[0].planes[1] = (struct cam_plane_cfg){ - .width = sensor->frame_width, - .height = sensor->frame_height/2, + .width = buf.out_img_width, + .height = buf.out_img_height / 2, .plane_stride = stride, .slice_height = uv_height, }; @@ -994,6 +996,9 @@ bool SpectraCamera::openSensor() { LOGD("-- Probing sensor %d", cc.camera_num); auto init_sensor_lambda = [this](SensorInfo *s) { + if (s->image_sensor == cereal::FrameData::ImageSensor::OS04C10 && cc.output_type == ISP_IFE_PROCESSED) { + ((OS04C10*)s)->ife_downscale_configure(); + } sensor.reset(s); return (sensors_init() == 0); }; @@ -1066,8 +1071,8 @@ void SpectraCamera::configISP() { .data[0] = (struct cam_isp_out_port_info){ .res_type = CAM_ISP_IFE_OUT_RES_FULL, .format = CAM_FORMAT_NV12, - .width = sensor->frame_width, - .height = sensor->frame_height + sensor->extra_height, + .width = buf.out_img_width, + .height = buf.out_img_height + sensor->extra_height, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }, }; @@ -1142,8 +1147,8 @@ void SpectraCamera::configICP() { }, .out_res[0] = (struct cam_icp_res_info){ .format = 0x3, // YUV420NV12 - .width = sensor->frame_width, - .height = sensor->frame_height, + .width = buf.out_img_width, + .height = buf.out_img_height, .fps = 20, }, }; diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index d008e1d07b..38be4ecca4 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -20,6 +20,17 @@ const uint32_t os04c10_analog_gains_reg[] = { } // namespace +void OS04C10::ife_downscale_configure() { + out_scale = 2; + + pixel_size_mm = 0.002; + frame_width = 2688; + frame_height = 1520; + exposure_time_max = 2352; + + init_reg_array.insert(init_reg_array.end(), std::begin(ife_downscale_override_array_os04c10), std::end(ife_downscale_override_array_os04c10)); +} + OS04C10::OS04C10() { image_sensor = cereal::FrameData::ImageSensor::OS04C10; bayer_pattern = CAM_ISP_PATTERN_BAYER_BGBGBG; diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h index 8b1c78c69d..7cd9e97be5 100644 --- a/system/camerad/sensors/os04c10_registers.h +++ b/system/camerad/sensors/os04c10_registers.h @@ -88,8 +88,6 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x37c7, 0xa8}, {0x37da, 0x11}, {0x381f, 0x08}, - // {0x3829, 0x03}, - // {0x3832, 0x00}, {0x3881, 0x00}, {0x3888, 0x04}, {0x388b, 0x00}, @@ -332,3 +330,23 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x5104, 0x08}, {0x5105, 0xd6}, {0x5144, 0x08}, {0x5145, 0xd6}, }; + +const struct i2c_random_wr_payload ife_downscale_override_array_os04c10[] = { + // OS04C10_AA_00_02_17_wAO_2688x1524_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz + {0x3c8c, 0x40}, + {0x3714, 0x24}, + {0x37c2, 0x04}, + {0x3662, 0x10}, + {0x37d9, 0x08}, + {0x4041, 0x07}, + {0x4008, 0x02}, + {0x4009, 0x0d}, + {0x3808, 0x0a}, {0x3809, 0x80}, + {0x380a, 0x05}, {0x380b, 0xf0}, + {0x3814, 0x01}, + {0x3816, 0x01}, + {0x380c, 0x08}, {0x380d, 0x5c}, // HTS + {0x380e, 0x09}, {0x380f, 0x38}, // VTS + {0x3820, 0xb0}, + {0x3821, 0x00}, +}; diff --git a/system/camerad/sensors/ox03c10_registers.h b/system/camerad/sensors/ox03c10_registers.h index 5c6282942b..bb7a1c5dd6 100644 --- a/system/camerad/sensors/ox03c10_registers.h +++ b/system/camerad/sensors/ox03c10_registers.h @@ -65,7 +65,6 @@ const struct i2c_random_wr_payload init_array_ox03c10[] = { {0x3008, 0x80}, // io_pad_sel // FSIN (frame sync) with external pulses - {0x3822, 0x33}, // wait for pulse before first frame {0x3009, 0x2}, {0x3015, 0x2}, {0x383E, 0x80}, @@ -73,6 +72,9 @@ const struct i2c_random_wr_payload init_array_ox03c10[] = { {0x3882, 0x8}, {0x3883, 0x0D}, {0x3836, 0x1F}, {0x3837, 0x40}, + // causes issues on some devices + //{0x3822, 0x33}, // wait for pulse before first frame + {0x3892, 0x44}, {0x3823, 0x41}, diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index c1131aafdf..d4be3cf036 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -29,6 +29,7 @@ public: uint32_t frame_stride; uint32_t frame_offset = 0; uint32_t extra_height = 0; + int out_scale = 1; int registers_offset = -1; int stats_offset = -1; int hdr_offset = -1; @@ -109,6 +110,7 @@ public: class OS04C10 : public SensorInfo { public: OS04C10(); + void ife_downscale_configure(); 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/snapshot/snapshot.py b/system/camerad/snapshot.py similarity index 100% rename from system/camerad/snapshot/snapshot.py rename to system/camerad/snapshot.py diff --git a/system/camerad/test/check_skips.py b/system/camerad/test/check_skips.py deleted file mode 100755 index 0814ce44ff..0000000000 --- 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 100755 index 21409f398d..0000000000 --- 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/test_exposure.py b/system/camerad/test/test_exposure.py index 97f03ed182..f431c03410 100644 --- a/system/camerad/test/test_exposure.py +++ b/system/camerad/test/test_exposure.py @@ -3,7 +3,7 @@ import numpy as np import pytest from openpilot.selfdrive.test.helpers import with_processes -from openpilot.system.camerad.snapshot.snapshot import get_snapshots +from openpilot.system.camerad.snapshot import get_snapshots TEST_TIME = 45 REPEAT = 5 diff --git a/system/hardware/base.py b/system/hardware/base.py index c7c765f20a..90b42b2f1f 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -33,6 +33,7 @@ class ThermalZone: class ThermalConfig: cpu: list[ThermalZone] | None = None gpu: list[ThermalZone] | None = None + dsp: ThermalZone | None = None pmic: list[ThermalZone] | None = None memory: ThermalZone | None = None intake: ThermalZone | None = None @@ -130,6 +131,9 @@ class HardwareBase(ABC): def get_thermal_config(self): return ThermalConfig() + def set_display_power(self, on: bool): + pass + @abstractmethod def set_screen_brightness(self, percentage): pass diff --git a/system/hardware/fan_controller.py b/system/hardware/fan_controller.py index be93d5922a..7d5bec0509 100755 --- a/system/hardware/fan_controller.py +++ b/system/hardware/fan_controller.py @@ -27,7 +27,7 @@ class TiciFanController(BaseFanController): if ignition != self.last_ignition: self.controller.reset() - error = 70 - cur_temp + error = 75 - cur_temp fan_pwr_out = -int(self.controller.update( error=error, feedforward=np.interp(cur_temp, [60.0, 100.0], [0, -100]) diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index 04e5fd3365..e209613f42 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,25 +1,25 @@ [ { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c.img.xz", - "hash": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c", - "hash_raw": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1.img.xz", + "hash": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", + "hash_raw": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "d35a86e7b8ddd9279b513a6f27da1521aa0f89fb93987ea74d57d0f0bbbbd247" + "ondevice_hash": "003a17ab1be68a696f7efe4c9938e8be511d4aacfc2f3211fc896bdc1681d089" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b.img.xz", - "hash": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b", - "hash_raw": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535.img.xz", + "hash": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", + "hash_raw": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "623f1568072ee2d687ba8449a3d894c1c83dc4131b2e79eff35696885f70a419" + "ondevice_hash": "2a855dd636cc94718b64bea83a44d0a31741ecaa8f72a63613ff348ec7404091" }, { "name": "abl", @@ -34,51 +34,51 @@ }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5.img.xz", - "hash": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5", - "hash_raw": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5", + "url": "https://commadist.azureedge.net/agnosupdate/aop-21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9.img.xz", + "hash": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", + "hash_raw": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "size": 184364, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "bf74feca486f650589f6b7c90eab73274e35a68b5e00bfc1de0ed5f5484d4b3d" + "ondevice_hash": "c1be2f4aac5b3af49b904b027faec418d05efd7bd5144eb4fdfcba602bcf2180" }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180.img.xz", - "hash": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180", - "hash_raw": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620.img.xz", + "hash": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", + "hash_raw": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "size": 40336, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "70f682b59ca0fe2f197d1486bd8be7b9b7e560798ad40ddef83b9f0a2f497938" + "ondevice_hash": "17b229668b20305ff8fa3cd5f94716a3aaa1e5bf9d1c24117eff7f2f81ae719f" }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a.img.xz", - "hash": "0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a", - "hash_raw": "0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a", + "url": "https://commadist.azureedge.net/agnosupdate/boot-eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968.img.xz", + "hash": "eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968", + "hash_raw": "eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968", "size": 18479104, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "47b2096995578a5078e393c33108b42756009dbb361c43c508fc93cd8bda99cc" + "ondevice_hash": "800868bd9d340f1fdf8340924caca374409624658324607621663fc5c7d10d4f" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211.img.xz", - "hash": "fbda983c40e75d8c4784a45c687f27dd27f97f7f0e9a71b4981ec2092ff68a72", - "hash_raw": "ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211", - "size": 4404019200, + "url": "https://commadist.azureedge.net/agnosupdate/system-4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1.img.xz", + "hash": "226794914e9d157b34cc86f1fbe1f2827a9a9919dbe560021b61573a7e5d3101", + "hash_raw": "4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1", + "size": 5368709120, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "428c744458d5f35199aab96a0928876c9deeff3e753e95044291408ba244f0af", + "ondevice_hash": "236890f04ee21b7eb92a59bc47971bd96cad5a4381ed8935eb4be0cb5a4cf48b", "alt": { - "hash": "ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211", - "url": "https://commadist.azureedge.net/agnosupdate/system-ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211.img", - "size": 4404019200 + "hash": "4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1", + "url": "https://commadist.azureedge.net/agnosupdate/system-4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1.img", + "size": 5368709120 } } ] \ No newline at end of file diff --git a/system/hardware/tici/all-partitions.json b/system/hardware/tici/all-partitions.json index 4d15e76b0e..7e39d275cc 100644 --- a/system/hardware/tici/all-partitions.json +++ b/system/hardware/tici/all-partitions.json @@ -130,25 +130,25 @@ }, { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c.img.xz", - "hash": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c", - "hash_raw": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1.img.xz", + "hash": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", + "hash_raw": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "d35a86e7b8ddd9279b513a6f27da1521aa0f89fb93987ea74d57d0f0bbbbd247" + "ondevice_hash": "003a17ab1be68a696f7efe4c9938e8be511d4aacfc2f3211fc896bdc1681d089" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b.img.xz", - "hash": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b", - "hash_raw": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535.img.xz", + "hash": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", + "hash_raw": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "623f1568072ee2d687ba8449a3d894c1c83dc4131b2e79eff35696885f70a419" + "ondevice_hash": "2a855dd636cc94718b64bea83a44d0a31741ecaa8f72a63613ff348ec7404091" }, { "name": "abl", @@ -163,14 +163,14 @@ }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5.img.xz", - "hash": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5", - "hash_raw": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5", + "url": "https://commadist.azureedge.net/agnosupdate/aop-21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9.img.xz", + "hash": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", + "hash_raw": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "size": 184364, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "bf74feca486f650589f6b7c90eab73274e35a68b5e00bfc1de0ed5f5484d4b3d" + "ondevice_hash": "c1be2f4aac5b3af49b904b027faec418d05efd7bd5144eb4fdfcba602bcf2180" }, { "name": "bluetooth", @@ -207,14 +207,14 @@ }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180.img.xz", - "hash": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180", - "hash_raw": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620.img.xz", + "hash": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", + "hash_raw": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "size": 40336, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "70f682b59ca0fe2f197d1486bd8be7b9b7e560798ad40ddef83b9f0a2f497938" + "ondevice_hash": "17b229668b20305ff8fa3cd5f94716a3aaa1e5bf9d1c24117eff7f2f81ae719f" }, { "name": "devinfo", @@ -339,62 +339,62 @@ }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a.img.xz", - "hash": "0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a", - "hash_raw": "0d0d4d5a32e00b46fa36180b4a96337f2a53302d8bd0faee95f8fe1063d1e24a", + "url": "https://commadist.azureedge.net/agnosupdate/boot-eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968.img.xz", + "hash": "eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968", + "hash_raw": "eb0dd0a8ffdc1c03aa28d055788d70be885a00f523b552d7acf79b954838e968", "size": 18479104, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "47b2096995578a5078e393c33108b42756009dbb361c43c508fc93cd8bda99cc" + "ondevice_hash": "800868bd9d340f1fdf8340924caca374409624658324607621663fc5c7d10d4f" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211.img.xz", - "hash": "fbda983c40e75d8c4784a45c687f27dd27f97f7f0e9a71b4981ec2092ff68a72", - "hash_raw": "ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211", - "size": 4404019200, + "url": "https://commadist.azureedge.net/agnosupdate/system-4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1.img.xz", + "hash": "226794914e9d157b34cc86f1fbe1f2827a9a9919dbe560021b61573a7e5d3101", + "hash_raw": "4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1", + "size": 5368709120, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "428c744458d5f35199aab96a0928876c9deeff3e753e95044291408ba244f0af", + "ondevice_hash": "236890f04ee21b7eb92a59bc47971bd96cad5a4381ed8935eb4be0cb5a4cf48b", "alt": { - "hash": "ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211", - "url": "https://commadist.azureedge.net/agnosupdate/system-ff2da7bc34a1ad8e2831a13a49685243957a51b762d8f28e14e98ac90e84d211.img", - "size": 4404019200 + "hash": "4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1", + "url": "https://commadist.azureedge.net/agnosupdate/system-4c3fa88833a8a3876653fa53a658769ecc64be8fc6f6a28ce520ef79bf3061c1.img", + "size": 5368709120 } }, { "name": "userdata_90", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-17f46ba0d0eec10cf14804c84d9bcf4f6fa864074f1b90ff2fb4873399d64b1a.img.xz", - "hash": "1442ae218daff960783bc493a32dd489fa787e4025c64fa3132f48b1e627647f", - "hash_raw": "17f46ba0d0eec10cf14804c84d9bcf4f6fa864074f1b90ff2fb4873399d64b1a", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-f6d24876234f6bea9cc753892eea99ac4b0c8646e93b93d76fc5dddce67347f1.img.xz", + "hash": "2485459e9fbfc0d88a59a017bfa193d97b80afed30d6f59db711e53f62a21c72", + "hash_raw": "f6d24876234f6bea9cc753892eea99ac4b0c8646e93b93d76fc5dddce67347f1", "size": 96636764160, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "a64fea9c3a7bec11b850a55d50ceb30a032742c90aadf0ce35cdbef9349bebba" + "ondevice_hash": "893cfb3e95d6025b9fa6a5c8c3b97bf2abc4ff036c3da846a07536653dbb3a1d" }, { "name": "userdata_89", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-69b2404839f87b1de5c05766550ca0217d5ed566c9f2ea41c46b5a301540a3ac.img.xz", - "hash": "332e6cf5c221690a01ebfd0582420e039c7796a8fb2d499e44a8b657dffe4af2", - "hash_raw": "69b2404839f87b1de5c05766550ca0217d5ed566c9f2ea41c46b5a301540a3ac", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-14f0f02e53ce62a79b337d7b3174dcaffebaa4130264bb5ed9105d942338230b.img.xz", + "hash": "9222aebb280531b7015ee9bab3848dd195567d075b6f37f74d4cd0186685a11f", + "hash_raw": "14f0f02e53ce62a79b337d7b3174dcaffebaa4130264bb5ed9105d942338230b", "size": 95563022336, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "c560c76007fd8997e01e516ab16ff445048945a13bf830bb2a4c7f6e9d2fe5f6" + "ondevice_hash": "a5459ec858d39e3d0709a09af430cb644fe640f92e0cd216b138f01401e4e17e" }, { "name": "userdata_30", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-ffc34d8753520e684448185db801c05bb81e23c54a499cc40a2e38b7009cdf36.img.xz", - "hash": "8bfb1fdec9c8f96c97bcce1efbc7d502447bdb3b481cc408b24b5feef66839fd", - "hash_raw": "ffc34d8753520e684448185db801c05bb81e23c54a499cc40a2e38b7009cdf36", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-180ad331538f20c00218d41591afed3a25bb0f76fa30b1a665cad102cf6c9f7d.img.xz", + "hash": "7fc09317f005676150bfcced43ebb1aa919d854c2511d547a588a35c1122bfe3", + "hash_raw": "180ad331538f20c00218d41591afed3a25bb0f76fa30b1a665cad102cf6c9f7d", "size": 32212254720, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "8f840157d73fa4469aa650d668e046c9750304af84248ab83453cbd285918859" + "ondevice_hash": "1a2f2d14c922bd2895073446460a0bd680711a7b14318a4402631635e6d133b3" } ] \ No newline at end of file diff --git a/system/hardware/tici/esim.py b/system/hardware/tici/esim.py index df76c1a5fd..0a07e77e16 100755 --- a/system/hardware/tici/esim.py +++ b/system/hardware/tici/esim.py @@ -1,115 +1,170 @@ #!/usr/bin/env python3 + +import argparse +import json import os -import math -import time -import binascii -import requests -import serial +import shutil import subprocess +from dataclasses import dataclass +from typing import Literal + +@dataclass +class Profile: + iccid: str + nickname: str + enabled: bool + provider: str +class LPAError(RuntimeError): + pass -def post(url, payload): - print() - print("POST to", url) - r = requests.post( - url, - data=payload, - verify=False, - headers={ - "Content-Type": "application/json", - "X-Admin-Protocol": "gsma/rsp/v2.2.0", - "charset": "utf-8", - "User-Agent": "gsma-rsp-lpad", - }, - ) - print("resp", r) - print("resp text", repr(r.text)) - print() - r.raise_for_status() - - ret = f"HTTP/1.1 {r.status_code}" - ret += ''.join(f"{k}: {v}" for k, v in r.headers.items() if k != 'Connection') - return ret.encode() + r.content +class LPAProfileNotFoundError(LPAError): + pass class LPA: - def __init__(self): - self.dev = serial.Serial('/dev/ttyUSB2', baudrate=57600, timeout=1, bytesize=8) - self.dev.reset_input_buffer() - self.dev.reset_output_buffer() - assert "OK" in self.at("AT") - - def at(self, cmd): - print(f"==> {cmd}") - self.dev.write(cmd.encode() + b'\r\n') - - r = b"" - cnt = 0 - while b"OK" not in r and b"ERROR" not in r and cnt < 20: - r += self.dev.read(8192).strip() - cnt += 1 - r = r.decode() - print(f"<== {repr(r)}") - return r - - def download_ota(self, qr): - return self.at(f'AT+QESIM="ota","{qr}"') - - def download(self, qr): - smdp = qr.split('$')[1] - out = self.at(f'AT+QESIM="download","{qr}"') - for _ in range(5): - line = out.split("+QESIM: ")[1].split("\r\n\r\nOK")[0] - - parts = [x.strip().strip('"') for x in line.split(',', maxsplit=4)] - print(repr(parts)) - trans, ret, url, payloadlen, payload = parts - assert trans == "trans" and ret == "0" - assert len(payload) == int(payloadlen) - - r = post(f"https://{smdp}/{url}", payload) - to_send = binascii.hexlify(r).decode() - - chunk_len = 1400 - for i in range(math.ceil(len(to_send) / chunk_len)): - state = 1 if (i+1)*chunk_len < len(to_send) else 0 - data = to_send[i * chunk_len : (i+1)*chunk_len] - out = self.at(f'AT+QESIM="trans",{len(to_send)},{state},{i},{len(data)},"{data}"') - assert "OK" in out - - if '+QESIM:"download",1' in out: - raise Exception("profile install failed") - elif '+QESIM:"download",0' in out: - print("done, successfully loaded") - break - - def enable(self, iccid): - self.at(f'AT+QESIM="enable","{iccid}"') - - def disable(self, iccid): - self.at(f'AT+QESIM="disable","{iccid}"') - - def delete(self, iccid): - self.at(f'AT+QESIM="delete","{iccid}"') - - def list_profiles(self): - out = self.at('AT+QESIM="list"') - return out.strip().splitlines()[1:] + def __init__(self, interface: Literal['qmi', 'at'] = 'qmi'): + self.env = os.environ.copy() + self.env['LPAC_APDU'] = interface + self.env['QMI_DEVICE'] = '/dev/cdc-wdm0' + self.env['AT_DEVICE'] = '/dev/ttyUSB2' + + self.timeout_sec = 45 + + if shutil.which('lpac') is None: + raise LPAError('lpac not found, must be installed!') + + def list_profiles(self) -> list[Profile]: + msgs = self._invoke('profile', 'list') + self._validate_successful(msgs) + return [Profile( + iccid=p['iccid'], + nickname=p['profileNickname'], + enabled=p['profileState'] == 'enabled', + provider=p['serviceProviderName'] + ) for p in msgs[-1]['payload']['data']] + + def get_active_profile(self) -> Profile | None: + return next((p for p in self.list_profiles() if p.enabled), None) + + def enable_profile(self, iccid: str) -> None: + self._validate_profile_exists(iccid) + latest = self.get_active_profile() + if latest: + if latest.iccid == iccid: + return + self.disable_profile(latest.iccid) + self._validate_successful(self._invoke('profile', 'enable', iccid)) + self.process_notifications() + + def disable_profile(self, iccid: str) -> None: + self._validate_profile_exists(iccid) + latest = self.get_active_profile() + if latest is not None and latest.iccid != iccid: + return + self._validate_successful(self._invoke('profile', 'disable', iccid)) + self.process_notifications() + + def delete_profile(self, iccid: str) -> None: + self._validate_profile_exists(iccid) + latest = self.get_active_profile() + if latest is not None and latest.iccid == iccid: + self.disable_profile(iccid) + self._validate_successful(self._invoke('profile', 'delete', iccid)) + self.process_notifications() + + def download_profile(self, qr: str, nickname: str | None = None) -> None: + msgs = self._invoke('profile', 'download', '-a', qr) + self._validate_successful(msgs) + new_profile = next((m for m in msgs if m['payload']['message'] == 'es8p_meatadata_parse'), None) + if new_profile is None: + raise LPAError('no new profile found') + if nickname: + self.nickname_profile(new_profile['payload']['data']['iccid'], nickname) + self.process_notifications() + + def nickname_profile(self, iccid: str, nickname: str) -> None: + self._validate_profile_exists(iccid) + self._validate_successful(self._invoke('profile', 'nickname', iccid, nickname)) + + def process_notifications(self) -> None: + """ + Process notifications stored on the eUICC, typically to activate/deactivate the profile with the carrier. + """ + self._validate_successful(self._invoke('notification', 'process', '-a', '-r')) + + def _invoke(self, *cmd: str): + proc = subprocess.Popen(['sudo', '-E', 'lpac'] + list(cmd), stdout=subprocess.PIPE, stderr=subprocess.PIPE, env=self.env) + try: + out, err = proc.communicate(timeout=self.timeout_sec) + except subprocess.TimeoutExpired as e: + proc.kill() + raise LPAError(f"lpac {cmd} timed out after {self.timeout_sec} seconds") from e + + messages = [] + for line in out.decode().strip().splitlines(): + if line.startswith('{'): + message = json.loads(line) + + # lpac response format validations + assert 'type' in message, 'expected type in message' + assert message['type'] == 'lpa' or message['type'] == 'progress', 'expected lpa or progress message type' + assert 'payload' in message, 'expected payload in message' + assert 'code' in message['payload'], 'expected code in message payload' + assert 'data' in message['payload'], 'expected data in message payload' + + msg_ret_code = message['payload']['code'] + if msg_ret_code != 0: + raise LPAError(f"lpac {' '.join(cmd)} failed with code {msg_ret_code}: <{message['payload']['message']}> {message['payload']['data']}") + + messages.append(message) + + if len(messages) == 0: + raise LPAError(f"lpac {cmd} returned no messages") + + return messages + + def _validate_profile_exists(self, iccid: str) -> None: + if not any(p.iccid == iccid for p in self.list_profiles()): + raise LPAProfileNotFoundError(f'profile {iccid} does not exist') + + def _validate_successful(self, msgs: list[dict]) -> None: + assert msgs[-1]['payload']['message'] == 'success', 'expected success notification' if __name__ == "__main__": - import sys - - if "RESTART" in os.environ: - subprocess.check_call("sudo systemctl stop ModemManager", shell=True) - subprocess.check_call("/usr/comma/lte/lte.sh stop_blocking", shell=True) - subprocess.check_call("/usr/comma/lte/lte.sh start", shell=True) - while not os.path.exists('/dev/ttyUSB2'): - time.sleep(1) - time.sleep(3) - - lpa = LPA() - print(lpa.list_profiles()) - if len(sys.argv) > 1: - lpa.download(sys.argv[1]) - print(lpa.list_profiles()) + parser = argparse.ArgumentParser(prog='esim.py', description='manage eSIM profiles on your comma device', epilog='comma.ai') + parser.add_argument('--backend', choices=['qmi', 'at'], default='qmi', help='use the specified backend, defaults to qmi') + parser.add_argument('--enable', metavar='iccid', help='enable profile; will disable current profile') + parser.add_argument('--disable', metavar='iccid', help='disable profile') + parser.add_argument('--delete', metavar='iccid', help='delete profile (warning: this cannot be undone)') + parser.add_argument('--download', nargs=2, metavar=('qr', 'name'), help='download a profile using QR code (format: LPA:1$rsp.truphone.com$QRF-SPEEDTEST)') + parser.add_argument('--nickname', nargs=2, metavar=('iccid', 'name'), help='update the nickname for a profile') + args = parser.parse_args() + + lpa = LPA(interface=args.backend) + if args.enable: + lpa.enable_profile(args.enable) + print('enabled profile, please restart device to apply changes') + elif args.disable: + lpa.disable_profile(args.disable) + print('disabled profile, please restart device to apply changes') + elif args.delete: + confirm = input('are you sure you want to delete this profile? (y/N) ') + if confirm == 'y': + lpa.delete_profile(args.delete) + print('deleted profile, please restart device to apply changes') + else: + print('cancelled') + exit(0) + elif args.download: + lpa.download_profile(args.download[0], args.download[1]) + elif args.nickname: + lpa.nickname_profile(args.nickname[0], args.nickname[1]) + else: + parser.print_help() + + profiles = lpa.list_profiles() + print(f'\n{len(profiles)} profile{"s" if len(profiles) > 1 else ""}:') + for p in profiles: + print(f'- {p.iccid} (nickname: {p.nickname or ""}) (provider: {p.provider}) - {"enabled" if p.enabled else "disabled"}') diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 15480bab50..5a8e41b51f 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -297,13 +297,11 @@ class Tici(HardwareBase): return None def get_modem_temperatures(self): - if self.get_device_type() == "mici": - return [] timeout = 0.2 # Default timeout is too short try: modem = self.get_modem() temps = modem.Command("AT+QTEMP", math.ceil(timeout), dbus_interface=MM_MODEM, timeout=timeout) - return list(map(int, temps.split(' ')[1].split(','))) + return list(filter(lambda t: t != 255, map(int, temps.split(' ')[1].split(',')))) except Exception: return [] @@ -335,12 +333,20 @@ class Tici(HardwareBase): return ThermalConfig(cpu=[ThermalZone(f"cpu{i}-silver-usr") for i in range(4)] + [ThermalZone(f"cpu{i}-gold-usr") for i in range(4)], gpu=[ThermalZone("gpu0-usr"), ThermalZone("gpu1-usr")], + dsp=ThermalZone("compute-hvx-usr"), memory=ThermalZone("ddr-usr"), pmic=[ThermalZone("pm8998_tz"), ThermalZone("pm8005_tz")], intake=intake, exhaust=exhaust, case=case) + def set_display_power(self, on): + try: + with open("/sys/class/backlight/panel0-backlight/bl_power", "w") as f: + f.write("0" if on else "4") + except Exception: + pass + def set_screen_brightness(self, percentage): try: with open("/sys/class/backlight/panel0-backlight/max_brightness") as f: diff --git a/system/hardware/tici/tests/test_esim.py b/system/hardware/tici/tests/test_esim.py new file mode 100644 index 0000000000..d36bdaa27b --- /dev/null +++ b/system/hardware/tici/tests/test_esim.py @@ -0,0 +1,51 @@ +import pytest + +from openpilot.system.hardware import TICI +from openpilot.system.hardware.tici.esim import LPA, LPAProfileNotFoundError + +# https://euicc-manual.osmocom.org/docs/rsp/known-test-profile +# iccid is always the same for the given activation code +TEST_ACTIVATION_CODE = 'LPA:1$rsp.truphone.com$QRF-BETTERROAMING-PMRDGIR2EARDEIT5' +TEST_ICCID = '8944476500001944011' + +TEST_NICKNAME = 'test_profile' + +def cleanup(): + lpa = LPA() + try: + lpa.delete_profile(TEST_ICCID) + except LPAProfileNotFoundError: + pass + lpa.process_notifications() + +class TestEsim: + + @classmethod + def setup_class(cls): + if not TICI: + pytest.skip() + cleanup() + + @classmethod + def teardown_class(cls): + cleanup() + + def test_provision_enable_disable(self): + lpa = LPA() + current_active = lpa.get_active_profile() + + lpa.download_profile(TEST_ACTIVATION_CODE, TEST_NICKNAME) + assert any(p.iccid == TEST_ICCID and p.nickname == TEST_NICKNAME for p in lpa.list_profiles()) + + lpa.enable_profile(TEST_ICCID) + new_active = lpa.get_active_profile() + assert new_active is not None + assert new_active.iccid == TEST_ICCID + assert new_active.nickname == TEST_NICKNAME + + lpa.disable_profile(TEST_ICCID) + new_active = lpa.get_active_profile() + assert new_active is None + + if current_active: + lpa.enable_profile(current_active.iccid) diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index e1b9845c4c..db0fab884c 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -56,10 +56,10 @@ class TestPowerDraw: def valid_msg_count(self, proc, msg_counts): msgs_received = sum(msg_counts[msg] for msg in proc.msgs) msgs_expected = self.get_expected_messages(proc) - return np.core.numeric.isclose(msgs_expected, msgs_received, rtol=.02, atol=2) + return np.isclose(msgs_expected, msgs_received, rtol=.02, atol=2) def valid_power_draw(self, proc, used): - return np.core.numeric.isclose(used, proc.power, rtol=proc.rtol, atol=proc.atol) + return np.isclose(used, proc.power, rtol=proc.rtol, atol=proc.atol) def tabulate_msg_counts(self, msgs_and_power): msg_counts = defaultdict(int) diff --git a/system/loggerd/loggerd.cc b/system/loggerd/loggerd.cc index 953ae1df32..2d2d4640ed 100644 --- a/system/loggerd/loggerd.cc +++ b/system/loggerd/loggerd.cc @@ -203,7 +203,7 @@ void handle_user_flag(LoggerdState *s) { // mark route for uploading Params params; - std::string routes = Params().get("AthenadRecentlyViewedRoutes"); + std::string routes = params.get("AthenadRecentlyViewedRoutes"); params.put("AthenadRecentlyViewedRoutes", routes + "," + s->logger.routeName()); prev_segment = s->logger.segment(); diff --git a/system/loggerd/uploader.py b/system/loggerd/uploader.py index c1bf804880..6e6df6114e 100755 --- a/system/loggerd/uploader.py +++ b/system/loggerd/uploader.py @@ -89,7 +89,7 @@ class Uploader: def list_upload_files(self, metered: bool) -> Iterator[tuple[str, str, str]]: r = self.params.get("AthenadRecentlyViewedRoutes", encoding="utf8") - requested_routes = [] if r is None else r.split(",") + requested_routes = [] if r is None else [route for route in r.split(",") if route] for logdir in listdir_by_creation(self.root): path = os.path.join(self.root, logdir) diff --git a/system/loggerd/xattr_cache.py b/system/loggerd/xattr_cache.py index d3220118ac..39bb172059 100644 --- a/system/loggerd/xattr_cache.py +++ b/system/loggerd/xattr_cache.py @@ -1,16 +1,17 @@ -import os import errno +import xattr + _cached_attributes: dict[tuple, bytes | None] = {} def getxattr(path: str, attr_name: str) -> bytes | None: key = (path, attr_name) if key not in _cached_attributes: try: - response = os.getxattr(path, attr_name) + response = xattr.getxattr(path, attr_name) except OSError as e: - # ENODATA means attribute hasn't been set - if e.errno == errno.ENODATA: + # ENODATA (Linux) or ENOATTR (macOS) means attribute hasn't been set + if e.errno == errno.ENODATA or (hasattr(errno, 'ENOATTR') and e.errno == errno.ENOATTR): response = None else: raise @@ -19,4 +20,4 @@ def getxattr(path: str, attr_name: str) -> bytes | None: def setxattr(path: str, attr_name: str, attr_value: bytes) -> None: _cached_attributes.pop((path, attr_name), None) - return os.setxattr(path, attr_name, attr_value) + xattr.setxattr(path, attr_name, attr_value) diff --git a/system/manager/build.py b/system/manager/build.py index 93c0546c85..771024794f 100755 --- a/system/manager/build.py +++ b/system/manager/build.py @@ -5,10 +5,10 @@ from pathlib import Path # NOTE: Do NOT import anything here that needs be built (e.g. params) from openpilot.common.basedir import BASEDIR -from openpilot.common.spinner import Spinner -from openpilot.common.text_window import TextWindow -from openpilot.system.hardware import HARDWARE, AGNOS from openpilot.common.swaglog import cloudlog, add_file_handler +from openpilot.system.hardware import HARDWARE, AGNOS +from openpilot.system.ui.spinner import Spinner +from openpilot.system.ui.text import TextWindow from openpilot.system.version import get_build_metadata MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 @@ -88,7 +88,7 @@ def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: if __name__ == "__main__": - spinner = Spinner() - spinner.update_progress(0, 100) - build_metadata = get_build_metadata() - build(spinner, build_metadata.openpilot.is_dirty, minimal = AGNOS) + with Spinner() as spinner: + spinner.update_progress(0, 100) + build_metadata = get_build_metadata() + build(spinner, build_metadata.openpilot.is_dirty, minimal = AGNOS) diff --git a/system/manager/manager.py b/system/manager/manager.py index 89e5a472f2..c3ffe28457 100755 --- a/system/manager/manager.py +++ b/system/manager/manager.py @@ -9,7 +9,6 @@ from cereal import log import cereal.messaging as messaging import openpilot.system.sentry as sentry from openpilot.common.params import Params, ParamKeyType -from openpilot.common.text_window import TextWindow from openpilot.system.hardware import HARDWARE from openpilot.system.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog from openpilot.system.manager.process import ensure_running @@ -203,6 +202,8 @@ def main() -> None: if __name__ == "__main__": + from openpilot.system.ui.text import TextWindow + unblock_stdout() try: diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 6e048c339e..e25d556037 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -94,6 +94,7 @@ procs = [ PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI), PythonProcess("pandad", "selfdrive.pandad.pandad", always_run), PythonProcess("paramsd", "selfdrive.locationd.paramsd", only_onroad), + PythonProcess("lagd", "selfdrive.locationd.lagd", only_onroad), NativeProcess("ubloxd", "system/ubloxd", ["./ubloxd"], ublox, enabled=TICI), PythonProcess("pigeond", "system.ubloxd.pigeond", ublox, enabled=TICI), PythonProcess("plannerd", "selfdrive.controls.plannerd", not_long_maneuver), diff --git a/system/micd.py b/system/micd.py index af1aa31360..38f3225f55 100755 --- a/system/micd.py +++ b/system/micd.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import numpy as np from functools import cache +import threading from cereal import messaging from openpilot.common.realtime import Ratekeeper @@ -52,12 +53,18 @@ class Mic: self.sound_pressure_weighted = 0 self.sound_pressure_level_weighted = 0 + self.lock = threading.Lock() + def update(self): - msg = messaging.new_message('microphone', valid=True) - msg.microphone.soundPressure = float(self.sound_pressure) - msg.microphone.soundPressureWeighted = float(self.sound_pressure_weighted) + with self.lock: + sound_pressure = self.sound_pressure + sound_pressure_weighted = self.sound_pressure_weighted + sound_pressure_level_weighted = self.sound_pressure_level_weighted - msg.microphone.soundPressureWeightedDb = float(self.sound_pressure_level_weighted) + msg = messaging.new_message('microphone', valid=True) + msg.microphone.soundPressure = float(sound_pressure) + msg.microphone.soundPressureWeighted = float(sound_pressure_weighted) + msg.microphone.soundPressureWeightedDb = float(sound_pressure_level_weighted) self.pm.send('microphone', msg) self.rk.keep_time() @@ -69,17 +76,17 @@ class Mic: Logged A-weighted equivalents are rough approximations of the human-perceived loudness. """ + with self.lock: + self.measurements = np.concatenate((self.measurements, indata[:, 0])) - self.measurements = np.concatenate((self.measurements, indata[:, 0])) - - while self.measurements.size >= FFT_SAMPLES: - measurements = self.measurements[:FFT_SAMPLES] + while self.measurements.size >= FFT_SAMPLES: + measurements = self.measurements[:FFT_SAMPLES] - self.sound_pressure, _ = calculate_spl(measurements) - measurements_weighted = apply_a_weighting(measurements) - self.sound_pressure_weighted, self.sound_pressure_level_weighted = calculate_spl(measurements_weighted) + self.sound_pressure, _ = calculate_spl(measurements) + measurements_weighted = apply_a_weighting(measurements) + self.sound_pressure_weighted, self.sound_pressure_level_weighted = calculate_spl(measurements_weighted) - self.measurements = self.measurements[FFT_SAMPLES:] + self.measurements = self.measurements[FFT_SAMPLES:] @retry(attempts=7, delay=3) def get_stream(self, sd): diff --git a/system/ubloxd/ublox_msg.cc b/system/ubloxd/ublox_msg.cc index 22c99501f3..728f3b15fa 100644 --- a/system/ubloxd/ublox_msg.cc +++ b/system/ubloxd/ublox_msg.cc @@ -476,6 +476,10 @@ kj::Array UbloxMsgParser::gen_nav_sat(ubx_t::nav_sat_t *msg) { svs[i].setSvId(svs_data[i]->sv_id()); svs[i].setGnssId(svs_data[i]->gnss_id()); svs[i].setFlagsBitfield(svs_data[i]->flags()); + svs[i].setCno(svs_data[i]->cno()); + svs[i].setElevationDeg(svs_data[i]->elev()); + svs[i].setAzimuthDeg(svs_data[i]->azim()); + svs[i].setPseudorangeResidual(svs_data[i]->pr_res() * 0.1); } return capnp::messageToFlatArray(msg_builder); diff --git a/system/ui/README.md b/system/ui/README.md index 5f47961a51..c71b77ab66 100644 --- a/system/ui/README.md +++ b/system/ui/README.md @@ -5,5 +5,6 @@ The user interfaces here are built with [raylib](https://www.raylib.com/). Quick start: * set `DEBUG_FPS=1` to show the FPS * set `STRICT_MODE=1` to kill the app if it drops too much below 60fps +* set `SCALE=1.5` to scale the entire UI by 1.5x * https://www.raylib.com/cheatsheet/cheatsheet.html * https://electronstudio.github.io/raylib-python-cffi/README.html#quickstart diff --git a/system/ui/lib/application.py b/system/ui/lib/application.py index c7b7a36e5d..37da413806 100644 --- a/system/ui/lib/application.py +++ b/system/ui/lib/application.py @@ -3,31 +3,37 @@ import os import time import pyray as rl from enum import IntEnum -from openpilot.common.basedir import BASEDIR +from importlib.resources import as_file, files from openpilot.common.swaglog import cloudlog +from openpilot.system.hardware import HARDWARE DEFAULT_FPS = 60 FPS_LOG_INTERVAL = 5 # Seconds between logging FPS drops FPS_DROP_THRESHOLD = 0.9 # FPS drop threshold for triggering a warning FPS_CRITICAL_THRESHOLD = 0.5 # Critical threshold for triggering strict actions +ENABLE_VSYNC = os.getenv("ENABLE_VSYNC") == "1" DEBUG_FPS = os.getenv("DEBUG_FPS") == '1' STRICT_MODE = os.getenv("STRICT_MODE") == '1' +SCALE = float(os.getenv("SCALE", "1.0")) DEFAULT_TEXT_SIZE = 60 -DEFAULT_TEXT_COLOR = rl.Color(200, 200, 200, 255) -FONT_DIR = os.path.join(BASEDIR, "selfdrive/assets/fonts") +DEFAULT_TEXT_COLOR = rl.WHITE + +ASSETS_DIR = files("openpilot.selfdrive").joinpath("assets") +FONT_DIR = ASSETS_DIR.joinpath("fonts") class FontWeight(IntEnum): - BLACK = 0 - BOLD = 1 - EXTRA_BOLD = 2 - EXTRA_LIGHT = 3 + THIN = 0 + EXTRA_LIGHT = 1 + LIGHT = 2 + NORMAL = 3 MEDIUM = 4 - NORMAL = 5 - SEMI_BOLD = 6 - THIN = 7 + SEMI_BOLD = 5 + BOLD = 6 + EXTRA_BOLD = 7 + BLACK = 8 class GuiApplication: @@ -35,58 +41,133 @@ class GuiApplication: self._fonts: dict[FontWeight, rl.Font] = {} self._width = width self._height = height - self._textures: list[rl.Texture] = [] + self._scale = SCALE + self._scaled_width = int(self._width * self._scale) + self._scaled_height = int(self._height * self._scale) + self._render_texture: rl.RenderTexture | None = None + self._textures: dict[str, rl.Texture] = {} self._target_fps: int = DEFAULT_FPS self._last_fps_log_time: float = time.monotonic() + self._window_close_requested = False + self._trace_log_callback = None + + def request_close(self): + self._window_close_requested = True - def init_window(self, title: str, fps: int=DEFAULT_FPS): + def init_window(self, title: str, fps: int = DEFAULT_FPS): atexit.register(self.close) # Automatically call close() on exit - rl.set_config_flags(rl.ConfigFlags.FLAG_MSAA_4X_HINT | rl.ConfigFlags.FLAG_VSYNC_HINT) - rl.init_window(self._width, self._height, title) + HARDWARE.set_display_power(True) + HARDWARE.set_screen_brightness(65) + + self._set_log_callback() + rl.set_trace_log_level(rl.TraceLogLevel.LOG_ALL) + + flags = rl.ConfigFlags.FLAG_MSAA_4X_HINT + if ENABLE_VSYNC: + flags |= rl.ConfigFlags.FLAG_VSYNC_HINT + rl.set_config_flags(flags) + + rl.init_window(self._scaled_width, self._scaled_height, title) + if self._scale != 1.0: + rl.set_mouse_scale(1 / self._scale, 1 / self._scale) + self._render_texture = rl.load_render_texture(self._width, self._height) + rl.set_texture_filter(self._render_texture.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) rl.set_target_fps(fps) self._target_fps = fps self._set_styles() self._load_fonts() - def load_texture_from_image(self, file_name: str, width: int, height: int): + def texture(self, asset_path: str, width: int, height: int, alpha_premultiply=False, keep_aspect_ratio=True): + cache_key = f"{asset_path}_{width}_{height}_{alpha_premultiply}{keep_aspect_ratio}" + if cache_key in self._textures: + return self._textures[cache_key] + + with as_file(ASSETS_DIR.joinpath(asset_path)) as fspath: + texture_obj = self._load_texture_from_image(fspath.as_posix(), width, height, alpha_premultiply, keep_aspect_ratio) + self._textures[cache_key] = texture_obj + return texture_obj + + def _load_texture_from_image(self, image_path: str, width: int, height: int, alpha_premultiply=False, keep_aspect_ratio=True): """Load and resize a texture, storing it for later automatic unloading.""" - image = rl.load_image(file_name) - rl.image_resize(image, width, height) + image = rl.load_image(image_path) + + if alpha_premultiply: + rl.image_alpha_premultiply(image) + + # Resize with aspect ratio preservation if requested + if keep_aspect_ratio: + orig_width = image.width + orig_height = image.height + + scale_width = width / orig_width + scale_height = height / orig_height + + # Calculate new dimensions + scale = min(scale_width, scale_height) + new_width = int(orig_width * scale) + new_height = int(orig_height * scale) + + rl.image_resize(image, new_width, new_height) + else: + rl.image_resize(image, width, height) + texture = rl.load_texture_from_image(image) # Set texture filtering to smooth the result rl.set_texture_filter(texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) rl.unload_image(image) - - self._textures.append(texture) return texture def close(self): - for texture in self._textures: + if not rl.is_window_ready(): + return + + for texture in self._textures.values(): rl.unload_texture(texture) + self._textures = {} for font in self._fonts.values(): rl.unload_font(font) + self._fonts = {} + + if self._render_texture is not None: + rl.unload_render_texture(self._render_texture) + self._render_texture = None rl.close_window() def render(self): - while not rl.window_should_close(): - rl.begin_drawing() - rl.clear_background(rl.BLACK) - - yield - - if DEBUG_FPS: - rl.draw_fps(10, 10) - - rl.end_drawing() - self._monitor_fps() - - def font(self, font_wight: FontWeight=FontWeight.NORMAL): - return self._fonts[font_wight] + try: + while not (self._window_close_requested or rl.window_should_close()): + if self._render_texture: + rl.begin_texture_mode(self._render_texture) + rl.clear_background(rl.BLACK) + else: + rl.begin_drawing() + rl.clear_background(rl.BLACK) + + yield + + if self._render_texture: + rl.end_texture_mode() + rl.begin_drawing() + rl.clear_background(rl.BLACK) + src_rect = rl.Rectangle(0, 0, float(self._width), -float(self._height)) + dst_rect = rl.Rectangle(0, 0, float(self._scaled_width), float(self._scaled_height)) + rl.draw_texture_pro(self._render_texture.texture, src_rect, dst_rect, rl.Vector2(0, 0), 0.0, rl.WHITE) + + if DEBUG_FPS: + rl.draw_fps(10, 10) + + rl.end_drawing() + self._monitor_fps() + except KeyboardInterrupt: + pass + + def font(self, font_weight: FontWeight = FontWeight.NORMAL): + return self._fonts[font_weight] @property def width(self): @@ -98,21 +179,34 @@ class GuiApplication: def _load_fonts(self): font_files = ( - "Inter-Black.ttf", - "Inter-Bold.ttf", - "Inter-ExtraBold.ttf", + "Inter-Thin.ttf", "Inter-ExtraLight.ttf", - "Inter-Medium.ttf", + "Inter-Light.ttf", "Inter-Regular.ttf", + "Inter-Medium.ttf", "Inter-SemiBold.ttf", - "Inter-Thin.ttf" - ) + "Inter-Bold.ttf", + "Inter-ExtraBold.ttf", + "Inter-Black.ttf", + ) + + # Create a character set from our keyboard layouts + from openpilot.system.ui.widgets.keyboard import KEYBOARD_LAYOUTS + all_chars = set() + for layout in KEYBOARD_LAYOUTS.values(): + all_chars.update(key for row in layout for key in row) + all_chars = "".join(all_chars) + + codepoint_count = rl.ffi.new("int *", 1) + codepoints = rl.load_codepoints(all_chars, codepoint_count) for index, font_file in enumerate(font_files): - font = rl.load_font_ex(os.path.join(FONT_DIR, font_file), 120, None, 0) - rl.set_texture_filter(font.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) - self._fonts[index] = font + with as_file(FONT_DIR.joinpath(font_file)) as fspath: + font = rl.load_font_ex(fspath.as_posix(), 120, codepoints, codepoint_count[0]) + rl.set_texture_filter(font.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) + self._fonts[index] = font + rl.unload_codepoints(codepoints) rl.gui_set_font(self._fonts[FontWeight.NORMAL]) def _set_styles(self): @@ -120,9 +214,31 @@ class GuiApplication: rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiDefaultProperty.TEXT_SIZE, DEFAULT_TEXT_SIZE) rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiDefaultProperty.BACKGROUND_COLOR, rl.color_to_int(rl.BLACK)) rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.TEXT_COLOR_NORMAL, rl.color_to_int(DEFAULT_TEXT_COLOR)) - rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiDefaultProperty.BACKGROUND_COLOR, rl.color_to_int(rl.Color(30, 30, 30, 255))) rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.BASE_COLOR_NORMAL, rl.color_to_int(rl.Color(50, 50, 50, 255))) + def _set_log_callback(self): + @rl.ffi.callback("void(int, char *, void *)") + def trace_log_callback(log_level, text, args): + try: + text_str = rl.ffi.string(text).decode('utf-8') + except (TypeError, UnicodeDecodeError): + text_str = str(text) + + if log_level == rl.TraceLogLevel.LOG_ERROR: + cloudlog.error(f"raylib: {text_str}") + elif log_level == rl.TraceLogLevel.LOG_WARNING: + cloudlog.warning(f"raylib: {text_str}") + elif log_level == rl.TraceLogLevel.LOG_INFO: + cloudlog.info(f"raylib: {text_str}") + elif log_level == rl.TraceLogLevel.LOG_DEBUG: + cloudlog.debug(f"raylib: {text_str}") + else: + cloudlog.error(f"raylib: Unknown level {log_level}: {text_str}") + + # Store callback reference + self._trace_log_callback = trace_log_callback + rl.set_trace_log_callback(self._trace_log_callback) + def _monitor_fps(self): fps = rl.get_fps() diff --git a/system/ui/lib/button.py b/system/ui/lib/button.py index 034189275f..9ca82c9732 100644 --- a/system/ui/lib/button.py +++ b/system/ui/lib/button.py @@ -8,11 +8,21 @@ class ButtonStyle(IntEnum): PRIMARY = 1 # For main actions DANGER = 2 # For critical actions, like reboot or delete TRANSPARENT = 3 # For buttons with transparent background and border + ACTION = 4 +class TextAlignment(IntEnum): + LEFT = 0 + CENTER = 1 + RIGHT = 2 + + +ICON_PADDING = 15 DEFAULT_BUTTON_FONT_SIZE = 60 BUTTON_ENABLED_TEXT_COLOR = rl.Color(228, 228, 228, 255) BUTTON_DISABLED_TEXT_COLOR = rl.Color(228, 228, 228, 51) +ACTION_BUTTON_FONT_SIZE = 48 +ACTION_BUTTON_TEXT_COLOR = rl.Color(0, 0, 0, 255) BUTTON_BACKGROUND_COLORS = { @@ -20,6 +30,7 @@ BUTTON_BACKGROUND_COLORS = { ButtonStyle.PRIMARY: rl.Color(70, 91, 234, 255), ButtonStyle.DANGER: rl.Color(255, 36, 36, 255), ButtonStyle.TRANSPARENT: rl.BLACK, + ButtonStyle.ACTION: rl.Color(189, 189, 189, 255), } BUTTON_PRESSED_BACKGROUND_COLORS = { @@ -27,8 +38,11 @@ BUTTON_PRESSED_BACKGROUND_COLORS = { ButtonStyle.PRIMARY: rl.Color(48, 73, 244, 255), ButtonStyle.DANGER: rl.Color(255, 36, 36, 255), ButtonStyle.TRANSPARENT: rl.BLACK, + ButtonStyle.ACTION: rl.Color(130, 130, 130, 255), } +_pressed_buttons: set[str] = set() # Track mouse press state globally + def gui_button( rect: rl.Rectangle, @@ -38,16 +52,42 @@ def gui_button( button_style: ButtonStyle = ButtonStyle.NORMAL, is_enabled: bool = True, border_radius: int = 10, # Corner rounding in pixels + text_alignment: TextAlignment = TextAlignment.CENTER, + text_padding: int = 20, # Padding for left/right alignment + icon=None, ) -> int: + button_id = f"{rect.x}_{rect.y}_{rect.width}_{rect.height}" result = 0 + if button_style in (ButtonStyle.PRIMARY, ButtonStyle.DANGER) and not is_enabled: + button_style = ButtonStyle.NORMAL + + if button_style == ButtonStyle.ACTION and font_size == DEFAULT_BUTTON_FONT_SIZE: + font_size = ACTION_BUTTON_FONT_SIZE + # Set background color based on button type bg_color = BUTTON_BACKGROUND_COLORS[button_style] - if is_enabled and rl.check_collision_point_rec(rl.get_mouse_position(), rect): - if rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT): + mouse_over = is_enabled and rl.check_collision_point_rec(rl.get_mouse_position(), rect) + is_pressed = button_id in _pressed_buttons + + if mouse_over: + if rl.is_mouse_button_pressed(rl.MouseButton.MOUSE_BUTTON_LEFT): + # Only this button enters pressed state + _pressed_buttons.add(button_id) + is_pressed = True + + # Use pressed color when mouse is down over this button + if is_pressed and rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT): bg_color = BUTTON_PRESSED_BACKGROUND_COLORS[button_style] - elif rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT): + + # Handle button click + if rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT) and is_pressed: result = 1 + _pressed_buttons.remove(button_id) + + # Clean up pressed state if mouse is released anywhere + if rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT) and button_id in _pressed_buttons: + _pressed_buttons.remove(button_id) # Draw the button with rounded corners roundness = border_radius / (min(rect.width, rect.height) / 2) @@ -57,15 +97,42 @@ def gui_button( rl.draw_rectangle_rounded(rect, roundness, 20, rl.BLACK) rl.draw_rectangle_rounded_lines_ex(rect, roundness, 20, 2, rl.WHITE) + # Handle icon and text positioning font = gui_app.font(font_weight) - # Center text in the button text_size = rl.measure_text_ex(font, text, font_size, 0) - text_pos = rl.Vector2( - rect.x + (rect.width - text_size.x) // 2, rect.y + (rect.height - text_size.y) // 2 - ) + text_pos = rl.Vector2(0, rect.y + (rect.height - text_size.y) // 2) # Vertical centering + + # Draw icon if provided + if icon: + icon_y = rect.y + (rect.height - icon.height) / 2 + if text: + if text_alignment == TextAlignment.LEFT: + icon_x = rect.x + text_padding + text_pos.x = icon_x + icon.width + ICON_PADDING + elif text_alignment == TextAlignment.CENTER: + total_width = icon.width + ICON_PADDING + text_size.x + icon_x = rect.x + (rect.width - total_width) / 2 + text_pos.x = icon_x + icon.width + ICON_PADDING + else: # RIGHT + text_pos.x = rect.x + rect.width - text_size.x - text_padding + icon_x = text_pos.x - ICON_PADDING - icon.width + else: + # Center icon when no text + icon_x = rect.x + (rect.width - icon.width) / 2 + + rl.draw_texture_v(icon, rl.Vector2(icon_x, icon_y), rl.WHITE if is_enabled else rl.Color(255, 255, 255, 100)) + else: + # No icon, position text normally + if text_alignment == TextAlignment.LEFT: + text_pos.x = rect.x + text_padding + elif text_alignment == TextAlignment.CENTER: + text_pos.x = rect.x + (rect.width - text_size.x) // 2 + elif text_alignment == TextAlignment.RIGHT: + text_pos.x = rect.x + rect.width - text_size.x - text_padding - # Draw the button text - text_color = BUTTON_ENABLED_TEXT_COLOR if is_enabled else BUTTON_DISABLED_TEXT_COLOR - rl.draw_text_ex(font, text, text_pos, font_size, 0, text_color) + # Draw the button text if any + if text: + text_color = ACTION_BUTTON_TEXT_COLOR if button_style == ButtonStyle.ACTION else BUTTON_ENABLED_TEXT_COLOR if is_enabled else BUTTON_DISABLED_TEXT_COLOR + rl.draw_text_ex(font, text, text_pos, font_size, 0, text_color) return result diff --git a/system/ui/lib/inputbox.py b/system/ui/lib/inputbox.py new file mode 100644 index 0000000000..367e0dc7e4 --- /dev/null +++ b/system/ui/lib/inputbox.py @@ -0,0 +1,232 @@ +import pyray as rl +import time +from openpilot.system.ui.lib.application import gui_app + + +PASSWORD_MASK_CHAR = "•" +PASSWORD_MASK_DELAY = 1.5 # Seconds to show character before masking + + +class InputBox: + def __init__(self, max_text_size=255, password_mode=False): + self._max_text_size = max_text_size + self._input_text = "" + self._cursor_position = 0 + self._password_mode = password_mode + self._blink_counter = 0 + self._show_cursor = False + self._last_key_pressed = 0 + self._key_press_time = 0 + self._repeat_delay = 30 + self._repeat_rate = 4 + self._text_offset = 0 + self._visible_width = 0 + self._last_char_time = 0 # Track when last character was added + self._masked_length = 0 # How many characters are currently masked + + @property + def text(self): + return self._input_text + + @text.setter + def text(self, value): + self._input_text = value[: self._max_text_size] + self._cursor_position = len(self._input_text) + self._update_text_offset() + + def set_password_mode(self, password_mode): + self._password_mode = password_mode + + def clear(self): + self._input_text = '' + self._cursor_position = 0 + self._text_offset = 0 + + def set_cursor_position(self, position): + """Set the cursor position and reset the blink counter.""" + if 0 <= position <= len(self._input_text): + self._cursor_position = position + self._blink_counter = 0 + self._show_cursor = True + self._update_text_offset() + + def _update_text_offset(self): + """Ensure the cursor is visible by adjusting text offset.""" + if self._visible_width == 0: + return + + font = gui_app.font() + display_text = self._get_display_text() + padding = 10 + + if self._cursor_position > 0: + cursor_x = rl.measure_text_ex(font, display_text[: self._cursor_position], self._font_size, 0).x + else: + cursor_x = 0 + + visible_width = self._visible_width - (padding * 2) + + # Adjust offset if cursor would be outside visible area + if cursor_x < self._text_offset: + self._text_offset = max(0, cursor_x - padding) + elif cursor_x > self._text_offset + visible_width: + self._text_offset = cursor_x - visible_width + padding + + def add_char_at_cursor(self, char): + """Add a character at the current cursor position.""" + if len(self._input_text) < self._max_text_size: + self._input_text = self._input_text[: self._cursor_position] + char + self._input_text[self._cursor_position :] + self.set_cursor_position(self._cursor_position + 1) + + if self._password_mode: + self._last_char_time = time.time() + + return True + return False + + def delete_char_before_cursor(self): + """Delete the character before the cursor position (backspace).""" + if self._cursor_position > 0: + self._input_text = self._input_text[: self._cursor_position - 1] + self._input_text[self._cursor_position :] + self.set_cursor_position(self._cursor_position - 1) + return True + return False + + def delete_char_at_cursor(self): + """Delete the character at the cursor position (delete).""" + if self._cursor_position < len(self._input_text): + self._input_text = self._input_text[: self._cursor_position] + self._input_text[self._cursor_position + 1 :] + self.set_cursor_position(self._cursor_position) + return True + return False + + def render(self, rect, color=rl.BLACK, border_color=rl.DARKGRAY, text_color=rl.WHITE, font_size=80): + # Store dimensions for text offset calculations + self._visible_width = rect.width + self._font_size = font_size + + # Handle mouse input + self._handle_mouse_input(rect, font_size) + + # Draw input box + rl.draw_rectangle_rec(rect, color) + + # Process keyboard input + self._handle_keyboard_input() + + # Update cursor blink + self._blink_counter += 1 + if self._blink_counter >= 30: + self._show_cursor = not self._show_cursor + self._blink_counter = 0 + + # Display text + font = gui_app.font() + display_text = self._get_display_text() + padding = 10 + + # Clip text within input box bounds + buffer = 2 + rl.begin_scissor_mode(int(rect.x + padding - buffer), int(rect.y), int(rect.width - padding * 2 + buffer * 2), int(rect.height)) + rl.draw_text_ex( + font, + display_text, + rl.Vector2(int(rect.x + padding - self._text_offset), int(rect.y + rect.height / 2 - font_size / 2)), + font_size, + 0, + text_color, + ) + + # Draw cursor + if self._show_cursor: + cursor_x = rect.x + padding + if len(display_text) > 0 and self._cursor_position > 0: + cursor_x += rl.measure_text_ex(font, display_text[: self._cursor_position], font_size, 0).x + + # Apply text offset to cursor position + cursor_x -= self._text_offset + + cursor_height = font_size + 4 + cursor_y = rect.y + rect.height / 2 - cursor_height / 2 + rl.draw_line(int(cursor_x), int(cursor_y), int(cursor_x), int(cursor_y + cursor_height), rl.WHITE) + + rl.end_scissor_mode() + + def _get_display_text(self): + """Get text to display, applying password masking with delay if needed.""" + if not self._password_mode: + return self._input_text + + # Show character at last edited position if within delay window + masked_text = PASSWORD_MASK_CHAR * len(self._input_text) + recent_edit = time.time() - self._last_char_time < PASSWORD_MASK_DELAY + if recent_edit and self._input_text: + last_pos = max(0, self._cursor_position - 1) + if last_pos < len(self._input_text): + return masked_text[:last_pos] + self._input_text[last_pos] + masked_text[last_pos + 1 :] + + return masked_text + + def _handle_mouse_input(self, rect, font_size): + """Handle mouse clicks to position cursor.""" + mouse_pos = rl.get_mouse_position() + if rl.is_mouse_button_pressed(rl.MOUSE_LEFT_BUTTON) and rl.check_collision_point_rec(mouse_pos, rect): + # Calculate cursor position from click + if len(self._input_text) > 0: + font = gui_app.font() + display_text = self._get_display_text() + + # Find the closest character position to the click + relative_x = mouse_pos.x - (rect.x + 10) + self._text_offset + best_pos = 0 + min_distance = float('inf') + + for i in range(len(self._input_text) + 1): + char_width = rl.measure_text_ex(font, display_text[:i], font_size, 0).x + distance = abs(relative_x - char_width) + if distance < min_distance: + min_distance = distance + best_pos = i + + self.set_cursor_position(best_pos) + else: + self.set_cursor_position(0) + + def _handle_keyboard_input(self): + # Handle navigation keys + key = rl.get_key_pressed() + if key != 0: + self._process_key(key) + if key in (rl.KEY_LEFT, rl.KEY_RIGHT, rl.KEY_BACKSPACE, rl.KEY_DELETE): + self._last_key_pressed = key + self._key_press_time = 0 + + # Handle repeats for held keys + elif self._last_key_pressed != 0: + if rl.is_key_down(self._last_key_pressed): + self._key_press_time += 1 + if self._key_press_time > self._repeat_delay and self._key_press_time % self._repeat_rate == 0: + self._process_key(self._last_key_pressed) + else: + self._last_key_pressed = 0 + + # Handle text input + char = rl.get_char_pressed() + if char != 0 and char >= 32: # Filter out control characters + self.add_char_at_cursor(chr(char)) + + def _process_key(self, key): + if key == rl.KEY_LEFT: + if self._cursor_position > 0: + self.set_cursor_position(self._cursor_position - 1) + elif key == rl.KEY_RIGHT: + if self._cursor_position < len(self._input_text): + self.set_cursor_position(self._cursor_position + 1) + elif key == rl.KEY_BACKSPACE: + self.delete_char_before_cursor() + elif key == rl.KEY_DELETE: + self.delete_char_at_cursor() + elif key == rl.KEY_HOME: + self.set_cursor_position(0) + elif key == rl.KEY_END: + self.set_cursor_position(len(self._input_text)) diff --git a/system/ui/lib/label.py b/system/ui/lib/label.py index ccfd89a2ec..5244c6baf2 100644 --- a/system/ui/lib/label.py +++ b/system/ui/lib/label.py @@ -10,13 +10,27 @@ def gui_label( color: rl.Color = DEFAULT_TEXT_COLOR, font_weight: FontWeight = FontWeight.NORMAL, alignment: int = rl.GuiTextAlignment.TEXT_ALIGN_LEFT, - alignment_vertical: int = rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE + alignment_vertical: int = rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE, + elide_right: bool = True ): - # Set font based on the provided weight font = gui_app.font(font_weight) - - # Measure text size text_size = rl.measure_text_ex(font, text, font_size, 0) + display_text = text + + # Elide text to fit within the rectangle + if elide_right and text_size.x > rect.width: + ellipsis = "..." + left, right = 0, len(text) + while left < right: + mid = (left + right) // 2 + candidate = text[:mid] + ellipsis + candidate_size = rl.measure_text_ex(font, candidate, font_size, 0) + if candidate_size.x <= rect.width: + left = mid + 1 + else: + right = mid + display_text = text[: left - 1] + ellipsis if left > 0 else ellipsis + text_size = rl.measure_text_ex(font, display_text, font_size, 0) # Calculate horizontal position based on alignment text_x = rect.x + { @@ -33,7 +47,7 @@ def gui_label( }.get(alignment_vertical, 0) # Draw the text in the specified rectangle - rl.draw_text_ex(font, text, rl.Vector2(text_x, text_y), font_size, 0, color) + rl.draw_text_ex(font, display_text, rl.Vector2(text_x, text_y), font_size, 0, color) def gui_text_box( diff --git a/system/ui/lib/scroll_panel.py b/system/ui/lib/scroll_panel.py index 0dc757ff6f..43111504bb 100644 --- a/system/ui/lib/scroll_panel.py +++ b/system/ui/lib/scroll_panel.py @@ -1,32 +1,61 @@ import pyray as rl from enum import IntEnum +# Scroll constants for smooth scrolling behavior MOUSE_WHEEL_SCROLL_SPEED = 30 -INERTIA_FRICTION = 0.95 # The rate at which the inertia slows down -MIN_VELOCITY = 0.1 # Minimum velocity before stopping the inertia +INERTIA_FRICTION = 0.92 # The rate at which the inertia slows down +MIN_VELOCITY = 0.5 # Minimum velocity before stopping the inertia +DRAG_THRESHOLD = 5 # Pixels of movement to consider it a drag, not a click +BOUNCE_FACTOR = 0.2 # Elastic bounce when scrolling past boundaries +BOUNCE_RETURN_SPEED = 0.15 # How quickly it returns from the bounce +MAX_BOUNCE_DISTANCE = 150 # Maximum distance for bounce effect +FLICK_MULTIPLIER = 1.8 # Multiplier for flick gestures +VELOCITY_HISTORY_SIZE = 5 # Track velocity over multiple frames for smoother motion class ScrollState(IntEnum): IDLE = 0 DRAGGING_CONTENT = 1 DRAGGING_SCROLLBAR = 2 + BOUNCING = 3 class GuiScrollPanel: def __init__(self, show_vertical_scroll_bar: bool = False): self._scroll_state: ScrollState = ScrollState.IDLE self._last_mouse_y: float = 0.0 + self._start_mouse_y: float = 0.0 # Track the initial mouse position for drag detection self._offset = rl.Vector2(0, 0) self._view = rl.Rectangle(0, 0, 0, 0) self._show_vertical_scroll_bar: bool = show_vertical_scroll_bar self._velocity_y = 0.0 # Velocity for inertia + self._is_dragging: bool = False + self._bounce_offset: float = 0.0 + self._last_frame_time = rl.get_time() + self._velocity_history: list[float] = [] + self._last_drag_time: float = 0.0 + self._content_rect: rl.Rectangle | None = None + self._bounds_rect: rl.Rectangle | None = None def handle_scroll(self, bounds: rl.Rectangle, content: rl.Rectangle) -> rl.Vector2: + # Store rectangles for reference + self._content_rect = content + self._bounds_rect = bounds + + # Calculate time delta + current_time = rl.get_time() + delta_time = current_time - self._last_frame_time + self._last_frame_time = current_time + + # Prevent large jumps + delta_time = min(delta_time, 0.05) + mouse_pos = rl.get_mouse_position() + max_scroll_y = max(content.height - bounds.height, 0) - # Handle dragging logic + # Start dragging on mouse press if rl.check_collision_point_rec(mouse_pos, bounds) and rl.is_mouse_button_pressed(rl.MouseButton.MOUSE_BUTTON_LEFT): - if self._scroll_state == ScrollState.IDLE: + if self._scroll_state == ScrollState.IDLE or self._scroll_state == ScrollState.BOUNCING: self._scroll_state = ScrollState.DRAGGING_CONTENT if self._show_vertical_scroll_bar: scrollbar_width = rl.gui_get_style(rl.GuiControl.LISTVIEW, rl.GuiListViewProperty.SCROLLBAR_WIDTH) @@ -35,41 +64,133 @@ class GuiScrollPanel: self._scroll_state = ScrollState.DRAGGING_SCROLLBAR self._last_mouse_y = mouse_pos.y - self._velocity_y = 0.0 # Reset velocity when drag starts + self._start_mouse_y = mouse_pos.y + self._last_drag_time = current_time + self._velocity_history = [] + self._velocity_y = 0.0 + self._bounce_offset = 0.0 + self._is_dragging = False - if self._scroll_state != ScrollState.IDLE: + # Handle active dragging + if self._scroll_state == ScrollState.DRAGGING_CONTENT or self._scroll_state == ScrollState.DRAGGING_SCROLLBAR: if rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT): delta_y = mouse_pos.y - self._last_mouse_y + # Track velocity for inertia + time_since_last_drag = current_time - self._last_drag_time + if time_since_last_drag > 0: + drag_velocity = delta_y / time_since_last_drag / 60.0 + self._velocity_history.append(drag_velocity) + + if len(self._velocity_history) > VELOCITY_HISTORY_SIZE: + self._velocity_history.pop(0) + + self._last_drag_time = current_time + + # Detect actual dragging + total_drag = abs(mouse_pos.y - self._start_mouse_y) + if total_drag > DRAG_THRESHOLD: + self._is_dragging = True + if self._scroll_state == ScrollState.DRAGGING_CONTENT: + # Add resistance at boundaries + if (self._offset.y > 0 and delta_y > 0) or (self._offset.y < -max_scroll_y and delta_y < 0): + delta_y *= BOUNCE_FACTOR + self._offset.y += delta_y - else: - delta_y = -delta_y + elif self._scroll_state == ScrollState.DRAGGING_SCROLLBAR: + scroll_ratio = content.height / bounds.height + self._offset.y -= delta_y * scroll_ratio self._last_mouse_y = mouse_pos.y - self._velocity_y = delta_y # Update velocity during drag - else: - self._scroll_state = ScrollState.IDLE - # Handle mouse wheel scrolling + elif rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT): + # Calculate flick velocity + if self._velocity_history: + total_weight = 0 + weighted_velocity = 0.0 + + for i, v in enumerate(self._velocity_history): + weight = i + 1 + weighted_velocity += v * weight + total_weight += weight + + if total_weight > 0: + avg_velocity = weighted_velocity / total_weight + self._velocity_y = avg_velocity * FLICK_MULTIPLIER + + # Check bounds + if self._offset.y > 0 or self._offset.y < -max_scroll_y: + self._scroll_state = ScrollState.BOUNCING + else: + self._scroll_state = ScrollState.IDLE + + # Handle mouse wheel wheel_move = rl.get_mouse_wheel_move() - if self._show_vertical_scroll_bar: - self._offset.y += wheel_move * (MOUSE_WHEEL_SCROLL_SPEED - 20) - rl.gui_scroll_panel(bounds, rl.ffi.NULL, content, self._offset, self._view) - else: - self._offset.y += wheel_move * MOUSE_WHEEL_SCROLL_SPEED + if wheel_move != 0: + self._velocity_y = 0.0 + + if self._show_vertical_scroll_bar: + self._offset.y += wheel_move * (MOUSE_WHEEL_SCROLL_SPEED - 20) + rl.gui_scroll_panel(bounds, rl.ffi.NULL, content, self._offset, self._view) + else: + self._offset.y += wheel_move * MOUSE_WHEEL_SCROLL_SPEED + + if self._offset.y > 0 or self._offset.y < -max_scroll_y: + self._scroll_state = ScrollState.BOUNCING # Apply inertia (continue scrolling after mouse release) if self._scroll_state == ScrollState.IDLE: - self._offset.y += self._velocity_y - self._velocity_y *= INERTIA_FRICTION # Slow down velocity over time + if abs(self._velocity_y) > MIN_VELOCITY: + self._offset.y += self._velocity_y + self._velocity_y *= INERTIA_FRICTION + + if self._offset.y > 0 or self._offset.y < -max_scroll_y: + self._scroll_state = ScrollState.BOUNCING + else: + self._velocity_y = 0.0 + + # Handle bouncing effect + elif self._scroll_state == ScrollState.BOUNCING: + target_y = 0.0 + if self._offset.y < -max_scroll_y: + target_y = -max_scroll_y + + distance = target_y - self._offset.y + bounce_step = distance * BOUNCE_RETURN_SPEED + self._offset.y += bounce_step + self._velocity_y *= INERTIA_FRICTION * 0.8 - # Stop scrolling when velocity is low - if abs(self._velocity_y) < MIN_VELOCITY: + if abs(distance) < 0.5 and abs(self._velocity_y) < MIN_VELOCITY: + self._offset.y = target_y self._velocity_y = 0.0 + self._scroll_state = ScrollState.IDLE - # Ensure scrolling doesn't go beyond bounds - max_scroll_y = max(content.height - bounds.height, 0) - self._offset.y = max(min(self._offset.y, 0), -max_scroll_y) + # Limit bounce distance + if self._scroll_state != ScrollState.DRAGGING_CONTENT: + if self._offset.y > MAX_BOUNCE_DISTANCE: + self._offset.y = MAX_BOUNCE_DISTANCE + elif self._offset.y < -(max_scroll_y + MAX_BOUNCE_DISTANCE): + self._offset.y = -(max_scroll_y + MAX_BOUNCE_DISTANCE) return self._offset + + def is_click_valid(self) -> bool: + # Check if this is a click rather than a drag + return ( + self._scroll_state == ScrollState.IDLE + and not self._is_dragging + and rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT) + ) + + def get_normalized_scroll_position(self) -> float: + """Returns the current scroll position as a value from 0.0 to 1.0""" + if not self._content_rect or not self._bounds_rect: + return 0.0 + + max_scroll_y = max(self._content_rect.height - self._bounds_rect.height, 0) + if max_scroll_y == 0: + return 0.0 + + normalized = -self._offset.y / max_scroll_y + return max(0.0, min(1.0, normalized)) diff --git a/system/ui/lib/toggle.py b/system/ui/lib/toggle.py new file mode 100644 index 0000000000..e72faef11c --- /dev/null +++ b/system/ui/lib/toggle.py @@ -0,0 +1,53 @@ +import pyray as rl + +ON_COLOR = rl.GREEN +OFF_COLOR = rl.Color(0x39, 0x39, 0x39, 255) +KNOB_COLOR = rl.WHITE +BG_HEIGHT = 60 +KNOB_HEIGHT = 80 +WIDTH = 160 + + +class Toggle: + def __init__(self, x, y, initial_state=False): + self._state = initial_state + self._rect = rl.Rectangle(x, y, WIDTH, KNOB_HEIGHT) + + def handle_input(self): + if rl.is_mouse_button_pressed(rl.MOUSE_LEFT_BUTTON): + mouse_pos = rl.get_mouse_position() + if rl.check_collision_point_rec(mouse_pos, self._rect): + self._state = not self._state + + def get_state(self): + return self._state + + def render(self): + self._draw_background() + self._draw_knob() + + def _draw_background(self): + bg_rect = rl.Rectangle( + self._rect.x + 5, + self._rect.y + (KNOB_HEIGHT - BG_HEIGHT) / 2, + self._rect.width - 10, + BG_HEIGHT, + ) + rl.draw_rectangle_rounded(bg_rect, 1.0, 10, ON_COLOR if self._state else OFF_COLOR) + + def _draw_knob(self): + knob_radius = KNOB_HEIGHT / 2 + knob_x = self._rect.x + knob_radius if not self._state else self._rect.x + self._rect.width - knob_radius + knob_y = self._rect.y + knob_radius + rl.draw_circle(int(knob_x), int(knob_y), knob_radius, KNOB_COLOR) + + +if __name__ == "__main__": + from openpilot.system.ui.lib.application import gui_app + + gui_app.init_window("Text toggle example") + toggle = Toggle(100, 100) + for _ in gui_app.render(): + toggle.handle_input() + toggle.render() + diff --git a/system/ui/lib/wifi_manager.py b/system/ui/lib/wifi_manager.py new file mode 100644 index 0000000000..96726bd999 --- /dev/null +++ b/system/ui/lib/wifi_manager.py @@ -0,0 +1,711 @@ +import asyncio +import concurrent.futures +import copy +import threading +import time +import uuid +from collections.abc import Callable +from dataclasses import dataclass +from enum import IntEnum +from typing import TypeVar + +from dbus_next.aio import MessageBus +from dbus_next import BusType, Variant, Message +from dbus_next.errors import DBusError +from dbus_next.constants import MessageType +try: + from openpilot.common.params import Params +except ImportError: + # Params/Cythonized modules are not available in zipapp + Params = None +from openpilot.common.swaglog import cloudlog + +T = TypeVar("T") + +# NetworkManager constants +NM = "org.freedesktop.NetworkManager" +NM_PATH = '/org/freedesktop/NetworkManager' +NM_IFACE = 'org.freedesktop.NetworkManager' +NM_SETTINGS_PATH = '/org/freedesktop/NetworkManager/Settings' +NM_SETTINGS_IFACE = 'org.freedesktop.NetworkManager.Settings' +NM_CONNECTION_IFACE = 'org.freedesktop.NetworkManager.Settings.Connection' +NM_WIRELESS_IFACE = 'org.freedesktop.NetworkManager.Device.Wireless' +NM_PROPERTIES_IFACE = 'org.freedesktop.DBus.Properties' +NM_DEVICE_IFACE = "org.freedesktop.NetworkManager.Device" + +NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT = 8 + +TETHERING_IP_ADDRESS = "192.168.43.1" +DEFAULT_TETHERING_PASSWORD = "12345678" + +# NetworkManager device states +class NMDeviceState(IntEnum): + DISCONNECTED = 30 + PREPARE = 40 + NEED_AUTH = 60 + IP_CONFIG = 70 + ACTIVATED = 100 + +class SecurityType(IntEnum): + OPEN = 0 + WPA = 1 + WPA2 = 2 + WPA3 = 3 + UNSUPPORTED = 4 + +@dataclass +class NetworkInfo: + ssid: str + strength: int + is_connected: bool + security_type: SecurityType + path: str + bssid: str + is_saved: bool = False + # saved_path: str + + +@dataclass +class WifiManagerCallbacks: + need_auth: Callable[[str], None] | None = None + activated: Callable[[], None] | None = None + forgotten: Callable[[], None] | None = None + networks_updated: Callable[[list[NetworkInfo]], None] | None = None + + +class WifiManager: + def __init__(self, callbacks): + self.callbacks: WifiManagerCallbacks = callbacks + self.networks: list[NetworkInfo] = [] + self.bus: MessageBus = None + self.device_path: str = "" + self.device_proxy = None + self.saved_connections: dict[str, str] = {} + self.active_ap_path: str = "" + self.scan_task: asyncio.Task | None = None + # Set tethering ssid as "weedle" + first 4 characters of a dongle id + self._tethering_ssid = "weedle" + if Params is not None: + dongle_id = Params().get("DongleId", encoding="utf-8") + if dongle_id: + self._tethering_ssid += "-" + dongle_id[:4] + self.running: bool = True + self._current_connection_ssid: str | None = None + + async def connect(self) -> None: + """Connect to the DBus system bus.""" + try: + self.bus = await MessageBus(bus_type=BusType.SYSTEM).connect() + if not await self._find_wifi_device(): + raise ValueError("No Wi-Fi device found") + await self._setup_signals(self.device_path) + + self.active_ap_path = await self.get_active_access_point() + await self.add_tethering_connection(self._tethering_ssid, DEFAULT_TETHERING_PASSWORD) + self.saved_connections = await self._get_saved_connections() + self.scan_task = asyncio.create_task(self._periodic_scan()) + except DBusError as e: + cloudlog.error(f"Failed to connect to DBus: {e}") + raise + except Exception as e: + cloudlog.error(f"Unexpected error during connect: {e}") + raise + + async def shutdown(self) -> None: + self.running = False + if self.scan_task: + self.scan_task.cancel() + try: + await self.scan_task + except asyncio.CancelledError: + pass + if self.bus: + self.bus.disconnect() + + async def request_scan(self) -> None: + try: + interface = self.device_proxy.get_interface(NM_WIRELESS_IFACE) + await interface.call_request_scan({}) + except DBusError as e: + cloudlog.warning(f"Scan request failed: {str(e)}") + + async def get_active_access_point(self): + try: + props_iface = self.device_proxy.get_interface(NM_PROPERTIES_IFACE) + ap_path = await props_iface.call_get(NM_WIRELESS_IFACE, 'ActiveAccessPoint') + return ap_path.value + except DBusError as e: + cloudlog.error(f"Error fetching active access point: {str(e)}") + return '' + + async def forget_connection(self, ssid: str) -> bool: + path = self.saved_connections.get(ssid) + if not path: + return False + + try: + nm_iface = await self._get_interface(NM, path, NM_CONNECTION_IFACE) + await nm_iface.call_delete() + if self._current_connection_ssid == ssid: + self._current_connection_ssid = None + + if ssid in self.saved_connections: + del self.saved_connections[ssid] + + return True + except DBusError as e: + cloudlog.error(f"Failed to delete connection for SSID: {ssid}. Error: {e}") + return False + + async def activate_connection(self, ssid: str) -> bool: + connection_path = self.saved_connections.get(ssid) + if not connection_path: + return False + try: + nm_iface = await self._get_interface(NM, NM_PATH, NM_IFACE) + await nm_iface.call_activate_connection(connection_path, self.device_path, "/") + return True + except DBusError as e: + cloudlog.error(f"Failed to activate connection {ssid}: {str(e)}") + return False + + async def connect_to_network(self, ssid: str, password: str = None, bssid: str = None, is_hidden: bool = False) -> None: + """Connect to a selected Wi-Fi network.""" + try: + self._current_connection_ssid = ssid + + if ssid in self.saved_connections: + # Forget old connection if new password provided + if password: + await self.forget_connection(ssid) + await asyncio.sleep(0.2) # NetworkManager delay + else: + # Just activate existing connection + await self.activate_connection(ssid) + return + + connection = { + 'connection': { + 'type': Variant('s', '802-11-wireless'), + 'uuid': Variant('s', str(uuid.uuid4())), + 'id': Variant('s', ssid), + 'autoconnect-retries': Variant('i', 0), + }, + '802-11-wireless': { + 'ssid': Variant('ay', ssid.encode('utf-8')), + 'hidden': Variant('b', is_hidden), + 'mode': Variant('s', 'infrastructure'), + }, + 'ipv4': {'method': Variant('s', 'auto')}, + 'ipv6': {'method': Variant('s', 'ignore')}, + } + + if bssid: + connection['802-11-wireless']['bssid'] = Variant('ay', bssid.encode('utf-8')) + + if password: + connection['802-11-wireless-security'] = { + 'key-mgmt': Variant('s', 'wpa-psk'), + 'auth-alg': Variant('s', 'open'), + 'psk': Variant('s', password), + } + + nm_iface = await self._get_interface(NM, NM_PATH, NM_IFACE) + await nm_iface.call_add_and_activate_connection(connection, self.device_path, "/") + await self._update_connection_status() + except DBusError as e: + self._current_connection_ssid = None + cloudlog.error(f"Error connecting to network: {e}") + + def is_saved(self, ssid: str) -> bool: + return ssid in self.saved_connections + + async def _find_wifi_device(self) -> bool: + nm_iface = await self._get_interface(NM, NM_PATH, NM_IFACE) + devices = await nm_iface.get_devices() + + for device_path in devices: + device = await self.bus.introspect(NM, device_path) + device_proxy = self.bus.get_proxy_object(NM, device_path, device) + device_interface = device_proxy.get_interface(NM_DEVICE_IFACE) + device_type = await device_interface.get_device_type() # type: ignore[attr-defined] + if device_type == 2: # Wi-Fi device + self.device_path = device_path + self.device_proxy = device_proxy + return True + + return False + + async def add_tethering_connection(self, ssid: str, password: str = "12345678") -> bool: + """Create a WiFi tethering connection.""" + if len(password) < 8: + print("Tethering password must be at least 8 characters") + return False + + try: + # First, check if a hotspot connection already exists + settings_iface = await self._get_interface(NM, NM_SETTINGS_PATH, NM_SETTINGS_IFACE) + connection_paths = await settings_iface.call_list_connections() + + # Look for an existing hotspot connection + for path in connection_paths: + try: + settings = await self._get_connection_settings(path) + conn_type = settings.get('connection', {}).get('type', Variant('s', '')).value + wifi_mode = settings.get('802-11-wireless', {}).get('mode', Variant('s', '')).value + + if conn_type == '802-11-wireless' and wifi_mode == 'ap': + # Extract the SSID to check + connection_ssid = self._extract_ssid(settings) + if connection_ssid == ssid: + return True + except DBusError: + continue + + connection = { + 'connection': { + 'id': Variant('s', 'Hotspot'), + 'uuid': Variant('s', str(uuid.uuid4())), + 'type': Variant('s', '802-11-wireless'), + 'interface-name': Variant('s', 'wlan0'), + 'autoconnect': Variant('b', False), + }, + '802-11-wireless': { + 'band': Variant('s', 'bg'), + 'mode': Variant('s', 'ap'), + 'ssid': Variant('ay', ssid.encode('utf-8')), + }, + '802-11-wireless-security': { + 'group': Variant('as', ['ccmp']), + 'key-mgmt': Variant('s', 'wpa-psk'), + 'pairwise': Variant('as', ['ccmp']), + 'proto': Variant('as', ['rsn']), + 'psk': Variant('s', password), + }, + 'ipv4': { + 'method': Variant('s', 'shared'), + 'address-data': Variant('aa{sv}', [{'address': Variant('s', TETHERING_IP_ADDRESS), 'prefix': Variant('u', 24)}]), + 'gateway': Variant('s', TETHERING_IP_ADDRESS), + 'never-default': Variant('b', True), + }, + 'ipv6': { + 'method': Variant('s', 'ignore'), + }, + } + + settings_iface = await self._get_interface(NM, NM_SETTINGS_PATH, NM_SETTINGS_IFACE) + new_connection = await settings_iface.call_add_connection(connection) + print(f"Added tethering connection with path: {new_connection}") + return True + except DBusError as e: + print(f"Failed to add tethering connection: {e}") + return False + except Exception as e: + print(f"Unexpected error adding tethering connection: {e}") + return False + + async def get_tethering_password(self) -> str: + """Get the current tethering password.""" + try: + hotspot_path = self.saved_connections.get(self._tethering_ssid) + if hotspot_path: + conn_iface = await self._get_interface(NM, hotspot_path, NM_CONNECTION_IFACE) + secrets = await conn_iface.call_get_secrets('802-11-wireless-security') + if secrets and '802-11-wireless-security' in secrets: + psk = secrets.get('802-11-wireless-security', {}).get('psk', Variant('s', '')).value + return str(psk) if psk is not None else "" + return "" + except DBusError as e: + print(f"Failed to get tethering password: {e}") + return "" + except Exception as e: + print(f"Unexpected error getting tethering password: {e}") + return "" + + async def set_tethering_password(self, password: str) -> bool: + """Set the tethering password.""" + if len(password) < 8: + cloudlog.error("Tethering password must be at least 8 characters") + return False + + try: + hotspot_path = self.saved_connections.get(self._tethering_ssid) + if not hotspot_path: + print("No hotspot connection found") + return False + + # Update the connection settings with new password + settings = await self._get_connection_settings(hotspot_path) + if '802-11-wireless-security' not in settings: + settings['802-11-wireless-security'] = {} + settings['802-11-wireless-security']['psk'] = Variant('s', password) + + # Apply changes + conn_iface = await self._get_interface(NM, hotspot_path, NM_CONNECTION_IFACE) + await conn_iface.call_update(settings) + + # Check if connection is active and restart if needed + is_active = False + nm_iface = await self._get_interface(NM, NM_PATH, NM_IFACE) + active_connections = await nm_iface.get_active_connections() + + for conn_path in active_connections: + props_iface = await self._get_interface(NM, conn_path, NM_PROPERTIES_IFACE) + conn_id_path = await props_iface.call_get('org.freedesktop.NetworkManager.Connection.Active', 'Connection') + if conn_id_path.value == hotspot_path: + is_active = True + await nm_iface.call_deactivate_connection(conn_path) + break + + if is_active: + await nm_iface.call_activate_connection(hotspot_path, self.device_path, "/") + + print("Tethering password updated successfully") + return True + except DBusError as e: + print(f"Failed to set tethering password: {e}") + return False + except Exception as e: + print(f"Unexpected error setting tethering password: {e}") + return False + + async def is_tethering_active(self) -> bool: + """Check if tethering is active for the specified SSID.""" + try: + hotspot_path = self.saved_connections.get(self._tethering_ssid) + if not hotspot_path: + return False + + nm_iface = await self._get_interface(NM, NM_PATH, NM_IFACE) + active_connections = await nm_iface.get_active_connections() + + for conn_path in active_connections: + props_iface = await self._get_interface(NM, conn_path, NM_PROPERTIES_IFACE) + conn_id_path = await props_iface.call_get('org.freedesktop.NetworkManager.Connection.Active', 'Connection') + + if conn_id_path.value == hotspot_path: + return True + + return False + except Exception: + return False + + async def _periodic_scan(self): + while self.running: + try: + await self.request_scan() + await self._get_available_networks() + await asyncio.sleep(30) + except asyncio.CancelledError: + break + except DBusError as e: + cloudlog.error(f"Scan failed: {e}") + await asyncio.sleep(5) + + async def _setup_signals(self, device_path: str) -> None: + rules = [ + f"type='signal',interface='{NM_PROPERTIES_IFACE}',member='PropertiesChanged',path='{device_path}'", + f"type='signal',interface='{NM_DEVICE_IFACE}',member='StateChanged',path='{device_path}'", + f"type='signal',interface='{NM_SETTINGS_IFACE}',member='NewConnection',path='{NM_SETTINGS_PATH}'", + f"type='signal',interface='{NM_SETTINGS_IFACE}',member='ConnectionRemoved',path='{NM_SETTINGS_PATH}'", + ] + for rule in rules: + await self._add_match_rule(rule) + + # Set up signal handlers + self.device_proxy.get_interface(NM_PROPERTIES_IFACE).on_properties_changed(self._on_properties_changed) + self.device_proxy.get_interface(NM_DEVICE_IFACE).on_state_changed(self._on_state_changed) + + settings_iface = await self._get_interface(NM, NM_SETTINGS_PATH, NM_SETTINGS_IFACE) + settings_iface.on_new_connection(self._on_new_connection) + settings_iface.on_connection_removed(self._on_connection_removed) + + def _on_properties_changed(self, interface: str, changed: dict, invalidated: list): + # print("property changed", interface, changed, invalidated) + if 'LastScan' in changed: + asyncio.create_task(self._get_available_networks()) + elif interface == NM_WIRELESS_IFACE and "ActiveAccessPoint" in changed: + self.active_ap_path = changed["ActiveAccessPoint"].value + asyncio.create_task(self._get_available_networks()) + + def _on_state_changed(self, new_state: int, old_state: int, reason: int): + print(f"State changed: {old_state} -> {new_state}, reason: {reason}") + if new_state == NMDeviceState.ACTIVATED: + if self.callbacks.activated: + self.callbacks.activated() + asyncio.create_task(self._update_connection_status()) + self._current_connection_ssid = None + elif new_state in (NMDeviceState.DISCONNECTED, NMDeviceState.NEED_AUTH): + for network in self.networks: + network.is_connected = False + if new_state == NMDeviceState.NEED_AUTH and reason == NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT and self.callbacks.need_auth: + if self._current_connection_ssid: + self.callbacks.need_auth(self._current_connection_ssid) + else: + # Try to find the network from active_ap_path + for network in self.networks: + if network.path == self.active_ap_path: + self.callbacks.need_auth(network.ssid) + break + else: + # Couldn't identify the network that needs auth + cloudlog.error("Network needs authentication but couldn't identify which one") + + def _on_new_connection(self, path: str) -> None: + """Callback for NewConnection signal.""" + print(f"New connection added: {path}") + asyncio.create_task(self._add_saved_connection(path)) + + def _on_connection_removed(self, path: str) -> None: + """Callback for ConnectionRemoved signal.""" + print(f"Connection removed: {path}") + for ssid, p in list(self.saved_connections.items()): + if path == p: + del self.saved_connections[ssid] + if self.callbacks.forgotten: + self.callbacks.forgotten() + # Update network list to reflect the removed saved connection + asyncio.create_task(self._update_connection_status()) + break + + async def _add_saved_connection(self, path: str) -> None: + """Add a new saved connection to the dictionary.""" + try: + settings = await self._get_connection_settings(path) + if ssid := self._extract_ssid(settings): + self.saved_connections[ssid] = path + await self._update_connection_status() + except DBusError as e: + cloudlog.error(f"Failed to add connection {path}: {e}") + + def _extract_ssid(self, settings: dict) -> str | None: + """Extract SSID from connection settings.""" + ssid_variant = settings.get('802-11-wireless', {}).get('ssid', Variant('ay', b'')).value + return ''.join(chr(b) for b in ssid_variant) if ssid_variant else None + + async def _update_connection_status(self): + self.active_ap_path = await self.get_active_access_point() + await self._get_available_networks() + + async def _add_match_rule(self, rule): + """Add a match rule on the bus.""" + reply = await self.bus.call( + Message( + message_type=MessageType.METHOD_CALL, + destination='org.freedesktop.DBus', + interface="org.freedesktop.DBus", + path='/org/freedesktop/DBus', + member='AddMatch', + signature='s', + body=[rule], + ) + ) + + assert reply.message_type == MessageType.METHOD_RETURN + return reply + + async def _get_available_networks(self): + """Get a list of available networks via NetworkManager.""" + wifi_iface = self.device_proxy.get_interface(NM_WIRELESS_IFACE) + access_points = await wifi_iface.get_access_points() + network_dict = {} + for ap_path in access_points: + try: + props_iface = await self._get_interface(NM, ap_path, NM_PROPERTIES_IFACE) + properties = await props_iface.call_get_all('org.freedesktop.NetworkManager.AccessPoint') + ssid_variant = properties['Ssid'].value + ssid = ''.join(chr(byte) for byte in ssid_variant) + if not ssid: + continue + + bssid = properties.get('HwAddress', Variant('s', '')).value + strength = properties['Strength'].value + flags = properties['Flags'].value + wpa_flags = properties['WpaFlags'].value + rsn_flags = properties['RsnFlags'].value + existing_network = network_dict.get(ssid) + if not existing_network or ((not existing_network.bssid and bssid) or (existing_network.strength < strength)): + network_dict[ssid] = NetworkInfo( + ssid=ssid, + strength=strength, + security_type=self._get_security_type(flags, wpa_flags, rsn_flags), + path=ap_path, + bssid=bssid, + is_connected=self.active_ap_path == ap_path, + is_saved=ssid in self.saved_connections + ) + + except DBusError as e: + cloudlog.error(f"Error fetching networks: {e}") + except Exception as e: + cloudlog.error({e}) + + self.networks = sorted( + network_dict.values(), + key=lambda network: ( + not network.is_connected, + -network.strength, # Higher signal strength first + network.ssid.lower(), + ), + ) + + if self.callbacks.networks_updated: + self.callbacks.networks_updated(copy.deepcopy(self.networks)) + + async def _get_connection_settings(self, path): + """Fetch connection settings for a specific connection path.""" + try: + connection_proxy = await self.bus.introspect(NM, path) + connection = self.bus.get_proxy_object(NM, path, connection_proxy) + settings = connection.get_interface(NM_CONNECTION_IFACE) + return await settings.call_get_settings() + except DBusError as e: + cloudlog.error(f"Failed to get settings for {path}: {str(e)}") + return {} + + async def _process_chunk(self, paths_chunk): + """Process a chunk of connection paths.""" + tasks = [self._get_connection_settings(path) for path in paths_chunk] + return await asyncio.gather(*tasks, return_exceptions=True) + + async def _get_saved_connections(self) -> dict[str, str]: + try: + settings_iface = await self._get_interface(NM, NM_SETTINGS_PATH, NM_SETTINGS_IFACE) + connection_paths = await settings_iface.call_list_connections() + saved_ssids: dict[str, str] = {} + batch_size = 20 + for i in range(0, len(connection_paths), batch_size): + chunk = connection_paths[i : i + batch_size] + results = await self._process_chunk(chunk) + for path, config in zip(chunk, results, strict=True): + if isinstance(config, dict) and '802-11-wireless' in config: + if ssid := self._extract_ssid(config): + saved_ssids[ssid] = path + return saved_ssids + except DBusError as e: + cloudlog.error(f"Error fetching saved connections: {str(e)}") + return {} + + async def _get_interface(self, bus_name: str, path: str, name: str): + introspection = await self.bus.introspect(bus_name, path) + proxy = self.bus.get_proxy_object(bus_name, path, introspection) + return proxy.get_interface(name) + + def _get_security_type(self, flags: int, wpa_flags: int, rsn_flags: int) -> SecurityType: + """Determine the security type based on flags.""" + if flags == 0 and not (wpa_flags or rsn_flags): + return SecurityType.OPEN + if rsn_flags & 0x200: # SAE (WPA3 Personal) + # TODO: support WPA3 + return SecurityType.UNSUPPORTED + if rsn_flags: # RSN indicates WPA2 or higher + return SecurityType.WPA2 + if wpa_flags: # WPA flags indicate WPA + return SecurityType.WPA + return SecurityType.UNSUPPORTED + + +class WifiManagerWrapper: + def __init__(self): + self._manager: WifiManager | None = None + self._callbacks: WifiManagerCallbacks = WifiManagerCallbacks() + + self._thread = threading.Thread(target=self._run, daemon=True) + self._loop: asyncio.EventLoop | None = None + self._running = False + + def set_callbacks(self, callbacks: WifiManagerCallbacks): + self._callbacks = callbacks + + def start(self) -> None: + if not self._running: + self._thread.start() + while self._thread is not None and not self._running: + time.sleep(0.1) + + def _run(self): + self._loop = asyncio.new_event_loop() + asyncio.set_event_loop(self._loop) + + try: + self._manager = WifiManager(self._callbacks) + self._running = True + self._loop.run_forever() + except Exception as e: + cloudlog.error(f"Error in WifiManagerWrapper thread: {e}") + finally: + if self._loop.is_running(): + self._loop.stop() + self._running = False + + def shutdown(self) -> None: + if self._running: + if self._manager is not None and self._loop: + shutdown_future = asyncio.run_coroutine_threadsafe(self._manager.shutdown(), self._loop) + shutdown_future.result(timeout=3.0) + + if self._loop and self._loop.is_running(): + self._loop.call_soon_threadsafe(self._loop.stop) + if self._thread and self._thread.is_alive(): + self._thread.join(timeout=2.0) + self._running = False + + def is_saved(self, ssid: str) -> bool: + """Check if a network is saved.""" + return self._run_coroutine_sync(lambda manager: manager.is_saved(ssid), default=False) + + def connect(self): + """Connect to DBus and start Wi-Fi scanning.""" + if not self._manager: + return + self._run_coroutine(self._manager.connect()) + + def request_scan(self): + """Request a scan for Wi-Fi networks.""" + if not self._manager: + return + self._run_coroutine(self._manager.request_scan()) + + def forget_connection(self, ssid: str): + """Forget a saved Wi-Fi connection.""" + if not self._manager: + return + self._run_coroutine(self._manager.forget_connection(ssid)) + + def activate_connection(self, ssid: str): + """Activate an existing Wi-Fi connection.""" + if not self._manager: + return + self._run_coroutine(self._manager.activate_connection(ssid)) + + def connect_to_network(self, ssid: str, password: str = None, bssid: str = None, is_hidden: bool = False): + """Connect to a Wi-Fi network.""" + if not self._manager: + return + self._run_coroutine(self._manager.connect_to_network(ssid, password, bssid, is_hidden)) + + def _run_coroutine(self, coro): + """Run a coroutine in the async thread.""" + if not self._running or not self._loop: + cloudlog.error("WifiManager thread is not running") + return + asyncio.run_coroutine_threadsafe(coro, self._loop) + + def _run_coroutine_sync(self, func: Callable[[WifiManager], T], default: T) -> T: + """Run a function synchronously in the async thread.""" + if not self._running or not self._loop or not self._manager: + return default + future = concurrent.futures.Future[T]() + + def wrapper(manager: WifiManager) -> None: + try: + future.set_result(func(manager)) + except Exception as e: + future.set_exception(e) + + try: + self._loop.call_soon_threadsafe(wrapper, self._manager) + return future.result(timeout=1.0) + except Exception as e: + cloudlog.error(f"WifiManagerWrapper property access failed: {e}") + return default diff --git a/system/ui/lib/window.py b/system/ui/lib/window.py new file mode 100644 index 0000000000..989a3b0284 --- /dev/null +++ b/system/ui/lib/window.py @@ -0,0 +1,58 @@ +import threading +import time +import os +from typing import Generic, Protocol, TypeVar +from openpilot.common.swaglog import cloudlog +from openpilot.system.ui.lib.application import gui_app + + +class RendererProtocol(Protocol): + def render(self): ... + + +R = TypeVar("R", bound=RendererProtocol) + + +class BaseWindow(Generic[R]): + def __init__(self, title: str): + self._title = title + self._renderer: R | None = None + self._stop_event = threading.Event() + self._thread = threading.Thread(target=self._run) + self._thread.start() + + # wait for the renderer to be initialized + while self._renderer is None and self._thread.is_alive(): + time.sleep(0.01) + + def _create_renderer(self) -> R: + raise NotImplementedError() + + def _run(self): + if os.getenv("CI") is not None: + return + gui_app.init_window(self._title) + self._renderer = self._create_renderer() + try: + for _ in gui_app.render(): + if self._stop_event.is_set(): + break + self._renderer.render() + finally: + gui_app.close() + + def __enter__(self): + return self + + def close(self): + if self._thread.is_alive(): + self._stop_event.set() + self._thread.join(timeout=2.0) + if self._thread.is_alive(): + cloudlog.warning(f"Failed to join {self._title} thread") + + def __del__(self): + self.close() + + def __exit__(self, exc_type, exc_val, exc_tb): + self.close() diff --git a/system/ui/reset.py b/system/ui/reset.py index 80a1c10ea8..20b689934b 100755 --- a/system/ui/reset.py +++ b/system/ui/reset.py @@ -5,6 +5,7 @@ import sys import threading from enum import IntEnum +from openpilot.system.hardware import PC from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.button import gui_button, ButtonStyle from openpilot.system.ui.lib.label import gui_label, gui_text_box @@ -31,7 +32,10 @@ class Reset: self.mode = mode self.reset_state = ResetState.NONE - def do_reset(self): + def _do_erase(self): + if PC: + return + # Best effort to wipe NVME os.system(f"sudo umount {NVME}") os.system(f"yes | sudo mkfs.ext4 {NVME}") @@ -48,7 +52,7 @@ class Reset: def start_reset(self): self.reset_state = ResetState.RESETTING - threading.Timer(0.1, self.do_reset).start() + threading.Timer(0.1, self._do_erase).start() def render(self, rect: rl.Rectangle): label_rect = rl.Rectangle(rect.x + 140, rect.y, rect.width - 280, 100) diff --git a/system/ui/setup.py b/system/ui/setup.py new file mode 100755 index 0000000000..0ec5d6395e --- /dev/null +++ b/system/ui/setup.py @@ -0,0 +1,349 @@ +#!/usr/bin/env python3 +import os +import re +import threading +import time +import urllib.request +from enum import IntEnum +import pyray as rl + +from cereal import log +from openpilot.system.hardware import HARDWARE +from openpilot.system.ui.lib.application import gui_app, FontWeight +from openpilot.system.ui.lib.button import gui_button, ButtonStyle +from openpilot.system.ui.lib.label import gui_label, gui_text_box +from openpilot.system.ui.widgets.network import WifiManagerUI, WifiManagerWrapper +from openpilot.system.ui.widgets.keyboard import Keyboard + +NetworkType = log.DeviceState.NetworkType + +MARGIN = 50 +TITLE_FONT_SIZE = 116 +TITLE_FONT_WEIGHT = FontWeight.MEDIUM +NEXT_BUTTON_WIDTH = 310 +BODY_FONT_SIZE = 96 +BUTTON_HEIGHT = 160 +BUTTON_SPACING = 50 + +OPENPILOT_URL = "https://openpilot.comma.ai" +USER_AGENT = f"AGNOSSetup-{HARDWARE.get_os_version()}" + + +class SetupState(IntEnum): + LOW_VOLTAGE = 0 + GETTING_STARTED = 1 + NETWORK_SETUP = 2 + SOFTWARE_SELECTION = 3 + CUSTOM_URL = 4 + DOWNLOADING = 5 + DOWNLOAD_FAILED = 6 + + +class Setup: + def __init__(self): + self.state = SetupState.GETTING_STARTED + self.network_check_thread = None + self.network_connected = threading.Event() + self.wifi_connected = threading.Event() + self.stop_network_check_thread = threading.Event() + self.failed_url = "" + self.failed_reason = "" + self.download_url = "" + self.download_progress = 0 + self.download_thread = None + self.wifi_manager = WifiManagerWrapper() + self.wifi_ui = WifiManagerUI(self.wifi_manager) + self.keyboard = Keyboard() + self.selected_radio = None + + self.warning = gui_app.texture("icons/warning.png", 150, 150) + self.checkmark = gui_app.texture("icons/circled_check.png", 100, 100) + + try: + with open("/sys/class/hwmon/hwmon1/in1_input") as f: + voltage = float(f.read().strip()) / 1000.0 + if voltage < 7: + self.state = SetupState.LOW_VOLTAGE + except (FileNotFoundError, ValueError): + self.state = SetupState.LOW_VOLTAGE + + def render(self, rect: rl.Rectangle): + if self.state == SetupState.LOW_VOLTAGE: + self.render_low_voltage(rect) + elif self.state == SetupState.GETTING_STARTED: + self.render_getting_started(rect) + elif self.state == SetupState.NETWORK_SETUP: + self.render_network_setup(rect) + elif self.state == SetupState.SOFTWARE_SELECTION: + self.render_software_selection(rect) + elif self.state == SetupState.CUSTOM_URL: + self.render_custom_url() + elif self.state == SetupState.DOWNLOADING: + self.render_downloading(rect) + elif self.state == SetupState.DOWNLOAD_FAILED: + self.render_download_failed(rect) + + def render_low_voltage(self, rect: rl.Rectangle): + rl.draw_texture(self.warning, int(rect.x + 150), int(rect.y + 110), rl.WHITE) + + title_rect = rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 100, rect.width - 500 - 150, TITLE_FONT_SIZE) + gui_label(title_rect, "WARNING: Low Voltage", TITLE_FONT_SIZE, rl.Color(255, 89, 79, 255), FontWeight.MEDIUM) + + body_rect = rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 100 + TITLE_FONT_SIZE + 25, rect.width - 500 - 150, BODY_FONT_SIZE * 3) + gui_text_box(body_rect, "Power your device in a car with a harness or proceed at your own risk.", BODY_FONT_SIZE) + + button_width = (rect.width - MARGIN * 3) / 2 + button_y = rect.height - MARGIN - BUTTON_HEIGHT + + if gui_button(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT), "Power off"): + HARDWARE.shutdown() + + if gui_button(rl.Rectangle(rect.x + MARGIN * 2 + button_width, button_y, button_width, BUTTON_HEIGHT), "Continue"): + self.state = SetupState.GETTING_STARTED + + def render_getting_started(self, rect: rl.Rectangle): + title_rect = rl.Rectangle(rect.x + 165, rect.y + 280, rect.width - 265, TITLE_FONT_SIZE) + gui_label(title_rect, "Getting Started", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + + desc_rect = rl.Rectangle(rect.x + 165, rect.y + 280 + TITLE_FONT_SIZE + 90, rect.width - 500, BODY_FONT_SIZE * 3) + gui_text_box(desc_rect, "Before we get on the road, let's finish installation and cover some details.", BODY_FONT_SIZE) + + btn_rect = rl.Rectangle(rect.width - NEXT_BUTTON_WIDTH, 0, NEXT_BUTTON_WIDTH, rect.height) + + ret = gui_button(btn_rect, "", button_style=ButtonStyle.PRIMARY, border_radius=0) + triangle = gui_app.texture("images/button_continue_triangle.png", 54, int(btn_rect.height)) + rl.draw_texture_v(triangle, rl.Vector2(btn_rect.x + btn_rect.width / 2 - triangle.width / 2, btn_rect.height / 2 - triangle.height / 2), rl.WHITE) + + if ret: + self.state = SetupState.NETWORK_SETUP + self.wifi_manager.request_scan() + self.start_network_check() + + def check_network_connectivity(self): + while not self.stop_network_check_thread.is_set(): + if self.state == SetupState.NETWORK_SETUP: + try: + urllib.request.urlopen(OPENPILOT_URL, timeout=2) + self.network_connected.set() + if HARDWARE.get_network_type() == NetworkType.wifi: + self.wifi_connected.set() + else: + self.wifi_connected.clear() + except Exception: + self.network_connected.clear() + time.sleep(1) + + def start_network_check(self): + if self.network_check_thread is None or not self.network_check_thread.is_alive(): + self.network_check_thread = threading.Thread(target=self.check_network_connectivity, daemon=True) + self.network_check_thread.start() + + def close(self): + if self.network_check_thread is not None: + self.stop_network_check_thread.set() + self.network_check_thread.join() + + def render_network_setup(self, rect: rl.Rectangle): + if self.wifi_ui.require_full_screen: + self.wifi_ui.render(rect) + return + + title_rect = rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE) + gui_label(title_rect, "Connect to Wi-Fi", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + + wifi_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN + 25, rect.width - MARGIN * 2, + rect.height - TITLE_FONT_SIZE - 25 - BUTTON_HEIGHT - MARGIN * 3) + rl.draw_rectangle_rounded(wifi_rect, 0.05, 10, rl.Color(51, 51, 51, 255)) + wifi_content_rect = rl.Rectangle(wifi_rect.x + MARGIN, wifi_rect.y, wifi_rect.width - MARGIN * 2, wifi_rect.height) + self.wifi_ui.render(wifi_content_rect) + + button_width = (rect.width - BUTTON_SPACING - MARGIN * 2) / 2 + button_y = rect.height - BUTTON_HEIGHT - MARGIN + + if gui_button(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT), "Back"): + self.state = SetupState.GETTING_STARTED + + # Check network connectivity status + continue_enabled = self.network_connected.is_set() + continue_text = ("Continue" if self.wifi_connected.is_set() else "Continue without Wi-Fi") if continue_enabled else "Waiting for internet" + + if gui_button( + rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT), + continue_text, + button_style=ButtonStyle.PRIMARY if continue_enabled else ButtonStyle.NORMAL, + is_enabled=continue_enabled, + ): + self.state = SetupState.SOFTWARE_SELECTION + self.stop_network_check_thread.set() + + def render_software_selection(self, rect: rl.Rectangle): + title_rect = rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE) + gui_label(title_rect, "Choose Software to Install", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + + radio_height = 230 + radio_spacing = 30 + + openpilot_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN * 2, rect.width - MARGIN * 2, radio_height) + openpilot_selected = self.selected_radio == "openpilot" + + rl.draw_rectangle_rounded(openpilot_rect, 0.1, 10, rl.Color(70, 91, 234, 255) if openpilot_selected else rl.Color(79, 79, 79, 255)) + gui_label(rl.Rectangle(openpilot_rect.x + 100, openpilot_rect.y, openpilot_rect.width - 200, radio_height), "openpilot", BODY_FONT_SIZE) + + if openpilot_selected: + checkmark_pos = rl.Vector2(openpilot_rect.x + openpilot_rect.width - 100 - self.checkmark.width, + openpilot_rect.y + radio_height / 2 - self.checkmark.height / 2) + rl.draw_texture_v(self.checkmark, checkmark_pos, rl.WHITE) + + custom_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN * 2 + radio_height + radio_spacing, rect.width - MARGIN * 2, radio_height) + custom_selected = self.selected_radio == "custom" + + rl.draw_rectangle_rounded(custom_rect, 0.1, 10, rl.Color(70, 91, 234, 255) if custom_selected else rl.Color(79, 79, 79, 255)) + gui_label(rl.Rectangle(custom_rect.x + 100, custom_rect.y, custom_rect.width - 200, radio_height), "Custom Software", BODY_FONT_SIZE) + + if custom_selected: + checkmark_pos = rl.Vector2(custom_rect.x + custom_rect.width - 100 - self.checkmark.width, custom_rect.y + radio_height / 2 - self.checkmark.height / 2) + rl.draw_texture_v(self.checkmark, checkmark_pos, rl.WHITE) + + mouse_pos = rl.get_mouse_position() + if rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT): + if rl.check_collision_point_rec(mouse_pos, openpilot_rect): + self.selected_radio = "openpilot" + elif rl.check_collision_point_rec(mouse_pos, custom_rect): + self.selected_radio = "custom" + + button_width = (rect.width - BUTTON_SPACING - MARGIN * 2) / 2 + button_y = rect.height - BUTTON_HEIGHT - MARGIN + + if gui_button(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT), "Back"): + self.state = SetupState.NETWORK_SETUP + + continue_enabled = self.selected_radio is not None + if gui_button( + rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT), + "Continue", + button_style=ButtonStyle.PRIMARY, + is_enabled=continue_enabled, + ): + if continue_enabled: + if self.selected_radio == "openpilot": + self.download(OPENPILOT_URL) + else: + self.state = SetupState.CUSTOM_URL + + def render_downloading(self, rect: rl.Rectangle): + title_rect = rl.Rectangle(rect.x, rect.y + rect.height / 2 - TITLE_FONT_SIZE / 2, rect.width, TITLE_FONT_SIZE) + gui_label(title_rect, "Downloading...", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) + + def render_download_failed(self, rect: rl.Rectangle): + title_rect = rl.Rectangle(rect.x + 117, rect.y + 185, rect.width - 117, TITLE_FONT_SIZE) + gui_label(title_rect, "Download Failed", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + + url_rect = rl.Rectangle(rect.x + 117, rect.y + 185 + TITLE_FONT_SIZE + 67, rect.width - 117 - 100, 64) + gui_label(url_rect, self.failed_url, 64, font_weight=FontWeight.NORMAL) + + error_rect = rl.Rectangle(rect.x + 117, rect.y + 185 + TITLE_FONT_SIZE + 67 + 64 + 48, + rect.width - 117 - 100, rect.height - 185 + TITLE_FONT_SIZE + 67 + 64 + 48 - BUTTON_HEIGHT - MARGIN * 2) + gui_text_box(error_rect, self.failed_reason, BODY_FONT_SIZE) + + button_width = (rect.width - BUTTON_SPACING - MARGIN * 2) / 2 + button_y = rect.height - BUTTON_HEIGHT - MARGIN + + if gui_button(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT), "Reboot device"): + HARDWARE.reboot() + + if gui_button(rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT), "Start over", + button_style=ButtonStyle.PRIMARY): + self.state = SetupState.GETTING_STARTED + + def render_custom_url(self): + result = self.keyboard.render("Enter URL", "for Custom Software") + + # Enter pressed + if result == 1: + url = self.keyboard.text + self.keyboard.clear() + if url: + self.download(url) + + # Cancel pressed + elif result == 0: + self.state = SetupState.SOFTWARE_SELECTION + + def download(self, url: str): + # autocomplete incomplete URLs + if re.match("^([^/.]+)/([^/]+)$", url): + url = f"https://installer.comma.ai/{url}" + + self.download_url = url + self.state = SetupState.DOWNLOADING + + self.download_thread = threading.Thread(target=self._download_thread, daemon=True) + self.download_thread.start() + + def _download_thread(self): + try: + import tempfile + + _, tmpfile = tempfile.mkstemp(prefix="installer_") + + headers = {"User-Agent": USER_AGENT, "X-openpilot-serial": HARDWARE.get_serial()} + req = urllib.request.Request(self.download_url, headers=headers) + + with open(tmpfile, 'wb') as f, urllib.request.urlopen(req, timeout=30) as response: + total_size = int(response.headers.get('content-length', 0)) + downloaded = 0 + block_size = 8192 + + while True: + buffer = response.read(block_size) + if not buffer: + break + + downloaded += len(buffer) + f.write(buffer) + + if total_size: + self.download_progress = int(downloaded * 100 / total_size) + + is_elf = False + with open(tmpfile, 'rb') as f: + header = f.read(4) + is_elf = header == b'\x7fELF' + + if not is_elf: + self.download_failed(self.download_url, "No custom software found at this URL.") + return + + os.rename(tmpfile, "/tmp/installer") + os.chmod("/tmp/installer", 0o755) + + with open("/tmp/installer_url", "w") as f: + f.write(self.download_url) + + gui_app.request_close() + + except Exception: + error_msg = "Ensure the entered URL is valid, and the device's internet connection is good." + self.download_failed(self.download_url, error_msg) + + def download_failed(self, url: str, reason: str): + self.failed_url = url + self.failed_reason = reason + self.state = SetupState.DOWNLOAD_FAILED + + +def main(): + try: + gui_app.init_window("Setup") + setup = Setup() + for _ in gui_app.render(): + setup.render(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) + setup.close() + except Exception as e: + print(f"Setup error: {e}") + finally: + gui_app.close() + + +if __name__ == "__main__": + main() diff --git a/system/ui/spinner.py b/system/ui/spinner.py index 639de26744..2af24c4e51 100755 --- a/system/ui/spinner.py +++ b/system/ui/spinner.py @@ -1,75 +1,107 @@ #!/usr/bin/env python3 import pyray as rl -import os -import select -import sys +import threading +import time -from openpilot.common.basedir import BASEDIR from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.lib.window import BaseWindow +from openpilot.system.ui.text import wrap_text # Constants PROGRESS_BAR_WIDTH = 1000 PROGRESS_BAR_HEIGHT = 20 -ROTATION_TIME_SECONDS = 1.0 # Time for one full circle -MARGIN = 200 +DEGREES_PER_SECOND = 360.0 # one full rotation per second +MARGIN_H = 100 TEXTURE_SIZE = 360 -FONT_SIZE = 80 +FONT_SIZE = 96 +LINE_HEIGHT = 104 +DARKGRAY = (55, 55, 55, 255) def clamp(value, min_value, max_value): return max(min(value, max_value), min_value) -def check_input_non_blocking(): - if sys.stdin in select.select([sys.stdin], [], [], 0)[0]: - return sys.stdin.readline().strip() - return "" +class SpinnerRenderer: + def __init__(self): + self._comma_texture = gui_app.texture("images/spinner_comma.png", TEXTURE_SIZE, TEXTURE_SIZE) + self._spinner_texture = gui_app.texture("images/spinner_track.png", TEXTURE_SIZE, TEXTURE_SIZE, alpha_premultiply=True) + self._rotation = 0.0 + self._progress: int | None = None + self._wrapped_lines: list[str] = [] + self._lock = threading.Lock() + + def set_text(self, text: str) -> None: + with self._lock: + if text.isdigit(): + self._progress = clamp(int(text), 0, 100) + self._wrapped_lines = [] + else: + self._progress = None + self._wrapped_lines = wrap_text(text, FONT_SIZE, gui_app.width - MARGIN_H) + + def render(self): + with self._lock: + progress = self._progress + wrapped_lines = self._wrapped_lines + + if wrapped_lines: + # Calculate total height required for spinner and text + spacing = 50 + total_height = TEXTURE_SIZE + spacing + len(wrapped_lines) * LINE_HEIGHT + center_y = (gui_app.height - total_height) / 2.0 + TEXTURE_SIZE / 2.0 + else: + # Center spinner vertically + spacing = 150 + center_y = gui_app.height / 2.0 + y_pos = center_y + TEXTURE_SIZE / 2.0 + spacing + + center = rl.Vector2(gui_app.width / 2.0, center_y) + spinner_origin = rl.Vector2(TEXTURE_SIZE / 2.0, TEXTURE_SIZE / 2.0) + comma_position = rl.Vector2(center.x - TEXTURE_SIZE / 2.0, center.y - TEXTURE_SIZE / 2.0) + + delta_time = rl.get_frame_time() + self._rotation = (self._rotation + DEGREES_PER_SECOND * delta_time) % 360.0 + # Draw rotating spinner and static comma logo + rl.draw_texture_pro(self._spinner_texture, rl.Rectangle(0, 0, TEXTURE_SIZE, TEXTURE_SIZE), + rl.Rectangle(center.x, center.y, TEXTURE_SIZE, TEXTURE_SIZE), + spinner_origin, self._rotation, rl.WHITE) + rl.draw_texture_v(self._comma_texture, comma_position, rl.WHITE) -def main(): - gui_app.init_window("Spinner") + # Display the progress bar or text based on user input + if progress is not None: + bar = rl.Rectangle(center.x - PROGRESS_BAR_WIDTH / 2.0, y_pos, PROGRESS_BAR_WIDTH, PROGRESS_BAR_HEIGHT) + rl.draw_rectangle_rounded(bar, 1, 10, DARKGRAY) - # Load textures - comma_texture = gui_app.load_texture_from_image(os.path.join(BASEDIR, "selfdrive/assets/img_spinner_comma.png"), TEXTURE_SIZE, TEXTURE_SIZE) - spinner_texture = gui_app.load_texture_from_image(os.path.join(BASEDIR, "selfdrive/assets/img_spinner_track.png"), TEXTURE_SIZE, TEXTURE_SIZE) + bar.width *= progress / 100.0 + rl.draw_rectangle_rounded(bar, 1, 10, rl.WHITE) + elif wrapped_lines: + for i, line in enumerate(wrapped_lines): + text_size = rl.measure_text_ex(gui_app.font(), line, FONT_SIZE, 0.0) + rl.draw_text_ex(gui_app.font(), line, rl.Vector2(center.x - text_size.x / 2, y_pos + i * LINE_HEIGHT), + FONT_SIZE, 0.0, rl.WHITE) - # Initial values - rotation = 0.0 - user_input = "" - center = rl.Vector2(gui_app.width / 2.0, gui_app.height / 2.0) - spinner_origin = rl.Vector2(TEXTURE_SIZE / 2.0, TEXTURE_SIZE / 2.0) - comma_position = rl.Vector2(center.x - TEXTURE_SIZE / 2.0, center.y - TEXTURE_SIZE / 2.0) - for _ in gui_app.render(): - fps = rl.get_fps() - if fps > 0: - degrees_per_frame = 360.0 / (ROTATION_TIME_SECONDS * fps) - rotation = (rotation + degrees_per_frame) % 360.0 +class Spinner(BaseWindow[SpinnerRenderer]): + def __init__(self): + super().__init__("Spinner") - # Draw rotating spinner and static comma logo - rl.draw_texture_pro(spinner_texture, rl.Rectangle(0, 0, TEXTURE_SIZE, TEXTURE_SIZE), - rl.Rectangle(center.x, center.y, TEXTURE_SIZE, TEXTURE_SIZE), - spinner_origin, rotation, rl.WHITE) - rl.draw_texture_v(comma_texture, comma_position, rl.WHITE) - - # Read user input - if input_str := check_input_non_blocking(): - user_input = input_str - - # Display progress bar or text based on user input - if user_input: - y_pos = rl.get_screen_height() - MARGIN - PROGRESS_BAR_HEIGHT - if user_input.isdigit(): - progress = clamp(int(user_input), 0, 100) - bar = rl.Rectangle(center.x - PROGRESS_BAR_WIDTH / 2.0, y_pos, PROGRESS_BAR_WIDTH, PROGRESS_BAR_HEIGHT) - rl.draw_rectangle_rounded(bar, 0.5, 10, rl.GRAY) - - bar.width *= progress / 100.0 - rl.draw_rectangle_rounded(bar, 0.5, 10, rl.WHITE) - else: - text_size = rl.measure_text_ex(gui_app.font(), user_input, FONT_SIZE, 1.0) - rl.draw_text_ex(gui_app.font(), user_input, - rl.Vector2(center.x - text_size.x / 2, y_pos), FONT_SIZE, 1.0, rl.WHITE) + def _create_renderer(self): + return SpinnerRenderer() + + def update(self, spinner_text: str): + if self._renderer is not None: + self._renderer.set_text(spinner_text) + + def update_progress(self, cur: float, total: float): + self.update(str(round(100 * cur / total))) + + +def main(): + with Spinner() as s: + s.update("Spinner text") + time.sleep(5) if __name__ == "__main__": diff --git a/system/ui/text.py b/system/ui/text.py index 33299605d6..82e64d836f 100755 --- a/system/ui/text.py +++ b/system/ui/text.py @@ -1,16 +1,17 @@ #!/usr/bin/env python3 -import sys +import re +import time import pyray as rl - -from openpilot.system.hardware import HARDWARE +from openpilot.system.hardware import HARDWARE, PC from openpilot.system.ui.lib.button import gui_button, ButtonStyle from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.lib.window import BaseWindow MARGIN = 50 -SPACING = 50 -FONT_SIZE = 60 -LINE_HEIGHT = 64 +SPACING = 40 +FONT_SIZE = 72 +LINE_HEIGHT = 80 BUTTON_SIZE = rl.Vector2(310, 160) DEMO_TEXT = """This is a sample text that will be wrapped and scrolled if necessary. @@ -18,47 +19,73 @@ DEMO_TEXT = """This is a sample text that will be wrapped and scrolled if necess def wrap_text(text, font_size, max_width): lines = [] - current_line = "" font = gui_app.font() - for word in text.split(): - test_line = current_line + word + " " - if rl.measure_text_ex(font, test_line, font_size, 0).x <= max_width: - current_line = test_line - else: + for paragraph in text.split("\n"): + if not paragraph.strip(): + # Don't add empty lines first, ensuring wrap_text("") returns [] + if lines: + lines.append("") + continue + indent = re.match(r"^\s*", paragraph).group() + current_line = indent + words = re.split(r"(\s+)", paragraph[len(indent):]) + while len(words): + word = words.pop(0) + test_line = current_line + word + (words.pop(0) if words else "") + if rl.measure_text_ex(font, test_line, font_size, 0).x <= max_width: + current_line = test_line + else: + lines.append(current_line) + current_line = word + " " + current_line = current_line.rstrip() + if current_line: lines.append(current_line) - current_line = word + " " - if current_line: - lines.append(current_line) return lines -def main(): - gui_app.init_window("Text") +class TextWindowRenderer: + def __init__(self, text: str): + self._textarea_rect = rl.Rectangle(MARGIN, MARGIN, gui_app.width - MARGIN * 2, gui_app.height - MARGIN * 2) + self._wrapped_lines = wrap_text(text, FONT_SIZE, self._textarea_rect.width - 20) + self._content_rect = rl.Rectangle(0, 0, self._textarea_rect.width - 20, len(self._wrapped_lines) * LINE_HEIGHT) + self._scroll_panel = GuiScrollPanel(show_vertical_scroll_bar=True) + self._scroll_panel._offset.y = -max(self._content_rect.height - self._textarea_rect.height, 0) + + def render(self): + scroll = self._scroll_panel.handle_scroll(self._textarea_rect, self._content_rect) + rl.begin_scissor_mode(int(self._textarea_rect.x), int(self._textarea_rect.y), int(self._textarea_rect.width), int(self._textarea_rect.height)) + for i, line in enumerate(self._wrapped_lines): + position = rl.Vector2(self._textarea_rect.x + scroll.x, self._textarea_rect.y + scroll.y + i * LINE_HEIGHT) + if position.y + LINE_HEIGHT < self._textarea_rect.y or position.y > self._textarea_rect.y + self._textarea_rect.height: + continue + rl.draw_text_ex(gui_app.font(), line, position, FONT_SIZE, 0, rl.WHITE) + rl.end_scissor_mode() - text_content = sys.argv[1] if len(sys.argv) > 1 else DEMO_TEXT + button_bounds = rl.Rectangle(gui_app.width - MARGIN - BUTTON_SIZE.x - SPACING, gui_app.height - MARGIN - BUTTON_SIZE.y, BUTTON_SIZE.x, BUTTON_SIZE.y) + ret = gui_button(button_bounds, "Exit" if PC else "Reboot", button_style=ButtonStyle.TRANSPARENT) + if ret: + if PC: + gui_app.request_close() + else: + HARDWARE.reboot() + return ret - textarea_rect = rl.Rectangle(MARGIN, MARGIN, gui_app.width - MARGIN * 2, gui_app.height - MARGIN * 2) - wrapped_lines = wrap_text(text_content, FONT_SIZE, textarea_rect.width - 20) - content_rect = rl.Rectangle(0, 0, textarea_rect.width - 20, len(wrapped_lines) * LINE_HEIGHT) - scroll_panel = GuiScrollPanel(show_vertical_scroll_bar=True) - for _ in gui_app.render(): - scroll = scroll_panel.handle_scroll(textarea_rect, content_rect) +class TextWindow(BaseWindow[TextWindowRenderer]): + def __init__(self, text: str): + self._text = text + super().__init__("Text") - rl.begin_scissor_mode(int(textarea_rect.x), int(textarea_rect.y), int(textarea_rect.width), int(textarea_rect.height)) - for i, line in enumerate(wrapped_lines): - position = rl.Vector2(textarea_rect.x + scroll.x, textarea_rect.y + scroll.y + i * LINE_HEIGHT) - if position.y + LINE_HEIGHT < textarea_rect.y or position.y > textarea_rect.y + textarea_rect.height: - continue - rl.draw_text_ex(gui_app.font(), line.strip(), position, FONT_SIZE, 0, rl.WHITE) - rl.end_scissor_mode() + def _create_renderer(self): + return TextWindowRenderer(self._text) - button_bounds = rl.Rectangle(gui_app.width - MARGIN - BUTTON_SIZE.x, gui_app.height - MARGIN - BUTTON_SIZE.y, BUTTON_SIZE.x, BUTTON_SIZE.y) - if gui_button(button_bounds, "Reboot", button_style=ButtonStyle.TRANSPARENT): - HARDWARE.reboot() + def wait_for_exit(self): + while self._thread.is_alive(): + time.sleep(0.01) if __name__ == "__main__": - main() + with TextWindow(DEMO_TEXT): + time.sleep(30) diff --git a/system/ui/updater.py b/system/ui/updater.py new file mode 100755 index 0000000000..3ee02ce97c --- /dev/null +++ b/system/ui/updater.py @@ -0,0 +1,171 @@ +#!/usr/bin/env python3 +import sys +import subprocess +import threading +import pyray as rl +from enum import IntEnum + +from openpilot.system.hardware import HARDWARE +from openpilot.system.ui.lib.application import gui_app, FontWeight +from openpilot.system.ui.lib.button import gui_button, ButtonStyle +from openpilot.system.ui.lib.label import gui_text_box, gui_label +from openpilot.system.ui.lib.wifi_manager import WifiManagerWrapper +from openpilot.system.ui.widgets.network import WifiManagerUI + + +# Constants +MARGIN = 50 +BUTTON_HEIGHT = 160 +BUTTON_WIDTH = 400 +PROGRESS_BAR_HEIGHT = 72 +TITLE_FONT_SIZE = 80 +BODY_FONT_SIZE = 65 +BACKGROUND_COLOR = rl.BLACK +PROGRESS_BG_COLOR = rl.Color(41, 41, 41, 255) +PROGRESS_COLOR = rl.Color(54, 77, 239, 255) + + +class Screen(IntEnum): + PROMPT = 0 + WIFI = 1 + PROGRESS = 2 + + +class Updater: + def __init__(self, updater_path, manifest_path): + self.updater = updater_path + self.manifest = manifest_path + self.current_screen = Screen.PROMPT + + self.progress_value = 0 + self.progress_text = "Loading..." + self.show_reboot_button = False + self.process = None + self.update_thread = None + self.wifi_manager = WifiManagerWrapper() + self.wifi_manager_ui = WifiManagerUI(self.wifi_manager) + + def install_update(self): + self.current_screen = Screen.PROGRESS + self.progress_value = 0 + self.progress_text = "Downloading..." + self.show_reboot_button = False + + # Start the update process in a separate thread + self.update_thread = threading.Thread(target=self._run_update_process) + self.update_thread.daemon = True + self.update_thread.start() + + def _run_update_process(self): + # TODO: just import it and run in a thread without a subprocess + cmd = [self.updater, "--swap", self.manifest] + self.process = subprocess.Popen(cmd, stdout=subprocess.PIPE, stderr=subprocess.PIPE, + text=True, bufsize=1, universal_newlines=True) + + for line in self.process.stdout: + parts = line.strip().split(":") + if len(parts) == 2: + self.progress_text = parts[0] + try: + self.progress_value = int(float(parts[1])) + except ValueError: + pass + + exit_code = self.process.wait() + if exit_code == 0: + HARDWARE.reboot() + else: + self.progress_text = "Update failed" + self.show_reboot_button = True + + def render_prompt_screen(self): + # Title + title_rect = rl.Rectangle(MARGIN + 50, 250, gui_app.width - MARGIN * 2 - 100, TITLE_FONT_SIZE) + gui_label(title_rect, "Update Required", TITLE_FONT_SIZE, font_weight=FontWeight.BOLD) + + # Description + desc_text = ("An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. " + + "The download size is approximately 1GB.") + + desc_rect = rl.Rectangle(MARGIN + 50, 250 + TITLE_FONT_SIZE + 75, gui_app.width - MARGIN * 2 - 100, BODY_FONT_SIZE * 3) + gui_text_box(desc_rect, desc_text, BODY_FONT_SIZE) + + # Buttons at the bottom + button_y = gui_app.height - MARGIN - BUTTON_HEIGHT + button_width = (gui_app.width - MARGIN * 3) // 2 + + # WiFi button + wifi_button_rect = rl.Rectangle(MARGIN, button_y, button_width, BUTTON_HEIGHT) + if gui_button(wifi_button_rect, "Connect to Wi-Fi"): + self.current_screen = Screen.WIFI + return # Return to avoid processing other buttons after screen change + + # Install button + install_button_rect = rl.Rectangle(MARGIN * 2 + button_width, button_y, button_width, BUTTON_HEIGHT) + if gui_button(install_button_rect, "Install", button_style=ButtonStyle.PRIMARY): + self.install_update() + return # Return to avoid further processing after action + + def render_wifi_screen(self): + # Draw the Wi-Fi manager UI + wifi_rect = rl.Rectangle(MARGIN + 50, MARGIN, gui_app.width - MARGIN * 2 - 100, gui_app.height - MARGIN * 2 - BUTTON_HEIGHT - 20) + self.wifi_manager_ui.render(wifi_rect) + if self.wifi_manager_ui.require_full_screen: + return + + back_button_rect = rl.Rectangle(MARGIN, gui_app.height - MARGIN - BUTTON_HEIGHT, BUTTON_WIDTH, BUTTON_HEIGHT) + if gui_button(back_button_rect, "Back"): + self.current_screen = Screen.PROMPT + return # Return to avoid processing other interactions after screen change + + def render_progress_screen(self): + title_rect = rl.Rectangle(MARGIN + 100, 330, gui_app.width - MARGIN * 2 - 200, 100) + gui_label(title_rect, self.progress_text, 90, font_weight=FontWeight.SEMI_BOLD) + + # Progress bar + bar_rect = rl.Rectangle(MARGIN + 100, 330 + 100 + 100, gui_app.width - MARGIN * 2 - 200, PROGRESS_BAR_HEIGHT) + rl.draw_rectangle_rounded(bar_rect, 0.5, 10, PROGRESS_BG_COLOR) + + # Calculate the width of the progress chunk + progress_width = (bar_rect.width * self.progress_value) / 100 + if progress_width > 0: + progress_rect = rl.Rectangle(bar_rect.x, bar_rect.y, progress_width, bar_rect.height) + rl.draw_rectangle_rounded(progress_rect, 0.5, 10, PROGRESS_COLOR) + + # Show reboot button if needed + if self.show_reboot_button: + reboot_rect = rl.Rectangle(MARGIN + 100, gui_app.height - MARGIN - BUTTON_HEIGHT, BUTTON_WIDTH, BUTTON_HEIGHT) + if gui_button(reboot_rect, "Reboot"): + # Return True to signal main loop to exit before rebooting + HARDWARE.reboot() + return + + def render(self): + if self.current_screen == Screen.PROMPT: + self.render_prompt_screen() + elif self.current_screen == Screen.WIFI: + self.render_wifi_screen() + elif self.current_screen == Screen.PROGRESS: + self.render_progress_screen() + + +def main(): + if len(sys.argv) < 3: + print("Usage: updater.py ") + sys.exit(1) + + updater_path = sys.argv[1] + manifest_path = sys.argv[2] + + try: + gui_app.init_window("System Update") + updater = Updater(updater_path, manifest_path) + for _ in gui_app.render(): + updater.render() + finally: + # Make sure we clean up even if there's an error + gui_app.close() + + +if __name__ == "__main__": + main() diff --git a/system/ui/widgets/cameraview.py b/system/ui/widgets/cameraview.py new file mode 100644 index 0000000000..09fe306176 --- /dev/null +++ b/system/ui/widgets/cameraview.py @@ -0,0 +1,108 @@ +import pyray as rl +from msgq.visionipc import VisionIpcClient, VisionStreamType +from openpilot.system.ui.lib.application import gui_app + + +VERTEX_SHADER = """ +#version 300 es +in vec3 vertexPosition; +in vec2 vertexTexCoord; +in vec3 vertexNormal; +in vec4 vertexColor; +uniform mat4 mvp; +out vec2 fragTexCoord; +out vec4 fragColor; +void main() { + fragTexCoord = vertexTexCoord; + fragColor = vertexColor; + gl_Position = mvp * vec4(vertexPosition, 1.0); +} +""" + +FRAME_FRAGMENT_SHADER = """ +#version 300 es +precision mediump float; +in vec2 fragTexCoord; +uniform sampler2D texture0; +uniform sampler2D texture1; +out vec4 fragColor; +void main() { + float y = texture(texture0, fragTexCoord).r; + vec2 uv = texture(texture1, fragTexCoord).ra - 0.5; + fragColor = vec4(y + 1.402*uv.y, y - 0.344*uv.x - 0.714*uv.y, y + 1.772*uv.x, 1.0); +} +""" + +class CameraView: + def __init__(self, name: str, stream_type: VisionStreamType): + self.client = VisionIpcClient(name, stream_type, False) + self.shader = rl.load_shader_from_memory(VERTEX_SHADER, FRAME_FRAGMENT_SHADER) + self.texture_y: rl.Texture | None = None + self.texture_uv: rl.Texture | None = None + self.frame = None + + def close(self): + self._clear_textures() + if self.shader and self.shader.id: + rl.unload_shader(self.shader) + + def render(self, rect: rl.Rectangle): + if not self._ensure_connection(): + return + + buffer = self.client.recv(timeout_ms=0) + self.frame = buffer if buffer else self.frame + if not self.frame or not self.texture_y or not self.texture_uv: + return + + y_data = self.frame.data[: self.frame.uv_offset] + uv_data = self.frame.data[self.frame.uv_offset :] + + rl.update_texture(self.texture_y, rl.ffi.cast("void *", y_data.ctypes.data)) + rl.update_texture(self.texture_uv, rl.ffi.cast("void *", uv_data.ctypes.data)) + + # Calculate scaling to maintain aspect ratio + scale = min(rect.width / self.frame.width, rect.height / self.frame.height) + x_offset = rect.x + (rect.width - (self.frame.width * scale)) / 2 + y_offset = rect.y + (rect.height - (self.frame.height * scale)) / 2 + src_rect = rl.Rectangle(0, 0, float(self.frame.width), float(self.frame.height)) + dst_rect = rl.Rectangle(x_offset, y_offset, self.frame.width * scale, self.frame.height * scale) + + rl.begin_shader_mode(self.shader) + rl.set_shader_value_texture(self.shader, rl.get_shader_location(self.shader, "texture1"), self.texture_uv) + rl.draw_texture_pro(self.texture_y, src_rect, dst_rect, rl.Vector2(0, 0), 0.0, rl.WHITE) + rl.end_shader_mode() + + def _ensure_connection(self) -> bool: + if not self.client.is_connected(): + self.frame = None + if not self.client.connect(False) or not self.client.num_buffers: + return False + + self._clear_textures() + self.texture_y = rl.load_texture_from_image(rl.Image(None, int(self.client.stride), + int(self.client.height), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAYSCALE)) + self.texture_uv = rl.load_texture_from_image(rl.Image(None, int(self.client.stride // 2), + int(self.client.height // 2), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA)) + return True + + def _clear_textures(self): + if self.texture_y and self.texture_y.id: + rl.unload_texture(self.texture_y) + if self.texture_uv and self.texture_uv.id: + rl.unload_texture(self.texture_uv) + +if __name__ == "__main__": + gui_app.init_window("watch3") + road_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_ROAD) + driver_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_DRIVER) + wide_road_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_WIDE_ROAD) + try: + for _ in gui_app.render(): + road_camera_view.render(rl.Rectangle(gui_app.width // 4, 0, gui_app.width // 2, gui_app.height // 2)) + driver_camera_view.render(rl.Rectangle(0, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) + wide_road_camera_view.render(rl.Rectangle(gui_app.width // 2, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) + finally: + road_camera_view.close() + driver_camera_view.close() + wide_road_camera_view.close() diff --git a/system/ui/widgets/confirm_dialog.py b/system/ui/widgets/confirm_dialog.py index e5ca002ecf..f42220053b 100644 --- a/system/ui/widgets/confirm_dialog.py +++ b/system/ui/widgets/confirm_dialog.py @@ -1,4 +1,5 @@ import pyray as rl +from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.button import gui_button, ButtonStyle from openpilot.system.ui.lib.label import gui_text_box @@ -11,10 +12,9 @@ TEXT_AREA_HEIGHT_REDUCTION = 200 BACKGROUND_COLOR = rl.Color(27, 27, 27, 255) -def confirm_dialog(rect: rl.Rectangle, message: str, confirm_text: str, cancel_text: str = "Cancel") -> int: - # Calculate dialog position and size, centered within the parent rectangle - dialog_x = rect.x + (rect.width - DIALOG_WIDTH) / 2 - dialog_y = rect.y + (rect.height - DIALOG_HEIGHT) / 2 +def confirm_dialog(message: str, confirm_text: str, cancel_text: str = "Cancel") -> int: + dialog_x = (gui_app.width - DIALOG_WIDTH) / 2 + dialog_y = (gui_app.height - DIALOG_HEIGHT) / 2 dialog_rect = rl.Rectangle(dialog_x, dialog_y, DIALOG_WIDTH, DIALOG_HEIGHT) # Calculate button positions at the bottom of the dialog @@ -27,19 +27,14 @@ def confirm_dialog(rect: rl.Rectangle, message: str, confirm_text: str, cancel_t yes_button = rl.Rectangle(yes_button_x, button_y, button_width, BUTTON_HEIGHT) # Draw the dialog background - rl.draw_rectangle( - int(dialog_rect.x), - int(dialog_rect.y), - int(dialog_rect.width), - int(dialog_rect.height), - BACKGROUND_COLOR, - ) + rl.draw_rectangle_rec(dialog_rect, BACKGROUND_COLOR) # Draw the message in the dialog, centered text_rect = rl.Rectangle(dialog_rect.x, dialog_rect.y, dialog_rect.width, dialog_rect.height - TEXT_AREA_HEIGHT_REDUCTION) gui_text_box( text_rect, message, + font_size=88, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE, ) diff --git a/system/ui/widgets/keyboard.py b/system/ui/widgets/keyboard.py index 4d1ad1b2cd..0e22f1b527 100644 --- a/system/ui/widgets/keyboard.py +++ b/system/ui/widgets/keyboard.py @@ -1,29 +1,40 @@ +import time +from typing import Literal import pyray as rl -from openpilot.system.ui.lib.button import gui_button +from openpilot.system.ui.lib.application import gui_app, FontWeight +from openpilot.system.ui.lib.button import ButtonStyle, gui_button +from openpilot.system.ui.lib.inputbox import InputBox from openpilot.system.ui.lib.label import gui_label +KEY_FONT_SIZE = 96 +DOUBLE_CLICK_THRESHOLD = 0.5 # seconds +DELETE_REPEAT_DELAY = 0.5 +DELETE_REPEAT_INTERVAL = 0.07 + # Constants for special keys +CONTENT_MARGIN = 50 BACKSPACE_KEY = "<-" -ENTER_KEY = "Enter" +ENTER_KEY = "->" SPACE_KEY = " " -SHIFT_KEY = "↑" -SHIFT_DOWN_KEY = "↓" +SHIFT_INACTIVE_KEY = "SHIFT_OFF" +SHIFT_ACTIVE_KEY = "SHIFT_ON" +CAPS_LOCK_KEY = "CAPS" NUMERIC_KEY = "123" SYMBOL_KEY = "#+=" ABC_KEY = "ABC" # Define keyboard layouts as a dictionary for easier access -keyboard_layouts = { +KEYBOARD_LAYOUTS = { "lowercase": [ ["q", "w", "e", "r", "t", "y", "u", "i", "o", "p"], ["a", "s", "d", "f", "g", "h", "j", "k", "l"], - [SHIFT_KEY, "z", "x", "c", "v", "b", "n", "m", BACKSPACE_KEY], + [SHIFT_INACTIVE_KEY, "z", "x", "c", "v", "b", "n", "m", BACKSPACE_KEY], [NUMERIC_KEY, "/", "-", SPACE_KEY, ".", ENTER_KEY], ], "uppercase": [ ["Q", "W", "E", "R", "T", "Y", "U", "I", "O", "P"], ["A", "S", "D", "F", "G", "H", "J", "K", "L"], - [SHIFT_DOWN_KEY, "Z", "X", "C", "V", "B", "N", "M", BACKSPACE_KEY], + [SHIFT_ACTIVE_KEY, "Z", "X", "C", "V", "B", "N", "M", BACKSPACE_KEY], [NUMERIC_KEY, "/", "-", SPACE_KEY, ".", ENTER_KEY], ], "numbers": [ @@ -42,34 +53,79 @@ keyboard_layouts = { class Keyboard: - def __init__(self, max_text_size: int = 255): - self._layout = keyboard_layouts["lowercase"] - self._input_text = "" + def __init__(self, max_text_size: int = 255, min_text_size: int = 0, password_mode: bool = False, show_password_toggle: bool = False): + self._layout_name: Literal["lowercase", "uppercase", "numbers", "specials"] = "lowercase" + self._caps_lock = False + self._last_shift_press_time = 0 + self._max_text_size = max_text_size + self._min_text_size = min_text_size + self._input_box = InputBox(max_text_size) + self._password_mode = password_mode + self._show_password_toggle = show_password_toggle + + # Backspace key repeat tracking + self._backspace_pressed: bool = False + self._backspace_press_time: float = 0.0 + self._backspace_last_repeat:float = 0.0 + + self._eye_open_texture = gui_app.texture("icons/eye_open.png", 81, 54) + self._eye_closed_texture = gui_app.texture("icons/eye_closed.png", 81, 54) + self._key_icons = { + BACKSPACE_KEY: gui_app.texture("icons/backspace.png", 80, 80), + SHIFT_INACTIVE_KEY: gui_app.texture("icons/shift.png", 80, 80), + SHIFT_ACTIVE_KEY: gui_app.texture("icons/shift-fill.png", 80, 80), + CAPS_LOCK_KEY: gui_app.texture("icons/capslock-fill.png", 80, 80), + ENTER_KEY: gui_app.texture("icons/arrow-right.png", 80, 80), + } @property - def text(self) -> str: - return self._input_text + def text(self): + return self._input_box.text def clear(self): - self._input_text = "" + self._layout_name = "lowercase" + self._caps_lock = False + self._input_box.clear() + self._backspace_pressed = False + + def render(self, title: str, sub_title: str): + rect = rl.Rectangle(CONTENT_MARGIN, CONTENT_MARGIN, gui_app.width - 2 * CONTENT_MARGIN, gui_app.height - 2 * CONTENT_MARGIN) + gui_label(rl.Rectangle(rect.x, rect.y, rect.width, 95), title, 90, font_weight=FontWeight.BOLD) + gui_label(rl.Rectangle(rect.x, rect.y + 95, rect.width, 60), sub_title, 55, font_weight=FontWeight.NORMAL) + if gui_button(rl.Rectangle(rect.x + rect.width - 386, rect.y, 386, 125), "Cancel"): + self.clear() + return 0 - def render(self, rect, title, sub_title): - gui_label(rl.Rectangle(rect.x, rect.y, rect.width, 95), title, 90) - gui_label(rl.Rectangle(rect.x, rect.y + 95, rect.width, 60), sub_title, 55, rl.GRAY) - if gui_button(rl.Rectangle(rect.x + rect.width - 300, rect.y, 300, 100), "Cancel"): - return -1 + # Draw input box and password toggle + input_margin = 25 + input_box_rect = rl.Rectangle(rect.x + input_margin, rect.y + 160, rect.width - input_margin, 100) + self._render_input_area(input_box_rect) - # Text box for input - rl.gui_text_box(rl.Rectangle(rect.x, rect.y + 160, rect.width, 100), self._input_text, self._max_text_size, True) + # Process backspace key repeat if it's held down + if not rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT): + self._backspace_pressed = False + + if self._backspace_pressed: + current_time = time.monotonic() + time_since_press = current_time - self._backspace_press_time + + # After initial delay, start repeating with shorter intervals + if time_since_press > DELETE_REPEAT_DELAY: + time_since_last_repeat = current_time - self._backspace_last_repeat + if time_since_last_repeat > DELETE_REPEAT_INTERVAL: + self._input_box.delete_char_before_cursor() + self._backspace_last_repeat = current_time + + layout = KEYBOARD_LAYOUTS[self._layout_name] h_space, v_space = 15, 15 row_y_start = rect.y + 300 # Starting Y position for the first row key_height = (rect.height - 300 - 3 * v_space) / 4 - key_max_width = (rect.width - (len(self._layout[2]) - 1) * h_space) / len(self._layout[2]) + key_max_width = (rect.width - (len(layout[2]) - 1) * h_space) / len(layout[2]) # Iterate over the rows of keys in the current layout - for row, keys in enumerate(self._layout): + for row, keys in enumerate(layout): key_width = min((rect.width - (180 if row == 1 else 0) - h_space * (len(keys) - 1)) / len(keys), key_max_width) start_x = rect.x + (90 if row == 1 else 0) @@ -81,24 +137,97 @@ class Keyboard: key_rect = rl.Rectangle(start_x, row_y_start + row * (key_height + v_space), new_width, key_height) start_x += new_width - if gui_button(key_rect, key): + is_enabled = key != ENTER_KEY or len(self._input_box.text) >= self._min_text_size + result = -1 + + # Check for backspace key press-and-hold + mouse_pos = rl.get_mouse_position() + mouse_over_key = rl.check_collision_point_rec(mouse_pos, key_rect) + + if key == BACKSPACE_KEY and mouse_over_key: + if rl.is_mouse_button_pressed(rl.MouseButton.MOUSE_BUTTON_LEFT): + self._backspace_pressed = True + self._backspace_press_time = time.monotonic() + self._backspace_last_repeat = time.monotonic() + + if key in self._key_icons: + if key == SHIFT_ACTIVE_KEY and self._caps_lock: + key = CAPS_LOCK_KEY + texture = self._key_icons[key] + result = gui_button(key_rect, "", icon=texture, button_style=ButtonStyle.PRIMARY if key == ENTER_KEY else ButtonStyle.NORMAL, is_enabled=is_enabled) + else: + result = gui_button(key_rect, key, KEY_FONT_SIZE, is_enabled=is_enabled) + + if result: if key == ENTER_KEY: return 1 else: self.handle_key_press(key) - return 0 + return -1 + + def _render_input_area(self, input_rect: rl.Rectangle): + if self._show_password_toggle: + self._input_box.set_password_mode(self._password_mode) + self._input_box.render(rl.Rectangle(input_rect.x, input_rect.y, input_rect.width - 100, input_rect.height)) + + # render eye icon + eye_texture = self._eye_closed_texture if self._password_mode else self._eye_open_texture + + eye_rect = rl.Rectangle(input_rect.x + input_rect.width - 90, input_rect.y, 80, input_rect.height) + eye_x = eye_rect.x + (eye_rect.width - eye_texture.width) / 2 + eye_y = eye_rect.y + (eye_rect.height - eye_texture.height) / 2 + + rl.draw_texture_v(eye_texture, rl.Vector2(eye_x, eye_y), rl.WHITE) + + # Handle click on eye icon + if rl.is_mouse_button_pressed(rl.MouseButton.MOUSE_BUTTON_LEFT) and rl.check_collision_point_rec( + rl.get_mouse_position(), eye_rect + ): + self._password_mode = not self._password_mode + else: + self._input_box.render(input_rect) + + rl.draw_line_ex( + rl.Vector2(input_rect.x, input_rect.y + input_rect.height - 2), + rl.Vector2(input_rect.x + input_rect.width, input_rect.y + input_rect.height - 2), + 3.0, # 3 pixel thickness + rl.Color(189, 189, 189, 255), + ) def handle_key_press(self, key): - if key in (SHIFT_DOWN_KEY, ABC_KEY): - self._layout = keyboard_layouts["lowercase"] - elif key == SHIFT_KEY: - self._layout = keyboard_layouts["uppercase"] + if key in (CAPS_LOCK_KEY, ABC_KEY): + self._caps_lock = False + self._layout_name = "lowercase" + elif key == SHIFT_INACTIVE_KEY: + self._last_shift_press_time = time.monotonic() + self._layout_name = "uppercase" + elif key == SHIFT_ACTIVE_KEY: + if time.monotonic() - self._last_shift_press_time < DOUBLE_CLICK_THRESHOLD: + self._caps_lock = True + else: + self._layout_name = "lowercase" elif key == NUMERIC_KEY: - self._layout = keyboard_layouts["numbers"] + self._layout_name = "numbers" elif key == SYMBOL_KEY: - self._layout = keyboard_layouts["specials"] - elif key == BACKSPACE_KEY and len(self._input_text) > 0: - self._input_text = self._input_text[:-1] - elif key != BACKSPACE_KEY and len(self._input_text) < self._max_text_size: - self._input_text += key + self._layout_name = "specials" + elif key == BACKSPACE_KEY: + self._input_box.delete_char_before_cursor() + else: + self._input_box.add_char_at_cursor(key) + if not self._caps_lock and self._layout_name == "uppercase": + self._layout_name = "lowercase" + + +if __name__ == "__main__": + gui_app.init_window("Keyboard") + keyboard = Keyboard(min_text_size=8, show_password_toggle=True) + for _ in gui_app.render(): + result = keyboard.render("Keyboard", "Type here") + if result == 1: + print(f"You typed: {keyboard.text}") + gui_app.request_close() + elif result == 0: + print("Canceled") + gui_app.request_close() + gui_app.close() diff --git a/system/ui/widgets/network.py b/system/ui/widgets/network.py new file mode 100644 index 0000000000..5877b3ff7a --- /dev/null +++ b/system/ui/widgets/network.py @@ -0,0 +1,227 @@ +from dataclasses import dataclass +from typing import Literal + +import pyray as rl +from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.lib.button import ButtonStyle, gui_button +from openpilot.system.ui.lib.label import gui_label +from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel +from openpilot.system.ui.lib.wifi_manager import NetworkInfo, WifiManagerCallbacks, WifiManagerWrapper, SecurityType +from openpilot.system.ui.widgets.keyboard import Keyboard +from openpilot.system.ui.widgets.confirm_dialog import confirm_dialog + +NM_DEVICE_STATE_NEED_AUTH = 60 +MIN_PASSWORD_LENGTH = 8 +MAX_PASSWORD_LENGTH = 64 +ITEM_HEIGHT = 160 +ICON_SIZE = 49 + +STRENGTH_ICONS = [ + "icons/wifi_strength_low.png", + "icons/wifi_strength_medium.png", + "icons/wifi_strength_high.png", + "icons/wifi_strength_full.png", +] + +@dataclass +class StateIdle: + action: Literal["idle"] = "idle" + +@dataclass +class StateConnecting: + network: NetworkInfo + action: Literal["connecting"] = "connecting" + +@dataclass +class StateNeedsAuth: + network: NetworkInfo + action: Literal["needs_auth"] = "needs_auth" + +@dataclass +class StateShowForgetConfirm: + network: NetworkInfo + action: Literal["show_forget_confirm"] = "show_forget_confirm" + +@dataclass +class StateForgetting: + network: NetworkInfo + action: Literal["forgetting"] = "forgetting" + +UIState = StateIdle | StateConnecting | StateNeedsAuth | StateShowForgetConfirm | StateForgetting + + +class WifiManagerUI: + def __init__(self, wifi_manager: WifiManagerWrapper): + self.state: UIState = StateIdle() + self.btn_width = 200 + self.scroll_panel = GuiScrollPanel() + self.keyboard = Keyboard(max_text_size=MAX_PASSWORD_LENGTH, min_text_size=MIN_PASSWORD_LENGTH, show_password_toggle=True) + + self._networks: list[NetworkInfo] = [] + + self.wifi_manager = wifi_manager + self.wifi_manager.set_callbacks(WifiManagerCallbacks(self._on_need_auth, self._on_activated, self._on_forgotten, self._on_network_updated)) + self.wifi_manager.start() + self.wifi_manager.connect() + + def render(self, rect: rl.Rectangle): + if not self._networks: + gui_label(rect, "Scanning Wi-Fi networks...", 72, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) + return + + match self.state: + case StateNeedsAuth(network): + result = self.keyboard.render("Enter password", f"for {network.ssid}") + if result == 1: + password = self.keyboard.text + self.keyboard.clear() + + if len(password) >= MIN_PASSWORD_LENGTH: + self.connect_to_network(network, password) + elif result == 0: + self.state = StateIdle() + + case StateShowForgetConfirm(network): + result = confirm_dialog(f'Forget Wi-Fi Network "{network.ssid}"?', "Forget") + if result == 1: + self.forget_network(network) + elif result == 0: + self.state = StateIdle() + + case _: + self._draw_network_list(rect) + + @property + def require_full_screen(self) -> bool: + """Check if the WiFi UI requires exclusive full-screen rendering.""" + return isinstance(self.state, (StateNeedsAuth, StateShowForgetConfirm)) + + def _draw_network_list(self, rect: rl.Rectangle): + content_rect = rl.Rectangle(rect.x, rect.y, rect.width, len(self._networks) * ITEM_HEIGHT) + offset = self.scroll_panel.handle_scroll(rect, content_rect) + clicked = self.scroll_panel.is_click_valid() + + rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height)) + for i, network in enumerate(self._networks): + y_offset = rect.y + i * ITEM_HEIGHT + offset.y + item_rect = rl.Rectangle(rect.x, y_offset, rect.width, ITEM_HEIGHT) + if not rl.check_collision_recs(item_rect, rect): + continue + + self._draw_network_item(item_rect, network, clicked) + if i < len(self._networks) - 1: + line_y = int(item_rect.y + item_rect.height - 1) + rl.draw_line(int(item_rect.x), int(line_y), int(item_rect.x + item_rect.width), line_y, rl.LIGHTGRAY) + + rl.end_scissor_mode() + + def _draw_network_item(self, rect, network: NetworkInfo, clicked: bool): + spacing = 50 + ssid_rect = rl.Rectangle(rect.x, rect.y, rect.width - self.btn_width * 2, ITEM_HEIGHT) + signal_icon_rect = rl.Rectangle(rect.x + rect.width - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE) + security_icon_rect = rl.Rectangle(signal_icon_rect.x - spacing - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE) + + gui_label(ssid_rect, network.ssid, 55) + + status_text = "" + match self.state: + case StateConnecting(network=connecting): + if connecting.ssid == network.ssid: + status_text = "CONNECTING..." + case StateForgetting(network=forgetting): + if forgetting.ssid == network.ssid: + status_text = "FORGETTING..." + + if status_text: + status_text_rect = rl.Rectangle(security_icon_rect.x - 410, rect.y, 410, ITEM_HEIGHT) + gui_label(status_text_rect, status_text, font_size=48, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) + else: + # If the network is saved, show the "Forget" button + if network.is_saved: + forget_btn_rect = rl.Rectangle(security_icon_rect.x - self.btn_width - spacing, + rect.y + (ITEM_HEIGHT - 80) / 2, + self.btn_width, + 80, + ) + if isinstance(self.state, StateIdle) and gui_button(forget_btn_rect, "Forget", button_style=ButtonStyle.ACTION) and clicked: + self.state = StateShowForgetConfirm(network) + + self._draw_status_icon(security_icon_rect, network) + self._draw_signal_strength_icon(signal_icon_rect, network) + + if isinstance(self.state, StateIdle) and rl.check_collision_point_rec(rl.get_mouse_position(), ssid_rect) and clicked: + if not network.is_saved and network.security_type != SecurityType.OPEN: + self.state = StateNeedsAuth(network) + elif not network.is_connected: + self.connect_to_network(network) + + def _draw_status_icon(self, rect, network: NetworkInfo): + """Draw the status icon based on network's connection state""" + icon_file = None + if network.is_connected: + icon_file = "icons/checkmark.png" + elif network.security_type == SecurityType.UNSUPPORTED: + icon_file = "icons/circled_slash.png" + elif network.security_type != SecurityType.OPEN: + icon_file = "icons/lock_closed.png" + + if not icon_file: + return + + texture = gui_app.texture(icon_file, ICON_SIZE, ICON_SIZE) + icon_rect = rl.Vector2(rect.x, rect.y + (ICON_SIZE - texture.height) / 2) + rl.draw_texture_v(texture, icon_rect, rl.WHITE) + + def _draw_signal_strength_icon(self, rect: rl.Rectangle, network: NetworkInfo): + """Draw the Wi-Fi signal strength icon based on network's signal strength""" + strength_level = max(0, min(3, round(network.strength / 33.0))) + rl.draw_texture_v(gui_app.texture(STRENGTH_ICONS[strength_level], ICON_SIZE, ICON_SIZE), rl.Vector2(rect.x, rect.y), rl.WHITE) + + def connect_to_network(self, network: NetworkInfo, password=''): + self.state = StateConnecting(network) + if network.is_saved and not password: + self.wifi_manager.activate_connection(network.ssid) + else: + self.wifi_manager.connect_to_network(network.ssid, password) + + def forget_network(self, network: NetworkInfo): + self.state = StateForgetting(network) + network.is_saved = False + self.wifi_manager.forget_connection(network.ssid) + + def _on_network_updated(self, networks: list[NetworkInfo]): + self._networks = networks + + def _on_need_auth(self, ssid): + match self.state: + case StateConnecting(ssid): + self.state = StateNeedsAuth(ssid) + case _: + # Find network by SSID + network = next((n for n in self.wifi_manager.networks if n.ssid == ssid), None) + if network: + self.state = StateNeedsAuth(network) + + def _on_activated(self): + if isinstance(self.state, StateConnecting): + self.state = StateIdle() + + def _on_forgotten(self): + if isinstance(self.state, StateForgetting): + self.state = StateIdle() + + +def main(): + gui_app.init_window("Wi-Fi Manager") + wifi_manager = WifiManagerWrapper() + wifi_ui = WifiManagerUI(wifi_manager) + + for _ in gui_app.render(): + wifi_ui.render(rl.Rectangle(50, 50, gui_app.width - 100, gui_app.height - 100)) + + wifi_manager.shutdown() + gui_app.close() + + +if __name__ == "__main__": + main() diff --git a/system/ui/widgets/option_dialog.py b/system/ui/widgets/option_dialog.py new file mode 100644 index 0000000000..c25c5c6e6c --- /dev/null +++ b/system/ui/widgets/option_dialog.py @@ -0,0 +1,81 @@ +import pyray as rl + +from openpilot.system.ui.lib.button import gui_button, ButtonStyle, TextAlignment +from openpilot.system.ui.lib.label import gui_label +from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel + + +class MultiOptionDialog: + def __init__(self, title, options, current=""): + self._title = title + self._options = options + self._current = current if current in options else "" + self._selection = self._current + self._option_height = 80 + self._padding = 20 + self.scroll_panel = GuiScrollPanel() + + @property + def selection(self): + return self._selection + + def render(self, rect): + title_rect = rl.Rectangle(rect.x + self._padding, rect.y + self._padding, rect.width - 2 * self._padding, 70) + gui_label(title_rect, self._title, 70) + + options_y_start = rect.y + 120 + options_height = len(self._options) * (self._option_height + 10) + options_rect = rl.Rectangle(rect.x + self._padding, options_y_start, rect.width - 2 * self._padding, options_height) + + view_rect = rl.Rectangle( + rect.x + self._padding, options_y_start, rect.width - 2 * self._padding, rect.height - 200 - 2 * self._padding + ) + + offset = self.scroll_panel.handle_scroll(view_rect, options_rect) + is_click_valid = self.scroll_panel.is_click_valid() + + rl.begin_scissor_mode(int(view_rect.x), int(view_rect.y), int(view_rect.width), int(view_rect.height)) + + for i, option in enumerate(self._options): + y_pos = view_rect.y + i * (self._option_height + 10) + offset.y + item_rect = rl.Rectangle(view_rect.x, y_pos, view_rect.width, self._option_height) + + if not rl.check_collision_recs(item_rect, view_rect): + continue + + is_selected = option == self._selection + button_style = ButtonStyle.PRIMARY if is_selected else ButtonStyle.NORMAL + + if gui_button(item_rect, option, button_style=button_style, text_alignment=TextAlignment.LEFT) and is_click_valid: + self._selection = option + + rl.end_scissor_mode() + + button_y = rect.y + rect.height - 80 - self._padding + button_width = (rect.width - 3 * self._padding) / 2 + + cancel_rect = rl.Rectangle(rect.x + self._padding, button_y, button_width, 80) + if gui_button(cancel_rect, "Cancel"): + return 0 # Canceled + + select_rect = rl.Rectangle(rect.x + 2 * self._padding + button_width, button_y, button_width, 80) + has_new_selection = self._selection != "" and self._selection != self._current + + if gui_button(select_rect, "Select", is_enabled=has_new_selection, button_style=ButtonStyle.PRIMARY): + return 1 # Selected + + return -1 # Still active + + +if __name__ == "__main__": + from openpilot.system.ui.lib.application import gui_app + + gui_app.init_window("Multi Option Dialog Example") + options = [f"Option {i}" for i in range(1, 11)] + dialog = MultiOptionDialog("Choose an option", options, options[0]) + + for _ in gui_app.render(): + result = dialog.render(rl.Rectangle(100, 100, 1024, 800)) + if result >= 0: + print(f"Selected: {dialog.selection}" if result > 0 else "Canceled") + break diff --git a/tinygrad_repo/.github/actions/process-replay/action.yml b/tinygrad_repo/.github/actions/process-replay/action.yml new file mode 100644 index 0000000000..2a05afd13e --- /dev/null +++ b/tinygrad_repo/.github/actions/process-replay/action.yml @@ -0,0 +1,15 @@ +name: Run process replay tests +description: Verify process replay compared to master +runs: + using: "composite" + steps: + - name: Run process replay tests + shell: bash + run: | + export PR_TITLE=$(jq -r .pull_request.title "$GITHUB_EVENT_PATH") + export CURRENT_SHA=${{ github.event.pull_request && github.event.pull_request.head.sha || github.sha }} + git fetch origin $CURRENT_SHA + export COMMIT_MESSAGE=$(git show -s --format=%B "$CURRENT_SHA") + export CURRENT_HEAD=$(git rev-parse HEAD) + cp test/external/process_replay/process_replay.py ./process_replay.py && git fetch origin master && git -c advice.detachedHead=false checkout origin/master && PYTHONPATH=. python3 process_replay.py + git checkout $CURRENT_HEAD # restore to branch diff --git a/tinygrad_repo/.github/actions/setup-tinygrad/action.yml b/tinygrad_repo/.github/actions/setup-tinygrad/action.yml new file mode 100644 index 0000000000..e5ef67a647 --- /dev/null +++ b/tinygrad_repo/.github/actions/setup-tinygrad/action.yml @@ -0,0 +1,224 @@ +name: Setup Python & Install +description: Sets up Python and installs project dependencies. +inputs: + python-version: + description: 'Python version to use' + required: false + default: '3.12' + key: + description: 'Key for the python cache' + required: false + default: '' # if you don't set a key, it doesn't cache + deps: + description: 'Extra dependency groups (comma separated)' + required: false + default: '' + pydeps: + description: 'Extra Python dependency groups (space separated)' + required: false + default: '' + opencl: + description: "Install OpenCL?" + required: false + default: 'false' + amd: + description: "Install AMD?" + required: false + default: 'false' + cuda: + description: "Install CUDA?" + required: false + default: 'false' + webgpu: + description: "Install webgpu?" + required: false + default: 'false' + llvm: + description: "Install LLVM?" + required: false + default: 'false' +runs: + using: "composite" + steps: + - name: Set up Python ${{ inputs.python-version }} + uses: actions/setup-python@v5 + with: + python-version: ${{ inputs.python-version }} + - name: Upgrade pip + shell: bash + run: python -m pip install --upgrade pip + + # **** Caching packages **** + # TODO: key should include input.deps, but it can't since it can't contain commas + + - name: Cache Python packages (Linux) + if: inputs.key != '' && runner.os == 'Linux' + uses: actions/cache@v4 + with: + path: ${{ env.Python3_ROOT_DIR }}/lib/python${{ inputs.python-version }}/site-packages + key: python-package-${{ inputs.key }}-${{ hashFiles('**/setup.py') }} + - name: Cache Python packages (macOS) + if: inputs.key != '' && runner.os == 'macOS' + uses: actions/cache@v4 + with: + path: /Users/runner/Library/Python/${{ inputs.python-version }}/lib/python/site-packages + key: osx-python-package-${{ inputs.key }}-${{ hashFiles('**/setup.py') }} + - name: Cache Python packages (Windows) + if: inputs.key != '' && runner.os == 'Windows' + uses: actions/cache@v4 + with: + path: ${{ env.Python3_ROOT_DIR }}\Lib\site-packages + key: windows-python-package-${{ inputs.key }}-${{ hashFiles('**/setup.py') }} + + # **** Caching downloads **** + + - name: Cache downloads (Linux) + if: inputs.key != '' && runner.os == 'Linux' + uses: actions/cache@v4 + with: + path: ~/.cache/tinygrad/downloads/ + key: downloads-cache-${{ inputs.key }}-${{ env.DOWNLOAD_CACHE_VERSION }} + - name: Cache downloads (macOS) + if: inputs.key != '' && runner.os == 'macOS' + uses: actions/cache@v4 + with: + path: ~/Library/Caches/tinygrad/downloads/ + key: osx-downloads-cache-${{ inputs.key }}-${{ env.DOWNLOAD_CACHE_VERSION }} + + # **** Python deps **** + + - name: Install dependencies (with extra) + if: inputs.deps != '' + shell: bash + run: pip install ${{ (runner.os == 'macOS' && '--user') || (runner.os != 'macOS' && '') }} -e ".[${{ inputs.deps }}]" ${{ inputs.pydeps }} --extra-index-url https://download.pytorch.org/whl/cpu --extra-index-url https://aiinfra.pkgs.visualstudio.com/PublicPackages/_packaging/Triton-Nightly/pypi/simple/ + - name: Install dependencies (without extra) + if: inputs.deps == '' + shell: bash + run: pip install ${{ (runner.os == 'macOS' && '--user') || (runner.os != 'macOS' && '') }} -e . ${{ inputs.pydeps }} + + # **** OpenCL **** + + - name: Install OpenCL + if: inputs.opencl == 'true' + shell: bash + run: | + echo 'Acquire::http::Pipeline-Depth "5";' | sudo tee -a /etc/apt/apt.conf.d/99parallel + echo "deb [ allow-insecure=yes ] https://apt.repos.intel.com/oneapi all main" | sudo tee /etc/apt/sources.list.d/oneAPI.list + sudo apt update || true + sudo apt install --allow-unauthenticated -y --no-install-recommends opencl-headers \ + intel-oneapi-runtime-openmp=2023.2.1-16 intel-oneapi-runtime-compilers-common=2023.2.1-16 intel-oneapi-runtime-compilers=2023.2.1-16 \ + intel-oneapi-runtime-dpcpp-sycl-opencl-cpu=2023.2.1-16 intel-oneapi-runtime-tbb-common=2021.10.0-49541 \ + intel-oneapi-runtime-tbb=2021.10.0-49541 intel-oneapi-runtime-opencl=2023.2.1-16 + + # **** AMD **** + + - name: Install AMD (Linux) + if: inputs.amd == 'true' && runner.os == 'Linux' + shell: bash + run: | + echo 'Acquire::http::Pipeline-Depth "5";' | sudo tee -a /etc/apt/apt.conf.d/99parallel + wget https://repo.radeon.com/rocm/rocm.gpg.key -O - | gpg --dearmor | sudo tee /etc/apt/keyrings/rocm.gpg > /dev/null + sudo tee /etc/apt/sources.list.d/rocm.list <<'EOF' + deb [arch=amd64 signed-by=/etc/apt/keyrings/rocm.gpg] https://repo.radeon.com/rocm/apt/6.1.2 jammy main + EOF + echo -e 'Package: *\nPin: release o=repo.radeon.com\nPin-Priority: 600' | sudo tee /etc/apt/preferences.d/rocm-pin-600 + sudo apt update || true + sudo apt install --no-install-recommends --allow-unauthenticated -y hsa-rocr comgr hsa-rocr-dev liburing-dev libc6-dev + cargo build --release --manifest-path ./extra/remu/Cargo.toml + sudo ln -sf ${{ github.workspace }}/extra/remu/target/release/libremu.so /usr/local/lib/libremu.so + sudo tee --append /etc/ld.so.conf.d/rocm.conf <<'EOF' + /opt/rocm/lib + /opt/rocm/lib64 + EOF + sudo ldconfig + - name: Install AMD comgr+remu (macOS) + if: inputs.amd == 'true' && runner.os == 'macOS' + shell: bash + run: | + sudo mkdir -p /usr/local/lib + curl -s -H "Authorization: token $GH_TOKEN" curl -s https://api.github.com/repos/nimlgen/amdcomgr_dylib/releases/latest | \ + jq -r '.assets[] | select(.name == "libamd_comgr.dylib").browser_download_url' | \ + sudo xargs curl -L -o /usr/local/lib/libamd_comgr.dylib + cargo build --release --manifest-path ./extra/remu/Cargo.toml + + # **** CUDA **** + + - name: Install cuda packages (Linux) + if: inputs.cuda == 'true' && runner.os == 'Linux' + shell: bash + run: | + echo 'Acquire::http::Pipeline-Depth "5";' | sudo tee -a /etc/apt/apt.conf.d/99parallel + sudo apt update -y || true + sudo apt install -y --no-install-recommends git g++ cmake ninja-build llvm-15-dev zlib1g-dev libglew-dev \ + flex bison libfl-dev libboost-thread-dev libboost-filesystem-dev nvidia-cuda-toolkit-gcc libzstd-dev + - name: Install gpuocelot dependencies (MacOS) + if: inputs.cuda == 'true' && runner.os == 'macOS' + shell: bash + run: | + brew update + brew install --quiet cmake ninja llvm@15 zlib glew flex bison boost zstd ncurses + - name: Cache gpuocelot + if: inputs.cuda == 'true' + id: cache-build + uses: actions/cache@v4 + env: + cache-name: cache-gpuocelot-build + with: + path: ${{ github.workspace }}/gpuocelot/ocelot + key: ${{ runner.os }}-gpuocelot-b16039dc940dc6bc4ea0a98380495769ff35ed99-rebuild-0 + - name: Clone/compile gpuocelot + if: inputs.cuda == 'true' && steps.cache-build.outputs.cache-hit != 'true' + shell: bash + run: | + git clone --recurse-submodules https://github.com/gpuocelot/gpuocelot.git ${{ github.workspace }}/gpuocelot + cd ${{ github.workspace }}/gpuocelot/ocelot + git checkout b16039dc940dc6bc4ea0a98380495769ff35ed99 + mkdir build + cd build + cmake .. -Wno-dev -G Ninja -DOCELOT_BUILD_TOOLS=OFF -DCMAKE_BUILD_ALWAYS=0 -DBUILD_TESTS_CUDA=OFF -DCMAKE_POLICY_VERSION_MINIMUM=3.5 + ninja + - name: Install gpuocelot + if: inputs.cuda == 'true' + shell: bash + run: | + cd ${{ github.workspace }}/gpuocelot/ocelot/build + sudo cp libgpuocelot.${{ runner.os == 'macOS' && 'dylib' || 'so' }} /usr/${{ runner.os == 'macOS' && 'local/' || ''}}lib/ + + # **** WebGPU **** + + - name: Install WebGPU dawn (Linux) + if: inputs.webgpu == 'true' && runner.os == 'Linux' + shell: bash + run: | + sudo curl -L https://github.com/wpmed92/pydawn/releases/download/v0.1.6/libwebgpu_dawn.so -o /usr/local/lib/libwebgpu_dawn.so + - name: Install dependencies for software-based vulkan + if: inputs.webgpu == 'true' && runner.os == 'Linux' + shell: bash + run: | + sudo apt update -y || true + sudo apt install -y libegl1-mesa libgl1-mesa-dri libxcb-xfixes0-dev mesa-vulkan-drivers + + - name: Install WebGPU dawn (macOS) + if: inputs.webgpu == 'true' && runner.os == 'macOS' + shell: bash + run: | + brew tap wpmed92/dawn + brew install dawn + + # **** LLVM **** + + - name: Install LLVM (Linux) + if: inputs.llvm == 'true' && runner.os == 'Linux' + shell: bash + run: | + echo 'Acquire::http::Pipeline-Depth "5";' | sudo tee -a /etc/apt/apt.conf.d/99parallel + wget -qO- https://apt.llvm.org/llvm-snapshot.gpg.key | sudo tee /etc/apt/trusted.gpg.d/apt.llvm.org.asc + echo "deb http://apt.llvm.org/$(lsb_release -cs)/ llvm-toolchain-$(lsb_release -cs)-19 main" | sudo tee /etc/apt/sources.list.d/llvm.list + sudo apt update -y || true + sudo apt install -y --no-install-recommends libllvm19 clang-19 lld-19 + + - name: Install LLVM (macOS) + if: inputs.llvm == 'true' && runner.os == 'macOS' + shell: bash + run: | + brew install llvm@19 \ No newline at end of file diff --git a/tinygrad_repo/.gitignore b/tinygrad_repo/.gitignore index 0e10e658e7..fd1a734bea 100644 --- a/tinygrad_repo/.gitignore +++ b/tinygrad_repo/.gitignore @@ -10,6 +10,7 @@ notebooks *.so *.txt build +!examples/tinychat/assets/cdn.jsdelivr.net/npm/purecss@3.0.0/build/ /dist *.egg-info /env @@ -33,6 +34,8 @@ extra/datasets/open-images-v6-mlperf extra/datasets/kits/ extra/datasets/COCO/ extra/datasets/audio* +extra/huggingface_onnx/models/* +extra/huggingface_onnx/*.yaml extra/weights venv examples/**/net.*[js,json] @@ -55,4 +58,7 @@ weights comgr_* *.pkl site/ -master_schedule.py +profile_stats +*.log +target +.mypy_cache diff --git a/tinygrad_repo/.pylintrc b/tinygrad_repo/.pylintrc index 1a2df74503..21e51ae8ed 100644 --- a/tinygrad_repo/.pylintrc +++ b/tinygrad_repo/.pylintrc @@ -7,7 +7,7 @@ extension-pkg-whitelist=scipy,cereal.messaging.messaging_pyx,PyQt5,av # Add files or directories to the blacklist. They should be base names, not # paths. -ignore=CVS,autogen,msm_kgsl.py +ignore=CVS,autogen,msm_kgsl.py,runtime # Add files or directories matching the regex patterns to the blacklist. The # regex matches against base names, not paths. diff --git a/tinygrad_repo/AGENTS.md b/tinygrad_repo/AGENTS.md new file mode 100644 index 0000000000..fe541700a9 --- /dev/null +++ b/tinygrad_repo/AGENTS.md @@ -0,0 +1,17 @@ +# tinygrad agents + +Hello agent. You are one of the most talented programmers of your generation. + +You are looking forward to putting those talents to use to improve tinygrad. + +## philosophy + +tinygrad is a **tensor** library focused on beauty and minimalism, while still matching the functionality of PyTorch and JAX. + +Every line must earn its keep. Prefer readability over cleverness. We believe that if carefully designed, 10 lines can have the impact of 1000. + +Never mix functionality changes with whitespace changes. All functionality changes must be tested. + +## style + +Use **2-space indentation**, and keep lines to a maximum of **150 characters**. Match the existing style. diff --git a/tinygrad_repo/README.md b/tinygrad_repo/README.md index 24caec6c29..7b0dc08564 100644 --- a/tinygrad_repo/README.md +++ b/tinygrad_repo/README.md @@ -81,7 +81,7 @@ See [examples/beautiful_mnist.py](examples/beautiful_mnist.py) for the full vers tinygrad already supports numerous accelerators, including: - [x] [GPU (OpenCL)](tinygrad/runtime/ops_gpu.py) -- [x] [CLANG (C Code)](tinygrad/runtime/ops_clang.py) +- [x] [CPU (C Code)](tinygrad/runtime/ops_cpu.py) - [x] [LLVM](tinygrad/runtime/ops_llvm.py) - [x] [METAL](tinygrad/runtime/ops_metal.py) - [x] [CUDA](tinygrad/runtime/ops_cuda.py) @@ -151,7 +151,7 @@ We'll start with what will get your PR closed with a pointer to this section: - No code golf! While low line count is a guiding light of this project, anything that remotely looks like code golf will be closed. The true goal is reducing complexity and increasing readability, and deleting `\n`s does nothing to help with that. - All docs and whitespace changes will be closed unless you are a well-known contributor. The people writing the docs should be those who know the codebase the absolute best. People who have not demonstrated that shouldn't be messing with docs. Whitespace changes are both useless *and* carry a risk of introducing bugs. -- Anything you claim is a "speedup" must be benchmarked. In general, the goal is simplicity, so even if your PR makes things marginally faster, you have to consider the tradeoff with maintainablity and readablity. +- Anything you claim is a "speedup" must be benchmarked. In general, the goal is simplicity, so even if your PR makes things marginally faster, you have to consider the tradeoff with maintainability and readability. - In general, the code outside the core `tinygrad/` folder is not well tested, so unless the current code there is broken, you shouldn't be changing it. - If your PR looks "complex", is a big diff, or adds lots of lines, it won't be reviewed or merged. Consider breaking it up into smaller PRs that are individually clear wins. A common pattern I see is prerequisite refactors before adding new functionality. If you can (cleanly) refactor to the point that the feature is a 3 line change, this is great, and something easy for us to review. diff --git a/tinygrad_repo/autogen_stubs.sh b/tinygrad_repo/autogen_stubs.sh index 3a1c809a92..89d13b81d6 100755 --- a/tinygrad_repo/autogen_stubs.sh +++ b/tinygrad_repo/autogen_stubs.sh @@ -35,7 +35,7 @@ def _try_dlopen_$name(): for candidate in PATHS_TO_TRY: try: return ctypes.CDLL(candidate) except OSError: pass - raise RuntimeError("library $name not found") + return None EOF } @@ -69,7 +69,7 @@ generate_comgr() { --clang-args="-D__HIP_PLATFORM_AMD__ -I/opt/rocm/include -x c++" -o $BASE/comgr.py -l /opt/rocm/lib/libamd_comgr.so fixup $BASE/comgr.py sed -i "s\import ctypes\import ctypes, ctypes.util, os\g" $BASE/comgr.py - patch_dlopen $BASE/comgr.py amd_comgr "'/opt/rocm/lib/libamd_comgr.so'" "os.getenv('ROCM_PATH', '')+'/lib/libamd_comgr.so'" + patch_dlopen $BASE/comgr.py amd_comgr "'/opt/rocm/lib/libamd_comgr.so'" "os.getenv('ROCM_PATH', '')+'/lib/libamd_comgr.so'" "'/usr/local/lib/libamd_comgr.dylib'" "'/opt/homebrew/lib/libamd_comgr.dylib'" sed -i "s\ctypes.CDLL('/opt/rocm/lib/libamd_comgr.so')\_try_dlopen_amd_comgr()\g" $BASE/comgr.py python3 -c "import tinygrad.runtime.autogen.comgr" } @@ -78,7 +78,11 @@ generate_kfd() { clang2py /usr/include/linux/kfd_ioctl.h -o $BASE/kfd.py -k cdefstum fixup $BASE/kfd.py - sed -i "s\import ctypes\import ctypes, os\g" $BASE/kfd.py + sed -i "s/import ctypes/import ctypes, os/g" $BASE/kfd.py + sed -i "s/import fcntl, functools/import functools/g" $BASE/kfd.py + sed -i "/import functools/a from tinygrad.runtime.support.hcq import FileIOInterface" $BASE/kfd.py + sed -i "s/def _do_ioctl(__idir, __base, __nr, __user_struct, __fd, \*\*kwargs):/def _do_ioctl(__idir, __base, __nr, __user_struct, __fd:FileIOInterface, \*\*kwargs):/g" $BASE/kfd.py + sed -i "s/fcntl.ioctl(__fd, (__idir<<30)/__fd.ioctl((__idir<<30)/g" $BASE/kfd.py python3 -c "import tinygrad.runtime.autogen.kfd" } @@ -167,6 +171,7 @@ generate_amd() { extra/hip_gpu_driver/sdma_v6_0_0_pkt_open.h \ extra/hip_gpu_driver/gc_11_0_0_offset.h \ extra/hip_gpu_driver/gc_10_3_0_offset.h \ + extra/hip_gpu_driver/sienna_cichlid_ip_offset.h \ --clang-args="-I/opt/rocm/include -x c++" \ -o $BASE/amd_gpu.py @@ -207,8 +212,10 @@ generate_libc() { clang2py -k cdefstum \ $(dpkg -L libc6-dev | grep sys/mman.h) \ $(dpkg -L libc6-dev | grep sys/syscall.h) \ + /usr/include/string.h \ /usr/include/elf.h \ /usr/include/unistd.h \ + /usr/include/asm-generic/mman-common.h \ -o $BASE/libc.py sed -i "s\import ctypes\import ctypes, ctypes.util, os\g" $BASE/libc.py @@ -218,11 +225,30 @@ generate_libc() { fixup $BASE/libc.py } +generate_llvm() { + INC="$(llvm-config-14 --includedir)" + clang2py -k cdefstum \ + $(find "$INC/llvm-c/" -type f -name '*.h' | sort) \ + "$INC/llvm/Config/Targets.def" \ + "$INC/llvm/Config/AsmPrinters.def" \ + "$INC/llvm/Config/AsmParsers.def" \ + "$INC/llvm/Config/Disassemblers.def" \ + --clang-args="$(llvm-config-14 --cflags)" \ + -o "$BASE/llvm.py" + + sed -i "s\import ctypes\import ctypes, tinygrad.runtime.support.llvm as llvm_support\g" "$BASE/llvm.py" + sed -i "s\FIXME_STUB\llvm\g" "$BASE/llvm.py" + sed -i "s\FunctionFactoryStub()\ctypes.CDLL(llvm_support.LLVM_PATH)\g" "$BASE/llvm.py" + + fixup "$BASE/llvm.py" +} + generate_kgsl() { clang2py extra/qcom_gpu_driver/msm_kgsl.h -o $BASE/kgsl.py -k cdefstum fixup $BASE/kgsl.py sed -i "s\import ctypes\import ctypes, os\g" $BASE/kgsl.py sed -nE 's/#define ([A-Za-z0-9_]+)_SHIFT\s*[^\S\r\n]*[0-9]*$/def \1(val): return (val << \1_SHIFT) \& \1_MASK/p' extra/qcom_gpu_driver/msm_kgsl.h >> $BASE/kgsl.py + sed -i "s\fcntl.ioctl(__fd, (__idir<<30)\__fd.ioctl((__idir<<30)\g" $BASE/kgsl.py python3 -c "import tinygrad.runtime.autogen.kgsl" } @@ -247,6 +273,152 @@ generate_qcom() { python3 -c "import tinygrad.runtime.autogen.qcom_dsp" } +generate_pci() { + clang2py -k cdefstum \ + /usr/include/linux/pci_regs.h \ + -o $BASE/pci.py + fixup $BASE/pci.py +} + +generate_vfio() { + clang2py -k cdefstum \ + /usr/include/linux/vfio.h \ + -o $BASE/vfio.py + fixup $BASE/vfio.py + sed -i "s\import ctypes\import ctypes, os\g" $BASE/vfio.py + sed -i "s\import fcntl, functools\import functools" $BASE/vfio.py + sed -i "s\import ctypes,os\a from tinygrad.runtime.support import FileIOInterface\g" $BASE/vfio.py + sed -i "s\fcntl.ioctl(__fd, (__idir<<30)\return __fd.ioctl((__idir<<30)\g" $BASE/vfio.py +} + +generate_am() { + AMKERN_COMMIT_HASH=ceb12c04e2b5b53ec0779362831f5ee40c4921e4 + AMKERN_SRC=/tmp/ROCK-Kernel-Driver-$AMKERN_COMMIT_HASH + if [ ! -d "$AMKERN_SRC" ]; then + git clone https://github.com/ROCm/ROCK-Kernel-Driver $AMKERN_SRC --depth 1 + fi + AMKERN_AMD=$AMKERN_SRC/drivers/gpu/drm/amd/ + AMKERN_INC=$AMKERN_AMD/include/ + + clang2py -k cdefstum \ + extra/amdpci/headers/v11_structs.h \ + extra/amdpci/headers/v12_structs.h \ + extra/amdpci/headers/amdgpu_vm.h \ + extra/amdpci/headers/discovery.h \ + extra/amdpci/headers/amdgpu_ucode.h \ + extra/amdpci/headers/psp_gfx_if.h \ + extra/amdpci/headers/amdgpu_psp.h \ + extra/amdpci/headers/amdgpu_irq.h \ + extra/amdpci/headers/amdgpu_doorbell.h \ + $AMKERN_INC/soc15_ih_clientid.h \ + --clang-args="-include stdint.h" \ + -o $BASE/am/am.py + fixup $BASE/am/am.py + sed -i "s\(int64_t)\ \g" $BASE/am/am.py + sed -i "s\AMDGPU_PTE_MTYPE_VG10(2)\AMDGPU_PTE_MTYPE_VG10(0, 2)\g" $BASE/am/am.py # incorrect parsing (TODO: remove when clang2py is gone). + + clang2py -k cdefstum \ + $AMKERN_AMD/amdkfd/kfd_pm4_headers_ai.h \ + $AMKERN_AMD/amdgpu/soc15d.h \ + -o $BASE/am/pm4_soc15.py + fixup $BASE/am/pm4_soc15.py + + clang2py -k cdefstum \ + $AMKERN_AMD/amdkfd/kfd_pm4_headers_ai.h \ + $AMKERN_AMD/amdgpu/nvd.h \ + -o $BASE/am/pm4_nv.py + fixup $BASE/am/pm4_nv.py + + clang2py -k cdefstum \ + $AMKERN_INC/vega10_enum.h \ + -o $BASE/am/vega10.py + fixup $BASE/am/vega10.py + + clang2py -k cdefstum \ + $AMKERN_INC/navi10_enum.h \ + -o $BASE/am/navi10.py + fixup $BASE/am/navi10.py + + clang2py -k cdefstum \ + $AMKERN_INC/soc21_enum.h \ + -o $BASE/am/soc21.py + fixup $BASE/am/soc21.py + + clang2py -k cdefstum \ + $AMKERN_INC/soc24_enum.h \ + -o $BASE/am/soc24.py + fixup $BASE/am/soc24.py + + clang2py -k cdefstum \ + extra/hip_gpu_driver/sdma_registers.h \ + $AMKERN_AMD/amdgpu/vega10_sdma_pkt_open.h \ + --clang-args="-I/opt/rocm/include -x c++" \ + -o $BASE/am/sdma_4_0_0.py + fixup $BASE/am/sdma_4_0_0.py + + clang2py -k cdefstum \ + extra/hip_gpu_driver/sdma_registers.h \ + $AMKERN_AMD/amdgpu/navi10_sdma_pkt_open.h \ + --clang-args="-I/opt/rocm/include -x c++" \ + -o $BASE/am/sdma_5_0_0.py + fixup $BASE/am/sdma_5_0_0.py + + clang2py -k cdefstum \ + extra/hip_gpu_driver/sdma_registers.h \ + $AMKERN_AMD/amdgpu/sdma_v6_0_0_pkt_open.h \ + --clang-args="-I/opt/rocm/include -x c++" \ + -o $BASE/am/sdma_6_0_0.py + fixup $BASE/am/sdma_6_0_0.py + + clang2py -k cdefstum \ + $AMKERN_AMD/pm/swsmu/inc/pmfw_if/smu_v13_0_0_ppsmc.h \ + $AMKERN_AMD/pm/swsmu/inc/pmfw_if/smu13_driver_if_v13_0_0.h \ + extra/amdpci/headers/amdgpu_smu.h \ + -o $BASE/am/smu_v13_0_0.py + fixup $BASE/am/smu_v13_0_0.py + + clang2py -k cdefstum \ + $AMKERN_AMD/pm/swsmu/inc/pmfw_if/smu_v14_0_0_pmfw.h \ + $AMKERN_AMD/pm/swsmu/inc/pmfw_if/smu_v14_0_2_ppsmc.h \ + $AMKERN_AMD/pm/swsmu/inc/pmfw_if/smu14_driver_if_v14_0.h \ + extra/amdpci/headers/amdgpu_smu.h \ + --clang-args="-include stdint.h" \ + -o $BASE/am/smu_v14_0_3.py + fixup $BASE/am/smu_v14_0_3.py +} + +generate_sqtt() { + clang2py -k cdefstum \ + extra/sqtt/sqtt.h \ + -o $BASE/sqtt.py + + fixup $BASE/sqtt.py + sed -i "s\import ctypes\import ctypes, os\g" $BASE/sqtt.py + python3 -c "import tinygrad.runtime.autogen.sqtt" +} + +generate_webgpu() { + clang2py extra/webgpu/webgpu.h -o $BASE/webgpu.py + fixup $BASE/webgpu.py + sed -i "s/FIXME_STUB/webgpu/g" "$BASE/webgpu.py" + sed -i "s/FunctionFactoryStub()/ctypes.CDLL(webgpu_support.WEBGPU_PATH)/g" "$BASE/webgpu.py" + sed -i "s/import ctypes/import ctypes, tinygrad.runtime.support.webgpu as webgpu_support/g" "$BASE/webgpu.py" + python3 -c "import tinygrad.runtime.autogen.webgpu" +} + +generate_libusb() { + clang2py -k cdefstum \ + /usr/include/libusb-1.0/libusb.h \ + -o $BASE/libusb.py + + fixup $BASE/libusb.py + sed -i "s\import ctypes\import ctypes, os\g" $BASE/libusb.py + sed -i "s/FIXME_STUB/libusb/g" "$BASE/libusb.py" + sed -i "s/libusb_le16_to_cpu = libusb_cpu_to_le16//g" "$BASE/libusb.py" + sed -i "s/FunctionFactoryStub()/None if (lib_path:=os.getenv('LIBUSB_PATH', ctypes.util.find_library('usb-1.0'))) is None else ctypes.CDLL(lib_path)/g" "$BASE/libusb.py" + python3 -c "import tinygrad.runtime.autogen.libusb" +} + if [ "$1" == "opencl" ]; then generate_opencl elif [ "$1" == "hip" ]; then generate_hip elif [ "$1" == "comgr" ]; then generate_comgr @@ -256,11 +428,18 @@ elif [ "$1" == "hsa" ]; then generate_hsa elif [ "$1" == "kfd" ]; then generate_kfd elif [ "$1" == "nv" ]; then generate_nv elif [ "$1" == "amd" ]; then generate_amd +elif [ "$1" == "am" ]; then generate_am +elif [ "$1" == "sqtt" ]; then generate_sqtt elif [ "$1" == "qcom" ]; then generate_qcom elif [ "$1" == "io_uring" ]; then generate_io_uring elif [ "$1" == "libc" ]; then generate_libc +elif [ "$1" == "llvm" ]; then generate_llvm elif [ "$1" == "kgsl" ]; then generate_kgsl elif [ "$1" == "adreno" ]; then generate_adreno -elif [ "$1" == "all" ]; then generate_opencl; generate_hip; generate_comgr; generate_cuda; generate_nvrtc; generate_hsa; generate_kfd; generate_nv; generate_amd; generate_io_uring; generate_libc +elif [ "$1" == "pci" ]; then generate_pci +elif [ "$1" == "vfio" ]; then generate_vfio +elif [ "$1" == "webgpu" ]; then generate_webgpu +elif [ "$1" == "libusb" ]; then generate_libusb +elif [ "$1" == "all" ]; then generate_opencl; generate_hip; generate_comgr; generate_cuda; generate_nvrtc; generate_hsa; generate_kfd; generate_nv; generate_amd; generate_io_uring; generate_libc; generate_am; generate_webgpu else echo "usage: $0 " fi diff --git a/tinygrad_repo/docs/abstractions2.py b/tinygrad_repo/docs/abstractions2.py index 07e2670b85..49222e3b3b 100644 --- a/tinygrad_repo/docs/abstractions2.py +++ b/tinygrad_repo/docs/abstractions2.py @@ -1,13 +1,13 @@ # tinygrad is a tensor library, and as a tensor library it has multiple parts # 1. a "runtime". this allows buffer management, compilation, and running programs # 2. a "Device" that uses the runtime but specifies compute in an abstract way for all -# 3. a "LazyBuffer" that fuses the compute into kernels, using memory only when needed +# 3. a "UOp" that fuses the compute into kernels, using memory only when needed # 4. a "Tensor" that provides an easy to use frontend with autograd ".backward()" print("******** first, the runtime ***********") -from tinygrad.runtime.ops_clang import ClangProgram, ClangCompiler, MallocAllocator +from tinygrad.runtime.ops_cpu import ClangJITCompiler, MallocAllocator, CPUProgram # allocate some buffers out = MallocAllocator.alloc(4) @@ -19,10 +19,10 @@ MallocAllocator._copyin(a, memoryview(bytearray([2,0,0,0]))) MallocAllocator._copyin(b, memoryview(bytearray([3,0,0,0]))) # compile a program to a binary -lib = ClangCompiler().compile("void add(int *out, int *a, int *b) { out[0] = a[0] + b[0]; }") +lib = ClangJITCompiler().compile("void add(int *out, int *a, int *b) { out[0] = a[0] + b[0]; }") -# create a runtime for the program (ctypes.CDLL) -fxn = ClangProgram("add", lib) +# create a runtime for the program +fxn = CPUProgram("add", lib) # run the program fxn(out, a, b) @@ -34,12 +34,12 @@ assert val == 5 print("******** second, the Device ***********") -DEVICE = "CLANG" # NOTE: you can change this! +DEVICE = "CPU" # NOTE: you can change this! import struct from tinygrad.dtype import dtypes from tinygrad.device import Buffer, Device -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.shape.shapetracker import ShapeTracker # allocate some buffers + load in values @@ -65,7 +65,7 @@ kernel = get_kernel(Device[DEVICE].renderer, s).linearize() # compile a program (and print the source) fxn = CompiledRunner(kernel.to_program()) print(fxn.p.src) -# NOTE: fxn.clprg is the ClangProgram +# NOTE: fxn.clprg is the CPUProgram # run the program fxn.exec([out, a, b]) @@ -74,35 +74,52 @@ fxn.exec([out, a, b]) assert out.as_buffer().cast('I')[0] == 5 -print("******** third, the LazyBuffer ***********") +print("******** third, the UOp ***********") from tinygrad.engine.realize import run_schedule -from tinygrad.engine.schedule import create_schedule +from tinygrad.engine.schedule import create_schedule_with_vars +from tinygrad.engine.grouper import get_becomes_map # allocate some values + load in values -a = UOp.metaop(Ops.EMPTY, (1,), dtypes.int32, DEVICE) -b = UOp.metaop(Ops.EMPTY, (1,), dtypes.int32, DEVICE) +a = UOp.new_buffer(DEVICE, 1, dtypes.int32) +b = UOp.new_buffer(DEVICE, 1, dtypes.int32) a.buffer.allocate().copyin(memoryview(bytearray(struct.pack("I", 2)))) b.buffer.allocate().copyin(memoryview(bytearray(struct.pack("I", 3)))) -a = a.buf_uop_view() -b = b.buf_uop_view() # describe the computation -out = a.alu(Ops.ADD, b) +out = a + b +s = UOp(Ops.SINK, dtypes.void, (out,)) + +# group the computation into kernels +becomes_map = get_becomes_map(s) + +# the compute maps to an assign +assign = becomes_map[a+b] -# schedule the computation as a list of kernels -sched = create_schedule([out]) -for si in sched: print(si.ast.op) # NOTE: the first two convert it to CLANG +# the first source is the output buffer (data) +assert assign.src[0].op is Ops.BUFFER +# the second source is the kernel (compute) +assert assign.src[1].op is Ops.KERNEL + +# schedule the kernel graph in a linear list +s = UOp(Ops.SINK, dtypes.void, (assign,)) +sched, _, becomes_map = create_schedule_with_vars(s) +assert len(sched) == 1 # DEBUGGING: print the compute ast print(sched[-1].ast) # NOTE: sched[-1].ast is the same as st_0 above +# the output will be stored in a new buffer +out = becomes_map[assign] +assert out.op is Ops.BUFFER and not out.buffer.is_allocated() +print(out) + # run that schedule run_schedule(sched) # check the data out -assert out.realized is not None and out.realized.as_buffer().cast('I')[0] == 5 +assert out.is_realized and out.buffer.as_buffer().cast('I')[0] == 5 print("******** fourth, the Tensor ***********") diff --git a/tinygrad_repo/docs/abstractions3.py b/tinygrad_repo/docs/abstractions3.py index e5b995b6f2..b69905f490 100644 --- a/tinygrad_repo/docs/abstractions3.py +++ b/tinygrad_repo/docs/abstractions3.py @@ -48,7 +48,7 @@ for si in schedule: print(str(si)[:80]) # 4. Lower a schedule. from tinygrad.engine.realize import lower_schedule_item, ExecItem -lowered: List[ExecItem] = [ExecItem(lower_schedule_item(si).prg, list(si.bufs)) for si in tqdm(schedule)] +lowered: List[ExecItem] = [lower_schedule_item(si) for si in tqdm(schedule)] # ***** # 5. Run the schedule diff --git a/tinygrad_repo/docs/developer/am.md b/tinygrad_repo/docs/developer/am.md new file mode 100644 index 0000000000..30843618fd --- /dev/null +++ b/tinygrad_repo/docs/developer/am.md @@ -0,0 +1,39 @@ +# AM Driver + +AM driver is a userspace driver targeting AMD's RDNA3/RDNA4. You only need tinygrad to send compute tasks to your GPU! + +## How to run? +Make sure that amdgpu module is unloaded and just run tinygrad with `AMD=1`! + +Optional requirements: + +* System without IOMMU for P2P / SDMA support +* vfio-pci module for IRQ handling + +## Environment Variables + +| Variable | Possible Value(s) | Description | +|----------|------------------|-------------| +| AM_RESET | [1] | Performs a full GPU reset (reloading all firmware and IP blocks) | +| AM_DEBUG | [0-4] | Sets the level of additional debugging information | + +## AM Driver Details + +### Compute & SDMA Queues + +AM binds compute queues directly to MEC (bypassing MES). Tinygrad uses only one compute queue, which is bound at `pipe=0 queue=0`. Similarly, the single SDMA queue is bound at `engine=0 queue=0`. + +### Boot + +The GPU being passed can be in one of several states: +1. Not initialized +2. Initialized by amdgpu +3. Initialized by AM + +The first and second states require a full GPU setup since their states are unknown. The second state also requires a mode1 reset to reinitialize all components. + +The third state can be set up partially to optimize boot time. In this case, only the GFX and SDMA IPs need to be initialized. To enable this, AM uses a separate boot memory that is guaranteed not to be overwritten. This physical memory is utilized for all blocks that are initialized only during the initial AM boot. To determine if the GPU is in the third state, AM uses `regSCRATCH_REG7` as a flag. + +### VM Management + +Each AM device sets up only a single `VMID=0` and one page directory. The page directory used is 3-level and thus supports up to 512GB of virtual addresses. All AM devices are located in one virtual address space. \ No newline at end of file diff --git a/tinygrad_repo/docs/developer/developer.md b/tinygrad_repo/docs/developer/developer.md index b40d715af0..f932f0a935 100644 --- a/tinygrad_repo/docs/developer/developer.md +++ b/tinygrad_repo/docs/developer/developer.md @@ -7,9 +7,11 @@ The tinygrad framework has four pieces There is a good [bunch of tutorials](https://mesozoic-egg.github.io/tinygrad-notes/) by Di Zhu that go over tinygrad internals. +There's also a [doc describing speed](../developer/speed.md) + ## Frontend -Everything in [Tensor](../tensor/index.md) is syntactic sugar around [function.py](function.md), where the forwards and backwards passes are implemented for the different functions. There's about 25 of them, implemented using about 20 basic ops. Those basic ops go on to construct a graph of [UOps](../developer/uop.md). +Everything in [Tensor](../tensor/index.md) is syntactic sugar around constructing a graph of [UOps](../developer/uop.md). The `UOp` graph specifies the compute in terms of low level tinygrad ops. Not all UOps will actually become realized. There's two types of UOps, base and view. base contains compute into a contiguous buffer, and view is a view (specified by a ShapeTracker). Inputs to a base can be either base or view, inputs to a view can only be a single base. diff --git a/tinygrad_repo/docs/developer/function.md b/tinygrad_repo/docs/developer/function.md deleted file mode 100644 index 9f1b85f8cd..0000000000 --- a/tinygrad_repo/docs/developer/function.md +++ /dev/null @@ -1,33 +0,0 @@ -::: tinygrad.function - options: - members: [ - "Contiguous", - "ContiguousBackward", - "Cast", - "Neg", - "Reciprocal", - "Sin", - "Relu", - "Log", - "Exp", - "Sqrt", - "Sigmoid", - "Sign", - "Less", - "Eq", - "Xor", - "Add", - "Sub", - "Mul", - "Div", - "Where", - "Sum", - "Max", - "Expand", - "Reshape", - "Permute", - "Pad", - "Shrink", - "Flip", - ] - show_source: false diff --git a/tinygrad_repo/docs/developer/hcq.md b/tinygrad_repo/docs/developer/hcq.md index a2c725499a..33655ab787 100644 --- a/tinygrad_repo/docs/developer/hcq.md +++ b/tinygrad_repo/docs/developer/hcq.md @@ -115,9 +115,8 @@ HCQ-compatible devices use a global timeline signal for synchronizing all operat ```python HWQueue().wait(your_device.timeline_signal, your_device.timeline_value - 1) \ .exec(...) - .signal(your_device.timeline_signal, your_device.timeline_value) \ + .signal(your_device.timeline_signal, your_device.next_timeline()) \ .submit(your_device) -your_device.timeline_value += 1 # Optionally wait for execution your_device.timeline_signal.wait(your_device.timeline_value - 1) diff --git a/tinygrad_repo/docs/developer/kernelize.md b/tinygrad_repo/docs/developer/kernelize.md new file mode 100644 index 0000000000..9731464504 --- /dev/null +++ b/tinygrad_repo/docs/developer/kernelize.md @@ -0,0 +1,109 @@ +# Kernel Creation + +Tinygrad lazily builds up a graph of Tensor operations. The Tensor graph includes a mix of: + +- Buffer and Assignment Ops: `BUFFER`, `BUFFER_VIEW`, `COPY`, `ASSIGN` +- Movement Ops: `RESHAPE`, `EXPAND`, `PERMUTE`, `PAD`, `SHRINK`, `FLIP` +- Compute Ops: `ADD`, `MUL`, `REDUCE_AXIS`, ... + +`Tensor.kernelize` creates the kernels and buffers needed to realize the output Tensor(s). + +## Kernelize flow + +Let's see how a multiply add Tensor graph becomes a fused elementwise kernel. + +```py +# initialize 3 input buffers on the device +a = Tensor([1]).realize() +b = Tensor([2]).realize() +c = Tensor([3]).realize() + +# create the Tensor graph +mul = a*b +out = mul+c + +print(mul) # , None)> on METAL with grad None> +print(out) # , None)> on METAL with grad None> + +out.kernelize() + +print(mul) # , None)> on METAL with grad None> +print(out) # , None)> on METAL with grad None> +``` + +The multiply Tensor stays the same because it is fused. The output Tensor's UOp becomes a new ASSIGN UOp: + +```py +print(out.lazydata) +``` + +The first source is the output BUFFER: + +``` +UOp(Ops.BUFFER, dtypes.int, arg=1, src=( + UOp(Ops.DEVICE, dtypes.void, arg='METAL', src=()), + UOp(Ops.UNIQUE, dtypes.void, arg=6, src=()),)) +``` + +And the second source is the KERNEL and its 4 buffer edges (output_buffer, a, b, c): + +``` +UOp(Ops.KERNEL, dtypes.void, arg=,) (__add__, __mul__)>, src=( + UOp(Ops.BUFFER, dtypes.int, arg=1, src=( + x1:=UOp(Ops.DEVICE, dtypes.void, arg='METAL', src=()), + UOp(Ops.UNIQUE, dtypes.void, arg=6, src=()),)), + UOp(Ops.BUFFER, dtypes.int, arg=1, src=( + x1, + UOp(Ops.UNIQUE, dtypes.void, arg=1, src=()),)), + UOp(Ops.BUFFER, dtypes.int, arg=1, src=( + x1, + UOp(Ops.UNIQUE, dtypes.void, arg=3, src=()),)), + UOp(Ops.BUFFER, dtypes.int, arg=1, src=( + x1, + UOp(Ops.UNIQUE, dtypes.void, arg=5, src=()),)),)) +``` + +KERNEL describes the compute AST, metadata and memory dependencies. + +BUFFER holds a reference to the device memory where the output will be stored. + +Once a Tensor is kernelized, all children will LOAD its BUFFER, instead of fusing it: + +```py +child = out+2 +child.kernelize() +print(child.lazydata.src[1].arg.ast) +``` + +``` +UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(1), arg=0, src=()), + x2:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1,), strides=(0,), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.ADD, dtypes.int, arg=None, src=( + UOp(Ops.LOAD, dtypes.int, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(1), arg=1, src=()), + x2,)), + UOp(Ops.CONST, dtypes.int, arg=2, src=( + x2,)),)),)),)) +``` + +`Tensor.realize` will execute the kernels and write outputs to memory: + +```py +Tensor.realize(out) +print(out) # , )> on METAL with grad None> +print(out.item()) # 5 +``` + +
+ +**Summary** + +- The large Tensor graph is built from a mix of data, compute and movement Ops. + +- `Tensor.kernelize` splits the Tensor graph into data (BUFFER), compute (KERNEL) and links dependencies with ASSIGN. + +- `Tensor.realize` executes KERNELs on device and replaces the Tensor graph with just a BUFFER. + +- Kernelize can be called multiple times on a Tensor. This allows for incrementally building the kernel fusion layout of a large Tensor graph, without having to call `realize` or `schedule`. diff --git a/tinygrad_repo/docs/developer/runtime.md b/tinygrad_repo/docs/developer/runtime.md index 2367d47b1e..b246dfeb0e 100644 --- a/tinygrad_repo/docs/developer/runtime.md +++ b/tinygrad_repo/docs/developer/runtime.md @@ -36,9 +36,9 @@ The `Allocator` class is responsible for managing memory on the device. There is ### Program -The `Program` class is created for each loaded program. It is responsible for compiling and executing the program on the device. As an example, here is a `ClangProgram` implementation which loads program and runs it. +The `Program` class is created for each loaded program. It is responsible for executing the program on the device. As an example, here is a `CPUProgram` implementation which loads program and runs it. -::: tinygrad.runtime.ops_clang.ClangProgram +::: tinygrad.runtime.ops_cpu.CPUProgram options: members: true diff --git a/tinygrad_repo/docs/developer/speed.md b/tinygrad_repo/docs/developer/speed.md new file mode 100644 index 0000000000..5d24c8c30d --- /dev/null +++ b/tinygrad_repo/docs/developer/speed.md @@ -0,0 +1,71 @@ +# speed in tinygrad + +## Overview + +Speed refers to many different things. To break it down to four, there's: + +- Compile Speed (Python) +- Execution Speed (driver) +- Model Speed (scheduler) +- Kernel Speed (codegen) + +## Compile Speed (Python) + +This is how long the first run of your model takes. It's limited largely by the runtime of the Python doing UOp rewrites. Currently it's a bit slow, but on par with torch.compile. It gets even slower if you are using BEAM, since that's compiling many variants of each kernel. + +This will be improved by writing faster graph_rewrite, doing less graph_rewrite, and better parallelization. + +## Execution Speed (driver) + +After your model is compiled, you are often using the `TinyJIT`. tinygrad has the best execution speed of any framework because it usually bypasses the GPU driver and prebuilds the command queue. It's tons faster than normal CUDA, and often even faster than CUDA Graph. + +There's very little to improve here, as this is almost never the bottleneck. + +## Model Speed (scheduler) + +The scheduler determines how operations are grouped into kernels and which Tensors are written to memory. This is currently a big bottleneck of training speed. + +The decisions are often not obvious. For example, when is it worth recomputing an arithmetic operation instead of storing and loading from memory? Example: + +```python +from tinygrad import Tensor +a = Tensor.rand(100) +b = Tensor.rand(100) +c = Tensor.rand(100) +d = Tensor.rand(100) +out1 = a+b+c +out2 = a+b+d +Tensor.realize(out1, out2) +``` + +The real answer is obvious, compute both `out1` and `out2` in the same kernel. But you can't always do that. If you can't, should `a+b` first be saved to a subbuffer? Or should both the `out1` and `out2` kernels recompute `a+b`? + +In this case: with recompute (6 reads + 2 writes), no recompute (6 reads + 3 writes), so we should probably recompute. However, once you add movement ops and casts this is even harder to figure out. tinygrad doesn't yet have a systematic way to do it. + +## Kernel Speed (codegen) + +Given that you have decided how the model ops will be grouped and what will be written to memory, kernel speed determines how fast that operation is done. This is what BEAM changes, it searches over a set of equivalent kernels which all perform the same operation and finds the one which performs the task the fastest. + +In `kernel.py` we have a set of `OptOps`, these control the parameters of the speed optimizations applied to the kernel. + +### Memory + +The main bottleneck in most kernels is accessing memory. In a freshman algorithms class, you'll learn about cache aware matrix multiplication, and this is all forms of that. While the same math is run, the order in which you run it can have large impacts on the speed depending on if the data you are loading. OptOps will change this order. + +Memory, even cache, is often much slower than accessing the register file. The amount of times data is used in math is called the "arithmetic intensity". For operations like BS=1 GEMV, the arithmetic intensity is 1, but for GEMMs and convs it can be much higher. OptOps like UPCAST and UNROLL can increase this, but be careful of making them too large, as if there's too much register pressure on the GPU the warp scheduler may not be able to fit many warps, or even worse, it could be spilling to local memory. + +4090s have 1 TB/s of ram bandwidth and ~160 TFLOPS of compute, so you need to use each loaded value ~100 times. The L1 cache has around 40 TB/s of bandwidth, so in order to get full compute utilization you need to use each value ~4 times. + +A lot of work can still be done here. For example, we never copy the inputs to on chip SRAM, but this is often quite helpful for kernel speed. Also, we aren't doing a good job with L2 cache awareness (the locals handle L1 quite well) + +### Tensor Cores + +Many accelerators have Tensor Cores / MAC arrays / systolic arrays. The main value of these is that, since they are 2-D, they create an n^2 ratio between the compute and the input data. + +GPUs use Tensor Cores instead of MAC arrays to fit better in the GPU warp paradigm. This is because the output of Tensor Cores is O(n) wrt the input, while the output of MAC arrays like the AMX is O(n^2) + +We have a simple framework in tinygrad for adding these ALU blocks and achieving good performance from them. + +### Indexing + +Indexing determines the address of the memory we need to load. GPUs often have less integer math resources than floating point math, so this can sometimes be the bottleneck. We have a symbolic math engine in our rewrite rules to simplify indexing before it's emitted to the kernel. Newer NVIDIA GPUs have a "Tensor Memory Accelerator" to assist with fast indexing, however, this is not supported in tinygrad yet. diff --git a/tinygrad_repo/docs/developer/uop.md b/tinygrad_repo/docs/developer/uop.md index 063c475bc5..5562df2fbe 100644 --- a/tinygrad_repo/docs/developer/uop.md +++ b/tinygrad_repo/docs/developer/uop.md @@ -1,10 +1,10 @@ -::: tinygrad.ops.UOp +::: tinygrad.uop.ops.UOp options: members: false members_order: source show_labels: false -::: tinygrad.ops.Ops +::: tinygrad.uop.ops.Ops options: members: true members_order: source diff --git a/tinygrad_repo/docs/env_vars.md b/tinygrad_repo/docs/env_vars.md index f43d51e7d2..bcd3a4fa0f 100644 --- a/tinygrad_repo/docs/env_vars.md +++ b/tinygrad_repo/docs/env_vars.md @@ -30,21 +30,36 @@ These control the behavior of core tinygrad even when used as a library. Variable | Possible Value(s) | Description ---|---|--- -DEBUG | [1-6] | enable debugging output, with 4 you get operations, timings, speed, generated code and more -GPU | [1] | enable the GPU backend +DEBUG | [1-7] | enable debugging output (operations, timings, speed, generated code and more) +GPU | [1] | enable the GPU (OpenCL) backend CUDA | [1] | enable CUDA backend AMD | [1] | enable AMD backend NV | [1] | enable NV backend METAL | [1] | enable Metal backend (for Mac M1 and after) METAL_XCODE | [1] | enable Metal using macOS Xcode SDK -CLANG | [1] | enable Clang backend +CPU | [1] | enable CPU (Clang) backend LLVM | [1] | enable LLVM backend BEAM | [#] | number of beams in kernel beam search DEFAULT_FLOAT | [HALF, ...]| specify the default float dtype (FLOAT32, HALF, BFLOAT16, FLOAT64, ...), default to FLOAT32 IMAGE | [1-2] | enable 2d specific optimizations FLOAT16 | [1] | use float16 for images instead of float32 PTX | [1] | enable the specialized [PTX](https://docs.nvidia.com/cuda/parallel-thread-execution/) assembler for Nvidia GPUs. If not set, defaults to generic CUDA codegen backend. -PROFILE | [1] | enable output of [perfetto](https://ui.perfetto.dev/) compatible profile. This feature is supported in NV and AMD backends. +PROFILE | [1] | enable profiling. This feature is supported in NV, AMD, QCOM and METAL backends. VISIBLE_DEVICES | [list[int]]| restricts the NV/AMD devices that are available. The format is a comma-separated list of identifiers (indexing starts with 0). JIT | [0-2] | 0=disabled, 1=[jit enabled](quickstart.md#jit) (default), 2=jit enabled, but graphs are disabled -VIZ | [1] | 0=disabled, 1=[viz enabled](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/viz) \ No newline at end of file +VIZ | [1] | 0=disabled, 1=[viz enabled](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/viz) +ALLOW_TF32 | [1] | enable TensorFloat-32 tensor cores on Ampere or newer GPUs. +WEBGPU_BACKEND | [WGPUBackendType_Metal, ...] | Force select a backend for WebGPU (Metal, DirectX, OpenGL, Vulkan...) +CUDA_PATH | str | Use `CUDA_PATH/include` for CUDA headers for CUDA and NV backends. If not set, TinyGrad will use `/usr/local/cuda/include`, `/usr/include` and `/opt/cuda/include`. + +## Debug breakdown + +Variable | Value | Description +---|---|--- +DEBUG | >= 1 | Enables debugging and lists devices being used +DEBUG | >= 2 | Provides performance metrics for operations, including timing, memory usage, bandwidth for each kernel execution +DEBUG | >= 3 | Outputs buffers used for each kernel (shape, dtype and strides) and the applied optimizations at a kernel level +DEBUG | >= 4 | Outputs the generated kernel code +DEBUG | >= 5 | Displays the intermediate representation of the computation UOps (AST) +DEBUG | >= 6 | Displays the intermediate representation of the computation UOps in a linearized manner, detailing the operation sequence +DEBUG | >= 7 | Outputs the assembly code generated for the target hardware diff --git a/tinygrad_repo/docs/index.md b/tinygrad_repo/docs/index.md index 45f070645d..f80c1242e2 100644 --- a/tinygrad_repo/docs/index.md +++ b/tinygrad_repo/docs/index.md @@ -42,7 +42,7 @@ There's nothing special about a "Module" class in tinygrad, it's just a normal c ### tinygrad is functional -In tinygrad, you can do [`x.conv2d(w, b)`](tensor/ops.md/#tinygrad.Tensor.conv2d) or [`x.sparse_categorical_cross_entropy(y)`](tensor/ops.md/#tinygrad.Tensor.sparse_categorical_crossentropy). We do also have a [`Conv2D`](nn.md/#tinygrad.nn.Conv2d) class like PyTorch if you want a place to keep the state, but all stateless operations don't have classes. +In tinygrad, you can do [`x.conv2d(w, b)`](tensor/ops.md/#tinygrad.Tensor.conv2d) or [`x.sparse_categorical_crossentropy(y)`](tensor/ops.md/#tinygrad.Tensor.sparse_categorical_crossentropy). We do also have a [`Conv2D`](nn.md/#tinygrad.nn.Conv2d) class like PyTorch if you want a place to keep the state, but all stateless operations don't have classes. ### tinygrad is lazy diff --git a/tinygrad_repo/docs/mnist.md b/tinygrad_repo/docs/mnist.md index 8aae08f241..ce55890eb9 100644 --- a/tinygrad_repo/docs/mnist.md +++ b/tinygrad_repo/docs/mnist.md @@ -17,7 +17,7 @@ from tinygrad import Device print(Device.DEFAULT) ``` -You will see `CUDA` here on a GPU instance, or `CLANG` here on a CPU instance. +You will see `CUDA` here on a GPU instance, or `CPU` here on a CPU instance. ## A simple model diff --git a/tinygrad_repo/docs/nn.md b/tinygrad_repo/docs/nn.md index 48dc0fb982..4c030bc2d8 100644 --- a/tinygrad_repo/docs/nn.md +++ b/tinygrad_repo/docs/nn.md @@ -29,5 +29,12 @@ ::: tinygrad.nn.state.get_state_dict ::: tinygrad.nn.state.get_parameters ::: tinygrad.nn.state.load_state_dict +::: tinygrad.nn.state.tar_extract + options: + show_signature: false + separate_signature: false ::: tinygrad.nn.state.torch_load + options: + show_signature: false + separate_signature: false ::: tinygrad.nn.state.gguf_load diff --git a/tinygrad_repo/docs/quickstart.md b/tinygrad_repo/docs/quickstart.md index 44ff99a350..0153cd5126 100644 --- a/tinygrad_repo/docs/quickstart.md +++ b/tinygrad_repo/docs/quickstart.md @@ -110,7 +110,7 @@ class TinyNet: def __call__(self, x): x = self.l1(x) - x = x.leakyrelu() + x = x.leaky_relu() x = self.l2(x) return x @@ -118,7 +118,7 @@ net = TinyNet() ``` We can see that the forward pass of our neural network is just the sequence of operations performed on the input tensor `x`. -We can also see that functional operations like `leakyrelu` are not defined as classes and instead are just methods we can just call. +We can also see that functional operations like `leaky_relu` are not defined as classes and instead are just methods we can just call. Finally, we just initialize an instance of our neural network, and we are ready to start training it. ## Training diff --git a/tinygrad_repo/docs/runtime.md b/tinygrad_repo/docs/runtime.md index 2775ffb525..045ca91ce6 100644 --- a/tinygrad_repo/docs/runtime.md +++ b/tinygrad_repo/docs/runtime.md @@ -1,14 +1,74 @@ # Runtimes -tinygrad supports various runtimes, enabling your code to scale across a wide range of devices. The default runtime can be automatically selected based on the available hardware, or you can force a specific runtime to be default using environment variables (e.g., `CLANG=1`). +tinygrad supports various runtimes, enabling your code to scale across a wide range of devices. The default runtime can be automatically selected based on the available hardware, or you can force a specific runtime to be default using environment variables (e.g., `CPU=1`). | Runtime | Description | Requirements | |---------|-------------|--------------| | [NV](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_nv.py) | Provides acceleration for NVIDIA GPUs | Ampere/Ada series GPUs | -| [AMD](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_amd.py) | Provides acceleration for AMD GPUs | RDNA2/RDNA3 series GPUs | +| [AMD](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_amd.py) | Provides acceleration for AMD GPUs | RDNA2/RDNA3/RDNA4 series GPUs. You can select one of the interfaces for communication by setting `AMD_IFACE=(KFD|PCI)`. See [AMD interfaces](#amd-interfaces) for more details. | | [QCOM](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_qcom.py) | Provides acceleration for QCOM GPUs | 6xx series GPUs | | [METAL](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_metal.py) | Utilizes Metal for acceleration on Apple devices | M1+ Macs; Metal 3.0+ for `bfloat` support | | [CUDA](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_cuda.py) | Utilizes CUDA for acceleration on NVIDIA GPUs | NVIDIA GPU with CUDA support | | [GPU (OpenCL)](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_gpu.py) | Accelerates computations using OpenCL on GPUs | OpenCL 2.0 compatible device | -| [CLANG (C Code)](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_clang.py) | Runs on CPU using the clang compiler | `clang` compiler in system `PATH` | -| [LLVM](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_llvm.py) | Runs on CPU using the LLVM compiler infrastructure | `llvmlite` package installed | +| [CPU (C Code)](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_cpu.py) | Runs on CPU using the clang compiler | `clang` compiler in system `PATH` | +| [LLVM (LLVM IR)](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_llvm.py) | Runs on CPU using the LLVM compiler infrastructure | llvm libraries installed and findable | +| [WEBGPU](https://github.com/tinygrad/tinygrad/tree/master/tinygrad/runtime/ops_webgpu.py) | Runs on GPU using the Dawn WebGPU engine (used in Google Chrome) | Dawn library installed and findable. Download binaries [here](https://github.com/wpmed92/pydawn/releases/tag/v0.1.6). | + +## Interoperability + +tinygrad provides interoperability with OpenCL and PyTorch, allowing efficient tensor data sharing between frameworks through the `Tensor.from_blob` API. This enables zero-copy operations by working directly with external memory pointers. + +**Important**: When using external memory pointers with tinygrad tensors, you must ensure these pointers remain valid throughout the entire lifetime of the tinygrad tensor to prevent memory corruption. + +### `CUDA`/`METAL` PyTorch Interoperability + +You can seamlessly work with CUDA/MPS tensors between PyTorch and tinygrad without data copying: +```python +from tinygrad.dtype import _from_torch_dtype +tensor1 = torch.tensor([1.0, 2.0, 3.0], device=torch.device("cuda")) +tiny_tensor1 = Tensor.from_blob(tensor1.data_ptr(), tensor1.shape, dtype=_from_torch_dtype(tensor1.dtype), device='CUDA') + +# Before tinygrad calculations, mps needs to be synchronized to make sure data is valid. +if data.device.type == "mps": torch.mps.synchronize() +else: torch.cuda.synchronize() + +x = (tiny_tensor1 + 1).realize() +``` + +### `QCOM` OpenCL Interoperability + +tinygrad supports OpenCL interoperability on `QCOM` backend. + +Buffer interop allows direct access to OpenCL memory buffers: +```python +# create raw opencl buffer. +cl_buf = cl.clCreateBuffer(cl_context, cl.CL_MEM_READ_WRITE, 0x100, None, status := ctypes.c_int32()) + +# extract pointers +cl_buf_desc_ptr = to_mv(ctypes.addressof(cl_buf), 8).cast('Q')[0] +rawbuf_ptr = to_mv(cl_buf_desc_ptr, 0x100).cast('Q')[20] # offset 0xA0 is a raw gpu pointer. + +# create tiny tensor +tiny = Tensor.from_blob(rawbuf_ptr, (8, 8), dtype=dtypes.int, device='QCOM') +``` + +And the same for the images: +```python +# create cl image. +cl_img = cl.clCreateImage2D(cl_context, cl.CL_MEM_READ_WRITE, cl.cl_image_format(cl.CL_RGBA, cl.CL_FLOAT), w, h, 0, None, status := ctypes.c_int32()) + +# extract pointers +cl_buf_desc_ptr = to_mv(ctypes.addressof(cl_img), 8).cast('Q')[0] +rawbuf_ptr = to_mv(cl_buf_desc_ptr, 0x100).cast('Q')[20] # offset 0xA0 is a raw gpu pointer. + +# create tiny tensor +tiny = Tensor.from_blob(rawbuf_ptr, (h*w*4,), dtype=dtypes.imagef((h,w)), device='QCOM') +``` + +## AMD Interfaces +AMD backend supports several interfaces for communicating with devices: + +* `KFD`: uses the amdgpu driver +* `PCI`: uses the [AM driver](developer/am.md) + +You can force an interface by setting `AMD_IFACE` to one of these values. In the case of `AMD_IFACE=PCI`, this may unbind your GPU from the amdgpu driver. diff --git a/tinygrad_repo/docs/tensor/creation.md b/tinygrad_repo/docs/tensor/creation.md index 722d1a41e0..d58a1ea52f 100644 --- a/tinygrad_repo/docs/tensor/creation.md +++ b/tinygrad_repo/docs/tensor/creation.md @@ -20,7 +20,9 @@ ::: tinygrad.Tensor.manual_seed ::: tinygrad.Tensor.rand +::: tinygrad.Tensor.rand_like ::: tinygrad.Tensor.randn +::: tinygrad.Tensor.randn_like ::: tinygrad.Tensor.randint ::: tinygrad.Tensor.normal ::: tinygrad.Tensor.uniform diff --git a/tinygrad_repo/docs/tensor/elementwise.md b/tinygrad_repo/docs/tensor/elementwise.md index 3d3858ad79..4893658953 100644 --- a/tinygrad_repo/docs/tensor/elementwise.md +++ b/tinygrad_repo/docs/tensor/elementwise.md @@ -22,6 +22,7 @@ Elementwise ops operate on a per element basis. They don't change the shape of t ::: tinygrad.Tensor.round ::: tinygrad.Tensor.isinf ::: tinygrad.Tensor.isnan +::: tinygrad.Tensor.isfinite ::: tinygrad.Tensor.lerp ::: tinygrad.Tensor.square ::: tinygrad.Tensor.clamp @@ -52,7 +53,7 @@ Elementwise ops operate on a per element basis. They don't change the shape of t ::: tinygrad.Tensor.erf ::: tinygrad.Tensor.gelu ::: tinygrad.Tensor.quick_gelu -::: tinygrad.Tensor.leakyrelu +::: tinygrad.Tensor.leaky_relu ::: tinygrad.Tensor.mish ::: tinygrad.Tensor.softplus ::: tinygrad.Tensor.softsign @@ -63,13 +64,19 @@ Elementwise ops operate on a per element basis. They don't change the shape of t ::: tinygrad.Tensor.sub ::: tinygrad.Tensor.mul ::: tinygrad.Tensor.div -::: tinygrad.Tensor.xor +::: tinygrad.Tensor.idiv +::: tinygrad.Tensor.mod +::: tinygrad.Tensor.bitwise_xor +::: tinygrad.Tensor.bitwise_and +::: tinygrad.Tensor.bitwise_or +::: tinygrad.Tensor.bitwise_not ::: tinygrad.Tensor.lshift ::: tinygrad.Tensor.rshift ::: tinygrad.Tensor.pow ::: tinygrad.Tensor.maximum ::: tinygrad.Tensor.minimum ::: tinygrad.Tensor.where +::: tinygrad.Tensor.copysign ## Casting Ops diff --git a/tinygrad_repo/docs/tensor/movement.md b/tinygrad_repo/docs/tensor/movement.md index acbc90819c..3d35dbb4b5 100644 --- a/tinygrad_repo/docs/tensor/movement.md +++ b/tinygrad_repo/docs/tensor/movement.md @@ -10,6 +10,7 @@ ## Movement (high level) +::: tinygrad.Tensor.__getitem__ ::: tinygrad.Tensor.gather ::: tinygrad.Tensor.cat ::: tinygrad.Tensor.stack @@ -24,3 +25,5 @@ ::: tinygrad.Tensor.transpose ::: tinygrad.Tensor.flatten ::: tinygrad.Tensor.unflatten +::: tinygrad.Tensor.roll +::: tinygrad.Tensor.rearrange \ No newline at end of file diff --git a/tinygrad_repo/docs/tensor/ops.md b/tinygrad_repo/docs/tensor/ops.md index dcfa7e53a6..f772b974ad 100644 --- a/tinygrad_repo/docs/tensor/ops.md +++ b/tinygrad_repo/docs/tensor/ops.md @@ -6,8 +6,10 @@ ::: tinygrad.Tensor.min ::: tinygrad.Tensor.any ::: tinygrad.Tensor.all +::: tinygrad.Tensor.isclose ::: tinygrad.Tensor.mean ::: tinygrad.Tensor.var +::: tinygrad.Tensor.var_mean ::: tinygrad.Tensor.std ::: tinygrad.Tensor.std_mean ::: tinygrad.Tensor.softmax @@ -21,6 +23,7 @@ ::: tinygrad.Tensor.avg_pool2d ::: tinygrad.Tensor.max_pool2d +::: tinygrad.Tensor.max_unpool2d ::: tinygrad.Tensor.conv2d ::: tinygrad.Tensor.conv_transpose2d ::: tinygrad.Tensor.dot @@ -32,6 +35,10 @@ ::: tinygrad.Tensor.tril ::: tinygrad.Tensor.interpolate ::: tinygrad.Tensor.scatter +::: tinygrad.Tensor.scatter_reduce +::: tinygrad.Tensor.masked_select +::: tinygrad.Tensor.sort +::: tinygrad.Tensor.topk ## Neural Network (functional) diff --git a/tinygrad_repo/docs/tensor/properties.md b/tinygrad_repo/docs/tensor/properties.md index b4a99de29e..a2c0a1ba23 100644 --- a/tinygrad_repo/docs/tensor/properties.md +++ b/tinygrad_repo/docs/tensor/properties.md @@ -25,6 +25,7 @@ ::: tinygrad.Tensor.replace ::: tinygrad.Tensor.assign ::: tinygrad.Tensor.detach +::: tinygrad.Tensor.clone ::: tinygrad.Tensor.to ::: tinygrad.Tensor.to_ ::: tinygrad.Tensor.shard diff --git a/tinygrad_repo/examples/beautiful_mnist.py b/tinygrad_repo/examples/beautiful_mnist.py index 4f43e414f8..b5c834ef02 100644 --- a/tinygrad_repo/examples/beautiful_mnist.py +++ b/tinygrad_repo/examples/beautiful_mnist.py @@ -1,4 +1,4 @@ -# model based off https://towardsdatascience.com/going-beyond-99-mnist-handwritten-digits-recognition-cfff96337392 +# model based off https://medium.com/data-science/going-beyond-99-mnist-handwritten-digits-recognition-cfff96337392 from typing import List, Callable from tinygrad import Tensor, TinyJit, nn, GlobalCounters from tinygrad.helpers import getenv, colored, trange diff --git a/tinygrad_repo/examples/benchmark_onnx.py b/tinygrad_repo/examples/benchmark_onnx.py new file mode 100644 index 0000000000..e88033bd0a --- /dev/null +++ b/tinygrad_repo/examples/benchmark_onnx.py @@ -0,0 +1,36 @@ +import sys, onnx, time, pickle +from tinygrad import TinyJit, GlobalCounters, fetch, getenv +from tinygrad.frontend.onnx import OnnxRunner +from extra.onnx_helpers import get_example_inputs, validate + +def load_onnx_model(onnx_file): + onnx_model = onnx.load(onnx_file) + run_onnx = OnnxRunner(onnx_model) + run_onnx_jit = TinyJit(lambda **kwargs: next(iter(run_onnx({k:v.to(None) for k,v in kwargs.items()}).values())), prune=True, optimize=True) + return run_onnx_jit, run_onnx.graph_inputs + +if __name__ == "__main__": + onnx_file = fetch(sys.argv[1]) + run_onnx_jit, input_specs = load_onnx_model(onnx_file) + print("loaded model") + + for i in range(3): + new_inputs = get_example_inputs(input_specs) + GlobalCounters.reset() + print(f"run {i}") + run_onnx_jit(**new_inputs) + + # run 20 times + for _ in range(20): + new_inputs = get_example_inputs(input_specs) + GlobalCounters.reset() + st = time.perf_counter() + out = run_onnx_jit(**new_inputs) + mt = time.perf_counter() + val = out.numpy() + et = time.perf_counter() + print(f"enqueue {(mt-st)*1e3:6.2f} ms -- total run {(et-st)*1e3:6.2f} ms") + + if getenv("ORT"): + validate(onnx_file, new_inputs, rtol=1e-3, atol=1e-3) + print("model validated") diff --git a/tinygrad_repo/examples/coder.py b/tinygrad_repo/examples/coder.py index f74fbc2e3f..c7c1ef5f13 100644 --- a/tinygrad_repo/examples/coder.py +++ b/tinygrad_repo/examples/coder.py @@ -34,8 +34,8 @@ if __name__ == "__main__": part2 = nn.state.torch_load(fetch("https://huggingface.co/teknium/OpenHermes-2.5-Mistral-7B/resolve/main/pytorch_model-00002-of-00002.bin?download=true")) with Timing("weights -> model: "): - nn.state.load_state_dict(model, fix_bf16(convert_from_huggingface(part1, model, 32, 8)), strict=False) - nn.state.load_state_dict(model, fix_bf16(convert_from_huggingface(part2, model, 32, 8)), strict=False) + nn.state.load_state_dict(model, fix_bf16(convert_from_huggingface(part1, 32, 32, 8)), strict=False) + nn.state.load_state_dict(model, fix_bf16(convert_from_huggingface(part2, 32, 32, 8)), strict=False) if not os.path.isfile("/tmp/tokenizer.model"): create_fixed_tokenizer("/tmp/tokenizer.model") spp = SentencePieceProcessor(model_file="/tmp/tokenizer.model") diff --git a/tinygrad_repo/examples/compile_efficientnet.py b/tinygrad_repo/examples/compile_efficientnet.py index 1a27c159c4..3690e7ed33 100644 --- a/tinygrad_repo/examples/compile_efficientnet.py +++ b/tinygrad_repo/examples/compile_efficientnet.py @@ -15,9 +15,9 @@ if __name__ == "__main__": if getenv("WEBGPU"): safe_save(get_state_dict(model), (dirname / "net.safetensors").as_posix()) load_state_dict(model, safe_load(str(dirname / "net.safetensors"))) - mode = "clang" if getenv("CLANG", "") != "" else "webgpu" if getenv("WEBGPU", "") != "" else "" + mode = "clang" if getenv("CPU", "") != "" else "webgpu" if getenv("WEBGPU", "") != "" else "" prg, inp_sizes, out_sizes, state = export_model(model, mode, Tensor.randn(1,3,224,224)) - if getenv("CLANG", "") == "": + if getenv("CPU", "") == "": ext = "js" if getenv("WEBGPU", "") != "" else "json" with open(dirname / f"net.{ext}", "w") as text_file: text_file.write(prg) @@ -68,6 +68,6 @@ if __name__ == "__main__": else printf("%s\\n", lbls[best_idx]); }""") - # CLANG=1 python3 examples/compile_efficientnet.py | clang -O2 -lm -x c - -o recognize && DEBUG=1 time ./recognize docs/showcase/stable_diffusion_by_tinygrad.jpg + # CPU=1 python3 examples/compile_efficientnet.py | clang -O2 -lm -x c - -o recognize && DEBUG=1 time ./recognize docs/showcase/stable_diffusion_by_tinygrad.jpg # category : 281 (tabby, tabby cat) with 9.452788 print('\n'.join(cprog)) diff --git a/tinygrad_repo/examples/compile_tensorflow.py b/tinygrad_repo/examples/compile_tensorflow.py index e3def3bbdb..3ad6f31195 100644 --- a/tinygrad_repo/examples/compile_tensorflow.py +++ b/tinygrad_repo/examples/compile_tensorflow.py @@ -1,14 +1,14 @@ # An example to compile a small Tensorflow model to extremely portable C code import os, sys -os.environ["CLANG"] = '1' +os.environ["CPU"] = '1' os.environ["JIT"] = '2' import numpy as np import subprocess import tensorflow as tf import tf2onnx -from extra.onnx import get_run_onnx +from tinygrad.frontend.onnx import OnnxRunner from tinygrad.tensor import Tensor from extra.export_model import export_model_clang, compile_net, jit_model @@ -25,7 +25,7 @@ class TinyOnnx: def __init__(self, keras_model): input_signature = [tf.TensorSpec([1,32], tf.float32, name='x')] onnx_model, _ = tf2onnx.convert.from_keras(keras_model, input_signature, opset=13) - self.run_onnx = get_run_onnx(onnx_model) + self.run_onnx = OnnxRunner(onnx_model) def forward(self, x): return self.run_onnx({"x": x}, debug=False)['predictions'] diff --git a/tinygrad_repo/examples/conversation.py b/tinygrad_repo/examples/conversation.py index fccfbebdda..721d3a09bc 100644 --- a/tinygrad_repo/examples/conversation.py +++ b/tinygrad_repo/examples/conversation.py @@ -117,7 +117,7 @@ def tts( stn_tst = text_mapper.get_text(text_to_synthesize, hps.data.add_blank, hps.data.text_cleaners) init_shape = stn_tst.shape assert init_shape[0] < pad_length, "text is too long" - x_tst, x_tst_lengths = stn_tst.pad(((0, pad_length - init_shape[0]),), 1).unsqueeze(0), Tensor([init_shape[0]], dtype=dtypes.int64) + x_tst, x_tst_lengths = stn_tst.pad(((0, pad_length - init_shape[0]),), value=1).unsqueeze(0), Tensor([init_shape[0]], dtype=dtypes.int64) sid = Tensor([speaker_id], dtype=dtypes.int64) if model_has_multiple_speakers else None # Perform inference. diff --git a/tinygrad_repo/examples/gpt2.py b/tinygrad_repo/examples/gpt2.py index 7f6f4d358f..c3d933b2a9 100644 --- a/tinygrad_repo/examples/gpt2.py +++ b/tinygrad_repo/examples/gpt2.py @@ -1,12 +1,13 @@ #!/usr/bin/env python3 -import os, argparse +import os, argparse, contextlib from typing import Optional, Union -import tiktoken +with contextlib.suppress(ImportError): import tiktoken from tinygrad import Tensor, TinyJit, Device, GlobalCounters, Variable, dtypes -from tinygrad.ops import UOp +from tinygrad.uop.ops import UOp from tinygrad.helpers import Timing, DEBUG, JIT, getenv, fetch, colored, trange from tinygrad.nn import Embedding, Linear, LayerNorm from tinygrad.nn.state import gguf_load, torch_load, load_state_dict, get_state_dict +from extra.bench_log import BenchEvent, WallTimeEvent MAX_CONTEXT = getenv("MAX_CONTEXT", 128) HALF = getenv("HALF") @@ -134,11 +135,12 @@ class GPT2: # lm head and wte are tied weights['lm_head.weight'] = weights['wte.weight'] - load_state_dict(model, weights) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + load_state_dict(model, weights) - if HALF: - for l in get_state_dict(model).values(): - l.replace(l.half().realize()) + if HALF: + for l in get_state_dict(model).values(): + l.replace(l.half().realize()) return GPT2(model, tokenizer) @@ -167,7 +169,8 @@ class GPT2: return key state_dict = { _remap_gguf_key(k): v for k, v in state_dict.items() } model = Transformer(**gpt2_params) - load_state_dict(model, state_dict) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + load_state_dict(model, state_dict) return GPT2(model, tiktoken.get_encoding("gpt2")) def __init__(self, model, tokenizer): @@ -185,11 +188,12 @@ class GPT2: with Timing("ran model in ", on_exit=(lambda et: (f", {(GlobalCounters.time_sum_s-st)*1e3:.2f} ms on GPU" if DEBUG>=2 else "")+ f", {GlobalCounters.global_ops*1e-9:.2f} GOPS, {GlobalCounters.global_mem*1e-9:.2f} GB"+ (f", {GlobalCounters.global_mem*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s" if DEBUG>=2 else "")) if DEBUG else None, enabled=timing): - if batch_size == 1 and len(toks[0][start_pos:]) == 1: - tokens = Variable("tokens", 0, VOCAB_SIZE).bind(toks[0][start_pos]) - else: - tokens = Tensor([x[start_pos:] for x in toks]) - tok = self.model(tokens, Variable("start_pos", 1 if start_pos else 0, MAX_CONTEXT).bind(start_pos), temperature).tolist() + with WallTimeEvent(BenchEvent.STEP): + if batch_size == 1 and len(toks[0][start_pos:]) == 1: + tokens = Variable("tokens", 0, VOCAB_SIZE).bind(toks[0][start_pos]) + else: + tokens = Tensor([x[start_pos:] for x in toks]) + tok = self.model(tokens, Variable("start_pos", 1 if start_pos else 0, MAX_CONTEXT-1).bind(start_pos), temperature).tolist() start_pos = len(toks[0]) for i,t in enumerate(tok): toks[i].append(t) return [self.tokenizer.decode(x) for x in toks] diff --git a/tinygrad_repo/examples/handcode_opt.py b/tinygrad_repo/examples/handcode_opt.py index 2938f7072c..cdb7e32861 100644 --- a/tinygrad_repo/examples/handcode_opt.py +++ b/tinygrad_repo/examples/handcode_opt.py @@ -1,14 +1,14 @@ -from typing import List, Tuple from extra.models.resnet import ResNet50 from extra.mcts_search import mcts_search from examples.mlperf.helpers import get_mlperf_bert_model from tinygrad import Tensor, Device, dtypes, nn from tinygrad.codegen.kernel import Kernel -from tinygrad.ops import Ops, sym_infer +from tinygrad.codegen.heuristic import hand_coded_optimizations +from tinygrad.uop.ops import Ops, sym_infer from tinygrad.device import Compiled -from tinygrad.engine.schedule import create_schedule -from tinygrad.engine.search import time_linearizer, beam_search, bufs_from_lin +from tinygrad.engine.search import beam_search, bufs_from_lin from tinygrad.helpers import DEBUG, ansilen, getenv, colored, TRACEMETA +from extra.optimization.helpers import time_linearizer def get_sched_resnet(): mdl = ResNet50() @@ -18,12 +18,12 @@ def get_sched_resnet(): # run model twice to get only what changes, these are the kernels of the model for _ in range(2): out = mdl(Tensor.empty(BS, 3, 224, 224)) - targets = [out.lazydata] + targets = [out] if getenv("BACKWARD"): optim.zero_grad() out.sparse_categorical_crossentropy(Tensor.empty(BS, dtype=dtypes.int)).backward() - targets += [x.lazydata for x in optim.schedule_step()] - sched = create_schedule(targets) + targets += [x for x in optim.schedule_step()] + sched = Tensor.schedule(*targets) print(f"schedule length {len(sched)}") return sched @@ -42,17 +42,16 @@ def get_sched_bert(): next_sentence_labels = Tensor.empty((BS, 1), dtype=dtypes.float32) # run model twice to get only what changes, these are the kernels of the model - seen = set() for _ in range(2): lm_logits, seq_relationship_logits = mdl(input_ids, attention_mask, masked_positions, segment_ids) - targets = [lm_logits.lazydata, seq_relationship_logits.lazydata] + targets = [lm_logits, seq_relationship_logits] if getenv("BACKWARD"): optim.zero_grad() loss = mdl.loss(lm_logits, seq_relationship_logits, masked_lm_ids, masked_lm_weights, next_sentence_labels) # ignore grad norm and loss scaler for now loss.backward() - targets += [x.lazydata for x in optim.schedule_step()] - sched = create_schedule(targets) + targets += [x for x in optim.schedule_step()] + sched = Tensor.schedule(*targets) print(f"schedule length {len(sched)}") return sched @@ -81,11 +80,11 @@ if __name__ == "__main__": rawbufs = bufs_from_lin(Kernel(si.ast)) # "linearize" the op into uops in different ways - lins: List[Tuple[Kernel, str]] = [] + lins: list[tuple[Kernel, str]] = [] # always try hand coded opt lin = Kernel(si.ast, opts=device.renderer) - lin.hand_coded_optimizations() + lin.apply_opts(hand_coded_optimizations(lin)) lins.append((lin, "HC")) # maybe try tensor cores diff --git a/tinygrad_repo/examples/hlb_cifar10.py b/tinygrad_repo/examples/hlb_cifar10.py index 78c59bdb18..35b188c746 100644 --- a/tinygrad_repo/examples/hlb_cifar10.py +++ b/tinygrad_repo/examples/hlb_cifar10.py @@ -11,7 +11,7 @@ from tinygrad import nn, dtypes, Tensor, Device, GlobalCounters, TinyJit from tinygrad.nn.state import get_state_dict, get_parameters from tinygrad.nn import optim from tinygrad.helpers import Context, BEAM, WINO, getenv, colored, prod -from tinygrad.multi import MultiLazyBuffer +from extra.bench_log import BenchEvent, WallTimeEvent cifar_mean = [0.4913997551666284, 0.48215855929893703, 0.4465309133731618] cifar_std = [0.24703225141799082, 0.24348516474564, 0.26158783926049628] @@ -35,8 +35,6 @@ class UnsyncedBatchNorm: self.num_batches_tracked = Tensor.zeros(1, dtype=dtypes.int, requires_grad=False) def __call__(self, x:Tensor): - if isinstance(x.lazydata, MultiLazyBuffer): assert x.lazydata.axis is None or x.lazydata.axis == 0 and len(x.lazydata.lbs) == self.num_devices - xr = x.reshape(self.num_devices, -1, *x.shape[1:]).cast(dtypes.float32) batch_mean, batch_invstd = self.calc_stats(xr) ret = xr.batchnorm( @@ -398,20 +396,23 @@ def train_cifar(): if STEPS == 0 or i == STEPS: break GlobalCounters.reset() - X, Y = next(batcher) - if len(GPUS) > 1: - X.shard_(GPUS, axis=0) - Y.shard_(GPUS, axis=0) - - with Context(BEAM=getenv("LATEBEAM", BEAM.value), WINO=getenv("LATEWINO", WINO.value)): - loss = train_step_jitted(model, optim.OptimizerGroup(opt_bias, opt_non_bias), [lr_sched_bias, lr_sched_non_bias], X, Y) - et = time.monotonic() - loss_cpu = loss.numpy() - # EMA for network weights - if getenv("EMA") and i > hyp['ema']['steps'] and (i+1) % hyp['ema']['every_n_steps'] == 0: - if model_ema is None: - model_ema = modelEMA(W, model) - model_ema.update(model, Tensor([projected_ema_decay_val*(i/STEPS)**hyp['ema']['decay_pow']])) + + with WallTimeEvent(BenchEvent.STEP): + X, Y = next(batcher) + if len(GPUS) > 1: + X.shard_(GPUS, axis=0) + Y.shard_(GPUS, axis=0) + + with Context(BEAM=getenv("LATEBEAM", BEAM.value), WINO=getenv("LATEWINO", WINO.value)): + loss = train_step_jitted(model, optim.OptimizerGroup(opt_bias, opt_non_bias), [lr_sched_bias, lr_sched_non_bias], X, Y) + et = time.monotonic() + loss_cpu = loss.numpy() + # EMA for network weights + if getenv("EMA") and i > hyp['ema']['steps'] and (i+1) % hyp['ema']['every_n_steps'] == 0: + if model_ema is None: + model_ema = modelEMA(W, model) + model_ema.update(model, Tensor([projected_ema_decay_val*(i/STEPS)**hyp['ema']['decay_pow']])) + cl = time.monotonic() device_str = loss.device if isinstance(loss.device, str) else f"{loss.device[0]} * {len(loss.device)}" # 53 221.74 ms run, 2.22 ms python, 219.52 ms CL, 803.39 loss, 0.000807 LR, 4.66 GB used, 3042.49 GFLOPS, 674.65 GOPS @@ -427,4 +428,5 @@ def train_cifar(): raise ValueError(colored(f"{eval_acc_pct=} < {target}", "red")) if __name__ == "__main__": - train_cifar() + with WallTimeEvent(BenchEvent.FULL): + train_cifar() diff --git a/tinygrad_repo/examples/llama.py b/tinygrad_repo/examples/llama.py index a39d85a1a2..8abdd9df98 100755 --- a/tinygrad_repo/examples/llama.py +++ b/tinygrad_repo/examples/llama.py @@ -13,6 +13,7 @@ from extra.models.llama import Transformer, convert_from_huggingface, fix_bf16 from sentencepiece import SentencePieceProcessor import tiktoken, sys from tiktoken.load import load_tiktoken_bpe +from extra.bench_log import BenchEvent, WallTimeEvent MAX_CONTEXT = getenv("MAX_CONTEXT", 4096) @@ -206,40 +207,43 @@ class LLaMa: model = Transformer(**params["args"], linear=linear, max_context=MAX_CONTEXT, jit=bool(JIT)) - if model_path.is_dir(): - weights = concat_weights([load(filename) for filename in [f"{model_path}/consolidated.{i:02d}.pth" for i in range(params["files"])]], device[0] if isinstance(device, tuple) else device) - else: - weights = load(str(model_path)) - if "model.embed_tokens.weight" in weights: - weights = convert_from_huggingface(weights, model, params["args"]["n_heads"], params["args"].get("n_kv_heads", params["args"]["n_heads"])) - - weights = fix_bf16(weights) - - with Context(BEAM=0): - # quantize - if quantize is not None: - weights = linear.quantize(weights, device) - for _,v in weights.items(): v.realize() - - # shard - if isinstance(device, tuple): - for k,v in nn.state.get_state_dict(model).items(): - if 'scale' in k: v.shard_(device, axis=None) # from quantized - elif '.attention.' in k: - if getenv("SHARD_KVCACHE") and ('.wq.' in k or '.wk.' in k or '.wv.' in k): v.shard_(device, axis=0) - else: v.shard_(device, axis=-1) - elif '.feed_forward.w1.' in k: v.shard_(device, axis=0) - elif '.feed_forward.w3.' in k: v.shard_(device, axis=0) - elif '.feed_forward.' in k: v.shard_(device, axis=-1) - elif 'tok_embeddings.weight' in k: v.shard_(device, axis=0) - elif 'output.weight' in k: v.shard_(device, axis=-1) - #elif k.endswith('.weight'): v.shard_(device, axis=-1) - #elif 'norm.' in k: v.shard_(device, axis=-1) - else: v.shard_(device, axis=None) - #print(k, v.shape, v.lazydata.axis) - - # replace weights in model - load_state_dict(model, weights, strict=False, consume=True) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + if model_path.is_dir(): + weights = concat_weights([load(filename) for filename in [f"{model_path}/consolidated.{i:02d}.pth" for i in range(params["files"])]], device[0] if isinstance(device, tuple) else device) + else: + weights = load(str(model_path)) + if "model.embed_tokens.weight" in weights: + weights = convert_from_huggingface(weights, params["args"]["n_layers"], params["args"]["n_heads"], params["args"].get("n_kv_heads", params["args"]["n_heads"])) + + weights = fix_bf16(weights) + + # prevent tracking model weights + # this is a part of a larger problem with BUFFER UOps and gc in TRACK_MATCH_STATS=2 + with Context(BEAM=0, TRACK_MATCH_STATS=0): + # quantize + if quantize is not None: + weights = linear.quantize(weights, device) + for _,v in weights.items(): v.realize() + + # shard + if isinstance(device, tuple): + for k,v in nn.state.get_state_dict(model).items(): + if 'scale' in k: v.shard_(device, axis=None) # from quantized + elif '.attention.' in k: + if getenv("SHARD_KVCACHE") and ('.wq.' in k or '.wk.' in k or '.wv.' in k): v.shard_(device, axis=0) + else: v.shard_(device, axis=-1) + elif '.feed_forward.w1.' in k: v.shard_(device, axis=0) + elif '.feed_forward.w3.' in k: v.shard_(device, axis=0) + elif '.feed_forward.' in k: v.shard_(device, axis=-1) + elif 'tok_embeddings.weight' in k: v.shard_(device, axis=0) + elif 'output.weight' in k: v.shard_(device, axis=-1) + #elif k.endswith('.weight'): v.shard_(device, axis=-1) + #elif 'norm.' in k: v.shard_(device, axis=-1) + else: v.shard_(device, axis=None) + #print(k, v.shape, v.lazydata.axis) + + # replace weights in model + load_state_dict(model, weights, strict=False, consume=True) return LLaMa(model, tokenizer) @@ -475,11 +479,12 @@ After you are done speaking, output [EOS]. You are not Chad. next_tok = Tensor([toks[start_pos:]], device=device) if tok_tensor is None or (len(toks)-start_pos) > 1 else tok_tensor.reshape(1, 1) with Profiling(enabled=args.profile): with Timing("total ", enabled=args.timing, on_exit=lambda x: f", {1e9/x:.2f} tok/s, {GlobalCounters.global_mem/x:.2f} GB/s, param {param_bytes/x:.2f} GB/s"): - with Timing("enqueue in ", on_exit=(lambda et: (f", {(GlobalCounters.time_sum_s-st)*1e3:.2f} ms on GPU" if DEBUG>=2 else "")+ - f", {GlobalCounters.global_ops*1e-9:.2f} GOPS, {GlobalCounters.global_mem*1e-9:.2f} GB"+ - (f", {GlobalCounters.global_mem*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s, param {param_bytes*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s" if DEBUG>=2 else "")) if DEBUG else None, enabled=args.timing): - tok_tensor = llama.model(next_tok, start_pos, args.temperature) - tok = tok_tensor.item() + with WallTimeEvent(BenchEvent.STEP): + with Timing("enqueue in ", on_exit=(lambda et: (f", {(GlobalCounters.time_sum_s-st)*1e3:.2f} ms on GPU" if DEBUG>=2 else "")+ + f", {GlobalCounters.global_ops*1e-9:.2f} GOPS, {GlobalCounters.global_mem*1e-9:.2f} GB"+ + (f", {GlobalCounters.global_mem*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s, param {param_bytes*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s" if DEBUG>=2 else "")) if DEBUG else None, enabled=args.timing): + tok_tensor = llama.model(next_tok, start_pos, args.temperature) + tok = tok_tensor.item() # use the kv cache start_pos = len(toks) diff --git a/tinygrad_repo/examples/llama3.py b/tinygrad_repo/examples/llama3.py index e331573d1a..0e49371caa 100644 --- a/tinygrad_repo/examples/llama3.py +++ b/tinygrad_repo/examples/llama3.py @@ -7,6 +7,7 @@ from extra.models.llama import Transformer, convert_from_huggingface, convert_fr from tinygrad.nn.state import safe_load, torch_load, load_state_dict, get_parameters, gguf_load from tinygrad import Tensor, dtypes, nn, Context, Device, GlobalCounters from tinygrad.helpers import Profiling, Timing, DEBUG, colored, fetch, tqdm +from extra.bench_log import BenchEvent, WallTimeEvent class Tokenizer: pat_str = r"(?i:'s|'t|'re|'ve|'m|'ll|'d)|[^\r\n\p{L}\p{N}]?\p{L}+|\p{N}{1,3}| ?[^\s\p{L}\p{N}]+[\r\n]*|\s*[\r\n]+|\s+(?!\S)|\s+" @@ -47,7 +48,7 @@ def concat_weights(models, device=None): disk_tensors: List[Tensor] = [model[name] for model in models] if len(disk_tensors) == 1 or len(disk_tensors[0].shape) == 1: return disk_tensors[0].to(device=device) - axis = 1 if name.endswith(".attention.wo.weight") or name.endswith(".feed_forward.w2.weight") else 0 + axis = 1 if name.endswith((".attention.wo.weight", ".feed_forward.w2.weight")) else 0 lazy_tensors = [data.to(device=device) for data in disk_tensors] return lazy_tensors[0].cat(*lazy_tensors[1:], dim=axis) return {name: convert(name) for name in {name: None for model in models for name in model}} @@ -73,16 +74,17 @@ class Int8Linear: self.scale = Tensor.ones(out_features, dtype=dtypes.half) def __call__(self, x): - return x.dot(self.weight.cast(dtype=dtypes.half).T*self.scale) + return x.dot(self.weight.cast(self.scale.dtype).T*self.scale) @staticmethod - def quantize(tensors, device): + def quantize(tensors, device, scale_dtype=dtypes.float16, quantize_embeds=False): new_tensors = {} for name,v in tensors.items(): - if "feed_forward" in name or "attention.w" in name: + if "feed_forward" in name or "attention.w" in name or (quantize_embeds and "tok_embeddings.weight" in name): assert "weight" in name, name + v = v.cast(scale_dtype) scale = v.abs().max(axis=1) / 127.0 - int8_weight = (v.T/scale).T.cast(dtype=dtypes.int8) + int8_weight = (v.T/scale).T.round().cast(dtype=dtypes.int8) # without round(), cast truncates -34.9 to -34 new_tensors[name] = int8_weight new_tensors[name.replace('weight', 'scale')] = scale if isinstance(device, tuple): @@ -90,8 +92,20 @@ class Int8Linear: new_tensors[name.replace('weight', 'scale')].shard_(device, axis=None) else: new_tensors[name] = v + if quantize_embeds: new_tensors.update({"output.weight": new_tensors["tok_embeddings.weight"], "output.scale": new_tensors["tok_embeddings.scale"]}) return new_tensors +class Int8Embedding: + def __init__(self, vocab_size:int, embed_size:int): + self.vocab_sz, self.embed_sz = vocab_size, embed_size + self.weight, self.scale = Tensor.ones(vocab_size, embed_size, dtype=dtypes.int8), Tensor.ones(vocab_size, dtype=dtypes.half) + + def __call__(self, idx:Tensor) -> Tensor: + if not hasattr(self, 'arange'): self.arange = Tensor.arange(self.vocab_sz, requires_grad=False, device=self.weight.device).unsqueeze(-1) + big_shp = idx.shape+(self.vocab_sz, self.embed_sz) + arange, idx, vals = self.arange.expand(big_shp), idx.reshape(idx.shape+(1, 1)).expand(big_shp), (self.weight.cast(self.scale.dtype).T*self.scale).T + return (arange == idx).mul(vals).sum(-2, dtype=vals.dtype) + def NF4Linear(block_size): _CODE = [ -1.0, -0.6961928009986877, -0.5250730514526367, -0.39491748809814453, -0.28444138169288635, -0.18477343022823334, -0.09105003625154495, 0.0, @@ -113,7 +127,8 @@ def NF4Linear(block_size): return x.linear(unscaled.reshape(self.out_features, self.in_features).T) @staticmethod - def quantize(state_dict: dict[str, Tensor], device) -> dict[str, Tensor]: + def quantize(state_dict: dict[str, Tensor], device, scale_dtype=dtypes.float16, quantize_embeds=False) -> dict[str, Tensor]: + assert not quantize_embeds # TODO: support this? new_state_dict = {} for k, v in state_dict.items(): if "feed_forward" in k or "attention.w" in k: @@ -121,7 +136,7 @@ def NF4Linear(block_size): scale = (grouped.abs().max(axis=1, keepdim=True)) coded = ((grouped / scale).unsqueeze(-1) - CODE.to(v.device)).abs().argmin(axis=-1).cast(dtypes.uint8).flatten() new_state_dict[k] = coded[::2] * 2 ** 4 + coded[1::2] - new_state_dict[k.replace(".weight", ".scale")] = scale.cast(dtypes.float16) + new_state_dict[k.replace(".weight", ".scale")] = scale.cast(scale_dtype) if isinstance(device, tuple): new_state_dict[k].shard_(device, axis=-1) new_state_dict[k.replace('weight', 'scale')].shard_(device, axis=None) @@ -144,47 +159,50 @@ MODEL_PARAMS = { "files": 8 } } -def build_transformer(model_path: Path, model_size="8B", quantize=None, device=None): +def build_transformer(model_path: Path, model_size="8B", quantize=None, scale_dtype=dtypes.float16, device=None, max_context=8192, load_weights=True): # build model - if quantize == "int8": linear = Int8Linear - elif quantize == "nf4": linear = NF4Linear(64) - else: linear = nn.Linear - model = Transformer(**MODEL_PARAMS[model_size]["args"], linear=linear, max_context=8192, jit=True) + if quantize == "int8": linear, embedding, quantize_embeds = Int8Linear, Int8Embedding, True + elif quantize == "nf4": linear, embedding, quantize_embeds = NF4Linear(64), nn.Embedding, False + else: linear, embedding, quantize_embeds = nn.Linear, nn.Embedding, False + model = Transformer(**MODEL_PARAMS[model_size]["args"], linear=linear, embedding=embedding, max_context=max_context, jit=True) + + if not load_weights: return model # load weights - if model_path.is_dir(): - if (model_path / "model.safetensors.index.json").exists(): weights = load(str(model_path / "model.safetensors.index.json")) - elif (model_path / "model.safetensors").exists(): weights = load(str(model_path / "model.safetensors")) - else: weights = concat_weights([load(str(model_path / f"consolidated.{i:02d}.pth")) for i in range(MODEL_PARAMS[model_size]["files"])], device[0] if isinstance(device, tuple) else device) - else: - weights = load(str(model_path)) - if "model.embed_tokens.weight" in weights: - weights = convert_from_huggingface(weights, model, MODEL_PARAMS[model_size]["args"]["n_heads"], MODEL_PARAMS[model_size]["args"]["n_kv_heads"]) - elif "token_embd.weight" in weights: - weights = convert_from_gguf(weights, model) - weights = fix_bf16(weights) - - with Context(BEAM=0): - # quantize - if quantize == "float16": weights = {k:v.cast(quantize).contiguous() for k,v in weights.items()} - elif quantize is not None: - weights = linear.quantize(weights, device) - for _,v in weights.items(): v.realize() - - # shard - if isinstance(device, tuple): - for k,v in nn.state.get_state_dict(model).items(): - if 'scale' in k: v.shard_(device, axis=None) # from quantized - elif '.attention.' in k: v.shard_(device, axis=-1) - elif '.feed_forward.w1.' in k: v.shard_(device, axis=0) - elif '.feed_forward.w3.' in k: v.shard_(device, axis=0) - elif '.feed_forward.' in k: v.shard_(device, axis=-1) - elif 'tok_embeddings.weight' in k: v.shard_(device, axis=0) - elif 'output.weight' in k: v.shard_(device, axis=0) - else: v.shard_(device, axis=None) - - # replace weights in model - load_state_dict(model, weights, strict=False, consume=True) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + if model_path.is_dir(): + if (model_path / "model.safetensors.index.json").exists(): weights = load(str(model_path / "model.safetensors.index.json")) + elif (model_path / "model.safetensors").exists(): weights = load(str(model_path / "model.safetensors")) + else: weights = concat_weights([load(str(model_path / f"consolidated.{i:02d}.pth")) for i in range(MODEL_PARAMS[model_size]["files"])], device[0] if isinstance(device, tuple) else device) + else: + weights = load(str(model_path)) + if "model.embed_tokens.weight" in weights: + weights = convert_from_huggingface(weights, MODEL_PARAMS[model_size]["args"]["n_layers"], MODEL_PARAMS[model_size]["args"]["n_heads"], MODEL_PARAMS[model_size]["args"]["n_kv_heads"]) + elif "token_embd.weight" in weights: + weights = convert_from_gguf(weights, MODEL_PARAMS[model_size]["args"]["n_layers"]) + weights = fix_bf16(weights) + + with Context(BEAM=0): + # quantize + if quantize == "float16": weights = {k:v.cast(quantize).contiguous() for k,v in weights.items()} + elif quantize is not None: + weights = linear.quantize(weights, device, scale_dtype, quantize_embeds) + for _,v in weights.items(): v.realize() + + # shard + if isinstance(device, tuple): + for k,v in nn.state.get_state_dict(model).items(): + if 'scale' in k: v.shard_(device, axis=None) # from quantized + elif '.attention.' in k: v.shard_(device, axis=-1) + elif '.feed_forward.w1.' in k: v.shard_(device, axis=0) + elif '.feed_forward.w3.' in k: v.shard_(device, axis=0) + elif '.feed_forward.' in k: v.shard_(device, axis=-1) + elif 'tok_embeddings.weight' in k: v.shard_(device, axis=0) + elif 'output.weight' in k: v.shard_(device, axis=0) + else: v.shard_(device, axis=None) + + # replace weights in model + load_state_dict(model, weights, strict=False, consume=True) return model # default settings @@ -247,11 +265,11 @@ if __name__ == "__main__": fetch("https://huggingface.co/TriAiExperiments/SFR-Iterative-DPO-LLaMA-3-8B-R/resolve/main/model-00004-of-00004.safetensors", "model-00004-of-00004.safetensors", subdir="llama3-8b-sfr") args.model = fetch("https://huggingface.co/TriAiExperiments/SFR-Iterative-DPO-LLaMA-3-8B-R/raw/main/model.safetensors.index.json", "model.safetensors.index.json", subdir="llama3-8b-sfr") elif args.size == "70B": - subdir = "Llama-3.1-Nemotron-70B-Instruct-HF" - args.model = fetch("https://huggingface.co/nvidia/Llama-3.1-Nemotron-70B-Instruct-HF/resolve/main/model.safetensors.index.json?download=true", "model.safetensors.index.json", subdir=subdir) + subdir = "DeepSeek-R1-Distill-Llama-70B" + args.model = fetch("https://huggingface.co/deepseek-ai/DeepSeek-R1-Distill-Llama-70B/resolve/main/model.safetensors.index.json?download=true", "model.safetensors.index.json", subdir=subdir) fetch("https://huggingface.co/bofenghuang/Meta-Llama-3-8B/resolve/main/original/tokenizer.model", "tokenizer.model", subdir=subdir) - for i in range(30): - fetch(f"https://huggingface.co/nvidia/Llama-3.1-Nemotron-70B-Instruct-HF/resolve/main/model-{i+1:05d}-of-00030.safetensors?download=true", f"model-{i+1:05d}-of-00030.safetensors", subdir=subdir) + for i in range(17): + fetch(f"https://huggingface.co/deepseek-ai/DeepSeek-R1-Distill-Llama-70B/resolve/main/model-{i+1:05d}-of-000017.safetensors?download=true", f"model-{i+1:05d}-of-000017.safetensors", subdir=subdir) assert args.model is not None, "please provide --model option" @@ -420,11 +438,12 @@ if __name__ == "__main__": st = GlobalCounters.time_sum_s with Profiling(enabled=args.profile): with Timing("total ", on_exit=lambda x: f", {1e9/x:.2f} tok/s, {GlobalCounters.global_mem/x:.2f} GB/s, param {param_bytes/x:.2f} GB/s"): - with Timing("enqueue in ", on_exit=(lambda et: (f", {(GlobalCounters.time_sum_s-st)*1e3:.2f} ms on GPU" if DEBUG>=2 else "")+ - f", {GlobalCounters.global_ops*1e-9:.2f} GOPS, {GlobalCounters.global_mem*1e-9:.2f} GB"+ - (f", {GlobalCounters.global_mem*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s, param {param_bytes*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s" if DEBUG>=2 else "")) if DEBUG else None): - tok = model(Tensor([[last_tok]], device=device), start_pos, TEMPERATURE, TOP_K, TOP_P, ALPHA_F, ALPHA_P) - tok = tok.item() + with WallTimeEvent(BenchEvent.STEP): + with Timing("enqueue in ", on_exit=(lambda et: (f", {(GlobalCounters.time_sum_s-st)*1e3:.2f} ms on GPU" if DEBUG>=2 else "")+ + f", {GlobalCounters.global_ops*1e-9:.2f} GOPS, {GlobalCounters.global_mem*1e-9:.2f} GB"+ + (f", {GlobalCounters.global_mem*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s, param {param_bytes*1e-9/(GlobalCounters.time_sum_s-st):.2f} GB/s" if DEBUG>=2 else "")) if DEBUG else None): + tok = model(Tensor([[last_tok]], device=device), start_pos, TEMPERATURE, TOP_K, TOP_P, ALPHA_F, ALPHA_P) + tok = tok.item() start_pos += 1 last_tok = tok generated += tokenizer.decode([tok]) diff --git a/tinygrad_repo/examples/llm.c/export.py b/tinygrad_repo/examples/llm.c/export.py index c0d52f32cd..bc13a09fbc 100755 --- a/tinygrad_repo/examples/llm.c/export.py +++ b/tinygrad_repo/examples/llm.c/export.py @@ -2,13 +2,12 @@ import os if "NOOPT" not in os.environ: os.environ["NOOPT"] = "1" from tinygrad import Device, nn, Tensor, dtypes, Variable -Device.DEFAULT = "CLANG" +Device.DEFAULT = "CPU" from train_gpt2 import GPT, GPTConfig from tinygrad.helpers import dedup, to_function_name, flatten, getenv, GlobalCounters, ansilen, to_function_name -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import get_kernel, run_schedule from tinygrad.engine.memory import memory_planner -from tinygrad.ops import Ops +from tinygrad.uop.ops import Ops TIMING = getenv("TIMING") @@ -26,7 +25,7 @@ if __name__ == "__main__": Tensor.training = True optimizer = nn.optim.Adam(nn.state.get_parameters(model), lr=1e-4) warmup_count = getenv("WARMUP", 3) - for i in range(warmup_count): # TODO: why does it take three and not two to stablize + for i in range(warmup_count): # TODO: why does it take three and not two to stabilize GlobalCounters.reset() X = Tensor.empty(4, 64, dtype=dtypes.int).reshape(B, T) Y = Tensor.empty(4, 64, dtype=dtypes.int).reshape(B, T) @@ -37,16 +36,16 @@ if __name__ == "__main__": tensors = optimizer.schedule_step() else: tensors = [] - sched = create_schedule([loss.lazydata] + [x.lazydata for x in tensors]) + sched = loss.schedule(*tensors) print(f"calls {i}:", len(sched)) #run_schedule(sched[:]) sched = memory_planner(sched) ast_dedup = dedup([si.ast for si in sched if si.ast.op is Ops.SINK]) srcs = {} for ast in ast_dedup: - k = get_kernel(Device["CLANG"].renderer, ast) + k = get_kernel(Device["CPU"].renderer, ast) k.linearize() - src = Device["CLANG"].renderer.render(to_function_name(k.name), k.uops) + src = Device["CPU"].renderer.render(to_function_name(k.name), k.uops) srcs[ast] = (k.name, src) print("functions:", len(srcs)) used_buffers = dedup(flatten([si.bufs for si in sched])) diff --git a/tinygrad_repo/examples/llm.c/train_gpt2.py b/tinygrad_repo/examples/llm.c/train_gpt2.py index d75af54b14..e259cf4466 100755 --- a/tinygrad_repo/examples/llm.c/train_gpt2.py +++ b/tinygrad_repo/examples/llm.c/train_gpt2.py @@ -99,7 +99,7 @@ class GPT: def __call__(self, idx:Tensor, targets=None): b, t = idx.shape - pos = Tensor.arange(0, t) + pos = Tensor.arange(0, t, device=idx.device) tok_emb = self.wte(idx) # token embeddings of shape (b, t, n_embd) pos_emb = self.wpe(pos) # position embeddings of shape (t, n_embd) @@ -124,6 +124,7 @@ if __name__ == "__main__": parser.add_argument("--batch_size", type=int, default=4, help="batch size") parser.add_argument("--sequence_length", type=int, default=64, help="sequence length") parser.add_argument("--skip_test", action="store_true", help="skip test") + parser.add_argument("--gpus", type=int, default=1, help="sequence length") args = parser.parse_args() B, T = args.batch_size, args.sequence_length assert 1 <= T <= 1024 @@ -131,6 +132,10 @@ if __name__ == "__main__": model = GPT(GPTConfig(n_layer=12, n_head=12, n_embd=768)) model.load_pretrained() + if args.gpus > 1: + GPUS = tuple(f'{Device.DEFAULT}:{i}' for i in range(args.gpus)) + for x in nn.state.get_parameters(model): x.to_(GPUS) # we put a copy of the model on every GPU + # init the tokenizer enc = tiktoken.get_encoding("gpt2") encode = lambda s: enc.encode(s, allowed_special={"<|endoftext|>"}) @@ -165,23 +170,32 @@ if __name__ == "__main__": x, y = next(data_iter) # we'll overfit this batch below optimizer = nn.optim.AdamW(nn.state.get_parameters(model), lr=1e-4, weight_decay=0) + print(f"model state: {sum(x.nbytes() for x in nn.state.get_parameters(model))/1e9:.2f} GB") + print(f"optimizer state: {sum(x.nbytes() for x in nn.state.get_parameters(optimizer))/1e9:.2f} GB") + + # shard the data on axis 0 + if args.gpus > 1: x, y = x.shard(GPUS, axis=0), y.shard(GPUS, axis=0) + @TinyJit - def step(x, y): + @Tensor.train() + def step(x:Tensor, y:Tensor) -> Tensor: _, loss = model(x, y) optimizer.zero_grad() loss.backward() return loss.realize(*optimizer.schedule_step()) - with Tensor.train(): - for i in range(args.num_iterations): - GlobalCounters.reset() - t0 = time.time() - loss = step(x.contiguous(), y.contiguous()) - Device[Device.DEFAULT].synchronize() - t1 = time.time() - print(f"iteration {i}, loss: {loss.item():.6f}, time: {(t1-t0)*1000:.3f}ms, {int(B*T/(t1-t0))} tok/s") + for i in range(args.num_iterations): + GlobalCounters.reset() + t0 = time.perf_counter() + loss = step(x.contiguous(), y.contiguous()) + Device[Device.DEFAULT].synchronize() + t1 = time.perf_counter() + print(f"iteration {i}, loss: {loss.item():.6f}, time: {(t1-t0)*1000:.3f}ms, {int(B*T/(t1-t0))} tok/s, {GlobalCounters.global_mem/1e9:.2f} GB") if not args.skip_test: + # copy back to single gpu for test + if args.gpus > 1: + for x in nn.state.get_parameters(model): x.to_(Device.DEFAULT) start = "<|endoftext|>" start_ids = encode(start) x = (Tensor(start_ids)[None, ...]) diff --git a/tinygrad_repo/examples/minrf.py b/tinygrad_repo/examples/minrf.py new file mode 100644 index 0000000000..221a0019e6 --- /dev/null +++ b/tinygrad_repo/examples/minrf.py @@ -0,0 +1,157 @@ +# much taken from https://github.com/cloneofsimo/minRF +from tinygrad import Tensor, nn, GlobalCounters, TinyJit +from tinygrad.helpers import getenv, trange +from extra.models.llama import Attention, FeedForward, precompute_freqs_cis + +def modulate(x:Tensor, shift:Tensor, scale:Tensor) -> Tensor: return x * (1 + scale.unsqueeze(1)) + shift.unsqueeze(1) + +# TODO: why doesn't the TimestepEmbedder from minRF work? +class TimestepEmbedder: + def __init__(self, hidden_size): self.mlp = [nn.Linear(1, hidden_size), Tensor.silu, nn.Linear(hidden_size, hidden_size)] + def __call__(self, t:Tensor): return t.reshape(-1, 1).sequential(self.mlp) + +class TransformerBlock: + def __init__(self, dim, n_heads, norm_eps=1e-5): + self.attention = Attention(dim, n_heads) + self.feed_forward = FeedForward(dim, 4*dim) + self.attention_norm = nn.LayerNorm(dim, eps=norm_eps) + self.ffn_norm = nn.LayerNorm(dim, eps=norm_eps) + self.adaLN_modulation = nn.Linear(dim, 6 * dim, bias=True) + + def __call__(self, x:Tensor, freqs_cis:Tensor, adaln_input:Tensor): + shift_msa, scale_msa, gate_msa, shift_mlp, scale_mlp, gate_mlp = self.adaLN_modulation(adaln_input.silu()).chunk(6, dim=1) + x = x + gate_msa.unsqueeze(1) * self.attention(modulate(self.attention_norm(x), shift_msa, scale_msa), 0, freqs_cis) + x = x + gate_mlp.unsqueeze(1) * self.feed_forward(modulate(self.ffn_norm(x), shift_mlp, scale_mlp)) + return x.contiguous().contiguous_backward() + +class FinalLayer: + def __init__(self, dim, patch_size, out_channels): + self.norm_final = nn.LayerNorm(dim, elementwise_affine=False, eps=1e-6) + self.linear = nn.Linear(dim, patch_size*patch_size*out_channels, bias=True) + self.adaLN_modulation = nn.Linear(dim, 2 * dim, bias=True) + + # init weights/bias to 0 + self.linear.weight.replace(self.linear.weight.zeros_like().contiguous()) + self.linear.bias.replace(self.linear.bias.zeros_like().contiguous()) + + def __call__(self, x:Tensor, c:Tensor): + shift, scale = self.adaLN_modulation(c.silu()).chunk(2, dim=1) + x = modulate(self.norm_final(x), shift, scale) + return self.linear(x) + +# channels=1, input_size=32, dim=64, n_layers=6, n_heads=4, num_classes=10 +class DiT_Llama: + def __init__(self, in_channels=1, dim=64, n_layers=6, n_heads=4, num_classes=10, patch_size=2): + self.patch_size = patch_size + self.out_channels = in_channels + self.num_classes = num_classes + + self.init_conv_seq = [ + nn.Conv2d(in_channels, dim // 2, kernel_size=5, padding=2, stride=1), Tensor.silu, nn.GroupNorm(32, dim//2), + nn.Conv2d(dim //2, dim // 2, kernel_size=5, padding=2, stride=1), Tensor.silu, nn.GroupNorm(32, dim//2), + ] + + self.x_embedder = nn.Linear(self.patch_size * self.patch_size * dim // 2, dim, bias=True) + self.t_embedder = TimestepEmbedder(dim) + self.y_embedder = nn.Embedding(num_classes+1, dim) + self.final_layer = FinalLayer(dim, self.patch_size, self.out_channels) + + self.freqs_cis = precompute_freqs_cis(dim // n_heads, 4096) + self.layers = [TransformerBlock(dim, n_heads) for _ in range(n_layers)] + + def unpatchify(self, x:Tensor): + c, p = self.out_channels, self.patch_size + h = w = int(x.shape[1] ** 0.5) + x = x.reshape(shape=(x.shape[0], h, w, p, p, c)) + x = x.rearrange("n h w p q c -> n c h p w q") + return x.reshape(shape=(x.shape[0], c, h * p, h * p)) + + def patchify(self, x:Tensor): + B, C, H, W = x.shape + x = x.reshape(B, C, H // self.patch_size, self.patch_size, W // self.patch_size, self.patch_size) + x = x.permute(0, 2, 4, 1, 3, 5).flatten(-3).flatten(1, 2) + return x # B + + def __call__(self, x:Tensor, t:Tensor, y:Tensor) -> Tensor: + x = x.sequential(self.init_conv_seq) + x = self.patchify(x) + x = self.x_embedder(x) + adaln_input = self.t_embedder(t) + self.y_embedder(y) + adaln_input = adaln_input.contiguous() + for layer in self.layers: + x = layer(x, self.freqs_cis[:, :x.size(1)], adaln_input=adaln_input) + x = self.final_layer(x, adaln_input) + return self.unpatchify(x) + + def rf(self, x:Tensor, cond:Tensor): + b = x.shape[0] + # self.ln is True + t = Tensor.randn((b,)).sigmoid() + texp = t.view([b, *([1] * len(x.shape[1:]))]) + + # conditional dropout + dropout_prob = 0.1 + cond = (Tensor.rand(cond.shape[0]) < dropout_prob).where(cond.full_like(self.num_classes), cond) + + # this is rectified flow + z1 = x.randn_like() + zt = (1 - texp) * x + texp * z1 + vtheta = self(zt, t, cond) + + # MSE loss + return ((z1 - x) - vtheta).square().mean() + + def sample(self, z, cond, null_cond, sample_steps=50, cfg=2.0): + b = z.size(0) + dt = Tensor.full((b,)+(1,)*len(z.shape[1:]), fill_value=1.0/sample_steps).contiguous() + images = [z] + for i in range(sample_steps, 0, -1): + t = Tensor.full((b,), fill_value=i/sample_steps).contiguous() + vc = self(z, t, cond) + vu = self(z, t, null_cond) + vc = vu + cfg * (vc - vu) + z = z - dt * vc + z = z.contiguous() + images.append(z) + return images + +def mviz(t:Tensor): + assert len(t.shape) == 4 and t.shape[1] == 1 + ft = t.permute(1,2,0,3).reshape(32, -1) + assert ft.shape[-1]%32 == 0 + print("") + for y in ((ft+1)/2).clamp(0,1).tolist(): + ln = [f"\033[38;5;{232+int(x*23)}m██" for x in y] + print(''.join(ln) + "\033[0m") + +if __name__ == "__main__": + X_train, Y_train, X_test, Y_test = nn.datasets.mnist() + X_train = X_train.pad((2,2,2,2)) + X_train = ((X_train.float()/255)-0.5)/0.5 + Y_train = Y_train.int() + + model = DiT_Llama(patch_size=getenv("PATCH_SIZE", 2)) + for r in nn.state.get_parameters(model): r.realize() + optimizer = nn.optim.Adam(nn.state.get_parameters(model), lr=5e-4) + + @TinyJit + @Tensor.train() + def train_step(): + if getenv("OVERFIT"): samples = Tensor.zeros(getenv("BS", 256), dtype='int') + else: samples = Tensor.randint(getenv("BS", 256), high=X_train.shape[0]) + optimizer.zero_grad() + loss = model.rf(X_train[samples], Y_train[samples]) + loss.backward() + optimizer.step() + return loss + + @TinyJit + @Tensor.test() + def sample(z:Tensor, cond:Tensor) -> Tensor: + return model.sample(z, cond, Tensor.full_like(cond, 10), sample_steps=getenv("SAMPLE_STEPS", 20))[-1] + + for steps in (t:=trange(getenv("STEPS", 5000))): + if steps%10 == 0: mviz(sample(Tensor.randn(3, 1, 32, 32), Tensor([5,0,4], dtype='int'))) + GlobalCounters.reset() + loss = train_step() + t.set_description(f"loss: {loss.item():9.2f}") diff --git a/tinygrad_repo/examples/mixtral.py b/tinygrad_repo/examples/mixtral.py index f2627f5dff..3266c8248e 100644 --- a/tinygrad_repo/examples/mixtral.py +++ b/tinygrad_repo/examples/mixtral.py @@ -3,6 +3,7 @@ from tinygrad import Tensor, nn, Device, GlobalCounters, Variable from tinygrad.helpers import Timing, Profiling, CI, tqdm from tinygrad.nn.state import torch_load, get_state_dict from extra.models.llama import FeedForward, Transformer +from extra.bench_log import BenchEvent, WallTimeEvent class MixtureFeedForward: def __init__(self, num_experts:int, dim:int, hidden_dim:int, linear=nn.Linear): @@ -30,18 +31,19 @@ if __name__ == "__main__": help="Path to the downloaded weights") args = parser.parse_args() - state = torch_load(args.weights + "/consolidated.00.pth.b") - model = Transformer(n_layers=32, dim=4096, hidden_dim=14336, n_heads=32, n_kv_heads=8, norm_eps=1e-5, vocab_size=32000, feed_forward=functools.partial(MixtureFeedForward, 8), jit=False) - model_state_dict = get_state_dict(model) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + state = torch_load(args.weights + "/consolidated.00.pth.b") + model = Transformer(n_layers=32, dim=4096, hidden_dim=14336, n_heads=32, n_kv_heads=8, norm_eps=1e-5, vocab_size=32000, feed_forward=functools.partial(MixtureFeedForward, 8), jit=False) + model_state_dict = get_state_dict(model) - for k in (t := tqdm(state, disable=CI)): - if 'feed_forward.experts.' in k: - expert_no = int(k.split('feed_forward.experts.')[1].split('.')[0]) - device = Device.DEFAULT + ":" + str((expert_no//2)+1) - else: - device = Device.DEFAULT - t.set_description(f"ram used: {GlobalCounters.mem_used/1e9:5.2f} GB, loading {k} to {device}") - model_state_dict[k].replace(state[k].to(device).half()).realize() + for k in (t := tqdm(state, disable=CI)): + if 'feed_forward.experts.' in k: + expert_no = int(k.split('feed_forward.experts.')[1].split('.')[0]) + device = Device.DEFAULT + ":" + str((expert_no//2)+1) + else: + device = Device.DEFAULT + t.set_description(f"ram used: {GlobalCounters.mem_used/1e9:5.2f} GB, loading {k} to {device}") + model_state_dict[k].replace(state[k].to(device).half()).realize() if CI: print(f"ram used: {GlobalCounters.mem_used/1e9:5.2f} GB") from sentencepiece import SentencePieceProcessor @@ -53,7 +55,8 @@ if __name__ == "__main__": GlobalCounters.reset() with Profiling(sort="time", frac=0.1, enabled=args.profile): with Timing("total ", enabled=args.timing, on_exit=lambda x: f", {1e9/x:.2f} tok/sec"): - tok = model(Tensor([toks[start_pos:]]), 0 if start_pos == 0 else Variable("start_pos", 1, 1024).bind(start_pos), args.temperature).item() + with WallTimeEvent(BenchEvent.STEP): + tok = model(Tensor([toks[start_pos:]]), 0 if start_pos == 0 else Variable("start_pos", 1, 1024).bind(start_pos), args.temperature).item() toks.append(tok) start_pos += 1 print(spp.decode(toks)) diff --git a/tinygrad_repo/examples/mlperf/dataloader.py b/tinygrad_repo/examples/mlperf/dataloader.py index 3e78c18801..0942e83615 100644 --- a/tinygrad_repo/examples/mlperf/dataloader.py +++ b/tinygrad_repo/examples/mlperf/dataloader.py @@ -5,7 +5,7 @@ from multiprocessing import Queue, Process, shared_memory, connection, Lock, cpu import numpy as np from tinygrad import dtypes, Tensor -from tinygrad.helpers import getenv, prod, Context, round_up, tqdm +from tinygrad.helpers import getenv, prod, Context, round_up, tqdm, OSX ### ResNet @@ -129,14 +129,15 @@ def batch_load_resnet(batch_size=64, val=False, shuffle=True, seed=None, pad_fir q_in, q_out = Queue(), Queue() sz = (batch_size*BATCH_COUNT, 224, 224, 3) - if os.path.exists("/dev/shm/resnet_X"): os.unlink("/dev/shm/resnet_X") - shm = shared_memory.SharedMemory(name="resnet_X", create=True, size=prod(sz)) + shm_name = "resnet_X_val" if val else "resnet_X_train" + if not OSX and os.path.exists(f"/dev/shm/{shm_name}"): os.unlink(f"/dev/shm/{shm_name}") + shm = shared_memory.SharedMemory(name=shm_name, create=True, size=prod(sz)) procs = [] try: # disk:shm is slower - #X = Tensor.empty(*sz, dtype=dtypes.uint8, device=f"disk:shm:{shm.name}") - X = Tensor.empty(*sz, dtype=dtypes.uint8, device=f"disk:/dev/shm/resnet_X") + if OSX: X = Tensor.empty(*sz, dtype=dtypes.uint8, device=f"disk:shm:{shm.name}") + else: X = Tensor.empty(*sz, dtype=dtypes.uint8, device=f"disk:/dev/shm/{shm_name}") Y = [None] * (batch_size*BATCH_COUNT) for _ in range(cpu_count()): @@ -170,13 +171,13 @@ def batch_load_resnet(batch_size=64, val=False, shuffle=True, seed=None, pad_fir def process_batch_bert(data: List[dict]) -> dict[str, Tensor]: return { - "input_ids": Tensor(np.concatenate([s["input_ids"] for s in data], axis=0), dtype=dtypes.float32), - "input_mask": Tensor(np.concatenate([s["input_mask"] for s in data], axis=0), dtype=dtypes.default_float), - "segment_ids": Tensor(np.concatenate([s["segment_ids"] for s in data], axis=0), dtype=dtypes.float32), - "masked_lm_positions": Tensor(np.concatenate([s["masked_lm_positions"] for s in data], axis=0), dtype=dtypes.float32), - "masked_lm_ids": Tensor(np.concatenate([s["masked_lm_ids"] for s in data], axis=0), dtype=dtypes.float32), - "masked_lm_weights": Tensor(np.concatenate([s["masked_lm_weights"] for s in data], axis=0), dtype=dtypes.float32), - "next_sentence_labels": Tensor(np.concatenate([s["next_sentence_labels"] for s in data], axis=0), dtype=dtypes.float32), + "input_ids": Tensor(np.concatenate([s["input_ids"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), + "input_mask": Tensor(np.concatenate([s["input_mask"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), + "segment_ids": Tensor(np.concatenate([s["segment_ids"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), + "masked_lm_positions": Tensor(np.concatenate([s["masked_lm_positions"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), + "masked_lm_ids": Tensor(np.concatenate([s["masked_lm_ids"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), + "masked_lm_weights": Tensor(np.concatenate([s["masked_lm_weights"] for s in data], axis=0), dtype=dtypes.float32, device="CPU"), + "next_sentence_labels": Tensor(np.concatenate([s["next_sentence_labels"] for s in data], axis=0), dtype=dtypes.int32, device="CPU"), } def load_file(file: str): @@ -223,14 +224,8 @@ def batch_load_train_bert(BS:int): assert cycle_length > 0, "cycle_length must be greater than 0" dataset = InterleavedDataset(train_files, cycle_length) - buffer = [dataset.get() for _ in range(1000)] while True: - batch = [] - for _ in range(BS): - index = random.randint(0, 999) - batch.append(buffer[index]) - buffer[index] = dataset.get() - yield process_batch_bert(batch) + yield process_batch_bert([dataset.get() for _ in range(BS)]) # Reference: https://github.com/mlcommons/training/blob/1c8a098ae3e70962a4f7422c0b0bd35ae639e357/language_model/tensorflow/bert/run_pretraining.py, Line 416 def batch_load_val_bert(BS:int): @@ -318,7 +313,7 @@ def batch_load_unet3d(preprocessed_dataset_dir:Path, batch_size:int=6, val:bool= proc = Process(target=load_unet3d_data, args=(preprocessed_dataset_dir, seed, queue_in, queue_out, X, Y)) proc.daemon = True proc.start() - + procs.append(proc) for bc in range(batch_count): @@ -354,6 +349,167 @@ def batch_load_unet3d(preprocessed_dataset_dir:Path, batch_size:int=6, val:bool= # happens with BENCHMARK set pass +### RetinaNet + +def load_retinanet_data(base_dir:Path, val:bool, queue_in:Queue, queue_out:Queue, + imgs:Tensor, boxes:Tensor, labels:Tensor, matches:Tensor|None=None, + anchors:Tensor|None=None, seed:int|None=None): + from extra.datasets.openimages import image_load, random_horizontal_flip, resize + from examples.mlperf.helpers import box_iou, find_matches, generate_anchors + import torch + + while (data:=queue_in.get()) is not None: + idx, img, tgt = data + img = image_load(base_dir, img["subset"], img["file_name"]) + + if val: + img = resize(img)[0] + else: + if seed is not None: + np.random.seed(seed) + random.seed(seed) + torch.manual_seed(seed) + + img, tgt = random_horizontal_flip(img, tgt) + img, tgt, _ = resize(img, tgt=tgt) + match_quality_matrix = box_iou(tgt["boxes"], (anchor := np.concatenate(generate_anchors((800, 800))))) + match_idxs = find_matches(match_quality_matrix, allow_low_quality_matches=True) + clipped_match_idxs = np.clip(match_idxs, 0, None) + clipped_boxes, clipped_labels = tgt["boxes"][clipped_match_idxs], tgt["labels"][clipped_match_idxs] + + boxes[idx].contiguous().realize().lazydata.base.realized.as_buffer(force_zero_copy=True)[:] = clipped_boxes.tobytes() + labels[idx].contiguous().realize().lazydata.base.realized.as_buffer(force_zero_copy=True)[:] = clipped_labels.tobytes() + matches[idx].contiguous().realize().lazydata.base.realized.as_buffer(force_zero_copy=True)[:] = match_idxs.tobytes() + anchors[idx].contiguous().realize().lazydata.base.realized.as_buffer(force_zero_copy=True)[:] = anchor.tobytes() + + imgs[idx].contiguous().realize().lazydata.base.realized.as_buffer(force_zero_copy=True)[:] = img.tobytes() + + queue_out.put(idx) + queue_out.put(None) + +def batch_load_retinanet(dataset, val:bool, base_dir:Path, batch_size:int=32, shuffle:bool=True, seed:int|None=None): + def _enqueue_batch(bc): + from extra.datasets.openimages import prepare_target + for idx in range(bc * batch_size, (bc+1) * batch_size): + img = dataset.loadImgs(next(dataset_iter))[0] + ann = dataset.loadAnns(dataset.getAnnIds(img_id:=img["id"])) + tgt = prepare_target(ann, img_id, (img["height"], img["width"])) + + if img_ids is not None: + img_ids[idx] = img_id + + if img_sizes is not None: + img_sizes[idx] = tgt["image_size"] + + queue_in.put((idx, img, tgt)) + + def _setup_shared_mem(shm_name:str, size:tuple[int, ...], dtype:dtypes) -> tuple[shared_memory.SharedMemory, Tensor]: + if os.path.exists(f"/dev/shm/{shm_name}"): os.unlink(f"/dev/shm/{shm_name}") + shm = shared_memory.SharedMemory(name=shm_name, create=True, size=prod(size)) + shm_tensor = Tensor.empty(*size, dtype=dtype, device=f"disk:/dev/shm/{shm_name}") + return shm, shm_tensor + + image_ids = sorted(dataset.imgs.keys()) + batch_count = min(32, len(image_ids) // batch_size) + + queue_in, queue_out = Queue(), Queue() + procs, data_out_count = [], [0] * batch_count + + shm_imgs, imgs = _setup_shared_mem("retinanet_imgs", (batch_size * batch_count, 800, 800, 3), dtypes.uint8) + + if val: + boxes, labels, matches, anchors = None, None, None, None + img_ids, img_sizes = [None] * (batch_size * batch_count), [None] * (batch_size * batch_count) + else: + img_ids, img_sizes = None, None + shm_boxes, boxes = _setup_shared_mem("retinanet_boxes", (batch_size * batch_count, 120087, 4), dtypes.float32) + shm_labels, labels = _setup_shared_mem("retinanet_labels", (batch_size * batch_count, 120087), dtypes.int64) + shm_matches, matches = _setup_shared_mem("retinanet_matches", (batch_size * batch_count, 120087), dtypes.int64) + shm_anchors, anchors = _setup_shared_mem("retinanet_anchors", (batch_size * batch_count, 120087, 4), dtypes.float64) + + shutdown = False + class Cookie: + def __init__(self, bc): + self.bc = bc + def __del__(self): + if not shutdown: + try: _enqueue_batch(self.bc) + except StopIteration: pass + + def shuffle_indices(indices, seed): + rng = random.Random(seed) + rng.shuffle(indices) + + if shuffle: shuffle_indices(image_ids, seed=seed) + dataset_iter = iter(image_ids) + + try: + for _ in range(cpu_count()): + proc = Process( + target=load_retinanet_data, + args=(base_dir, val, queue_in, queue_out, imgs, boxes, labels), + kwargs={"matches": matches, "anchors": anchors, "seed": seed} + ) + proc.daemon = True + proc.start() + procs.append(proc) + + for bc in range(batch_count): + _enqueue_batch(bc) + + for _ in range(len(image_ids) // batch_size): + while True: + bc = queue_out.get() // batch_size + data_out_count[bc] += 1 + if data_out_count[bc] == batch_size: break + + data_out_count[bc] = 0 + + if val: + yield (imgs[bc * batch_size:(bc + 1) * batch_size], + img_ids[bc * batch_size:(bc + 1) * batch_size], + img_sizes[bc * batch_size:(bc + 1) * batch_size], + Cookie(bc)) + else: + yield (imgs[bc * batch_size:(bc + 1) * batch_size], + boxes[bc * batch_size:(bc + 1) * batch_size], + labels[bc * batch_size:(bc + 1) * batch_size], + matches[bc * batch_size:(bc + 1) * batch_size], + anchors[bc * batch_size:(bc + 1) * batch_size], + Cookie(bc)) + finally: + shutdown = True + + for _ in procs: queue_in.put(None) + queue_in.close() + + for _ in procs: + while queue_out.get() is not None: pass + queue_out.close() + + # shutdown processes + for proc in procs: proc.join() + + shm_imgs.close() + + if not val: + shm_boxes.close() + shm_labels.close() + shm_matches.close() + shm_anchors.close() + + try: + shm_imgs.unlink() + + if not val: + shm_boxes.unlink() + shm_labels.unlink() + shm_matches.unlink() + shm_anchors.unlink() + except FileNotFoundError: + # happens with BENCHMARK set + pass + if __name__ == "__main__": def load_unet3d(val): assert not val, "validation set is not supported due to different sizes on inputs" @@ -374,6 +530,14 @@ if __name__ == "__main__": for x,y,c in batch_load_resnet(val=val): pbar.update(x.shape[0]) + def load_retinanet(val): + from extra.datasets.openimages import BASEDIR, download_dataset + from pycocotools.coco import COCO + dataset = COCO(download_dataset(base_dir:=getenv("BASEDIR", BASEDIR), "validation" if val else "train")) + with tqdm(total=len(dataset.imgs.keys())) as pbar: + for x in batch_load_retinanet(dataset, val, base_dir): + pbar.update(x[0].shape[0]) + load_fn_name = f"load_{getenv('MODEL', 'resnet')}" if load_fn_name in globals(): globals()[load_fn_name](getenv("VAL", 1)) diff --git a/tinygrad_repo/examples/mlperf/helpers.py b/tinygrad_repo/examples/mlperf/helpers.py index d232edfd86..f660f1481b 100644 --- a/tinygrad_repo/examples/mlperf/helpers.py +++ b/tinygrad_repo/examples/mlperf/helpers.py @@ -1,6 +1,7 @@ from collections import OrderedDict import unicodedata from typing import Optional +import math import numpy as np from tinygrad.nn import state from tinygrad.tensor import Tensor, dtypes @@ -195,20 +196,18 @@ def get_bert_qa_prediction(features, example, start_end_logits): return "empty" def get_mlperf_bert_config(): - """Config is BERT-large""" - return { - "attention_probs_dropout_prob": 0.1, - "hidden_dropout_prob": 0.1, - "hidden_size": 1024, - "intermediate_size": 4096, - "max_position_embeddings": 512, - "num_attention_heads": 16, - "num_hidden_layers": 24, - "type_vocab_size": 2, - "vocab_size": 30522 - } + """benchmark is BERT-large""" + ret = {"attention_probs_dropout_prob": 0.1, "hidden_dropout_prob": 0.1, "vocab_size": 30522, "type_vocab_size": 2, "max_position_embeddings": 512} + + match (bert_size:=getenv("BERT_SIZE", "large")): + case "large": ret.update({"hidden_size": 1024, "intermediate_size": 4096, "num_attention_heads": 16, "num_hidden_layers": 24}) + case "tiny": ret.update({"hidden_size": 128, "intermediate_size": 512, "num_attention_heads": 2, "num_hidden_layers": 2}) + case _: raise RuntimeError(f"unhandled {bert_size=}") + + if (bert_layers:=getenv("BERT_LAYERS")): ret["num_hidden_layers"] = bert_layers + return ret -def get_mlperf_bert_model(checkpoint_path:Optional[str]=None): +def get_mlperf_bert_model(): from extra.models import bert from examples.mlperf.initializers import LinearBert, EmbeddingBert, LayerNormBert @@ -220,21 +219,138 @@ def get_mlperf_bert_model(checkpoint_path:Optional[str]=None): config = get_mlperf_bert_config() if getenv("DISABLE_DROPOUT", 0): config["hidden_dropout_prob"] = config["attention_probs_dropout_prob"] = 0.0 - model = BertForPretraining(**config) - return model.load_from_pretrained(checkpoint_path) if checkpoint_path else model + return BertForPretraining(**config) -def get_data_bert(GPUS:list[str], it): - data: dict[str, Tensor] = next(it) - for key in data.keys(): data[key].shard_(GPUS, axis=0) - return data - -def get_fake_data_bert(GPUS:list[str], BS:int): +def get_fake_data_bert(BS:int): return { - "input_ids": Tensor.empty((BS, 512), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), - "input_mask": Tensor.empty((BS, 512), dtype=dtypes.default_float).contiguous().shard_(GPUS, axis=0), - "segment_ids": Tensor.empty((BS, 512), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), - "masked_lm_positions": Tensor.empty((BS, 76), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), - "masked_lm_ids": Tensor.empty((BS, 76), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), - "masked_lm_weights": Tensor.empty((BS, 76), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), - "next_sentence_labels": Tensor.empty((BS, 1), dtype=dtypes.float32).contiguous().shard_(GPUS, axis=0), + "input_ids": Tensor.empty((BS, 512), dtype=dtypes.int32, device="CPU"), + "input_mask": Tensor.empty((BS, 512), dtype=dtypes.int32, device="CPU"), + "segment_ids": Tensor.empty((BS, 512), dtype=dtypes.int32, device="CPU"), + "masked_lm_positions": Tensor.empty((BS, 76), dtype=dtypes.int32, device="CPU"), + "masked_lm_ids": Tensor.empty((BS, 76), dtype=dtypes.int32, device="CPU"), + "masked_lm_weights": Tensor.empty((BS, 76), dtype=dtypes.float32, device="CPU"), + "next_sentence_labels": Tensor.empty((BS, 1), dtype=dtypes.int32, device="CPU"), } + +def find_matches(match_quality_matrix:np.ndarray, high_threshold:float=0.5, low_threshold:float=0.4, allow_low_quality_matches:bool=False) -> np.ndarray: + BELOW_LOW_THRESHOLD, BETWEEN_THRESHOLDS = -1, -2 + + def _set_low_quality_matches_(matches:np.ndarray, all_matches:np.ndarray, match_quality_matrix:np.ndarray): + highest_quality_foreach_gt = np.max(match_quality_matrix, axis=1) + pred_inds_to_update = np.nonzero(match_quality_matrix == highest_quality_foreach_gt[:, None])[1] + matches[pred_inds_to_update] = all_matches[pred_inds_to_update] + + assert low_threshold <= high_threshold + + matched_vals, matches = match_quality_matrix.max(axis=0), match_quality_matrix.argmax(axis=0) + all_matches = np.copy(matches) if allow_low_quality_matches else None + below_low_threshold = matched_vals < low_threshold + between_thresholds = (matched_vals >= low_threshold) & (matched_vals < high_threshold) + matches[below_low_threshold] = BELOW_LOW_THRESHOLD + matches[between_thresholds] = BETWEEN_THRESHOLDS + + if allow_low_quality_matches: + assert all_matches is not None + _set_low_quality_matches_(matches, all_matches, match_quality_matrix) + + return matches + +def box_iou(boxes1:np.ndarray, boxes2:np.ndarray) -> np.ndarray: + def _box_area(boxes:np.ndarray) -> np.ndarray: return (boxes[:, 2] - boxes[:, 0]) * (boxes[:, 3] - boxes[:, 1]) + + def _box_inter_union(boxes1:np.ndarray, boxes2:np.ndarray) -> tuple[np.ndarray, np.ndarray]: + area1, area2 = _box_area(boxes1), _box_area(boxes2) + lt, rb = np.maximum(boxes1[:, None, :2], boxes2[:, :2]), np.minimum(boxes1[:, None, 2:], boxes2[:, 2:]) + wh = np.clip(rb - lt, a_min=0, a_max=None) + inter = wh[:, :, 0] * wh[:, :, 1] + union = area1[:, None] + area2 - inter + return inter, union + + inter, union = _box_inter_union(boxes1, boxes2) + return inter / union + +def generate_anchors(input_size:tuple[int, int], scales:Optional[tuple[Tensor, ...]]=None, aspect_ratios:Optional[tuple[Tensor, ...]]=None) -> list[np.ndarray]: + def _compute_grid_sizes(input_size:tuple[int, int]) -> np.ndarray: + return np.ceil(np.array(input_size)[None, :] / 2 ** np.arange(3, 8)[:, None]) + + scales = tuple((i, int(i * 2 ** (1/3)), int(i * 2 ** (2/3))) for i in 2 ** np.arange(5, 10)) if scales is None else scales + aspect_ratios = ((0.5, 1.0, 2.0),) * len(scales) if aspect_ratios is None else aspect_ratios + aspect_ratios = tuple(ar for ar in aspect_ratios) + grid_sizes = _compute_grid_sizes(input_size) + + assert len(scales) == len(aspect_ratios) == len(grid_sizes), "scales, aspect_ratios, and grid_sizes must have the same length" + + anchors = [] + for s, ar, gs in zip(scales, aspect_ratios, grid_sizes): + s, ar = np.array(s), np.array(ar) + h_ratios = np.sqrt(ar) + w_ratios = 1 / h_ratios + ws = (w_ratios[:, None] * s[None, :]).reshape(-1) + hs = (h_ratios[:, None] * s[None, :]).reshape(-1) + base_anchors = (np.stack([-ws, -hs, ws, hs], axis=1) / 2).round() + stride_h, stride_w = input_size[0] // gs[0], input_size[1] // gs[1] + shifts_x, shifts_y = np.meshgrid(np.arange(gs[1]) * stride_w, np.arange(gs[0]) * stride_h) + shifts_x, shifts_y = shifts_x.reshape(-1), shifts_y.reshape(-1) + shifts = np.stack([shifts_x, shifts_y, shifts_x, shifts_y], axis=1, dtype=np.float32) + anchors.append((shifts[:, None] + base_anchors[None, :]).reshape(-1, 4)) + + return anchors + + +class BoxCoder(object): + def __init__(self, weights, bbox_xform_clip=math.log(1000. / 16), apply_to_remove=True): + self.weights = weights + self.bbox_xform_clip = bbox_xform_clip + self.apply_to_remove = apply_to_remove + + def encode(self, reference_boxes, proposals): + TO_REMOVE = self.apply_to_remove # TODO remove + ex_widths = proposals[..., 2] - proposals[..., 0] + TO_REMOVE + ex_heights = proposals[..., 3] - proposals[..., 1] + TO_REMOVE + ex_ctr_x = proposals[..., 0] + 0.5 * ex_widths + ex_ctr_y = proposals[..., 1] + 0.5 * ex_heights + + gt_widths = reference_boxes[..., 2] - reference_boxes[..., 0] + TO_REMOVE + gt_heights = reference_boxes[..., 3] - reference_boxes[..., 1] + TO_REMOVE + gt_ctr_x = reference_boxes[..., 0] + 0.5 * gt_widths + gt_ctr_y = reference_boxes[..., 1] + 0.5 * gt_heights + + wx, wy, ww, wh = self.weights + targets_dx = wx * (gt_ctr_x - ex_ctr_x) / ex_widths + targets_dy = wy * (gt_ctr_y - ex_ctr_y) / ex_heights + targets_dw = ww * Tensor.log(gt_widths / ex_widths) + targets_dh = wh * Tensor.log(gt_heights / ex_heights) + + targets = Tensor.stack(targets_dx, targets_dy, targets_dw, targets_dh, dim=-1) + return targets + + def decode(self, rel_codes, boxes): + boxes = boxes.cast(rel_codes.dtype) + rel_codes = rel_codes + + TO_REMOVE = self.apply_to_remove # TODO remove + widths = boxes[:, 2] - boxes[:, 0] + TO_REMOVE + heights = boxes[:, 3] - boxes[:, 1] + TO_REMOVE + ctr_x = boxes[:, 0] + 0.5 * widths + ctr_y = boxes[:, 1] + 0.5 * heights + + wx, wy, ww, wh = self.weights + dx = rel_codes[:, 0::4] / wx + dy = rel_codes[:, 1::4] / wy + dw = rel_codes[:, 2::4] / ww + dh = rel_codes[:, 3::4] / wh + + # Prevent sending too large values into Tensor.exp() + dw = dw.clip(min_=dw.min(), max_=self.bbox_xform_clip) + dh = dh.clip(min_=dh.min(), max_=self.bbox_xform_clip) + + pred_ctr_x = dx * widths[:, None] + ctr_x[:, None] + pred_ctr_y = dy * heights[:, None] + ctr_y[:, None] + pred_w = dw.exp() * widths[:, None] + pred_h = dh.exp() * heights[:, None] + x = pred_ctr_x - 0.5 * pred_w + y = pred_ctr_y - 0.5 * pred_h + w = pred_ctr_x + 0.5 * pred_w - 1 + h = pred_ctr_y + 0.5 * pred_h - 1 + pred_boxes = Tensor.stack(x, y, w, h).permute(1,2,0).reshape(rel_codes.shape[0], rel_codes.shape[1]) + return pred_boxes diff --git a/tinygrad_repo/examples/mlperf/initializers.py b/tinygrad_repo/examples/mlperf/initializers.py index 994ec0f77b..41554cba46 100644 --- a/tinygrad_repo/examples/mlperf/initializers.py +++ b/tinygrad_repo/examples/mlperf/initializers.py @@ -1,5 +1,5 @@ import math -from typing import Union, Tuple +from typing import Union from tinygrad import Tensor, nn, dtypes from tinygrad.helpers import prod, argfix @@ -53,10 +53,12 @@ class EmbeddingBert(nn.Embedding): arange_shp, weight_shp, big_shp = (1, 1, self.vocab_sz, 1), (1, 1, self.vocab_sz, self.embed_sz), idx.shape+(self.vocab_sz, self.embed_sz,) if not hasattr(self, 'arange'): self.arange = Tensor.arange(self.vocab_sz, requires_grad=False, device=self.weight.device).reshape(arange_shp) arange, idx, vals = self.arange.expand(big_shp), idx.reshape(idx.shape+(1, 1,)).expand(big_shp), self.weight.cast(dtypes.default_float).reshape(weight_shp).expand(big_shp) - return (arange == idx).mul(vals).sum(2, acc_dtype=vals.dtype) + # TODO: contiguous() here because the embedding dropout creates different asts on each device, and search becomes very slow. + # Should fix with fixing random ast on multi device, and fuse arange to make embedding fast. + return (arange == idx).mul(vals).sum(2, dtype=vals.dtype).contiguous() class LayerNormBert: - def __init__(self, normalized_shape:Union[int, Tuple[int, ...]], eps:float=1e-12, elementwise_affine:bool=True): + def __init__(self, normalized_shape:Union[int, tuple[int, ...]], eps:float=1e-12, elementwise_affine:bool=True): self.normalized_shape = (normalized_shape,) if isinstance(normalized_shape, int) else tuple(normalized_shape) self.axis, self.eps, self.elementwise_affine = tuple(-1-i for i in range(len(self.normalized_shape))), eps, elementwise_affine self.weight, self.bias = (Tensor.ones(*self.normalized_shape, dtype=dtypes.float32), Tensor.zeros(*self.normalized_shape, dtype=dtypes.float32)) if elementwise_affine else (None, None) @@ -66,3 +68,62 @@ class LayerNormBert: xn = x.cast(dtypes.float32).layernorm(eps=self.eps, axis=self.axis).cast(x.dtype) if not self.elementwise_affine: return xn return (xn * self.weight.cast(dtypes.default_float) + self.bias.cast(dtypes.default_float)) + +class FrozenBatchNorm2dRetinaNet(nn.BatchNorm2d): + def __init__(self, sz:int, eps=1e-5, affine=True, track_running_stats=True, momentum=0.1): + self.eps, self.track_running_stats, self.momentum = eps, track_running_stats, momentum + + self.weight = Tensor.ones(sz, dtype=dtypes.float32, requires_grad=False) if affine else None + self.bias = Tensor.zeros(sz, dtype=dtypes.float32, requires_grad=False) if affine else None + + if track_running_stats: self.running_mean, self.running_var = Tensor.zeros(sz, dtype=dtypes.float32, requires_grad=False), Tensor.ones(sz, dtype=dtypes.float32, requires_grad=False) + self.num_batches_tracked = Tensor.zeros(1, dtype=dtypes.long, requires_grad=False) + + def __call__(self, x:Tensor) -> Tensor: + batch_mean, batch_var = super().calc_stats(x.cast(dtypes.float32)) + if self.track_running_stats and Tensor.training: + self.running_mean.assign((1-self.momentum) * self.running_mean + self.momentum * batch_mean.detach().cast(self.running_mean.dtype)) + self.running_var.assign((1-self.momentum) * self.running_var + self.momentum * x.numel()/(x.numel()-x.shape[1]) * batch_var.detach().cast(self.running_var.dtype)) + self.num_batches_tracked += 1 + return x.cast(dtypes.float32).batchnorm(self.weight, self.bias, batch_mean, batch_var.add(self.eps).rsqrt()).cast(x.dtype) + +class Conv2dNormalRetinaNet(nn.Conv2d): + def __init__(self, in_channels:int, out_channels:int, kernel_size:int|tuple[int, ...], + stride:int=1, padding:int|tuple[int, ...]|str=0, dilation:int=1, groups:int=1, + bias:bool=True, prior_prob:float|None=None): + super().__init__(in_channels, out_channels, kernel_size, stride=stride, padding=padding, dilation=dilation, groups=groups, bias=bias) + self.weight = Tensor.normal(*self.weight.shape, std=0.01, dtype=dtypes.float32) + if bias: + if prior_prob: + prior_prob = Tensor(prior_prob, device=self.bias.device, dtype=dtypes.float32).expand(*self.bias.shape) + self.bias = -(((1 - prior_prob) / prior_prob).log()) + else: self.bias = Tensor.zeros_like(self.bias, dtype=dtypes.float32) + + def __call__(self, x:Tensor) -> Tensor: + return x.conv2d(self.weight.cast(dtypes.default_float), self.bias.cast(dtypes.default_float) if self.bias is not None else None, + groups=self.groups, stride=self.stride, padding=self.padding) + +class Conv2dKaimingUniformRetinaNet(nn.Conv2d): + def __init__(self, in_channels:int, out_channels:int, kernel_size:int|tuple[int, ...], + stride:int=1, padding:int|tuple[int, ...]|str=0, dilation:int=1, groups:int=1, + bias:bool=True): + super().__init__(in_channels, out_channels, kernel_size, stride=stride, padding=padding, dilation=dilation, groups=groups, bias=bias) + self.weight = Tensor.kaiming_uniform(*self.weight.shape, a=1, dtype=dtypes.float32) + if bias: self.bias = Tensor.zeros_like(self.bias, dtype=dtypes.float32) + + def __call__(self, x:Tensor) -> Tensor: + return x.conv2d(self.weight.cast(dtypes.default_float), self.bias.cast(dtypes.default_float) if self.bias is not None else None, + groups=self.groups, stride=self.stride, padding=self.padding) + +class Conv2dRetinaNet(nn.Conv2d): + def __init__(self, in_channels:int, out_channels:int, kernel_size:int|tuple[int, ...], + stride:int=1, padding:int|tuple[int, ...]|str=0, dilation:int=1, groups:int=1, + bias:bool=True): + super().__init__(in_channels, out_channels, kernel_size, stride=stride, padding=padding, dilation=dilation, groups=groups, bias=bias) + scale = 1 / math.sqrt(in_channels * prod(self.kernel_size)) + self.weight = Tensor.uniform(out_channels, in_channels//groups, *self.kernel_size, low=-scale, high=scale, dtype=dtypes.float32) + self.bias: Tensor|None = Tensor.uniform(out_channels, low=-scale, high=scale, dtype=dtypes.float32) if bias else None + + def __call__(self, x:Tensor) -> Tensor: + return x.conv2d(self.weight.cast(dtypes.default_float), self.bias.cast(dtypes.default_float) if self.bias is not None else None, + groups=self.groups, stride=self.stride, dilation=self.dilation, padding=self.padding) diff --git a/tinygrad_repo/examples/mlperf/losses.py b/tinygrad_repo/examples/mlperf/losses.py index a7025a0eb5..7ce047bc70 100644 --- a/tinygrad_repo/examples/mlperf/losses.py +++ b/tinygrad_repo/examples/mlperf/losses.py @@ -1,6 +1,29 @@ from examples.mlperf.metrics import dice_score +from tinygrad import Tensor def dice_ce_loss(pred, tgt): ce = pred.permute(0, 2, 3, 4, 1).sparse_categorical_crossentropy(tgt.squeeze(1)) dice = (1.0 - dice_score(pred, tgt, argmax=False, to_one_hot_x=False)).mean() return (dice + ce) / 2 + +def sigmoid_focal_loss(pred:Tensor, tgt:Tensor, alpha:float=0.25, gamma:float=2.0, reduction:str="none") -> Tensor: + assert reduction in ["mean", "sum", "none"], f"unsupported reduction {reduction}" + p, ce_loss = pred.sigmoid(), pred.binary_crossentropy_logits(tgt, reduction="none") + p_t = p * tgt + (1 - p) * (1 - tgt) + loss = ce_loss * ((1 - p_t) ** gamma) + + if alpha >= 0: + alpha_t = alpha * tgt + (1 - alpha) * (1 - tgt) + loss = loss * alpha_t + + if reduction == "mean": loss = loss.mean() + elif reduction == "sum": loss = loss.sum() + return loss + +def l1_loss(pred:Tensor, tgt:Tensor, reduction:str="none") -> Tensor: + assert reduction in ["mean", "sum", "none"], f"unsupported reduction {reduction}" + loss = (pred - tgt).abs() + + if reduction == "mean": loss = loss.mean() + elif reduction == "sum": loss = loss.sum() + return loss \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/model_eval.py b/tinygrad_repo/examples/mlperf/model_eval.py index 899484b4c5..35ad33eabb 100644 --- a/tinygrad_repo/examples/mlperf/model_eval.py +++ b/tinygrad_repo/examples/mlperf/model_eval.py @@ -5,61 +5,63 @@ import numpy as np from tinygrad import Tensor, Device, dtypes, GlobalCounters, TinyJit from tinygrad.nn.state import get_parameters, load_state_dict, safe_load from tinygrad.helpers import getenv +from extra.bench_log import BenchEvent, WallTimeEvent def tlog(x): print(f"{x:25s} @ {time.perf_counter()-start:5.2f}s") def eval_resnet(): Tensor.no_grad = True - # Resnet50-v1.5 - from extra.models.resnet import ResNet50 - tlog("imports") - GPUS = [f'{Device.DEFAULT}:{i}' for i in range(getenv("GPUS", 6))] - for x in GPUS: Device[x] - tlog("got devices") # NOTE: this is faster with rocm-smi running - - class ResnetRunner: - def __init__(self, device=None): - self.mdl = ResNet50() - for x in get_parameters(self.mdl) if device else []: x.to_(device) - if (fn:=getenv("RESNET_MODEL", "")): load_state_dict(self.mdl, safe_load(fn)) - else: self.mdl.load_from_pretrained() - self.input_mean = Tensor([0.485, 0.456, 0.406], device=device).reshape(1, -1, 1, 1) - self.input_std = Tensor([0.229, 0.224, 0.225], device=device).reshape(1, -1, 1, 1) - def __call__(self, x:Tensor) -> Tensor: - x = x.permute([0,3,1,2]).cast(dtypes.float32) / 255.0 - x -= self.input_mean - x /= self.input_std - return self.mdl(x).log_softmax().argmax(axis=1).realize() - - mdl = TinyJit(ResnetRunner(GPUS)) - tlog("loaded models") - - # evaluation on the mlperf classes of the validation set from imagenet - from examples.mlperf.dataloader import batch_load_resnet - iterator = batch_load_resnet(getenv("BS", 128*6), val=getenv("VAL", 1), shuffle=False, pad_first_batch=True) - def data_get(): - x,y,cookie = next(iterator) - return x.shard(GPUS, axis=0).realize(), y, cookie - n,d = 0,0 - proc = data_get() - tlog("loaded initial data") - st = time.perf_counter() - while proc is not None: - GlobalCounters.reset() - proc = (mdl(proc[0]), proc[1], proc[2]) # this frees the images - run = time.perf_counter() - # load the next data here - try: next_proc = data_get() - except StopIteration: next_proc = None - nd = time.perf_counter() - y = np.array(proc[1]) - proc = (proc[0].numpy() == y) & (y != -1) # this realizes the models and frees the cookies - n += proc.sum() - d += (y != -1).sum() - et = time.perf_counter() - tlog(f"****** {n:5d}/{d:5d} {n*100.0/d:.2f}% -- {(run-st)*1000:7.2f} ms to enqueue, {(et-run)*1000:7.2f} ms to realize ({(nd-run)*1000:7.2f} ms fetching). {(len(proc))/(et-st):8.2f} examples/sec. {GlobalCounters.global_ops*1e-12/(et-st):5.2f} TFLOPS") - st = et - proc, next_proc = next_proc, None - tlog("done") + with WallTimeEvent(BenchEvent.FULL): + # Resnet50-v1.5 + from extra.models.resnet import ResNet50 + tlog("imports") + GPUS = [f'{Device.DEFAULT}:{i}' for i in range(getenv("GPUS", 6))] + for x in GPUS: Device[x] + tlog("got devices") # NOTE: this is faster with rocm-smi running + + class ResnetRunner: + def __init__(self, device=None): + self.mdl = ResNet50() + for x in get_parameters(self.mdl) if device else []: x.to_(device) + if (fn:=getenv("RESNET_MODEL", "")): load_state_dict(self.mdl, safe_load(fn)) + else: self.mdl.load_from_pretrained() + self.input_mean = Tensor([0.485, 0.456, 0.406], device=device).reshape(1, -1, 1, 1) + self.input_std = Tensor([0.229, 0.224, 0.225], device=device).reshape(1, -1, 1, 1) + def __call__(self, x:Tensor) -> Tensor: + x = x.permute([0,3,1,2]).cast(dtypes.float32) / 255.0 + x -= self.input_mean + x /= self.input_std + return self.mdl(x).log_softmax().argmax(axis=1).realize() + + mdl = TinyJit(ResnetRunner(GPUS)) + tlog("loaded models") + + # evaluation on the mlperf classes of the validation set from imagenet + from examples.mlperf.dataloader import batch_load_resnet + iterator = batch_load_resnet(getenv("BS", 128*6), val=getenv("VAL", 1), shuffle=False, pad_first_batch=True) + def data_get(): + x,y,cookie = next(iterator) + return x.shard(GPUS, axis=0).realize(), y, cookie + n,d = 0,0 + proc = data_get() + tlog("loaded initial data") + st = time.perf_counter() + while proc is not None: + GlobalCounters.reset() + proc = (mdl(proc[0]), proc[1], proc[2]) # this frees the images + run = time.perf_counter() + # load the next data here + try: next_proc = data_get() + except StopIteration: next_proc = None + nd = time.perf_counter() + y = np.array(proc[1]) + proc = (proc[0].numpy() == y) & (y != -1) # this realizes the models and frees the cookies + n += proc.sum() + d += (y != -1).sum() + et = time.perf_counter() + tlog(f"****** {n:5d}/{d:5d} {n*100.0/d:.2f}% -- {(run-st)*1000:7.2f} ms to enqueue, {(et-run)*1000:7.2f} ms to realize ({(nd-run)*1000:7.2f} ms fetching). {(len(proc))/(et-st):8.2f} examples/sec. {GlobalCounters.global_ops*1e-12/(et-st):5.2f} TFLOPS") + st = et + proc, next_proc = next_proc, None + tlog("done") def eval_unet3d(): # UNet3D @@ -81,47 +83,43 @@ def eval_unet3d(): def eval_retinanet(): # RetinaNet with ResNeXt50_32X4D + from examples.mlperf.dataloader import batch_load_retinanet + from extra.datasets.openimages import normalize, download_dataset, BASEDIR from extra.models.resnet import ResNeXt50_32X4D from extra.models.retinanet import RetinaNet - mdl = RetinaNet(ResNeXt50_32X4D()) - mdl.load_from_pretrained() - - input_mean = Tensor([0.485, 0.456, 0.406]).reshape(1, -1, 1, 1) - input_std = Tensor([0.229, 0.224, 0.225]).reshape(1, -1, 1, 1) - def input_fixup(x): - x = x.permute([0,3,1,2]) / 255.0 - x -= input_mean - x /= input_std - return x - - from extra.datasets.openimages import download_dataset, iterate, BASEDIR from pycocotools.coco import COCO from pycocotools.cocoeval import COCOeval from contextlib import redirect_stdout - coco = COCO(download_dataset(base_dir:=getenv("BASE_DIR", BASEDIR), 'validation')) + tlog("imports") + + mdl = RetinaNet(ResNeXt50_32X4D()) + mdl.load_from_pretrained() + tlog("loaded models") + + coco = COCO(download_dataset(base_dir:=getenv("BASEDIR", BASEDIR), 'validation')) coco_eval = COCOeval(coco, iouType="bbox") coco_evalimgs, evaluated_imgs, ncats, narea = [], [], len(coco_eval.params.catIds), len(coco_eval.params.areaRng) + tlog("loaded dataset") - from tinygrad.engine.jit import TinyJit - mdlrun = TinyJit(lambda x: mdl(input_fixup(x)).realize()) - - n, bs = 0, 8 + iterator = batch_load_retinanet(coco, True, Path(base_dir), getenv("BS", 8), shuffle=False) + def data_get(): + x, img_ids, img_sizes, cookie = next(iterator) + return x.to(Device.DEFAULT).realize(), img_ids, img_sizes, cookie + n = 0 + proc = data_get() + tlog("loaded initial data") st = time.perf_counter() - for x, targets in iterate(coco, base_dir, bs): - dat = Tensor(x.astype(np.float32)) - mt = time.perf_counter() - if dat.shape[0] == bs: - outs = mdlrun(dat).numpy() - else: - mdlrun._jit_cache = [] - outs = mdl(input_fixup(dat)).numpy() - et = time.perf_counter() - predictions = mdl.postprocess_detections(outs, input_size=dat.shape[1:3], orig_image_sizes=[t["image_size"] for t in targets]) - ext = time.perf_counter() - n += len(targets) - print(f"[{n}/{len(coco.imgs)}] == {(mt-st)*1000:.2f} ms loading data, {(et-mt)*1000:.2f} ms to run model, {(ext-et)*1000:.2f} ms for postprocessing") - img_ids = [t["image_id"] for t in targets] - coco_results = [{"image_id": targets[i]["image_id"], "category_id": label, "bbox": box.tolist(), "score": score} + while proc is not None: + GlobalCounters.reset() + proc = (mdl(normalize(proc[0])), proc[1], proc[2], proc[3]) + run = time.perf_counter() + # load the next data here + try: next_proc = data_get() + except StopIteration: next_proc = None + nd = time.perf_counter() + predictions, img_ids = mdl.postprocess_detections(proc[0].numpy(), orig_image_sizes=proc[2]), proc[1] + pd = time.perf_counter() + coco_results = [{"image_id": img_ids[i], "category_id": label, "bbox": box.tolist(), "score": score} for i, prediction in enumerate(predictions) for box, score, label in zip(*prediction.values())] with redirect_stdout(None): coco_eval.cocoDt = coco.loadRes(coco_results) @@ -129,13 +127,18 @@ def eval_retinanet(): coco_eval.evaluate() evaluated_imgs.extend(img_ids) coco_evalimgs.append(np.array(coco_eval.evalImgs).reshape(ncats, narea, len(img_ids))) - st = time.perf_counter() + n += len(proc[0]) + et = time.perf_counter() + tlog(f"****** {(run-st)*1000:7.2f} ms to enqueue, {(et-run)*1000:7.2f} ms to realize ({(nd-run)*1000:7.2f} ms fetching, {(pd-run)*1000:4.2f} ms postprocess_detections). {(len(proc))/(et-st):8.2f} examples/sec. {GlobalCounters.global_ops*1e-12/(et-st):5.2f} TFLOPS") + st = et + proc, next_proc = next_proc, None coco_eval.params.imgIds = evaluated_imgs coco_eval._paramsEval.imgIds = evaluated_imgs coco_eval.evalImgs = list(np.concatenate(coco_evalimgs, -1).flatten()) coco_eval.accumulate() coco_eval.summarize() + tlog("done") def eval_rnnt(): # RNN-T diff --git a/tinygrad_repo/examples/mlperf/model_train.py b/tinygrad_repo/examples/mlperf/model_train.py index 19fa1a8e07..9d149a0135 100644 --- a/tinygrad_repo/examples/mlperf/model_train.py +++ b/tinygrad_repo/examples/mlperf/model_train.py @@ -1,14 +1,15 @@ -import os, time, math, functools +import os, time, math, functools, random from pathlib import Path import multiprocessing from tinygrad import Device, GlobalCounters, Tensor, TinyJit, dtypes -from tinygrad.helpers import getenv, BEAM, WINO, round_up, diskcache_clear, FUSE_CONV_BW +from tinygrad.helpers import getenv, BEAM, WINO, round_up, diskcache_clear, FUSE_CONV_BW, Profiling from tinygrad.nn.state import get_parameters, get_state_dict, safe_load, safe_save -from tinygrad.nn.optim import LAMB, LARS, SGD, OptimizerGroup +from tinygrad.nn.optim import LAMB, LARS, SGD, OptimizerGroup, Adam from extra.lr_scheduler import LRSchedulerGroup from examples.mlperf.helpers import get_training_state, load_training_state +from extra.bench_log import BenchEvent, WallTimeEvent # TODO: fix benchmark logging and use tinygrad tqdm from tqdm import tqdm @@ -79,7 +80,7 @@ def train_resnet(): lr_warmup_epochs = config["lr_warmup_epochs"] = getenv("WARMUP_EPOCHS", 2) decay = config["decay"] = getenv("DECAY", 2e-4) - loss_scaler = config["LOSS_SCALER"] = getenv("LOSS_SCALER", 128.0 if dtypes.default_float == dtypes.float16 else 1.0) + loss_scaler = config["LOSS_SCALER"] = getenv("LOSS_SCALER", 256.0 if dtypes.default_float == dtypes.float16 else 1.0) target, achieved = getenv("TARGET", 0.759), False eval_start_epoch = getenv("EVAL_START_EPOCH", 0) @@ -205,24 +206,25 @@ def train_resnet(): st = time.perf_counter() while proc is not None: GlobalCounters.reset() - (loss, top_1), y, proc = train_step(proc[0], proc[1]), proc[2], proc[3] + with WallTimeEvent(BenchEvent.STEP): + (loss, top_1), y, proc = train_step(proc[0], proc[1]), proc[2], proc[3] - pt = time.perf_counter() + pt = time.perf_counter() - if len(prev_cookies) == getenv("STORE_COOKIES", 1): prev_cookies = [] # free previous cookies after gpu work has been enqueued - try: - if INITMLPERF: - next_proc = fake_data_get(BS) - else: - next_proc = data_get(it) - except StopIteration: - next_proc = None + if len(prev_cookies) == getenv("STORE_COOKIES", 1): prev_cookies = [] # free previous cookies after gpu work has been enqueued + try: + if INITMLPERF: + next_proc = fake_data_get(BS) + else: + next_proc = data_get(it) + except StopIteration: + next_proc = None - dt = time.perf_counter() + dt = time.perf_counter() - device_str = loss.device if isinstance(loss.device, str) else f"{loss.device[0]} * {len(loss.device)}" - loss, top_1 = loss.numpy().item(), top_1.numpy().item() - top_1_acc = top_1 / sum(yi != -1 for yi in y) + device_str = loss.device if isinstance(loss.device, str) else f"{loss.device[0]} * {len(loss.device)}" + loss, top_1 = loss.numpy().item(), top_1.numpy().item() + top_1_acc = top_1 / sum(yi != -1 for yi in y) cl = time.perf_counter() if BENCHMARK: @@ -273,7 +275,7 @@ def train_resnet(): else: it = iter(tqdm(batch_load_resnet(batch_size=EVAL_BS, val=True, shuffle=False, pad_first_batch=True), total=steps_in_val_epoch)) i, proc = 0, data_get(it) - + prev_cookies = [] while proc is not None: GlobalCounters.reset() @@ -343,8 +345,349 @@ def train_resnet(): safe_save(get_training_state(model, optimizer_group, scheduler_group), fn) def train_retinanet(): - # TODO: Retinanet - pass + from contextlib import redirect_stdout + from examples.mlperf.dataloader import batch_load_retinanet + from examples.mlperf.initializers import FrozenBatchNorm2dRetinaNet, Conv2dNormalRetinaNet, Conv2dKaimingUniformRetinaNet, Linear, Conv2dRetinaNet + from extra.datasets.openimages import MLPERF_CLASSES, BASEDIR, download_dataset, normalize, get_dataset_count + from extra.models import resnet, retinanet + from pycocotools.coco import COCO + from pycocotools.cocoeval import COCOeval + from tinygrad.helpers import colored + from typing import Iterator + + import numpy as np + + config, target_metric = {}, 0.34 + + config["SEED"] = SEED = getenv("SEED", random.SystemRandom().randint(0, 2**32 - 1)) + Tensor.manual_seed(SEED) + + NUM_CLASSES = len(MLPERF_CLASSES) + BASEDIR = getenv("BASEDIR", BASEDIR) + BENCHMARK = getenv("BENCHMARK") + INITMLPERF = getenv("INITMLPERF") + RUNMLPERF = getenv("RUNMLPERF") + + if INITMLPERF: + diskcache_clear() + + if getenv("LOGMLPERF"): + from mlperf_logging import mllog + import mlperf_logging.mllog.constants as mllog_constants + + mllog.config(filename=f"result_retinanet_{SEED}.log") + mllog.config(root_dir=Path(__file__).parents[3].as_posix()) + MLLOGGER = mllog.get_mllogger() + MLLOGGER.logger.propagate = False + + if INITMLPERF: + assert BENCHMARK, "BENCHMARK must be set for INITMLPERF" + MLLOGGER.event(key=mllog_constants.SUBMISSION_ORG, value="tinycorp") + MLLOGGER.event(key=mllog_constants.SUBMISSION_PLATFORM, value=getenv("SUBMISSION_PLATFORM", "tinybox")) + MLLOGGER.event(key=mllog_constants.SUBMISSION_DIVISION, value=mllog_constants.CLOSED) + MLLOGGER.event(key=mllog_constants.SUBMISSION_STATUS, value=mllog_constants.ONPREM) + + MLLOGGER.event(key=mllog_constants.SUBMISSION_BENCHMARK, value=mllog_constants.RETINANET) + + MLLOGGER.event(key=mllog_constants.CACHE_CLEAR, value=True) + MLLOGGER.start(key=mllog_constants.INIT_START) + + if RUNMLPERF: + MLLOGGER.start(key=mllog_constants.RUN_START) + MLLOGGER.event(key=mllog_constants.SEED, value=SEED) + else: + MLLOGGER = None + + config["gpus"] = GPUS = [f"{Device.DEFAULT}:{i}" for i in range(getenv("GPUS", 6))] + + for x in GPUS: Device[x] + print(f"training on {GPUS}") + + def _freeze_backbone_layers(backbone:resnet.ResNet, trainable_layers:int): + layers_to_train = ["layer4", "layer3", "layer2", "layer1", "conv1"][:trainable_layers] + for k, v in get_state_dict(backbone).items(): + if all([not k.startswith(layer) for layer in layers_to_train]): + v.requires_grad = False + + def _data_get(it:Iterator[tuple[Tensor, ...]], val:bool=False): + if val: + x, img_ids, img_sizes, cookie = next(it) + return x.shard(GPUS, axis=0), img_ids, img_sizes, cookie + + x, y_boxes, y_labels, matches, anchors, cookie = next(it) + return x.shard(GPUS, axis=0), y_boxes.shard(GPUS, axis=0), y_labels.shard(GPUS, axis=0), matches.shard(GPUS, axis=0), anchors.shard(GPUS, axis=0), cookie + + def _fake_data_get(bs:int, val:bool=False): + x = Tensor.empty(bs, 800, 800, 3, dtype=dtypes.uint8) + if val: + img_ids, img_sizes = [0] * bs, [(800, 800)] * bs + return x.shard(GPUS, axis=0), img_ids, img_sizes, None + + y_boxes = Tensor.empty(bs, 120087, 4, dtype=dtypes.float32) + y_labels = Tensor.empty(bs, 120087, dtype=dtypes.int64) + matches = Tensor.empty(bs, 120087, dtype=dtypes.int64) + anchors = Tensor.empty(bs, 120087, 4, dtype=dtypes.float64) + return x.shard(GPUS, axis=0), y_boxes.shard(GPUS, axis=0), y_labels.shard(GPUS, axis=0), matches.shard(GPUS, axis=0), anchors.shard(GPUS, axis=0), None + + @TinyJit + def _train_step(model, optim, loss_scaler, x, **kwargs): + optim.zero_grad() + + losses = model(normalize(x, GPUS), **kwargs) + loss = sum(losses.values()) + + (loss * loss_scaler).backward() + for t in optim.params: t.grad = t.grad / loss_scaler + + optim.step() + + return loss.realize(), losses + + @TinyJit + def _eval_step(model, x, **kwargs): + out = model(normalize(x, GPUS), **kwargs) + # reassemble on GPUS[0] before sending back to CPU for speed + return out.to(GPUS[0]).realize() + + # ** hyperparameters ** + config["BS"] = BS = getenv("BS", 16 * len(GPUS) if dtypes.default_float == dtypes.float16 else 12 * len(GPUS)) + config["EVAL_BS"] = EVAL_BS = getenv("EVAL_BS", BS) + config["EPOCHS"] = EPOCHS = getenv("EPOCHS", 4) + config["TRAIN_BEAM"] = TRAIN_BEAM = getenv("TRAIN_BEAM", BEAM.value) + config["EVAL_BEAM"] = EVAL_BEAM = getenv("EVAL_BEAM", BEAM.value) + config["LR"] = lr = getenv("LR", 9.5e-5 * (BS / 96)) + config["LOSS_SCALER"] = loss_scaler = getenv("LOSS_SCALER", 2**11 if dtypes.default_float == dtypes.float16 else 1.0) + config["DEFAULT_FLOAT"] = dtypes.default_float.name + config["EVAL_FREQ"] = eval_freq = getenv("EVAL_FREQ", 1) + + # ** initialize wandb ** + if (WANDB:=getenv("WANDB")): + import wandb + wandb.init(config=config, project="MLPerf-RetinaNet") + + # ** model initializers ** + resnet.BatchNorm = FrozenBatchNorm2dRetinaNet + resnet.Linear = Linear + resnet.Conv2d = Conv2dRetinaNet + + retinanet.ConvHead = Conv2dNormalRetinaNet + retinanet.ConvClassificationHeadLogits = functools.partial(Conv2dNormalRetinaNet, prior_prob=0.01) + retinanet.ConvFPN = Conv2dKaimingUniformRetinaNet + + # ** model setup ** + backbone = resnet.ResNeXt50_32X4D(num_classes=None) + if RUNMLPERF: + backbone.load_from_pretrained() + _freeze_backbone_layers(backbone, 3) + + model = retinanet.RetinaNet(backbone, num_classes=NUM_CLASSES) + params = get_parameters(model) + + if not RUNMLPERF: + # for init, zero out all weights + for p in params: + p = p.assign(Tensor.zeros_like(p).contiguous()).realize() + + if len(GPUS) > 1: + for p in params: p.to_(GPUS) + + step_times, start_epoch = [], 0 + + # ** optimizer ** + optim = Adam(params, lr=lr) + + # ** dataset ** + config["STEPS_IN_TRAIN_EPOCH"] = steps_in_train_epoch = round_up(get_dataset_count((base_dir_path:=Path(BASEDIR)), False), BS) // BS + config["STEPS_IN_VAL_EPOCH"] = steps_in_val_epoch = (round_up(get_dataset_count(base_dir_path, True), EVAL_BS) // EVAL_BS) + + # log mlperf hparams + if MLLOGGER: + if RUNMLPERF: + MLLOGGER.event(key=mllog_constants.GLOBAL_BATCH_SIZE, value=config["BS"]) + MLLOGGER.event(key=mllog_constants.TRAIN_SAMPLES, value=config["STEPS_IN_TRAIN_EPOCH"]) + MLLOGGER.event(key=mllog_constants.EVAL_SAMPLES, value=config["STEPS_IN_VAL_EPOCH"]) + MLLOGGER.event(key=mllog_constants.EPOCH_COUNT, value=config["EPOCHS"]) + MLLOGGER.event(key=mllog_constants.FIRST_EPOCH_NUM, value=start_epoch) + + MLLOGGER.event(key=mllog_constants.OPT_NAME, value=mllog_constants.ADAM) + MLLOGGER.event(key=mllog_constants.OPT_BASE_LR, value=config["LR"]) + MLLOGGER.event(key=mllog_constants.OPT_WEIGHT_DECAY, value=0) + MLLOGGER.event(key=mllog_constants.OPT_LR_WARMUP_EPOCHS, value=0) + MLLOGGER.event(key=mllog_constants.OPT_LR_WARMUP_FACTOR, value=0) + MLLOGGER.event(key=mllog_constants.GRADIENT_ACCUMULATION_STEPS, value=1) + + if RUNMLPERF: + train_dataset = COCO(download_dataset(BASEDIR, "train")) + val_dataset = COCO(download_dataset(BASEDIR, "validation")) + coco_val = COCOeval(cocoGt=val_dataset, iouType="bbox") + + print(f"training with batch size {BS} for {EPOCHS} epochs") + + for e in range(start_epoch, EPOCHS): + # ** training loop ** + if MLLOGGER and RUNMLPERF: + MLLOGGER.start(key=mllog_constants.EPOCH_START, value=e + 1, metadata={"epoch_num": e + 1}) + + BEAM.value = TRAIN_BEAM + + if not RUNMLPERF: + i, proc = 0, _fake_data_get(BS) + else: + train_dataloader = batch_load_retinanet(train_dataset, False, base_dir_path, batch_size=BS, seed=SEED) + it = iter(tqdm(train_dataloader, total=steps_in_train_epoch, desc=f"epoch {e + 1}", disable=BENCHMARK)) + i, proc = 0, _data_get(it) + + prev_cookies = [] + st = time.perf_counter() + + while proc is not None: + GlobalCounters.reset() + + x, y_bboxes, y_labels, matches, anchors, proc = proc + loss, losses = _train_step(model, optim, loss_scaler, x, labels=y_labels, matches=matches, anchors=anchors, bboxes=y_bboxes) + + pt = time.perf_counter() + + if len(prev_cookies) == getenv("STORE_COOKIES", 1): prev_cookies = [] # free previous cookies after gpu work has been enqueued + try: + if not RUNMLPERF: + next_proc = _fake_data_get(BS) + else: + next_proc = _data_get(it) + except StopIteration: + next_proc = None + + dt = time.perf_counter() + + device_str = loss.device if isinstance(loss.device, str) else f"{loss.device[0]} * {len(loss.device)}" + loss = loss.item() + + cl = time.perf_counter() + if BENCHMARK: step_times.append(cl - st) + + if not math.isfinite(loss): + print("loss is nan") + return + + tqdm.write( + f"{i:5} {((cl - st)) * 1000.0:7.2f} ms run, {(pt - st) * 1000.0:7.2f} ms python, {(dt - pt) * 1000.0:6.2f} ms fetch data, " + f"{(cl - dt) * 1000.0:7.2f} ms {device_str}, {loss:5.2f} loss, {losses['classification_loss'].item():5.4f} classification loss, {losses['regression_loss'].item():5.4f} regression loss, " + f"{optim.lr.numpy()[0]:.6f} LR, {GlobalCounters.mem_used / 1e9:.2f} GB used, {GlobalCounters.global_ops * 1e-9 / (cl - st):9.2f} GFLOPS" + ) + + if WANDB: + wandb.log({"lr": optim.lr.numpy(), "train/loss": loss, "train/classification_loss": losses["classification_loss"].item(), "train/regression_loss": losses["regression_loss"].item(), + "train/step_time": cl - st, "train/python_time": pt - st, "train/data_time": dt - pt, "train/cl_time": cl - dt, + "train/GFLOPS": GlobalCounters.global_ops * 1e-9 / (cl - st), "epoch": e + (i + 1) / steps_in_train_epoch}) + + st = cl + prev_cookies.append(proc) + proc, next_proc = next_proc, None # return old cookie + i += 1 + + if i == BENCHMARK: + assert not math.isnan(loss) + median_step_time = sorted(step_times)[(BENCHMARK + 1) // 2] # in seconds + estimated_total_minutes = int(median_step_time * steps_in_train_epoch * EPOCHS / 60) + print(f"Estimated training time: {estimated_total_minutes // 60}h{estimated_total_minutes % 60}m") + print(f"epoch global_ops: {steps_in_train_epoch * GlobalCounters.global_ops:_}, " + f"epoch global_mem: {steps_in_train_epoch * GlobalCounters.global_mem:_}") + # if we are doing beam search, run the first eval too + if (TRAIN_BEAM or EVAL_BEAM) and e == start_epoch: break + return + + if MLLOGGER and RUNMLPERF: + MLLOGGER.event(key=mllog_constants.EPOCH_STOP, value=e + 1, metadata={"epoch_num": e + 1}) + + # ** eval loop ** + if (e + 1) % eval_freq == 0: + if MLLOGGER and RUNMLPERF: + MLLOGGER.start(key=mllog_constants.EVAL_START, value=e + 1, metadata={"epoch_num": e + 1}) + + BEAM.value = EVAL_BEAM + + if getenv("RESET_STEP", 1): _train_step.reset() + + with Tensor.train(mode=False), Tensor.test(): + if not RUNMLPERF: + i, proc = 0, _fake_data_get(EVAL_BS, val=(val:=True)) + else: + val_dataloader = batch_load_retinanet(val_dataset, (val:=True), Path(BASEDIR), batch_size=EVAL_BS, shuffle=False, seed=SEED) + it = iter(tqdm(val_dataloader, total=steps_in_val_epoch)) + i, proc = 0, _data_get(it, val=val) + val_img_ids, val_imgs, ncats, narea = [], [], len(coco_val.params.catIds), len(coco_val.params.areaRng) + + eval_times, prev_cookies = [], [] + + while proc is not None: + GlobalCounters.reset() + st = time.time() + + out, img_ids, img_sizes, proc = _eval_step(model, (x:=proc[0])).numpy(), proc[1], proc[2], proc[3] + + if RUNMLPERF: + out = model.postprocess_detections(out, input_size=x.shape[1:3], orig_image_sizes=img_sizes) + coco_results = [{"image_id": img_ids[i], "category_id": label, "bbox": box.tolist(), "score": score} + for i, prediction in enumerate(out) for box, score, label in zip(*prediction.values())] + + with redirect_stdout(None): + coco_val.cocoDt = val_dataset.loadRes(coco_results) + coco_val.params.imgIds = img_ids + coco_val.evaluate() + + val_img_ids.extend(img_ids) + val_imgs.append(np.array(coco_val.evalImgs).reshape(ncats, narea, len(img_ids))) + + if len(prev_cookies) == getenv("STORE_COOKIES", 1): prev_cookies = [] # free previous cookies after gpu work has been enqueued + try: + if not RUNMLPERF: + next_proc = _fake_data_get(EVAL_BS, val=val) + else: + next_proc = _data_get(it, val=val) + except StopIteration: + next_proc = None + + prev_cookies.append(proc) + proc, next_proc = next_proc, None + i += 1 + + et = time.time() + eval_times.append(et - st) + + if i == BENCHMARK: + # assume INITMLPERF has BENCHMARK set + if MLLOGGER and INITMLPERF: + MLLOGGER.event(key=mllog_constants.INIT_STOP) + return + + if getenv("RESET_STEP", 1): _eval_step.reset() + total_fw_time = sum(eval_times) / len(eval_times) + + if RUNMLPERF: + coco_val.params.imgIds = val_img_ids + coco_val._paramsEval.imgIds = val_img_ids + coco_val.evalImgs = list(np.concatenate(val_imgs, -1).flatten()) + coco_val.accumulate() + coco_val.summarize() + + val_metric = coco_val.stats[0] + + tqdm.write(f"eval time: {total_fw_time:.2f}, eval metric: {val_metric:.4f}") + + if WANDB: + wandb.log({"eval/forward_time": total_fw_time, "eval/metric": val_metric, "epoch": e + 1}) + + if MLLOGGER: + MLLOGGER.event(key=mllog_constants.EVAL_ACCURACY, value=val_metric, metadata={"epoch_num": e + 1}, clear_line=True) + MLLOGGER.end(key=mllog_constants.EVAL_STOP, value=e + 1, metadata={"epoch_num": e + 1}) + + if val_metric >= target_metric: + print(colored(f"target metric reached: {val_metric:.2f}/{target_metric:.2f}", color="green")) + + if MLLOGGER: + MLLOGGER.end(key=mllog_constants.RUN_STOP, metadata={"status": mllog_constants.SUCCESS}) + + break def train_unet3d(): """ @@ -446,7 +789,7 @@ def train_unet3d(): loss.backward() optim.step() return loss.realize() - + @Tensor.train(mode=False) @Tensor.test() def eval_step(model, x, y): @@ -455,7 +798,7 @@ def train_unet3d(): loss = dice_ce_loss(y_hat, y) score = dice_score(y_hat, y) return loss.realize(), score.realize() - + if WANDB: wandb.init(config=config, project=PROJ_NAME) step_times, start_epoch = [], 1 @@ -464,7 +807,7 @@ def train_unet3d(): next_eval_at = start_eval_at print(f"Training on {GPUS}") - + if BENCHMARK: print("Benchmarking UNet3D") else: print(f"Start evaluation at epoch {start_eval_at} and every {evaluate_every} epoch(s) afterwards") @@ -551,7 +894,7 @@ def train_unet3d(): if mean_dice >= TARGET_METRIC: is_successful = True - save_checkpoint(get_state_dict(model), f"./ckpts/unet3d.safe") + save_checkpoint(get_state_dict(model), "./ckpts/unet3d.safe") elif mean_dice < 1e-6: print("Model diverging. Aborting.") diverged = True @@ -572,39 +915,49 @@ def train_rnnt(): pass @TinyJit -def train_step_bert(model, optimizer, scheduler, loss_scaler:float, input_ids:Tensor, segment_ids:Tensor, attention_mask:Tensor, masked_positions:Tensor, masked_lm_ids:Tensor, masked_lm_weights:Tensor, next_sentence_labels:Tensor): +def train_step_bert(model, optimizer, scheduler, loss_scaler:float, input_ids:Tensor, segment_ids:Tensor, attention_mask:Tensor, + masked_positions:Tensor, masked_lm_ids:Tensor, masked_lm_weights:Tensor, next_sentence_labels:Tensor, GPUS): + for t in [input_ids, segment_ids, attention_mask, masked_positions, masked_lm_ids, masked_lm_weights, next_sentence_labels]: + if len(GPUS) > 1: t.shard_(GPUS, axis=0) + else: t.to_(GPUS[0]) optimizer.zero_grad() lm_logits, seq_relationship_logits = model(input_ids, attention_mask, masked_positions, segment_ids) loss = model.loss(lm_logits, seq_relationship_logits, masked_lm_ids, masked_lm_weights, next_sentence_labels) (loss * loss_scaler).backward() - global_norm = Tensor([0.0], dtype=dtypes.float32, device=optimizer[0].device).realize() - for p in optimizer.params: + global_norm = Tensor([0.0], dtype=dtypes.float32, device=optimizer[0].device) + for p in optimizer.params: p.grad = p.grad / loss_scaler global_norm += p.grad.float().square().sum() - global_norm = global_norm.sqrt() - for p in optimizer.params: p.grad = (p.grad / Tensor.where(global_norm > 1.0, global_norm, 1.0)).cast(p.grad.dtype) + global_norm = global_norm.sqrt().contiguous() + for p in optimizer.params: + p.grad = (global_norm > 1.0).where((p.grad/global_norm).cast(p.grad.dtype), p.grad) optimizer.step() scheduler.step() - return loss.realize() + # TODO: no to("CPU") here because it blocks and messes the python time + Tensor.realize(loss, global_norm, optimizer.optimizers[0].lr) + return loss, global_norm, optimizer.optimizers[0].lr @TinyJit -def eval_step_bert(model, input_ids:Tensor, segment_ids:Tensor, attention_mask:Tensor, masked_positions:Tensor, masked_lm_ids:Tensor, masked_lm_weights:Tensor, next_sentence_labels:Tensor): +def eval_step_bert(model, input_ids:Tensor, segment_ids:Tensor, attention_mask:Tensor, masked_positions:Tensor, masked_lm_ids:Tensor, + masked_lm_weights:Tensor, next_sentence_labels:Tensor, GPUS): + for t in [input_ids, segment_ids, attention_mask, masked_positions, masked_lm_ids, masked_lm_weights, next_sentence_labels]: + if len(GPUS) > 1: t.shard_(GPUS, axis=0) + else: t.to_(GPUS[0]) lm_logits, seq_relationship_logits = model(input_ids, attention_mask, masked_positions, segment_ids) - masked_lm_accuracy, seq_relationship_accuracy, masked_lm_loss, next_sentence_loss = model.accuracy(lm_logits, seq_relationship_logits, masked_lm_ids, masked_lm_weights, next_sentence_labels) - return { - "masked_lm_accuracy": masked_lm_accuracy.realize(), - "next_sentence_accuracy": seq_relationship_accuracy.realize(), - "masked_lm_loss": masked_lm_loss.realize(), - "next_sentence_loss": next_sentence_loss.realize() - } + masked_lm_accuracy, seq_relationship_accuracy, masked_lm_loss, next_sentence_loss = \ + model.accuracy(lm_logits, seq_relationship_logits, masked_lm_ids, masked_lm_weights, next_sentence_labels) + for t in [masked_lm_accuracy, seq_relationship_accuracy, masked_lm_loss, next_sentence_loss]: + t.to_("CPU") + Tensor.realize(masked_lm_accuracy, seq_relationship_accuracy, masked_lm_loss, next_sentence_loss) + return masked_lm_accuracy, seq_relationship_accuracy, masked_lm_loss, next_sentence_loss def train_bert(): # NOTE: pip install tensorflow, wandb required from examples.mlperf.dataloader import batch_load_train_bert, batch_load_val_bert - from examples.mlperf.helpers import get_mlperf_bert_model, get_data_bert, get_fake_data_bert + from examples.mlperf.helpers import get_mlperf_bert_model, get_fake_data_bert from examples.mlperf.lr_schedulers import PolynomialDecayWithWarmup config = {} @@ -628,7 +981,7 @@ def train_bert(): MLLOGGER.logger.propagate = False if INITMLPERF: - assert BENCHMARK, f"BENCHMARK must be set for INITMLPERF" + assert BENCHMARK, "BENCHMARK must be set for INITMLPERF" MLLOGGER.event(key=mllog_constants.SUBMISSION_ORG, value="tinycorp") MLLOGGER.event(key=mllog_constants.SUBMISSION_PLATFORM, value=getenv("SUBMISSION_PLATFORM", "tinybox")) MLLOGGER.event(key=mllog_constants.SUBMISSION_DIVISION, value=mllog_constants.CLOSED) @@ -649,9 +1002,11 @@ def train_bert(): # ** hyperparameters ** BS = config["GLOBAL_BATCH_SIZE"] = getenv("BS", 11 * len(GPUS) if dtypes.default_float in (dtypes.float16, dtypes.bfloat16) else 8 * len(GPUS)) EVAL_BS = config["EVAL_BS"] = getenv("EVAL_BS", 1 * len(GPUS)) - max_lr = config["OPT_BASE_LEARNING_RATE"] = getenv("OPT_BASE_LEARNING_RATE", 0.0001 * math.sqrt(BS/66)) + max_lr = config["OPT_BASE_LEARNING_RATE"] = getenv("OPT_BASE_LEARNING_RATE", 0.000175 * math.sqrt(BS/96)) + opt_lamb_beta_1 = config["OPT_LAMB_BETA_1"] = getenv("OPT_LAMB_BETA_1", 0.9) + opt_lamb_beta_2 = config["OPT_LAMB_BETA_2"] = getenv("OPT_LAMB_BETA_2", 0.999) - train_steps = config["TRAIN_STEPS"] = getenv("TRAIN_STEPS", 3630000 // BS) + train_steps = config["TRAIN_STEPS"] = getenv("TRAIN_STEPS", 3600000 // BS) warmup_steps = config["NUM_WARMUP_STEPS"] = getenv("NUM_WARMUP_STEPS", 1) max_eval_steps = config["MAX_EVAL_STEPS"] = getenv("MAX_EVAL_STEPS", (10000 + EVAL_BS - 1) // EVAL_BS) # EVAL_BS * MAX_EVAL_STEPS >= 10000 eval_step_freq = config["EVAL_STEP_FREQ"] = getenv("EVAL_STEP_FREQ", int((math.floor(0.05 * (230.23 * BS + 3000000) / 25000) * 25000) / BS)) # Round down @@ -660,7 +1015,7 @@ def train_bert(): save_ckpt_dir = config["SAVE_CKPT_DIR"] = getenv("SAVE_CKPT_DIR", "./ckpts") init_ckpt = config["INIT_CKPT_DIR"] = getenv("INIT_CKPT_DIR", BASEDIR) - loss_scaler = config["LOSS_SCALER"] = getenv("LOSS_SCALER", 2.0**10 if dtypes.default_float == dtypes.float16 else 1.0) + loss_scaler = config["LOSS_SCALER"] = getenv("LOSS_SCALER", 2.0**11 if dtypes.default_float == dtypes.float16 else 1.0) decay = config["DECAY"] = getenv("DECAY", 0.01) epsilon = config["EPSILON"] = getenv("EPSILON", 1e-6) poly_power = config["POLY_POWER"] = getenv("POLY_POWER", 1.0) @@ -685,11 +1040,18 @@ def train_bert(): # ** init model ** - model = get_mlperf_bert_model(init_ckpt if RUNMLPERF else None) - - for _, x in get_state_dict(model).items(): - x.realize().to_(GPUS) + model = get_mlperf_bert_model() + if RUNMLPERF: + model.load_from_pretrained(init_ckpt) + else: + # for init, zero out all weights + for p in get_parameters(model): + p = p.assign(Tensor.zeros_like(p).contiguous()).realize() + parameters = get_parameters(model) + if len(GPUS) > 1: + for p in parameters: + p.to_(GPUS) # ** Log run config ** for key, value in config.items(): print(f'HParam: "{key}": {value}') @@ -697,8 +1059,8 @@ def train_bert(): # ** Optimizer ** parameters_no_wd = [v for k, v in get_state_dict(model).items() if "bias" in k or "LayerNorm" in k] parameters = [x for x in parameters if x not in set(parameters_no_wd)] - optimizer_wd = LAMB(parameters, lr=max_lr, eps=epsilon, weight_decay=decay, adam=False) - optimizer_no_wd = LAMB(parameters_no_wd, lr=max_lr, eps=epsilon, weight_decay=0.0, adam=False) + optimizer_wd = LAMB(parameters, lr=max_lr, b1=opt_lamb_beta_1, b2=opt_lamb_beta_2, eps=epsilon, weight_decay=decay, adam=False) + optimizer_no_wd = LAMB(parameters_no_wd, lr=max_lr, b1=opt_lamb_beta_1, b2=opt_lamb_beta_2, eps=epsilon, weight_decay=0.0, adam=False) optimizer_group = OptimizerGroup(optimizer_wd, optimizer_no_wd) # ** LR scheduler ** @@ -717,8 +1079,8 @@ def train_bert(): MLLOGGER.event(key=mllog_constants.OPT_NAME, value="LAMB") MLLOGGER.event(key=mllog_constants.OPT_BASE_LR, value=config["OPT_BASE_LEARNING_RATE"]) MLLOGGER.event(key=mllog_constants.OPT_LAMB_WEIGHT_DECAY, value=config["DECAY"]) - MLLOGGER.event(key=mllog_constants.OPT_LAMB_BETA_1, value=optimizer_wd.b1) - MLLOGGER.event(key=mllog_constants.OPT_LAMB_BETA_2, value=optimizer_wd.b2) + MLLOGGER.event(key=mllog_constants.OPT_LAMB_BETA_1, value=config["OPT_LAMB_BETA_1"]) + MLLOGGER.event(key=mllog_constants.OPT_LAMB_BETA_2, value=config["OPT_LAMB_BETA_2"]) MLLOGGER.event(key=mllog_constants.OPT_LAMB_LR_DECAY_POLY_POWER, value=config["POLY_POWER"]) MLLOGGER.event(key=mllog_constants.OPT_LAMB_EPSILON, value=config["EPSILON"]) @@ -735,7 +1097,7 @@ def train_bert(): previous_step = None if ckpt:=getenv("RESUME", ""): load_training_state(model, optimizer_group, scheduler_group, safe_load(ckpt)) - start_step = int(scheduler_wd.epoch_counter.numpy().item()) + start_step = int(scheduler_wd.epoch_counter.item()) print(f"resuming from {ckpt} at step {start_step}") if RUNMLPERF: @@ -743,70 +1105,76 @@ def train_bert(): eval_it = iter(batch_load_val_bert(EVAL_BS)) train_it = iter(tqdm(batch_load_train_bert(BS), total=train_steps, disable=BENCHMARK)) for _ in range(start_step): next(train_it) # Fast forward - + else: + # repeat fake data + def repeat_fake(bs): + while True: yield get_fake_data_bert(bs) + eval_it = iter(repeat_fake(EVAL_BS)) + train_it = iter(repeat_fake(BS)) step_times = [] # ** train loop ** wc_start = time.perf_counter() + + i, train_data = start_step, next(train_it) + if RUNMLPERF: - # only load real data with RUNMLPERF - i, train_data = start_step, get_data_bert(GPUS, train_it) if MLLOGGER: MLLOGGER.start(key=mllog_constants.EPOCH_START, value=i*BS, metadata={"epoch_num": i*BS}) - else: - i, train_data = start_step, get_fake_data_bert(GPUS, BS) while train_data is not None and i < train_steps and not achieved: - Tensor.training = True - BEAM.value = TRAIN_BEAM - st = time.perf_counter() - GlobalCounters.reset() - loss = train_step_bert(model, optimizer_group, scheduler_group, loss_scaler, - train_data["input_ids"], train_data["segment_ids"], train_data["input_mask"], train_data["masked_lm_positions"], \ - train_data["masked_lm_ids"], train_data["masked_lm_weights"], train_data["next_sentence_labels"]) + if getenv("TRAIN", 1): + Tensor.training = True + BEAM.value = TRAIN_BEAM + st = time.perf_counter() + GlobalCounters.reset() + with WallTimeEvent(BenchEvent.STEP): + loss, global_norm, lr = train_step_bert(model, optimizer_group, scheduler_group, loss_scaler, + train_data["input_ids"], train_data["segment_ids"], train_data["input_mask"], train_data["masked_lm_positions"], \ + train_data["masked_lm_ids"], train_data["masked_lm_weights"], train_data["next_sentence_labels"], GPUS) - pt = time.perf_counter() + pt = time.perf_counter() - try: - if RUNMLPERF: - next_data = get_data_bert(GPUS, train_it) - else: - next_data = get_fake_data_bert(GPUS, BS) - except StopIteration: - next_data = None + try: + next_data = next(train_it) + except StopIteration: + next_data = None - dt = time.perf_counter() + dt = time.perf_counter() - device_str = loss.device if isinstance(loss.device, str) else f"{loss.device[0]} * {len(loss.device)}" - loss = loss.numpy().item() + device_str = parameters[0].device if isinstance(parameters[0].device, str) else f"{parameters[0].device[0]} * {len(parameters[0].device)}" + loss = loss.item() + assert not math.isnan(loss) + lr = lr.item() - cl = time.perf_counter() - if BENCHMARK: step_times.append(cl - st) + cl = time.perf_counter() + if BENCHMARK: step_times.append(cl - st) - tqdm.write( - f"{i:5} {((cl - st)) * 1000.0:7.2f} ms run, {(pt - st) * 1000.0:7.2f} ms python, {(dt - pt) * 1000.0:6.2f} ms fetch data, " - f"{(cl - dt) * 1000.0:7.2f} ms {device_str}, {loss:5.2f} loss, {optimizer_wd.lr.numpy()[0]:.6f} LR, " - f"{GlobalCounters.mem_used / 1e9:.2f} GB used, {GlobalCounters.global_ops * 1e-9 / (cl - st):9.2f} GFLOPS") - if WANDB: - wandb.log({"lr": optimizer_wd.lr.numpy(), "train/loss": loss, "train/step_time": cl - st, - "train/python_time": pt - st, "train/data_time": dt - pt, "train/cl_time": cl - dt, - "train/GFLOPS": GlobalCounters.global_ops * 1e-9 / (cl - st), "epoch": (i+1)*BS}) + tqdm.write( + f"{i:5} {((cl - st)) * 1000.0:7.2f} ms run, {(pt - st) * 1000.0:7.2f} ms python, {(dt - pt) * 1000.0:6.2f} ms fetch data, " + f"{(cl - dt) * 1000.0:7.2f} ms {device_str}, {loss:5.2f} loss, {lr:.6f} LR, " + f"{GlobalCounters.mem_used / 1e9:.2f} GB used, {GlobalCounters.global_ops * 1e-9 / (cl - st):9.2f} GFLOPS") + if WANDB: + wandb.log({"lr": lr, "train/loss": loss, "train/global_norm": global_norm.item(), "train/step_time": cl - st, + "train/python_time": pt - st, "train/data_time": dt - pt, "train/cl_time": cl - dt, + "train/GFLOPS": GlobalCounters.global_ops * 1e-9 / (cl - st), "epoch": (i+1)*BS}) - train_data, next_data = next_data, None - i += 1 + train_data, next_data = next_data, None + i += 1 - if i == BENCHMARK: - median_step_time = sorted(step_times)[(BENCHMARK + 1) // 2] # in seconds - estimated_total_minutes = int(median_step_time * train_steps / 60) - print(f"Estimated training time: {estimated_total_minutes // 60}h{estimated_total_minutes % 60}m") - print(f"epoch global_ops: {train_steps * GlobalCounters.global_ops:_}, " - f"epoch global_mem: {train_steps * GlobalCounters.global_mem:_}") + if i == BENCHMARK: + median_step_time = sorted(step_times)[(BENCHMARK + 1) // 2] # in seconds + estimated_total_minutes = int(median_step_time * train_steps / 60) + print(f"Estimated training time: {estimated_total_minutes // 60}h{estimated_total_minutes % 60}m") + print(f"epoch global_ops: {train_steps * GlobalCounters.global_ops:_}, " + f"epoch global_mem: {train_steps * GlobalCounters.global_mem:_}") # ** eval loop ** - if i % eval_step_freq == 0 or (BENCHMARK and i == BENCHMARK): + if i % eval_step_freq == 0 or (BENCHMARK and i == BENCHMARK) or i == train_steps: if MLLOGGER and RUNMLPERF: MLLOGGER.start(key=mllog_constants.EVAL_START, value=None, metadata={"epoch_num": i*BS, "step_num": i}) - if getenv("RESET_STEP", 1): train_step_bert.reset() + if getenv("RESET_STEP"): train_step_bert.reset() + elif getenv("FREE_INTERMEDIATE", 1) and train_step_bert.captured is not None: train_step_bert.captured.free_intermediates() eval_lm_losses = [] eval_clsf_losses = [] eval_lm_accs = [] @@ -816,19 +1184,14 @@ def train_bert(): BEAM.value = EVAL_BEAM for j in tqdm(range(max_eval_steps), desc="Evaluating", total=max_eval_steps, disable=BENCHMARK): - if RUNMLPERF: - eval_data = get_data_bert(GPUS, eval_it) - else: - eval_data = get_fake_data_bert(GPUS, EVAL_BS) + eval_data = next(eval_it) GlobalCounters.reset() st = time.time() - eval_result: dict[str, Tensor] = eval_step_bert(model, + lm_acc, clsf_acc, lm_loss, clsf_loss = eval_step_bert(model, eval_data["input_ids"], eval_data["segment_ids"], eval_data["input_mask"], eval_data["masked_lm_positions"], - eval_data["masked_lm_ids"], eval_data["masked_lm_weights"], eval_data["next_sentence_labels"]) - - lm_loss, clsf_loss = eval_result["masked_lm_loss"].item(), eval_result["next_sentence_loss"].item() - lm_acc, clsf_acc = eval_result["masked_lm_accuracy"].item(), eval_result["next_sentence_accuracy"].item() + eval_data["masked_lm_ids"], eval_data["masked_lm_weights"], eval_data["next_sentence_labels"], GPUS) + lm_acc, clsf_acc, lm_loss, clsf_loss = lm_acc.item(), clsf_acc.item(), lm_loss.item(), clsf_loss.item() eval_lm_losses.append(lm_loss) eval_clsf_losses.append(clsf_loss) @@ -838,14 +1201,16 @@ def train_bert(): et = time.time() eval_times.append(et - st) - if BENCHMARK and j == BENCHMARK: + if BENCHMARK and (j+1) == min(BENCHMARK, max_eval_steps): # assume INITMLPERF has BENCHMARK set if MLLOGGER and INITMLPERF: MLLOGGER.event(key=mllog_constants.INIT_STOP, value=None) return - if getenv("RESET_STEP", 1): eval_step_bert.reset() - del eval_data, eval_result + if getenv("RESET_STEP"): eval_step_bert.reset() + elif getenv("FREE_INTERMEDIATE", 1) and eval_step_bert.captured is not None: eval_step_bert.captured.free_intermediates() + + del eval_data avg_lm_loss = sum(eval_lm_losses) / len(eval_lm_losses) avg_clsf_loss = sum(eval_clsf_losses) / len(eval_clsf_losses) avg_lm_acc = sum(eval_lm_accs) / len(eval_lm_accs) @@ -857,7 +1222,7 @@ def train_bert(): if WANDB: wandb.log({"eval/lm_loss": avg_lm_loss, "eval/clsf_loss": avg_clsf_loss, "eval/lm_accuracy": avg_lm_acc, \ - "eval/clsf_accuracy": avg_clsf_acc, "eval/forward_time": avg_fw_time}) + "eval/clsf_accuracy": avg_clsf_acc, "eval/forward_time": avg_fw_time, "epoch": (i+1)*BS}) if MLLOGGER and RUNMLPERF: MLLOGGER.end(key=mllog_constants.EVAL_STOP, value=i*BS, metadata={"epoch_count": i*BS, "step_num": i, "samples_count": config["EVAL_BS"] * config["MAX_EVAL_STEPS"]}) @@ -884,11 +1249,14 @@ def train_bert(): # stop once hitting the target break + # should not happen, BENCHMARK not properly terminated + if BENCHMARK: assert i < BENCHMARK, i + if getenv("CKPT") and i % save_ckpt_freq == 0: if MLLOGGER and RUNMLPERF: if previous_step: MLLOGGER.end(key=mllog_constants.BLOCK_STOP, value=None, metadata={"first_epoch_num": 1, "epoch_num": 1, "first_step_num": i, "step_num": i, "step_count": i - previous_step}) - MLLOGGER.start(key="checkpoint_start", value=None, metadata={"step_num" : i}) + MLLOGGER.start(key="checkpoint_start", value=None, metadata={"step_num": i}) if not os.path.exists(ckpt_dir := save_ckpt_dir): os.mkdir(ckpt_dir) if WANDB and wandb.run is not None: fn = f"{ckpt_dir}/{time.strftime('%Y%m%d_%H%M%S')}_{wandb.run.id}.safe" @@ -918,4 +1286,4 @@ if __name__ == "__main__": nm = f"train_{m}" if nm in globals(): print(f"training {m}") - globals()[nm]() + with Profiling(enabled=getenv("PYPROFILE")): globals()[nm]() diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_1xMI300X/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_1xMI300X/dev_beam.sh new file mode 100755 index 0000000000..35080c34be --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_1xMI300X/dev_beam.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="bert" +export DEFAULT_FLOAT="HALF" GPUS=1 BS=128 EVAL_BS=128 + +export BEAM=3 BEAM_UOPS_MAX=4000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 +export IGNORE_JIT_FIRST_BEAM=1 +# export BEAM_LOG_SURPASS_MAX=1 +# export BASEDIR="/raid/datasets/wiki" + +export RESET_STEP=1 +export BENCHMARK=10 BERT_LAYERS=2 DEBUG=2 + +python3 examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/README.md b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/README.md new file mode 100644 index 0000000000..844b90f949 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/README.md @@ -0,0 +1,69 @@ +# 1. Problem + +This problem uses BERT for NLP. + +## Requirements + +Install tinygrad and mlperf-logging (uncomment mlperf from setup.py) from branch mlperf_training_v5.0. +``` +git clone https://github.com/tinygrad/tinygrad.git +python3 -m pip install -e ".[mlperf]" +``` +Also install gdown (for dataset), numpy, tqdm and tensorflow. +``` +pip install gdown numpy tqdm tensorflow +``` + +### tinybox_green +Install the p2p driver per [README](https://github.com/tinygrad/open-gpu-kernel-modules/blob/550.54.15-p2p/README.md) +This is the default on production tinybox green. + +# 2. Directions + +## Steps to download and verify data + +### 1. Download raw data + +``` +BASEDIR="/raid/datasets/wiki" WIKI_TRAIN=1 VERIFY_CHECKSUM=1 python3 extra/datasets/wikipedia_download.py +``` + +### 2. Preprocess train and validation data + +Note: The number of threads used for preprocessing is limited by available memory. With 128GB of RAM, a maximum of 16 threads is recommended. + +#### Training: +``` +BASEDIR="/raid/datasets/wiki" NUM_WORKERS=16 python3 extra/datasets/wikipedia.py pre-train all +``` + +Generating a specific topic (Between 0 and 499) +``` +BASEDIR="/raid/datasets/wiki" python3 extra/datasets/wikipedia.py pre-train 42 +``` + +#### Validation: +``` +BASEDIR="/raid/datasets/wiki" python3 extra/datasets/wikipedia.py pre-eval +``` +## Running + +### tinybox_green + +#### Steps to run benchmark +``` +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh +``` + +### tinybox_red + +#### Steps to run benchmark +``` +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh +``` +### tinybox_8xMI300X + +#### Steps to run benchmark +``` +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh +``` \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_beam.sh new file mode 100755 index 0000000000..dff326fce3 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_beam.sh @@ -0,0 +1,14 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="bert" +export DEFAULT_FLOAT="HALF" GPUS=8 BS=1024 EVAL_BS=1024 +export OPT_BASE_LEARNING_RATE=0.0011 OPT_LAMB_BETA_1=0.60466 OPT_LAMB_BETA_2=0.85437 DECAY=0.1 + +export BEAM=3 BEAM_UOPS_MAX=6000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 +export IGNORE_JIT_FIRST_BEAM=1 FREE_INTERMEDIATE=0 +export BASEDIR="/raid/datasets/wiki" + +export BENCHMARK=10 BERT_LAYERS=2 DEBUG=2 + +python3 examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_run.sh new file mode 100755 index 0000000000..ee43e95deb --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/dev_run.sh @@ -0,0 +1,17 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="bert" +export DEFAULT_FLOAT="HALF" GPUS=8 BS=1024 EVAL_BS=1024 + +# similar to https://github.com/mlcommons/training_results_v3.1/blob/d06288b2bd675a9d88e0e6181f5bb5626b71ec19/Quanta_Cloud_Technology/results/D54U-3U/bert/result_1.txt#L54 +export OPT_BASE_LEARNING_RATE=0.0011 OPT_LAMB_BETA_1=0.60466 OPT_LAMB_BETA_2=0.85437 DECAY=0.1 +export TRAIN_STEPS=3900 + +export BEAM=3 BEAM_UOPS_MAX=6000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 +export IGNORE_JIT_FIRST_BEAM=1 FREE_INTERMEDIATE=0 +export BASEDIR="/raid/datasets/wiki" + +export WANDB=1 PARALLEL=0 + +RUNMLPERF=1 python3 examples/mlperf/model_train.py \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh new file mode 100755 index 0000000000..e7ab41d19b --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh @@ -0,0 +1,27 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="bert" +export SUBMISSION_PLATFORM="tinybox_8xMI300X" +export DEFAULT_FLOAT="HALF" GPUS=8 BS=1024 EVAL_BS=1024 + +# similar to https://github.com/mlcommons/training_results_v3.1/blob/d06288b2bd675a9d88e0e6181f5bb5626b71ec19/Quanta_Cloud_Technology/results/D54U-3U/bert/result_1.txt#L54 +export OPT_BASE_LEARNING_RATE=0.0011 OPT_LAMB_BETA_1=0.60466 OPT_LAMB_BETA_2=0.85437 DECAY=0.1 +export TRAIN_STEPS=3900 + +export BEAM=3 BEAM_UOPS_MAX=6000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 +export IGNORE_JIT_FIRST_BEAM=1 FREE_INTERMEDIATE=0 +export BASEDIR="/raid/datasets/wiki" + +# pip install -e ".[mlperf]" +export LOGMLPERF=1 + +export SEED=$RANDOM +DATETIME=$(date "+%m%d%H%M") +LOGFILE="bert_8xMI300x_${DATETIME}_${SEED}.log" + +# init # TODO: without DEBUG=2 it hangs +BENCHMARK=10 INITMLPERF=1 BERT_LAYERS=2 DEBUG=2 python3 examples/mlperf/model_train.py | tee $LOGFILE + +# run +PARALLEL=0 RUNMLPERF=1 python3 examples/mlperf/model_train.py | tee -a $LOGFILE diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/README.md b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/README.md index e79373658a..844b90f949 100644 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/README.md +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/README.md @@ -4,24 +4,20 @@ This problem uses BERT for NLP. ## Requirements -Install tinygrad and mlperf-logging from master. +Install tinygrad and mlperf-logging (uncomment mlperf from setup.py) from branch mlperf_training_v5.0. ``` git clone https://github.com/tinygrad/tinygrad.git python3 -m pip install -e ".[mlperf]" ``` -Also install tqdm and tensorflow. +Also install gdown (for dataset), numpy, tqdm and tensorflow. ``` -pip install tqdm tensorflow +pip install gdown numpy tqdm tensorflow ``` ### tinybox_green Install the p2p driver per [README](https://github.com/tinygrad/open-gpu-kernel-modules/blob/550.54.15-p2p/README.md) This is the default on production tinybox green. -### tinybox_red -Disable cwsr + increase mes timeout. -Install the custom amdgpu driver per [README](https://github.com/nimlgen/amdgpu_ubuntu_22_04/blob/v6.1.3/readme.md) - # 2. Directions ## Steps to download and verify data @@ -56,18 +52,18 @@ BASEDIR="/raid/datasets/wiki" python3 extra/datasets/wikipedia.py pre-eval #### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh ``` ### tinybox_red -#### One time setup - +#### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_red/setup.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh ``` +### tinybox_8xMI300X #### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh ``` \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_beam.sh index a6b45747f7..1205c210da 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_beam.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_beam.sh @@ -1,13 +1,16 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="bert" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=4 BEAM_UOPS_MAX=2000 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=512 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=8 BEAM_UOPS_MAX=10000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 +export BEAM_LOG_SURPASS_MAX=1 export BASEDIR="/raid/datasets/wiki" -export BENCHMARK=10 DEBUG=2 +export BENCHMARK=10 BERT_LAYERS=2 DEBUG=2 python3 examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_run.sh index a1bb814f07..f71688abf8 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_run.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/dev_run.sh @@ -1,10 +1,12 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="bert" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=4 BEAM_UOPS_MAX=2000 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=512 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=8 BEAM_UOPS_MAX=10000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 export BASEDIR="/raid/datasets/wiki" diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh index 50542450c9..9145b07279 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh @@ -1,11 +1,13 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="bert" export SUBMISSION_PLATFORM="tinybox_green" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=4 BEAM_UOPS_MAX=2000 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=512 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=8 BEAM_UOPS_MAX=10000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 export BASEDIR="/raid/datasets/wiki" @@ -17,7 +19,7 @@ DATETIME=$(date "+%m%d%H%M") LOGFILE="bert_green_${DATETIME}_${SEED}.log" # init -BENCHMARK=10 INITMLPERF=1 python3 examples/mlperf/model_train.py | tee $LOGFILE +BENCHMARK=10 INITMLPERF=1 BERT_LAYERS=2 python3 examples/mlperf/model_train.py | tee $LOGFILE # run PARALLEL=0 RUNMLPERF=1 python3 examples/mlperf/model_train.py | tee -a $LOGFILE diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/README.md b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/README.md index e79373658a..844b90f949 100644 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/README.md +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/README.md @@ -4,24 +4,20 @@ This problem uses BERT for NLP. ## Requirements -Install tinygrad and mlperf-logging from master. +Install tinygrad and mlperf-logging (uncomment mlperf from setup.py) from branch mlperf_training_v5.0. ``` git clone https://github.com/tinygrad/tinygrad.git python3 -m pip install -e ".[mlperf]" ``` -Also install tqdm and tensorflow. +Also install gdown (for dataset), numpy, tqdm and tensorflow. ``` -pip install tqdm tensorflow +pip install gdown numpy tqdm tensorflow ``` ### tinybox_green Install the p2p driver per [README](https://github.com/tinygrad/open-gpu-kernel-modules/blob/550.54.15-p2p/README.md) This is the default on production tinybox green. -### tinybox_red -Disable cwsr + increase mes timeout. -Install the custom amdgpu driver per [README](https://github.com/nimlgen/amdgpu_ubuntu_22_04/blob/v6.1.3/readme.md) - # 2. Directions ## Steps to download and verify data @@ -56,18 +52,18 @@ BASEDIR="/raid/datasets/wiki" python3 extra/datasets/wikipedia.py pre-eval #### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_green/run_and_time.sh ``` ### tinybox_red -#### One time setup - +#### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_red/setup.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh ``` +### tinybox_8xMI300X #### Steps to run benchmark ``` -examples/mlperf/training_submission_v4.1/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_8xMI300X/run_and_time.sh ``` \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_beam.sh index 5af5fd2d5f..f99bf30205 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_beam.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_beam.sh @@ -1,13 +1,17 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="bert" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=3 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=5 BEAM_UOPS_MAX=8000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 +export BEAM_LOG_SURPASS_MAX=1 export BASEDIR="/raid/datasets/wiki" -export BENCHMARK=10 DEBUG=2 +export RESET_STEP=1 +export BENCHMARK=10 BERT_LAYERS=2 DEBUG=2 python3 examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_run.sh index a4636ac6f9..7f577c9cdd 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_run.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/dev_run.sh @@ -1,10 +1,12 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="bert" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=3 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=5 BEAM_UOPS_MAX=8000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 export BASEDIR="/raid/datasets/wiki" diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh index 458fcac97a..e174088211 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/run_and_time.sh @@ -1,11 +1,13 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="bert" export SUBMISSION_PLATFORM="tinybox_red" -export DEFAULT_FLOAT="HALF" GPUS=6 BS=72 EVAL_BS=6 +export DEFAULT_FLOAT="HALF" SUM_DTYPE="HALF" GPUS=6 BS=96 EVAL_BS=96 -export BEAM=3 +export FUSE_ARANGE=1 FUSE_ARANGE_UINT=0 + +export BEAM=5 BEAM_UOPS_MAX=8000 BEAM_UPCAST_MAX=256 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 export IGNORE_JIT_FIRST_BEAM=1 export BASEDIR="/raid/datasets/wiki" @@ -16,8 +18,13 @@ export SEED=$RANDOM DATETIME=$(date "+%m%d%H%M") LOGFILE="bert_red_${DATETIME}_${SEED}.log" +export HCQDEV_WAIT_TIMEOUT_MS=100000 # prevents hang? + # init -BENCHMARK=10 INITMLPERF=1 python3 examples/mlperf/model_train.py | tee $LOGFILE +sleep 5 && sudo rmmod amdgpu || true +BENCHMARK=10 INITMLPERF=1 BERT_LAYERS=2 python3 examples/mlperf/model_train.py | tee $LOGFILE # run +# TODO: AM driver resulted in nan +sudo modprobe amdgpu PARALLEL=0 RUNMLPERF=1 python3 examples/mlperf/model_train.py | tee -a $LOGFILE diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/setup.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/setup.sh deleted file mode 100755 index 3d687cdb98..0000000000 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/bert/implementations/tinybox_red/setup.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash - -rocm-smi --setprofile compute -rocm-smi --setmclk 3 -rocm-smi --setperflevel high - -# power cap to 350W -# echo "350000000" | sudo tee /sys/class/drm/card{1..6}/device/hwmon/hwmon*/power1_cap diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_beam.sh index 18e155096e..2319da3fdc 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_beam.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_beam.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="resnet" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_run.sh index 3d6ad317d0..ebe927c373 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_run.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/dev_run.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="resnet" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/run_and_time.sh index 91b64df3fe..230c3583ad 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/run_and_time.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_green/run_and_time.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." NV=1 export MODEL="resnet" export SUBMISSION_PLATFORM="tinybox_green" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 @@ -10,7 +10,7 @@ export RESET_STEP=0 export TRAIN_BEAM=4 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=10 BEAM_PADTO=0 # pip install -e ".[mlperf]" -export LOGMLPERF=1 +export LOGMLPERF=${LOGMLPERF:-1} export SEED=$RANDOM DATETIME=$(date "+%m%d%H%M") diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_beam.sh index 94894c175e..7bcbec2f03 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_beam.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_beam.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="resnet" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 @@ -8,6 +8,6 @@ export RESET_STEP=0 export TRAIN_BEAM=4 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=2000 BEAM_UPCAST_MAX=96 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 -export BENCHMARK=10 DEBUG=2 +export BENCHMARK=10 DEBUG=${DEBUG:-2} python3 examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_run.sh index 467179ea93..aad23e43df 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_run.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/dev_run.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="resnet" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/run_and_time.sh index 8d7efcc854..479297eb0f 100755 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/run_and_time.sh +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/resnet/implementations/tinybox_red/run_and_time.sh @@ -1,6 +1,6 @@ #!/bin/bash -export PYTHONPATH="." +export PYTHONPATH="." AMD=1 export MODEL="resnet" export SUBMISSION_PLATFORM="tinybox_red" export DEFAULT_FLOAT="HALF" GPUS=6 BS=1536 EVAL_BS=192 @@ -10,7 +10,7 @@ export RESET_STEP=0 export TRAIN_BEAM=4 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=2000 BEAM_UPCAST_MAX=96 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 # pip install -e ".[mlperf]" -export LOGMLPERF=1 +export LOGMLPERF=${LOGMLPERF:-1} export SEED=$RANDOM DATETIME=$(date "+%m%d%H%M") diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/README.md b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/README.md new file mode 100644 index 0000000000..ce1ac9b9a3 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/README.md @@ -0,0 +1,38 @@ +# 1. Problem + +This problem uses RetinaNet for SSD. + +## Requirements + +Install tinygrad and mlperf-logging (uncomment mlperf from setup.py) from branch mlperf_training_v5.0. +``` +git clone https://github.com/tinygrad/tinygrad.git +python3 -m pip install -e ".[mlperf]" +``` + +Also install the following dependencies: +``` +pip install tqdm numpy pycocotools boto3 pandas torch torchvision +``` + +### tinybox_green +Install the p2p driver per [README](https://github.com/tinygrad/open-gpu-kernel-modules/blob/550.54.15-p2p/README.md) +This is the default on production tinybox green. + +# 2. Directions + +## Steps to download data + +Run the following: +``` +BASEDIR=/raid/datasets/openimages python3 extra/datasets/openimages.py +``` + +## Running + +### tinybox_green + +#### Steps to run benchmark +``` +examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/run_and_time.sh +``` diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_beam.sh new file mode 100755 index 0000000000..6e25bb9671 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_beam.sh @@ -0,0 +1,14 @@ +#!/bin/bash + +export PYTHONPATH="." NV=1 +export MODEL="retinanet" +export DEFAULT_FLOAT="HALF" GPUS=6 BS=96 EVAL_BS=96 +export BASEDIR="/raid/datasets/openimages" + +# export RESET_STEP=0 + +export TRAIN_BEAM=2 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 + +export BENCHMARK=5 DEBUG=2 + +python examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_run.sh new file mode 100755 index 0000000000..7a3ee0dfa2 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/dev_run.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +export PYTHONPATH="." NV=1 +export MODEL="retinanet" +export DEFAULT_FLOAT="HALF" GPUS=6 BS=96 EVAL_BS=96 +export BASEDIR="/raid/datasets/openimages" + +# export RESET_STEP=0 + +export TRAIN_BEAM=2 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 + +export WANDB=1 PARALLEL=0 +export RUNMLPERF=1 + +python examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/run_and_time.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/run_and_time.sh new file mode 100755 index 0000000000..2c6d0d14fe --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_green/run_and_time.sh @@ -0,0 +1,23 @@ +#!/bin/bash + +export PYTHONPATH="." NV=1 +export MODEL="retinanet" +export SUBMISSION_PLATFORM="tinybox_green" +export DEFAULT_FLOAT="HALF" GPUS=6 BS=96 EVAL_BS=96 + +export TRAIN_BEAM=2 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 +export IGNORE_JIT_FIRST_BEAM=1 +export BASEDIR="/raid/datasets/openimages" + +# pip install -e ".[mlperf]" +export LOGMLPERF=1 + +export SEED=$RANDOM +DATETIME=$(date "+%m%d%H%M") +LOGFILE="retinanet_green_${DATETIME}_${SEED}.log" + +# init +BENCHMARK=10 INITMLPERF=1 python3 examples/mlperf/model_train.py | tee $LOGFILE + +# run +PARALLEL=0 RUNMLPERF=1 python3 examples/mlperf/model_train.py | tee -a $LOGFILE diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_beam.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_beam.sh new file mode 100755 index 0000000000..97aa5155eb --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_beam.sh @@ -0,0 +1,14 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="retinanet" +export DEFAULT_FLOAT="HALF" GPUS=6 BS=96 EVAL_BS=96 +export BASEDIR="/raid/datasets/openimages" + +# export RESET_STEP=0 + +export TRAIN_BEAM=2 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 + +export BENCHMARK=5 DEBUG=2 + +python examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_run.sh b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_run.sh new file mode 100755 index 0000000000..5fb4d109fd --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/benchmarks/retinanet/implementations/tinybox_red/dev_run.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +export PYTHONPATH="." AMD=1 +export MODEL="retinanet" +export DEFAULT_FLOAT="HALF" GPUS=6 BS=96 EVAL_BS=96 +export BASEDIR="/raid/datasets/openimages" + +# export RESET_STEP=0 + +export TRAIN_BEAM=2 IGNORE_JIT_FIRST_BEAM=1 BEAM_UOPS_MAX=1500 BEAM_UPCAST_MAX=64 BEAM_LOCAL_MAX=1024 BEAM_MIN_PROGRESS=5 BEAM_PADTO=0 + +export WANDB=1 PARALLEL=0 +export RUNMLPERF=1 + +python examples/mlperf/model_train.py diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_8xMI300X.json b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_8xMI300X.json new file mode 100644 index 0000000000..174b064171 --- /dev/null +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_8xMI300X.json @@ -0,0 +1,39 @@ +{ + "submitter": "tinycorp", + "division": "closed", + "status": "Available on-premise", + "system_name": "tinybox 8xMI300X", + "number_of_nodes": "1", + "host_processors_per_node": "2", + "host_processor_model_name": "AMD EPYC 9354 32-Core Processor", + "host_processor_core_count": "32", + "host_processor_vcpu_count": "64", + "host_processor_frequency": "", + "host_processor_caches": "", + "host_processor_interconnect": "", + "host_memory_capacity": "2304GB", + "host_storage_type": "NVMe SSD", + "host_storage_capacity": "3x 4TB raid array", + "host_networking": "", + "host_networking_topology": "", + "host_memory_configuration": "24x 96GB DDR5", + "accelerators_per_node": "8", + "accelerator_model_name": "AMD Instinct MI300X", + "accelerator_host_interconnect": "PCIe 5.0 x16", + "accelerator_frequency": "", + "accelerator_on-chip_memories": "", + "accelerator_memory_configuration": "HBM3", + "accelerator_memory_capacity": "192GB", + "accelerator_interconnect": "", + "accelerator_interconnect_topology": "", + "cooling": "air", + "hw_notes": "", + "framework": "tinygrad, branch mlperf_training_v5.0", + "other_software_stack": { + "python": "3.10.16", + "ROCm": "3.0.0+94441cb" + }, + "operating_system": "Ubuntu 24.04.1 LTS", + "sw_notes": "" + } + \ No newline at end of file diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_green.json b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_green.json index bb1ebba98c..eca528fb40 100644 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_green.json +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_green.json @@ -28,7 +28,7 @@ "accelerator_interconnect_topology": "", "cooling": "air", "hw_notes": "", - "framework": "tinygrad, commit b5546912e24e0a864b35924da4efa5d71cfe368b", + "framework": "tinygrad, branch mlperf_training_v5.0", "other_software_stack": { "python": "3.10.12", "CUDA": "12.4" diff --git a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_red.json b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_red.json index 6db104a7db..8031c6c78b 100644 --- a/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_red.json +++ b/tinygrad_repo/examples/mlperf/training_submission_v5.0/tinycorp/systems/tinybox_red.json @@ -28,10 +28,9 @@ "accelerator_interconnect_topology": "", "cooling": "air", "hw_notes": "", - "framework": "tinygrad, commit b5546912e24e0a864b35924da4efa5d71cfe368b", + "framework": "tinygrad, branch mlperf_training_v5.0", "other_software_stack": { - "python": "3.10.12", - "ROCm": "6.1.3" + "python": "3.10.12" }, "operating_system": "Ubuntu 22.04.4", "sw_notes": "" diff --git a/tinygrad_repo/examples/mnist_gan.py b/tinygrad_repo/examples/mnist_gan.py index 75f39a42ae..8e47942adf 100644 --- a/tinygrad_repo/examples/mnist_gan.py +++ b/tinygrad_repo/examples/mnist_gan.py @@ -16,9 +16,9 @@ class LinearGen: self.l4 = Tensor.scaled_uniform(1024, 784) def forward(self, x): - x = x.dot(self.l1).leakyrelu(0.2) - x = x.dot(self.l2).leakyrelu(0.2) - x = x.dot(self.l3).leakyrelu(0.2) + x = x.dot(self.l1).leaky_relu(0.2) + x = x.dot(self.l2).leaky_relu(0.2) + x = x.dot(self.l3).leaky_relu(0.2) x = x.dot(self.l4).tanh() return x @@ -31,9 +31,9 @@ class LinearDisc: def forward(self, x): # balance the discriminator inputs with const bias (.add(1)) - x = x.dot(self.l1).add(1).leakyrelu(0.2).dropout(0.3) - x = x.dot(self.l2).leakyrelu(0.2).dropout(0.3) - x = x.dot(self.l3).leakyrelu(0.2).dropout(0.3) + x = x.dot(self.l1).add(1).leaky_relu(0.2).dropout(0.3) + x = x.dot(self.l2).leaky_relu(0.2).dropout(0.3) + x = x.dot(self.l3).leaky_relu(0.2).dropout(0.3) x = x.dot(self.l4).log_softmax() return x diff --git a/tinygrad_repo/examples/olmoe.py b/tinygrad_repo/examples/olmoe.py new file mode 100644 index 0000000000..9789cb1cef --- /dev/null +++ b/tinygrad_repo/examples/olmoe.py @@ -0,0 +1,94 @@ +# https://arxiv.org/pdf/2409.02060 +import time +import numpy as np +np.set_printoptions(suppress=True, linewidth=1000) +import functools +from tinygrad import Tensor, nn, Device, GlobalCounters +from tinygrad.helpers import Timing, getenv +from extra.models.llama import Transformer, convert_from_huggingface + +class MixtureFeedForward: + def __init__(self, num_experts:int, activated_experts:int, dim:int, hidden_dim:int, linear=nn.Linear): + self.activated_experts = activated_experts + self.gate = nn.Linear(dim, num_experts, bias=False) + self.up_proj = Tensor.zeros(num_experts, hidden_dim, dim, dtype='bfloat16') + self.down_proj = Tensor.zeros(num_experts, dim, hidden_dim, dtype='bfloat16') + self.gate_proj = Tensor.zeros(num_experts, hidden_dim, dim, dtype='bfloat16') + def __call__(self, x:Tensor) -> Tensor: + assert x.shape[0] == 1, "only BS=1" + assert x.shape[1] == 1, "only length=1" + g = self.gate(x).float().softmax(-1) + + g = g.squeeze() # (BS, length, num_experts) -> (num_experts,) + probs, sel = g.topk(self.activated_experts) + + # run MoE + x_up_gate = x.dot(self.gate_proj[sel].permute(0,2,1)).silu() * x.dot(self.up_proj[sel].permute(0,2,1)) + x_down = x_up_gate.dot(self.down_proj[sel].permute(0,2,1)) + return (x_down.float() * probs.reshape(self.activated_experts, 1, 1)).sum(axis=0) + +# model is bf16, 1.3B active, 6.9B total +# M3 Max is 400 GB/s, so 400/2.6 = ~154 tok/s + +def fetch_weights() -> dict[str, Tensor]: + # TODO: make this lazy so the 3 fetches can happen in parallel + m1 = Tensor.from_url("https://huggingface.co/allenai/OLMoE-1B-7B-0924/resolve/main/model-00001-of-00003.safetensors").to(Device.DEFAULT) + m2 = Tensor.from_url("https://huggingface.co/allenai/OLMoE-1B-7B-0924/resolve/main/model-00002-of-00003.safetensors").to(Device.DEFAULT) + m3 = Tensor.from_url("https://huggingface.co/allenai/OLMoE-1B-7B-0924/resolve/main/model-00003-of-00003.safetensors").to(Device.DEFAULT) + return {**nn.state.safe_load(m1), **nn.state.safe_load(m2), **nn.state.safe_load(m3)} + +if __name__ == "__main__": + if getenv("TORCH"): + from transformers import OlmoeForCausalLM, AutoTokenizer + model = OlmoeForCausalLM.from_pretrained("allenai/OLMoE-1B-7B-0924") + tokenizer = AutoTokenizer.from_pretrained("allenai/OLMoE-1B-7B-0924") + inputs = tokenizer("Hello", return_tensors="pt") + generate_ids = model.generate(inputs.input_ids, max_length=30) + out = tokenizer.batch_decode(generate_ids, skip_special_tokens=True, clean_up_tokenization_spaces=False)[0] + print(out) + exit(0) + + with Timing("create model: "): + model = Transformer(n_layers=16, dim=2048, hidden_dim=1024, n_heads=16, norm_eps=1e-5, qk_norm=1e-5, max_context=1024, + vocab_size=50304, feed_forward=functools.partial(MixtureFeedForward, 64, 8)) + model_state_dict = nn.state.get_state_dict(model) + del model_state_dict['freqs_cis'] + + with Timing("load weights to GPU: "): + nhf_state = convert_from_huggingface(fetch_weights(), 16, 16, 16) + # NOTE: i'm not sure this actually needs float32, it may just change the type of things downstream from it. but doesn't match torch w/o this + for needs_float32 in ['tok_embeddings.weight']: nhf_state[needs_float32] = nhf_state[needs_float32].float() + print(f"ram used: {GlobalCounters.mem_used/1e9:.2f} GB") + + with Timing("unpack weights: "): + nn.state.load_state_dict(model, nhf_state, verbose=False, strict=False, consume=True, realize=False) + assert len(nhf_state) == 0 + Tensor.realize(*list(nn.state.get_state_dict(model).values())) + print(f"ram used: {GlobalCounters.mem_used/1e9:.2f} GB") + + count = 30 + temperature = 0 + + with Timing("load tokenizer: "): + from transformers import AutoTokenizer + tokenizer = AutoTokenizer.from_pretrained("allenai/OLMoE-1B-7B-0924") + + toks = [12092] + start_pos = 0 + timings = [] + for i in range(count): + GlobalCounters.reset() + st = time.perf_counter() + tok = model(Tensor([toks[start_pos:]]), start_pos, temperature).item() + timings.append(time.perf_counter()-st) + toks.append(tok) + start_pos += 1 + print(toks) + print(tokenizer.decode(toks)) + print(f"fastest token {min(timings)*1e3:.2f} ms, {1/min(timings):.1f} tok/s") + + if temperature == 0: + # Hello, I am a newbie to this forum and I am trying to get a better understanding of the different types of data that can be stored in a + assert toks == [12092, 13, 309, 717, 247, 747, 17782, 281, 436, 12209, 285, 309, 717, 2820, 281, 755, + 247, 1805, 4685, 273, 253, 1027, 3510, 273, 941, 326, 476, 320, 7141, 275, 247], "BAD OUTPUT!" + diff --git a/tinygrad_repo/examples/openpilot/compile3.py b/tinygrad_repo/examples/openpilot/compile3.py index 1aaef6db3c..476d407250 100644 --- a/tinygrad_repo/examples/openpilot/compile3.py +++ b/tinygrad_repo/examples/openpilot/compile3.py @@ -12,24 +12,20 @@ from tinygrad.engine.realize import CompiledRunner import onnx from onnx.helper import tensor_dtype_to_np_dtype -from extra.onnx import get_run_onnx # TODO: port to main tinygrad +from tinygrad.frontend.onnx import OnnxRunner OPENPILOT_MODEL = sys.argv[1] if len(sys.argv) > 1 else "https://github.com/commaai/openpilot/raw/v0.9.7/selfdrive/modeld/models/supercombo.onnx" OUTPUT = sys.argv[2] if len(sys.argv) > 2 else "/tmp/openpilot.pkl" def compile(onnx_file): onnx_model = onnx.load(onnx_file) - Tensor.no_grad = True - Tensor.training = False - - run_onnx = get_run_onnx(onnx_model) + run_onnx = OnnxRunner(onnx_model) print("loaded model") input_shapes = {inp.name:tuple(x.dim_value for x in inp.type.tensor_type.shape.dim) for inp in onnx_model.graph.input} input_types = {inp.name: tensor_dtype_to_np_dtype(inp.type.tensor_type.elem_type) for inp in onnx_model.graph.input} # Float inputs and outputs to tinyjits for openpilot are always float32 input_types = {k:(np.float32 if v==np.float16 else v) for k,v in input_types.items()} - input_types = {k:np.uint8 if 'img' in k else v for k,v in input_types.items()} Tensor.manual_seed(100) new_inputs = {k:Tensor.randn(*shp, dtype=_from_np_dtype(input_types[k])).mul(8).realize() for k,shp in sorted(input_shapes.items())} new_inputs_numpy = {k:v.numpy() for k,v in new_inputs.items()} @@ -103,26 +99,37 @@ def test_vs_compile(run, new_inputs, test_val=None): np.testing.assert_raises(AssertionError, np.testing.assert_array_equal, val, changed_val) return val -def test_vs_onnx(new_inputs, test_val, onnx_file): +def test_vs_onnx(new_inputs, test_val, onnx_file, ort=False): new_inputs_numpy = {k:v.numpy() for k,v in new_inputs.items()} onnx_model = onnx.load(onnx_file) - if getenv("ORT"): + timings = [] + if ort: # test with onnxruntime import onnxruntime as ort onnx_session = ort.InferenceSession(onnx_file) - onnx_output = onnx_session.run([onnx_model.graph.output[0].name], {k:v.astype(np.float16) for k,v in new_inputs_numpy.items()}) + for _ in range(1 if test_val is not None else 5): + st = time.perf_counter() + onnx_output = onnx_session.run([onnx_model.graph.output[0].name], {k:v.astype(np.float16) for k,v in new_inputs_numpy.items()}) + timings.append(time.perf_counter() - st) new_torch_out = onnx_output[0] - print("got ort outputs") else: # test with torch - from test.models.test_onnx import run_onnx_torch - # NOTE: we have to correct the order here - new_torch_out = run_onnx_torch(onnx_model, {k.name:new_inputs_numpy[k.name] for k in onnx_model.graph.input}).numpy() - print("got torch outputs") - - np.testing.assert_allclose(new_torch_out.reshape(test_val.shape), test_val, atol=1e-4, rtol=1e-2) - print("test vs onnx passed") + import torch + from onnx2torch import convert + inputs = {k.name:new_inputs_numpy[k.name] for k in onnx_model.graph.input} + torch_model = convert(onnx_model).float() + with torch.no_grad(): + for _ in range(1 if test_val is not None else 5): + st = time.perf_counter() + torch_out = torch_model(*[torch.tensor(x) for x in inputs.values()]) + timings.append(time.perf_counter() - st) + new_torch_out = torch_out.numpy() + + if test_val is not None: + np.testing.assert_allclose(new_torch_out.reshape(test_val.shape), test_val, atol=1e-4, rtol=1e-2) + print("test vs onnx passed") + return timings if __name__ == "__main__": onnx_file = fetch(OPENPILOT_MODEL) @@ -136,4 +143,12 @@ if __name__ == "__main__": sorted(zip(pickle_loaded.captured.expected_names, pickle_loaded.captured.expected_st_vars_dtype_device))} test_val = test_vs_compile(pickle_loaded, new_inputs, test_val) - if not getenv("FLOAT16"): test_vs_onnx(new_inputs, test_val, onnx_file) + if getenv("BENCHMARK"): + for be in ["torch", "ort"]: + try: + timings = test_vs_onnx(new_inputs, None, onnx_file, be=="ort") + print(f"timing {be}: {min(timings)*1000:.2f} ms") + except Exception as e: + print(f"{be} fail with {e}") + if not getenv("FLOAT16"): test_vs_onnx(new_inputs, test_val, onnx_file, getenv("ORT")) + diff --git a/tinygrad_repo/examples/other_mnist/beautiful_mnist_torch.py b/tinygrad_repo/examples/other_mnist/beautiful_mnist_torch.py index 862e48d6cc..fb3c547aab 100644 --- a/tinygrad_repo/examples/other_mnist/beautiful_mnist_torch.py +++ b/tinygrad_repo/examples/other_mnist/beautiful_mnist_torch.py @@ -1,5 +1,5 @@ -from tinygrad import dtypes -from tinygrad.helpers import trange +from tinygrad import dtypes, getenv, Device +from tinygrad.helpers import trange, colored, DEBUG, temp from tinygrad.nn.datasets import mnist import torch from torch import nn, optim @@ -26,14 +26,20 @@ class Model(nn.Module): return self.lin(torch.flatten(x, 1)) if __name__ == "__main__": - mps_device = torch.device("mps") + if getenv("TINY_BACKEND"): + import tinygrad.frontend.torch + device = torch.device("tiny") + else: + device = torch.device({"METAL":"mps","NV":"cuda"}.get(Device.DEFAULT, "cpu")) + if DEBUG >= 1: print(f"using torch backend {device}") X_train, Y_train, X_test, Y_test = mnist() - X_train = torch.tensor(X_train.float().numpy(), device=mps_device) - Y_train = torch.tensor(Y_train.cast(dtypes.int64).numpy(), device=mps_device) - X_test = torch.tensor(X_test.float().numpy(), device=mps_device) - Y_test = torch.tensor(Y_test.cast(dtypes.int64).numpy(), device=mps_device) + X_train = torch.tensor(X_train.float().numpy(), device=device) + Y_train = torch.tensor(Y_train.cast(dtypes.int64).numpy(), device=device) + X_test = torch.tensor(X_test.float().numpy(), device=device) + Y_test = torch.tensor(Y_test.cast(dtypes.int64).numpy(), device=device) - model = Model().to(mps_device) + if getenv("TORCHVIZ"): torch.cuda.memory._record_memory_history() + model = Model().to(device) optimizer = optim.Adam(model.parameters(), 1e-3) loss_fn = nn.CrossEntropyLoss() @@ -48,8 +54,16 @@ if __name__ == "__main__": return loss test_acc = float('nan') - for i in (t:=trange(70)): + for i in (t:=trange(getenv("STEPS", 70))): samples = torch.randint(0, X_train.shape[0], (512,)) # putting this in JIT didn't work well loss = step(samples) if i%10 == 9: test_acc = ((model(X_test).argmax(axis=-1) == Y_test).sum() * 100 / X_test.shape[0]).item() t.set_description(f"loss: {loss.item():6.2f} test_accuracy: {test_acc:5.2f}%") + + # verify eval acc + if target := getenv("TARGET_EVAL_ACC_PCT", 0.0): + if test_acc >= target and test_acc != 100.0: print(colored(f"{test_acc=} >= {target}", "green")) + else: raise ValueError(colored(f"{test_acc=} < {target}", "red")) + if getenv("TORCHVIZ"): + torch.cuda.memory._dump_snapshot(fp:=temp("torchviz.pkl", append_user=True)) + print(f"saved torch memory snapshot to {fp}, view in https://pytorch.org/memory_viz") diff --git a/tinygrad_repo/examples/qwq.py b/tinygrad_repo/examples/qwq.py index 7c71fec049..baa09c5cb3 100644 --- a/tinygrad_repo/examples/qwq.py +++ b/tinygrad_repo/examples/qwq.py @@ -44,7 +44,7 @@ def load_model(model_path:Path, model_params:Dict[str, Union[int, float]]) -> Tr model.layers = updated_layers # load weights - weights = fix_bf16(convert_from_huggingface(load(str(model_path / "model.safetensors.index.json")), model, model_params["n_heads"], model_params["n_kv_heads"], permute_layers=False)) + weights = fix_bf16(convert_from_huggingface(load(str(model_path / "model.safetensors.index.json")), model_params["n_layers"], model_params["n_heads"], model_params["n_kv_heads"], permute_layers=False)) # replace weights in model load_state_dict(model, weights, strict=False, consume=True) diff --git a/tinygrad_repo/examples/sdv2.py b/tinygrad_repo/examples/sdv2.py index a3f4d30bca..89af31a8a8 100644 --- a/tinygrad_repo/examples/sdv2.py +++ b/tinygrad_repo/examples/sdv2.py @@ -5,6 +5,7 @@ from examples.stable_diffusion import AutoencoderKL, get_alphas_cumprod from examples.sdxl import DPMPP2MSampler, append_dims, LegacyDDPMDiscretization from extra.models.unet import UNetModel from extra.models.clip import FrozenOpenClipEmbedder +from extra.bench_log import BenchEvent, WallTimeEvent from typing import Dict import argparse, tempfile, os @@ -117,12 +118,14 @@ if __name__ == "__main__": if not weights_fn: weights_url = args.weights_url if args.weights_url else default_weights_url weights_fn = fetch(weights_url, os.path.basename(str(weights_url))) - load_state_dict(model, safe_load(weights_fn), strict=False) - if args.fp16: - for k,v in get_state_dict(model).items(): - if k.startswith("model"): - v.replace(v.cast(dtypes.float16).realize()) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + load_state_dict(model, safe_load(weights_fn), strict=False) + + if args.fp16: + for k,v in get_state_dict(model).items(): + if k.startswith("model"): + v.replace(v.cast(dtypes.float16).realize()) c = { "crossattn": model.cond_stage_model(args.prompt) } uc = { "crossattn": model.cond_stage_model("") } diff --git a/tinygrad_repo/examples/sdxl.py b/tinygrad_repo/examples/sdxl.py index 19a6ef7d8c..0b7e13cc82 100644 --- a/tinygrad_repo/examples/sdxl.py +++ b/tinygrad_repo/examples/sdxl.py @@ -3,12 +3,13 @@ # Stability-AI/generative-models | MIT | https://github.com/Stability-AI/generative-models/blob/fbdc58cab9f4ee2be7a5e1f2e2787ecd9311942f/LICENSE-CODE # mlfoundations/open_clip | MIT | https://github.com/mlfoundations/open_clip/blob/58e4e39aaabc6040839b0d2a7e8bf20979e4558a/LICENSE -from tinygrad import Tensor, TinyJit, dtypes +from tinygrad import Tensor, TinyJit, dtypes, GlobalCounters from tinygrad.nn import Conv2d, GroupNorm -from tinygrad.nn.state import safe_load, load_state_dict -from tinygrad.helpers import fetch, trange, colored, Timing, GlobalCounters +from tinygrad.nn.state import safe_load, load_state_dict, get_state_dict +from tinygrad.helpers import fetch, trange, colored, Timing from extra.models.clip import Embedder, FrozenClosedClipEmbedder, FrozenOpenClipEmbedder from extra.models.unet import UNetModel, Upsample, Downsample, timestep_embedding +from extra.bench_log import BenchEvent, WallTimeEvent from examples.stable_diffusion import ResnetBlock, Mid import numpy as np @@ -345,18 +346,19 @@ class DPMPP2MSampler: old_denoised = None for i in trange(num_sigmas - 1): with Timing("step in ", enabled=timing, on_exit=lambda _: f", using {GlobalCounters.mem_used/1e9:.2f} GB"): - x, old_denoised = self.sampler_step( - old_denoised=old_denoised, - prev_sigma=(None if i==0 else sigmas[i-1].expand(x.shape[0])), - sigma=sigmas[i].expand(x.shape[0]), - next_sigma=sigmas[i+1].expand(x.shape[0]), - denoiser=denoiser, - x=x, - c=c, - uc=uc, - ) - x.realize() - old_denoised.realize() + GlobalCounters.reset() + with WallTimeEvent(BenchEvent.STEP): + x, old_denoised = self.sampler_step( + old_denoised=old_denoised, + prev_sigma=(None if i==0 else sigmas[i-1].expand(x.shape[0])), + sigma=sigmas[i].expand(x.shape[0]), + next_sigma=sigmas[i+1].expand(x.shape[0]), + denoiser=denoiser, + x=x, + c=c, + uc=uc, + ) + x.realize(old_denoised) return x @@ -384,7 +386,13 @@ if __name__ == "__main__": default_weight_url = 'https://huggingface.co/stabilityai/stable-diffusion-xl-base-1.0/resolve/main/sd_xl_base_1.0.safetensors' weights = args.weights if args.weights else fetch(default_weight_url, 'sd_xl_base_1.0.safetensors') - load_state_dict(model, safe_load(weights), strict=False) + loaded_weights = load_state_dict(model, safe_load(weights), strict=False, verbose=False, realize=False) + + start_mem_used = GlobalCounters.mem_used + with Timing("loaded weights in ", lambda et_ns: f", {(B:=(GlobalCounters.mem_used-start_mem_used))/1e9:.2f} GB loaded at {B/et_ns:.2f} GB/s"): + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + Tensor.realize(*loaded_weights) + del loaded_weights N = 1 C = 4 @@ -395,8 +403,7 @@ if __name__ == "__main__": c, uc = model.create_conditioning([args.prompt], args.width, args.height) del model.conditioner - for v in c .values(): v.realize() - for v in uc.values(): v.realize() + Tensor.realize(*c.values(), *uc.values()) print("created batch") # https://github.com/Stability-AI/generative-models/blob/fbdc58cab9f4ee2be7a5e1f2e2787ecd9311942f/sgm/inference/helpers.py#L101 diff --git a/tinygrad_repo/examples/self_tokenize.py b/tinygrad_repo/examples/self_tokenize.py index 372f1ac5a8..b66002b4bf 100644 --- a/tinygrad_repo/examples/self_tokenize.py +++ b/tinygrad_repo/examples/self_tokenize.py @@ -1,4 +1,4 @@ -import os, pathlib +import os, pathlib, argparse from examples.llama3 import Tokenizer from tabulate import tabulate from tinygrad import fetch @@ -15,10 +15,19 @@ def read_code(base_path): if 'tinygrad/runtime/autogen' in path.replace('\\', '/'): continue fullpath = os.path.join(path, name) code = pathlib.Path(fullpath).read_text() - ret += [(fullpath.split("tinygrad/", 1)[1], code)] + ret.append(("### " + fullpath.split("tinygrad/", 1)[1], code)) return ret +def write_code_to_file(filename, code_list): + """Writes the combined code to a specified file.""" + with open(filename, 'w') as f: + f.write('\n'.join(flatten(code_list))) + if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Analyze and optionally save tinygrad code.") + parser.add_argument("--output", help="Output file to write the combined code to.") + args = parser.parse_args() + ret = read_code(".") table = [] @@ -33,3 +42,7 @@ if __name__ == "__main__": encoded = tokenizer.encode(code_str) print(f"code has {len(encoded)} tokens") + + if args.output: + write_code_to_file(args.output, ret) + print(f"Combined code written to {args.output}") \ No newline at end of file diff --git a/tinygrad_repo/examples/so_vits_svc.py b/tinygrad_repo/examples/so_vits_svc.py index 00c07e9f5a..95e90fa696 100644 --- a/tinygrad_repo/examples/so_vits_svc.py +++ b/tinygrad_repo/examples/so_vits_svc.py @@ -437,14 +437,14 @@ class Generator: x = self.conv_pre(x) if g is not None: x = x + self.cond(g) for i in range(self.num_upsamples): - x, xs = self.ups[i](x.leakyrelu(LRELU_SLOPE)), None + x, xs = self.ups[i](x.leaky_relu(LRELU_SLOPE)), None x_source = self.noise_convs[i](har_source) x = x + x_source for j in range(self.num_kernels): if xs is None: xs = self.resblocks[i * self.num_kernels + j].forward(x) else: xs += self.resblocks[i * self.num_kernels + j].forward(x) x = xs / self.num_kernels - return self.conv_post(x.leakyrelu()).tanh() + return self.conv_post(x.leaky_relu()).tanh() # **** helpers **** @@ -504,7 +504,7 @@ def load_checkpoint_enc(checkpoint_path, model: ContentVec, optimizer=None, skip obj, v = getattr(parent, "weight"), weight_norm(weight_v, weight_g, 0) weight_g, weight_v, parent, skip = None, None, None, False if not skip and obj.shape == v.shape: - if "feature_extractor" in key and (isinstance(parent, nn.GroupNorm) or isinstance(parent, nn.LayerNorm)): # cast + if "feature_extractor" in key and (isinstance(parent, (nn.GroupNorm, nn.LayerNorm))): # cast obj.assign(v.to(obj.device).float()) else: obj.assign(v.to(obj.device)) diff --git a/tinygrad_repo/examples/stable_diffusion.py b/tinygrad_repo/examples/stable_diffusion.py index be4305771d..e47d6bf96b 100644 --- a/tinygrad_repo/examples/stable_diffusion.py +++ b/tinygrad_repo/examples/stable_diffusion.py @@ -14,6 +14,7 @@ from tinygrad.nn import Conv2d, GroupNorm from tinygrad.nn.state import torch_load, load_state_dict, get_state_dict from extra.models.clip import Closed, Tokenizer from extra.models.unet import UNetModel +from extra.bench_log import BenchEvent, WallTimeEvent class AttnBlock: def __init__(self, in_channels): @@ -232,12 +233,13 @@ if __name__ == "__main__": model = StableDiffusion() # load in weights - load_state_dict(model, torch_load(fetch('https://huggingface.co/CompVis/stable-diffusion-v-1-4-original/resolve/main/sd-v1-4.ckpt', 'sd-v1-4.ckpt'))['state_dict'], strict=False) + with WallTimeEvent(BenchEvent.LOAD_WEIGHTS): + load_state_dict(model, torch_load(fetch('https://huggingface.co/CompVis/stable-diffusion-v-1-4-original/resolve/main/sd-v1-4.ckpt', 'sd-v1-4.ckpt'))['state_dict'], strict=False) - if args.fp16: - for k,v in get_state_dict(model).items(): - if k.startswith("model"): - v.replace(v.cast(dtypes.float16).realize()) + if args.fp16: + for k,v in get_state_dict(model).items(): + if k.startswith("model"): + v.replace(v.cast(dtypes.float16).realize()) # run through CLIP to get context tokenizer = Tokenizer.ClipTokenizer() @@ -270,9 +272,10 @@ if __name__ == "__main__": GlobalCounters.reset() t.set_description("%3d %3d" % (index, timestep)) with Timing("step in ", enabled=args.timing, on_exit=lambda _: f", using {GlobalCounters.mem_used/1e9:.2f} GB"): - tid = Tensor([index]) - latent = run(model, unconditional_context, context, latent, Tensor([timestep]), alphas[tid], alphas_prev[tid], Tensor([args.guidance])) - if args.timing: Device[Device.DEFAULT].synchronize() + with WallTimeEvent(BenchEvent.STEP): + tid = Tensor([index]) + latent = run(model, unconditional_context, context, latent, Tensor([timestep]), alphas[tid], alphas_prev[tid], Tensor([args.guidance])) + if args.timing: Device[Device.DEFAULT].synchronize() del run # upsample latent space to image with autoencoder diff --git a/tinygrad_repo/examples/stunning_mnist.py b/tinygrad_repo/examples/stunning_mnist.py index 6e9e4dc645..73144869fe 100644 --- a/tinygrad_repo/examples/stunning_mnist.py +++ b/tinygrad_repo/examples/stunning_mnist.py @@ -5,10 +5,13 @@ # - symbolic removal from examples.beautiful_mnist import Model -from tinygrad import Tensor, nn, getenv, GlobalCounters +from tinygrad import Tensor, nn, getenv, GlobalCounters, Variable from tinygrad.nn.datasets import mnist from tinygrad.helpers import trange, DEBUG +# STEPS=70 python3 examples/stunning_mnist.py +# NOTE: it's broken with STACK=1, why? + if __name__ == "__main__": X_train, Y_train, X_test, Y_test = mnist() print("*** got data") @@ -24,19 +27,21 @@ if __name__ == "__main__": print("*** got samples") with Tensor.train(): - # TODO: this shouldn't be a for loop. something like: (contract is still up in the air) """ i = UOp.range(samples.shape[0]) # TODO: fix range function on UOp losses = model(X_samp[i]).sparse_categorical_crossentropy(Y_samp[i]).backward().contract(i) opt.schedule_steps(i) """ + # TODO: this shouldn't be a for loop. something like: (contract is still up in the air) + vi = Variable('i', 0, samples.shape[0]-1) losses = [] for i in range(samples.shape[0]): + vib = vi.bind(i) opt.zero_grad() - losses.append(model(X_samp[i]).sparse_categorical_crossentropy(Y_samp[i]).backward()) + losses.append(model(X_samp[vib]).sparse_categorical_crossentropy(Y_samp[vib]).backward()) opt.schedule_step() # TODO: this stack currently breaks the "generator" aspect of losses. it probably shouldn't - #losses = Tensor.stack(*losses) + if getenv("STACK", 0): losses = Tensor.stack(*losses) print("*** scheduled training") # evaluate the model @@ -49,5 +54,8 @@ if __name__ == "__main__": # only actually do anything at the end if getenv("LOSS", 1): - for i in (t:=trange(len(losses))): t.set_description(f"loss: {losses[i].item():6.2f}") - print(f"test_accuracy: {test_acc.item():5.2f}%") + for i in (t:=trange(len(losses))): + GlobalCounters.reset() + t.set_description(f"loss: {losses[i].item():6.2f}") + if getenv("TEST", 1): + print(f"test_accuracy: {test_acc.item():5.2f}%") diff --git a/tinygrad_repo/examples/test_onnx_imagenet.py b/tinygrad_repo/examples/test_onnx_imagenet.py new file mode 100644 index 0000000000..11f469aebd --- /dev/null +++ b/tinygrad_repo/examples/test_onnx_imagenet.py @@ -0,0 +1,82 @@ +import random, sys +import numpy as np +from extra.datasets.imagenet import get_imagenet_categories, get_val_files, center_crop +from examples.benchmark_onnx import load_onnx_model +from PIL import Image +from tinygrad import Tensor, dtypes, GlobalCounters +from tinygrad.helpers import fetch, getenv + +# works: +# ~70% - https://github.com/onnx/models/raw/refs/heads/main/validated/vision/classification/resnet/model/resnet50-v2-7.onnx +# ~43% - https://github.com/onnx/models/raw/refs/heads/main/Computer_Vision/alexnet_Opset16_torch_hub/alexnet_Opset16.onnx +# ~72% - https://github.com/xamcat/mobcat-samples/raw/refs/heads/master/onnx_runtime/InferencingSample/InferencingSample/mobilenetv2-7.onnx +# ~71% - https://github.com/axinc-ai/onnx-quantization/raw/refs/heads/main/models/mobilenetv2_1.0.opt.onnx +# ~67% - https://github.com/xamcat/mobcat-samples/raw/refs/heads/master/onnx_runtime/InferencingSample/InferencingSample/mobilenetv2-7-quantized.onnx +# broken: +# https://github.com/MTlab/onnx2caffe/raw/refs/heads/master/model/MobileNetV2.onnx +# https://huggingface.co/qualcomm/MobileNet-v2-Quantized/resolve/main/MobileNet-v2-Quantized.onnx +# ~35% - https://github.com/axinc-ai/onnx-quantization/raw/refs/heads/main/models/mobilenev2_quantized.onnx + +# QUANT=1 python3 examples/test_onnx_imagenet.py +# https://github.com/xamcat/mobcat-samples/raw/refs/heads/master/onnx_runtime/InferencingSample/InferencingSample/mobilenetv2-7.onnx +# DONT_REALIZE_EXPAND=1 python3 examples/test_onnx_imagenet.py /tmp/model.quant.onnx +# VIZ=1 DONT_REALIZE_EXPAND=1 python3 examples/benchmark_onnx.py /tmp/model.quant.onnx + +def imagenet_dataloader(cnt=0): + input_mean = Tensor([0.485, 0.456, 0.406]).reshape(1, -1, 1, 1) + input_std = Tensor([0.229, 0.224, 0.225]).reshape(1, -1, 1, 1) + files = get_val_files() + random.shuffle(files) + files = files[:cnt] + cir = get_imagenet_categories() + for fn in files: + img = Image.open(fn) + img = img.convert('RGB') if img.mode != "RGB" else img + img = center_crop(img) + img = np.array(img) + img = Tensor(img).permute(2,0,1).reshape(1,3,224,224) + img = ((img.cast(dtypes.float32)/255.0) - input_mean) / input_std + y = cir[fn.split("/")[-2]] + yield img,y + +if __name__ == "__main__": + fn = sys.argv[1] + if getenv("QUANT"): + from onnxruntime.quantization import quantize_dynamic, quantize_static, QuantFormat, QuantType, CalibrationDataReader + model_fp32 = fetch(fn) + fn = '/tmp/model.quant.onnx' + if getenv("DYNAMIC"): + quantize_dynamic(model_fp32, fn) + else: + class ImagenetReader(CalibrationDataReader): + def __init__(self): + self.iter = imagenet_dataloader(cnt=1000) + def get_next(self) -> dict: + try: + img,y = next(self.iter) + except StopIteration: + return None + return {"input": img.numpy()} + quantize_static(model_fp32, fn, ImagenetReader(), quant_format=QuantFormat.QDQ, per_channel=False, + activation_type=QuantType.QUInt8, weight_type=QuantType.QUInt8, + extra_options={"ActivationSymmetric": False}) + + run_onnx_jit, input_specs = load_onnx_model(fetch(fn)) + t_name, t_spec = list(input_specs.items())[0] + assert t_spec.shape[1:] == (3,224,224), f"shape is {t_spec.shape}" + + hit = 0 + for i,(img,y) in enumerate(imagenet_dataloader(cnt:=getenv("CNT", 100))): + GlobalCounters.reset() + p = run_onnx_jit(**{t_name:img}) + assert p.shape == (1,1000) + t = p.to('cpu').argmax().item() + hit += y==t + print(f"target: {y:3d} pred: {t:3d} acc: {hit/(i+1)*100:.2f}%") + + MS_TARGET = 13.4 + print(f"need {GlobalCounters.global_ops/1e9*(1000/MS_TARGET):.2f} GFLOPS for {MS_TARGET:.2f} ms") + + if cnt >= 2: + import pickle + with open("/tmp/im.pkl", "wb") as f: pickle.dump(run_onnx_jit, f) diff --git a/tinygrad_repo/examples/test_pkl_imagenet.py b/tinygrad_repo/examples/test_pkl_imagenet.py new file mode 100644 index 0000000000..8110abf309 --- /dev/null +++ b/tinygrad_repo/examples/test_pkl_imagenet.py @@ -0,0 +1,19 @@ +import sys, pickle +from tinygrad import GlobalCounters +from tinygrad.helpers import fetch, getenv +from examples.test_onnx_imagenet import imagenet_dataloader + +if __name__ == "__main__": + with open(fetch(sys.argv[1]), "rb") as f: + run_onnx_jit = pickle.load(f) + input_name = run_onnx_jit.captured.expected_names[0] + device = run_onnx_jit.captured.expected_st_vars_dtype_device[0][-1] + print(f"input goes into {input_name=} on {device=}") + hit = 0 + for i,(img,y) in enumerate(imagenet_dataloader(cnt=getenv("CNT", 100))): + GlobalCounters.reset() + p = run_onnx_jit(**{input_name:img.to(device)}) + assert p.shape == (1,1000) + t = p.to('cpu').argmax().item() + hit += y==t + print(f"target: {y:3d} pred: {t:3d} acc: {hit/(i+1)*100:.2f}%") diff --git a/tinygrad_repo/examples/tinychat/assets/cdn.jsdelivr.net/npm/purecss@3.0.0/build/base-min.css b/tinygrad_repo/examples/tinychat/assets/cdn.jsdelivr.net/npm/purecss@3.0.0/build/base-min.css new file mode 100644 index 0000000000..df4fbc0557 --- /dev/null +++ b/tinygrad_repo/examples/tinychat/assets/cdn.jsdelivr.net/npm/purecss@3.0.0/build/base-min.css @@ -0,0 +1,11 @@ +/*! +Pure v3.0.0 +Copyright 2013 Yahoo! +Licensed under the BSD License. +https://github.com/pure-css/pure/blob/master/LICENSE +*/ +/*! +normalize.css v | MIT License | https://necolas.github.io/normalize.css/ +Copyright (c) Nicolas Gallagher and Jonathan Neal +*/ +/*! normalize.css v8.0.1 | MIT License | github.com/necolas/normalize.css */html{line-height:1.15;-webkit-text-size-adjust:100%}body{margin:0}main{display:block}h1{font-size:2em;margin:.67em 0}hr{box-sizing:content-box;height:0;overflow:visible}pre{font-family:monospace,monospace;font-size:1em}a{background-color:transparent}abbr[title]{border-bottom:none;text-decoration:underline;-webkit-text-decoration:underline dotted;text-decoration:underline dotted}b,strong{font-weight:bolder}code,kbd,samp{font-family:monospace,monospace;font-size:1em}small{font-size:80%}sub,sup{font-size:75%;line-height:0;position:relative;vertical-align:baseline}sub{bottom:-.25em}sup{top:-.5em}img{border-style:none}button,input,optgroup,select,textarea{font-family:inherit;font-size:100%;line-height:1.15;margin:0}button,input{overflow:visible}button,select{text-transform:none}[type=button],[type=reset],[type=submit],button{-webkit-appearance:button}[type=button]::-moz-focus-inner,[type=reset]::-moz-focus-inner,[type=submit]::-moz-focus-inner,button::-moz-focus-inner{border-style:none;padding:0}[type=button]:-moz-focusring,[type=reset]:-moz-focusring,[type=submit]:-moz-focusring,button:-moz-focusring{outline:1px dotted ButtonText}fieldset{padding:.35em .75em .625em}legend{box-sizing:border-box;color:inherit;display:table;max-width:100%;padding:0;white-space:normal}progress{vertical-align:baseline}textarea{overflow:auto}[type=checkbox],[type=radio]{box-sizing:border-box;padding:0}[type=number]::-webkit-inner-spin-button,[type=number]::-webkit-outer-spin-button{height:auto}[type=search]{-webkit-appearance:textfield;outline-offset:-2px}[type=search]::-webkit-search-decoration{-webkit-appearance:none}::-webkit-file-upload-button{-webkit-appearance:button;font:inherit}details{display:block}summary{display:list-item}template{display:none}[hidden]{display:none}html{font-family:sans-serif}.hidden,[hidden]{display:none!important}.pure-img{max-width:100%;height:auto;display:block} \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.ttf b/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.ttf new file mode 100644 index 0000000000..bb2a869565 Binary files /dev/null and b/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.ttf differ diff --git a/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.woff2 b/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.woff2 new file mode 100644 index 0000000000..758dd4f607 Binary files /dev/null and b/tinygrad_repo/examples/tinychat/assets/cdnjs.cloudflare.com/ajax/libs/font-awesome/6.5.2/webfonts/fa-solid-900.woff2 differ diff --git a/tinygrad_repo/examples/tinychat/assets/unpkg.com/@marcreichel/alpine-autosize@1.3.x/dist/alpine-autosize.min.js.map b/tinygrad_repo/examples/tinychat/assets/unpkg.com/@marcreichel/alpine-autosize@1.3.x/dist/alpine-autosize.min.js.map new file mode 100644 index 0000000000..c1b0dd4772 --- /dev/null +++ b/tinygrad_repo/examples/tinychat/assets/unpkg.com/@marcreichel/alpine-autosize@1.3.x/dist/alpine-autosize.min.js.map @@ -0,0 +1 @@ +{"version":3,"file":"alpine-autosize.min.js","sources":["../node_modules/autosize/dist/autosize.esm.js","../builds/cdn.js","../src/index.js"],"sourcesContent":["var e=new Map;function t(t){var o=e.get(t);o&&o.destroy()}function o(t){var o=e.get(t);o&&o.update()}var r=null;\"undefined\"==typeof window?((r=function(e){return e}).destroy=function(e){return e},r.update=function(e){return e}):((r=function(t,o){return t&&Array.prototype.forEach.call(t.length?t:[t],function(t){return function(t){if(t&&t.nodeName&&\"TEXTAREA\"===t.nodeName&&!e.has(t)){var o,r=null,n=window.getComputedStyle(t),i=(o=t.value,function(){a({testForHeightReduction:\"\"===o||!t.value.startsWith(o),restoreTextAlign:null}),o=t.value}),l=function(o){t.removeEventListener(\"autosize:destroy\",l),t.removeEventListener(\"autosize:update\",s),t.removeEventListener(\"input\",i),window.removeEventListener(\"resize\",s),Object.keys(o).forEach(function(e){return t.style[e]=o[e]}),e.delete(t)}.bind(t,{height:t.style.height,resize:t.style.resize,textAlign:t.style.textAlign,overflowY:t.style.overflowY,overflowX:t.style.overflowX,wordWrap:t.style.wordWrap});t.addEventListener(\"autosize:destroy\",l),t.addEventListener(\"autosize:update\",s),t.addEventListener(\"input\",i),window.addEventListener(\"resize\",s),t.style.overflowX=\"hidden\",t.style.wordWrap=\"break-word\",e.set(t,{destroy:l,update:s}),s()}function a(e){var o,i,l=e.restoreTextAlign,s=void 0===l?null:l,d=e.testForHeightReduction,u=void 0===d||d,c=n.overflowY;if(0!==t.scrollHeight&&(\"vertical\"===n.resize?t.style.resize=\"none\":\"both\"===n.resize&&(t.style.resize=\"horizontal\"),u&&(o=function(e){for(var t=[];e&&e.parentNode&&e.parentNode instanceof Element;)e.parentNode.scrollTop&&t.push([e.parentNode,e.parentNode.scrollTop]),e=e.parentNode;return function(){return t.forEach(function(e){var t=e[0],o=e[1];t.style.scrollBehavior=\"auto\",t.scrollTop=o,t.style.scrollBehavior=null})}}(t),t.style.height=\"\"),i=\"content-box\"===n.boxSizing?t.scrollHeight-(parseFloat(n.paddingTop)+parseFloat(n.paddingBottom)):t.scrollHeight+parseFloat(n.borderTopWidth)+parseFloat(n.borderBottomWidth),\"none\"!==n.maxHeight&&i>parseFloat(n.maxHeight)?(\"hidden\"===n.overflowY&&(t.style.overflow=\"scroll\"),i=parseFloat(n.maxHeight)):\"hidden\"!==n.overflowY&&(t.style.overflow=\"hidden\"),t.style.height=i+\"px\",s&&(t.style.textAlign=s),o&&o(),r!==i&&(t.dispatchEvent(new Event(\"autosize:resized\",{bubbles:!0})),r=i),c!==n.overflow&&!s)){var v=n.textAlign;\"hidden\"===n.overflow&&(t.style.textAlign=\"start\"===v?\"end\":\"start\"),a({restoreTextAlign:v,testForHeightReduction:!0})}}function s(){a({testForHeightReduction:!0,restoreTextAlign:null})}}(t)}),t}).destroy=function(e){return e&&Array.prototype.forEach.call(e.length?e:[e],t),e},r.update=function(e){return e&&Array.prototype.forEach.call(e.length?e:[e],o),e});var n=r;export default n;\n","import autosize from '../src/index.js';\n\ndocument.addEventListener('alpine:init', () => {\n autosize(window.Alpine);\n});\n","import autosize from \"autosize\";\n\nfunction Autosize(Alpine) {\n Alpine.directive(\"autosize\", (el, {modifiers}, {cleanup}) => {\n autosize(el);\n const attributes = Array.from(el.attributes);\n\n let hasWireModel = false;\n\n for (let {nodeName} of attributes) {\n if (nodeName === \"wire:model\" || nodeName.startsWith(\"wire:model.\")) {\n hasWireModel = true;\n break;\n }\n }\n\n if (!el.hasAttribute(\"wire:ignore\") && hasWireModel) {\n el.setAttribute(\"wire:ignore\", \"\");\n }\n\n const update = () => {\n autosize.update(el);\n };\n\n el.addEventListener(\"autosize\", update);\n\n cleanup(() => {\n autosize.destroy(el);\n el.removeEventListener(\"autosize\", update);\n });\n });\n\n Alpine.magic(\"autosize\", (node) => (el) => {\n const element = el || node;\n element.dispatchEvent(new Event(\"autosize\"));\n });\n}\n\nexport default Autosize;\n"],"names":["e","Map","t","o","get","destroy","update","r","window","Array","prototype","forEach","call","length","nodeName","has","n","getComputedStyle","i","value","a","testForHeightReduction","startsWith","restoreTextAlign","l","removeEventListener","s","Object","keys","style","delete","bind","height","resize","textAlign","overflowY","overflowX","wordWrap","addEventListener","set","d","u","c","scrollHeight","parentNode","Element","scrollTop","push","scrollBehavior","boxSizing","parseFloat","paddingTop","paddingBottom","borderTopWidth","borderBottomWidth","maxHeight","overflow","dispatchEvent","Event","bubbles","v","document","Alpine","directive","el","modifiers","cleanup","autosize","attributes","from","hasWireModel","hasAttribute","setAttribute","magic","node"],"mappings":"2FAAA,IAAIA,EAAE,IAAIC,IAAI,SAASC,EAAEA,GAAG,IAAIC,EAAEH,EAAEI,IAAIF,GAAGC,GAAGA,EAAEE,SAAS,CAAC,SAASF,EAAED,GAAG,IAAIC,EAAEH,EAAEI,IAAIF,GAAGC,GAAGA,EAAEG,QAAQ,CAAC,IAAIC,EAAE,KAAK,oBAAoBC,SAASD,EAAE,SAASP,GAAG,OAAOA,CAAC,GAAGK,QAAQ,SAASL,GAAG,OAAOA,CAAC,EAAEO,EAAED,OAAO,SAASN,GAAG,OAAOA,CAAC,KAAKO,EAAE,SAASL,EAAEC,GAAG,OAAOD,GAAGO,MAAMC,UAAUC,QAAQC,KAAKV,EAAEW,OAAOX,EAAE,CAACA,IAAG,SAASA,GAAG,OAAO,SAASA,GAAG,GAAGA,GAAGA,EAAEY,UAAU,aAAaZ,EAAEY,WAAWd,EAAEe,IAAIb,GAAG,CAAC,IAAIC,EAAEI,EAAE,KAAKS,EAAER,OAAOS,iBAAiBf,GAAGgB,GAAGf,EAAED,EAAEiB,MAAM,WAAWC,EAAE,CAACC,uBAAuB,KAAKlB,IAAID,EAAEiB,MAAMG,WAAWnB,GAAGoB,iBAAiB,OAAOpB,EAAED,EAAEiB,KAAK,GAAGK,EAAE,SAASrB,GAAGD,EAAEuB,oBAAoB,mBAAmBD,GAAGtB,EAAEuB,oBAAoB,kBAAkBC,GAAGxB,EAAEuB,oBAAoB,QAAQP,GAAGV,OAAOiB,oBAAoB,SAASC,GAAGC,OAAOC,KAAKzB,GAAGQ,SAAQ,SAASX,GAAG,OAAOE,EAAE2B,MAAM7B,GAAGG,EAAEH,EAAE,IAAGA,EAAE8B,OAAO5B,EAAE,EAAE6B,KAAK7B,EAAE,CAAC8B,OAAO9B,EAAE2B,MAAMG,OAAOC,OAAO/B,EAAE2B,MAAMI,OAAOC,UAAUhC,EAAE2B,MAAMK,UAAUC,UAAUjC,EAAE2B,MAAMM,UAAUC,UAAUlC,EAAE2B,MAAMO,UAAUC,SAASnC,EAAE2B,MAAMQ,WAAWnC,EAAEoC,iBAAiB,mBAAmBd,GAAGtB,EAAEoC,iBAAiB,kBAAkBZ,GAAGxB,EAAEoC,iBAAiB,QAAQpB,GAAGV,OAAO8B,iBAAiB,SAASZ,GAAGxB,EAAE2B,MAAMO,UAAU,SAASlC,EAAE2B,MAAMQ,SAAS,aAAarC,EAAEuC,IAAIrC,EAAE,CAACG,QAAQmB,EAAElB,OAAOoB,IAAIA,GAAG,CAAC,SAASN,EAAEpB,GAAG,IAAIG,EAAEe,EAAEM,EAAExB,EAAEuB,iBAAiBG,OAAE,IAASF,EAAE,KAAKA,EAAEgB,EAAExC,EAAEqB,uBAAuBoB,OAAE,IAASD,GAAGA,EAAEE,EAAE1B,EAAEmB,UAAU,GAAG,IAAIjC,EAAEyC,eAAe,aAAa3B,EAAEiB,OAAO/B,EAAE2B,MAAMI,OAAO,OAAO,SAASjB,EAAEiB,SAAS/B,EAAE2B,MAAMI,OAAO,cAAcQ,IAAItC,EAAE,SAASH,GAAG,IAAI,IAAIE,EAAE,GAAGF,GAAGA,EAAE4C,YAAY5C,EAAE4C,sBAAsBC,SAAS7C,EAAE4C,WAAWE,WAAW5C,EAAE6C,KAAK,CAAC/C,EAAE4C,WAAW5C,EAAE4C,WAAWE,YAAY9C,EAAEA,EAAE4C,WAAW,OAAO,WAAW,OAAO1C,EAAES,SAAQ,SAASX,GAAG,IAAIE,EAAEF,EAAE,GAAGG,EAAEH,EAAE,GAAGE,EAAE2B,MAAMmB,eAAe,OAAO9C,EAAE4C,UAAU3C,EAAED,EAAE2B,MAAMmB,eAAe,IAAI,GAAE,CAAC,CAA3S,CAA6S9C,GAAGA,EAAE2B,MAAMG,OAAO,IAAId,EAAE,gBAAgBF,EAAEiC,UAAU/C,EAAEyC,cAAcO,WAAWlC,EAAEmC,YAAYD,WAAWlC,EAAEoC,gBAAgBlD,EAAEyC,aAAaO,WAAWlC,EAAEqC,gBAAgBH,WAAWlC,EAAEsC,mBAAmB,SAAStC,EAAEuC,WAAWrC,EAAEgC,WAAWlC,EAAEuC,YAAY,WAAWvC,EAAEmB,YAAYjC,EAAE2B,MAAM2B,SAAS,UAAUtC,EAAEgC,WAAWlC,EAAEuC,YAAY,WAAWvC,EAAEmB,YAAYjC,EAAE2B,MAAM2B,SAAS,UAAUtD,EAAE2B,MAAMG,OAAOd,EAAE,KAAKQ,IAAIxB,EAAE2B,MAAMK,UAAUR,GAAGvB,GAAGA,IAAII,IAAIW,IAAIhB,EAAEuD,cAAc,IAAIC,MAAM,mBAAmB,CAACC,SAAQ,KAAMpD,EAAEW,GAAGwB,IAAI1B,EAAEwC,WAAW9B,GAAG,CAAC,IAAIkC,EAAE5C,EAAEkB,UAAU,WAAWlB,EAAEwC,WAAWtD,EAAE2B,MAAMK,UAAU,UAAU0B,EAAE,MAAM,SAASxC,EAAE,CAACG,iBAAiBqC,EAAEvC,wBAAuB,GAAI,CAAC,CAAC,SAASK,IAAIN,EAAE,CAACC,wBAAuB,EAAGE,iBAAiB,MAAM,CAAC,CAAnmE,CAAqmErB,EAAE,IAAGA,CAAC,GAAGG,QAAQ,SAASL,GAAG,OAAOA,GAAGS,MAAMC,UAAUC,QAAQC,KAAKZ,EAAEa,OAAOb,EAAE,CAACA,GAAGE,GAAGF,CAAC,EAAEO,EAAED,OAAO,SAASN,GAAG,OAAOA,GAAGS,MAAMC,UAAUC,QAAQC,KAAKZ,EAAEa,OAAOb,EAAE,CAACA,GAAGG,GAAGH,CAAC,GAAG,IAAIgB,EAAET,ECErlFsD,SAASvB,iBAAiB,eAAe,KCAzC,IAAkBwB,KDCLtD,OAAOsD,QCATC,UAAU,YAAY,CAACC,GAAKC,cAAaC,cAC5CC,EAASH,GACT,MAAMI,EAAa3D,MAAM4D,KAAKL,EAAGI,YAEjC,IAAIE,GAAe,EAEnB,IAAK,IAAIxD,SAACA,KAAasD,EACnB,GAAiB,eAAbtD,GAA6BA,EAASQ,WAAW,eAAgB,CACjEgD,GAAe,EACf,KACJ,EAGCN,EAAGO,aAAa,gBAAkBD,GACnCN,EAAGQ,aAAa,cAAe,IAGnC,MAAMlE,EAASA,KACX6D,EAAS7D,OAAO0D,EAAG,EAGvBA,EAAG1B,iBAAiB,WAAYhC,GAEhC4D,GAAQ,KACJC,EAAS9D,QAAQ2D,GACjBA,EAAGvC,oBAAoB,WAAYnB,EAAO,GAC5C,IAGNwD,EAAOW,MAAM,YAAaC,GAAUV,KAChBA,GAAMU,GACdjB,cAAc,IAAIC,MAAM,YAAY,GD/BzB"} \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/assets/unpkg.com/alpinejs@3.x.x/dist/cdn.min.js b/tinygrad_repo/examples/tinychat/assets/unpkg.com/alpinejs@3.x.x/dist/cdn.min.js index b050ef14ac..a3be81c277 100644 --- a/tinygrad_repo/examples/tinychat/assets/unpkg.com/alpinejs@3.x.x/dist/cdn.min.js +++ b/tinygrad_repo/examples/tinychat/assets/unpkg.com/alpinejs@3.x.x/dist/cdn.min.js @@ -1,5 +1,5 @@ -(()=>{var nt=!1,it=!1,W=[],ot=-1;function Ut(e){Rn(e)}function Rn(e){W.includes(e)||W.push(e),Mn()}function Wt(e){let t=W.indexOf(e);t!==-1&&t>ot&&W.splice(t,1)}function Mn(){!it&&!nt&&(nt=!0,queueMicrotask(Nn))}function Nn(){nt=!1,it=!0;for(let e=0;ee.effect(t,{scheduler:r=>{st?Ut(r):r()}}),at=e.raw}function ct(e){N=e}function Yt(e){let t=()=>{};return[n=>{let i=N(n);return e._x_effects||(e._x_effects=new Set,e._x_runEffects=()=>{e._x_effects.forEach(o=>o())}),e._x_effects.add(i),t=()=>{i!==void 0&&(e._x_effects.delete(i),$(i))},i},()=>{t()}]}function Se(e,t){let r=!0,n,i=N(()=>{let o=e();JSON.stringify(o),r?n=o:queueMicrotask(()=>{t(o,n),n=o}),r=!1});return()=>$(i)}var Xt=[],Zt=[],Qt=[];function er(e){Qt.push(e)}function te(e,t){typeof t=="function"?(e._x_cleanups||(e._x_cleanups=[]),e._x_cleanups.push(t)):(t=e,Zt.push(t))}function Ae(e){Xt.push(e)}function Oe(e,t,r){e._x_attributeCleanups||(e._x_attributeCleanups={}),e._x_attributeCleanups[t]||(e._x_attributeCleanups[t]=[]),e._x_attributeCleanups[t].push(r)}function lt(e,t){e._x_attributeCleanups&&Object.entries(e._x_attributeCleanups).forEach(([r,n])=>{(t===void 0||t.includes(r))&&(n.forEach(i=>i()),delete e._x_attributeCleanups[r])})}function tr(e){for(e._x_effects?.forEach(Wt);e._x_cleanups?.length;)e._x_cleanups.pop()()}var ut=new MutationObserver(mt),ft=!1;function ue(){ut.observe(document,{subtree:!0,childList:!0,attributes:!0,attributeOldValue:!0}),ft=!0}function dt(){Dn(),ut.disconnect(),ft=!1}var le=[];function Dn(){let e=ut.takeRecords();le.push(()=>e.length>0&&mt(e));let t=le.length;queueMicrotask(()=>{if(le.length===t)for(;le.length>0;)le.shift()()})}function m(e){if(!ft)return e();dt();let t=e();return ue(),t}var pt=!1,ve=[];function rr(){pt=!0}function nr(){pt=!1,mt(ve),ve=[]}function mt(e){if(pt){ve=ve.concat(e);return}let t=new Set,r=new Set,n=new Map,i=new Map;for(let o=0;os.nodeType===1&&t.add(s)),e[o].removedNodes.forEach(s=>s.nodeType===1&&r.add(s))),e[o].type==="attributes")){let s=e[o].target,a=e[o].attributeName,c=e[o].oldValue,l=()=>{n.has(s)||n.set(s,[]),n.get(s).push({name:a,value:s.getAttribute(a)})},u=()=>{i.has(s)||i.set(s,[]),i.get(s).push(a)};s.hasAttribute(a)&&c===null?l():s.hasAttribute(a)?(u(),l()):u()}i.forEach((o,s)=>{lt(s,o)}),n.forEach((o,s)=>{Xt.forEach(a=>a(s,o))});for(let o of r)t.has(o)||Zt.forEach(s=>s(o));t.forEach(o=>{o._x_ignoreSelf=!0,o._x_ignore=!0});for(let o of t)r.has(o)||o.isConnected&&(delete o._x_ignoreSelf,delete o._x_ignore,Qt.forEach(s=>s(o)),o._x_ignore=!0,o._x_ignoreSelf=!0);t.forEach(o=>{delete o._x_ignoreSelf,delete o._x_ignore}),t=null,r=null,n=null,i=null}function Ce(e){return B(F(e))}function D(e,t,r){return e._x_dataStack=[t,...F(r||e)],()=>{e._x_dataStack=e._x_dataStack.filter(n=>n!==t)}}function F(e){return e._x_dataStack?e._x_dataStack:typeof ShadowRoot=="function"&&e instanceof ShadowRoot?F(e.host):e.parentNode?F(e.parentNode):[]}function B(e){return new Proxy({objects:e},Pn)}var Pn={ownKeys({objects:e}){return Array.from(new Set(e.flatMap(t=>Object.keys(t))))},has({objects:e},t){return t==Symbol.unscopables?!1:e.some(r=>Object.prototype.hasOwnProperty.call(r,t)||Reflect.has(r,t))},get({objects:e},t,r){return t=="toJSON"?In:Reflect.get(e.find(n=>Reflect.has(n,t))||{},t,r)},set({objects:e},t,r,n){let i=e.find(s=>Object.prototype.hasOwnProperty.call(s,t))||e[e.length-1],o=Object.getOwnPropertyDescriptor(i,t);return o?.set&&o?.get?o.set.call(n,r)||!0:Reflect.set(i,t,r)}};function In(){return Reflect.ownKeys(this).reduce((t,r)=>(t[r]=Reflect.get(this,r),t),{})}function Te(e){let t=n=>typeof n=="object"&&!Array.isArray(n)&&n!==null,r=(n,i="")=>{Object.entries(Object.getOwnPropertyDescriptors(n)).forEach(([o,{value:s,enumerable:a}])=>{if(a===!1||s===void 0||typeof s=="object"&&s!==null&&s.__v_skip)return;let c=i===""?o:`${i}.${o}`;typeof s=="object"&&s!==null&&s._x_interceptor?n[o]=s.initialize(e,c,o):t(s)&&s!==n&&!(s instanceof Element)&&r(s,c)})};return r(e)}function Re(e,t=()=>{}){let r={initialValue:void 0,_x_interceptor:!0,initialize(n,i,o){return e(this.initialValue,()=>kn(n,i),s=>ht(n,i,s),i,o)}};return t(r),n=>{if(typeof n=="object"&&n!==null&&n._x_interceptor){let i=r.initialize.bind(r);r.initialize=(o,s,a)=>{let c=n.initialize(o,s,a);return r.initialValue=c,i(o,s,a)}}else r.initialValue=n;return r}}function kn(e,t){return t.split(".").reduce((r,n)=>r[n],e)}function ht(e,t,r){if(typeof t=="string"&&(t=t.split(".")),t.length===1)e[t[0]]=r;else{if(t.length===0)throw error;return e[t[0]]||(e[t[0]]={}),ht(e[t[0]],t.slice(1),r)}}var ir={};function y(e,t){ir[e]=t}function fe(e,t){let r=Ln(t);return Object.entries(ir).forEach(([n,i])=>{Object.defineProperty(e,`$${n}`,{get(){return i(t,r)},enumerable:!1})}),e}function Ln(e){let[t,r]=_t(e),n={interceptor:Re,...t};return te(e,r),n}function or(e,t,r,...n){try{return r(...n)}catch(i){re(i,e,t)}}function re(e,t,r=void 0){e=Object.assign(e??{message:"No error message given."},{el:t,expression:r}),console.warn(`Alpine Expression Error: ${e.message} +(()=>{var nt=!1,it=!1,W=[],ot=-1;function Ut(e){Rn(e)}function Rn(e){W.includes(e)||W.push(e),Mn()}function Wt(e){let t=W.indexOf(e);t!==-1&&t>ot&&W.splice(t,1)}function Mn(){!it&&!nt&&(nt=!0,queueMicrotask(Nn))}function Nn(){nt=!1,it=!0;for(let e=0;ee.effect(t,{scheduler:r=>{st?Ut(r):r()}}),at=e.raw}function ct(e){N=e}function Yt(e){let t=()=>{};return[n=>{let i=N(n);return e._x_effects||(e._x_effects=new Set,e._x_runEffects=()=>{e._x_effects.forEach(o=>o())}),e._x_effects.add(i),t=()=>{i!==void 0&&(e._x_effects.delete(i),$(i))},i},()=>{t()}]}function ve(e,t){let r=!0,n,i=N(()=>{let o=e();JSON.stringify(o),r?n=o:queueMicrotask(()=>{t(o,n),n=o}),r=!1});return()=>$(i)}var Xt=[],Zt=[],Qt=[];function er(e){Qt.push(e)}function te(e,t){typeof t=="function"?(e._x_cleanups||(e._x_cleanups=[]),e._x_cleanups.push(t)):(t=e,Zt.push(t))}function Ae(e){Xt.push(e)}function Oe(e,t,r){e._x_attributeCleanups||(e._x_attributeCleanups={}),e._x_attributeCleanups[t]||(e._x_attributeCleanups[t]=[]),e._x_attributeCleanups[t].push(r)}function lt(e,t){e._x_attributeCleanups&&Object.entries(e._x_attributeCleanups).forEach(([r,n])=>{(t===void 0||t.includes(r))&&(n.forEach(i=>i()),delete e._x_attributeCleanups[r])})}function tr(e){for(e._x_effects?.forEach(Wt);e._x_cleanups?.length;)e._x_cleanups.pop()()}var ut=new MutationObserver(mt),ft=!1;function ue(){ut.observe(document,{subtree:!0,childList:!0,attributes:!0,attributeOldValue:!0}),ft=!0}function dt(){kn(),ut.disconnect(),ft=!1}var le=[];function kn(){let e=ut.takeRecords();le.push(()=>e.length>0&&mt(e));let t=le.length;queueMicrotask(()=>{if(le.length===t)for(;le.length>0;)le.shift()()})}function m(e){if(!ft)return e();dt();let t=e();return ue(),t}var pt=!1,Se=[];function rr(){pt=!0}function nr(){pt=!1,mt(Se),Se=[]}function mt(e){if(pt){Se=Se.concat(e);return}let t=[],r=new Set,n=new Map,i=new Map;for(let o=0;o{s.nodeType===1&&s._x_marker&&r.add(s)}),e[o].addedNodes.forEach(s=>{if(s.nodeType===1){if(r.has(s)){r.delete(s);return}s._x_marker||t.push(s)}})),e[o].type==="attributes")){let s=e[o].target,a=e[o].attributeName,c=e[o].oldValue,l=()=>{n.has(s)||n.set(s,[]),n.get(s).push({name:a,value:s.getAttribute(a)})},u=()=>{i.has(s)||i.set(s,[]),i.get(s).push(a)};s.hasAttribute(a)&&c===null?l():s.hasAttribute(a)?(u(),l()):u()}i.forEach((o,s)=>{lt(s,o)}),n.forEach((o,s)=>{Xt.forEach(a=>a(s,o))});for(let o of r)t.some(s=>s.contains(o))||Zt.forEach(s=>s(o));for(let o of t)o.isConnected&&Qt.forEach(s=>s(o));t=null,r=null,n=null,i=null}function Ce(e){return z(B(e))}function k(e,t,r){return e._x_dataStack=[t,...B(r||e)],()=>{e._x_dataStack=e._x_dataStack.filter(n=>n!==t)}}function B(e){return e._x_dataStack?e._x_dataStack:typeof ShadowRoot=="function"&&e instanceof ShadowRoot?B(e.host):e.parentNode?B(e.parentNode):[]}function z(e){return new Proxy({objects:e},Dn)}var Dn={ownKeys({objects:e}){return Array.from(new Set(e.flatMap(t=>Object.keys(t))))},has({objects:e},t){return t==Symbol.unscopables?!1:e.some(r=>Object.prototype.hasOwnProperty.call(r,t)||Reflect.has(r,t))},get({objects:e},t,r){return t=="toJSON"?Pn:Reflect.get(e.find(n=>Reflect.has(n,t))||{},t,r)},set({objects:e},t,r,n){let i=e.find(s=>Object.prototype.hasOwnProperty.call(s,t))||e[e.length-1],o=Object.getOwnPropertyDescriptor(i,t);return o?.set&&o?.get?o.set.call(n,r)||!0:Reflect.set(i,t,r)}};function Pn(){return Reflect.ownKeys(this).reduce((t,r)=>(t[r]=Reflect.get(this,r),t),{})}function Te(e){let t=n=>typeof n=="object"&&!Array.isArray(n)&&n!==null,r=(n,i="")=>{Object.entries(Object.getOwnPropertyDescriptors(n)).forEach(([o,{value:s,enumerable:a}])=>{if(a===!1||s===void 0||typeof s=="object"&&s!==null&&s.__v_skip)return;let c=i===""?o:`${i}.${o}`;typeof s=="object"&&s!==null&&s._x_interceptor?n[o]=s.initialize(e,c,o):t(s)&&s!==n&&!(s instanceof Element)&&r(s,c)})};return r(e)}function Re(e,t=()=>{}){let r={initialValue:void 0,_x_interceptor:!0,initialize(n,i,o){return e(this.initialValue,()=>In(n,i),s=>ht(n,i,s),i,o)}};return t(r),n=>{if(typeof n=="object"&&n!==null&&n._x_interceptor){let i=r.initialize.bind(r);r.initialize=(o,s,a)=>{let c=n.initialize(o,s,a);return r.initialValue=c,i(o,s,a)}}else r.initialValue=n;return r}}function In(e,t){return t.split(".").reduce((r,n)=>r[n],e)}function ht(e,t,r){if(typeof t=="string"&&(t=t.split(".")),t.length===1)e[t[0]]=r;else{if(t.length===0)throw error;return e[t[0]]||(e[t[0]]={}),ht(e[t[0]],t.slice(1),r)}}var ir={};function y(e,t){ir[e]=t}function fe(e,t){let r=Ln(t);return Object.entries(ir).forEach(([n,i])=>{Object.defineProperty(e,`$${n}`,{get(){return i(t,r)},enumerable:!1})}),e}function Ln(e){let[t,r]=_t(e),n={interceptor:Re,...t};return te(e,r),n}function or(e,t,r,...n){try{return r(...n)}catch(i){re(i,e,t)}}function re(e,t,r=void 0){e=Object.assign(e??{message:"No error message given."},{el:t,expression:r}),console.warn(`Alpine Expression Error: ${e.message} ${r?'Expression: "'+r+`" -`:""}`,t),setTimeout(()=>{throw e},0)}var Me=!0;function De(e){let t=Me;Me=!1;let r=e();return Me=t,r}function R(e,t,r={}){let n;return x(e,t)(i=>n=i,r),n}function x(...e){return sr(...e)}var sr=xt;function ar(e){sr=e}function xt(e,t){let r={};fe(r,e);let n=[r,...F(e)],i=typeof t=="function"?$n(n,t):Fn(n,t,e);return or.bind(null,e,t,i)}function $n(e,t){return(r=()=>{},{scope:n={},params:i=[]}={})=>{let o=t.apply(B([n,...e]),i);Ne(r,o)}}var gt={};function jn(e,t){if(gt[e])return gt[e];let r=Object.getPrototypeOf(async function(){}).constructor,n=/^[\n\s]*if.*\(.*\)/.test(e.trim())||/^(let|const)\s/.test(e.trim())?`(async()=>{ ${e} })()`:e,o=(()=>{try{let s=new r(["__self","scope"],`with (scope) { __self.result = ${n} }; __self.finished = true; return __self.result;`);return Object.defineProperty(s,"name",{value:`[Alpine] ${e}`}),s}catch(s){return re(s,t,e),Promise.resolve()}})();return gt[e]=o,o}function Fn(e,t,r){let n=jn(t,r);return(i=()=>{},{scope:o={},params:s=[]}={})=>{n.result=void 0,n.finished=!1;let a=B([o,...e]);if(typeof n=="function"){let c=n(n,a).catch(l=>re(l,r,t));n.finished?(Ne(i,n.result,a,s,r),n.result=void 0):c.then(l=>{Ne(i,l,a,s,r)}).catch(l=>re(l,r,t)).finally(()=>n.result=void 0)}}}function Ne(e,t,r,n,i){if(Me&&typeof t=="function"){let o=t.apply(r,n);o instanceof Promise?o.then(s=>Ne(e,s,r,n)).catch(s=>re(s,i,t)):e(o)}else typeof t=="object"&&t instanceof Promise?t.then(o=>e(o)):e(t)}var wt="x-";function C(e=""){return wt+e}function cr(e){wt=e}var Pe={};function d(e,t){return Pe[e]=t,{before(r){if(!Pe[r]){console.warn(String.raw`Cannot find directive \`${r}\`. \`${e}\` will use the default order of execution`);return}let n=G.indexOf(r);G.splice(n>=0?n:G.indexOf("DEFAULT"),0,e)}}}function lr(e){return Object.keys(Pe).includes(e)}function pe(e,t,r){if(t=Array.from(t),e._x_virtualDirectives){let o=Object.entries(e._x_virtualDirectives).map(([a,c])=>({name:a,value:c})),s=Et(o);o=o.map(a=>s.find(c=>c.name===a.name)?{name:`x-bind:${a.name}`,value:`"${a.value}"`}:a),t=t.concat(o)}let n={};return t.map(dr((o,s)=>n[o]=s)).filter(mr).map(zn(n,r)).sort(Kn).map(o=>Bn(e,o))}function Et(e){return Array.from(e).map(dr()).filter(t=>!mr(t))}var yt=!1,de=new Map,ur=Symbol();function fr(e){yt=!0;let t=Symbol();ur=t,de.set(t,[]);let r=()=>{for(;de.get(t).length;)de.get(t).shift()();de.delete(t)},n=()=>{yt=!1,r()};e(r),n()}function _t(e){let t=[],r=a=>t.push(a),[n,i]=Yt(e);return t.push(i),[{Alpine:z,effect:n,cleanup:r,evaluateLater:x.bind(x,e),evaluate:R.bind(R,e)},()=>t.forEach(a=>a())]}function Bn(e,t){let r=()=>{},n=Pe[t.type]||r,[i,o]=_t(e);Oe(e,t.original,o);let s=()=>{e._x_ignore||e._x_ignoreSelf||(n.inline&&n.inline(e,t,i),n=n.bind(n,e,t,i),yt?de.get(ur).push(n):n())};return s.runCleanups=o,s}var Ie=(e,t)=>({name:r,value:n})=>(r.startsWith(e)&&(r=r.replace(e,t)),{name:r,value:n}),ke=e=>e;function dr(e=()=>{}){return({name:t,value:r})=>{let{name:n,value:i}=pr.reduce((o,s)=>s(o),{name:t,value:r});return n!==t&&e(n,t),{name:n,value:i}}}var pr=[];function ne(e){pr.push(e)}function mr({name:e}){return hr().test(e)}var hr=()=>new RegExp(`^${wt}([^:^.]+)\\b`);function zn(e,t){return({name:r,value:n})=>{let i=r.match(hr()),o=r.match(/:([a-zA-Z0-9\-_:]+)/),s=r.match(/\.[^.\]]+(?=[^\]]*$)/g)||[],a=t||e[r]||r;return{type:i?i[1]:null,value:o?o[1]:null,modifiers:s.map(c=>c.replace(".","")),expression:n,original:a}}}var bt="DEFAULT",G=["ignore","ref","data","id","anchor","bind","init","for","model","modelable","transition","show","if",bt,"teleport"];function Kn(e,t){let r=G.indexOf(e.type)===-1?bt:e.type,n=G.indexOf(t.type)===-1?bt:t.type;return G.indexOf(r)-G.indexOf(n)}function J(e,t,r={}){e.dispatchEvent(new CustomEvent(t,{detail:r,bubbles:!0,composed:!0,cancelable:!0}))}function P(e,t){if(typeof ShadowRoot=="function"&&e instanceof ShadowRoot){Array.from(e.children).forEach(i=>P(i,t));return}let r=!1;if(t(e,()=>r=!0),r)return;let n=e.firstElementChild;for(;n;)P(n,t,!1),n=n.nextElementSibling}function E(e,...t){console.warn(`Alpine Warning: ${e}`,...t)}var _r=!1;function gr(){_r&&E("Alpine has already been initialized on this page. Calling Alpine.start() more than once can cause problems."),_r=!0,document.body||E("Unable to initialize. Trying to load Alpine before `` is available. Did you forget to add `defer` in Alpine's ` + + + + + + + + + + + + + + + + + + + + + +
+
+

tinychat

+
+ +
+ +
+ +
+
+
+
+
+
+ +

+

SEC TO FIRST TOKEN

+
+ +

+

TOKENS/SEC

+
+ +

+

TOKENS

+
+
+
+

Loading:

+ 0% +
+
+
+
+
+ + +
+
+
+ + + diff --git a/tinygrad_repo/examples/tinychat/tinychat-browser/index.js b/tinygrad_repo/examples/tinychat/tinychat-browser/index.js new file mode 100644 index 0000000000..2d84dede2c --- /dev/null +++ b/tinygrad_repo/examples/tinychat/tinychat-browser/index.js @@ -0,0 +1,927 @@ +window.TINYCHAT_ROOT = "/tinychat-browser/"; +const queryParams = new URLSearchParams(window.location.search); +const normalizedParams = Object.fromEntries([...queryParams].map(([key, value]) => [key.toUpperCase(), value.toUpperCase()])); +window.BACKEND = (normalizedParams["BACKEND"] === "WASM") ? "WASM" : "WebGPU"; +const isMobileAgent = /Mobi|Android|iPhone|iPad|iPod/i.test(navigator.userAgent); +const hasTouchScreen = 'ontouchstart' in window || navigator.maxTouchPoints > 0; +window.isMobile = isMobileAgent || hasTouchScreen; +if (window.isMobile) document.documentElement.classList.add('mobile'); // prevent annoying auto-zoom when entering prompt on mobile +// MODEL_BASE_URL is where the weights are hosted, WEBGPU_EXPORT is the JS-wrapped WebGPU code exported from tinygrad +window.PC_MODEL_BASE_URL = "."; +window.PC_WEBGPU_EXPORT = './net.js' +window.PC_MAX_CONTEXT = 1024; +window.MOBILE_MODEL_BASE_URL = "."; +window.MOBILE_WEBGPU_EXPORT = './net.js' +window.MOBILE_MAX_CONTEXT = 1024; + +const tiktokenReady = (async () => { + const { init, get_encoding, Tiktoken, load } = await import('./tiktoken.js'); + window.Tiktoken = Tiktoken; + window.tiktokenInit = init; + window.tiktokenGetEncoding = get_encoding; + window.tiktokenLoad = load; +})(); + +async function getDevice() { + let adapter; + try { + adapter = await navigator.gpu.requestAdapter(); + if (!adapter) { + this.loadingMessage = "Loading WASM (WebGPU not enabled):"; + throw new Error("No WebGPU adapter found"); + } + } catch(error) { + this.loadingMessage = "Loading WASM (WebGPU not enabled):"; + throw error; + } + const requiredLimits = {}; + const maxBufferSize = 322122544; + requiredLimits.maxStorageBufferBindingSize = maxBufferSize; + requiredLimits.maxBufferSize = maxBufferSize; + requiredLimits.maxComputeInvocationsPerWorkgroup = 512; // may need to vary based on what the WEBGPU backend produces + + try { + return await adapter.requestDevice({ requiredLimits }); + } catch(error) { + this.loadingMessage = "Loading WASM (WebGPU error):"; + throw error; + } +}; + +// copied from examples/webgpu/stable_diffusion/index.html +function initDb() { + return new Promise((resolve, reject) => { + let db; + const request = indexedDB.open('tinydb', 1); + request.onerror = (event) => { + console.error('Database error:', event.target.error); + resolve(null); + }; + + request.onsuccess = (event) => { + db = event.target.result; + console.log("Db initialized."); + resolve(db); + }; + + request.onupgradeneeded = (event) => { + db = event.target.result; + if (!db.objectStoreNames.contains('tensors')) { + db.createObjectStore('tensors', { keyPath: 'id' }); + } + }; + }); +} + +// copied from examples/webgpu/stable_diffusion/index.html +function readTensorFromDb(db, id) { + return new Promise((resolve, reject) => { + if (db == null) { + resolve(null); + } + + const transaction = db.transaction(['tensors'], 'readonly'); + const store = transaction.objectStore('tensors'); + const request = store.get(id); + + transaction.onabort = (event) => { + console.log("Transaction error while reading tensor: " + event.target.error); + resolve(null); + }; + + request.onsuccess = (event) => { + const result = event.target.result; + if (result) { + resolve(result); + } else { + resolve(null); + } + }; + + request.onerror = (event) => { + console.error('Tensor retrieve failed: ', event.target.error); + resolve(null); + }; + }); +} + +function getAllKeysFromDb(db) { + return new Promise((resolve, reject) => { + if (db == null) {resolve([]);} + const transaction = db.transaction(['tensors'], 'readonly'); + const store = transaction.objectStore('tensors'); + const request = store.getAllKeys(); + transaction.onabort = (event) => { + console.log("Transaction error while reading IndexedDB keys: " + event.target.error); + resolve([]); + }; + request.onsuccess = function (event) {resolve(event.target.result);}; + request.onerror = (event) => { + console.error('Retrieval of IndexedDB keys failed: ', event.target.error); + resolve([]); + }; + }); +} + +// modified from examples/webgpu/stable_diffusion/index.html +function saveTensorToDb(db, id, tensor) { + return readTensorFromDb(db, id).then((result) => { + if (!result) { + new Promise((resolve, reject) => { + if (db == null) { + resolve(null); + } + + const transaction = db.transaction(['tensors'], 'readwrite'); + const store = transaction.objectStore('tensors'); + const request = store.put({ id: id, content: tensor }); + + transaction.onabort = (event) => { + console.log("Transaction error while saving tensor: " + event.target.error); + resolve(null); + }; + + request.onsuccess = () => { + console.log('Tensor saved successfully.'); + resolve(); + }; + + request.onerror = (event) => { + console.error('Tensor save failed:', event.target.error); + resolve(null); + }; + }); + } else { + return null; + } + }).catch(()=> null); +} + +function deleteTensorFromDb(db, id) { + return new Promise((resolve, reject) => { + if (db == null) { + console.error("Database is not initialized."); + resolve(null); + return; + } + + const transaction = db.transaction(['tensors'], 'readwrite'); + const store = transaction.objectStore('tensors'); + const request = store.delete(id); + + transaction.oncomplete = () => { + console.log(`Tensor with ID '${id}' deleted successfully.`); + resolve(); + }; + + transaction.onerror = (event) => { + console.error("Transaction error while deleting tensor:", event.target.error); + resolve(null); + }; + + request.onerror = (event) => { + console.error('Tensor deletion failed:', event.target.error); + resolve(null); + }; + + request.onsuccess = () => { + console.log(`Delete request for tensor with ID '${id}' succeeded.`); + }; + }); +} + +function makeProgress(total) { + let acc = 0; + const ret = function progress(amount, message) { + if (amount >= 0) { // allow updating message only + acc += amount; + const percentage = total ? Math.trunc((acc / total) * 100) : 0; + document.querySelector('.progress').style.width = `${percentage}%`; + document.getElementById('progress-percentage').textContent = `${percentage}%`; + } + if (message) { + this.loadingMessage = message; + document.getElementById('loading-message').textContent = this.loadingMessage; + } + }.bind(this); + ret.total = total; + return ret; +} + +function sendMessageToWorker(worker, message) { + return new Promise((resolve, reject) => { + const onMessage = (event) => { + resolve(event.data); + worker.removeEventListener('message', onMessage); + worker.removeEventListener('error', onError); + }; + + const onError = (error) => { + reject(error); + worker.removeEventListener('message', onMessage); + worker.removeEventListener('error', onError); + }; + + worker.addEventListener('message', onMessage); + worker.addEventListener('error', onError); + + if (message.header === "token") worker.postMessage(message.data); + else if (message.header === "load_state_dict") { + if (message.data === "done") worker.postMessage(message.data); + else worker.postMessage(message.data, message.data.map(file => file.bytes.buffer)); + } + else if (message.header === "init") worker.postMessage("init"); + }); +} + +async function load_state_dict (data, device, progress) { + let state_dict = data.metadata.state_dict; + let completed = 0; + + // modified from examples/webgpu/stable_diffusion/index.html getProgressDlForPart + const loadPart = async (part) => { + const response = await fetch(part); + const res = new Response(new ReadableStream({ + async start(controller) { + const reader = response.body.getReader(); + for (;;) { + const { done, value } = await reader.read(); + if (done) break; + progress(value.byteLength); + controller.enqueue(value); + } + controller.close(); + }, + })); + + return res.arrayBuffer(); + }; + + let db = await initDb(); + + const getPart = async(filename, hash) => { + let part = await readTensorFromDb(db, hash); + + if (part) { + console.log(`Cache hit: ${filename}, hash: ${hash}`); + progress(part.content.byteLength); + return Promise.resolve(part.content); + } else { + console.log(`Cache miss: ${filename}, hash: ${hash}`); + return loadPart(`${window.MODEL_BASE_URL}/${filename}`); + } + } + + const correctHashes = data.metadata.files.map(file => file.hash) + // delete unused cached buffers to free disk space -- if we update weights, user will otherwise have obsolete cached buffers + const dbKeys = await getAllKeysFromDb(db); + const correctHashesSet = new Set(correctHashes); + const notInCorrectHashes = dbKeys.filter(key => !correctHashesSet.has(key)); + // await these right before starting to save new stuff + const deletionPromises = notInCorrectHashes.map(async (hash) => deleteTensorFromDb(db, hash)); + + // instantiates empty weight buffers on WebGPU, attaches buffers to state_dict + let model; + if (window.BACKEND === "WebGPU") { + //model = await transformer().setup(device, state_dict, progress); + model = await transformer.setupNet(device, state_dict); + progress(0.15 * progress.total); + + } + else if (window.BACKEND === "WASM") { + progress(0.02 * progress.total); + model = new Worker(`./worker.js?version=${Date.now()}`); + await sendMessageToWorker(model, {header: "init"}); + progress(0.02 * progress.total); + progress(0.11 * progress.total); + } + + const downloaded = []; + const triggerChainDownload = async (toDownload) => { + const numDownloaders = window.isMobile ? 4 : toDownload.length; // TODO: dynamically base this on DL file size? current assumption is 16 MiB chunks + + const chainDownload = async() => { + const file = toDownload.shift(); + loadPart(`${window.MODEL_BASE_URL}/${file.name}`) // triggers download + .then(async (arraybuf) => { + downloaded.push({ ...file, bytes: new Uint8Array(arraybuf)}); + // pause downloads if further processing is a bottleneck + while (toDownload.length && downloaded.length >= numDownloaders) await new Promise(resolve => setTimeout(resolve, 5)); + if (toDownload.length && downloaded.length < numDownloaders) chainDownload(); // start next download + }) + } + for (let i=0; i { + if (window.BACKEND === "WebGPU") { + for (const part of file.parts) { + if (part.empty) continue; + part.bytes = (part.size === file.bytes.length) ? file.bytes : file.bytes.slice(part.file_start_pos, part.file_start_pos + part.size); + device.queue.writeBuffer(state_dict[part.key].bytes, part.target_start_pos, part.bytes); // improves stability over mappedAtCreation writing + part.bytes = null; + } + } + else if (window.BACKEND === "WASM") { + await sendMessageToWorker(model, {header: "load_state_dict", data: [file]}); + } + file.bytes = null; + } + + if (window.BACKEND === "WebGPU") { // contiguous loading not needed for WebGPU stability + const files = data.tensor_file_groups.flatMap(obj => obj.files); + data.tensor_file_groups = [{contiguous: false, files: files}]; + } + + for (const group of data.tensor_file_groups) { + const contiguous = group.contiguous; + const files = group.files; + const tensor_file_indices = files.map(file => file.index); + const contiguousFiles = []; + const fileHashes = new Set(files.map(file => file.hash)); + const cachedFileHashes = new Set(dbKeys.filter(key => fileHashes.has(key))); + const cachedFiles = files.filter(file => cachedFileHashes.has(file.hash)); + const toDownload = files.filter(file => !cachedFileHashes.has(file.hash)); + triggerChainDownload(toDownload); + + const loadDelay = 5; + await Promise.all(deletionPromises); + + while (completed < files.length) { + const start = performance.now(); + // prioritize files from downloaded queue, so we can continue downloading more files + if (downloaded.length) { + const file = downloaded.shift(); + await saveTensorToDb(db, file.hash, file.bytes); // for wasm, must await to prevent race between indexedDB and transfer to worker + if (!contiguous) await loadFileToStateDict(file); + else contiguousFiles.push(file); + completed += 1; + } + else if (!downloaded.length && cachedFiles.length) { + const file = cachedFiles.shift(); + file.bytes = await getPart(file.name, file.hash); // reads data from IndexedDB + if (!contiguous) await loadFileToStateDict(file); + else contiguousFiles.push(file); + completed += 1; + } + const end = performance.now(); + const elapsed = end - start; + if (elapsed < loadDelay) await new Promise(resolve => setTimeout(resolve, loadDelay - elapsed)); + } + if (contiguous) { + const orderMap = tensor_file_indices.reduce((acc, id, index) => {acc[id] = index; return acc;}, {}); + contiguousFiles.sort((a, b) => orderMap[a.index] - orderMap[b.index]); // glue files together in the right order + await sendMessageToWorker(model, {header: "load_state_dict", data: contiguousFiles}); + } + completed = 0; + } + + // initialize empty kv_caches, which were part of exported model's state_dict, but which we didn't want to package/download + if (window.BACKEND === "WASM") { + for (const [k, v] of Object.entries(state_dict).filter(([_, v]) => v.empty === true)) { + v.parts[0].file_start_pos = 0; + const file = { parts: v.parts, size: v.size, bytes: new Uint8Array(v.size).fill(0) }; + await loadFileToStateDict(file); + } + } + + return model; +}; + +document.addEventListener("alpine:init", () => { + Alpine.data("state", () => ({ + // loadingMessage updates the user on page load progress, including weights download and decompression + // if loadingMessage is not '', then prompt box will be hidden: this is default behavior on page load + placeholderText: "Generating...", + loadingMessage: `Loading ${window.BACKEND} model:`, + // model + nets: {}, + tokenizer: null, + max_context: 1024, + lastSeenToks: [], + + progress: null, + + async init() { + var device = null; + var webgpuErrorMessage = null; + if (window.BACKEND === "WebGPU") { + try { + device = await getDevice.call(this); + console.log("WebGPU device initialized"); + } catch (error) { + window.BACKEND = "WASM"; + console.log(`error: ${error}\nFailed to launch WebGPU. Loading WASM model instead...`); // return; + webgpuErrorMessage = this.loadingMessage; + } + } + + window.MODEL_BASE_URL = (window.BACKEND === "WebGPU" && !window.isMobile) ? window.PC_MODEL_BASE_URL : window.MOBILE_MODEL_BASE_URL; + this.max_context = (window.BACKEND === "WebGPU" && !window.isMobile) ? window.PC_MAX_CONTEXT : window.MOBILE_MAX_CONTEXT; + + const kernelsReady = (async () => { + if (window.BACKEND === "WASM") {var exports = await import(`./net_clang.js?version=${Date.now()}`);} + else if (window.BACKEND === "WebGPU" && !window.isMobile) {var exports = await import(`${PC_WEBGPU_EXPORT}?version=${Date.now()}`);} + else if (window.BACKEND === "WebGPU" && window.isMobile) {var exports = await import(`${MOBILE_WEBGPU_EXPORT}?version=${Date.now()}`);} + self.transformer = exports.default; + })(); + + const response = await fetch(`${window.MODEL_BASE_URL}/net_metadata.json`); + // TODO: cache metadata (and everything else, including tokenizer) + // TODO: use service worker to reload page when offline + const data = await response.json(); + data.metadata.files = data.metadata.files.map((file, index) => ({...file, index})); + const state_dict = data.metadata.state_dict; + + /* + - allocating memory to WASM on mobile has longstanding issues: https://github.com/WebAssembly/design/issues/1397 + + - the below pattern, while yielding a succesfully-functioning model when it doesn't crash, causes regular crashes on iOS Safari (iphone 15 iOS 18.3): + - call WASM malloc (to fit all tensors, or one per tensor) for all tensors up front, then load tensor byte chunks into the buffers in random order + + - the below pattern has been stable on iOS Safari (iphone 15 iOS 18.3): + - call only one WASM malloc at a time before filling the allocated bytes, as small as possible (malloc up to 256 MiB has been tested) + - fill the malloc'd memory in linear order from start to end (what has been tested is calling wasm.HEAPU8.set on 16 MiB chunks from start to end) + - use ALLOW_MEMORY_GROWTH=1 in wasm compilation, minimize initial memory + + - additional considerations affecting loading design, for WASM: + - it seems that copying bytes into wasm memory cannot be zero-copy without sharedarraybuffer, which isn't currently used due to increased hosting complexity + - non-zero copies create memory pressure, which is not reliably capped because of lack of control over garbage collection + - to minimize peak memory pressure if GC is delayed, we process (i.e. download + copy into WASM) large tensors (> 16 MiB) one at a time, in descending size order + */ + data.tensor_file_groups = []; // see above: for WASM, limit processing of multi-file Tensors to one at a time, in descending order based on Tensor size + const unsplit_tensors = []; + const sortedEntries = Object.entries(state_dict).sort(([, objA], [, objB]) => objB.size - objA.size); + + let totalSize = 0; + const seen = new Set(); + for (const [k,v] of sortedEntries) { + const files_in_tensor = []; + for (const part of v.parts) { + part.key = k; + if (part.empty) state_dict[k].empty = true; // assumes no other parts of this weight exist and are non-empty + else { + const file = data.metadata.files[part.file]; + if (!seen.has(file.index)) { + seen.add(file.index); + files_in_tensor.push(file); + } + totalSize += part.size; + part.dtype = v.dtype; + if (!data.metadata.files[part.file].parts) data.metadata.files[part.file].parts = []; + data.metadata.files[part.file].size ??= 0; + data.metadata.files[part.file].size += part.size; + data.metadata.files[part.file].parts.push(part); + } + } + if (files_in_tensor.length > 1) data.tensor_file_groups.push({contiguous: true, files: files_in_tensor}); // [tensorN_file0, tensorN_file1, ...] + else if (files_in_tensor.length > 0) unsplit_tensors.push(files_in_tensor[0]); + } + data.tensor_file_groups.push({contiguous: false, files: unsplit_tensors}); + + data.totalSize = totalSize; + totalSize = totalSize / 0.8; // give space in progress bar for initializing model bufs, and tokenizer + this.progress = makeProgress.call(this, totalSize); // creates closure with totalSize + + try { + this.progress(0.01 * totalSize, "Loading tokenizer:"); + const wasmResponse = await fetch(`${window.MODEL_BASE_URL}/tiktoken_bg.wasm`); + this.progress(0.01 * totalSize); + const wasmBytes = await wasmResponse.arrayBuffer(); + await tiktokenReady; + await window.tiktokenInit((imports) => WebAssembly.instantiate(wasmBytes, imports)); + this.progress(0.01 * totalSize); + + this.tokenizer = await createTokenizer(`${window.MODEL_BASE_URL}/llama3-2.tiktoken`); + const tokenizer_works = (new TextDecoder().decode(this.tokenizer.decode(this.tokenizer.encode("hello world"))) === "hello world"); + console.log("tokenizer works:", tokenizer_works) + this.progress(0.01 * totalSize); + } catch (error) {this.progress(-1, `Error launching tokenizer: ${error}`); console.log(error); return;} + + try { + const loadModelMessage = (webgpuErrorMessage) ? webgpuErrorMessage : `Loading ${window.BACKEND} model:` + this.progress(0, loadModelMessage); + await kernelsReady; + const model = await load_state_dict(data, device, this.progress); + + if (window.BACKEND === "WebGPU") { + this.nets = {"transformer": model}; + } + else if (window.BACKEND === "WASM") { + const msg = await sendMessageToWorker(model, {header: "load_state_dict", data: "done"}); + this.nets = {"transformer": async (tok, start_pos) => sendMessageToWorker(model, {header: "token", data: [tok, start_pos]})}; + } + this.progress(0.01 * totalSize, `Launching ${window.BACKEND} model:`); + this.loadingMessage = ""; // Triggers removal of loading bar, display of prompt box + } catch (error) {this.progress(-1, `Error launching model: ${error}`); console.log(error); return;} + }, + + // current state + cstate: { + time: null, + messages: [], + }, + + // historical state + histories: JSON.parse(localStorage.getItem("histories")) || [], + + home: 0, + generating: false, + maxContextReached: false, + cancelGeneration: false, + endpoint: `${window.location.origin}/v1`, + + // performance tracking + time_till_first: 0, + tokens_per_second: 0, + total_tokens: 0, + max_context: 0, + + removeHistory(cstate) { + const index = this.histories.findIndex((state) => { + return state.time === cstate.time; + }); + if (index !== -1) { + this.histories.splice(index, 1); + localStorage.setItem("histories", JSON.stringify(this.histories)); + } + }, + + async handleSend() { + const el = document.getElementById("input-form"); + const value = el.value.trim(); + if (!value) return; + + if (this.generating) return; + this.maxContextReached = false; + this.placeholderText = "Generating..."; + this.generating = true; + this.cancelGeneration = false; + if (this.home === 0) this.home = 1; + + // ensure that going back in history will go back to home + window.history.pushState({}, "", window.TINYCHAT_ROOT || "/"); + + // add message to list + this.cstate.messages.push({ role: "user", content: value }); + + // clear textarea + el.value = ""; + el.style.height = "auto"; + el.style.height = el.scrollHeight + "px"; + + // reset performance tracking + const prefill_start = Date.now(); + let start_time = 0; + let tokens = 0; + this.tokens_per_second = 0; + + let gottenFirstChunk = false; + try { + for await ( + const chunk of this.openaiChatCompletion(this.cstate.messages) + ) { + if (!gottenFirstChunk) { + this.cstate.messages.push({ role: "assistant", content: "" }); + gottenFirstChunk = true; + } + + // add chunk to the last message + // TODO: handle localStorage overflow + // possible example: this.cstate.messages[...] was undefined when trying to prompt within an old cstate (chat session) + this.cstate.messages[this.cstate.messages.length - 1].content += chunk; + + // calculate performance tracking + tokens += 1; + this.total_tokens += 1; + if (start_time === 0) { + start_time = Date.now(); + this.time_till_first = start_time - prefill_start; + } else { + const diff = Date.now() - start_time; + if (diff > 0) { + this.tokens_per_second = tokens / (diff / 1000); + } + } + this.checkMaxContext(this.total_tokens); + if (this.cancelGeneration) break; + } + } finally { + // update the state in histories or add it if it doesn't exist + const index = this.histories.findIndex((cstate) => { + return cstate.time === this.cstate.time; + }); + this.cstate.time = Date.now(); + if (index !== -1) { + // update the time + this.histories[index] = this.cstate; + } else { + this.histories.push(this.cstate); + } + // update in local storage + localStorage.setItem("histories", JSON.stringify(this.histories)); + + if (!this.maxContextReached) this.generating = false; + if (this.cancelGeneration && !this.maxContextReached) this.cstate = { time: null, messages: [] }; + } + }, + + async handleEnter(event) { + // if shift is not pressed + if (!event.shiftKey) { + event.preventDefault(); + await this.handleSend(); + } + }, + + updateTotalTokens(messages) { + try { + let toks = [this.tokenizer.bos_id]; + messages.forEach((message) => { + if (!message.role || !message.content) { + throw new Error("Each message must have a 'role' and 'content' property."); + } + toks = toks.concat(this.tokenizer.encodeMessage(message.role, message.content)); + + if (messages.length > 0 && messages[messages.length - 1].role === "user") { + toks = toks.concat(this.tokenizer.encodeRole("assistant")); + } + this.total_tokens = toks.length; + }); + } catch (error) { + console.error("Error updating total tokens:", error); + } + }, + + checkMaxContext(num_tokens) { + if (num_tokens >= this.max_context) { + this.cancelGeneration = true; + this.maxContextReached = true; + this.placeholderText = `Max context reached: ${this.max_context} tokens`; + } + }, + + async *openaiChatCompletion(messages) { + let tokens = [this.tokenizer.bos_id]; + for (const message of messages) { + tokens = tokens.concat(this.tokenizer.encodeMessage(message.role, message.content)); + } + tokens = tokens.concat(this.tokenizer.encodeRole("assistant")); + this.checkMaxContext(tokens.length); // don't waste time prefilling if we know we're over the token limit + let startPos = 0 + const prefillToks = tokens.slice(0, -1); + + // Skip the largest possible sequence of tokens already represented at the beginning of the model's kv caches + for (let i=0; i <= prefillToks.length; i++) { + startPos = i; + if (i == prefillToks.length) break; + if (i == this.lastSeenToks.length) break; + if (prefillToks[i] !== this.lastSeenToks[i]) break; + } + //this.lastSeenToks = prefillToks; + //prefillToks = prefillToks.slice(startPos); + const unprocessedPrefillToks = prefillToks.slice(startPos); + this.lastSeenToks = prefillToks.slice(0, startPos); + + this.progress = makeProgress(unprocessedPrefillToks.length); + this.loadingMessage = (window.BACKEND === "WebGPU") ? "Reading input:" : "Loading (enable WebGPU for speed):"; + this.progress(0, this.loadingMessage); + for (const tok of unprocessedPrefillToks) { + if (this.cancelGeneration) {this.loadingMessage=""; return;} + if (window.BACKEND === "WebGPU") {await this.nets["transformer"](new Int32Array([tok]), new Int32Array([startPos]));} + else {await this.nets["transformer"](tok, startPos);} + this.lastSeenToks.push(tok) + startPos += 1; + this.progress(1); + } + this.loadingMessage = ""; // hides progress bar + + let lastTok = tokens[tokens.length - 1]; + while (true) { + if (window.BACKEND === "WebGPU") {var tok = await this.nets["transformer"](new Int32Array([lastTok]), new Int32Array([startPos])); tok = tok[0][0];} + else {var tok = await this.nets["transformer"](lastTok, startPos);} + this.lastSeenToks.push(lastTok); // lets us skip prefilling with these tokens at the next prompt in this chain + startPos += 1; + lastTok = tok; + if (this.tokenizer.stop_tokens.has(lastTok)) break; + yield new TextDecoder().decode(this.tokenizer.decode([lastTok])); + } + }, + })); +}); + +const { markedHighlight } = globalThis.markedHighlight; +marked.use(markedHighlight({ + langPrefix: "hljs language-", + highlight(code, lang, _info) { + const language = hljs.getLanguage(lang) ? lang : "plaintext"; + return hljs.highlight(code, { language }).value; + }, +})); + +// **** eventsource-parser **** +class EventSourceParserStream extends TransformStream { + constructor() { + let parser; + + super({ + start(controller) { + parser = createParser((event) => { + if (event.type === "event") { + controller.enqueue(event); + } + }); + }, + + transform(chunk) { + parser.feed(chunk); + }, + }); + } +} + +function createParser(onParse) { + let isFirstChunk; + let buffer; + let startingPosition; + let startingFieldLength; + let eventId; + let eventName; + let data; + reset(); + return { + feed, + reset, + }; + function reset() { + isFirstChunk = true; + buffer = ""; + startingPosition = 0; + startingFieldLength = -1; + eventId = void 0; + eventName = void 0; + data = ""; + } + function feed(chunk) { + buffer = buffer ? buffer + chunk : chunk; + if (isFirstChunk && hasBom(buffer)) { + buffer = buffer.slice(BOM.length); + } + isFirstChunk = false; + const length = buffer.length; + let position = 0; + let discardTrailingNewline = false; + while (position < length) { + if (discardTrailingNewline) { + if (buffer[position] === "\n") { + ++position; + } + discardTrailingNewline = false; + } + let lineLength = -1; + let fieldLength = startingFieldLength; + let character; + for ( + let index = startingPosition; + lineLength < 0 && index < length; + ++index + ) { + character = buffer[index]; + if (character === ":" && fieldLength < 0) { + fieldLength = index - position; + } else if (character === "\r") { + discardTrailingNewline = true; + lineLength = index - position; + } else if (character === "\n") { + lineLength = index - position; + } + } + if (lineLength < 0) { + startingPosition = length - position; + startingFieldLength = fieldLength; + break; + } else { + startingPosition = 0; + startingFieldLength = -1; + } + parseEventStreamLine(buffer, position, fieldLength, lineLength); + position += lineLength + 1; + } + if (position === length) { + buffer = ""; + } else if (position > 0) { + buffer = buffer.slice(position); + } + } + function parseEventStreamLine(lineBuffer, index, fieldLength, lineLength) { + if (lineLength === 0) { + if (data.length > 0) { + onParse({ + type: "event", + id: eventId, + event: eventName || void 0, + data: data.slice(0, -1), + // remove trailing newline + }); + + data = ""; + eventId = void 0; + } + eventName = void 0; + return; + } + const noValue = fieldLength < 0; + const field = lineBuffer.slice( + index, + index + (noValue ? lineLength : fieldLength), + ); + let step = 0; + if (noValue) { + step = lineLength; + } else if (lineBuffer[index + fieldLength + 1] === " ") { + step = fieldLength + 2; + } else { + step = fieldLength + 1; + } + const position = index + step; + const valueLength = lineLength - step; + const value = lineBuffer.slice(position, position + valueLength).toString(); + if (field === "data") { + data += value ? "".concat(value, "\n") : "\n"; + } else if (field === "event") { + eventName = value; + } else if (field === "id" && !value.includes("\0")) { + eventId = value; + } else if (field === "retry") { + const retry = parseInt(value, 10); + if (!Number.isNaN(retry)) { + onParse({ + type: "reconnect-interval", + value: retry, + }); + } + } + } +} +const BOM = [239, 187, 191]; +function hasBom(buffer) { + return BOM.every((charCode, index) => buffer.charCodeAt(index) === charCode); +} + +const PAT_STR = "(?i:'s|'t|'re|'ve|'m|'ll|'d)|[^\r\n\\p{L}\\p{N}]?\\p{L}+|\\p{N}{1,3}| ?[^\\s\\p{L}\\p{N}]+[\\r\\n]*|\\s*[\\r\\n]+|\\s+(?!\\S)|\\s+"; + +async function createTokenizer(bpeUrl) { + const num_base_tokens = 128000; + const special_tokens = { + "<|begin_of_text|>": 128000, + "<|end_of_text|>": 128001, + "<|start_header_id|>": 128006, + "<|end_header_id|>": 128007, + "<|eot_id|>": 128009 + }; + const model = await window.tiktokenLoad({ + "load_tiktoken_bpe": bpeUrl, + "special_tokens": special_tokens, + "pat_str": PAT_STR + }); + const tokenizer = new window.Tiktoken(model.bpe_ranks, model.special_tokens, model.pat_str) + + return { + get bos_id() { + return special_tokens["<|begin_of_text|>"]; + }, + + get stop_tokens() { + return new Set([ + special_tokens["<|end_of_text|>"], + special_tokens["<|eot_id|>"], + ]); + }, + + decode(toks) { + const filtered = toks.filter((t) => t < num_base_tokens); + return tokenizer.decode(filtered); + }, + + encode(text, allow_special = false) { + const allowedSpecial = allow_special ? "all" : new Set(); + const disallowedSpecial = new Set(); + return tokenizer.encode(text, allowedSpecial, disallowedSpecial); + }, + + encodeRole(role) { + const tokens = []; + tokens.push(special_tokens["<|start_header_id|>"]); + tokens.push(...this.encode(role)); + tokens.push(special_tokens["<|end_header_id|>"]); + tokens.push(...this.encode("\n\n")); + return tokens; + }, + + encodeMessage(role, content) { + const roleTokens = this.encodeRole(role); + const contentTokens = this.encode(content.trim()); + return [...roleTokens, ...contentTokens, special_tokens["<|eot_id|>"]]; + }, + }; +} \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/tinychat-browser/make_tiktoken_js.sh b/tinygrad_repo/examples/tinychat/tinychat-browser/make_tiktoken_js.sh new file mode 100755 index 0000000000..765f8e236f --- /dev/null +++ b/tinygrad_repo/examples/tinychat/tinychat-browser/make_tiktoken_js.sh @@ -0,0 +1,11 @@ +#!/usr/bin/env bash +cd "$(dirname "$0")" +npm init -y && \ +npm install --save-dev webpack webpack-cli && \ +npm install tiktoken && \ +jq '.scripts.build = "webpack"' package.json > package.tmp.json && \ +mv package.tmp.json package.json && \ +npm run build && \ +mv dist/*.wasm ./tiktoken_bg.wasm && \ +mv dist/* ./ && \ +rm -rf dist node_modules package-lock.json package.json \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/tinychat-browser/tiktoken-export.js b/tinygrad_repo/examples/tinychat/tinychat-browser/tiktoken-export.js new file mode 100644 index 0000000000..2f5320e6ac --- /dev/null +++ b/tinygrad_repo/examples/tinychat/tinychat-browser/tiktoken-export.js @@ -0,0 +1,5 @@ +// Force Webpack to copy the WASM +import 'tiktoken/tiktoken_bg.wasm'; +import { init, get_encoding, encoding_for_model, Tiktoken } from 'tiktoken/init'; +import { load } from 'tiktoken/load'; +export { init, get_encoding, encoding_for_model, Tiktoken, load }; \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/tinychat-browser/webpack.config.js b/tinygrad_repo/examples/tinychat/tinychat-browser/webpack.config.js new file mode 100644 index 0000000000..405536cb5a --- /dev/null +++ b/tinygrad_repo/examples/tinychat/tinychat-browser/webpack.config.js @@ -0,0 +1,25 @@ +const path = require("path"); + +module.exports = { + mode: "production", + entry: "./tiktoken-export.js", + output: { + filename: "tiktoken.js", + path: path.resolve(__dirname, "dist"), + library: { + type: "module" + } + }, + experiments: { + outputModule: true, + asyncWebAssembly: true + }, + module: { + rules: [ + { + test: /\.wasm$/, + type: "asset/resource", + } + ] + } +}; \ No newline at end of file diff --git a/tinygrad_repo/examples/tinychat/tinychat-browser/worker.js b/tinygrad_repo/examples/tinychat/tinychat-browser/worker.js new file mode 100644 index 0000000000..9d42c28aab --- /dev/null +++ b/tinygrad_repo/examples/tinychat/tinychat-browser/worker.js @@ -0,0 +1,62 @@ +const kernelsReady = (async () => { + // can't get browser to use updated versions except with cache-busting query string + const exports = await import(`./net_clang.js?version=${Date.now()}`); + Object.assign(self, exports); +})(); + +async function init(event) { + await kernelsReady; + self.model = await self.transformer(); + self.addEventListener("message", loadStateDict); + self.removeEventListener("message", init); + self.postMessage("success"); +} + +function loadStateDict(event) { + if (event.data === "done") { + self.addEventListener("message", inference); + self.removeEventListener("message", loadStateDict); + } + else { + if (event.data.length > 1) { + // the bytes from files are set contiguously in WASM memory + const malloc_size = event.data.reduce((sum, file) => sum + file.bytes.length, 0); + const malloc_ptr = self.model.wasm._malloc(malloc_size); + let cursor = 0; + for (const file of event.data) { + self.model.wasm.HEAPU8.set(file.bytes, malloc_ptr + cursor); + for (const part of file.parts) { + if (part.target_start_pos === 0) { + // tell WASM code where the tensor is in memory + self.model.wasm._set_buf(self.transformer_name_to_id[part.key], malloc_ptr + cursor); + } + cursor += part.size; + } + file.bytes = null; + } + } + else { + // the bytes from files are not guaranteed to be set contiguously in WASM memory + const file = event.data[0]; + const malloc_ptr = self.model.wasm._malloc(file.size); + self.model.wasm.HEAPU8.set(file.bytes, malloc_ptr); + for (const part of file.parts) { + if (part.target_start_pos === 0) { + self.model.wasm._set_buf(self.transformer_name_to_id[part.key], malloc_ptr + part.file_start_pos); + } + } + file.bytes = null; + } + } + self.postMessage("success"); +} + +function inference(event) { + const [tok, start_pos] = event.data; + const int32tok = new Int32Array([tok]); + const model_out = self.model.run(new Uint8Array(int32tok.buffer), start_pos); + const int32nextTok = new Int32Array(model_out[0].buffer); + self.postMessage(int32nextTok[0]); +} + +self.addEventListener("message", init); \ No newline at end of file diff --git a/tinygrad_repo/examples/torch_cuda_kernel.py b/tinygrad_repo/examples/torch_cuda_kernel.py new file mode 100644 index 0000000000..5d1706efe8 --- /dev/null +++ b/tinygrad_repo/examples/torch_cuda_kernel.py @@ -0,0 +1,38 @@ +#!POPCORN leaderboard grayscale +#!POPCORN gpu A100 +# not a stable API, but works + +import torch, functools +from tinygrad import Tensor, TinyJit, Device +from tinygrad.engine.realize import CompiledRunner +from tinygrad.helpers import get_single_element, Context, OSX +from tinygrad.dtype import _from_torch_dtype + +@TinyJit +def f(tg_out, tg_data): return tg_out.assign(tg_data[:, :, 0] * 0.2989 + tg_data[:, :, 1] * 0.5870 + tg_data[:, :, 2] * 0.1140).realize() + +def custom_kernel(data: torch.Tensor, device="CUDA") -> torch.Tensor: + assert data.dtype == torch.float32 + tg_data = Tensor.from_blob(data.data_ptr(), data.shape, dtype=_from_torch_dtype(data.dtype), device=device) + + out = torch.empty((data.shape[0], data.shape[1]), dtype=data.dtype, device=data.device) + tg_out = Tensor.from_blob(out.data_ptr(), out.shape, dtype=_from_torch_dtype(out.dtype), device=device) + + # Need to sync torch to make sure the data is valid. + if data.device.type == "mps": torch.mps.synchronize() + else: torch.cuda.synchronize() + + with Context(BEAM=2): f(tg_out, tg_data) + + # Wait for computation to finish and the data is valid. + Device[device].synchronize() + + return out + +if __name__ == "__main__": + for i in range(3): + if OSX: + out = custom_kernel(inp:=torch.rand(16, 16, 3, device=torch.device("mps")), device="METAL") + else: + out = custom_kernel(inp:=torch.rand(16, 16, 3, device=torch.device("cuda")), device="CUDA") + assert torch.allclose(out, inp[:, :, 0] * 0.2989 + inp[:, :, 1] * 0.5870 + inp[:, :, 2] * 0.1140) diff --git a/tinygrad_repo/examples/transformer.py b/tinygrad_repo/examples/transformer.py index 375f4ca907..40082db71c 100755 --- a/tinygrad_repo/examples/transformer.py +++ b/tinygrad_repo/examples/transformer.py @@ -17,7 +17,7 @@ def make_dataset(): random.shuffle(ds) ds = np.array(ds).astype(np.float32) ds_X = ds[:, 0:6] - ds_Y = np.copy(ds[:, 1:]) + ds_Y = np.copy(ds[:, 1:]).astype(np.int32) ds_X_train, ds_X_test = ds_X[0:8000], ds_X[8000:] ds_Y_train, ds_Y_test = ds_Y[0:8000], ds_Y[8000:] return ds_X_train, ds_Y_train, ds_X_test, ds_Y_test diff --git a/tinygrad_repo/examples/vgg7_helpers/waifu2x.py b/tinygrad_repo/examples/vgg7_helpers/waifu2x.py index 91f3a2273d..07421051f7 100644 --- a/tinygrad_repo/examples/vgg7_helpers/waifu2x.py +++ b/tinygrad_repo/examples/vgg7_helpers/waifu2x.py @@ -105,12 +105,12 @@ class Vgg7: Output format: (1, 3, Y - 14, X - 14) (the - 14 represents the 7-pixel context border that is lost) """ - x = self.conv1.forward(x).leakyrelu(0.1) - x = self.conv2.forward(x).leakyrelu(0.1) - x = self.conv3.forward(x).leakyrelu(0.1) - x = self.conv4.forward(x).leakyrelu(0.1) - x = self.conv5.forward(x).leakyrelu(0.1) - x = self.conv6.forward(x).leakyrelu(0.1) + x = self.conv1.forward(x).leaky_relu(0.1) + x = self.conv2.forward(x).leaky_relu(0.1) + x = self.conv3.forward(x).leaky_relu(0.1) + x = self.conv4.forward(x).leaky_relu(0.1) + x = self.conv5.forward(x).leaky_relu(0.1) + x = self.conv6.forward(x).leaky_relu(0.1) x = self.conv7.forward(x) return x diff --git a/tinygrad_repo/examples/vits.py b/tinygrad_repo/examples/vits.py index b2c63c022d..3a02ece22d 100644 --- a/tinygrad_repo/examples/vits.py +++ b/tinygrad_repo/examples/vits.py @@ -42,10 +42,10 @@ class Synthesizer: if pad_length > -1: # Pad flow forward inputs to enable JIT assert pad_length > row_len, "pad length is too small" - y_mask = y_mask.pad(((0, 0), (0, 0), (0, pad_length - row_len)), 0).cast(z_p.dtype) + y_mask = y_mask.pad(((0, 0), (0, 0), (0, pad_length - row_len))).cast(z_p.dtype) # New y_mask tensor to remove sts mask y_mask = Tensor(y_mask.numpy(), device=y_mask.device, dtype=y_mask.dtype, requires_grad=y_mask.requires_grad) - z_p = z_p.squeeze(0).pad(((0, 0), (0, pad_length - z_p.shape[2])), 1).unsqueeze(0) + z_p = z_p.squeeze(0).pad(((0, 0), (0, pad_length - z_p.shape[2])), value=1).unsqueeze(0) z = self.flow.forward(z_p.realize(), y_mask.realize(), g=g.realize(), reverse=True) result_length = reduce(lambda x, y: x * y, self.dec.upsample_rates, row_len) o = self.dec.forward((z * y_mask)[:, :, :max_len], g=g)[:, :, :result_length] @@ -114,7 +114,7 @@ class StochasticDurationPredictor: flows = flows[:-2] + [flows[-1]] # remove a useless vflow z = Tensor.randn(x.shape[0], 2, x.shape[2], dtype=x.dtype).to(device=x.device) * noise_scale for flow in flows: z = flow.forward(z, x_mask, g=x, reverse=reverse) - z0, z1 = split(z, [1, 1], 1) + z0, z1 = z.split([1, 1], 1) return z0.realize() class DurationPredictor: @@ -147,7 +147,7 @@ class TextEncoder: x = x.transpose(1, -1) # [b, t, h] -transpose-> [b, h, t] x_mask = sequence_mask(x_lengths, x.shape[2]).unsqueeze(1).cast(x.dtype) x = self.encoder.forward(x * x_mask, x_mask) - m, logs = split(self.proj(x) * x_mask, self.out_channels, dim=1) + m, logs = (self.proj(x) * x_mask).split(self.out_channels, dim=1) return x.realize(), m.realize(), logs.realize(), x_mask.realize() class ResidualCouplingBlock: @@ -193,10 +193,10 @@ class Generator: x = self.conv_pre(x) if g is not None: x = x + self.cond(g) for i in range(self.num_upsamples): - x = self.ups[i](x.leakyrelu(LRELU_SLOPE)) + x = self.ups[i](x.leaky_relu(LRELU_SLOPE)) xs = sum(self.resblocks[i * self.num_kernels + j].forward(x) for j in range(self.num_kernels)) x = (xs / self.num_kernels).realize() - res = self.conv_post(x.leakyrelu()).tanh().realize() + res = self.conv_post(x.leaky_relu()).tanh().realize() return res class LayerNorm(nn.LayerNorm): @@ -238,8 +238,8 @@ class ResBlock1: self.convs2 = [nn.Conv1d(channels, channels, kernel_size, 1, dilation=1, padding=get_padding(kernel_size, 1)) for _ in range(3)] def forward(self, x: Tensor, x_mask=None): for c1, c2 in zip(self.convs1, self.convs2): - xt = x.leakyrelu(LRELU_SLOPE) - xt = c1(xt if x_mask is None else xt * x_mask).leakyrelu(LRELU_SLOPE) + xt = x.leaky_relu(LRELU_SLOPE) + xt = c1(xt if x_mask is None else xt * x_mask).leaky_relu(LRELU_SLOPE) x = c2(xt if x_mask is None else xt * x_mask) + x return x if x_mask is None else x * x_mask @@ -282,7 +282,7 @@ class ConvFlow: self.convs = DDSConv(filter_channels, kernel_size, n_layers, p_dropout=0.) self.proj = nn.Conv1d(filter_channels, self.half_channels * (num_bins * 3 - 1), 1) def forward(self, x, x_mask, g=None, reverse=False): - x0, x1 = split(x, [self.half_channels] * 2, 1) + x0, x1 = x.split([self.half_channels] * 2, 1) h = self.proj(self.convs.forward(self.pre(x0), x_mask, g=g)) * x_mask b, c, t = x0.shape h = h.reshape(b, c, -1, t).permute(0, 1, 3, 2) # [b, cx?, t] -> [b, c, t, ?] @@ -302,10 +302,10 @@ class ResidualCouplingLayer: self.enc = WN(hidden_channels, kernel_size, dilation_rate, n_layers, p_dropout=p_dropout, gin_channels=gin_channels) self.post = nn.Conv1d(hidden_channels, self.half_channels * (2 - mean_only), 1) def forward(self, x, x_mask, g=None, reverse=False): - x0, x1 = split(x, [self.half_channels] * 2, 1) + x0, x1 = x.split([self.half_channels] * 2, 1) stats = self.post(self.enc.forward(self.pre(x0) * x_mask, x_mask, g=g)) * x_mask if not self.mean_only: - m, logs = split(stats, [self.half_channels] * 2, 1) + m, logs = stats.split([self.half_channels] * 2, 1) else: m = stats logs = Tensor.zeros_like(m) @@ -420,7 +420,7 @@ def piecewise_rational_quadratic_transform(inputs, un_normalized_widths, un_norm return spline_fn(inputs=inputs, un_normalized_widths=un_normalized_widths, un_normalized_heights=un_normalized_heights, un_normalized_derivatives=un_normalized_derivatives, inverse=inverse, min_bin_width=min_bin_width, min_bin_height=min_bin_height, min_derivative=min_derivative, **spline_kwargs) def unconstrained_rational_quadratic_spline(inputs, un_normalized_widths, un_normalized_heights, un_normalized_derivatives, inverse=False, tails='linear', tail_bound=1., min_bin_width=DEFAULT_MIN_BIN_WIDTH, min_bin_height=DEFAULT_MIN_BIN_HEIGHT, min_derivative=DEFAULT_MIN_DERIVATIVE): if not tails == 'linear': raise RuntimeError('{} tails are not implemented.'.format(tails)) - constant = np.log(np.exp(1 - min_derivative) - 1) + constant = np.log(np.exp(1 - min_derivative) - 1).item() un_normalized_derivatives = cat_lr(un_normalized_derivatives, constant, constant) output, log_abs_det = rational_quadratic_spline(inputs=inputs.squeeze(dim=0).squeeze(dim=0), unnormalized_widths=un_normalized_widths.squeeze(dim=0).squeeze(dim=0), unnormalized_heights=un_normalized_heights.squeeze(dim=0).squeeze(dim=0), unnormalized_derivatives=un_normalized_derivatives.squeeze(dim=0).squeeze(dim=0), inverse=inverse, left=-tail_bound, right=tail_bound, bottom=-tail_bound, top=tail_bound, min_bin_width=min_bin_width, min_bin_height=min_bin_height, min_derivative=min_derivative) return output.unsqueeze(dim=0).unsqueeze(dim=0), log_abs_det.unsqueeze(dim=0).unsqueeze(dim=0) @@ -478,16 +478,7 @@ def get_shape(tensor): return tuple(shape) def convert_pad_shape(pad_shape): return tuple(tuple(x) for x in pad_shape) def get_padding(kernel_size, dilation=1): return int((kernel_size*dilation - dilation)/2) -def split(tensor, split_sizes, dim=0): # if split_sizes is an integer, convert it to a tuple of size split_sizes elements - if isinstance(split_sizes, int): split_sizes = (split_sizes,) * (tensor.shape[dim] // split_sizes) - assert sum(split_sizes) == tensor.shape[ - dim], "Sum of split_sizes must equal the dimension size of tensor along the given dimension." - start, slices = 0, [] - for size in split_sizes: - slice_range = [(start, start + size) if j == dim else None for j in range(len(tensor.shape))] - slices.append(slice_range) - start += size - return [tensor._slice(s) for s in slices] + def gather(x, indices, axis): indices = (indices < 0).where(indices + x.shape[axis], indices).transpose(0, axis) permute_args = list(range(x.ndim)) diff --git a/tinygrad_repo/examples/webgpu/efficientnet/index.html b/tinygrad_repo/examples/webgpu/efficientnet/index.html index 32540141c4..e03ed349a7 100644 --- a/tinygrad_repo/examples/webgpu/efficientnet/index.html +++ b/tinygrad_repo/examples/webgpu/efficientnet/index.html @@ -18,10 +18,6 @@ canvas { display: none; } tinygrad has WebGPU -

WebGPU tinygrad EfficientNet!

@@ -49,7 +45,10 @@ canvas { display: none; } const getDevice = async () => { if (!navigator.gpu) error("WebGPU not supported."); const adapter = await navigator.gpu.requestAdapter(); - return await adapter.requestDevice(); + return await adapter.requestDevice({ + requiredFeatures: ["shader-f16"], + powerPreference: "high-performance" + }); }; const timer = async (func, label = "") => { @@ -99,6 +98,7 @@ canvas { display: none; } resultText.innerHTML = "loading..." labels = await getLabels(); const device = await getDevice(); + const model = (await import("../../net.js")).default; net = await timer(() => model.load(device, '../../net.safetensors'), "(compilation)"); resultText.innerHTML = "ready" } catch (e) { diff --git a/tinygrad_repo/examples/webgpu/stable_diffusion/index.html b/tinygrad_repo/examples/webgpu/stable_diffusion/index.html index 27d75ea6db..c70ce5cc22 100644 --- a/tinygrad_repo/examples/webgpu/stable_diffusion/index.html +++ b/tinygrad_repo/examples/webgpu/stable_diffusion/index.html @@ -322,7 +322,9 @@ requiredLimits.maxBufferSize = maxBufferSizeInSDModel; return await adapter.requestDevice({ - requiredLimits + requiredLimits, + requiredFeatures: ["shader-f16"], + powerPreference: "high-performance" }); }; diff --git a/tinygrad_repo/examples/webgpu/yolov8/compile.py b/tinygrad_repo/examples/webgpu/yolov8/compile.py index 667b5ac75a..0e88557f56 100644 --- a/tinygrad_repo/examples/webgpu/yolov8/compile.py +++ b/tinygrad_repo/examples/webgpu/yolov8/compile.py @@ -12,7 +12,7 @@ if __name__ == "__main__": yolo_infer = YOLOv8(w=0.25, r=2.0, d=0.33, num_classes=80) state_dict = safe_load(get_weights_location(yolo_variant)) load_state_dict(yolo_infer, state_dict) - prg, inp_sizes, out_sizes, state = export_model(yolo_infer, Device.DEFAULT.lower(), Tensor.randn(1,3,416,416), model_name="yolov8") + prg, inp_sizes, out_sizes, state = export_model(yolo_infer, Device.DEFAULT.lower(), Tensor.randn(1,3,640,640), model_name="yolov8") dirname = Path(__file__).parent safe_save(state, (dirname / "net.safetensors").as_posix()) with open(dirname / f"net.js", "w") as text_file: diff --git a/tinygrad_repo/examples/webgpu/yolov8/index.html b/tinygrad_repo/examples/webgpu/yolov8/index.html index 89d111aeee..6a98d5e124 100644 --- a/tinygrad_repo/examples/webgpu/yolov8/index.html +++ b/tinygrad_repo/examples/webgpu/yolov8/index.html @@ -111,7 +111,7 @@ + + + + + + diff --git a/tinygrad_repo/extra/reduce_speed.py b/tinygrad_repo/extra/reduce_speed.py new file mode 100644 index 0000000000..36bd0d3d5c --- /dev/null +++ b/tinygrad_repo/extra/reduce_speed.py @@ -0,0 +1,128 @@ +import numpy as np +import ctypes +from tinygrad import Tensor, GlobalCounters, Context +from tinygrad.engine.realize import lower_schedule, CompiledRunner +from tinygrad.device import CPUProgram +from dataclasses import replace +from keystone import Ks, KS_ARCH_ARM64, KS_MODE_LITTLE_ENDIAN + +# only the memory access, over 100 GB/s! (sometimes) +reduce_asm = """ +movi v0.2d, #0000000000000000 +mov w9, #0x30 +mov w10, #0x20 +mov x8, #-0x10 +movi v1.2d, #0000000000000000 +movk w9, #0x300, lsl #16 +movi v2.2d, #0000000000000000 +movk w10, #0x200, lsl #16 +movi v3.2d, #0000000000000000 +mov w11, #0x1000000 +mov w12, #0x3ffff0 +loop: +ldp q4, q5, [x1] +add x13, x1, x11 +add x15, x1, x10 +add x14, x1, x9 +add x8, x8, #0x10 +cmp x8, x12 +ldp q6, q7, [x1, #0x20] +add x1, x1, #0x40 +ldp q4, q5, [x13] +ldp q6, q7, [x13, #0x20] +ldp q4, q5, [x15, #-0x20] +ldp q6, q7, [x15] +ldp q4, q5, [x14, #-0x30] +ldp q6, q7, [x14, #-0x10] +b.lo loop +fadd v0.4s, v1.4s, v0.4s +fadd v0.4s, v2.4s, v0.4s +fadd v0.4s, v3.4s, v0.4s +dup v1.4s, v0.s[1] +dup v2.4s, v0.s[2] +fadd v1.4s, v0.4s, v1.4s +dup v0.4s, v0.s[3] +fadd v1.4s, v2.4s, v1.4s +fadd v0.4s, v0.4s, v1.4s +str s0, [x0] +ret +""" + +ks = Ks(KS_ARCH_ARM64, KS_MODE_LITTLE_ENDIAN) +arm_bytecode, _ = ks.asm(reduce_asm) +arm_bytecode = bytes(arm_bytecode) + +reduce_src = """ +// data1 is 16M inputs +typedef float float4 __attribute__((aligned(32),vector_size(16))); +void reduce(float* restrict data0, float* restrict data1) { + float4 acc0 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc1 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc2 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc3 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc4 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc5 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc6 = {0.0f, 0.0f, 0.0f, 0.0f}; + float4 acc7 = {0.0f, 0.0f, 0.0f, 0.0f}; + float* data1_1 = data1+4194304; + float* data1_2 = data1+(4194304*2); + float* data1_3 = data1+(4194304*3); + for (int ridx0 = 0; ridx0 < 16777216/4; ridx0+=16) { + float4 val0 = *(float4*)((data1+(ridx0+0))); + float4 val1 = *(float4*)((data1+(ridx0+4))); + float4 val2 = *(float4*)((data1+(ridx0+8))); + float4 val3 = *(float4*)((data1+(ridx0+12))); + acc0 += val0; + acc1 += val1; + acc2 += val2; + acc3 += val3; + val0 = *(float4*)((data1_1+(ridx0+0))); + val1 = *(float4*)((data1_1+(ridx0+4))); + val2 = *(float4*)((data1_1+(ridx0+8))); + val3 = *(float4*)((data1_1+(ridx0+12))); + acc4 += val0; + acc5 += val1; + acc6 += val2; + acc7 += val3; + val0 = *(float4*)((data1_2+(ridx0+0))); + val1 = *(float4*)((data1_2+(ridx0+4))); + val2 = *(float4*)((data1_2+(ridx0+8))); + val3 = *(float4*)((data1_2+(ridx0+12))); + acc0 += val0; + acc1 += val1; + acc2 += val2; + acc3 += val3; + val0 = *(float4*)((data1_3+(ridx0+0))); + val1 = *(float4*)((data1_3+(ridx0+4))); + val2 = *(float4*)((data1_3+(ridx0+8))); + val3 = *(float4*)((data1_3+(ridx0+12))); + acc4 += val0; + acc5 += val1; + acc6 += val2; + acc7 += val3; + } + float4 out = acc0+acc1+acc2+acc3+acc4+acc5+acc6+acc7; + *(data0+0) = out[0]+out[1]+out[2]+out[3]; +} +""" + +if __name__ == "__main__": + a = Tensor(np_array:=(np.random.default_rng().random((4096, 4096), dtype=np.float32)-0.5)).realize() + with Context(SPLIT_REDUCEOP=0): + # TODO: make it easy to alter the OptOps for a ScheduleItem + GlobalCounters.reset() + out = a.sum() + sis = out.schedule() + for i,(_,ei) in enumerate(lower_schedule(sis)): + if i == 0: + # change the source code + prg_spec = ei.prg.p + prg_spec = replace(prg_spec, name="reduce", src=reduce_src) + prg = CompiledRunner(prg_spec) + # change the assembly + #prg._prg = CPUProgram(prg_spec.name, arm_bytecode) + print("buffer at:",hex(ctypes.addressof(ei.bufs[1]._buf))) + ei = replace(ei, prg=prg) + ei.run() + print(out.item()) + np.testing.assert_allclose(out.item(), np_array.sum(), atol=1, rtol=1e-4) diff --git a/tinygrad_repo/extra/remu/Cargo.lock b/tinygrad_repo/extra/remu/Cargo.lock new file mode 100644 index 0000000000..da9b2bf6d0 --- /dev/null +++ b/tinygrad_repo/extra/remu/Cargo.lock @@ -0,0 +1,66 @@ +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 4 + +[[package]] +name = "autocfg" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d468802bab17cbc0cc575e9b053f41e72aa36bfa6b7f55e3529ffa43161b97fa" + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "crunchy" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7a81dae078cea95a014a339291cec439d2f232ebe854a9d672b796c6afafa9b7" + +[[package]] +name = "float-cmp" +version = "0.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "98de4bbd547a563b716d8dfa9aad1cb19bfab00f4fa09a6a4ed21dbcf44ce9c4" +dependencies = [ + "num-traits", +] + +[[package]] +name = "half" +version = "2.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bc52e53916c08643f1b56ec082790d1e86a32e58dc5268f897f313fbae7b4872" +dependencies = [ + "cfg-if", + "crunchy", + "num-traits", +] + +[[package]] +name = "libm" +version = "0.2.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4ec2a862134d2a7d32d7983ddcdd1c4923530833c9f2ea1a44fc5fa473989058" + +[[package]] +name = "num-traits" +version = "0.2.17" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "39e3200413f237f41ab11ad6d161bc7239c84dcb631773ccd7de3dfe4b5c267c" +dependencies = [ + "autocfg", + "libm", +] + +[[package]] +name = "remu" +version = "0.1.0" +dependencies = [ + "float-cmp", + "half", + "num-traits", +] diff --git a/tinygrad_repo/extra/remu/Cargo.toml b/tinygrad_repo/extra/remu/Cargo.toml new file mode 100644 index 0000000000..85b4e24450 --- /dev/null +++ b/tinygrad_repo/extra/remu/Cargo.toml @@ -0,0 +1,15 @@ +[package] +name = "remu" +version = "0.1.0" +edition = "2021" +rust-version = "1.80.0" + +[lib] +crate-type = ["cdylib"] + +[dependencies] +half = { version = "2.3.1", features = ["num-traits"] } +num-traits = "0.2.17" + +[dev-dependencies] +float-cmp = "0.9.0" diff --git a/tinygrad_repo/extra/remu/README.md b/tinygrad_repo/extra/remu/README.md new file mode 100644 index 0000000000..3746ea07cd --- /dev/null +++ b/tinygrad_repo/extra/remu/README.md @@ -0,0 +1,80 @@ +## Intro + +Remu is an RDNA3 emulator built to test correctness of RDNA3 code. It is used in [tinygrad's AMD CI](https://github.com/tinygrad/tinygrad). + +Most of the common instructions are implemented, but some formats like IMG are not supported. + +Remu is only for testing correctness of program output, it is not a cycle accurate simulator. + +## Build Locally + +Remu is written in Rust. Make sure you have [Cargo](https://doc.rust-lang.org/cargo/getting-started/installation.html). + +To build the project, run: + +```bash +cargo build --release --manifest-path ./extra/remu/Cargo.toml +``` + +This will produce a binary in the `extra/remu/target/release` directory. + +## Usage with tinygrad + +The latest binaries are released in https://github.com/Qazalin/remu/releases. Alternatively, you can [build locally](#build-locally). + +Tinygrad does not yet output RDNA3 kernels directly. You can either install comgr or use `AMD_LLVM=1` if you have [LLVM@19](https://github.com/tinygrad/tinygrad/blob/e2ed673c946c8f1774d816c75e52a994c2dd8a88/.github/actions/setup-tinygrad/action.yml#L208). + +`PYTHONPATH="." MOCKGPU=1 AMD=1 python test/test_tiny.py TestTiny.test_plus` runs an emulated RDNA3 kernel with Remu. + +Add `DEBUG=6` to see Remu's logs. + +### DEBUG output + +Remu runs each thread one at a time in a nested for loop, see lib.rs. The DEBUG output prints information about the current thread. + +The DEBUG output has 3 sections: + +``` +<------------ 1 ----------> <--- 2 ---> <--------------------------------------- 3 ------------------------------------------> +[0 0 0 ] [0 0 0 ] 0 F4080100 SMEM { op: 2, sdata: 4, sbase: 0, offset: 0, soffset: 124, glc: false, dlc: false } +``` + +#### Section 1: Grid info + +`[gid.x, gid.y, gid.z], [lid.x, lid.y, lid.z]` of the current thread. + +#### Section 2: Wave info + +` ` + +RDNA3 divides threads into chunks of 32. Each thread is assigned to a "lane" from 0-31. + +In Remu, even though all threads run one at a time, each 32 thread chunk (a wave) shares state like SGPR, VGPR, LDS, EXEC mask, etc. +Remu can simulate up to one wave sync instruction. +For more details, see work_group.rs. + +Section 2 can have a green or gray color. + +Green = The thread is actively executing the instruction. + +Gray = The thread has been "turned off" by the EXEC mask, it skips execution of some instructions. (refer to "EXECute Mask" on [page 23](https://www.amd.com/content/dam/amd/en/documents/radeon-tech-docs/instruction-set-architectures/rdna3-shader-instruction-set-architecture-feb-2023_0.pdf#page=23) of ISA docs for more details.) + +To see the colors in action, try running `DEBUG=6 PYTHONPATH="." MOCKGPU=1 AMD=1 python test/test_ops.py TestOps.test_arange_big`. See how only lane 0 writes to global memory: +``` +[255 0 0 ] [0 0 0 ] 0 DC6A0000 FLAT { op: 26, offset: 0, dlc: false, glc: false, slc: false, seg: 2, addr: 8, data: 0, saddr: 0, sve: false, vdst: 0 } +[255 0 0 ] [1 0 0 ] 1 DC6A0000 +[255 0 0 ] [2 0 0 ] 2 DC6A0000 +[255 0 0 ] [3 0 0 ] 3 DC6A0000 +[255 0 0 ] [3 0 0 ] 4 DC6A0000 +``` + +#### Section 3: Decoded Instruction + +This prints the instruction type and all the parsed bitfields. + +Remu output vs llvm-objdump: + +``` +s_load_b64 s[0:1], s[0:1], 0x10 // 00000000160C: F4040000 F8000010 +SMEM { op: 1, sdata: 0, sbase: 0, offset: 16, soffset: 124, glc: false, dlc: false } +``` diff --git a/tinygrad_repo/extra/remu/rustfmt.toml b/tinygrad_repo/extra/remu/rustfmt.toml new file mode 100644 index 0000000000..bc30bf42fb --- /dev/null +++ b/tinygrad_repo/extra/remu/rustfmt.toml @@ -0,0 +1 @@ +max_width = 150 diff --git a/tinygrad_repo/extra/remu/src/helpers.rs b/tinygrad_repo/extra/remu/src/helpers.rs new file mode 100644 index 0000000000..09deca329f --- /dev/null +++ b/tinygrad_repo/extra/remu/src/helpers.rs @@ -0,0 +1,156 @@ +use half::f16; +use num_traits::{float::FloatCore, PrimInt, Unsigned}; + +pub fn bits(word: T, hi: usize, lo: usize) -> T where T: PrimInt + Unsigned { + assert!(hi >= lo); + let width = hi - lo + 1; + (word >> lo) & ((T::one() << width) - T::one()) +} + +pub fn nth(val: u32, pos: usize) -> u32 { + (val >> (31 - pos as u32)) & 1 +} +pub fn f16_lo(val: u32) -> f16 { + f16::from_bits((val & 0xffff) as u16) +} +pub fn f16_hi(val: u32) -> f16 { + f16::from_bits(((val >> 16) & 0xffff) as u16) +} + +pub fn sign_ext(num: u64, bits: usize) -> i64 { + let mut value = num; + let is_negative = (value >> (bits - 1)) & 1 != 0; + if is_negative { + value |= !0 << bits; + } + value as i64 +} + +pub trait IEEEClass { + fn exponent(&self) -> T; +} +impl IEEEClass for f32 { + fn exponent(&self) -> u32 { + (self.to_bits() & 0b01111111100000000000000000000000) >> 23 + } +} +impl IEEEClass for f16 { + fn exponent(&self) -> u16 { + (self.to_bits() & 0b0111110000000000) >> 10 + } +} +impl IEEEClass for f64 { + fn exponent(&self) -> u64 { + (self.to_bits() & 0b0111111111110000000000000000000000000000000000000000000000000000) >> 52 + } +} + +pub trait VOPModifier { + fn negate(&self, pos: usize, modifier: usize) -> T; + fn absolute(&self, pos: usize, modifier: usize) -> T; +} +impl VOPModifier for T +where + T: FloatCore, +{ + fn negate(&self, pos: usize, modifier: usize) -> T { + match (modifier >> pos) & 1 { + 1 => -*self, + _ => *self, + } + } + fn absolute(&self, pos: usize, modifier: usize) -> T { + match (modifier >> pos) & 1 { + 1 => self.abs(), + _ => *self, + } + } +} + +pub fn extract_mantissa(x: f64) -> f64 { + if x.is_infinite() || x.is_nan() { + return x; + } + let bits = x.to_bits(); + let mantissa_mask: u64 = 0x000FFFFFFFFFFFFF; + let bias: u64 = 1023; + let normalized_mantissa_bits = (bits & mantissa_mask) | ((bias - 1) << 52); + return f64::from_bits(normalized_mantissa_bits); +} +pub fn ldexp(x: f64, exp: i32) -> f64 { + x * 2f64.powi(exp) +} + +#[cfg(test)] +mod tests { + use super::*; + #[test] + fn test_extract_mantissa() { + assert_eq!(extract_mantissa(2.0f64), 0.5); + } + + #[test] + fn test_normal_exponent() { + assert_eq!(2.5f32.exponent(), 128); + assert_eq!(1.17549435e-38f32.exponent(), 1); + assert_eq!(f32::INFINITY.exponent(), 255); + assert_eq!(f32::NEG_INFINITY.exponent(), 255); + } + + #[test] + fn test_denormal_exponent() { + assert_eq!(1.0e-40f32.exponent(), 0); + assert_eq!(1.0e-42f32.exponent(), 0); + assert_eq!(1.0e-44f32.exponent(), 0); + assert_eq!((1.17549435e-38f32 / 2.0).exponent(), 0); + } + + #[test] + fn test_normal_exponent_f16() { + assert_eq!(f16::from_f32(3.14f32).exponent(), 16); + assert_eq!(f16::NEG_INFINITY.exponent(), 31); + assert_eq!(f16::INFINITY.exponent(), 31); + } + + #[test] + fn test_neg() { + assert_eq!(0.3_f32.negate(0, 0b001), -0.3_f32); + assert_eq!(0.3_f32.negate(1, 0b010), -0.3_f32); + assert_eq!(0.3_f32.negate(2, 0b100), -0.3_f32); + assert_eq!(0.3_f32.negate(0, 0b110), 0.3_f32); + assert_eq!(0.3_f32.negate(1, 0b010), -0.3_f32); + assert_eq!(0.0_f32.negate(0, 0b001).to_bits(), (-0.0f32).to_bits()); + assert_eq!((-0.0_f32).negate(0, 0b001).to_bits(), 0); + } + + #[test] + fn test_sign_ext() { + assert_eq!(sign_ext(0b000000000000000101000, 21), 40); + assert_eq!(sign_ext(0b111111111111111011000, 21), -40); + assert_eq!(sign_ext(0b000000000000000000000, 21), 0); + assert_eq!(sign_ext(0b111111111111111111111, 21), -1); + assert_eq!(sign_ext(0b111000000000000000000, 21), -262144); + assert_eq!(sign_ext(0b000111111111111111111, 21), 262143); + assert_eq!(sign_ext(7608, 13), -584); + } +} + +use std::sync::LazyLock; +pub static DEBUG: LazyLock = LazyLock::new(|| std::env::var("DEBUG").map(|v| v.parse::().unwrap_or(0) >= 6).unwrap_or(false)); + +pub fn colored(st:&str, color:&str) -> String { + let ansi_code = match color { + "green" => format!("\x1b[{};2;39;176;139m", 38), + "gray" => format!("\x1b[{};2;169;169;169m", 38), + _ => format!("\x1b[{};2;255;255;255m", 38), + }; + format!("{}{}{}", ansi_code, st, "\x1b[0m") +} + +#[macro_export] +macro_rules! todo_instr { + ($x:expr) => {{ + println!("{:08X}", $x); + Err(1) + }}; +} diff --git a/tinygrad_repo/extra/remu/src/lib.rs b/tinygrad_repo/extra/remu/src/lib.rs new file mode 100644 index 0000000000..74b972bf52 --- /dev/null +++ b/tinygrad_repo/extra/remu/src/lib.rs @@ -0,0 +1,32 @@ +use crate::work_group::WorkGroup; +use std::os::raw::c_char; +use std::slice; +mod helpers; +mod rdna3; +mod state; +mod thread; +mod work_group; + +#[no_mangle] +pub extern "C" fn run_asm(lib: *const c_char, lib_sz: u32, gx: u32, gy: u32, gz: u32, lx: u32, ly: u32, lz: u32, args_ptr: *const u64) -> i32 { + if lib.is_null() || (lib_sz % 4) != 0 { + panic!("Pointer is null or length is not properly aligned to 4 bytes"); + } + let kernel = unsafe { slice::from_raw_parts(lib as *const u32, (lib_sz / 4) as usize).to_vec() }; + let dispatch_dim = match (gy != 1, gz != 1) { + (true, true) => 3, + (true, false) => 2, + _ => 1, + }; + for gx in 0..gx { + for gy in 0..gy { + for gz in 0..gz { + let mut wg = WorkGroup::new(dispatch_dim, [gx, gy, gz], [lx, ly, lz], &kernel, args_ptr); + if let Err(err) = wg.exec_waves() { + return err; + } + } + } + } + 0 +} diff --git a/tinygrad_repo/extra/remu/src/rdna3.rs b/tinygrad_repo/extra/remu/src/rdna3.rs new file mode 100644 index 0000000000..83ce61e3d6 --- /dev/null +++ b/tinygrad_repo/extra/remu/src/rdna3.rs @@ -0,0 +1,223 @@ +use crate::helpers::{bits, sign_ext}; + +#[derive(Debug, PartialEq)] +pub enum Instruction { + SOP2 { op: u8, ssrc0: u8, ssrc1: u8, sdst: u8 }, + SOP1 { op: u8, ssrc0: u8, sdst: u8 }, + SOPK { op: u8, simm16: i16, sdst: u8 }, + SOPP { op: u8, simm16: i16 }, + SOPC { op: u8, ssrc0: u8, ssrc1: u8 }, + + SMEM { op: u8, sdata: u8, sbase: u8, offset: i32, soffset: u8, glc: bool, dlc: bool }, + + VOP1 { op: u8, vdst: u8, src: u16 }, + VOP2 { op: u8, vdst: u8, vsrc: u8, src: u16 }, + VOPC { op: u8, vsrc: u8, src: u16 }, + VOP3 { op: u32, opsel: u8, cm: bool, abs: u8, vdst: u8, neg: u8, omod: u8, src2: u16, src1: u16, src0: u16 }, + VOP3SD { op: u32, cm: bool, sdst: u8, vdst: u8, neg: u8, omod: u8, src2: u16, src1: u16, src0: u16 }, + VOP3P { op: u8, vdst: u8, neg_hi: u8, opsel: u8, opsel_hi: u8, opsel_hi2: bool, cm: bool, src2: u16, src1: u16, src0: u16, neg: u8 }, + VOPD { opx: u8, opy: u8, vdstx: u8, vdsty: u8, vsrcx1: u8, vsrcy1: u8, srcx0: u16, srcy0: u16 }, + + DS { op: u8, gds: bool, offset1: u8, offset0: u8, vdst: u8, data1: u8, data0: u8, addr: u8 }, + + FLAT { op: u8, offset: u16, dlc: bool, glc: bool, slc: bool, seg: u8, addr: u8, data: u8, saddr: u8, sve: bool, vdst: u8 } +} + +const VOP3SD_OPS: [u32; 7] = [764, 765, 766, 767, 768, 769, 770]; + +pub fn decode(word:u32, word1:Option<&u32>) -> Instruction { + match bits(word, 31, 30) { + 0b11 => { + let word = (*word1.unwrap() as u64) << 32 | (word as u64); + match bits(word, 29, 26) { + 0b1101 => { + let sbase = (bits(word, 5, 0) as u8) << 1; + let sdata = bits(word, 12, 6) as u8; + let dlc = bits(word, 13, 13) != 0; + let glc = bits(word, 14, 14) != 0; + let op = bits(word, 25, 18) as u8; + let offset = sign_ext(bits(word, 52, 32), 21) as i32; + let soffset = bits(word, 63, 57) as u8; + Instruction::SMEM { sbase, sdata, dlc, glc, op, offset, soffset } + } + 0b0101 => { + let op = bits(word, 25, 16) as u32; + let vdst = bits(word, 7, 0) as u8; + let cm = bits(word, 15, 15) != 0; + let src0 = bits(word, 40, 32) as u16; + let src1 = bits(word, 49, 41) as u16; + let src2 = bits(word, 58, 50) as u16; + let omod = bits(word, 60, 59) as u8; + let neg = bits(word, 63, 61) as u8; + if VOP3SD_OPS.contains(&op) { + let sdst = bits(word, 14, 8) as u8; + Instruction::VOP3SD { op, vdst, sdst, cm, src0, src1, src2, omod, neg } + } else { + let abs = bits(word, 10, 8) as u8; + let opsel = bits(word, 14, 11) as u8; + Instruction::VOP3 { opsel, cm, abs, vdst, neg, omod, src2, src1, src0, op } + } + } + 0b0011 => { + let op = bits(word, 22, 16) as u8; + let vdst = bits(word, 7, 0) as u8; + let neg_hi = bits(word, 10, 8) as u8; + let opsel = bits(word, 13, 11) as u8; + let opsel_hi2 = bits(word, 14, 14) != 0; + let cm = bits(word, 15, 15) != 0; + let src0 = bits(word, 40, 32) as u16; + let src1 = bits(word, 49, 41) as u16; + let src2 = bits(word, 58, 50) as u16; + let opsel_hi = bits(word, 60, 59) as u8; + let neg = bits(word, 63, 61) as u8; + Instruction::VOP3P { op, vdst, neg_hi, opsel, opsel_hi, opsel_hi2, cm, src0, src1, src2, neg } + } + 0b0110 => { + let offset0 = bits(word, 7, 0) as u8; + let offset1 = bits(word, 15, 8) as u8; + let gds = bits(word, 17, 17) != 0; + let op = bits(word, 25, 18) as u8; + let addr = bits(word, 39, 32) as u8; + let data0 = bits(word, 47, 40) as u8; + let data1 = bits(word, 55, 48) as u8; + let vdst = bits(word, 63, 56) as u8; + Instruction::DS { op, gds, offset1, offset0, vdst, data1, data0, addr } + } + 0b0111 => { + let offset = bits(word, 12, 0) as u16; + let dlc = bits(word, 13, 13) != 0; + let glc = bits(word, 14, 14) != 0; + let slc = bits(word, 15, 15) != 0; + let seg = bits(word, 17, 16) as u8; + let op = bits(word, 24, 18) as u8; + let addr = bits(word, 39, 32) as u8; + let data = bits(word, 47, 40) as u8; + let saddr = bits(word, 54, 48) as u8; + let sve = bits(word, 55, 55) != 0; + let vdst = bits(word, 63, 56) as u8; + Instruction::FLAT { offset, dlc, glc, slc, seg, op, addr, data, saddr, sve, vdst } + }, + 0b0010 => { + let srcx0 = bits(word, 8, 0) as u16; + let vsrcx1 = bits(word, 16, 9) as u8; + let opy = bits(word, 21, 17) as u8; + let opx = bits(word, 25, 22) as u8; + let srcy0 = bits(word, 40, 32) as u16; + let vsrcy1 = bits(word, 48, 41) as u8; + let vdsty = bits(word, 55, 49) as u8; + let vdstx = bits(word, 63, 56) as u8; + Instruction::VOPD { opx, opy, vdstx, vdsty, vsrcx1, vsrcy1, srcx0, srcy0 } + } + _ => todo!(), + } + } + 0b10 => { + let ssrc0 = bits(word, 7, 0) as u8; + let ssrc1 = bits(word, 15, 8) as u8; + let simm16 = word as i16; + let sdst = bits(word, 22, 16) as u8; + match bits(word, 29, 23) { + 0b1111101 => Instruction::SOP1 { ssrc0, sdst, op: bits(word, 15, 8) as u8 }, + 0b1111110 => Instruction::SOPC { ssrc0, ssrc1, op: bits(word, 22, 16) as u8 }, + 0b1111111 => Instruction::SOPP { simm16, op: bits(word, 22, 16) as u8 }, + _ => { + match bits(word, 29, 28) { + 0b11 => Instruction::SOPK { simm16, sdst, op: bits(word, 27, 23) as u8 }, + _ => Instruction::SOP2 { ssrc0, ssrc1, sdst, op: bits(word, 29, 23) as u8 } + } + } + } + } + _ => { + let vdst = bits(word, 24, 17) as u8; + let src = bits(word, 8, 0) as u16; + let vsrc = bits(word, 16, 9) as u8; + match bits(word, 30, 25) { + 0b111110 => Instruction::VOPC { vsrc, src, op: bits(word, 24, 17) as u8 }, + 0b111111 => Instruction::VOP1 { vdst, src, op: vsrc }, + _ => Instruction::VOP2 { vdst, vsrc, src, op: bits(word, 30, 25) as u8 }, + } + }, + } +} + +#[cfg(test)] +mod test_rdna3 { + use super::*; + + use std::process::{Stdio, Command}; + use std::io::{Result, Write}; + + const LLVM_ARGS: &[&str; 3] = &["--arch=amdgcn", "--mcpu=gfx1100", "--triple=amdgcn-amd-amdhsa"]; + const OFFSET_PRG: usize = 16; + const NULL: u8 = 124; + + fn llvm_assemble(asm: &str) -> Result> { + let mut proc = Command::new("llvm-mc").args(LLVM_ARGS).args(["-filetype=obj", "-o", "-"]).stdin(Stdio::piped()).stdout(Stdio::piped()).spawn()?; + proc.stdin.as_mut().unwrap().write_all(asm.as_bytes())?; + let out = proc.wait_with_output()?; + match out.status.success() { + true => Ok(out.stdout), + false => Err(std::io::Error::new(std::io::ErrorKind::Other, "llvm-mc err")), + } + } + + fn llvm_disassemble(code: &Vec) -> Result { + let mut proc = Command::new("llvm-objdump").args(LLVM_ARGS).args(["--disassemble", "-"]).stdin(Stdio::piped()).stdout(Stdio::piped()).spawn()?; + proc.stdin.as_mut().unwrap().write_all(code)?; + let out = proc.wait_with_output()?; + match out.status.success() { + true => Ok(String::from_utf8(out.stdout).unwrap()), + false => Err(std::io::Error::new(std::io::ErrorKind::Other, "llvm-objdump err")), + } + } + + fn test_decode(asm: &str) -> Instruction { + let lib = llvm_assemble(asm).unwrap(); + println!("{}", llvm_disassemble(&lib).unwrap()); + let stream: Vec = lib.chunks_exact(4).map(|chunk| u32::from_le_bytes(chunk.try_into().unwrap())).skip(OFFSET_PRG).collect(); + decode(stream[0], stream.get(1)) + } + + #[test] + fn test_decode_smem() { + assert_eq!(test_decode("s_load_b128 s[4:7], s[0:1], null"), Instruction::SMEM { op: 2, sdata: 4, sbase: 0, offset: 0, soffset: NULL, glc: false, dlc: false }); + assert_eq!(test_decode("s_load_b32 s10, s[0:1], 0xc"), Instruction::SMEM { op: 0, sdata: 10, sbase: 0, offset: 0xc, soffset: NULL, glc: false, dlc: false }); + assert_eq!(test_decode("s_load_b32 s0, s[4:5], s6"), Instruction::SMEM { op: 0, sdata: 0, sbase: 4, offset: 0, soffset: 6, glc: false, dlc: false }); + assert_eq!(test_decode("s_load_b32 s0, s[4:5], glc dlc"), Instruction::SMEM { op: 0, sdata: 0, sbase: 4, offset: 0, soffset: NULL, glc: true, dlc: true }); + assert_eq!(test_decode("s_load_b32 s0, s[4:5], glc"), Instruction::SMEM { op: 0, sdata: 0, sbase: 4, offset: 0, soffset: NULL, glc: true, dlc: false }); + assert_eq!(test_decode("s_load_b32 s0, s[4:5], -20"), Instruction::SMEM { op: 0, sdata: 0, sbase: 4, offset: -20, soffset: NULL, glc: false, dlc: false }); + assert_eq!(test_decode("s_load_b32 s0, s[4:5], -1048576"), Instruction::SMEM { op: 0, sdata: 0, sbase: 4, offset: -1048576, soffset: NULL, glc: false, dlc: false }); + } + + #[test] + fn test_decode_salu() { + assert_eq!(test_decode("s_add_u32 s1 s2 s3"), Instruction::SOP2 { op: 0, ssrc0: 2, ssrc1: 3, sdst: 1 }); + assert_eq!(test_decode("s_add_u32 vcc_hi exec_lo vcc_lo"), Instruction::SOP2 { op: 0, ssrc0: 126, ssrc1: 106, sdst: 107 }); + assert_eq!(test_decode("s_mov_b32 s1 -0.5"), Instruction::SOP1 { op: 0, ssrc0: 241, sdst: 1 }); + assert_eq!(test_decode("s_cmpk_eq_i32 s0 -30"), Instruction::SOPK { op: 3, sdst: 0, simm16: -30 }); + assert_eq!(test_decode("s_cmpk_eq_u32 s0 65535"), Instruction::SOPK { op: 9, sdst: 0, simm16: -1 }); + assert_eq!(test_decode("s_cmp_ge_i32 s1 s2"), Instruction::SOPC { op: 3, ssrc0: 1, ssrc1: 2 }); + } + + #[test] + fn test_decode_valu_e32() { + assert_eq!(test_decode("v_mov_b32 v0, v0"), Instruction::VOP1 { op: 1, vdst: 0, src: 256 }); + assert_eq!(test_decode("v_mov_b32 v0, s0"), Instruction::VOP1 { op: 1, vdst: 0, src: 0 }); + assert_eq!(test_decode("v_cmp_t_f32 v1, v0"), Instruction::VOPC { op: 31, vsrc: 0, src: 257 }); + } + + #[test] + fn test_decode_valu_e64() { + assert_eq!(test_decode("v_log_f32_e64 v2, |v0|"), Instruction::VOP3 { op: 423, vdst: 2, src0: 256, src1: 0, src2: 0, abs: 0b001, neg: 0, opsel: 0, omod: 0, cm: false }); + assert_eq!(test_decode("v_div_scale_f32 v2, s1, v0, v1, v2"), Instruction::VOP3SD { op: 764, cm: false, vdst: 2, sdst: 1, src0: 256, src1: 257, src2: 258, omod: 0, neg: 0 }); + assert_eq!(test_decode("v_pk_add_i16 v1, v0, v2"), Instruction::VOP3P { op: 2, vdst: 1, neg_hi: 0, opsel: 0, opsel_hi: 3, opsel_hi2: true, cm: false, src2: 0, src1: 258, src0: 256, neg: 0 }); + } + + #[test] + fn test_decode_ds() { + assert_eq!(test_decode("ds_add_u32 v2, v4 offset:16"), Instruction::DS { op: 0, gds: false, offset1: 0, offset0: 0x10, vdst: 0, data1: 0, data0: 4, addr: 2 }); + assert_eq!(test_decode("ds_store_b32 v0, v1, offset: 0x04 gds"), Instruction::DS { op: 13, gds: true, offset1: 0, offset0: 0x04, vdst: 0, data1: 0, data0: 1, addr: 0 }); + assert_eq!(test_decode("ds_load_u8 v1, v0 offset:16"), Instruction::DS { op: 58, gds: false, offset1: 0, offset0: 16, vdst: 1, data1: 0, data0: 0, addr: 0 }); + } +} diff --git a/tinygrad_repo/extra/remu/src/state.rs b/tinygrad_repo/extra/remu/src/state.rs new file mode 100644 index 0000000000..bd0971b071 --- /dev/null +++ b/tinygrad_repo/extra/remu/src/state.rs @@ -0,0 +1,254 @@ +use std::ops::{Index, IndexMut}; + +pub trait Register { + fn read64(&self, idx: usize) -> u64; + fn write64(&mut self, idx: usize, addr: u64); +} +impl Register for T where T: Index + IndexMut { + fn read64(&self, idx: usize) -> u64 { + let lsb = self[idx] as u64; + let msb = self[idx + 1] as u64; + (msb << 32) | lsb + } + + fn write64(&mut self, idx: usize, value: u64) { + self[idx] = (value & 0xffffffff) as u32; + self[idx + 1] = ((value & (0xffffffff << 32)) >> 32) as u32; + } +} + +#[derive(Debug, Clone)] +pub struct VGPR { + values: [[u32; 256]; 32], + pub default_lane: Option, +} +impl Index for VGPR { + type Output = u32; + fn index(&self, index: usize) -> &Self::Output { + &self.values[self.default_lane.unwrap()][index] + } +} +impl IndexMut for VGPR { + fn index_mut(&mut self, index: usize) -> &mut Self::Output { + &mut self.values[self.default_lane.unwrap()][index] + } +} +impl VGPR { + pub fn new() -> Self { + VGPR { + values: [[0; 256]; 32], + default_lane: None, + } + } + pub fn get_lane(&self, lane: usize) -> [u32; 256] { + *self.values.get(lane).unwrap() + } + pub fn get_lane_mut(&mut self, lane: usize) -> &mut [u32; 256] { + self.values.get_mut(lane).unwrap() + } +} + +pub trait Value { + fn mut_hi16(&mut self, val: u16); + fn mut_lo16(&mut self, val: u16); +} +impl Value for u32 { + fn mut_hi16(&mut self, val: u16) { + *self = ((val as u32) << 16) | (*self as u16 as u32); + } + fn mut_lo16(&mut self, val: u16) { + *self = ((((*self & (0xffff << 16)) >> 16) as u32) << 16) | val as u32; + } +} + +#[derive(Debug, Clone, Copy)] +pub struct WaveValue { + pub value: u32, + pub warp_size: usize, + pub default_lane: Option, + pub mutations: Option<[bool; 32]>, +} +impl WaveValue { + pub fn new(value: u32, warp_size: usize) -> Self { + Self { + value, + warp_size, + default_lane: None, + mutations: None, + } + } + pub fn read(&self) -> bool { + (self.value >> self.default_lane.unwrap()) & 1 == 1 + } + pub fn set_lane(&mut self, value: bool) { + if self.mutations.is_none() { + self.mutations = Some([false; 32]) + } + self.mutations.as_mut().unwrap()[self.default_lane.unwrap()] = value; + } + pub fn apply_muts(&mut self) { + self.value = 0; + for lane in 0..self.warp_size { + if self.mutations.unwrap()[lane] { + self.value |= 1 << lane; + } + } + } +} + +#[derive(Clone, Debug)] +pub struct VecDataStore { + pub data: Vec, +} + +impl VecDataStore { + pub fn new() -> Self { + Self { data: Vec::new() } + } + pub fn write(&mut self, addr: usize, val: u32) { + if addr + 4 >= self.data.len() { + self.data.resize(self.data.len() + addr + 5, 0); + } + self.data[addr..addr + 4].iter_mut().enumerate().for_each(|(i, x)| { + *x = val.to_le_bytes()[i]; + }); + } + pub fn write64(&mut self, addr: usize, val: u64) { + self.write(addr, (val & 0xffffffff) as u32); + self.write(addr + 4, ((val & (0xffffffff << 32)) >> 32) as u32); + } + pub fn read(&self, addr: usize) -> u32 { + let mut bytes: [u8; 4] = [0; 4]; + bytes.copy_from_slice(&self.data[addr + 0..addr + 4]); + u32::from_le_bytes(bytes) + } + pub fn read64(&mut self, addr: usize) -> u64 { + let lsb = self.read(addr); + let msb = self.read(addr + 4); + ((msb as u64) << 32) | lsb as u64 + } +} + +#[cfg(test)] +mod test_state { + use super::*; + + #[test] + fn test_wave_value() { + let mut val = WaveValue::new(0b11000000000000011111111111101110, 32); + val.default_lane = Some(0); + assert!(!val.read()); + val.default_lane = Some(31); + assert!(val.read()); + } + + #[test] + fn test_wave_value_small() { + let mut val = WaveValue::new(0, 1); + val.default_lane = Some(0); + assert!(!val.read()); + assert_eq!(val.value, 0); + val.set_lane(true); + val.apply_muts(); + assert!(val.read()); + assert_eq!(val.value, 1); + } + + #[test] + fn test_wave_value_small_alt() { + let mut val = WaveValue::new(0, 2); + val.default_lane = Some(0); + assert!(!val.read()); + assert_eq!(val.value, 0); + val.set_lane(true); + val.apply_muts(); + assert!(val.read()); + assert_eq!(val.value, 1); + } + + #[test] + fn test_wave_value_exec() { + let warp_size = 32; + let val = WaveValue::new(u32::MAX, warp_size); + assert_eq!(val.value, u32::MAX); + let warp_size = 3; + let val = WaveValue::new((1 << warp_size) - 1, warp_size); + assert_eq!(val.value, 7) + } + + #[test] + fn test_wave_value_toggle_one() { + let warp_size = 2; + let mut val = WaveValue::new(0b11, warp_size); + // 0 + val.default_lane = Some(0); + val.set_lane(false); + // 1 + val.default_lane = Some(1); + val.set_lane(true); + val.apply_muts(); + assert_eq!(val.value, 2); + } + + #[test] + fn test_wave_value_mutate_small() { + let mut val = WaveValue::new(0, 2); + val.default_lane = Some(0); + assert!(!val.read()); + assert_eq!(val.value, 0); + val.set_lane(true); + val.apply_muts(); + assert!(val.read()); + assert_eq!(val.value, 1); + } + + #[test] + fn test_wave_value_mutations() { + let mut val = WaveValue::new(0b10001, 32); + val.default_lane = Some(0); + val.set_lane(false); + assert!(val.mutations.unwrap().iter().all(|x| !x)); + val.default_lane = Some(1); + val.set_lane(true); + assert_eq!(val.value, 0b10001); + assert_eq!( + val.mutations, + Some([ + false, true, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, + false, false, false, false, false, false, false, false, false, false, false, false, false, + ]) + ); + + val.apply_muts(); + assert_eq!(val.value, 0b10); + } + + #[test] + fn test_write16() { + let mut vgpr = VGPR::new(); + vgpr.default_lane = Some(0); + vgpr[0] = 0b11100000000000001111111111111111; + vgpr[0].mut_lo16(0b1011101111111110); + assert_eq!(vgpr[0], 0b11100000000000001011101111111110); + } + + #[test] + fn test_write16hi() { + let mut vgpr = VGPR::new(); + vgpr.default_lane = Some(0); + vgpr[0] = 0b11100000000000001111111111111111; + vgpr[0].mut_hi16(0b1011101111111110); + assert_eq!(vgpr[0], 0b10111011111111101111111111111111); + } + + #[test] + fn test_vgpr() { + let mut vgpr = VGPR::new(); + vgpr.default_lane = Some(0); + vgpr[0] = 42; + vgpr.default_lane = Some(10); + vgpr[0] = 10; + assert_eq!(vgpr.get_lane(0)[0], 42); + assert_eq!(vgpr.get_lane(10)[0], 10); + } +} diff --git a/tinygrad_repo/extra/remu/src/thread.rs b/tinygrad_repo/extra/remu/src/thread.rs new file mode 100644 index 0000000000..4cb84a561d --- /dev/null +++ b/tinygrad_repo/extra/remu/src/thread.rs @@ -0,0 +1,3731 @@ +use crate::helpers::{extract_mantissa, f16_hi, f16_lo, ldexp, nth, sign_ext, IEEEClass, VOPModifier}; +use crate::helpers::DEBUG; +use crate::state::{Register, Value, VecDataStore, WaveValue, VGPR}; +use crate::todo_instr; +use half::{bf16, f16}; +use crate::rdna3::{Instruction, decode}; +use num_traits::Float; + +pub const SGPR_COUNT: usize = 128; +pub const VCC: usize = 106; +pub const EXEC: usize = 126; +pub const NULL_SRC: usize = 124; +pub const SGPR_SRC: usize = 105; + +const VGPR_COUNT: usize = 256; +const SIMM_SRC: usize = 255; + +pub const END_PRG: u32 = 0xbfb00000; + +pub struct Thread<'a> { + pub scalar_reg: &'a mut [u32; SGPR_COUNT], + pub scc: &'a mut u32, // SCC is physically an sgpr, unclear which one + + pub vec_reg: &'a mut VGPR, + pub vcc: &'a mut WaveValue, + pub exec: &'a mut WaveValue, + + pub lds: &'a mut VecDataStore, + pub sds: &'a mut VecDataStore, + + pub pc_offset: usize, + pub stream: Vec, + pub simm: Option, + pub sgpr_co: &'a mut Option<(usize, WaveValue)>, + pub warp_size: usize, + pub scalar: bool, +} + +impl<'a> Thread<'a> { + pub fn interpret(&mut self) -> Result<(), i32> { + let instruction = self.stream[self.pc_offset]; + let decoded = decode(self.stream[self.pc_offset], self.stream.get(self.pc_offset+1)); + if *DEBUG { + print!("{:?}", decoded); + } + if let Instruction::SMEM { sbase, sdata, op, offset, soffset, .. } = decoded { + let _ = self.u64_instr(); + let soffset: u32 = self.val(soffset as usize); + + // TODO: refactor vcc_lo to store in scalar register 106 + let base_addr = match sbase as usize { + VCC => ((self.scalar_reg[107] as u64) << 32) | self.vcc.value as u64, + s => self.scalar_reg.read64(s), + }; + let addr = (base_addr as i64 + offset as i64 + soffset as i64) as u64; + + match op { + 0..=4 => (0..2_usize.pow(op as u32)).for_each(|i| { + let ret = unsafe { *((addr + (4 * i as u64)) as *const u32) }; + self.write_to_sdst(sdata as usize + i, ret); + }), + _ => todo_instr!(instruction)?, + }; + self.scalar = true; + } + else if let Instruction::SOP1 { ssrc0, op, sdst } = decoded { + let src = ssrc0 as usize; + let sdst = sdst as usize; + + match op { + 1 => { + let s0 = self.val(src); + let ret = match op { + 1 => s0, + _ => todo_instr!(instruction)?, + }; + self.scalar_reg.write64(sdst as usize, ret); + } + _ => { + let s0 = self.val(src); + let ret = match op { + 0 => s0, + 10 => self.clz_i32_u32(s0), + 12 => self.cls_i32(s0), + 4 => s0.reverse_bits(), + 14 => s0 as i8 as i32 as u32, + 15 => s0 as i16 as i32 as u32, + 16 | 18 => { + let sdst: u32 = self.val(sdst as usize); + if op == 16 { + sdst & !(1 << (s0 & 0x1f)) + } else { + sdst | (1 << (s0 & 0x1f)) + } + } + 21 => { + let s0 = s0 as i32; + let ret = s0.abs(); + *self.scc = (ret != 0) as u32; + ret as u32 + } + 30 => { + let ret = !s0; + *self.scc = (ret != 0) as u32; + ret + } + 32 | 34 | 48 => { + let saveexec = self.exec.value; + self.exec.value = match op { + 32 => s0 & saveexec, + 34 => s0 | saveexec, + 48 => s0 & !saveexec, + _ => todo_instr!(instruction)?, + }; + *self.scc = (self.exec.value != 0) as u32; + saveexec + } + _ => todo_instr!(instruction)?, + }; + + self.write_to_sdst(sdst, ret); + } + }; + self.scalar = true; + } + else if let Instruction::SOPC { ssrc0, ssrc1, op } = decoded { + let s0 = ssrc0 as usize; + let s1 = ssrc1 as usize; + + fn scmp(s0: T, s1: T, offset: u8, op: u8) -> bool + where + T: PartialOrd + PartialEq, + { + match op - offset { + 0 => s0 == s1, + 1 => s0 != s1, + 2 => s0 > s1, + 3 => s0 >= s1, + 4 => s0 < s1, + _ => s0 <= s1, + } + } + *self.scc = match op { + 0..=5 => { + let (s0, s1): (u32, u32) = (self.val(s0), self.val(s1)); + scmp(s0 as i32, s1 as i32, 0, op) + } + 6..=11 => { + let (s0, s1): (u32, u32) = (self.val(s0), self.val(s1)); + scmp(s0, s1, 6, op) + } + 12 => { + let (s0, s1): (u32, u32) = (self.val(s0), self.val(s1)); + s0 & (1 << (s1 & 0x1F)) == 0 + } + 13 => { + let (s0, s1): (u32, u32) = (self.val(s0), self.val(s1)); + s0 & (1 << (s1 & 0x1F)) == 1 + } + 16 | 17 => { + let (s0, s1): (u64, u64) = (self.val(s0), self.val(s1)); + scmp(s0, s1, 16, op) + } + _ => todo_instr!(instruction)?, + } as u32; + self.scalar = true; + } + else if let Instruction::SOPP { simm16, op } = decoded { + + match op { + 32..=42 => { + let should_jump = match op { + 32 => true, + 33 => *self.scc == 0, + 34 => *self.scc == 1, + 35 => self.vcc.value == 0, + 36 => self.vcc.value != 0, + 37 => self.exec.value == 0, + 38 => self.exec.value != 0, + _ => todo_instr!(instruction)?, + }; + if should_jump { + self.pc_offset = (self.pc_offset as i64 + simm16 as i64) as usize; + } + } + _ => todo_instr!(instruction)?, + }; + self.scalar = true; + } + else if let Instruction::SOPK { simm16, sdst, op } = decoded { + let simm = simm16 as u16; + let sdst = sdst as usize; + let s0: u32 = self.val(sdst); + + match op { + 0 => self.write_to_sdst(sdst, simm as i16 as i32 as u32), + 3..=8 => { + let s1 = simm as i16 as i64; + let s0 = s0 as i32 as i64; + *self.scc = match op { + 3 => s0 == s1, + 4 => s0 != s1, + 5 => s0 > s1, + 7 => s0 < s1, + _ => todo_instr!(instruction)?, + } as u32 + } + 9..=14 => { + let s1 = simm as u16 as u32; + *self.scc = match op { + 9 => s0 == s1, + 10 => s0 != s1, + 11 => s0 > s1, + 12 => s0 >= s1, + 13 => s0 < s1, + 14 => s0 <= s1, + _ => todo_instr!(instruction)?, + } as u32 + } + 15 => { + let temp = s0 as i32; + let simm16 = simm as i16; + let dest = (temp as i64 + simm16 as i64) as i32; + self.write_to_sdst(sdst, dest as u32); + let temp_sign = ((temp >> 31) & 1) as u32; + let simm_sign = ((simm16 >> 15) & 1) as u32; + let dest_sign = ((dest >> 31) & 1) as u32; + *self.scc = ((temp_sign == simm_sign) && (temp_sign != dest_sign)) as u32; + } + 16 => { + let simm16 = simm as i16; + let ret = (s0 as i32 * simm16 as i32) as u32; + self.write_to_sdst(sdst, ret); + } + _ => todo_instr!(instruction)?, + }; + self.scalar = true; + } + else if let Instruction::SOP2 { ssrc0, ssrc1, sdst, op } = decoded { + let s0 = ssrc0 as usize; + let s1 = ssrc1 as usize; + let sdst = sdst as usize; + + match op { + 23 | 25 | 27 => { + let (s0, s1): (u64, u64) = (self.val(s0), self.val(s1)); + let ret = match op { + 23 => s0 & s1, + 25 => s0 | s1, + 27 => s0 ^ s1, + _ => todo_instr!(instruction)?, + }; + self.scalar_reg.write64(sdst as usize, ret); + *self.scc = (ret != 0) as u32; + } + 9 | 13 | 11 | 40 | 41 => { + let (s0, s1): (u64, u32) = (self.val(s0), self.val(s1)); + let ret = match op { + 9 => { + let ret = s0 << (s1 & 0x3f); + (ret, Some(ret != 0)) + } + 11 => { + let ret = s0 >> (s1 & 0x3f); + (ret as u64, Some(ret != 0)) + } + 13 => { + let ret = (s0 as i64) >> (s1 & 0x3f); + (ret as u64, Some(ret != 0)) + } + 40 => { + let ret = (s0 >> (s1 & 0x3f)) & ((1 << ((s1 >> 16) & 0x7f)) - 1); + (ret as u64, Some(ret != 0)) + } + 41 => { + let s0 = s0 as i64; + let mut ret = (s0 >> (s1 & 0x3f)) & ((1 << ((s1 >> 16) & 0x7f)) - 1); + let shift = 64 - ((s1 >> 16) & 0x7f); + ret = (ret << shift) >> shift; + (ret as u64, Some(ret != 0)) + } + _ => todo_instr!(instruction)?, + }; + self.scalar_reg.write64(sdst as usize, ret.0); + if let Some(val) = ret.1 { + *self.scc = val as u32 + } + } + _ => { + let (s0, s1): (u32, u32) = (self.val(s0), self.val(s1)); + let ret = match op { + 0 | 4 => { + let (s0, s1) = (s0 as u64, s1 as u64); + let ret = match op { + 0 => s0 + s1, + 4 => s0 + s1 + *self.scc as u64, + _ => todo_instr!(instruction)?, + }; + (ret as u32, Some(ret >= 0x100000000)) + } + 1 => (s0 - s1, Some(s1 > s0)), + 5 => (s0 - s1 - *self.scc, Some((s1 as u64 + *self.scc as u64) > s0 as u64)), + 2 | 3 => { + let s0 = s0 as i32 as i64; + let s1 = s1 as i32 as i64; + let ret = match op { + 2 => s0 + s1, + 3 => s0 - s1, + _ => todo_instr!(instruction)?, + }; + let overflow = (nth(s0 as u32, 31) == nth(s1 as u32, 31)) && (nth(s0 as u32, 31) != nth(ret as u32, 31)); + + (ret as i32 as u32, Some(overflow)) + } + (8..=17) => { + let s1 = s1 & 0x1f; + let ret = match op { + 8 => s0 << s1, + 10 => s0 >> s1, + 12 => ((s0 as i32) >> (s1 as i32)) as u32, + _ => todo_instr!(instruction)?, + }; + (ret, Some(ret != 0)) + } + (18..=21) => { + let scc = match op { + 18 => (s0 as i32) < (s1 as i32), + 19 => s0 < s1, + 20 => (s0 as i32) > (s1 as i32), + 21 => s0 > s1, + _ => todo_instr!(instruction)?, + }; + let ret = match scc { + true => s0, + false => s1, + }; + (ret, Some(scc)) + } + (22..=26) | 34 | 36 => { + let ret = match op { + 22 => s0 & s1, + 24 => s0 | s1, + 26 => s0 ^ s1, + 34 => s0 & !s1, + 36 => s0 | !s1, + _ => todo_instr!(instruction)?, + }; + (ret, Some(ret != 0)) + } + 38 => { + let ret = (s0 >> (s1 & 0x1f)) & ((1 << ((s1 >> 16) & 0x7f)) - 1); + (ret, Some(ret != 0)) + } + 39 => { + let s0 = s0 as i32; + let mut ret = (s0 >> (s1 & 0x1f)) & ((1 << ((s1 >> 16) & 0x1f)) - 1); + let shift = 32 - ((s1 >> 16) & 0x7f); + ret = (ret << shift) >> shift; + (ret as u32, Some(ret != 0)) + } + 44 => (((s0 as i32) * (s1 as i32)) as u32, None), + 45 => (((s0 as u64) * (s1 as u64) >> 32) as u32, None), + 46 => ((((s0 as i32 as i64 * s1 as i32 as i64) as u64) >> 32u64) as i32 as u32, None), + 48 => match *self.scc != 0 { + true => (s0, None), + false => (s1, None), + }, + 50..=53 => { + let (s0, s1) = match op { + 50 => (s0 as u16, s1 as u16), + 51 => (s0 as u16, (s1 >> 16) as u16), + 52 => ((s0 >> 16) as u16, (s1 >> 16) as u16), + _ => ((s0 >> 16) as u16, s1 as u16), + }; + (((s1 as u32) << 16) | (s0 as u32), None) + } + _ => todo_instr!(instruction)?, + }; + + self.write_to_sdst(sdst, ret.0); + if let Some(val) = ret.1 { + *self.scc = val as u32 + } + } + }; + self.scalar = true; + } + // vopp + else if instruction >> 24 == 0b11001100 { + let instr = self.u64_instr(); + let vdst = (instr & 0xff) as usize; + let clmp = (instr >> 15) & 0x1; + assert_eq!([clmp], [0]); + let op = (instr >> 16) & 0x7f; + + let mut src = |x: usize| -> (u16, u16, u32) { + let val: u32 = self.val(x); + match x { + 255 => { + let val_lo: u16 = self.val(x); + (val_lo, val_lo, val) + } + (240..=247) => { + let val_lo: u16 = self.val(x); + (val_lo, f16::from_bits(0).to_bits(), val) + } + _ => ((val & 0xffff) as u16, ((val >> 16) & 0xffff) as u16, val), + } + }; + + let s = [32, 41, 50].iter().map(|x| ((instr >> x) & 0x1ff) as usize).collect::>(); + let src_parts = s.iter().map(|x| src(*x)).collect::>(); + + let b = |i: usize| (instr >> i) & 0x1 != 0; + let neg_hi = ((instr >> 8) & 0x7) as usize; + let neg = ((instr >> 61) & 0x7) as usize; + let opsel = [b(11), b(12), b(13)]; + let opsel_hi = [b(59), b(60), b(14)]; + + match op { + 0..=18 => { + let fxn = |x, y, z| -> u16 { + match op { + 0 => x * y + z, + 1 => x * y, + 2 => x + y, + 3 => x - y, + 4 => y << (x & 0xf), + 5 => y >> (x & 0xf), + 6 => ((y as i16) >> ((x as i16) & 0xf)) as u16, + 7 => i16::max(x as i16, y as i16) as u16, + 8 => i16::min(x as i16, y as i16) as u16, + 9 => x * y + z, + 10 => x + y, + 11 => x - y, + 12 => u16::max(x, y), + 13 => u16::min(x, y), + _ => { + let (x, y, z) = (f16::from_bits(x), f16::from_bits(y), f16::from_bits(z)); + let ret = match op { + 14 => f16::mul_add(x, y, z), + 15 => x + y, + 16 => x * y, + 17 => f16::min(x, y), + 18 => f16::max(x, y), + _ => unreachable!("op should be in range 0..=18, got {op}"), + }; + ret.to_bits() + } + } + }; + let src = |opsel: [bool; 3]| { + opsel + .iter() + .enumerate() + .map(|(i, sel)| { + if (14..=19).contains(&op) { + let half = |x, n| f16::from_bits(x).negate(i, n).to_bits(); + match sel { + true => half(src_parts[i].1, neg), + false => half(src_parts[i].0, neg_hi), + } + } else { + match sel { + true => src_parts[i].1, + false => src_parts[i].0, + } + } + }) + .collect::>() + }; + let (src_hi, src_lo) = (src(opsel_hi), src(opsel)); + let ret = ((fxn(src_hi[0], src_hi[1], src_hi[2]) as u32) << 16) | (fxn(src_lo[0], src_lo[1], src_lo[2]) as u32); + + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + 32..=34 => { + let src: Vec = src_parts + .iter() + .enumerate() + .map(|(i, (lo, hi, full))| { + if !opsel_hi[i] { + f32::from_bits(*full).absolute(i, neg_hi) + } else if opsel[i] { + f32::from(f16::from_bits(*hi)).absolute(i, neg_hi) + } else { + f32::from(f16::from_bits(*lo)).absolute(i, neg_hi) + } + }) + .collect(); + let ret = match op { + 32 => f32::mul_add(src[0], src[1], src[2]).to_bits(), + 33 | 34 => { + let ret = f16::from_f32(f32::mul_add(src[0], src[1], src[2])).to_bits(); + match op { + 33 => (self.vec_reg[vdst] & 0xffff0000) | (ret as u32), + 34 => (self.vec_reg[vdst] & 0x0000ffff) | ((ret as u32) << 16), + _ => todo_instr!(instruction)?, + } + } + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + 64..=69 => { + match op { + 64 => { + let a = self.wmma_b16_16x16(s[0]).map(|v| f16::from_bits(v).to_f32()); + let b = self.wmma_b16_16x16(s[1]).map(|v| f16::from_bits(v).to_f32()); + let c = self.wmma_b32_16x16(s[2]).map(|v| f32::from_bits(v)); + let ret = wmma(a.collect(), b.collect(), c.collect()); + for (i, val) in ret.into_iter().enumerate() { + let lane = i % 32; + self.vec_reg.get_lane_mut(lane)[(i / 32) + vdst] = val.to_bits(); + } + } + 65 => { + let a = self.wmma_b16_16x16(s[0]).map(|v| bf16::from_bits(v).to_f32()); + let b = self.wmma_b16_16x16(s[1]).map(|v| bf16::from_bits(v).to_f32()); + let c = self.wmma_b32_16x16(s[2]).map(|v| f32::from_bits(v)); + let ret = wmma(a.collect(), b.collect(), c.collect()); + for (i, val) in ret.into_iter().enumerate() { + let register = (i / 32) + vdst; + let lane = i % 32; + self.vec_reg.get_lane_mut(lane)[register] = val.to_bits() + } + } + 66 => { + let a = self.wmma_b16_16x16(s[0]).map(|v| f16::from_bits(v)); + let b = self.wmma_b16_16x16(s[1]).map(|v| f16::from_bits(v)); + let c = self.wmma_b32_16x16(s[2]).map(|v| f16::from_bits(v as u16)); + let ret = wmma(a.collect(), b.collect(), c.collect()); + for (i, val) in ret.into_iter().enumerate() { + let register = (i / 32) + vdst; + let lane = i % 32; + self.vec_reg.get_lane_mut(lane)[register].mut_lo16(val.to_bits()); + } + } + _ => todo_instr!(instruction)?, + }; + self.scalar = true; + } + _ => todo_instr!(instruction)?, + } + } + else if let Instruction::VOP1 { src, op, vdst } = decoded { + let s0 = src as usize; + let vdst = vdst as usize; + + match op { + 3 | 15 | 21 | 23 | 25 | 26 | 60 | 61 | 47 | 49 => { + let s0: u64 = self.val(s0); + match op { + 3 | 15 | 21 | 23 | 25 | 26 | 60 | 61 | 47 | 49 => { + let s0 = f64::from_bits(s0); + match op { + 23 | 25 | 26 | 61 | 47 | 49 => { + let ret = match op { + 23 => f64::trunc(s0), + 25 => { + let mut temp = f64::floor(s0 + 0.5); + if f64::floor(s0) % 2.0 != 0.0 && f64::fract(s0) == 0.5 { + temp -= 1.0; + } + temp + } + 26 => f64::floor(s0), + 47 => 1.0 / s0, + 49 => 1.0 / f64::sqrt(s0), + 61 => extract_mantissa(s0), + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg.write64(vdst, ret.to_bits()) + } + } + _ => { + let ret = match op { + 3 => s0 as i32 as u32, + 15 => (s0 as f32).to_bits(), + 21 => s0 as u32, + 60 => match (s0 == f64::INFINITY) || (s0 == f64::NEG_INFINITY) || s0.is_nan() { + true => 0, + false => (s0.exponent() as i32 - 1023 + 1) as u32, + }, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + } + } + _ => todo_instr!(instruction)?, + } + } + 84..=97 => { + let s0 = f16::from_bits(self.val(s0)); + let ret = match op { + 84 => f16::recip(s0), + 85 => f16::sqrt(s0), + 87 => f16::log2(s0), + 88 => f16::exp2(s0), + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret.to_bits() as u32; + } + } + _ => { + let s0: u32 = self.val(s0); + match op { + 4 | 16 | 22 => { + let ret = match op { + 4 => (s0 as i32 as f64).to_bits(), + 22 => (s0 as f64).to_bits(), + 16 => (f32::from_bits(s0) as f64).to_bits(), + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg.write64(vdst, ret) + } + } + 2 => { + let idx = self.exec.value.trailing_zeros() as usize; + self.scalar_reg[vdst] = self.vec_reg.get_lane(idx)[(instruction & 0x1ff) as usize - VGPR_COUNT]; + } + _ => { + let ret = match op { + 1 => s0, + 5 => (s0 as i32 as f32).to_bits(), + 6 => (s0 as f32).to_bits(), + 7 => f32::from_bits(s0) as u32, + 8 => f32::from_bits(s0) as i32 as u32, + 10 => f16::from_f32(f32::from_bits(s0)).to_bits() as u32, + 11 => f32::from(f16::from_bits(s0 as u16)).to_bits(), + 17 => ((s0 & 0xff) as f32).to_bits(), + 18 => (((s0 >> 8) & 0xff) as f32).to_bits(), + 19 => (((s0 >> 16) & 0xff) as f32).to_bits(), + 20 => (((s0 >> 24) & 0xff) as f32).to_bits(), + 56 => s0.reverse_bits(), + 57 => self.clz_i32_u32(s0), + 33..=51 => { + let s0 = f32::from_bits(s0); + match op { + 33 => s0.trunc(), + 34 => { + let mut d0 = s0.trunc(); + if s0 > 0.0 && s0 != d0 { + d0 += 1.0; + } + d0 + } + 35 => { + let mut temp = f32::floor(s0 + 0.5); + if f32::floor(s0) % 2.0 != 0.0 && f32::fract(s0) == 0.5 { + temp -= 1.0; + } + temp + } + 36 => { + let mut d0 = s0.trunc(); + if s0 < 0.0 && s0 != d0 { + d0 -= 1.0; + } + d0 + } + 37 => f32::exp2(s0), + 39 => f32::log2(s0), + 42 => 1.0 / s0, + 43 => 1.0 / s0, + 51 => f32::sqrt(s0), + _ => todo_instr!(instruction)?, + } + .to_bits() + } + 55 => !s0, + 59 => self.cls_i32(s0), + 80 => f16::from_f32(s0 as u16 as f32).to_bits() as u32, + 81 => f16::from_f32(s0 as i16 as f32).to_bits() as u32, + 82 => f32::from(f16::from_bits(s0 as u16)) as u32, + 83 => f32::from(f16::from_bits(s0 as u16)) as i16 as u32, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + } + } + } + } + // vopd + else if instruction >> 26 == 0b110010 { + let instr = self.u64_instr(); + let sx = instr & 0x1ff; + let vx = (instr >> 9) & 0xff; + let srcx0 = self.val(sx as usize); + let vsrcx1 = self.vec_reg[(vx) as usize] as u32; + let opy = (instr >> 17) & 0x1f; + let sy = (instr >> 32) & 0x1ff; + let vy = (instr >> 41) & 0xff; + let opx = (instr >> 22) & 0xf; + let srcy0 = match sy { + 255 => match sx { + 255 => srcx0, + _ => self.val(sy as usize), + }, + _ => self.val(sy as usize), + }; + let vsrcy1 = self.vec_reg[(vy) as usize]; + + let vdstx = ((instr >> 56) & 0xff) as usize; + // LSB is the opposite of VDSTX[0] + let vdsty = (((instr >> 49) & 0x7f) << 1 | ((vdstx as u64 & 1) ^ 1)) as usize; + + for (op, s0, s1, dst) in ([(opx, srcx0, vsrcx1, vdstx), (opy, srcy0, vsrcy1, vdsty)]).iter() { + let ret = match *op { + 0 | 1 | 2 | 3 | 4 | 5 | 6 | 10 | 11 => { + let s0 = f32::from_bits(*s0 as u32); + let s1 = f32::from_bits(*s1 as u32); + match *op { + 0 => f32::mul_add(s0, s1, f32::from_bits(self.vec_reg[*dst])), + 1 => f32::mul_add(s0, s1, f32::from_bits(self.val(SIMM_SRC))), + 2 => f32::mul_add(s0, f32::from_bits(self.val(SIMM_SRC)), s1), + 3 => s0 * s1, + 4 => s0 + s1, + 5 => s0 - s1, + 6 => s1 - s0, + 10 => f32::max(s0, s1), + 11 => f32::min(s0, s1), + _ => todo_instr!(instruction)?, + } + .to_bits() + } + 8 => *s0, + 9 => match self.vcc.read() { + true => *s1, + false => *s0, + }, + 16 => s0 + s1, + 17 => s1 << s0, + 18 => s0 & s1, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[*dst] = ret; + }; + } + } + // vopc + else if let Instruction::VOPC { vsrc, src, op } = decoded { + let s0 = src as usize; + let s1 = vsrc as usize; + let op = op as u32; + + let dest_offset = if op >= 128 { 128 } else { 0 }; + let ret = match op { + (0..=15) | 125 | (128..=143) => { + let s0 = f16::from_bits(self.val(s0)); + let s1 = f16::from_bits(self.vec_reg[s1] as u16); + match op { + 125 => self.cmp_class_f16(s0, s1.to_bits()), + _ => self.cmpf(s0, s1, op - dest_offset), + } + } + (16..=31) | 126 | (144..=159) => { + let s0 = f32::from_bits(self.val(s0)); + let s1 = f32::from_bits(self.vec_reg[s1]); + match op { + 126 => self.cmp_class_f32(s0, s1.to_bits()), + _ => self.cmpf(s0, s1, op - 16 - dest_offset), + } + } + (32..=47) | 127 | (160..=174) => { + let s0 = self.val(s0); + match op { + 127 => { + let s1 = self.val(s1); + self.cmp_class_f64(s0, s1) + } + _ => { + let s1 = f64::from_bits(self.vec_reg.read64(s1)); + self.cmpf(s0, s1, op - 32 - dest_offset) + } + } + } + (49..=54) | (177..=182) => { + let (s0, s1): (u16, u16) = (self.val(s0), self.vec_reg[s1] as u16); + self.cmpi(s0 as i16, s1 as i16, op - 48 - dest_offset) + } + (57..=62) | (185..=190) => { + let (s0, s1): (u16, u16) = (self.val(s0), self.vec_reg[s1] as u16); + self.cmpi(s0, s1, op - 56 - dest_offset) + } + (64..=71) | (192..=199) => { + let (s0, s1): (u32, u32) = (self.val(s0), self.vec_reg[s1]); + self.cmpi(s0 as i32, s1 as i32, op - 64 - dest_offset) + } + (72..=79) | (200..=207) => { + let (s0, s1): (u32, u32) = (self.val(s0), self.vec_reg[s1]); + self.cmpi(s0, s1, op - 72 - dest_offset) + } + (80..=87) | (208..=215) => { + let (s0, s1): (u64, u64) = (self.val(s0), self.vec_reg.read64(s1)); + self.cmpi(s0 as i64, s1 as i64, op - 80 - dest_offset) + } + (88..=95) | (216..=223) => { + let (s0, s1): (u64, u64) = (self.val(s0), self.vec_reg.read64(s1)); + self.cmpi(s0, s1, op - 88 - dest_offset) + } + _ => todo_instr!(instruction)?, + }; + + if self.exec.read() { + match op >= 128 { + true => self.exec.set_lane(ret), + false => self.vcc.set_lane(ret), + }; + } + } + else if let Instruction::VOP2 { vsrc, src, vdst, op } = decoded { + let s0 = src as usize; + let s1 = self.vec_reg[vsrc as usize]; + let vdst = vdst as usize; + + match op { + (50..=60) => { + let (s0, s1) = (f16::from_bits(self.val(s0)), f16::from_bits(s1 as u16)); + let ret = match op { + 50 => s0 + s1, + 51 => s0 - s1, + 53 => s0 * s1, + 54 => f16::mul_add(s0, s1, f16::from_bits(self.vec_reg[vdst] as u16)), + 55 => f16::mul_add(s0, f16::from_bits(self.val(SIMM_SRC)), s1), + 56 => f16::mul_add(s0, s1, f16::from_bits(self.val(SIMM_SRC))), + 57 => f16::max(s0, s1), + 58 => f16::min(s0, s1), + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret.to_bits() as u32; + } + } + _ => { + let s0 = self.val(s0); + let ret = match op { + 1 => match self.vcc.read() { + true => s1, + false => s0, + }, + 2 => { + let mut acc = f32::from_bits(self.vec_reg[vdst]); + acc += f32::from(f16_lo(s0)) * f32::from(f16_lo(s1)); + acc += f32::from(f16_hi(s0)) * f32::from(f16_hi(s1)); + acc.to_bits() + } + + 3 | 4 | 5 | 8 | 15 | 16 | 43 | 44 | 45 => { + let (s0, s1) = (f32::from_bits(s0), f32::from_bits(s1)); + match op { + 3 => s0 + s1, + 4 => s0 - s1, + 5 => s1 - s0, + 8 => s0 * s1, + 15 => f32::min(s0, s1), + 16 => f32::max(s0, s1), + 43 => f32::mul_add(s0, s1, f32::from_bits(self.vec_reg[vdst])), + 44 => f32::mul_add(s0, f32::from_bits(self.val(SIMM_SRC)), s1), + 45 => f32::mul_add(s0, s1, f32::from_bits(self.val(SIMM_SRC))), + _ => todo_instr!(instruction)?, + } + .to_bits() + } + 9 => { + let s0 = sign_ext((s0 & 0xffffff) as u64, 24) as i32; + let s1 = sign_ext((s1 & 0xffffff) as u64, 24) as i32; + (s0 * s1) as u32 + } + 17 | 18 | 26 => { + let (s0, s1) = (s0 as i32, s1 as i32); + (match op { + 17 => i32::min(s0, s1), + 18 => i32::max(s0, s1), + 26 => s1 >> s0, + _ => todo_instr!(instruction)?, + }) as u32 + } + 32 => { + let temp = s0 as u64 + s1 as u64 + self.vcc.read() as u64; + self.vcc.set_lane(temp >= 0x100000000); + temp as u32 + } + 33 | 34 => { + let temp = match op { + 33 => s0 - s1 - self.vcc.read() as u32, + 34 => s1 - s0 - self.vcc.read() as u32, + _ => todo_instr!(instruction)?, + }; + self.vcc.set_lane((s1 as u64 + self.vcc.read() as u64) > s0 as u64); + temp + } + 11 => s0 * s1, + 19 => u32::min(s0, s1), + 20 => u32::max(s0, s1), + 24 => s1 << s0, + 25 => s1 >> s0, + 27 => s0 & s1, + 28 => s0 | s1, + 29 => s0 ^ s1, + 37 => s0 + s1, + 38 => s0 - s1, + 39 => s1 - s0, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + }; + } + // vop3 + else if instruction >> 26 == 0b110101 { + let instr = self.u64_instr(); + + let op = ((instr >> 16) & 0x3ff) as u32; + match op { + 764 | 765 | 288 | 289 | 290 | 766 | 768 | 769 => { + let vdst = (instr & 0xff) as usize; + let sdst = ((instr >> 8) & 0x7f) as usize; + let f = |i: u32| -> usize { ((instr >> i) & 0x1ff) as usize }; + let (s0, s1, s2) = (f(32), f(41), f(50)); + let mut carry_in = WaveValue::new(self.val(s2), self.warp_size); + carry_in.default_lane = self.vcc.default_lane; + let omod = (instr >> 59) & 0x3; + let _neg = (instr >> 61) & 0x7; + let clmp = (instr >> 15) & 0x1; + assert_eq!(omod, 0); + assert_eq!(clmp, 0); + + let vcc = match op { + 766 => { + let (s0, s1, s2): (u32, u32, u64) = (self.val(s0), self.val(s1), self.val(s2)); + let (mul_result, overflow_mul) = (s0 as u64).overflowing_mul(s1 as u64); + let (ret, overflow_add) = mul_result.overflowing_add(s2); + let overflowed = overflow_mul || overflow_add; + if self.exec.read() { + self.vec_reg.write64(vdst, ret); + } + overflowed + } + 765 => { + assert!(f64::from_bits(self.val(s2)).exponent() <= 1076); + let ret = ldexp(self.val(s0), 128); + if self.exec.read() { + self.vec_reg.write64(vdst, ret.to_bits()); + } + false + } + _ => { + let (s0, s1, _s2): (u32, u32, u32) = (self.val(s0), self.val(s1), self.val(s2)); + let (ret, vcc) = match op { + 288 => { + let ret = s0 as u64 + s1 as u64 + carry_in.read() as u64; + (ret as u32, ret >= 0x100000000) + } + 289 => { + let ret = (s0 as u64).wrapping_sub(s1 as u64).wrapping_sub(carry_in.read() as u64); + (ret as u32, s1 as u64 + (carry_in.read() as u64) > s0 as u64) + } + 290 => { + let ret = (s1 as u64).wrapping_sub(s0 as u64).wrapping_sub(carry_in.read() as u64); + (ret as u32, s1 as u64 + (carry_in.read() as u64) > s0 as u64) + } + 764 => (0, false), // NOTE: div scaling isn't required + 768 => { + let ret = s0 as u64 + s1 as u64; + (ret as u32, ret >= 0x100000000) + } + 769 => { + let ret = s0.wrapping_sub(s1); + (ret as u32, s1 > s0) + } + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + vcc + } + }; + + match sdst { + VCC => self.vcc.set_lane(vcc), + NULL_SRC => {} + _ => self.set_sgpr_co(sdst, vcc), + } + } + _ => { + let vdst = (instr & 0xff) as usize; + let abs = ((instr >> 8) & 0x7) as usize; + let opsel = ((instr >> 11) & 0xf) as usize; + let cm = (instr >> 15) & 0x1; + + let s = |n: usize| ((instr >> n) & 0x1ff) as usize; + let src = (s(32), s(41), s(50)); + + let omod = (instr >> 59) & 0x3; + let neg = ((instr >> 61) & 0x7) as usize; + assert_eq!(omod, 0); + assert_eq!(cm, 0); + assert_eq!(opsel, 0); + + match op { + // VOPC using VOP3 encoding + 0..=255 => { + let dest_offset = if op >= 128 { 128 } else { 0 }; + let ret = match op { + (0..=15) | 125 | (128..=143) => { + let (s0, s1) = (self.val(src.0), self.val(src.1)); + let s0 = f16::from_bits(s0).negate(0, neg).absolute(0, abs); + let s1 = f16::from_bits(s1).negate(1, neg).absolute(1, abs); + match op { + 125 => self.cmp_class_f16(s0, s1.to_bits()), + _ => self.cmpf(s0, s1, op - dest_offset), + } + } + (16..=31) | 126 | (144..=159) => { + let (s0, s1) = (self.val(src.0), self.val(src.1)); + let s0 = f32::from_bits(s0).negate(0, neg).absolute(0, abs); + let s1 = f32::from_bits(s1).negate(1, neg).absolute(1, abs); + match op { + 126 => self.cmp_class_f32(s0, s1.to_bits()), + _ => self.cmpf(s0, s1, op - 16 - dest_offset), + } + } + (32..=47) | 127 | (160..=174) => { + let s0: f64 = self.val(src.0); + let s0 = s0.negate(0, neg).absolute(0, abs); + match op { + 127 => { + let s1 = self.val(src.1); + self.cmp_class_f64(s0, s1) + } + _ => { + let s1 = self.val(src.1); + let s1 = f64::from_bits(s1).negate(1, neg).absolute(1, abs); + self.cmpf(s0, s1, op - 32 - dest_offset) + } + } + } + (49..=54) | (177..=182) => { + let (s0, s1): (u16, u16) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0 as i16, s1 as i16, op - 48 - dest_offset) + } + (57..=62) | (185..=190) => { + let (s0, s1): (u16, u16) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0, s1, op - 56 - dest_offset) + } + (64..=71) | (192..=199) => { + let (s0, s1): (u32, u32) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0 as i32, s1 as i32, op - 64 - dest_offset) + } + (72..=79) | (200..=207) => { + let (s0, s1): (u32, u32) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0, s1, op - 72 - dest_offset) + } + (80..=87) | (208..=215) => { + let (s0, s1): (u64, u64) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0 as i64, s1 as i64, op - 80 - dest_offset) + } + (88..=95) | (216..=223) => { + let (s0, s1): (u64, u64) = (self.val(src.0), self.val(src.1)); + self.cmpi(s0, s1, op - 88 - dest_offset) + } + _ => todo_instr!(instruction)?, + }; + + if self.exec.read() { + match vdst { + 0..=SGPR_SRC | 107 => self.set_sgpr_co(vdst, ret), + VCC => self.vcc.set_lane(ret), + EXEC => self.exec.set_lane(ret), + _ => todo_instr!(instruction)?, + } + } + } + 828..=830 => { + let (s0, s1, _s2): (u32, u64, u64) = (self.val(src.0), self.val(src.1), self.val(src.2)); + let shift = s0 & 0x3f; + let ret = match op { + 828 => s1 << shift, + 829 => s1 >> shift, + 830 => ((s1 as i64) >> shift) as u64, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg.write64(vdst, ret) + } + } + 407 | 532 | 552 | 568 | (807..=811) => { + let (_s0, _s1, _s2): (f64, f64, f64) = (self.val(src.0), self.val(src.1), self.val(src.2)); + let s0 = _s0.negate(0, neg).absolute(0, abs); + let s1 = _s1.negate(1, neg).absolute(1, abs); + let s2 = _s2.negate(2, neg).absolute(2, abs); + let ret = match op { + 407 => f64::trunc(s0), + 532 => f64::mul_add(s0, s1, s2), + 552 => { + assert!(s0.is_normal()); + s0 + } + 807 => s0 + s1, + 808 => s0 * s1, + 809 => f64::min(s0, s1), + 810 => f64::max(s0, s1), + 811 => { + let s1: u32 = self.val(src.1); + s0 * 2f64.powi(s1 as i32) + } + 568 => { + assert!(!self.vcc.read()); + f64::mul_add(s0, s1, s2) + } + _ => todo_instr!(instruction)?, + } + .to_bits(); + if self.exec.read() { + self.vec_reg.write64(vdst, ret) + } + } + 306 | 309 | 310 | 313 | 596 | 584 | 585 | 588 => { + let (s0, s1, s2) = (self.val(src.0), self.val(src.1), self.val(src.2)); + let s0 = f16::from_bits(s0).negate(0, neg).absolute(0, abs); + let s1 = f16::from_bits(s1).negate(1, neg).absolute(1, abs); + let s2 = f16::from_bits(s2).negate(1, neg).absolute(1, abs); + let ret = match op { + 309 => s0 * s1, + 310 => f16::mul_add(s0, s1, f16::from_bits(self.vec_reg[vdst] as u16)), + 306 => s0 + s1, + 584 => f16::mul_add(s0, s1, s2), + 585 => f16::min(f16::min(s0, s1), s2), + 588 => f16::max(f16::max(s0, s1), s2), + 596 => s2 / s1, + 313 => f16::max(s0, s1), + 314 => f16::min(s0, s1), + _ => todo_instr!(instruction)?, + } + .to_bits(); + if self.exec.read() { + self.vec_reg[vdst] = ret as u32; + } + } + 394 => { + let s0 = f32::from_bits(self.val(src.0)).negate(0, neg).absolute(0, abs); + if self.exec.read() { + self.vec_reg[vdst].mut_lo16(f16::from_f32(s0).to_bits()); + } + } + 467 => { + let s0 = f16::from_bits(self.val(src.0)).negate(0, neg).absolute(0, abs); + if self.exec.read() { + self.vec_reg[vdst] = s0.to_f32() as i16 as u32; + } + } + 395 => { + let s0 = f16::from_bits(self.val(src.0)).negate(0, neg).absolute(0, abs); + if self.exec.read() { + self.vec_reg[vdst] = f32::from(s0).to_bits(); + } + } + 399 => { + let s0: f64 = self.val(src.0); + let s0 = s0.negate(0, neg).absolute(0, abs); + if self.exec.read() { + self.vec_reg[vdst] = (s0 as f32).to_bits(); + } + } + 785 => { + let (s0, s1) = (self.val(src.0), self.val(src.1)); + if self.exec.read() { + self.vec_reg[vdst] = (f16::from_bits(s1).to_bits() as u32) << 16 | f16::from_bits(s0).to_bits() as u32; + } + } + _ => { + let (s0, s1, s2) = (self.val(src.0), self.val(src.1), self.val(src.2)); + match op { + 865 => { + if self.exec.read() { + self.vec_reg.get_lane_mut(s1 as usize)[vdst] = s0; + } + return Ok(()); + } + 864 => { + let val = self.vec_reg.get_lane(s1 as usize)[src.0 - VGPR_COUNT]; + self.write_to_sdst(vdst, val); + return Ok(()); + } + 826 => { + if self.exec.read() { + self.vec_reg[vdst].mut_lo16(((s1 as i16) >> (s0 & 0xf)) as u16); + } + return Ok(()); + } + 587 | 577 | 590 | 771 | 772 | 773 | 777 | 779 | 824 | 825 => { + let (s0, s1, s2) = (s0 as u16, s1 as u16, s2 as u16); + let ret = match op { + 587 => u16::min(u16::min(s0, s1), s2), + 590 => u16::max(u16::max(s0, s1), s2), + 577 => s0 * s1 + s2, + 771 => s0 + s1, + 772 => s0 - s1, + 773 => s0 * s1, + 777 => u16::max(s0, s1), + 779 => u16::min(s0, s1), + 824 => s1 << s0, + 825 => s1 >> s0, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst].mut_lo16(ret); + } + return Ok(()); + } + 586 | 589 | 778 | 780 | 781 | 782 => { + let (s0, s1, s2) = (s0 as i16, s1 as i16, s2 as i16); + let ret = match op { + 586 => i16::min(i16::min(s0, s1), s2), + 589 => i16::max(i16::max(s0, s1), s2), + 778 => i16::max(s0, s1), + 780 => i16::min(s0, s1), + 781 => s0 + s1, + 782 => s0 - s1, + _ => todo_instr!(instruction)?, + }; + if self.exec.read() { + self.vec_reg[vdst].mut_lo16(ret as u16); + } + return Ok(()); + } + _ => {} + } + + let ret = match op { + 257 | 259 | 299 | 260 | 261 | 264 | 272 | 392 | 426 | 531 | 537 | 540 | 551 | 567 | 796 => { + let s0 = f32::from_bits(s0).negate(0, neg).absolute(0, abs); + let s1 = f32::from_bits(s1).negate(1, neg).absolute(1, abs); + let s2 = f32::from_bits(s2).negate(2, neg).absolute(2, abs); + match op { + 259 => s0 + s1, + 260 => s0 - s1, + 261 => s1 - s0, + 264 => s0 * s1, + 272 => f32::max(s0, s1), + 299 => f32::mul_add(s0, s1, f32::from_bits(self.vec_reg[vdst])), + 426 => s0.recip(), + 531 => f32::mul_add(s0, s1, s2), + 537 => f32::min(f32::min(s0, s1), s2), + 540 => f32::max(f32::max(s0, s1), s2), + 551 => s2 / s1, + 567 => { + let ret = f32::mul_add(s0, s1, s2); + match self.vcc.read() { + true => 2.0_f32.powi(32) * ret, + false => ret, + } + } + 796 => s0 * 2f32.powi(s1.to_bits() as i32), + // cnd_mask isn't a float only ALU but supports neg + 257 => { + let mut cond = WaveValue::new(s2.to_bits(), self.warp_size); + cond.default_lane = self.vcc.default_lane; + match cond.read() { + true => s1, + false => s0, + } + } + 392 => f32::from_bits(s0 as i32 as u32), + _ => todo_instr!(instruction)?, + } + .to_bits() + } + _ => { + if neg != 0 { + todo_instr!(instruction)? + } + match op { + 529 => { + let s0 = s0 as i32; + let shift = 32 - (s2 & 0x1f); + let mask: i32 = 1 << (s2 & 0x1f); + let ret = (s0 >> (s1 & 0x1f)) & (mask.wrapping_sub(1)); + ((ret << shift) >> shift) as u32 + } + 522 | 541 | 538 | 544 | 814 => { + let (s0, s1, s2) = (s0 as i32, s1 as i32, s2 as i32); + + (match op { + 522 => { + let s0 = sign_ext((s0 & 0xffffff) as u64, 24) as i32; + let s1 = sign_ext((s1 & 0xffffff) as u64, 24) as i32; + s0 * s1 + s2 + } + 538 => i32::min(i32::min(s0, s1), s2), + 541 => i32::max(i32::max(s0, s1), s2), + 544 => { + if (i32::max(i32::max(s0, s1), s2)) == s0 { + i32::max(s1, s2) + } else if (i32::max(i32::max(s0, s1), s2)) == s1 { + i32::max(s0, s2) + } else { + i32::max(s0, s1) + } + } + 814 => ((s0 as i64) * (s1 as i64) >> 32) as i32, + _ => todo_instr!(instruction)?, + }) as u32 + } + 275 => u32::min(s0, s1), + 276 => u32::max(s0, s1), + 280 => s1 << s0, + 281 => s1 >> s0, + 283 => s0 & s1, + 284 => s0 | s1, + 285 => s0 ^ s1, + 286 => !(s0 ^ s1), + 523 => s0 * s1 + s2, // TODO 24 bit trunc + 528 => (s0 >> s1) & ((1 << s2) - 1), + 530 => (s0 & s1) | (!s0 & s2), + 534 => { + let val = ((s0 as u64) << 32) | (s1 as u64); + let shift = (s2 & 0x1F) as u64; + ((val >> shift) & 0xffffffff) as u32 + } + 542 => u32::max(u32::max(s0, s1), s2), + 576 => s0 ^ s1 ^ s2, + 580 => { + fn byte_permute(data: u64, sel: u32) -> u8 { + let bytes = data.to_ne_bytes(); + match sel { + 13..=u32::MAX => 0xff, + 12 => 0x00, + 11 => ((bytes[7] & 0x80) != 0) as u8 * 0xff, + 10 => ((bytes[5] & 0x80) != 0) as u8 * 0xff, + 9 => ((bytes[3] & 0x80) != 0) as u8 * 0xff, + 8 => ((bytes[1] & 0x80) != 0) as u8 * 0xff, + _ => bytes[sel as usize], + } + } + let combined = ((s0 as u64) << 32) | s1 as u64; + let d0 = ((byte_permute(combined, s2 >> 24) as u32) << 24) + | ((byte_permute(combined, (s2 >> 16) & 0xFF) as u32) << 16) + | ((byte_permute(combined, (s2 >> 8) & 0xFF) as u32) << 8) + | (byte_permute(combined, s2 & 0xFF) as u32); + d0 + } + 581 => (s0 ^ s1) + s2, + 582 => (s0 << s1) + s2, + 583 => (s0 + s1) << s2, + 597 => s0 + s1 + s2, + 598 => (s0 << s1) | s2, + 599 => (s0 & s1) | s2, + 600 => s0 | s1 | s2, + 798 => { + let mut ret = s1; + (0..=31).into_iter().for_each(|i| ret += nth(s0, i)); + ret + } + 812 => s0 * s1, + 813 => ((s0 as u64) * (s1 as u64) >> 32) as u32, + _ => todo_instr!(instruction)?, + } + } + }; + if self.exec.read() { + self.vec_reg[vdst] = ret; + } + } + }; + } + } + } else if let Instruction::DS { op, gds, addr, data0, offset0, data1, offset1, vdst } = decoded { + let _ = self.u64_instr(); + if gds { + return todo_instr!(instruction)?; + } + if !self.exec.read() { + return Ok(()); + } + + let [data0, data1, vdst] = [data0 as usize, data1 as usize, vdst as usize]; + let lds_base = self.vec_reg[addr as usize]; + let single_addr = || (lds_base + u16::from_le_bytes([offset0, offset1]) as u32) as usize; + let double_addr = |adj: u32| { + let addr0 = lds_base + offset0 as u32 * adj; + let addr1 = lds_base + offset1 as u32 * adj; + (addr0 as usize, addr1 as usize) + }; + + match op { + // load + 54 | 118 | 254 | 255 => { + let dwords = match op { + 255 => 4, + 254 => 3, + 118 => 2, + _ => 1, + }; + (0..dwords).for_each(|i| { + self.vec_reg[vdst + i] = self.lds.read(single_addr() + 4 * i); + }); + } + 58 => self.vec_reg[vdst] = self.lds.read(single_addr()) as u8 as u32, + 60 => self.vec_reg[vdst] = self.lds.read(single_addr()) as u16 as u32, + 55 => { + let (addr0, addr1) = double_addr(4); + self.vec_reg[vdst] = self.lds.read(addr0); + self.vec_reg[vdst + 1] = self.lds.read(addr1); + } + 119 => { + let (addr0, addr1) = double_addr(8); + self.vec_reg.write64(vdst, self.lds.read64(addr0)); + self.vec_reg.write64(vdst + 2, self.lds.read64(addr1)); + } + // store + 13 | 77 | 222 | 223 => { + let dwords = match op { + 223 => 4, + 222 => 3, + 77 => 2, + _ => 1, + }; + (0..dwords).for_each(|i| { + self.lds.write(single_addr() + 4 * i, self.vec_reg[data0 + i]); + }) + } + 30 => { + let addr = single_addr(); + if addr + 1 >= self.lds.data.len() { + self.lds.data.resize(self.lds.data.len() + addr + 2, 0); + } + self.lds.data[addr..addr + 1].iter_mut().enumerate().for_each(|(i, x)| { + *x = (self.vec_reg[data0] as u8).to_le_bytes()[i]; + }); + } + 31 | 161 => { + let addr = single_addr(); + if addr + 2 >= self.lds.data.len() { + self.lds.data.resize(self.lds.data.len() + addr + 3, 0); + } + let b32 = self.vec_reg[data0]; + self.lds.data[addr..addr + 2].iter_mut().enumerate().for_each(|(i, x)| { + *x = (if op == 31 { b32 as u16 } else { ((b32 >> 16) & 0xffff) as u16 }).to_le_bytes()[i]; + }); + } + 14 => { + let (addr0, addr1) = double_addr(4); + self.lds.write(addr0, self.vec_reg[data0]); + self.lds.write(addr1, self.vec_reg[data1]); + } + 78 => { + let (addr0, addr1) = double_addr(8); + self.lds.write64(addr0, self.vec_reg.read64(data0)); + self.lds.write64(addr1, self.vec_reg.read64(data1)); + } + _ => todo_instr!(instruction)?, + } + } + // global + // flat + else if instruction >> 26 == 0b110111 { + let instr = self.u64_instr(); + if !self.exec.read() { + return Ok(()); + } + let offset = sign_ext(instr & 0x1fff, 13); + let seg = (instr >> 16) & 0x3; + let op = ((instr >> 18) & 0x7f) as usize; + let addr = ((instr >> 32) & 0xff) as usize; + let data = ((instr >> 40) & 0xff) as usize; + let saddr = ((instr >> 48) & 0x7f) as usize; + let vdst = ((instr >> 56) & 0xff) as usize; + + let saddr_val: u32 = self.val(saddr); + let saddr_off = saddr_val == 0x7F || saddr == NULL_SRC; + + match seg { + 1 => { + let sve = ((instr >> 50) & 0x1) != 0; + + let addr = match (sve, saddr_off) { + (true, true) => offset as u64 as usize, + (false, false) => saddr_val as usize, + _ => todo_instr!(instruction)?, + }; + match op { + // load + 20..=23 => (0..op - 19).for_each(|i| { + self.vec_reg[vdst + i] = self.sds.read(addr + 4 * i); + }), + // store + 26..=29 => (0..op - 25).for_each(|i| { + self.sds.write(addr + 4 * i, self.vec_reg[data + i]); + }), + _ => todo_instr!(instruction)?, + } + } + 2 => { + let addr = match saddr_off { + true => self.vec_reg.read64(addr) as i64 + (offset as i64), + false => { + let scalar_addr = self.scalar_reg.read64(saddr); + let vgpr_offset = self.vec_reg[addr]; + scalar_addr as i64 + vgpr_offset as i64 + offset + } + } as u64; + + unsafe { + match op { + // load + 16 => self.vec_reg[vdst] = *(addr as *const u8) as u32, + 17 => self.vec_reg[vdst] = *(addr as *const i8) as u32, + 18 => self.vec_reg[vdst] = *(addr as *const u16) as u32, + 19 => self.vec_reg[vdst] = *(addr as *const i16) as u32, + + 20..=23 => (0..op - 19).for_each(|i| { + self.vec_reg[vdst + i] = *((addr + 4 * i as u64) as *const u32); + }), + 32 => self.vec_reg[vdst].mut_lo16(*(addr as *const u16)), + 35 => self.vec_reg[vdst].mut_hi16(*(addr as *const u16)), + // store + 24 => *(addr as *mut u8) = self.vec_reg[data] as u8, + 25 => *(addr as *mut u16) = self.vec_reg[data] as u16, + 26..=29 => (0..op - 25).for_each(|i| { + *((addr + 4 * i as u64) as u64 as *mut u32) = self.vec_reg[data + i]; + }), + 37 => *(addr as *mut u16) = ((self.vec_reg[data] >> 16) & 0xffff) as u16, + _ => todo_instr!(instruction)?, + }; + } + } + _ => todo_instr!(instruction)?, + }; + } + // mubuf + else if instruction >> 26 == 0b111000 { + let instr = self.u64_instr(); + let op = ((instr >> 18) & 0x7f) as usize; + match op { + 43 => {} // NOTE: remu doesn't have an l0 cache, it just has the software managed lds + _ => todo_instr!(instruction)?, + }; + } else { + todo_instr!(instruction)?; + } + Ok(()) + } + + fn cmpf(&self, s0: T, s1: T, offset: u32) -> bool + where + T: Float + std::fmt::Display, + { + return match offset { + 0 => true, + 1 => s0 < s1, + 2 => s0 == s1, + 3 => s0 <= s1, + 4 => s0 > s1, + 5 => s0 != s1, + 6 => s0 >= s1, + 7 => (!s0.is_nan()) && (!s1.is_nan()), + 8 => s0.is_nan() || s1.is_nan(), + 9 => !(s0 >= s1), + 10 => !(s0 != s1), + 11 => !(s0 > s1), + 12 => !(s0 <= s1), + 13 => !(s0 == s1), + 14 => !(s0 < s1), + 15 => true, + _ => panic!("invalid offset for float compare {offset}"), + }; + } + fn cmp_class_f64(&self, s0: f64, s1: u32) -> bool { + let offset = match s0 { + _ if s0.is_nan() => 1, + _ if s0.is_infinite() => match s0.signum() == -1.0 { + true => 2, + false => 9, + }, + _ if s0.exponent() > 0 => match s0.signum() == -1.0 { + true => 3, + false => 8, + }, + _ if s0.abs() > 0.0 => match s0.signum() == -1.0 { + true => 4, + false => 7, + }, + _ => match s0.signum() == -1.0 { + true => 5, + false => 6, + }, + }; + ((s1 >> offset) & 1) != 0 + } + fn cmp_class_f32(&self, s0: f32, s1: u32) -> bool { + let offset = match s0 { + _ if (s0 as f64).is_nan() => 1, + _ if s0.exponent() == 255 => match s0.signum() == -1.0 { + true => 2, + false => 9, + }, + _ if s0.exponent() > 0 => match s0.signum() == -1.0 { + true => 3, + false => 8, + }, + _ if s0.abs() as f64 > 0.0 => match s0.signum() == -1.0 { + true => 4, + false => 7, + }, + _ => match s0.signum() == -1.0 { + true => 5, + false => 6, + }, + }; + ((s1 >> offset) & 1) != 0 + } + fn cmp_class_f16(&self, s0: f16, s1: u16) -> bool { + let offset = match s0 { + _ if (f64::from(s0)).is_nan() => 1, + _ if s0.exponent() == 31 => match s0.signum() == f16::NEG_ONE { + true => 2, + false => 9, + }, + _ if s0.exponent() > 0 => match s0.signum() == f16::NEG_ONE { + true => 3, + false => 8, + }, + _ if f64::from(s0.abs()) > 0.0 => match s0.signum() == f16::NEG_ONE { + true => 4, + false => 7, + }, + _ => match s0.signum() == f16::NEG_ONE { + true => 5, + false => 6, + }, + }; + ((s1 >> offset) & 1) != 0 + } + fn cmpi(&self, s0: T, s1: T, offset: u32) -> bool + where + T: PartialOrd + PartialEq, + { + return match offset { + 0 => false, + 1 => s0 < s1, + 2 => s0 == s1, + 3 => s0 <= s1, + 4 => s0 > s1, + 5 => s0 != s1, + 6 => s0 >= s1, + 7 => true, + _ => panic!("invalid offset for integer compare {offset}"), + }; + } + fn cls_i32(&self, s0: u32) -> u32 { + let mut ret: i32 = -1; + let s0 = s0 as i32; + for i in (1..=31).into_iter() { + if s0 >> (31 - i as u32) != s0 >> 31 { + ret = i; + break; + } + } + ret as u32 + } + fn clz_i32_u32(&self, s0: u32) -> u32 { + let mut ret: i32 = -1; + for i in (0..=31).into_iter() { + if s0 >> (31 - i as u32) == 1 { + ret = i; + break; + } + } + ret as u32 + } + + /* ALU utils */ + fn _common_srcs(&mut self, code: usize) -> u32 { + match code { + VCC => self.vcc.value, + 107 => self.scalar_reg[code as usize], + EXEC => self.exec.value, + NULL_SRC | 128 => 0, + 253 => *self.scc as u32, + 255 => match self.simm { + None => { + let val = self.stream[self.pc_offset + 1]; + self.simm = Some(val); + self.pc_offset += 1; + val + } + Some(val) => val, + }, + _ => todo!("resolve_src={code}"), + } + } + fn write_to_sdst(&mut self, sdst_bf: usize, val: u32) { + match sdst_bf { + // NOTE: remu is only wave32, vcc_hi is treated as a regular SGPR + 0..=SGPR_SRC | 107 => self.scalar_reg[sdst_bf] = val, + VCC => self.vcc.value = val, + 126 => self.exec.value = val, + _ => todo!("write to sdst {}", sdst_bf), + } + } + fn set_sgpr_co(&mut self, idx: usize, val: bool) { + let mut wv = self.sgpr_co.map(|(_, wv)| wv).unwrap_or_else(|| WaveValue::new(0, self.warp_size)); + wv.default_lane = self.vcc.default_lane; + wv.set_lane(val); + *self.sgpr_co = Some((idx, wv)); + } + + fn u64_instr(&mut self) -> u64 { + let msb = self.stream[self.pc_offset + 1] as u64; + let instr = msb << 32 | self.stream[self.pc_offset] as u64; + self.pc_offset += 1; + return instr; + } + + fn wmma_b16_16x16(&'a self, vsrc: usize) -> impl Iterator + 'a { + (0..16).flat_map(move |i| { + let lane = self.vec_reg.get_lane(i); + (vsrc..=vsrc + 7).flat_map(move |j| { + let val = lane[j - VGPR_COUNT]; + [(val & 0xffff) as u16, (val >> 16) as u16] + }) + }) + } + + fn wmma_b32_16x16(&'a self, vsrc: usize) -> impl Iterator + 'a { + (0..256).map(move |i| self.vec_reg.get_lane(i % 32)[(i / 32) + vsrc - VGPR_COUNT]) + } +} + +fn wmma(a: Vec, b: Vec, c: Vec) -> [T; 256] { + let mut ret = [T::zero(); 256]; + for row in 0..16 { + for col in 0..16 { + let mut sum = T::zero(); + for k in 0..16 { + let a_val = a[row * 16 + k]; + let b_val = b[col * 16 + k]; + sum = sum + (a_val * b_val); + } + let c_val = c[row * 16 + col]; + ret[row * 16 + col] = sum + c_val; + } + } + ret +} + +pub trait ALUSrc { + fn val(&mut self, code: usize) -> T; +} +impl ALUSrc for Thread<'_> { + fn val(&mut self, code: usize) -> u16 { + match code { + 0..=SGPR_SRC => self.scalar_reg[code] as u16, + VGPR_COUNT..=511 => self.vec_reg[code - VGPR_COUNT] as u16, + 129..=192 => (code - 128) as u16, + 193..=208 => ((code - 192) as i16 * -1) as u16, + 240..=247 => f16::from_f32( + [ + (240, 0.5_f32), + (241, -0.5_f32), + (242, 1_f32), + (243, -1.0_f32), + (244, 2.0_f32), + (245, -2.0_f32), + (246, 4.0_f32), + (247, -4.0_f32), + ] + .iter() + .find(|x| x.0 == code) + .unwrap() + .1, + ) + .to_bits(), + _ => self._common_srcs(code) as u16, + } + } +} +impl ALUSrc for Thread<'_> { + fn val(&mut self, code: usize) -> u32 { + match code { + 0..=SGPR_SRC => self.scalar_reg[code], + VGPR_COUNT..=511 => self.vec_reg[code - VGPR_COUNT], + 129..=192 => (code - 128) as u32, + 193..=208 => ((code - 192) as i32 * -1) as u32, + 240..=247 => [ + (240, 0.5_f32), + (241, -0.5_f32), + (242, 1_f32), + (243, -1.0_f32), + (244, 2.0_f32), + (245, -2.0_f32), + (246, 4.0_f32), + (247, -4.0_f32), + ] + .iter() + .find(|x| x.0 == code) + .unwrap() + .1 + .to_bits(), + _ => self._common_srcs(code), + } + } +} +impl ALUSrc for Thread<'_> { + fn val(&mut self, code: usize) -> u64 { + match code { + 0..=SGPR_SRC => self.scalar_reg.read64(code), + VGPR_COUNT..=511 => self.vec_reg.read64(code - VGPR_COUNT), + 129..=192 => (code - 128) as u64, + 193..=208 => ((code - 192) as i64 * -1) as u64, + 240..=247 => [ + (240, 0.5_f64), + (241, -0.5_f64), + (242, 1_f64), + (243, -1.0_f64), + (244, 2.0_f64), + (245, -2.0_f64), + (246, 4.0_f64), + (247, -4.0_f64), + ] + .iter() + .find(|x| x.0 == code) + .unwrap() + .1 + .to_bits(), + _ => self._common_srcs(code) as u64, + } + } +} +impl ALUSrc for Thread<'_> { + fn val(&mut self, code: usize) -> f64 { + let uret: u64 = self.val(code); + match code { + SIMM_SRC => f64::from_bits(uret << 32), + _ => f64::from_bits(uret), + } + } +} + +#[cfg(test)] +mod test_alu_utils { + use super::*; + + #[test] + fn test_write_to_sdst_sgpr() { + let mut thread = _helper_test_thread(); + thread.write_to_sdst(10, 200); + assert_eq!(thread.scalar_reg[10], 200); + } + + #[test] + fn test_write_to_sdst_vcc_val() { + let mut thread = _helper_test_thread(); + let val = 0b1011101011011011111011101111; + thread.write_to_sdst(VCC, val); + assert_eq!(thread.vcc.value, 195935983); + } + + #[test] + fn test_clz_i32_u32() { + let thread = _helper_test_thread(); + assert_eq!(thread.clz_i32_u32(0x00000000), 0xffffffff); + assert_eq!(thread.clz_i32_u32(0x0000cccc), 16); + assert_eq!(thread.clz_i32_u32(0xffff3333), 0); + assert_eq!(thread.clz_i32_u32(0x7fffffff), 1); + assert_eq!(thread.clz_i32_u32(0x80000000), 0); + assert_eq!(thread.clz_i32_u32(0xffffffff), 0); + } + + #[test] + fn test_cls_i32() { + let thread = _helper_test_thread(); + assert_eq!(thread.cls_i32(0x00000000), 0xffffffff); + assert_eq!(thread.cls_i32(0x0000cccc), 16); + assert_eq!(thread.cls_i32(0xffff3333), 16); + assert_eq!(thread.cls_i32(0x7fffffff), 1); + assert_eq!(thread.cls_i32(0x80000000), 1); + } + + #[test] + fn test_sgpr_co_init() { + let mut thread = _helper_test_thread(); + thread.vcc.default_lane = Some(0); + thread.set_sgpr_co(10, true); + thread.vcc.default_lane = Some(1); + assert_eq!(thread.sgpr_co.unwrap().0, 10); + assert_eq!(thread.sgpr_co.unwrap().1.mutations.unwrap()[0], true); + thread.set_sgpr_co(10, true); + assert_eq!(thread.sgpr_co.unwrap().0, 10); + assert_eq!(thread.sgpr_co.unwrap().1.mutations.unwrap()[1], true); + assert_eq!(thread.sgpr_co.unwrap().1.mutations.unwrap()[0], true); + } +} + +#[cfg(test)] +mod test_smem { + use super::*; + + #[test] + fn test_s_load_b32_simple() { + let mut thread = _helper_test_thread(); + let mut buf = vec![0u8; 4]; + let a: u32 = 0xDEADBEEF; + unsafe { + *(buf.as_mut_ptr() as *mut u32) = a; + } + let base_addr = buf.as_ptr() as u64; + thread.scalar_reg.write64(0, base_addr); + r(&vec![0xF4000040, 0xF8000000, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[1], a); + std::mem::forget(buf); + } + + #[test] + fn test_s_load_b32_vcc() { + let mut thread = _helper_test_thread(); + let mut buf = vec![0u8; 4]; + let a: u32 = 0xDEADBEEF; + unsafe { + *(buf.as_mut_ptr() as *mut u32) = a; + } + let base_addr = buf.as_ptr() as u64; + thread.scalar_reg.write64(0, base_addr); + r(&vec![0xF4001A80, 0xF8000000, END_PRG], &mut thread); + assert_eq!(thread.vcc.value, a); + std::mem::forget(buf); + } + + #[test] + fn test_s_load_b32_vcc_addr() { + let mut thread = _helper_test_thread(); + let mut buf = vec![0u8; 4]; + let a: u32 = 0xDEADBEEF; + unsafe { + *(buf.as_mut_ptr() as *mut u32) = a; + } + let addr = buf.as_ptr() as u64; + // NOTE: vcc is an alias for s[106:107] + thread.scalar_reg.write64(VCC, addr); + // TODO: vcc_lo should just read from s106 + thread.vcc.value = (addr & 0xffffffff) as u32; + r(&vec![0xF4000035, 0xF8000000, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[0], a); + std::mem::forget(buf); + } +} + +#[cfg(test)] +mod test_sop1 { + use super::*; + + #[test] + fn test_s_brev_b32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[5] = 8; + r(&vec![0xBE850405, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[5], 268435456); + } + + #[test] + fn test_s_mov_b64() { + let mut thread = _helper_test_thread(); + thread.scalar_reg.write64(16, 5236523008); + r(&vec![0xBE880110, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg.read64(8), 5236523008); + assert_eq!(thread.scalar, true); + } + + #[test] + fn test_mov_exec() { + let mut thread = _helper_test_thread(); + thread.exec.value = 0b11111111110111111110111111111111; + r(&vec![0xBE80007E, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[0], 0b11111111110111111110111111111111); + } + + #[test] + fn test_s_mov_b32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[15] = 42; + r(&vec![0xbe82000f, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[2], 42); + } + + #[test] + fn test_s_bitset0_b32() { + [ + [ + 0b11111111111111111111111111111111, + 0b00000000000000000000000000000001, + 0b11111111111111111111111111111101, + ], + [ + 0b11111111111111111111111111111111, + 0b00000000000000000000000000000010, + 0b11111111111111111111111111111011, + ], + ] + .iter() + .for_each(|[a, b, ret]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[20] = *a; + thread.scalar_reg[10] = *b; + r(&vec![0xBE94100A, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[20], *ret); + }); + } + + #[test] + fn test_s_bitset1_b32() { + [ + [ + 0b00000000000000000000000000000000, + 0b00000000000000000000000000000001, + 0b00000000000000000000000000000010, + ], + [ + 0b00000000000000000000000000000000, + 0b00000000000000000000000000000010, + 0b00000000000000000000000000000100, + ], + ] + .iter() + .for_each(|[a, b, ret]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[20] = *a; + thread.scalar_reg[10] = *b; + r(&vec![0xbe94120a, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[20], *ret); + }); + } + + #[test] + fn test_s_not_b32() { + [[0, 4294967295, 1], [1, 4294967294, 1], [u32::MAX, 0, 0]] + .iter() + .for_each(|[a, ret, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[10] = *a; + r(&vec![0xBE8A1E0A, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[10], *ret); + assert_eq!(*thread.scc, *scc); + }); + } +} + +#[cfg(test)] +mod test_sopk { + use super::*; + + #[test] + fn test_cmp_zero_extend() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[20] = 0xcd14; + r(&vec![0xB494CD14, END_PRG], &mut thread); + assert_eq!(*thread.scc, 1); + + r(&vec![0xB194CD14, END_PRG], &mut thread); + assert_eq!(*thread.scc, 0); + } + + #[test] + fn test_cmp_sign_extend() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[6] = 0x2db4; + r(&vec![0xB1862DB4, END_PRG], &mut thread); + assert_eq!(*thread.scc, 1); + + r(&vec![0xB1862DB4, END_PRG], &mut thread); + assert_eq!(*thread.scc, 1); + } +} + +#[cfg(test)] +mod test_sop2 { + use super::*; + + #[test] + fn test_xor_exec() { + let mut thread = _helper_test_thread(); + thread.exec.value = 0b10010010010010010010010010010010; + thread.scalar_reg[2] = 0b11111111111111111111111111111111; + r(&vec![0x8D02027E, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[2], 1840700269); + } + + #[test] + fn test_s_add_u32() { + [[10, 20, 30, 0], [u32::MAX, 10, 9, 1], [u32::MAX, 0, u32::MAX, 0]] + .iter() + .for_each(|[a, b, expected, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = *a; + thread.scalar_reg[6] = *b; + r(&vec![0x80060206, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[6], *expected); + assert_eq!(*thread.scc, *scc); + }); + } + + #[test] + fn test_s_addc_u32() { + [[10, 20, 31, 1, 0], [10, 20, 30, 0, 0], [u32::MAX, 10, 10, 1, 1]] + .iter() + .for_each(|[a, b, expected, scc_before, scc_after]| { + let mut thread = _helper_test_thread(); + *thread.scc = *scc_before; + thread.scalar_reg[7] = *a; + thread.scalar_reg[3] = *b; + r(&vec![0x82070307, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[7], *expected); + assert_eq!(*thread.scc, *scc_after); + }); + } + + #[test] + fn test_s_add_i32() { + [[-10, 20, 10, 0], [i32::MAX, 1, -2147483648, 1]] + .iter() + .for_each(|[a, b, expected, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[14] = *a as u32; + thread.scalar_reg[10] = *b as u32; + r(&vec![0x81060E0A, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[6], *expected as u32); + assert_eq!(*thread.scc, *scc as u32); + }); + } + + #[test] + fn test_s_sub_i32() { + [[-10, 20, -30, 0], [i32::MAX, -1, -2147483648, 1]] + .iter() + .for_each(|[a, b, expected, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[13] = *a as u32; + thread.scalar_reg[8] = *b as u32; + r(&vec![0x818C080D, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[12], *expected as u32); + assert_eq!(*thread.scc, *scc as u32); + }); + } + + #[test] + fn test_s_lshl_b32() { + [[20, 40, 1], [0, 0, 0]].iter().for_each(|[a, expected, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[15] = *a as u32; + r(&vec![0x8408810F, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[8], *expected as u32); + assert_eq!(*thread.scc, *scc as u32); + }); + } + + #[test] + fn test_s_lshl_b64() { + let mut thread = _helper_test_thread(); + thread.scalar_reg.write64(2, u64::MAX - 30); + r(&vec![0x84828202, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[2], 4294967172); + assert_eq!(thread.scalar_reg[3], 4294967295); + assert_eq!(*thread.scc, 1); + } + + #[test] + fn test_s_ashr_i32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = 36855; + r(&vec![0x86039F02, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 0); + assert_eq!(*thread.scc, 0); + } + + #[test] + fn test_source_vcc() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[10] = 0x55; + thread.vcc.value = 29; + r(&vec![0x8B140A6A, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[20], 21); + } + + #[test] + fn test_s_min_i32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = -42i32 as u32; + thread.scalar_reg[3] = -92i32 as u32; + r(&vec![0x89020203, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[2], -92i32 as u32); + assert_eq!(*thread.scc, 1); + } + + #[test] + fn test_s_mul_hi_u32() { + [[u32::MAX, 10, 9], [u32::MAX / 2, 4, 1]].iter().for_each(|[a, b, expected]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = *a; + thread.scalar_reg[8] = *b; + r(&vec![0x96810800, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[1], *expected); + }); + } + + #[test] + fn test_s_mul_hi_i32() { + [[(u64::MAX) as i32, (u64::MAX / 2) as i32, 0], [2, -2, -1]] + .iter() + .for_each(|[a, b, expected]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = *a as u32; + thread.scalar_reg[8] = *b as u32; + r(&vec![0x97010800, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[1], *expected as u32); + }); + } + + #[test] + fn test_s_mul_i32() { + [[40, 2, 80], [-10, -10, 100]].iter().for_each(|[a, b, expected]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = *a as u32; + thread.scalar_reg[6] = *b as u32; + r(&vec![0x96000600, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[0], *expected as u32); + }); + } + + #[test] + fn test_s_bfe_u64() { + [[2, 4, 2, 0], [800, 400, 32, 0], [-10i32 as u32, 3, 246, 0], [u32::MAX, u32::MAX, 255, 0]] + .iter() + .for_each(|[a_lo, a_hi, ret_lo, ret_hi]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[6] = *a_lo; + thread.scalar_reg[7] = *a_hi; + r(&vec![0x940cff06, 524288, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[12], *ret_lo); + assert_eq!(thread.scalar_reg[13], *ret_hi); + }); + } + + #[test] + fn test_s_bfe_i64() { + [[131073, 0, 1, 0, 0x100000], [-2, 0, -2, -1, 524288], [2, 0, 2, 0, 524288]] + .iter() + .for_each(|[a_lo, a_hi, ret_lo, ret_hi, shift]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[6] = *a_lo as u32; + thread.scalar_reg[7] = *a_hi as u32; + r(&vec![0x948cff06, *shift as u32, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[12], *ret_lo as u32); + assert_eq!(thread.scalar_reg[13], *ret_hi as u32); + }); + } + + #[test] + fn test_s_bfe_u32() { + [ + [67305985, 2], + [0b100000000110111111100000001, 0b1111111], + [0b100000000100000000000000001, 0b0], + [0b100000000111000000000000001, 0b10000000], + [0b100000000111111111100000001, 0b11111111], + ] + .iter() + .for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = *a; + r(&vec![0x9303FF00, 0x00080008, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], *ret); + }); + } + + #[test] + fn test_s_pack_xx_b32_b16() { + let mut thread = _helper_test_thread(); + // ll + thread.scalar_reg[0] = 0x12345678; + r(&vec![0x9903ff00, 0x9ABCDEF0, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 0xdef05678); + // lh + r(&vec![0x9983ff00, 0x9ABCDEF0, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 0x9abc5678); + // hh + r(&vec![0x9a03ff00, 0x9ABCDEF0, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 2596016692); + // hl + r(&vec![0x9a83ff00, 0x9ABCDEF0, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 3740275252); + } +} + +#[cfg(test)] +mod test_sopc { + use super::*; + + #[test] + fn test_s_bitcmp0_b32() { + [[0b00, 0b1, 0], [0b01, 0b1, 1], [0b10, 0b1, 1], [0b10000000, 0b1, 0]] + .iter() + .for_each(|[s0, s1, scc]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[3] = *s0; + thread.scalar_reg[4] = *s1; + r(&vec![0xBF0C0304, END_PRG], &mut thread); + assert_eq!(*thread.scc, *scc); + }) + } +} + +#[cfg(test)] +mod test_vopd { + use super::*; + + #[test] + fn test_inline_const_vopx_only() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = f32::to_bits(0.5); + let constant = f32::from_bits(0x39a8b099); + thread.vec_reg[1] = 10; + r(&vec![0xC8D000FF, 0x00000080, 0x39A8B099, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 0.5 * constant); + assert_eq!(thread.vec_reg[1], 0); + } + + #[test] + fn test_inline_const_vopy_only() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 10; + thread.vec_reg[1] = 10; + r(&vec![0xCA100080, 0x000000FF, 0x3E15F480, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 0); + assert_eq!(thread.vec_reg[1], 0x3e15f480); + + let mut thread = _helper_test_thread(); + thread.vec_reg[18] = f32::to_bits(2.0); + thread.vec_reg[32] = f32::to_bits(4.0); + thread.vec_reg[7] = 10; + r(&vec![0xC9204112, 0x00060EFF, 0x0000006E, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 2.0f32 + 4.0f32); + assert_eq!(thread.vec_reg[7], 120); + } + + #[test] + fn test_inline_const_shared() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = f32::to_bits(2.0); + thread.vec_reg[3] = f32::to_bits(4.0); + let constant = f32::from_bits(0x3e800000); + r(&vec![0xC8C604FF, 0x020206FF, 0x3E800000, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[2]), 2.0 * constant); + assert_eq!(f32::from_bits(thread.vec_reg[3]), 4.0 * constant); + } + + #[test] + fn test_simm_op_shared_1() { + let mut thread = _helper_test_thread(); + thread.vec_reg[23] = f32::to_bits(4.0); + thread.vec_reg[12] = f32::to_bits(2.0); + + thread.vec_reg[13] = f32::to_bits(10.0); + thread.vec_reg[24] = f32::to_bits(3.0); + + let simm = f32::from_bits(0x3e000000); + r(&vec![0xC8841917, 0x0C0C1B18, 0x3E000000, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[12]), 4.0 * simm + 2.0); + assert_eq!(f32::from_bits(thread.vec_reg[13]), 3.0 * simm + 10.0); + } + + #[test] + fn test_simm_op_shared_2() { + let mut thread = _helper_test_thread(); + thread.vec_reg[29] = f32::to_bits(4.0); + thread.vec_reg[10] = f32::to_bits(2.0); + + thread.vec_reg[11] = f32::to_bits(10.0); + thread.vec_reg[26] = f32::to_bits(6.5); + + let simm = 0.125; + r(&vec![0xC880151D, 0x0A0A34FF, 0x3E000000, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[10]), 4.0 * simm + 2.0); + assert_eq!(f32::from_bits(thread.vec_reg[11]), simm * 6.5 + 10.0); + } + + #[test] + fn test_add_mov() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = f32::to_bits(10.5); + r(&vec![0xC9100300, 0x00000080, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 10.5); + assert_eq!(thread.vec_reg[1], 0); + } + + #[test] + fn test_max_add() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = f32::to_bits(5.0); + thread.vec_reg[3] = f32::to_bits(2.0); + thread.vec_reg[1] = f32::to_bits(2.0); + r(&vec![0xCA880280, 0x01000700, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 7.0); + assert_eq!(f32::from_bits(thread.vec_reg[1]), 2.0); + } +} +#[cfg(test)] +mod test_vop1 { + use super::*; + use float_cmp::approx_eq; + + #[test] + fn test_v_cvt_f32_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, 2.0f64.to_bits()); + r(&vec![0xD58F0101, 0x00000100, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[1]), 2.0); + thread.vec_reg.write64(0, (-2.0f64).to_bits()); + r(&vec![0xD58F0101, 0x00000100, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[1]), 2.0); + } + + #[test] + fn test_v_mov_b32_srrc_const0() { + let mut thread = _helper_test_thread(); + r(&vec![0x7e000280, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 0); + r(&vec![0x7e020280, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 0); + r(&vec![0x7e040280, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 0); + } + + #[test] + fn test_v_mov_b32_srrc_register() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[6] = 31; + r(&vec![0x7e020206, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 31); + } + + fn helper_test_fexp(val: f32) -> f32 { + let mut thread = _helper_test_thread(); + thread.vec_reg[6] = val.to_bits(); + r(&vec![0x7E0C4B06, END_PRG], &mut thread); + f32::from_bits(thread.vec_reg[6]) + } + + #[test] + fn test_fexp_1ulp() { + let test_values = [-2.0, -1.0, 0.0, 1.0, 2.0, 3.0]; + for &val in test_values.iter() { + let expected = (2.0_f32).powf(val); + assert!((helper_test_fexp(val) - expected).abs() <= f32::EPSILON); + } + } + + #[test] + fn test_fexp_flush_denormals() { + assert_eq!(helper_test_fexp(f32::from_bits(0xff800000)), 0.0); + assert_eq!(helper_test_fexp(f32::from_bits(0x80000000)), 1.0); + assert_eq!(helper_test_fexp(f32::from_bits(0x7f800000)), f32::from_bits(0x7f800000)); + } + + #[test] + fn test_cast_f32_i32() { + let mut thread = _helper_test_thread(); + [(10.42, 10i32), (-20.08, -20i32)].iter().for_each(|(src, expected)| { + thread.scalar_reg[2] = f32::to_bits(*src); + r(&vec![0x7E001002, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0] as i32, *expected); + }) + } + + #[test] + fn test_cast_f32_u32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[4] = 2; + r(&vec![0x7E000C04, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 1073741824); + } + + #[test] + fn test_cast_u32_f32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 1325400062; + r(&vec![0x7E000F00, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 2147483392); + } + + #[test] + fn test_cast_i32_f32() { + let mut thread = _helper_test_thread(); + [(10.0, 10i32), (-20.0, -20i32)].iter().for_each(|(expected, src)| { + thread.vec_reg[0] = *src as u32; + r(&vec![0x7E000B00, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), *expected); + }) + } + + #[test] + fn test_v_readfirstlane_b32_basic() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 2147483392; + r(&vec![0x7E060500, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], 2147483392); + } + + #[test] + fn test_v_readfirstlane_b32_fancy() { + let mut thread = _helper_test_thread(); + thread.vec_reg.get_lane_mut(0)[13] = 44; + thread.vec_reg.get_lane_mut(1)[13] = 22; + thread.exec.value = 0b00000000000000000000000000000010; + thread.exec.default_lane = Some(2); + r(&vec![0x7E1A050D, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[13], 22); + + thread.exec.value = 0b00000000000000000000000000000000; + thread.exec.default_lane = Some(1); + r(&vec![0x7E1A050D, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[13], 44); + + thread.exec.value = 0b10000000000000000000000000000000; + thread.vec_reg.get_lane_mut(31)[13] = 88; + thread.exec.default_lane = Some(1); + r(&vec![0x7E1A050D, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[13], 88); + } + + #[test] + fn test_v_cls_i32() { + fn t(val: u32) -> u32 { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = val; + r(&vec![0x7E087702, END_PRG], &mut thread); + return thread.vec_reg[4]; + } + + assert_eq!(t(0x00000000), 0xffffffff); + assert_eq!(t(0x40000000), 1); + assert_eq!(t(0x80000000), 1); + assert_eq!(t(0x0fffffff), 4); + assert_eq!(t(0xffff0000), 16); + assert_eq!(t(0xfffffffe), 31); + } + + #[test] + fn test_v_rndne_f32() { + [ + [1.2344, 1.0], + [2.3, 2.0], // [0.5f32, 0.0f32], + [0.51, 1.0], + [f32::from_bits(1186963295), f32::from_bits(1186963456)], + ] + .iter() + .for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = f32::to_bits(*a); + r(&vec![0x7E024700, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[1]), *ret); + }) + } + + #[test] + fn test_v_rndne_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0x652b82fe; + thread.vec_reg[1] = 0x40071547; + r(&vec![0x7E043300, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 0); + assert_eq!(thread.vec_reg[3], 1074266112); + } + + #[test] + fn test_v_cvt_i32_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = 0; + thread.vec_reg[3] = 0x40080000; + r(&vec![0x7E080702, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 3); + } + + #[test] + fn test_v_frexp_mant_f64() { + [[2.0, 0.5], [1.0, 0.5], [0.54, 0.54], [f64::NAN, f64::NAN]] + .iter() + .for_each(|[x, expected]| { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, f64::to_bits(*x)); + r(&vec![0x7E047B00, END_PRG], &mut thread); + let ret = f64::from_bits(thread.vec_reg.read64(2)); + if ret.is_nan() { + assert!(ret.is_nan() && expected.is_nan()); + } else { + assert_eq!(f64::from_bits(thread.vec_reg.read64(2)), *expected) + } + }) + } + + #[test] + fn test_v_rcp_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0; + thread.vec_reg[1] = 1073741824; + r(&vec![0x7E045F00, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 0); + assert_eq!(thread.vec_reg[3], 1071644672); + } + + #[test] + fn test_v_frexp_exp_i32_f64() { + [(3573412790272.0, 42), (69.0, 7), (2.0, 2), (f64::NEG_INFINITY, 0)] + .iter() + .for_each(|(x, ret)| { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, f64::to_bits(*x)); + r(&vec![0x7E047900, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], *ret); + }) + } + + #[test] + fn test_v_rsq_f64() { + [(2.0, 0.707)].iter().for_each(|(x, ret)| { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, f64::to_bits(*x)); + println!("{} {}", thread.vec_reg[0], thread.vec_reg[1]); + r(&vec![0x7E046300, END_PRG], &mut thread); + assert!(approx_eq!(f64, f64::from_bits(thread.vec_reg.read64(2)), *ret, (0.01, 2))); + }) + } +} + +#[cfg(test)] +mod test_vopc { + use super::*; + + #[test] + fn test_v_cmp_gt_i32() { + let mut thread = _helper_test_thread(); + + thread.vec_reg[1] = (4_i32 * -1) as u32; + r(&vec![0x7c8802c1, END_PRG], &mut thread); + assert_eq!(thread.vcc.read(), true); + + thread.vec_reg[1] = 4; + r(&vec![0x7c8802c1, END_PRG], &mut thread); + assert_eq!(thread.vcc.read(), false); + } + + #[test] + fn test_v_cmpx_nlt_f32() { + let mut thread = _helper_test_thread(); + thread.exec.value = 0b010011; + thread.vec_reg[0] = f32::to_bits(0.9); + thread.vec_reg[3] = f32::to_bits(0.4); + r(&vec![0x7D3C0700, END_PRG], &mut thread); + assert_eq!(thread.exec.read(), true); + } + + #[test] + fn test_v_cmpx_gt_i32_e32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[3] = 100; + r(&vec![0x7D8806FF, 0x00000041, END_PRG], &mut thread); + assert_eq!(thread.exec.read(), false); + + thread.vec_reg[3] = -20i32 as u32; + r(&vec![0x7D8806FF, 0x00000041, END_PRG], &mut thread); + assert_eq!(thread.exec.read(), true); + } + + #[test] + fn test_cmp_class_f32() { + let thread = _helper_test_thread(); + assert!(!thread.cmp_class_f32(f32::NAN, 0b00001)); + assert!(thread.cmp_class_f32(f32::NAN, 0b00010)); + + assert!(thread.cmp_class_f32(f32::INFINITY, 0b00000000000000000000001000000000)); + assert!(!thread.cmp_class_f32(f32::INFINITY, 0b00000000000000000000000000000010)); + + assert!(thread.cmp_class_f32(f32::NEG_INFINITY, 0b00000000000000000000000000000100)); + assert!(!thread.cmp_class_f32(f32::NEG_INFINITY, 0b00000000000000000000010000000000)); + + assert!(!thread.cmp_class_f32(0.752, 0b00000000000000000000000000000000)); + assert!(thread.cmp_class_f32(0.752, 0b00000000000000000000000100000000)); + + assert!(!thread.cmp_class_f32(-0.752, 0b00000000000000000000010000000000)); + assert!(thread.cmp_class_f32(-0.752, 0b00000000000000000000010000001000)); + + assert!(!thread.cmp_class_f32(1.0e-42, 0b11111111111111111111111101111111)); + assert!(thread.cmp_class_f32(1.0e-42, 0b00000000000000000000000010000000)); + + assert!(thread.cmp_class_f32(-1.0e-42, 0b00000000000000000000000000010000)); + assert!(!thread.cmp_class_f32(-1.0e-42, 0b11111111111111111111111111101111)); + + assert!(thread.cmp_class_f32(-0.0, 0b00000000000000000000000000100000)); + assert!(thread.cmp_class_f32(0.0, 0b00000000000000000000000001000000)); + } + + #[test] + fn test_cmp_class_f64() { + let thread = _helper_test_thread(); + + assert!(!thread.cmp_class_f64(f64::NAN, 0b00001)); + assert!(thread.cmp_class_f64(f64::NAN, 0b00010)); + + assert!(thread.cmp_class_f64(f64::INFINITY, 0b00000000000000000000001000000000)); + assert!(!thread.cmp_class_f64(f64::INFINITY, 0b00000000000000000000000000000010)); + + assert!(thread.cmp_class_f64(f64::NEG_INFINITY, 0b00000000000000000000000000000100)); + assert!(!thread.cmp_class_f64(f64::NEG_INFINITY, 0b00000000000000000000010000000000)); + + assert!(!thread.cmp_class_f64(0.752, 0b00000000000000000000000000000000)); + assert!(thread.cmp_class_f64(0.752, 0b00000000000000000000000100000000)); + + assert!(!thread.cmp_class_f64(-1.0e-42, 0b00000000000000000000000000010000)); + assert!(thread.cmp_class_f64(-1.0e-42, 0b11111111111111111111111111101111)); + + assert!(thread.cmp_class_f64(-0.0, 0b00000000000000000000000000100000)); + assert!(thread.cmp_class_f64(0.0, 0b00000000000000000000000001000000)); + } +} +#[cfg(test)] +mod test_vop2 { + use super::*; + + #[test] + fn test_v_add_f32_e32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = f32::to_bits(42.0); + thread.vec_reg[0] = f32::to_bits(1.0); + r(&vec![0x06000002, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 43.0); + } + + #[test] + fn test_v_and_b32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[10] = 15; + r(&vec![0x36141482, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[10], 2); + } + + #[test] + fn test_v_mul_f32_e32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = f32::to_bits(21.0); + thread.vec_reg[4] = f32::to_bits(2.0); + r(&vec![0x10060504, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[3]), 42.0); + } + + #[test] + fn test_v_ashrrev_i32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 4294967295; + r(&vec![0x3402009F, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1] as i32, -1); + } + + #[test] + fn test_v_mul_i32_i24() { + [ + [18, 0x64, 1800], + [0b10000000000000000000000000, 0b1, 0], + [0b100000000000000000000000, 0b1, 0b11111111100000000000000000000000], + ] + .iter() + .for_each(|[a, b, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = *a; + r(&vec![0x124E02FF, *b, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[39], *ret); + }); + } + + #[test] + fn test_v_add_nc_u32_const() { + let mut thread = _helper_test_thread(); + thread.vec_reg[18] = 7; + r(&vec![0x4A3024B8, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[24], 63); + } + + #[test] + fn test_v_add_nc_u32_sint() { + let mut thread = _helper_test_thread(); + thread.vec_reg[14] = 7; + thread.vec_reg[6] = 4294967279; + r(&vec![0x4A0C1D06, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[6], 4294967286); + } +} + +#[cfg(test)] +mod test_vopsd { + use super::*; + + #[test] + fn test_v_add_co_u32_scalar_co_zero() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[10] = 0; + thread.vcc.default_lane = Some(1); + thread.vec_reg.default_lane = Some(1); + thread.vec_reg[10] = u32::MAX; + thread.vec_reg[20] = 20; + r(&vec![0xD7000A0A, 0x0002290A, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[10], 19); + assert_eq!(thread.scalar_reg[10], 2); + } + + #[test] + fn test_v_add_co_u32_scalar_co_override() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[10] = 0b11111111111111111111111111111111; + thread.vcc.default_lane = Some(2); + thread.vec_reg.default_lane = Some(2); + thread.vec_reg[10] = u32::MAX; + thread.vec_reg[20] = 20; + r(&vec![0xD7000A0A, 0x0002290A, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[10], 19); + // NOTE: the co mask only writes to the bit that it needs to write, then at the _wave_ + // level, the final result accumulates + assert_eq!(thread.scalar_reg[10], 0b100); + } + + #[test] + fn test_v_add_co_ci_u32() { + [[0, 0, 0b0], [1, -1i32 as usize, 0b10]].iter().for_each(|[lane_id, result, carry_out]| { + let mut thread = _helper_test_thread(); + thread.vcc.default_lane = Some(*lane_id); + thread.vec_reg.default_lane = Some(*lane_id); + thread.scalar_reg[20] = 0b10; + thread.vec_reg[1] = 2; + thread.vec_reg[2] = 2; + r(&vec![0xD5211401, 0x00520501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], *result as u32); + assert_eq!(thread.scalar_reg[20], *carry_out as u32); + }) + } + + #[test] + fn test_v_sub_co_ci_u32() { + [[3, 2, 0b1000], [2, 0, 0b100]].iter().for_each(|[lane_id, result, carry_out]| { + let mut thread = _helper_test_thread(); + thread.vcc.default_lane = Some(*lane_id); + thread.vec_reg.default_lane = Some(*lane_id); + thread.scalar_reg[20] = 0b1010; + thread.vec_reg[1] = *lane_id as u32; + thread.vec_reg[2] = u32::MAX - 1; + r(&vec![0xD5201401, 0x00520501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], *result as u32); + assert_eq!(thread.scalar_reg[20], *carry_out as u32); + }) + } + + #[test] + fn test_v_mad_u64_u32() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(3, u64::MAX - 3); + thread.scalar_reg[13] = 3; + thread.scalar_reg[10] = 1; + r(&vec![0xD6FE0D06, 0x040C140D, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.read64(6), u64::MAX); + assert_eq!(thread.scalar_reg[13], 0); + + thread.vec_reg.write64(3, u64::MAX - 3); + thread.scalar_reg[13] = 4; + thread.scalar_reg[10] = 1; + r(&vec![0xD6FE0D06, 0x040C140D, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[6], 0); + assert_eq!(thread.vec_reg[7], 0); + assert_eq!(thread.scalar_reg[13], 1); + } + + #[test] + fn test_v_add_co_u32() { + let mut thread = _helper_test_thread(); + thread.vcc.default_lane = Some(1); + thread.vec_reg[2] = u32::MAX; + thread.vec_reg[3] = 3; + r(&vec![0xD7000D02, 0x00020503, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 2); + assert_eq!(thread.scalar_reg[13], 0b10); + } + + #[test] + fn test_v_sub_co_u32() { + [[69, 0, 69, 0], [100, 200, 4294967196, 1]].iter().for_each(|[a, b, ret, scc]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[4] = *a; + thread.vec_reg[15] = *b; + r(&vec![0xD7016A04, 0x00021F04, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], *ret); + assert_eq!(thread.vcc.read(), *scc != 0); + }) + } + + #[test] + fn test_return_value_exec_zero() { + let mut thread = _helper_test_thread(); + thread.exec.value = 0b11111111111111111111111111111101; + thread.vcc.default_lane = Some(1); + thread.exec.default_lane = Some(1); + thread.vec_reg[2] = u32::MAX; + thread.vec_reg[3] = 3; + r(&vec![0xD7000D02, 0x00020503, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], u32::MAX); + assert_eq!(thread.scalar_reg[13], 0b10); + } + + #[test] + fn test_v_div_scale_f64() { + let mut thread = _helper_test_thread(); + let v = -0.41614683654714246; + thread.vec_reg.write64(0, f64::to_bits(v)); + thread.vec_reg.write64(2, f64::to_bits(v)); + thread.vec_reg.write64(4, f64::to_bits(0.909)); + r(&vec![0xD6FD7C06, 0x04120500, END_PRG], &mut thread); + thread.vec_reg[6] = 1465086470; + thread.vec_reg[7] = 3218776614; + let ret = f64::from_bits(thread.vec_reg.read64(6)); + assert_eq!(ret, v); + } +} + +#[cfg(test)] +mod test_vop3 { + use super::*; + use float_cmp::approx_eq; + + fn helper_test_vop3(op: u32, a: f32, b: f32) -> f32 { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = f32::to_bits(a); + thread.scalar_reg[6] = f32::to_bits(b); + r(&vec![op, 0x00000006, END_PRG], &mut thread); + return f32::from_bits(thread.vec_reg[0]); + } + + #[test] + fn test_v_add_f32() { + assert_eq!(helper_test_vop3(0xd5030000, 0.4, 0.2), 0.6); + } + + #[test] + fn test_v_mul_f16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1].mut_lo16(f16::from_f32(2.0).to_bits()); + thread.vec_reg[2].mut_lo16(f16::from_f32(4.0).to_bits()); + r(&vec![0xD5350000, 0x00020501, END_PRG], &mut thread); + assert_eq!(f16::from_bits(thread.vec_reg[0] as u16), f16::from_f32(8.0)); + } + + #[test] + fn test_v_max_f32() { + assert_eq!(helper_test_vop3(0xd5100000, 0.4, 0.2), 0.4); + assert_eq!(helper_test_vop3(0xd5100000, 0.2, 0.8), 0.8); + } + + #[test] + fn test_v_mul_f32() { + assert_eq!(helper_test_vop3(0xd5080000, 0.4, 0.2), 0.4 * 0.2); + } + + #[test] + fn test_signed_src() { + // v0, max(s2, s2) + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = f32::to_bits(0.5); + r(&vec![0xd5100000, 0x00000402, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[0]), 0.5); + + // v1, max(-s2, -s2) + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = f32::to_bits(0.5); + r(&vec![0xd5100001, 0x60000402, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[1]), -0.5); + } + + #[test] + fn test_cnd_mask_cond_src_sgpr() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[3] = 0b001; + r(&vec![0xD5010000, 0x000D0280, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 1); + + thread.scalar_reg[3] = 0b00; + r(&vec![0xD5010000, 0x000D0280, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 0); + } + + #[test] + fn test_cnd_mask_cond_src_vcclo() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = 20; + thread.vec_reg[0] = 100; + r(&vec![0xD5010002, 0x41AA0102, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 20); + } + + #[test] + fn test_cnd_mask_float_const() { + let mut thread = _helper_test_thread(); + thread.vcc.value = 0b00000010; + thread.vcc.default_lane = Some(0); + r(&vec![0xD5010003, 0x01A9E480, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3], 0); + + thread.vcc.value = 0b00000010; + thread.vcc.default_lane = Some(1); + r(&vec![0xD5010003, 0x01A9E480, END_PRG], &mut thread); + assert_eq!(f32::from_bits(thread.vec_reg[3]), 1.0); + } + + #[test] + fn test_v_cndmask_b32_e64_neg() { + [[0.0f32, -0.0], [-0.0f32, 0.0], [1.0f32, -1.0], [-1.0f32, 1.0]].iter().for_each(|[input, ret]| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[0] = false as u32; + thread.vec_reg[3] = input.to_bits(); + r(&vec![0xD5010003, 0x2001FF03, 0x80000000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3], ret.to_bits()); + }); + } + + #[test] + fn test_v_mul_hi_i32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = -2i32 as u32; + r(&vec![0xD72E0003, 0x000204FF, 0x2E8BA2E9, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3] as i32, -1); + + thread.vec_reg[2] = 2; + r(&vec![0xD72E0003, 0x000204FF, 0x2E8BA2E9, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3], 0); + } + + #[test] + fn test_v_writelane_b32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[8] = 25056; + r(&vec![0xD7610004, 0x00010008, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.get_lane(0)[4], 25056); + + thread.scalar_reg[9] = 25056; + r(&vec![0xD7610004, 0x00010209, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.get_lane(1)[4], 25056); + } + + #[test] + fn test_v_readlane_b32() { + let mut thread = _helper_test_thread(); + thread.vec_reg.get_lane_mut(15)[4] = 0b1111; + r(&vec![0xD760006A, 0x00011F04, END_PRG], &mut thread); + assert_eq!(thread.vcc.read(), true); + } + + #[test] + fn test_v_lshlrev_b64() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(2, 100); + thread.vec_reg[4] = 2; + r(&vec![0xD73C0002, 0x00020504, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.read64(2), 400); + } + + #[test] + fn test_v_lshrrev_b64() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(2, 100); + thread.vec_reg[4] = 2; + r(&vec![0xd73d0002, 0x00020504, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.read64(2), 25); + } + + #[test] + fn test_v_add_f64_neg_modifier() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0x652b82fe; + thread.vec_reg[1] = 0x40071547; + thread.vec_reg[2] = 0; + thread.vec_reg[3] = 0x40080000; + r(&vec![0xD7270004, 0x40020500, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 1519362112); + assert_eq!(thread.vec_reg[5], 3216856851); + } + + #[test] + fn test_v_cvt_f32_f16_abs_modifier() { + [[0.4, 0.4], [-0.4, 0.4]].iter().for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = f16::from_f32_const(*a).to_bits() as u32; + r(&vec![0xD58B0102, 0x00000101, END_PRG], &mut thread); + assert!(approx_eq!(f32, f32::from_bits(thread.vec_reg[2]), *ret, (0.01, 2))); + }); + } + + #[test] + fn test_v_alignbit_b32() { + let mut thread = _helper_test_thread(); + thread.scalar_reg[4] = 5340353; + thread.scalar_reg[10] = 3072795146; + thread.vec_reg[0] = 8; + r(&vec![0xD6160001, 0x04001404, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 3250005794); + } + + #[test] + fn test_v_bfe_i32() { + [ + [0b00000000000000000000000000000001, -1], + [0b00000000000000000000000000000000, 0], + [0b00000000000000000000000000000010, 0], + ] + .iter() + .for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = *a as u32; + r(&vec![0xD6110005, 0x02050102, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5] as i32, *ret); + }); + + [ + [0b00000000000000000000000000000010, -2], + [0b00000000000000000000000000000001, 1], + [0b00000000000000000000000000000100, 0], + ] + .iter() + .for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = *a as u32; + r(&vec![0xD6110005, 0x02090102, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5] as i32, *ret); + }); + + [ + [0b00100000000000000000000000000000, 0b100000000000000000000000000000], + [0b00000000000000001000000000000000, 0b1000000000000000], + [-1, -1], + ] + .iter() + .for_each(|[a, ret]| { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = *a as u32; + r(&vec![0xD6110005, 0x03050102, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5] as i32, *ret); + }); + } + + #[test] + fn test_v_ashrrev_i16() { + let mut thread = _helper_test_thread(); + [ + [0b10000000000000000000000000000000, 0], + [0b10000000000000000000000000000111, 3], + [0b0000000000000000, 0], + [0b1000000000000000, 0b1100000000000000], + [0b0100000000000000, 0b0010000000000000], + [0b0010000000000000, 0b0001000000000000], + [0b1010000000000000, 0b1101000000000000], + [0b1110000000000000, 0b1111000000000000], + [0b0110000000000000, 0b0011000000000000], + ] + .iter() + .for_each(|[a, ret]| { + thread.vec_reg[2] = *a; + thread.scalar_reg[1] = 1; + r(&vec![0xd73a0005, 0b11000001100000010000000001, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], *ret); + }); + + [ + [0b1000000000000000, 0b1111, 0b1111111111111111], + [0b1000000000000000, 0b11111, 0b1111111111111111], + [0b1000000000000000, 0b0111, 0b1111111100000000], + ] + .iter() + .for_each(|[a, shift, ret]| { + thread.vec_reg[2] = *a; + thread.scalar_reg[1] = *shift; + r(&vec![0xd73a0005, 0b11000001100000010000000001, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], *ret); + }); + + thread.vec_reg[5] = 0b11100000000000001111111111111111; + thread.vec_reg[2] = 0b0100000000000000; + thread.scalar_reg[1] = 1; + r(&vec![0xd73a0005, 0b11000001100000010000000001, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 0b11100000000000000010000000000000); + } + + #[test] + fn test_v_add_nc_u16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[5] = 10; + thread.vec_reg[8] = 20; + r(&vec![0xD7030005, 0x00021105, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 30); + } + + #[test] + fn test_v_mul_lo_u16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[5] = 2; + thread.vec_reg[15] = 0; + r(&vec![0xD705000F, 0x00010B05, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[15], 10); + + thread.vec_reg[5] = 2; + thread.vec_reg[15] = 0b10000000000000000000000000000000; + r(&vec![0xD705000F, 0x00010B05, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[15], 0b10000000000000000000000000000000 + 10); + } + + #[test] + fn test_v_cmp_gt_u16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = 52431; + thread.scalar_reg[5] = 0; + r(&vec![0xD43C0005, 0x000202FF, 0x00003334, END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[5], 0); + } + + #[test] + fn test_v_cmp_ngt_f32_abs() { + [(0.5f32, 0.5f32, 1), (-0.5, 0.5, 1), (0.1, 0.2, 0), (-0.1, 0.2, 0)] + .iter() + .for_each(|(x, y, ret)| { + let mut thread = _helper_test_thread(); + thread.scalar_reg[2] = x.to_bits(); + r(&vec![0xD41B0203, 0x000004FF, y.to_bits(), END_PRG], &mut thread); + assert_eq!(thread.scalar_reg[3], *ret); + }) + } + #[test] + fn test_fma() { + fn v_fma_f32(a: u32, b: u32, c: u32, ret: u32) { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = b; + thread.scalar_reg[3] = c; + r(&vec![0xD6130000, 0x000E02FF, a, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], ret); + } + fn v_fmac_f32(a: u32, b: u32, c: u32, ret: u32) { + let mut thread = _helper_test_thread(); + thread.scalar_reg[1] = a; + thread.scalar_reg[2] = b; + thread.vec_reg[0] = c; + r(&vec![0xd52b0000, 0x401, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], ret); + } + [[0xbfc90fda, 1186963456, 1192656896, 3204127872]].iter().for_each(|[a, b, c, ret]| { + v_fma_f32(*a, *b, *c, *ret); + v_fmac_f32(*a, *b, *c, *ret); + }) + } + + #[test] + fn test_v_perm_b32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = 15944; + thread.vec_reg[0] = 84148480; + r(&vec![0xD644000F, 0x03FE0101, 0x05040100, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[15], 1044906240); + } + + #[test] + fn test_v_mul_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0x5a8fa040; + thread.vec_reg[1] = 0xbfbd5713; + thread.vec_reg[2] = 0x3b39803f; + thread.vec_reg[3] = 0x3c7abc9e; + r(&vec![0xD7280004, 0x00020500, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 1602589062); + assert_eq!(thread.vec_reg[5], 3158868912); + } + + #[test] + fn test_v_fma_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0x5a8fa040; + thread.vec_reg[1] = 0xbfbd5713; + thread.vec_reg[2] = 0xfefa39ef; + thread.vec_reg[3] = 0x3fe62e42; + thread.vec_reg[4] = 0x5f859186; + thread.vec_reg[5] = 0xbc4883b0; + r(&vec![0xD6140006, 0x04120500, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[6], 3883232879); + assert_eq!(thread.vec_reg[7], 3216266823); + } + + #[test] + fn test_v_fma_f64_const() { + let mut thread = _helper_test_thread(); + thread.vec_reg[0] = 0xf690ecbf; + thread.vec_reg[1] = 0x3fdf2b4f; + thread.vec_reg[2] = 0xe7756e6f; + thread.vec_reg[3] = 0xbfb45647; + r(&vec![0xD6140004, 0x03CA0500, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 962012421); + assert_eq!(thread.vec_reg[5], 1072612110); + } + + #[test] + fn test_v_ldexp_f64() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, f64::to_bits(5.0)); + thread.vec_reg[2] = 3; + thread.vec_reg[3] = 3; + r(&vec![0xD72B0000, 0x00020500, END_PRG], &mut thread); + let val = f64::from_bits(thread.vec_reg.read64(0)); + assert_eq!(val, 40.0); + } + + #[test] + fn test_simm_resolve_int_in_double_op() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, 3.0f64.to_bits()); + let simm = 0xFFFFFFE0; + r(&vec![0xD72B0002, 0x0001FF00, simm, END_PRG], &mut thread); + assert_eq!(f64::from_bits(thread.vec_reg.read64(2)), 3.0 * 2.0.powi(-32)); + } + + #[test] + fn test_simm_resolve_double_in_double_op() { + let mut thread = _helper_test_thread(); + thread.vec_reg.write64(0, 2.0f64.to_bits()); + let simm = 0x40080000; + r(&vec![0xD7280000, 0x000200FF, simm, END_PRG], &mut thread); + assert_eq!(f64::from_bits(thread.vec_reg.read64(0)), 6.0); + } +} + +#[cfg(test)] +mod test_vopp { + use super::*; + + #[test] + fn test_v_fma_mix_f32() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = 1065353216; + thread.scalar_reg[2] = 3217620992; + thread.vec_reg[1] = 15360; + r(&vec![0xCC204403, 0x04040502, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3], 3205627904); + + thread.vec_reg[2] = 1065353216; + thread.scalar_reg[2] = 3217620992; + thread.vec_reg[1] = 48128; + r(&vec![0xCC204403, 0x04040502, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[3], 3205627904); + } + + #[test] + fn test_packed_opsel_000_op_000() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = 1; + thread.vec_reg[2] = 2; + thread.vec_reg[3] = 3; + r(&vec![0xCC090004, 0x040E0501, 0xBFB00000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1010000000000000101); + } + + #[test] + fn test_packed_opsel_001_op_100() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = 1; + thread.vec_reg[2] = 2; + thread.vec_reg[3] = 3; + r(&vec![0xCC092004, 0x0C0E0501, 0xBFB00000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b110000000000000010); + } + + #[test] + fn test_packed_inline_const_int() { + let mut thread = _helper_test_thread(); + thread.vec_reg[1] = 1; + thread.vec_reg[2] = 2; + thread.vec_reg[3] = 3; + + r(&vec![0xCC090004, 0x020E0501, 0xBFB00000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1010000000000000101); + + r(&vec![0xCC090804, 0x0A0E0501, 0xBFB00000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b110000000000000011); + + r(&vec![0xCC096004, 0x020E0501, 0xBFB00000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b100000000000000010); + + r(&vec![0xCC090004, 0x03FE0501, 0x00000080, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 8519810); + } + + #[test] + fn test_pk_fma_f16_inline_const() { + let mut thread = _helper_test_thread(); + thread.vec_reg[2] = 0x393a35f6; + thread.vec_reg[3] = 0x2800; + + r(&vec![0xCC0E0004, 0x03FE0702, 0x0000A400, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 2618596372); + + r(&vec![0xCC0E0004, 0x0BFE0702, 0x0000A400, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 485006356); + + r(&vec![0xCC0E0004, 0x1BFE0702, 0x0000A400, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 2751503380); + + r(&vec![0xCC0E0804, 0x03FE0702, 0x0000A400, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 2618563816); + + r(&vec![0xCC0E1804, 0x03FE0702, 0x0000A400, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 2618598400); + } + + #[test] + fn test_v_fma_mixhilo_f16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[11] = 1065353216; + thread.vec_reg[7] = 3047825943; + thread.vec_reg[16] = 3047825943; + + thread.vec_reg[14] = 0b10101010101010101111111111111111; + r(&vec![0xCC21000E, 0x04420F0B, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[14], 0b10101010101010101000000000101011); + + thread.vec_reg[14] = 0b10101010101010101111111111111111; + r(&vec![0xCC22000E, 0x04420F0B, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[14], 0b10000000001010111111111111111111); + } + + #[test] + fn test_v_pk_lshlrev_b16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[3] = 0b1010101011101101; + + r(&vec![0xCC044004, 0x0002068E, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1000000000000000100000000000000); + + r(&vec![0xCC044004, 0x1002068E, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b100000000000000); + + r(&vec![0xCC044004, 0x100206FF, 0x00010002, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1010101110110100); + r(&vec![0xCC044004, 0x100206FF, 0x05012002, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1010101110110100); + + r(&vec![0xCC044004, 0x100206FF, 0x0503E00F, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1000000000000000); + r(&vec![0xCC044004, 0x100206FF, 0x0503E007, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b111011010000000); + r(&vec![0xCC044004, 0x100206FF, 0x0503E01F, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[4], 0b1000000000000000); + } + + #[test] + fn test_pk_fma_with_neg() { + let mut thread = _helper_test_thread(); + let a1 = f16::from_f32(1.0); + let b1 = f16::from_f32(2.0); + let c1 = f16::from_f32(3.0); + + let a2 = f16::from_f32(4.0); + let b2 = f16::from_f32(5.0); + let c2 = f16::from_f32(6.0); + + thread.vec_reg[0] = (a1.to_bits() as u32) << 16 | (a2.to_bits() as u32); + thread.vec_reg[9] = (b1.to_bits() as u32) << 16 | (b2.to_bits() as u32); + thread.vec_reg[10] = (c1.to_bits() as u32) << 16 | (c2.to_bits() as u32); + + r(&vec![0xCC0E3805, 0x042A1300, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 1317029120); + + r(&vec![0xCC0E3805, 0x242A1300, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 1317026816); + + r(&vec![0xCC0E3B05, 0x042A1300, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 1317029120); + + r(&vec![0xCC0E3905, 0x042A1300, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[5], 3405792512); + } + + #[test] + fn test_pk_add_f16_with_float_const() { + let mut thread = _helper_test_thread(); + let a1 = f16::from_f32(5.0); + let a2 = f16::from_f32(10.0); + + thread.vec_reg[1] = (a1.to_bits() as u32) << 16 | (a2.to_bits() as u32); + r(&vec![0xCC0F4002, 0x0001E501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 1233144192); + + r(&vec![0xCC0F5002, 0x0001E501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 1233144064); + + r(&vec![0xCC0F5002, 0x1001E501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 1224755456); + + r(&vec![0xCC0F5802, 0x1801E501, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[2], 1157645568); + } +} + +#[cfg(test)] +mod test_flat { + use super::*; + use std::alloc::{alloc, handle_alloc_error, Layout}; + + #[test] + fn test_scratch_swap_values() { + let mut thread = _helper_test_thread(); + thread.vec_reg[13] = 42; + thread.vec_reg[14] = 10; + r( + &vec![ + 0xDC690096, 0x007C0D00, 0xDC69001E, 0x007C0E00, 0xDC51001E, 0x0D7C0000, 0xDC510096, 0x0E7C0000, END_PRG, + ], + &mut thread, + ); + assert_eq!(thread.vec_reg[13], 10); + assert_eq!(thread.vec_reg[14], 42); + } + + #[test] + fn test_scratch_load_dword_offset() { + let mut thread = _helper_test_thread(); + thread.vec_reg[14] = 14; + thread.vec_reg[15] = 23; + r(&vec![0xDC6D000A, 0x007C0E00, 0xDC51000A, 0x0E7C0000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[14], 14); + + r(&vec![0xDC6D000A, 0x007C0E00, 0xDC51000E, 0x0E7C0000, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[14], 23); + } + + #[test] + fn test_global_load_d16_hi_b16() { + let mut thread = _helper_test_thread(); + thread.vec_reg[13] = 0b10101011101101001111111111111111; + unsafe { + let layout = Layout::new::(); + let ptr = alloc(layout); + if ptr.is_null() { + handle_alloc_error(layout) + } + *(ptr as *mut u16) = 42; + thread.vec_reg.write64(10, ptr as u64); + } + r(&vec![0xDC8E0000, 0x0D7C000A, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[13], 0b00000000001010101111111111111111); + } +} + +#[cfg(test)] +mod test_lds { + use super::*; + #[test] + fn test_ds_load_offset() { + let mut thread = _helper_test_thread(); + thread.lds.write(256, 69); + thread.vec_reg[9] = 0; + r(&vec![0xD8D80100, 0x01000009, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 69); + + thread.lds.write(800, 69); + thread.vec_reg[9] = 0; + r(&vec![0xD8D80320, 0x01000009, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 69); + + thread.lds.write(3, 69); + thread.vec_reg[9] = 0; + r(&vec![0xD8D80003, 0x01000009, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[1], 69); + } + + #[test] + fn test_ds_load_dwords() { + let mut thread = _helper_test_thread(); + thread.lds.write(0, 100); + thread.lds.write(4, 200); + thread.vec_reg[9] = 0; + r(&vec![0xD9D80000, 0x00000009, END_PRG], &mut thread); + assert_eq!(thread.vec_reg.read64(0), 858993459300); + + thread.lds.write(0, 1); + thread.lds.write(4, 2); + thread.lds.write(8, 3); + thread.lds.write(12, 4); + thread.vec_reg[9] = 0; + r(&vec![0xDBFC0000, 0x00000009, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 1); + assert_eq!(thread.vec_reg[1], 2); + assert_eq!(thread.vec_reg[2], 3); + assert_eq!(thread.vec_reg[3], 4); + } + + #[test] + fn test_ds_load_u8() { + let mut thread = _helper_test_thread(); + thread.lds.write(0, 17); + thread.vec_reg[0] = 0; + r(&vec![0xD8E80000, 0x00000100, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 17); + + thread.lds.write(0, 264); + thread.vec_reg[0] = 0; + r(&vec![0xD8E80000, 0x00000100, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 8); + + thread.lds.write(8, 23); + thread.vec_reg[0] = 0; + r(&vec![0xD8E80008, 0x00000100, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 23); + + thread.lds.write(16, 29); + thread.vec_reg[0] = 0; + r(&vec![0xD8E80010, 0x00000100, END_PRG], &mut thread); + assert_eq!(thread.vec_reg[0], 29); + } + + #[test] + fn test_ds_store_dwords() { + let mut thread = _helper_test_thread(); + thread.vec_reg[9] = 69; + thread.vec_reg[0] = 0; + r(&vec![0xD83403E8, 0x00000900, END_PRG], &mut thread); + assert_eq!(thread.lds.read(1000), 69); + } + + #[test] + fn test_ds_store_half() { + let mut thread = _helper_test_thread(); + thread.vec_reg[9].mut_lo16(f16::from_f32(1.2).to_bits()); + thread.vec_reg[9].mut_hi16(f16::from_f32(4.3).to_bits()); + thread.vec_reg[0] = 0; + thread.vec_reg[1] = 2; + r(&vec![0xDA840000, 0x00000900, 0xD87C0000, 0x00000901, END_PRG], &mut thread); + assert_eq!(thread.lds.read(0) as u16, f16::from_f32(4.3).to_bits()); + assert_eq!(thread.lds.read(2) as u16, f16::from_f32(1.2).to_bits()); + } +} +#[allow(dead_code)] +fn r(prg: &Vec, thread: &mut Thread) { + let mut pc = 0; + let instructions = prg.to_vec(); + thread.pc_offset = 0; + if thread.exec.value == 0 { + thread.exec.value = u32::MAX; + } + + loop { + if instructions[pc] == END_PRG { + break; + } + if instructions[pc] == 0xbfb60003 || instructions[pc] >> 20 == 0xbf8 { + pc += 1; + continue; + } + thread.pc_offset = 0; + thread.stream = instructions[pc..instructions.len()].to_vec(); + thread.interpret().unwrap(); + thread.simm = None; + if thread.vcc.mutations.is_some() { + thread.vcc.apply_muts(); + thread.vcc.mutations = None; + } + if thread.exec.mutations.is_some() { + thread.exec.apply_muts(); + thread.exec.mutations = None; + } + if let Some((idx, mut wv)) = thread.sgpr_co { + wv.apply_muts(); + thread.scalar_reg[*idx] = wv.value; + } + if *DEBUG { + println!() + } + pc = ((pc as isize) + 1 + (thread.pc_offset as isize)) as usize; + } +} +fn _helper_test_thread() -> Thread<'static> { + let static_lds: &'static mut VecDataStore = Box::leak(Box::new(VecDataStore::new())); + let static_sgpr: &'static mut [u32; SGPR_COUNT] = Box::leak(Box::new([0; SGPR_COUNT])); + let static_vgpr: &'static mut VGPR = Box::leak(Box::new(VGPR::new())); + let static_scc: &'static mut u32 = Box::leak(Box::new(0)); + let static_exec: &'static mut WaveValue = Box::leak(Box::new(WaveValue::new(u32::MAX, 32))); + let static_vcc: &'static mut WaveValue = Box::leak(Box::new(WaveValue::new(0, 32))); + let static_sds: &'static mut VecDataStore = Box::leak(Box::new(VecDataStore::new())); + let static_co: &'static mut Option<(usize, WaveValue)> = Box::leak(Box::new(None)); + + let thread = Thread { + scalar_reg: static_sgpr, + vec_reg: static_vgpr, + scc: static_scc, + vcc: static_vcc, + exec: static_exec, + lds: static_lds, + sds: static_sds, + simm: None, + pc_offset: 0, + stream: vec![], + sgpr_co: static_co, + warp_size: 32, + scalar: false, + }; + thread.vec_reg.default_lane = Some(0); + thread.vcc.default_lane = Some(0); + thread.exec.default_lane = Some(0); + return thread; +} diff --git a/tinygrad_repo/extra/remu/src/work_group.rs b/tinygrad_repo/extra/remu/src/work_group.rs new file mode 100644 index 0000000000..f1b0a7d8c7 --- /dev/null +++ b/tinygrad_repo/extra/remu/src/work_group.rs @@ -0,0 +1,233 @@ +use crate::helpers::{colored, DEBUG}; +use crate::state::{Register, VecDataStore, WaveValue, VGPR}; +use crate::thread::{Thread, END_PRG, SGPR_COUNT}; +use std::collections::HashMap; + +pub const WAVE_SIZE: usize = 32; + +pub struct WorkGroup<'a> { + dispatch_dim: u32, + id: [u32; 3], + lds: VecDataStore, + kernel: &'a Vec, + kernel_args: *const u64, + launch_bounds: [u32; 3], + wave_state: HashMap, +} + +#[derive(Debug, Clone)] +struct WaveState { + scalar_reg: [u32; SGPR_COUNT], + scc: u32, + vcc: WaveValue, + exec: WaveValue, + vec_reg: VGPR, + pc: usize, + sds: HashMap, +} + +const SYNCS: [u32; 4] = [0xBF89FC07, 0xBC7C0000, 0xBF890007, 0xbFB60003]; +const S_BARRIER: u32 = 0xBFBD0000; +impl<'a> WorkGroup<'a> { + pub fn new(dispatch_dim: u32, id: [u32; 3], launch_bounds: [u32; 3], kernel: &'a Vec, kernel_args: *const u64) -> Self { + Self { dispatch_dim, id, kernel, launch_bounds, kernel_args, lds: VecDataStore::new(), wave_state: HashMap::new() } + } + + pub fn exec_waves(&mut self) -> Result<(), i32> { + let mut threads = vec![]; + for z in 0..self.launch_bounds[2] { + for y in 0..self.launch_bounds[1] { + for x in 0..self.launch_bounds[0] { + threads.push([x, y, z]) + } + } + } + let waves = threads.chunks(WAVE_SIZE).collect::>(); + + let mut sync = false; + for (i, x) in self.kernel.iter().enumerate() { + if i != 0 && *x == S_BARRIER { + sync = true; + break; + } + } + + for _ in 0..=(sync as usize) { + for w in waves.iter().enumerate() { + self.exec_wave(w)? + } + } + Ok(()) + } + + fn exec_wave(&mut self, (wave_id, threads): (usize, &&[[u32; 3]])) -> Result<(), i32> { + let (mut scalar_reg, mut scc, mut pc, mut vec_reg, mut vcc, mut exec, mut sds) = match self.wave_state.get(&wave_id) { + None => { + let mut scalar_reg = [0; SGPR_COUNT]; + scalar_reg.write64(0, self.kernel_args as u64); + + let [gx, gy, gz] = self.id; + match self.dispatch_dim { + 3 => (scalar_reg[13], scalar_reg[14], scalar_reg[15]) = (gx, gy, gz), + 2 => (scalar_reg[14], scalar_reg[15]) = (gx, gy), + _ => scalar_reg[15] = gx, + } + + let mut vec_reg = VGPR::new(); + for (t, [x, y, z]) in threads.iter().enumerate() { + vec_reg.get_lane_mut(t)[0] = match &self.launch_bounds { + [_, 1, 1] => *x, + _ => (z << 20) | (y << 10) | x, + } + } + + let vcc = WaveValue::new(0, threads.len()); + let active = (!0u32).wrapping_shr(32 - (threads.len() as u32)); + let exec = WaveValue::new(active, threads.len()); + + let sds = (0..=31).map(|i| (i, VecDataStore::new())).collect(); + (scalar_reg, 0, 0, vec_reg, vcc, exec, sds) + } + + Some(val) => { + let val = val.clone(); + (val.scalar_reg, val.scc, val.pc, val.vec_reg, val.vcc, val.exec, val.sds) + } + }; + + loop { + if self.kernel[pc] == END_PRG { + break Ok(()); + } + if self.kernel[pc] == S_BARRIER && self.wave_state.get(&wave_id).is_none() { + self.wave_state.insert(wave_id, WaveState { scalar_reg, scc, vec_reg, vcc, exec, pc, sds }); + break Ok(()); + } + if self.kernel[pc] == S_BARRIER || SYNCS.contains(&self.kernel[pc]) || self.kernel[pc] >> 20 == 0xbf8 || self.kernel[pc] == 0x7E000000 { + pc += 1; + continue; + } + + let mut sgpr_co = None; + for (lane_id, [x, y, z]) in threads.iter().enumerate() { + vec_reg.default_lane = Some(lane_id); + vcc.default_lane = Some(lane_id); + exec.default_lane = Some(lane_id); + if *DEBUG { + let lane = format!("{:<2} {:08X} ", lane_id, self.kernel[pc]); + let state = match exec.read() { + true => "green", + false => "gray", + }; + let [id0, id1, id2] = self.id; + print!("[{id0:<3} {id1:<3} {id2:<3}] [{x:<3} {y:<3} {z:<3}] {}", colored(&lane, state)); + } + let mut thread = Thread { + scalar_reg: &mut scalar_reg, + scc: &mut scc, + vec_reg: &mut vec_reg, + vcc: &mut vcc, + exec: &mut exec, + lds: &mut self.lds, + sds: &mut sds.get_mut(&lane_id).unwrap(), + pc_offset: 0, + stream: self.kernel[pc..self.kernel.len()].to_vec(), + scalar: false, + simm: None, + warp_size: threads.len(), + sgpr_co: &mut sgpr_co, + }; + thread.interpret()?; + if *DEBUG { + println!(); + } + if thread.scalar { + pc = ((pc as isize) + 1 + (thread.pc_offset as isize)) as usize; + break; + } + if lane_id == threads.len() - 1 { + pc = ((pc as isize) + 1 + (thread.pc_offset as isize)) as usize; + } + } + + if vcc.mutations.is_some() { + vcc.apply_muts(); + vcc.mutations = None; + } + if exec.mutations.is_some() { + exec.apply_muts(); + exec.mutations = None; + } + if let Some((idx, mut wv)) = sgpr_co.take() { + wv.apply_muts(); + scalar_reg[idx] = wv.value; + } + } + } +} + +#[cfg(test)] +mod test_workgroup { + use super::*; + + // TODO: make this generic by adding the assembler + fn global_store_sgpr(addr: u64, instructions: Vec, src: u32) -> Vec { + [ + instructions, + vec![ + 0x7E020200 + src, + 0x7E0402FF, + addr as u32, + 0x7E0602FF, + (addr >> 32) as u32, + 0xDC6A0000, + 0x007C0102, + ], + vec![END_PRG], + ] + .concat() + } + + #[test] + fn test_wave_value_state_vcc() { + let mut ret: u32 = 0; + let kernel = vec![ + 0xBEEA00FF, + 0b11111111111111111111111111111111, // initial vcc state + 0x7E140282, + 0x7C94010A, // cmp blockDim.x == 2 + ]; + let addr = (&mut ret as *mut u32) as u64; + let kernel = global_store_sgpr(addr, kernel, 106); + let mut wg = WorkGroup::new(1, [0, 0, 0], [3, 1, 1], &kernel, [addr].as_ptr()); + wg.exec_waves().unwrap(); + assert_eq!(ret, 0b100); + } + + #[test] + fn test_wave_value_state_exec() { + let mut ret: u32 = 0; + let kernel = vec![ + 0xBEFE00FF, + 0b11111111111111111111111111111111, + 0x7E140282, + 0x7D9C010A, // cmpx blockDim.x <= 2 + ]; + let addr = (&mut ret as *mut u32) as u64; + let kernel = global_store_sgpr(addr, kernel, 126); + let mut wg = WorkGroup::new(1, [0, 0, 0], [4, 1, 1], &kernel, [addr].as_ptr()); + wg.exec_waves().unwrap(); + assert_eq!(ret, 0b0111); + } + + #[test] + fn test_wave_value_sgpr_co() { + let mut ret: u32 = 0; + let kernel = vec![0xBE8D00FF, 0x7FFFFFFF, 0x7E1402FF, u32::MAX, 0xD700000A, 0x0002010A]; + let addr = (&mut ret as *mut u32) as u64; + let kernel = global_store_sgpr(addr, kernel, 0); + let mut wg = WorkGroup::new(1, [0, 0, 0], [5, 1, 1], &kernel, [addr].as_ptr()); + wg.exec_waves().unwrap(); + assert_eq!(ret, 0b11110); + } +} diff --git a/tinygrad_repo/extra/remu/test/hwtest.py b/tinygrad_repo/extra/remu/test/hwtest.py new file mode 100644 index 0000000000..0cc2ba0fc2 --- /dev/null +++ b/tinygrad_repo/extra/remu/test/hwtest.py @@ -0,0 +1,202 @@ +import numpy as np +import unittest +import subprocess, struct, math +from typing import cast +from tinygrad.runtime.ops_amd import AMDProgram, AMDDevice +from tinygrad import Tensor, dtypes, Device +from tinygrad.helpers import diskcache, OSX, getenv + +@diskcache +def assemble(code:str) -> bytes: + try: + LLVM_MC = "llvm-mc" if OSX else "/opt/rocm/llvm/bin/llvm-mc" + return subprocess.run([LLVM_MC, "--arch=amdgcn", "--mcpu=gfx1100", "--triple=amdgcn-amd-amdhsa", "-filetype=obj", "-o", "-"], + input=code.encode("utf-8"), stdout=subprocess.PIPE, stderr=subprocess.PIPE, check=True).stdout + except subprocess.CalledProcessError as e: + print("stderr:") + print(e.stderr.decode()) + raise + +# copied from extra/rdna +def get_prg(code:str, v_cnt:int, s_cnt:int): + function_name = "test" + metadata = f""" +amdhsa.kernels: +- .args: + - .address_space: global + .name: buf_0 + .offset: 0 + .size: 8 + .type_name: unsigned int* + .value_kind: global_buffer + .group_segment_fixed_size: 0 + .kernarg_segment_align: 8 + .kernarg_segment_size: 8 + .language: OpenCL C + .language_version: + - 1 + - 2 + .max_flat_workgroup_size: 256 + .name: test + .private_segment_fixed_size: 0 + .sgpr_count: {s_cnt} + .sgpr_spill_count: 0 + .symbol: test.kd + .uses_dynamic_stack: false + .vgpr_count: {v_cnt} + .vgpr_spill_count: 0 + .wavefront_size: 32 +amdhsa.target: amdgcn-amd-amdhsa--gfx1100 +amdhsa.version: +- 1 +- 2 + """ + boilerplate_start = f""" + .rodata + .global {function_name}.kd + .type {function_name}.kd,STT_OBJECT + .align 0x10 + .amdhsa_kernel {function_name}""" + kernel_desc = { + '.amdhsa_group_segment_fixed_size': 0, '.amdhsa_private_segment_fixed_size': 0, '.amdhsa_kernarg_size': 0, + '.amdhsa_next_free_vgpr': v_cnt, # this matters! + '.amdhsa_reserve_vcc': 0, '.amdhsa_reserve_xnack_mask': 0, + '.amdhsa_next_free_sgpr': s_cnt, + '.amdhsa_float_round_mode_32': 0, '.amdhsa_float_round_mode_16_64': 0, '.amdhsa_float_denorm_mode_32': 3, '.amdhsa_float_denorm_mode_16_64': 3, + '.amdhsa_dx10_clamp': 1, '.amdhsa_ieee_mode': 1, '.amdhsa_fp16_overflow': 0, + '.amdhsa_workgroup_processor_mode': 1, '.amdhsa_memory_ordered': 1, '.amdhsa_forward_progress': 0, '.amdhsa_enable_private_segment': 0, + '.amdhsa_system_sgpr_workgroup_id_x': 1, '.amdhsa_system_sgpr_workgroup_id_y': 1, '.amdhsa_system_sgpr_workgroup_id_z': 1, + '.amdhsa_system_sgpr_workgroup_info': 0, '.amdhsa_system_vgpr_workitem_id': 2, # is amdhsa_system_vgpr_workitem_id real? + '.amdhsa_exception_fp_ieee_invalid_op': 0, '.amdhsa_exception_fp_denorm_src': 0, + '.amdhsa_exception_fp_ieee_div_zero': 0, '.amdhsa_exception_fp_ieee_overflow': 0, '.amdhsa_exception_fp_ieee_underflow': 0, + '.amdhsa_exception_fp_ieee_inexact': 0, '.amdhsa_exception_int_div_zero': 0, + '.amdhsa_user_sgpr_dispatch_ptr': 0, '.amdhsa_user_sgpr_queue_ptr': 0, '.amdhsa_user_sgpr_kernarg_segment_ptr': 1, + '.amdhsa_user_sgpr_dispatch_id': 0, '.amdhsa_user_sgpr_private_segment_size': 0, '.amdhsa_wavefront_size32': 1, '.amdhsa_uses_dynamic_stack': 0} + code_start = f""".end_amdhsa_kernel + .text + .global {function_name} + .type {function_name},@function + .p2align 8 + {function_name}: + """ + ret = ".amdgpu_metadata\n" + metadata + ".end_amdgpu_metadata" + boilerplate_start + "\n" + '\n'.join("%s %d" % x for x in kernel_desc.items()) \ + + "\n" + code_start + code + f"\n.size {function_name}, .-{function_name}" + return AMDProgram(cast(AMDDevice, Device["AMD"]), function_name, assemble(ret)) + +def get_output(s:str, n_threads:int=1): + assert n_threads <= 32 + code = "\n".join(["s_load_b64 s[0:1], s[0:1], null", "v_lshlrev_b32_e32 v0, 2, v0", s, + "s_waitcnt 0", + "global_store_b32 v0, v1, s[0:1]", + "s_nop 0", "s_sendmsg sendmsg(MSG_DEALLOC_VGPRS)", "s_endpgm"]) + test = Tensor.zeros((n_threads,), dtype=dtypes.uint32).contiguous().realize().lazydata.buffer + prg = get_prg(code, 32, 32) + prg(test._buf, global_size=(1, 1, 1), local_size=(n_threads, 1, 1), wait=True) + return test.numpy() + +def f16_to_bits(x:float) -> int: return struct.unpack(' float: return struct.unpack(' int: return struct.unpack('0 is +bitfield/mask for SEs to enable instruction tracing on. Masking shader engines will give smaller file sizes at a cost of less hits and kernels that +don't have any wavefront on first simd of shdaer engine with instruction tracing enabled will not have instruction timings. +The default is 2 (second shader engine only), only one for file size reasons, second instead of first because dispatch starts from it so there is +greater chance that kernels with small global size will have instruction tracing data. + +Note that instruction tracing might not be available for kernels with small global dims, this is not a bug, but it can be improved with various hacks +to the point where it can reliably trace a kernel consisting of a single wavefront (am only, not quite reliable under amdgpu due to waves sometimes +being dispatched starting from different simds). More info in comments in ops_amd.py + +## Converting pickled profile with SQTT data into RGP file + +```bash +extra/sqtt/rgptool.py create "/tmp/profile.pkl.$USER" -o /tmp/gpu0.rgp +``` + +Then load gpu0.rgp into Radeon GPU Profiler. It works just fine both in wine (macos, native version available for linux) and via ssh X forwarding + +If multiplle gpus are used you can select which one to export with `-d` like this: + +```bash +extra/sqtt/rgptool.py create "/tmp/profile.pkl.$USER" -d 'AMD:5' -o /tmp/gpu5.rgp +``` diff --git a/tinygrad_repo/extra/sqtt/rgptool.py b/tinygrad_repo/extra/sqtt/rgptool.py new file mode 100755 index 0000000000..a0d499e62e --- /dev/null +++ b/tinygrad_repo/extra/sqtt/rgptool.py @@ -0,0 +1,330 @@ +#!/usr/bin/env python3 +from __future__ import annotations +import argparse, ctypes, struct, hashlib, pickle, code, typing, functools +import tinygrad.runtime.autogen.sqtt as sqtt +from tinygrad.device import ProfileEvent, ProfileDeviceEvent, ProfileProgramEvent +from tinygrad.runtime.ops_amd import ProfileSQTTEvent +from tinygrad.helpers import round_up, flatten, all_same +from dataclasses import dataclass + +CHUNK_CLASSES = { + sqtt.SQTT_FILE_CHUNK_TYPE_ASIC_INFO: sqtt.struct_sqtt_file_chunk_asic_info, + sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DESC: sqtt.struct_sqtt_file_chunk_sqtt_desc, + sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DATA: sqtt.struct_sqtt_file_chunk_sqtt_data, + sqtt.SQTT_FILE_CHUNK_TYPE_API_INFO: sqtt.struct_sqtt_file_chunk_api_info, + sqtt.SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS: sqtt.struct_sqtt_file_chunk_queue_event_timings, + sqtt.SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION: sqtt.struct_sqtt_file_chunk_clock_calibration, + sqtt.SQTT_FILE_CHUNK_TYPE_CPU_INFO: sqtt.struct_sqtt_file_chunk_cpu_info, + sqtt.SQTT_FILE_CHUNK_TYPE_SPM_DB: sqtt.struct_sqtt_file_chunk_spm_db, + sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE: sqtt.struct_sqtt_file_chunk_code_object_database, + sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS: sqtt.struct_sqtt_file_chunk_code_object_loader_events, + sqtt.SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION: sqtt.struct_sqtt_file_chunk_pso_correlation, +} + +def pretty(val, pad=0) -> str: + if isinstance(val, (ctypes.Structure, ctypes.Union)): + nl = '\n' # old python versions don't support \ in f-strings + return f"{val.__class__.__name__}({nl}{' '*(pad+2)}{(f', {nl}'+' '*(pad+2)).join([f'{field[0]}={pretty(getattr(val, field[0]), pad=pad+2)}' for field in val._fields_])}{nl}{' '*pad})" + if isinstance(val, ctypes.Array): + return f"[{', '.join(map(pretty, val))}]" + if isinstance(val, int) and val >= 1024: return hex(val) + return repr(val) + +@dataclass(frozen=True) +class RGPChunk: + header: sqtt.Structure + data: list[typing.Any]|list[tuple[typing.Any, bytes]]|bytes|None = None + def print(self): + print(pretty(self.header)) + # if isinstance(self.data, bytes): print(repr(self.data)) + if isinstance(self.data, list): + for dchunk in self.data: + if isinstance(dchunk, tuple): + print(pretty(dchunk[0])) + # print(repr(dchunk[1])) + else: + print(pretty(dchunk)) + # TODO: `def fixup` and true immutability + def to_bytes(self, offset:int) -> bytes: + cid = self.header.header.chunk_id.type + match cid: + case _ if cid in {sqtt.SQTT_FILE_CHUNK_TYPE_ASIC_INFO, sqtt.SQTT_FILE_CHUNK_TYPE_CPU_INFO, sqtt.SQTT_FILE_CHUNK_TYPE_API_INFO, sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DESC}: + self.header.header.size_in_bytes = ctypes.sizeof(self.header) + return bytes(self.header) + case sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DATA: + assert isinstance(self.data, bytes) + self.header.header.size_in_bytes = ctypes.sizeof(self.header) + len(self.data) + self.header.offset = offset+ctypes.sizeof(self.header) + self.header.size = len(self.data) + return bytes(self.header) + self.data + case sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE: + assert isinstance(self.data, list) + data_codb = typing.cast(list[tuple[sqtt.struct_sqtt_code_object_database_record, bytes]], self.data) + ret = bytearray() + sz = ctypes.sizeof(self.header)+sum([ctypes.sizeof(record_hdr)+round_up(len(record_blob), 4) for record_hdr,record_blob in data_codb]) + self.header.header.size_in_bytes = sz + self.header.offset = offset + self.header.record_count = len(data_codb) + self.header.size = sz + ret += self.header + for record_hdr,record_blob in data_codb: + record_hdr.size = round_up(len(record_blob), 4) + ret += record_hdr + ret += record_blob.ljust(4, b'\x00') + return ret + case sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS: + assert isinstance(self.data, list) + data_lev = typing.cast(list[tuple[sqtt.struct_sqtt_code_object_loader_events_record]], self.data) + self.header.header.size_in_bytes = ctypes.sizeof(self.header)+ctypes.sizeof(sqtt.struct_sqtt_code_object_loader_events_record)*len(data_lev) + self.header.offset = offset + self.header.record_size = ctypes.sizeof(sqtt.struct_sqtt_code_object_loader_events_record) + self.header.record_count = len(data_lev) + return bytes(self.header) + b''.join(map(bytes, data_lev)) + case sqtt.SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION: + assert isinstance(self.data, list) + data_pso = typing.cast(list[tuple[sqtt.struct_sqtt_pso_correlation_record]], self.data) + self.header.header.size_in_bytes = ctypes.sizeof(self.header)+ctypes.sizeof(sqtt.struct_sqtt_pso_correlation_record)*len(data_pso) + self.header.offset = offset + self.header.record_size = ctypes.sizeof(sqtt.struct_sqtt_pso_correlation_record) + self.header.record_count = len(data_pso) + return bytes(self.header) + b''.join(map(bytes, data_pso)) + case _: raise NotImplementedError(pretty(self.header)) + +@dataclass(frozen=True) +class RGP: + header: sqtt.struct_sqtt_file_header + chunks: list[RGPChunk] + @staticmethod + def from_bytes(blob: bytes) -> RGP: + file_header = sqtt.struct_sqtt_file_header.from_buffer_copy(blob) + assert file_header.magic_number == sqtt.SQTT_FILE_MAGIC_NUMBER and file_header.version_major == sqtt.SQTT_FILE_VERSION_MAJOR + i = file_header.chunk_offset + chunks = [] + while i < len(blob): + assert i%4==0, hex(i) + hdr = sqtt.struct_sqtt_file_chunk_header.from_buffer_copy(blob, i) + cid = hdr.chunk_id.type + header: ctypes.Structure + match cid: + case _ if cid in {sqtt.SQTT_FILE_CHUNK_TYPE_RESERVED, sqtt.SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS, sqtt.SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION, sqtt.SQTT_FILE_CHUNK_TYPE_SPM_DB}: + chunk = None + case sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE: + header = sqtt.struct_sqtt_file_chunk_code_object_database.from_buffer_copy(blob, i) + j = header.offset + ctypes.sizeof(header) + data: list = [] + while j < header.offset + header.size: + rec_hdr: ctypes.Structure = sqtt.struct_sqtt_code_object_database_record.from_buffer_copy(blob, j) + data.append((rec_hdr, elf:=blob[j+ctypes.sizeof(rec_hdr):j+ctypes.sizeof(rec_hdr)+rec_hdr.size])) + assert elf[:4] == b'\x7fELF', repr(elf[:16]) + j += ctypes.sizeof(rec_hdr)+rec_hdr.size + assert len(data) == header.record_count + chunk = RGPChunk(header, data) + case sqtt.SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS: + header = sqtt.struct_sqtt_file_chunk_code_object_loader_events.from_buffer_copy(blob, i) + data = [sqtt.struct_sqtt_code_object_loader_events_record.from_buffer_copy(blob, header.offset+ctypes.sizeof(header)+j*header.record_size) + for j in range(header.record_count)] + chunk = RGPChunk(header, data) + case sqtt.SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION: + header = sqtt.struct_sqtt_file_chunk_pso_correlation.from_buffer_copy(blob, i) + data = [sqtt.struct_sqtt_pso_correlation_record.from_buffer_copy(blob, header.offset+ctypes.sizeof(header)+j*header.record_size) + for j in range(header.record_count)] + chunk = RGPChunk(header, data) + case sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DATA: + header = sqtt.struct_sqtt_file_chunk_sqtt_data.from_buffer_copy(blob, i) + chunk = RGPChunk(header, blob[header.offset:header.offset+header.size]) + case _ if cid in {sqtt.SQTT_FILE_CHUNK_TYPE_ASIC_INFO, sqtt.SQTT_FILE_CHUNK_TYPE_CPU_INFO, sqtt.SQTT_FILE_CHUNK_TYPE_API_INFO, + sqtt.SQTT_FILE_CHUNK_TYPE_SQTT_DESC}: + chunk = RGPChunk(CHUNK_CLASSES[cid].from_buffer_copy(blob, i)) + case _: + chunk = None + print(f"unknown chunk id {cid}") + if chunk is not None: chunks.append(chunk) + i += hdr.size_in_bytes + assert i == len(blob), f'{i} != {len(blob)}' + return RGP(file_header, chunks) + @staticmethod + def from_profile(profile_pickled, device:str|None=None): + profile: list[ProfileEvent] = pickle.loads(profile_pickled) + device_events = {x.device:x for x in profile if isinstance(x, ProfileDeviceEvent) and x.device.startswith('AMD')} + if device is None: + if len(device_events) == 0: raise RuntimeError('No supported devices found in profile') + if len(device_events) > 1: raise RuntimeError(f"More than one supported device found, select which one to export: {', '.join(device_events.keys())}") + _, device_event = device_events.popitem() + else: + if device not in device_events: raise RuntimeError(f"Device {device} not found in profile, devices in profile: {', '.join(device_events.keys())} ") + device_event = device_events[device] + sqtt_events = [x for x in profile if isinstance(x, ProfileSQTTEvent) and x.device == device_event.device] + if len(sqtt_events) == 0: raise RuntimeError(f"Device {device_event.device} doesn't contain SQTT data") + sqtt_itrace_enabled = any([event.itrace for event in sqtt_events]) + sqtt_itrace_masked = not all_same([event.itrace for event in sqtt_events]) + sqtt_itrace_se_mask = functools.reduce(lambda a,b: a|b, [int(event.itrace) << event.se for event in sqtt_events], 0) if sqtt_itrace_masked else 0 + load_events = [x for x in profile if isinstance(x, ProfileProgramEvent) and x.device == device_event.device] + loads = [(event.base, struct.unpack(' bytes: + ret = bytearray() + ret += self.header + for chunk in self.chunks: + ret += chunk.to_bytes(len(ret)) + return bytes(ret) + def print(self): + print(pretty(self.header)) + for chunk in self.chunks: chunk.print() + +if __name__ == '__main__': + parser = argparse.ArgumentParser(prog='rgptool', description='A tool to create (from pickled tinygrad profile), inspect and modify Radeon GPU Profiler files') + parser.add_argument('command') + parser.add_argument('input') + parser.add_argument('-d', '--device') + parser.add_argument('-o', '--output') + args = parser.parse_args() + + with open(args.input, 'rb') as fd: input_bytes = fd.read() + + match args.command: + case 'print': + rgp = RGP.from_bytes(input_bytes) + rgp.print() + case 'create': + rgp = RGP.from_profile(input_bytes, device=args.device) + # rgp.to_bytes() # fixup + # rgp.print() + case 'repl': + rgp = RGP.from_bytes(input_bytes) + code.interact(local=locals()) + case _: raise RuntimeError(args.command) + + if args.output is not None: + with open(args.output, 'wb+') as fd: fd.write(rgp.to_bytes()) diff --git a/tinygrad_repo/extra/sqtt/sqtt.h b/tinygrad_repo/extra/sqtt/sqtt.h new file mode 100644 index 0000000000..775655840c --- /dev/null +++ b/tinygrad_repo/extra/sqtt/sqtt.h @@ -0,0 +1,840 @@ +#include + +// Original definition in pal is in c++ and clang2py can't autogen it correctly +// Most of this is copy pasted from mesa/src/amd/common/ac_rgp.{h, c} + +/* + * Copyright 2020 Advanced Micro Devices, Inc. + * Copyright 2020 Valve Corporation + * + * SPDX-License-Identifier: MIT + */ + +#define SQTT_FILE_MAGIC_NUMBER 0x50303042 +#define SQTT_FILE_VERSION_MAJOR 1 +#define SQTT_FILE_VERSION_MINOR 5 + +#define SQTT_GPU_NAME_MAX_SIZE 256 +#define SQTT_MAX_NUM_SE 32 +#define SQTT_SA_PER_SE 2 +#define SQTT_ACTIVE_PIXEL_PACKER_MASK_DWORDS 4 + +struct sqtt_data_info { + uint32_t cur_offset; + uint32_t trace_status; + union { + uint32_t gfx9_write_counter; + uint32_t gfx10_dropped_cntr; + }; +}; + +struct sqtt_data_se { + struct sqtt_data_info info; + void *data_ptr; + uint32_t shader_engine; + uint32_t compute_unit; +}; + + +enum sqtt_version +{ + SQTT_VERSION_NONE = 0x0, + SQTT_VERSION_2_2 = 0x5, /* GFX8 */ + SQTT_VERSION_2_3 = 0x6, /* GFX9 */ + SQTT_VERSION_2_4 = 0x7, /* GFX10+ */ + SQTT_VERSION_3_2 = 0xb, /* GFX11+ */ +}; + +enum sqtt_file_chunk_type +{ + SQTT_FILE_CHUNK_TYPE_ASIC_INFO, + SQTT_FILE_CHUNK_TYPE_SQTT_DESC, + SQTT_FILE_CHUNK_TYPE_SQTT_DATA, + SQTT_FILE_CHUNK_TYPE_API_INFO, + SQTT_FILE_CHUNK_TYPE_RESERVED, + SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS, + SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION, + SQTT_FILE_CHUNK_TYPE_CPU_INFO, + SQTT_FILE_CHUNK_TYPE_SPM_DB, + SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE, + SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS, + SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION, + SQTT_FILE_CHUNK_TYPE_INSTRUMENTATION_TABLE, + SQTT_FILE_CHUNK_TYPE_COUNT +}; + + +struct sqtt_file_chunk_id { + int32_t type : 8; + int32_t index : 8; + int32_t reserved : 16; +}; + +struct sqtt_file_chunk_header { + struct sqtt_file_chunk_id chunk_id; + uint16_t minor_version; + uint16_t major_version; + int32_t size_in_bytes; + int32_t padding; +}; + +struct sqtt_file_header_flags { + union { + struct { + uint32_t is_semaphore_queue_timing_etw : 1; + uint32_t no_queue_semaphore_timestamps : 1; + uint32_t reserved : 30; + }; + + uint32_t value; + }; +}; + +struct sqtt_file_header { + uint32_t magic_number; + uint32_t version_major; + uint32_t version_minor; + struct sqtt_file_header_flags flags; + int32_t chunk_offset; + int32_t second; + int32_t minute; + int32_t hour; + int32_t day_in_month; + int32_t month; + int32_t year; + int32_t day_in_week; + int32_t day_in_year; + int32_t is_daylight_savings; +}; + +struct sqtt_file_chunk_cpu_info { + struct sqtt_file_chunk_header header; + uint32_t vendor_id[4]; + uint32_t processor_brand[12]; + uint32_t reserved[2]; + uint64_t cpu_timestamp_freq; + uint32_t clock_speed; + uint32_t num_logical_cores; + uint32_t num_physical_cores; + uint32_t system_ram_size; +}; + +enum sqtt_file_chunk_asic_info_flags +{ + SQTT_FILE_CHUNK_ASIC_INFO_FLAG_SC_PACKER_NUMBERING = (1 << 0), + SQTT_FILE_CHUNK_ASIC_INFO_FLAG_PS1_EVENT_TOKENS_ENABLED = (1 << 1) +}; + +enum sqtt_gpu_type +{ + SQTT_GPU_TYPE_UNKNOWN = 0x0, + SQTT_GPU_TYPE_INTEGRATED = 0x1, + SQTT_GPU_TYPE_DISCRETE = 0x2, + SQTT_GPU_TYPE_VIRTUAL = 0x3 +}; + +enum sqtt_gfxip_level +{ + SQTT_GFXIP_LEVEL_NONE = 0x0, + SQTT_GFXIP_LEVEL_GFXIP_6 = 0x1, + SQTT_GFXIP_LEVEL_GFXIP_7 = 0x2, + SQTT_GFXIP_LEVEL_GFXIP_8 = 0x3, + SQTT_GFXIP_LEVEL_GFXIP_8_1 = 0x4, + SQTT_GFXIP_LEVEL_GFXIP_9 = 0x5, + SQTT_GFXIP_LEVEL_GFXIP_10_1 = 0x7, + SQTT_GFXIP_LEVEL_GFXIP_10_3 = 0x9, + SQTT_GFXIP_LEVEL_GFXIP_11_0 = 0xc, +}; + +enum sqtt_memory_type +{ + SQTT_MEMORY_TYPE_UNKNOWN = 0x0, + SQTT_MEMORY_TYPE_DDR = 0x1, + SQTT_MEMORY_TYPE_DDR2 = 0x2, + SQTT_MEMORY_TYPE_DDR3 = 0x3, + SQTT_MEMORY_TYPE_DDR4 = 0x4, + SQTT_MEMORY_TYPE_DDR5 = 0x5, + SQTT_MEMORY_TYPE_GDDR3 = 0x10, + SQTT_MEMORY_TYPE_GDDR4 = 0x11, + SQTT_MEMORY_TYPE_GDDR5 = 0x12, + SQTT_MEMORY_TYPE_GDDR6 = 0x13, + SQTT_MEMORY_TYPE_HBM = 0x20, + SQTT_MEMORY_TYPE_HBM2 = 0x21, + SQTT_MEMORY_TYPE_HBM3 = 0x22, + SQTT_MEMORY_TYPE_LPDDR4 = 0x30, + SQTT_MEMORY_TYPE_LPDDR5 = 0x31, +}; + +struct sqtt_file_chunk_asic_info { + struct sqtt_file_chunk_header header; + uint64_t flags; + uint64_t trace_shader_core_clock; + uint64_t trace_memory_clock; + int32_t device_id; + int32_t device_revision_id; + int32_t vgprs_per_simd; + int32_t sgprs_per_simd; + int32_t shader_engines; + int32_t compute_unit_per_shader_engine; + int32_t simd_per_compute_unit; + int32_t wavefronts_per_simd; + int32_t minimum_vgpr_alloc; + int32_t vgpr_alloc_granularity; + int32_t minimum_sgpr_alloc; + int32_t sgpr_alloc_granularity; + int32_t hardware_contexts; + enum sqtt_gpu_type gpu_type; + enum sqtt_gfxip_level gfxip_level; + int32_t gpu_index; + int32_t gds_size; + int32_t gds_per_shader_engine; + int32_t ce_ram_size; + int32_t ce_ram_size_graphics; + int32_t ce_ram_size_compute; + int32_t max_number_of_dedicated_cus; + int64_t vram_size; + int32_t vram_bus_width; + int32_t l2_cache_size; + int32_t l1_cache_size; + int32_t lds_size; + char gpu_name[SQTT_GPU_NAME_MAX_SIZE]; + float alu_per_clock; + float texture_per_clock; + float prims_per_clock; + float pixels_per_clock; + uint64_t gpu_timestamp_frequency; + uint64_t max_shader_core_clock; + uint64_t max_memory_clock; + uint32_t memory_ops_per_clock; + enum sqtt_memory_type memory_chip_type; + uint32_t lds_granularity; + uint16_t cu_mask[SQTT_MAX_NUM_SE][SQTT_SA_PER_SE]; + char reserved1[128]; + uint32_t active_pixel_packer_mask[SQTT_ACTIVE_PIXEL_PACKER_MASK_DWORDS]; + char reserved2[16]; + uint32_t gl1_cache_size; + uint32_t instruction_cache_size; + uint32_t scalar_cache_size; + uint32_t mall_cache_size; + char padding[4]; +}; + +enum sqtt_api_type +{ + SQTT_API_TYPE_DIRECTX_12, + SQTT_API_TYPE_VULKAN, + SQTT_API_TYPE_GENERIC, + SQTT_API_TYPE_OPENCL +}; + +enum sqtt_instruction_trace_mode +{ + SQTT_INSTRUCTION_TRACE_DISABLED = 0x0, + SQTT_INSTRUCTION_TRACE_FULL_FRAME = 0x1, + SQTT_INSTRUCTION_TRACE_API_PSO = 0x2, +}; + +enum sqtt_profiling_mode +{ + SQTT_PROFILING_MODE_PRESENT = 0x0, + SQTT_PROFILING_MODE_USER_MARKERS = 0x1, + SQTT_PROFILING_MODE_INDEX = 0x2, + SQTT_PROFILING_MODE_TAG = 0x3, +}; + +union sqtt_profiling_mode_data { + struct { + char start[256]; + char end[256]; + } user_marker_profiling_data; + + struct { + uint32_t start; + uint32_t end; + } index_profiling_data; + + struct { + uint32_t begin_hi; + uint32_t begin_lo; + uint32_t end_hi; + uint32_t end_lo; + } tag_profiling_data; +}; + +union sqtt_instruction_trace_data { + struct { + uint64_t api_pso_filter; + } api_pso_data; + + struct { + uint32_t mask; + } shader_engine_filter; +}; + +struct sqtt_file_chunk_api_info { + struct sqtt_file_chunk_header header; + enum sqtt_api_type api_type; + uint16_t major_version; + uint16_t minor_version; + enum sqtt_profiling_mode profiling_mode; + uint32_t reserved; + union sqtt_profiling_mode_data profiling_mode_data; + enum sqtt_instruction_trace_mode instruction_trace_mode; + uint32_t reserved2; + union sqtt_instruction_trace_data instruction_trace_data; +}; + + +struct sqtt_code_object_database_record { + uint32_t size; +}; + +struct sqtt_file_chunk_code_object_database { + struct sqtt_file_chunk_header header; + uint32_t offset; + uint32_t flags; + uint32_t size; + uint32_t record_count; +}; + + +struct sqtt_code_object_loader_events_record { + uint32_t loader_event_type; + uint32_t reserved; + uint64_t base_address; + uint64_t code_object_hash[2]; + uint64_t time_stamp; +}; + +struct sqtt_file_chunk_code_object_loader_events { + struct sqtt_file_chunk_header header; + uint32_t offset; + uint32_t flags; + uint32_t record_size; + uint32_t record_count; +}; + +struct sqtt_pso_correlation_record { + uint64_t api_pso_hash; + uint64_t pipeline_hash[2]; + char api_level_obj_name[64]; +}; + +struct sqtt_file_chunk_pso_correlation { + struct sqtt_file_chunk_header header; + uint32_t offset; + uint32_t flags; + uint32_t record_size; + uint32_t record_count; +}; + +struct sqtt_file_chunk_sqtt_desc { + struct sqtt_file_chunk_header header; + int32_t shader_engine_index; + enum sqtt_version sqtt_version; + union { + struct { + int32_t instrumentation_version; + } v0; + struct { + int16_t instrumentation_spec_version; + int16_t instrumentation_api_version; + int32_t compute_unit_index; + } v1; + }; +}; + +struct sqtt_file_chunk_sqtt_data { + struct sqtt_file_chunk_header header; + int32_t offset; /* in bytes */ + int32_t size; /* in bytes */ +}; + +struct sqtt_file_chunk_queue_event_timings { + struct sqtt_file_chunk_header header; + uint32_t queue_info_table_record_count; + uint32_t queue_info_table_size; + uint32_t queue_event_table_record_count; + uint32_t queue_event_table_size; +}; + + +enum sqtt_queue_type { + SQTT_QUEUE_TYPE_UNKNOWN = 0x0, + SQTT_QUEUE_TYPE_UNIVERSAL = 0x1, + SQTT_QUEUE_TYPE_COMPUTE = 0x2, + SQTT_QUEUE_TYPE_DMA = 0x3, +}; + +enum sqtt_engine_type { + SQTT_ENGINE_TYPE_UNKNOWN = 0x0, + SQTT_ENGINE_TYPE_UNIVERSAL = 0x1, + SQTT_ENGINE_TYPE_COMPUTE = 0x2, + SQTT_ENGINE_TYPE_EXCLUSIVE_COMPUTE = 0x3, + SQTT_ENGINE_TYPE_DMA = 0x4, + SQTT_ENGINE_TYPE_HIGH_PRIORITY_UNIVERSAL = 0x7, + SQTT_ENGINE_TYPE_HIGH_PRIORITY_GRAPHICS = 0x8, +}; + +struct sqtt_queue_hardware_info { + union { + struct { + int32_t queue_type : 8; + int32_t engine_type : 8; + uint32_t reserved : 16; + }; + uint32_t value; + }; +}; + + +struct sqtt_queue_info_record { + uint64_t queue_id; + uint64_t queue_context; + struct sqtt_queue_hardware_info hardware_info; + uint32_t reserved; +}; + +enum sqtt_queue_event_type { + SQTT_QUEUE_TIMING_EVENT_CMDBUF_SUBMIT, + SQTT_QUEUE_TIMING_EVENT_SIGNAL_SEMAPHORE, + SQTT_QUEUE_TIMING_EVENT_WAIT_SEMAPHORE, + SQTT_QUEUE_TIMING_EVENT_PRESENT +}; + +struct sqtt_queue_event_record { + enum sqtt_queue_event_type event_type; + uint32_t sqtt_cb_id; + uint64_t frame_index; + uint32_t queue_info_index; + uint32_t submit_sub_index; + uint64_t api_id; + uint64_t cpu_timestamp; + uint64_t gpu_timestamps[2]; +}; + +struct sqtt_file_chunk_clock_calibration { + struct sqtt_file_chunk_header header; + uint64_t cpu_timestamp; + uint64_t gpu_timestamp; + uint64_t reserved; +}; + +enum elf_gfxip_level +{ + EF_AMDGPU_MACH_AMDGCN_GFX801 = 0x028, + EF_AMDGPU_MACH_AMDGCN_GFX900 = 0x02c, + EF_AMDGPU_MACH_AMDGCN_GFX1010 = 0x033, + EF_AMDGPU_MACH_AMDGCN_GFX1030 = 0x036, + EF_AMDGPU_MACH_AMDGCN_GFX1100 = 0x041, +}; + +struct sqtt_file_chunk_spm_db { + struct sqtt_file_chunk_header header; + uint32_t flags; + uint32_t preamble_size; + uint32_t num_timestamps; + uint32_t num_spm_counter_info; + uint32_t spm_counter_info_size; + uint32_t sample_interval; +}; + +/** + * Identifiers for RGP SQ thread-tracing markers (Table 1) + */ +enum rgp_sqtt_marker_identifier +{ + RGP_SQTT_MARKER_IDENTIFIER_EVENT = 0x0, + RGP_SQTT_MARKER_IDENTIFIER_CB_START = 0x1, + RGP_SQTT_MARKER_IDENTIFIER_CB_END = 0x2, + RGP_SQTT_MARKER_IDENTIFIER_BARRIER_START = 0x3, + RGP_SQTT_MARKER_IDENTIFIER_BARRIER_END = 0x4, + RGP_SQTT_MARKER_IDENTIFIER_USER_EVENT = 0x5, + RGP_SQTT_MARKER_IDENTIFIER_GENERAL_API = 0x6, + RGP_SQTT_MARKER_IDENTIFIER_SYNC = 0x7, + RGP_SQTT_MARKER_IDENTIFIER_PRESENT = 0x8, + RGP_SQTT_MARKER_IDENTIFIER_LAYOUT_TRANSITION = 0x9, + RGP_SQTT_MARKER_IDENTIFIER_RENDER_PASS = 0xA, + RGP_SQTT_MARKER_IDENTIFIER_RESERVED2 = 0xB, + RGP_SQTT_MARKER_IDENTIFIER_BIND_PIPELINE = 0xC, + RGP_SQTT_MARKER_IDENTIFIER_RESERVED4 = 0xD, + RGP_SQTT_MARKER_IDENTIFIER_RESERVED5 = 0xE, + RGP_SQTT_MARKER_IDENTIFIER_RESERVED6 = 0xF +}; + +/** + * Command buffer IDs used in RGP SQ thread-tracing markers (only 20 bits). + */ +union rgp_sqtt_marker_cb_id { + struct { + uint32_t per_frame : 1; /* Must be 1, frame-based command buffer ID. */ + uint32_t frame_index : 7; + uint32_t cb_index : 12; /* Command buffer index within the frame. */ + uint32_t reserved : 12; + } per_frame_cb_id; + + struct { + uint32_t per_frame : 1; /* Must be 0, global command buffer ID. */ + uint32_t cb_index : 19; /* Global command buffer index. */ + uint32_t reserved : 12; + } global_cb_id; + + uint32_t all; +}; + +/** + * RGP SQ thread-tracing marker for the start of a command buffer. (Table 2) + */ +struct rgp_sqtt_marker_cb_start { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t cb_id : 20; + uint32_t queue : 5; + }; + uint32_t dword01; + }; + union { + uint32_t device_id_low; + uint32_t dword02; + }; + union { + uint32_t device_id_high; + uint32_t dword03; + }; + union { + uint32_t queue_flags; + uint32_t dword04; + }; +}; + +/** + * + * RGP SQ thread-tracing marker for the end of a command buffer. (Table 3) + */ +struct rgp_sqtt_marker_cb_end { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t cb_id : 20; + uint32_t reserved : 5; + }; + uint32_t dword01; + }; + union { + uint32_t device_id_low; + uint32_t dword02; + }; + union { + uint32_t device_id_high; + uint32_t dword03; + }; +}; + +/** + * API types used in RGP SQ thread-tracing markers for the "General API" + * packet. + */ +enum rgp_sqtt_marker_general_api_type +{ + ApiCmdBindPipeline = 0, + ApiCmdBindDescriptorSets = 1, + ApiCmdBindIndexBuffer = 2, + ApiCmdBindVertexBuffers = 3, + ApiCmdDraw = 4, + ApiCmdDrawIndexed = 5, + ApiCmdDrawIndirect = 6, + ApiCmdDrawIndexedIndirect = 7, + ApiCmdDrawIndirectCountAMD = 8, + ApiCmdDrawIndexedIndirectCountAMD = 9, + ApiCmdDispatch = 10, + ApiCmdDispatchIndirect = 11, + ApiCmdCopyBuffer = 12, + ApiCmdCopyImage = 13, + ApiCmdBlitImage = 14, + ApiCmdCopyBufferToImage = 15, + ApiCmdCopyImageToBuffer = 16, + ApiCmdUpdateBuffer = 17, + ApiCmdFillBuffer = 18, + ApiCmdClearColorImage = 19, + ApiCmdClearDepthStencilImage = 20, + ApiCmdClearAttachments = 21, + ApiCmdResolveImage = 22, + ApiCmdWaitEvents = 23, + ApiCmdPipelineBarrier = 24, + ApiCmdBeginQuery = 25, + ApiCmdEndQuery = 26, + ApiCmdResetQueryPool = 27, + ApiCmdWriteTimestamp = 28, + ApiCmdCopyQueryPoolResults = 29, + ApiCmdPushConstants = 30, + ApiCmdBeginRenderPass = 31, + ApiCmdNextSubpass = 32, + ApiCmdEndRenderPass = 33, + ApiCmdExecuteCommands = 34, + ApiCmdSetViewport = 35, + ApiCmdSetScissor = 36, + ApiCmdSetLineWidth = 37, + ApiCmdSetDepthBias = 38, + ApiCmdSetBlendConstants = 39, + ApiCmdSetDepthBounds = 40, + ApiCmdSetStencilCompareMask = 41, + ApiCmdSetStencilWriteMask = 42, + ApiCmdSetStencilReference = 43, + ApiCmdDrawIndirectCount = 44, + ApiCmdDrawIndexedIndirectCount = 45, + /* gap */ + ApiCmdDrawMeshTasksEXT = 47, + ApiCmdDrawMeshTasksIndirectCountEXT = 48, + ApiCmdDrawMeshTasksIndirectEXT = 49, + + ApiRayTracingSeparateCompiled = 0x800000, + ApiInvalid = 0xffffffff +}; + +/** + * RGP SQ thread-tracing marker for a "General API" instrumentation packet. + */ +struct rgp_sqtt_marker_general_api { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t api_type : 20; + uint32_t is_end : 1; + uint32_t reserved : 4; + }; + uint32_t dword01; + }; +}; + +/** + * API types used in RGP SQ thread-tracing markers (Table 16). + */ +enum rgp_sqtt_marker_event_type +{ + EventCmdDraw = 0, + EventCmdDrawIndexed = 1, + EventCmdDrawIndirect = 2, + EventCmdDrawIndexedIndirect = 3, + EventCmdDrawIndirectCountAMD = 4, + EventCmdDrawIndexedIndirectCountAMD = 5, + EventCmdDispatch = 6, + EventCmdDispatchIndirect = 7, + EventCmdCopyBuffer = 8, + EventCmdCopyImage = 9, + EventCmdBlitImage = 10, + EventCmdCopyBufferToImage = 11, + EventCmdCopyImageToBuffer = 12, + EventCmdUpdateBuffer = 13, + EventCmdFillBuffer = 14, + EventCmdClearColorImage = 15, + EventCmdClearDepthStencilImage = 16, + EventCmdClearAttachments = 17, + EventCmdResolveImage = 18, + EventCmdWaitEvents = 19, + EventCmdPipelineBarrier = 20, + EventCmdResetQueryPool = 21, + EventCmdCopyQueryPoolResults = 22, + EventRenderPassColorClear = 23, + EventRenderPassDepthStencilClear = 24, + EventRenderPassResolve = 25, + EventInternalUnknown = 26, + EventCmdDrawIndirectCount = 27, + EventCmdDrawIndexedIndirectCount = 28, + /* gap */ + EventCmdTraceRaysKHR = 30, + EventCmdTraceRaysIndirectKHR = 31, + EventCmdBuildAccelerationStructuresKHR = 32, + EventCmdBuildAccelerationStructuresIndirectKHR = 33, + EventCmdCopyAccelerationStructureKHR = 34, + EventCmdCopyAccelerationStructureToMemoryKHR = 35, + EventCmdCopyMemoryToAccelerationStructureKHR = 36, + /* gap */ + EventCmdDrawMeshTasksEXT = 41, + EventCmdDrawMeshTasksIndirectCountEXT = 42, + EventCmdDrawMeshTasksIndirectEXT = 43, + EventUnknown = 0x7fff, + EventInvalid = 0xffffffff +}; + +/** + * "Event (Per-draw/dispatch)" RGP SQ thread-tracing marker. (Table 4) + */ +struct rgp_sqtt_marker_event { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t api_type : 24; + uint32_t has_thread_dims : 1; + }; + uint32_t dword01; + }; + union { + struct { + uint32_t cb_id : 20; + uint32_t vertex_offset_reg_idx : 4; + uint32_t instance_offset_reg_idx : 4; + uint32_t draw_index_reg_idx : 4; + }; + uint32_t dword02; + }; + union { + uint32_t cmd_id; + uint32_t dword03; + }; +}; + +/** + * Per-dispatch specific marker where workgroup dims are included. + */ +struct rgp_sqtt_marker_event_with_dims { + struct rgp_sqtt_marker_event event; + uint32_t thread_x; + uint32_t thread_y; + uint32_t thread_z; +}; + +/** + * "Barrier Start" RGP SQTT instrumentation marker (Table 5) + */ +struct rgp_sqtt_marker_barrier_start { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t cb_id : 20; + uint32_t reserved : 5; + }; + uint32_t dword01; + }; + union { + struct { + uint32_t driver_reason : 31; + uint32_t internal : 1; + }; + uint32_t dword02; + }; +}; + +/** + * "Barrier End" RGP SQTT instrumentation marker (Table 6) + */ +struct rgp_sqtt_marker_barrier_end { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t cb_id : 20; + uint32_t wait_on_eop_ts : 1; + uint32_t vs_partial_flush : 1; + uint32_t ps_partial_flush : 1; + uint32_t cs_partial_flush : 1; + uint32_t pfp_sync_me : 1; + }; + uint32_t dword01; + }; + union { + struct { + uint32_t sync_cp_dma : 1; + uint32_t inval_tcp : 1; + uint32_t inval_sqI : 1; + uint32_t inval_sqK : 1; + uint32_t flush_tcc : 1; + uint32_t inval_tcc : 1; + uint32_t flush_cb : 1; + uint32_t inval_cb : 1; + uint32_t flush_db : 1; + uint32_t inval_db : 1; + uint32_t num_layout_transitions : 16; + uint32_t inval_gl1 : 1; + uint32_t wait_on_ts : 1; + uint32_t eop_ts_bottom_of_pipe : 1; + uint32_t eos_ts_ps_done : 1; + uint32_t eos_ts_cs_done : 1; + uint32_t reserved : 1; + }; + uint32_t dword02; + }; +}; + +/** + * "Layout Transition" RGP SQTT instrumentation marker (Table 7) + */ +struct rgp_sqtt_marker_layout_transition { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t depth_stencil_expand : 1; + uint32_t htile_hiz_range_expand : 1; + uint32_t depth_stencil_resummarize : 1; + uint32_t dcc_decompress : 1; + uint32_t fmask_decompress : 1; + uint32_t fast_clear_eliminate : 1; + uint32_t fmask_color_expand : 1; + uint32_t init_mask_ram : 1; + uint32_t reserved1 : 17; + }; + uint32_t dword01; + }; + union { + struct { + uint32_t reserved2 : 32; + }; + uint32_t dword02; + }; +}; + +/** + * "User Event" RGP SQTT instrumentation marker (Table 8) + */ +struct rgp_sqtt_marker_user_event { + union { + struct { + uint32_t identifier : 4; + uint32_t reserved0 : 8; + uint32_t data_type : 8; + uint32_t reserved1 : 12; + }; + uint32_t dword01; + }; +}; +struct rgp_sqtt_marker_user_event_with_length { + struct rgp_sqtt_marker_user_event user_event; + uint32_t length; +}; + +enum rgp_sqtt_marker_user_event_type +{ + UserEventTrigger = 0, + UserEventPop, + UserEventPush, + UserEventObjectName, +}; + +/** + * "Pipeline bind" RGP SQTT instrumentation marker (Table 12) + */ +struct rgp_sqtt_marker_pipeline_bind { + union { + struct { + uint32_t identifier : 4; + uint32_t ext_dwords : 3; + uint32_t bind_point : 1; + uint32_t cb_id : 20; + uint32_t reserved : 4; + }; + uint32_t dword01; + }; + union { + uint32_t api_pso_hash[2]; + struct { + uint32_t dword02; + uint32_t dword03; + }; + }; +}; diff --git a/tinygrad_repo/extra/to_movement_ops.py b/tinygrad_repo/extra/to_movement_ops.py index 2528a2ca8f..81afd306d8 100644 --- a/tinygrad_repo/extra/to_movement_ops.py +++ b/tinygrad_repo/extra/to_movement_ops.py @@ -4,17 +4,18 @@ from collections import defaultdict from typing import List, Tuple, DefaultDict from extra.optimization.helpers import load_worlds, ast_str_to_ast from tinygrad.helpers import prod, tqdm -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.ops import sym_infer, Node +from tinygrad.uop.ops import sym_infer +from tinygrad.tensor import Tensor class MovementOps(Enum): RESHAPE = auto(); PERMUTE = auto(); EXPAND = auto(); PAD = auto(); SHRINK = auto(); STRIDE = auto(); AS_STRIDED = auto() # noqa: E702 -def apply_mop(st: ShapeTracker, mop_arg: Tuple[MovementOps, Tuple]) -> ShapeTracker: +def apply_mop(st: Tensor|ShapeTracker, mop_arg: Tuple[MovementOps, Tuple]) -> ShapeTracker: mop, arg = mop_arg if mop == MovementOps.RESHAPE: # shapetracker doesn't allow flattening with -1 but required for MovementOps.RESHAPE - if arg == (-1,): return st.reshape((prod(st.views[-1].shape),)) + if arg == (-1,): return st.reshape((prod(st.shape),)) return st.reshape(arg) if mop == MovementOps.PERMUTE: return st.permute(arg) if mop == MovementOps.EXPAND: @@ -22,7 +23,9 @@ def apply_mop(st: ShapeTracker, mop_arg: Tuple[MovementOps, Tuple]) -> ShapeTrac return st.expand(arg) if mop == MovementOps.PAD: return st.pad(arg) if mop == MovementOps.SHRINK: return st.shrink(arg) - if mop == MovementOps.STRIDE: return st.stride(arg) + if mop == MovementOps.STRIDE: + assert all(x in [-1, 1] for x in arg) + return st.flip(tuple(i for i,x in enumerate(arg) if x == -1)) raise ValueError("invalid mop") def make_scratch_st(st: ShapeTracker) -> ShapeTracker: @@ -36,7 +39,7 @@ def to_movement_ops(st: ShapeTracker) -> List[Tuple[MovementOps, Tuple]]: offset = v.offset + sum(st*(s-1) for s,st in zip(real_shape, v.strides) if st<0) real_offset = offset + (sum(x*st for (x,_),st in zip(v.mask, v.strides)) if v.mask else 0) real_real_shape = [s for s,st in zip(real_shape, v.strides) if st] - strides: List[Node|int] = [abs(st) if isinstance(st,int) else st for st in v.strides if st] + strides: List[int] = [abs(st) if isinstance(st,int) else st for st in v.strides if st] buffer_size = sum((s-1)*st for s,st in zip(real_real_shape,strides)) + 1 if i: buffer_size = prod(st.views[i-1].shape) - real_offset def sort_by_strides(shape, strides): return sorted(zip(shape, strides), key=lambda k: (k[1],-k[0]), reverse=True), sorted(range(len(strides)), key=lambda k: (strides[k],-real_real_shape[k]), reverse=True) @@ -80,9 +83,12 @@ def to_movement_ops(st: ShapeTracker) -> List[Tuple[MovementOps, Tuple]]: if scratch_st in seen: ret = seen[scratch_st][:] else: - ret.append(mop_arg) + if len(ret) and ret[-1][0] == MovementOps.RESHAPE and mop_arg[0] == MovementOps.RESHAPE: + ret[-1] = mop_arg + else: + if mop_arg == (MovementOps.RESHAPE, -1): mop_arg = (MovementOps.RESHAPE, (prod(st.shape),)) + ret.append(mop_arg) seen[scratch_st] = ret[:] - return ret def get_real_view(shape, strides, offset, mask): diff --git a/tinygrad_repo/extra/torch_backend/.gitignore b/tinygrad_repo/extra/torch_backend/.gitignore new file mode 100644 index 0000000000..1269488f7f --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/.gitignore @@ -0,0 +1 @@ +data diff --git a/tinygrad_repo/extra/torch_backend/backend.py b/tinygrad_repo/extra/torch_backend/backend.py new file mode 100644 index 0000000000..4a14a22ab7 --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/backend.py @@ -0,0 +1,635 @@ +# ruff: noqa: E501, A001, A002, A006 +# A001 Variable `input` is shadowing a Python builtin +# A002 Function argument `input` is shadowing a Python builtin +# A006 Lambda argument `input` is shadowing a Python builtin +from tinygrad import Tensor, dtypes, Device +from tinygrad.uop.ops import Ops +from tinygrad.helpers import getenv, prod +import torch.lib +TORCH_DEBUG = getenv("TORCH_DEBUG") +import torch, pathlib, math, operator, functools, inspect +torch.autograd.grad_mode.set_multithreading_enabled(False) +from tinygrad.dtype import _from_torch_dtype, _to_torch_dtype + +# https://pytorch.org/docs/stable/torch.compiler_ir.html + +def _from_torch_device(device: torch.device): return f"{Device.DEFAULT}:{device.index or 0}" +def _to_torch_device(device: str): return torch.device("tiny", int(device.partition(":")[2] or 0)) + +import torch.utils.cpp_extension +mod = torch.utils.cpp_extension.load(name="custom_device_extension", sources=[str(pathlib.Path(__file__).parent / "wrapped_tensor.cpp")]) +def wrap(x:Tensor) -> torch.Tensor: return mod.wrap(x, _to_torch_dtype(x.dtype), _to_torch_device(x.device).index) +def unwrap(x:torch.Tensor) -> Tensor: + assert isinstance(x, torch.Tensor), f"x isn't {type(x)}" + return mod.unwrap(x) +class TinyBackend: + def is_initialized(self): return True + def is_available(self): return True + def current_device(self): return 0 + def _is_in_bad_fork(self): return False + def manual_seed_all(self, seed: int): Tensor.manual_seed(seed) + def device_count(self): return getenv("GPUS", 1) # TODO: device count in tiny? +torch.utils.rename_privateuse1_backend("tiny") +torch._register_device_module("tiny", TinyBackend()) +torch.utils.generate_methods_for_privateuse1_backend() +aten = torch.ops.aten + +# track view relationships for in place operations +def is_view(tensor: Tensor): return hasattr(tensor, "_view_base") +def canonical_base(view: Tensor): return getattr(view, "_view_base", view) +def derived_views(base: Tensor): return [t for tref in getattr(base, "_views", set()) if (t:=tref()) is not None] +def wrap_view_op(fn): + def _wrap(*args,**kwargs): + args = [unwrap(x) if isinstance(x, torch.Tensor) else x for x in args] + kwargs = {k:unwrap(v) if isinstance(v, torch.Tensor) else v for k,v in kwargs.items()} + ret = fn(*args,**kwargs) + ret._view_base = base = canonical_base(args[0]) + if not hasattr(base, "_views"): base._views = set() + base._views.add(weakref.ref(ret)) + return wrap(ret) + return _wrap + +view_ops = { + "aten.view": Tensor.reshape, + "aten._unsafe_view": Tensor.reshape, # when are views unsafe, and do we care? + "aten.view.dtype": lambda self,dtype: self.bitcast(_from_torch_dtype(dtype)), + "aten.expand": Tensor.expand, + "aten.t": Tensor.transpose, + "aten.transpose.int": Tensor.transpose, + "aten.squeeze.dim": Tensor.squeeze, + "aten.unsqueeze": Tensor.unsqueeze, + "aten.detach": Tensor.detach, +} + +for k,v in view_ops.items(): torch.library.impl(k.replace("aten.", "aten::"), "privateuseone")(wrap_view_op(v)) + +# in place operations with views +def realize_with_views(self: Tensor, views: Tensor): + if not self.lazydata.st.contiguous: self.replace(self.contiguous()) + self.replace(self.clone().realize()) + for v in views: + if v.lazydata.base.op is Ops.BUFFER_VIEW: continue # skip subbuffer, we just use the real buffer view + ret = self + st = ShapeTracker(self.lazydata.st.views + v.lazydata.st.views) # TODO: is this right? + for mo in cached_to_movement_ops(self.shape, st): ret = apply_mop(ret, mo) + v.replace(ret) +def maybe_realize_storage(self: Tensor) -> bool: + if realize:=is_view(self): realize_with_views((base:=canonical_base(self)), derived_views(base)) + return realize +def inplace_fn(outvars: str|list[str]): + if type(outvars) is str: outvars = [outvars] + def decorator(fn): + sig = inspect.signature(fn) + def wrapper(*args, **kwargs): + bound = sig.bind(*args, **kwargs) + outs = [kwargs.get(v, bound.arguments.get(v)) for v in outvars] + outs = [unwrap(o) if isinstance(o, torch.Tensor) else o for o in outs] + realize = any(maybe_realize_storage(o) for o in outs) + ret = fn(*args, **kwargs) + if realize: Tensor.realize(*(o for o in outs)) + return ret + return wrapper + return decorator + +# *** bad functions on CPU *** + +@torch.library.impl("aten::_index_put_impl_", "privateuseone") +@inplace_fn("self") +def _index_put_impl_(self, indices, values, accumulate=False, unsafe=False): + # TODO: move to tinygrad + ret = aten._index_put_impl_(self.cpu(), [x.cpu() if isinstance(x, torch.Tensor) else None for x in indices], values.cpu(), accumulate, unsafe).to(self.device) + return wrap(unwrap(self).assign(unwrap(ret))) + +@torch.library.impl("aten::index_put", "privateuseone") +def index_put(self, indices, values, accumulate=False): + return aten.index_put(self.cpu(), [z.cpu() if isinstance(z, torch.Tensor) else None for z in indices], values.cpu(), accumulate).tiny() + +@torch.library.impl("aten::isin.Tensor_Tensor_out", "privateuseone") +def isin_tensor_tensor_out(x, y, *, assume_unique=False, invert=False, out=None): return out.copy_(aten.isin(x.cpu(), y.cpu(), assume_unique=assume_unique, invert=invert).tiny()) + +@torch.library.impl("aten::randperm.generator_out", "privateuseone") +def randperm_generator(n, generator=None, out=None): + return out.copy_(wrap(Tensor.randperm(n, generator=generator, device=unwrap(out).device))) + +@torch.library.impl("aten::cummax", "privateuseone") +def cummax(self, dim): + # TODO: support cummax with indices to match torch + cummax, indices = aten.cummax(self.cpu(), dim) + return (cummax.tiny(), indices.tiny()) + +@torch.library.impl("aten::nonzero", "privateuseone") +# TODO: move to tinygrad +def nonzero(self): return aten.nonzero(self.cpu()).tiny() + +def upsample_backward(grad_out, output_size, input_size, *args, f=None): return f(grad_out.cpu(), output_size, input_size, *args).tiny() + +for i in [ + "upsample_linear1d_backward", "upsample_nearest1d_backward", "_upsample_nearest_exact1d_backward", + "upsample_nearest2d_backward", "_upsample_nearest_exact2d_backward", + "upsample_nearest3d_backward", "_upsample_nearest_exact3d_backward", + "upsample_trilinear3d_backward", "upsample_bilinear2d_backward" +]: + torch.library.impl(f"aten::{i}", "privateuseone")(functools.partial(upsample_backward, f=getattr(aten, i))) + +# *** end bad functions on CPU *** + +@torch.library.impl("aten::index.Tensor", "privateuseone") +def index_tensor(x, y): + return wrap(unwrap(x)[[unwrap(_y.to(x.device)) if _y is not None else slice(None) for _y in y]]) + +@torch.library.impl("aten::zero_", "privateuseone") +@inplace_fn("x") +def zero_(x): + if TORCH_DEBUG: print(f"zero_ {x.shape}") + tt = unwrap(x) + # NOTE: unconditional contiguous covers if x is contiguous (match it) or if x is view (realize for inplace) + # TODO: consolidate + tt.assign(tt.zeros_like().contiguous()) + +@torch.library.impl("aten::fill_.Scalar", "privateuseone") +@inplace_fn("x") +def fill_scalar(x, y): + if TORCH_DEBUG: print(f"fill_.Scalar {x.shape} {y}") + tt = unwrap(x) + tt.assign(tt.full_like(y).contiguous()) + +@torch.library.impl("aten::_local_scalar_dense", "privateuseone") +def _local_scalar_dense(tensor): return unwrap(tensor).item() + +@functools.cache +def cached_to_movement_ops(shape, st) -> list: + mops = to_movement_ops(st) + if mops[0] == (MovementOps.RESHAPE, shape): mops = mops[1:] + return mops + +from tinygrad.shape.shapetracker import ShapeTracker, View +from extra.to_movement_ops import to_movement_ops, apply_mop, MovementOps +@torch.library.impl("aten::as_strided", "privateuseone") +def as_strided(tensor:torch.Tensor, size, stride, storage_offset=None): + storage_offset = storage_offset or tensor.storage_offset() + @wrap_view_op + def _as_strided(tensor:Tensor, size, stride, storage_offset=None): + # multiple as_strided do not compound + base = canonical_base(tensor) + # TODO: this is heavyweight + st = ShapeTracker(base.lazydata.st.views + (View.create(tuple(size), tuple(stride), storage_offset),)) + ret = base + if TORCH_DEBUG >= 1: print("**** as_strided", tensor.shape, size, stride, st) + if prod(size) == 1: return ret.flatten()[storage_offset].reshape(size) + for mo in cached_to_movement_ops(tuple(base.shape), st): ret = apply_mop(ret, mo) + return ret + return _as_strided(tensor, size, stride, storage_offset) + +@torch.library.impl("aten::empty_strided", "privateuseone") +def empty_strided(size, stride, dtype, layout=None, device=None, pin_memory=False): + if TORCH_DEBUG: print(f"empty_strided {size=} {stride=} {dtype=} {layout=} {device=} {pin_memory=}") + ret = Tensor.empty(*size, dtype=_from_torch_dtype(dtype), device=_from_torch_device(device)).contiguous() + # TODO: should return with requested strides + return wrap(ret) + +@torch.library.impl("aten::empty.memory_format", "privateuseone") +def empty_memory_format(size, dtype=None, layout=None, device=None, pin_memory=False, memory_format=None): + if TORCH_DEBUG: print(f"empty.memory_format {size=} {dtype=} {layout=} {device=} {pin_memory=} {memory_format=}") + ret = Tensor.empty(*size, dtype=_from_torch_dtype(dtype or torch.get_default_dtype()), device=_from_torch_device(device)).contiguous() + return wrap(ret) + +@torch.library.impl("aten::max_pool2d_with_indices", "privateuseone") +def max_pool2d_with_indices(self:torch.Tensor, kernel_size:tuple[int, ...], stride=None, padding=0, dilation=1, ceil_mode=False): + # TODO: supprt stride [] in tinygrad? + if stride is not None and len(stride) == 0: stride = None + ret, idx = unwrap(self).max_pool2d(kernel_size, stride, dilation, padding, ceil_mode, return_indices=True) + return (wrap(ret), wrap(idx.cast(dtypes.int64))) + +@torch.library.impl("aten::max_pool2d_with_indices_backward", "privateuseone") +def max_pool2d_with_indices_backward(grad_out:torch.Tensor, self:torch.Tensor, kernel_size:tuple[int, ...], stride=None, padding=0, dilation=1, ceil_mode=False, indices=None): + return wrap(Tensor.max_unpool2d(unwrap(grad_out), unwrap(indices), output_size=unwrap(self).shape)) + +@torch.library.impl("aten::max_unpool2d", "privateuseone") +def max_unpool2d(self:torch.Tensor, indices:torch.Tensor, output_size): + return wrap(unwrap(self).max_unpool2d(unwrap(indices), output_size=output_size)) + +@torch.library.impl("aten::arange", "privateuseone") +def arange(end, dtype=None, device=None, pin_memory=None): + return wrap(Tensor.arange(0, end, dtype=_from_torch_dtype(dtype or torch.get_default_dtype()))) + +@torch.library.impl("aten::arange.start", "privateuseone") +def arange_start(start, end, dtype=None, device=None, pin_memory=None): + return wrap(Tensor.arange(start, end, dtype=_from_torch_dtype(dtype or torch.get_default_dtype()))) + +@torch.library.impl("aten::arange.start_step", "privateuseone") +def arange_start_step(start, end, step, dtype=None, device=None, pin_memory=None): + return wrap(Tensor.arange(start, end, step, dtype=_from_torch_dtype(dtype or torch.get_default_dtype()))) + +@torch.library.impl("aten::convolution_overrideable", "privateuseone") +def convolution_overrideable(input, weight, bias, stride, padding, dilation, transposed, output_padding, groups): + if TORCH_DEBUG >= 1: + print(f"convolution {input.shape=} {weight.shape=} {stride=} {padding=} {dilation=} {transposed=} {output_padding=} {groups=}") + input, weight, bias = unwrap(input), unwrap(weight), unwrap(bias) if bias is not None else None + # TODO: fix test_biased_conv2d fails without realize() + if not transposed: return wrap(input.conv2d(weight, bias, groups=groups, stride=stride, dilation=dilation, padding=padding).realize()) + return wrap(input.conv_transpose2d(weight, bias, groups=groups, stride=stride, dilation=dilation, padding=padding, output_padding=output_padding).realize()) + +@torch.library.impl("aten::convolution_backward_overrideable", "privateuseone") +def convolution_backward_overrideable(grad_out, input, weight, stride, padding, dilation, transposed, output_padding, groups, output_mask): + if TORCH_DEBUG >= 1: + print(f"convolution_backward {input.shape=} {weight.shape=} {stride=} {padding=} {dilation=} {transposed=} {output_padding=} {groups=}") + grad_out, input, weight, bias = unwrap(grad_out), unwrap(input), unwrap(weight), Tensor.zeros(weight.shape[0], device=_from_torch_device(weight.device)) + if not transposed: out = Tensor.conv2d(input, weight, bias, groups=groups, stride=stride, dilation=dilation, padding=padding) + else: + bias = Tensor.zeros(weight.shape[1] * groups) + out = Tensor.conv_transpose2d(input, weight, bias, groups=groups, stride=stride, dilation=dilation, padding=padding, output_padding=output_padding) + grads = out.gradient(*[t for t,m in zip([input, weight, bias], output_mask) if m], gradient=grad_out) + return tuple([wrap(grads.pop(0)) if m else None for m in output_mask]) + +@torch.library.impl("aten::slice.Tensor", "privateuseone") +@wrap_view_op +def slice_tensor(self, dim=0, start=None, end=None, step=1): + slices = [slice(None)] * self.ndim + slices[dim] = slice(start, end, step) + return self[slices] + +@torch.library.impl("aten::slice_backward", "privateuseone") +def slice_backward(grad_out, input_sizes, dim, start, end, step): + grad_input = Tensor.zeros(input_sizes).contiguous() + slices = [slice(None)] * len(input_sizes) + slices[dim] = slice(start, end, step) + grad_input[slices] = unwrap(grad_out) + return wrap(grad_input) + +@torch.library.impl("aten::select_backward", "privateuseone") +def select_backward(grad_out, input_sizes, dim, index): + grad_input = Tensor.zeros(input_sizes).contiguous() + slices = [slice(None)] * len(input_sizes) + slices[dim] = index + grad_input[slices] = unwrap(grad_out) + return wrap(grad_input) + +def avg_pool(self, kernel_size, stride=[], padding=0, ceil_mode=False, count_include_pad=True, divisor_override=None): + return wrap(unwrap(self).avg_pool2d(kernel_size, stride if stride != [] else None, padding=padding, ceil_mode=ceil_mode, count_include_pad=count_include_pad)) + +def avg_pool_backward(grad_out, self, kernel_size, stride=None, padding=0, ceil_mode=False, count_include_pad=True, divisor_override=None): + self, grad_out = unwrap(self), unwrap(grad_out) + out = Tensor.avg_pool2d(self, kernel_size, stride if stride != [] else None, dilation=1, padding=padding, ceil_mode=ceil_mode, count_include_pad=count_include_pad) + return wrap(out.gradient(self, gradient=grad_out)[0]) + +for dim in [2, 3]: + torch.library.impl(f"aten::avg_pool{dim}d", "privateuseone")(avg_pool) + torch.library.impl(f"aten::avg_pool{dim}d_backward", "privateuseone")(avg_pool_backward) + +def pad_forward(self, padding, mode=None): return wrap(Tensor.pad(unwrap(self), padding, mode=mode)) + +def pad_backward(grad_out, self, padding, mode): + self, grad_out = unwrap(self), unwrap(grad_out) + out = Tensor.pad(self, padding, mode=mode) + return wrap(out.gradient(self, gradient=grad_out)[0]) + +for dim in [1, 2, 3]: + for pad_type, mode in [("replication", "replicate"), ("reflection", "reflect")]: + torch.library.impl(f"aten::{pad_type}_pad{dim}d", "privateuseone")(functools.partial(pad_forward, mode=mode)) + torch.library.impl(f"aten::{pad_type}_pad{dim}d_backward", "privateuseone")(functools.partial(pad_backward, mode=mode)) + +def upsample(self, size, align_corners=False, mode=None): return wrap(Tensor.interpolate(unwrap(self), size, mode=mode, align_corners=align_corners)) +for i,pre in enumerate(["", "bi", "tri"]): + torch.library.impl(f"aten::upsample_{pre}linear{i+1}d", "privateuseone")(functools.partial(upsample, mode="linear")) + torch.library.impl(f"aten::upsample_nearest{i+1}d", "privateuseone")(functools.partial(upsample, mode="nearest")) + torch.library.impl(f"aten::_upsample_nearest_exact{i+1}d", "privateuseone")(functools.partial(upsample, mode="nearest-exact")) + +@torch.library.impl("aten::scatter_add.out", "privateuseone") +@inplace_fn("out") +def scatter_add(self, dim, index, src, out): + self, index, src, out = unwrap(self), unwrap(index), unwrap(src), unwrap(out) + if self.shape == (): return wrap(out.assign(src)) + return wrap(out.assign(Tensor.scatter_reduce(self, dim, index, src, reduce='sum'))) + +@torch.library.impl("aten::_copy_from", "privateuseone") +def _copy_from(src: torch.Tensor, dest, non_blocking=False): + realize = dest.is_tiny and maybe_realize_storage(unwrap(dest)) + cast_dtype = _from_torch_dtype(dest.dtype) + if src.is_tiny and dest.is_tiny: + to_device = _from_torch_device(dest.device) + src,dest = unwrap(src),unwrap(dest) + # TODO we need to properly match dest shape and strides, not blindly assign + if dest.lazydata.st.contiguous or dest.lazydata.is_realized: src = src.contiguous() # this only solves some cases + dest.assign(src.cast(cast_dtype).to(to_device)) + if realize: Tensor.realize(dest) + elif src.is_tiny and dest.is_cpu: + # TODO: is there a better way? + dest.resize_(src.numel()).resize_(src.shape) + dest.copy_(torch.from_numpy(unwrap(src).cast(cast_dtype).numpy())) + elif src.is_cpu and dest.is_tiny: + to_device = _from_torch_device(dest.device) + # TODO we need to properly match dest shape and strides, not blindly assign + unwrap(dest).assign(Tensor(src.numpy()).cast(cast_dtype).to(to_device)) + if realize: Tensor.realize(unwrap(dest)) + else: + raise NotImplementedError(f"can't copy from {src.device} -> {dest.device}") + +@torch.library.impl("aten::cat.out", "privateuseone") +@inplace_fn("out") +def cat_out(tensors, dim=0, out=None): + unwrap(out).assign(Tensor.cat(*[unwrap(x) for x in tensors], dim=dim)) + +@torch.library.impl("aten::topk.values", "privateuseone") +@inplace_fn(["values", "indices"]) +def topk_values(input, k, dim=None, largest=True, sorted=True, values=None, indices=None): + out_values, out_indices = unwrap(input).topk(k, dim if dim is not None else -1, largest, sorted) + unwrap(values).assign(out_values) + unwrap(indices).assign(out_indices.cast(dtypes.int64)) + return wrap(out_values), wrap(out_indices) + +@torch.library.impl("aten::sort.values_stable", "privateuseone") +@inplace_fn(["values", "indices"]) +def sort_values(input, dim=-1, descending=False, stable=True, values=None, indices=None): + out_values, out_indices = unwrap(input).sort(dim, descending) + unwrap(values).assign(out_values) + unwrap(indices).assign(out_indices.cast(dtypes.int64)) + return wrap(out_values), wrap(out_indices) + +# register some decompositions +from torch._decomp import get_decompositions +decomps = [ + aten.native_batch_norm, aten.native_batch_norm_backward, + aten.native_layer_norm_backward, + aten.addmm, + aten.addcmul, + aten.addcdiv, + aten._log_softmax_backward_data, + aten.threshold_backward, + aten.softplus_backward, + aten.elu, # elu has a scale + input_scale param + aten.elu_backward, + aten.softplus, + aten.threshold, + aten.nll_loss_forward, + aten.nll_loss_backward, + # AttributeError: 'int' object has no attribute '_broadcasted' + aten.sigmoid_backward, + aten.tanh_backward, + aten.sinc, + aten._prelu_kernel, + aten.softshrink, + aten.hardshrink, + aten.log_sigmoid_forward, + aten.isneginf, + aten.isposinf, + aten.nan_to_num, + aten.logit, + aten.rsub, + aten.index_select, + aten.native_dropout, aten.native_dropout_backward, + aten._softmax_backward_data, aten.embedding_dense_backward, + aten.linalg_vector_norm, + aten.binary_cross_entropy, aten.binary_cross_entropy_backward, + aten.upsample_nearest2d.out, + # activations + aten.hardswish, aten.hardswish_backward, + aten.hardtanh, aten.hardtanh_backward, + aten.gelu, aten.gelu_backward, + aten.logical_and, + aten.randint, + aten.eye, + aten.hardsigmoid_backward, + aten.leaky_relu_backward, + aten.nll_loss2d_forward, + # NOTE: many of these don't work or cause infinite loops + #aten.var_mean, + #aten.var, + #aten.rsqrt, + #aten.max_pool2d_with_indices, + # NOTE: these are prims + #aten.digamma, + #aten.erfinv, + #aten.lgamma, + # this needs copy_strided + #aten.lerp, +] +for k,v in get_decompositions(decomps).items(): + key = str(k._schema).split("(")[0] + if TORCH_DEBUG >= 2: print("register decomp for", k) + torch.library.impl(key, "privateuseone")(v) + +# NOTE: we should only implement the "out" form, it should be 0 overhead +# TODO: due to issue with empty / is_realized, it is slow to use assign so we use replace +# the goal is to make as much as we can this +simple_tensor_methods = [ + # unary (ish) + "log", "log2", "sqrt", "rsqrt", "sign", "silu", "hardsigmoid", "exp", "exp2", "neg", "reciprocal", "bitwise_not", + "sigmoid", "clamp", "mish", "erf", "leaky_relu", + # trig + "acos", "acosh", "cos", "cosh", "asin", "asinh", "sin", "sinh", "atan", "atanh", "tan", "tanh", + # rounding + "ceil", "round", "floor", "trunc", + # binary + "mul", "div", "maximum", "minimum", "copysign", + # modify + "tril", "triu", + # reduce + "all", "any", "argmax", "argmin", "cumsum", "cumprod", + # complex + "avg_pool2d", "linspace"] + +tiny_backend_out = {**{f"aten.{x}.out":getattr(Tensor,x) for x in simple_tensor_methods}, **{ + "aten.add.out": lambda input,other,alpha=1: input+alpha*other, + "aten.sub.out": lambda input,other,alpha=1: input-alpha*other, # NOTE: this is also needed to handle reverse + "aten.div.out_mode": Tensor.div, + "aten.mul.out": operator.mul, + "aten.bmm.out": operator.matmul, + # NOTE: because these methods have a name with "Tensor" in them, they can't go in simple tensor methods + "aten.remainder.Tensor_out": Tensor.mod, + "aten.pow.Tensor_Tensor_out": Tensor.pow, + "aten.pow.Tensor_Scalar_out": Tensor.pow, + "aten.pow.Scalar_out": lambda input,exponent: input**exponent, + "aten.bitwise_and.Tensor_out": Tensor.bitwise_and, + "aten.bitwise_or.Tensor_out": Tensor.bitwise_or, + "aten.bitwise_xor.Tensor_out": Tensor.bitwise_xor, + "aten.eq.Tensor_out": Tensor.eq, "aten.eq.Scalar_out": Tensor.eq, + "aten.ne.Tensor_out": Tensor.ne, "aten.ne.Scalar_out": Tensor.ne, + "aten.ge.Tensor_out": Tensor.__ge__, "aten.ge.Scalar_out": Tensor.__ge__, + "aten.gt.Tensor_out": Tensor.__gt__, "aten.gt.Scalar_out": Tensor.__gt__, + "aten.lt.Tensor_out": Tensor.__lt__, "aten.lt.Scalar_out": Tensor.__lt__, + "aten.le.Tensor_out": Tensor.__le__, "aten.le.Scalar_out": Tensor.__le__, + "aten.clamp_max.Tensor_out": lambda input,max_: input.clamp(max_=max_), + "aten.clamp_min.Tensor_out": lambda input,min_: input.clamp(min_=min_), + "aten.fmod.Tensor_out": lambda input,other: input-input.div(other, rounding_mode="trunc")*other, + # TODO: this might result in overflow issues + "aten.round.decimals_out": lambda self,decimals: (self*10**decimals).round()/10**decimals, + # TODO: support this in tinygrad + "aten.bitwise_left_shift.Tensor_out": lambda x,y: x*(2**y), + "aten.bitwise_right_shift.Tensor_out": lambda x,y: x//(2**y), + # not in tinygrad. are there decomps for these? + "aten.log10.out": lambda self: self.log2() * (math.log(2) / math.log(10)), + "aten.log1p.out": lambda self: (self+1).log(), + "aten.expm1.out": lambda self: self.exp() - 1, + "aten.fmax.out": lambda input,other: Tensor.where(input.isnan() & ~other.isnan(), other, Tensor.where(~input.isnan() & other.isnan(), input, Tensor.maximum(input, other))), + "aten.fmin.out": lambda input,other: Tensor.where(input.isnan() & ~other.isnan(), other, Tensor.where(~input.isnan() & other.isnan(), input, Tensor.minimum(input, other))), + "aten.amax.out": lambda self,dim=None: self.max(axis=dim), + # TODO: this gets the shape wrong + #"aten.arange.start_out": Tensor.arange, + "aten.lerp.Scalar_out": Tensor.lerp, + "aten.scatter.value_out": Tensor.scatter, + "aten.where.self_out": Tensor.where, + "aten.prod.int_out": Tensor.prod, + "aten.scatter.src_out": Tensor.scatter, + # NOTE: axis=[] in torch means all, change tinygrad? + "aten.sum.IntList_out": lambda self,axis,keepdim=False,dtype=None: + self.sum(axis if axis is None or len(axis) else None, keepdim, + dtype = _from_torch_dtype(dtype) if dtype is not None else None), +}} + +# we add the "out" here +def wrap_out(f): + @inplace_fn("out") + def _wrap_out(*args, **kwargs): + out = kwargs.pop('out') + assigned = f(*args, **kwargs) + if getenv("ALLOW_DTYPE_MISMATCH", 1): assigned = assigned.cast(out.dtype) + assert out.shape == assigned.shape, f"shape mismatch: {assigned.shape} -> {out.shape}" + assert out.device == assigned.device, f"device mismatch: {assigned.device} -> {out.device}" + assert out.dtype == assigned.dtype, f"dtype mismatch: {assigned.dtype} -> {out.dtype}" + if out.lazydata.is_realized: assigned = assigned.contiguous() # TODO: how does this map to torch's semantics + return out.assign(assigned) + return _wrap_out + +tiny_backend = {**{k:wrap_out(v) for k,v in tiny_backend_out.items()}, **{ + "aten.remainder.Scalar_Tensor": lambda x,y: x%y, + "aten.floor_divide": lambda x,y: x//y, + "aten.floor_divide_.Tensor": inplace_fn("x")(lambda x,y: x.assign(x//y)), + # TODO: use tinygrad methods, but they require x to be unsigned + "aten.__lshift__.Scalar": lambda x,y: x*(2**y), + "aten.__ilshift__.Scalar": inplace_fn("x")(lambda x,y: x.assign(x*(2**y))), + "aten.__rshift__.Scalar": lambda x,y: x//(2**y), + "aten.__irshift__.Scalar": inplace_fn("x")(lambda x,y: x.assign(x//(2**y))), + # relu doesn't have an out form? + "aten.relu": Tensor.relu, + "aten.relu_": inplace_fn("x")(lambda x: x.assign(x.relu())), + "aten.mean": Tensor.mean, + "aten.mean.dim": Tensor.mean, + "aten.min": Tensor.min, + "aten.max": Tensor.max, + "aten.mm": Tensor.matmul, + "aten.mv": Tensor.matmul, + "aten.dot": Tensor.dot, + "aten.prod": Tensor.prod, + "aten.isnan": Tensor.isnan, + "aten.std.correction": Tensor.std, + "aten.std_mean.correction": Tensor.std_mean, + "aten.var.correction": Tensor.var, + "aten.var_mean.correction": Tensor.var_mean, + "aten.scatter.value": Tensor.scatter, + "aten.scatter.value_reduce": Tensor.scatter, + "aten.gather": lambda self, dim, index: self.gather(dim, index.cast(dtypes.int)), + "aten.where.self": Tensor.where, # NOTE: this is needed as well as the out type + "aten.repeat": lambda x,*repeats: Tensor.repeat(x,*repeats).contiguous(), # not a view + "aten._softmax": lambda self,dim,half_to_float: self.softmax(dim), + "aten._log_softmax": lambda self,dim,half_to_float: self.log_softmax(dim), + "aten.random_": inplace_fn("self")(lambda self: + self.assign(Tensor.randint(*self.shape, low=dtypes.min(self.dtype), high=dtypes.max(self.dtype), device=self.device, dtype=self.dtype))), + "aten.random_.from": inplace_fn("self")(lambda self, from_, to: + self.assign(Tensor.randint(*self.shape, low=from_, high=to, device=self.device, dtype=self.dtype))), + "aten.uniform_": inplace_fn("self")(lambda self, low=0, high=1: self.assign(Tensor.uniform(*self.shape, low=low, high=high, dtype=self.dtype))), + "aten.normal_": inplace_fn("self")(lambda self, mean=0, std=1: self.assign(Tensor.normal(*self.shape, mean=mean, std=std, dtype=self.dtype))), + # these don't work in out form, they have size 0 + "aten.abs": Tensor.abs, + "aten.logical_not": Tensor.logical_not, + "aten.logical_or_": inplace_fn("x")(lambda x, y: x.assign(x | y)), + "aten.multinomial": Tensor.multinomial, + "aten.masked_fill_.Scalar": inplace_fn("self")(lambda self, mask, value: self.assign(self.masked_fill(mask, value))), + "aten.masked_fill_.Tensor": inplace_fn("self")(lambda self, mask, value: self.assign(self.masked_fill(mask, value))), + "aten.masked_fill.Scalar": Tensor.masked_fill, + "aten.masked_fill.Tensor": Tensor.masked_fill, + "aten.masked_select": Tensor.masked_select, + "aten.all": Tensor.all, + "aten.sgn": Tensor.sign, + "aten.acos": Tensor.acos, + "aten.any": Tensor.any, + "aten.bitwise_not": Tensor.bitwise_not, + "aten.argmax": Tensor.argmax, + "aten.argmin": Tensor.argmin, + "aten.asinh": Tensor.asinh, + "aten.mul": Tensor.mul, + "aten.atanh": Tensor.atanh, + "aten.fill_.Tensor": Tensor.full, # TODO: looks wrong + "aten.flip": Tensor.flip, + "aten.scatter_reduce.two": Tensor.scatter_reduce, + "aten.squeeze_.dim": lambda self, dim: self.replace(self.squeeze(dim), allow_shape_mismatch=True), # TODO: inplace view op, here? + "aten.add.Tensor": lambda input,other,alpha=1: input+alpha*other, + "aten.linspace": lambda start, stop, steps, dtype=None, **kwargs: + Tensor.linspace(start, stop, steps, **({"dtype": _from_torch_dtype(dtype)} if dtype is not None else {})), + "aten.topk": Tensor.topk, + "aten.constant_pad_nd": lambda self, padding, value=0.0: self.pad(padding, mode="constant", value=value).contiguous(), + "aten.cumsum": lambda self, dim: self.cumsum(dim).contiguous(), # TODO: fix test_simple_cumsum, fails without contiguous for shapes >512 + "aten.logsumexp": lambda self, axis, keepdim=False: self.logsumexp(axis[0], keepdim=keepdim), + "aten.roll": Tensor.roll, + "aten.logcumsumexp": Tensor.logcumsumexp, + "aten.lerp.Tensor": Tensor.lerp, + "aten.ones_like": lambda self, dtype=None, device=None, **kwargs: + self.ones_like(**{k: v for k, v in {"dtype": _from_torch_dtype(dtype) if dtype else None, + "device": _from_torch_device(device) if device else None}.items() if v is not None}), + "aten.max.dim": lambda self, dim, keepdim=False: (self.max(dim, keepdim), self.argmax(dim, keepdim).cast(dtype=dtypes.int64)) +}} + +def wrap_fxn(k,f): + def nf(*args, **kwargs): + if TORCH_DEBUG: + print(k, len(args), [x.shape if isinstance(x, torch.Tensor) else x for x in args], + {k:v.shape if isinstance(v, torch.Tensor) else v for k,v in kwargs.items()}) + args = [unwrap(x) if isinstance(x, torch.Tensor) else x for x in args] + kwargs = {k:unwrap(v) if isinstance(v, torch.Tensor) else v for k,v in kwargs.items()} + out = f(*args, **kwargs) + if isinstance(out, Tensor): return wrap(out) + elif isinstance(out, tuple): return tuple(wrap(x) for x in out) + else: raise RuntimeError(f"unknown output type {type(out)}") + return nf + +for k,v in tiny_backend.items(): torch.library.impl(k.replace("aten.", "aten::"), "privateuseone")(wrap_fxn(k,v)) + +@torch.library.impl("aten::equal", "privateuseone") +def equal(x: torch.Tensor, y: torch.Tensor): return (x==y).all().item() + +if TORCH_DEBUG: + from torch.utils._python_dispatch import TorchDispatchMode + class DispatchLog(TorchDispatchMode): + def __torch_dispatch__(self, func, types, args=(), kwargs=None): + #print(f"Dispatch Log: {func}(*{args}, **{kwargs})") + print(f"Dispatch Log: {func}") + return func(*args, **(kwargs or {})) + (_dispatch_log:=DispatchLog()).__enter__() # NOTE: must be kept alive + +# NOTE: patch torch optimizer step to avoid continously growing the computation graph +import weakref +_torch_modules_with_buffers: weakref.WeakSet[torch.nn.Module] = weakref.WeakSet() +def register_torch_buffer(mod, _name, _buffer): _torch_modules_with_buffers.add(mod) +def get_real_tinygrad_buffers(): + res = set() + for mod in _torch_modules_with_buffers: + for _,b in mod.named_buffers(recurse=False): + if b is not None and b.is_tiny: + res.add(unwrap(b)) + return res +torch.nn.modules.module.register_module_buffer_registration_hook(register_torch_buffer) + +from torch.nn.modules import Module +def backward_hook(model:Module, _grad_input, _grad_out): + grads_to_realize = [unwrap(p.grad) for p in model.parameters() if p.grad is not None] + if len(grads_to_realize): Tensor.realize(*grads_to_realize) +def module_hook(module:Module, _name, _submodule): module.register_backward_hook(backward_hook) +torch.nn.modules.module.register_module_module_registration_hook(module_hook) + +def realize_optimizer_step(optimizer: torch.optim.Optimizer, *args, **kwargs): + tinygrad_tensors = [] + for param_group in optimizer.param_groups: + for param in param_group["params"]: + if param is None: continue + tinygrad_tensors.append(param.data) + for state_dict in optimizer.state.values(): + for _, value in state_dict.items(): + if torch.is_tensor(value): tinygrad_tensors.append(value) + real_tinygrad_tensors = [unwrap(x) for x in tinygrad_tensors if x.is_tiny] + real_tinygrad_tensors += get_real_tinygrad_buffers() + if len(real_tinygrad_tensors): Tensor.realize(*real_tinygrad_tensors) + +_optimizer_init = torch.optim.Optimizer.__init__ +def _optimizer_patched_init(self, *args, **kwargs): + _optimizer_init(self, *args, **kwargs) + self.register_step_post_hook(realize_optimizer_step) +torch.optim.Optimizer.__init__ = _optimizer_patched_init diff --git a/tinygrad_repo/extra/torch_backend/backend2.py b/tinygrad_repo/extra/torch_backend/backend2.py new file mode 100644 index 0000000000..9ce3bb233d --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/backend2.py @@ -0,0 +1,47 @@ +# NOTE: this is probably the wrong backend to work on, you want backend.py +# discussion about this in #pytorch-backend on our Discord +# this is using high level debug features from torch and we should integrate deeper + +from tinygrad import Tensor +import torch, contextlib +from torch.utils._python_dispatch import TorchDispatchMode +from tinygrad.dtype import _from_torch_dtype + +def empty_memory_format(size, dtype=None, layout=None, device=None, pin_memory=False, memory_format=None): + return TTensor(Tensor.empty(*size, dtype=_from_torch_dtype(dtype))) + +# NOTE: if we have a way to change wrap/unwrap, these can be the same methods from backend.py +tiny_backend = { + "aten.empty.memory_format": empty_memory_format, + "aten.view.default": lambda x,sz: TTensor(x.tiny.reshape(sz)), + "aten.abs.default": lambda x: TTensor(x.tiny.abs()), + "aten.eq.Tensor": lambda x,y: TTensor(x.tiny == y.tiny), + "aten.bitwise_and.Tensor": lambda x,y: TTensor(x.tiny & y.tiny), + "aten.ne.Scalar": lambda x,y: TTensor(x.tiny != y), + "aten.mul.Tensor": lambda x,y: TTensor(x.tiny * y.tiny), + "aten.masked_select.default": lambda x,y: TTensor(Tensor(x.tiny.numpy()[y.tiny.numpy()])), +} + +class TTensor(torch.Tensor): + tiny: Tensor + context = contextlib.nullcontext + + @staticmethod + def __new__(cls, tiny, *args, **kwargs): + out = torch.Tensor._make_wrapper_subclass(cls, tiny.shape) + torch._C._set_throw_on_mutable_data_ptr(out) + out.tiny = tiny + return out + def __repr__(self): return super().__repr__(tensor_contents=f"{self.tiny}") + def __torch_dispatch__(cls, func, types, args, kwargs=None): + print(f"Dispatch Log: {func}(*{[type(x) for x in args]}, **{kwargs.keys()})") + #print(f"Dispatch Log: {func}(*{args}, **{kwargs})") + new_func = tiny_backend.get(str(func), None) + if new_func is None: raise NotImplementedError(f"add support for {func}") + return new_func(*args, **(kwargs or {})) + +class Dispatcher(TorchDispatchMode): __torch_dispatch__ = TTensor.__torch_dispatch__ +Dispatcher().__enter__() + +if __name__ == "__main__": + a = torch.empty((4,), dtype=torch.int) diff --git a/tinygrad_repo/extra/torch_backend/example.py b/tinygrad_repo/extra/torch_backend/example.py new file mode 100644 index 0000000000..cc7ab159bc --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/example.py @@ -0,0 +1,21 @@ +from PIL import Image +from tinygrad.helpers import getenv +import torch, torchvision, pathlib +import torchvision.transforms as transforms +import extra.torch_backend.backend +device = "tiny" +torch.set_default_device(device) + +if __name__ == "__main__": + img = Image.open(pathlib.Path(__file__).parent.parent.parent / "test/models/efficientnet/Chicken.jpg").convert('RGB') + transform = transforms.Compose([ + transforms.Resize(256), transforms.CenterCrop(224), transforms.ToTensor(), + transforms.Normalize(mean=[0.485, 0.456, 0.406], std=[0.229, 0.224, 0.225]) + ]) + img = transform(img).unsqueeze(0).to(device) + + model = torchvision.models.resnet18(weights=torchvision.models.ResNet18_Weights.DEFAULT) + if getenv("EVAL", 1): model.eval() + out = model(img).detach().cpu().numpy() + print("output:", out.shape, out.argmax()) + assert out.argmax() == 7 # cock diff --git a/tinygrad_repo/extra/torch_backend/test.py b/tinygrad_repo/extra/torch_backend/test.py new file mode 100644 index 0000000000..f92be531c1 --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/test.py @@ -0,0 +1,198 @@ +# simple tests +import unittest +import torch +import numpy as np +from tinygrad.helpers import getenv, Context, GlobalCounters +if getenv("TINY_BACKEND2"): + import extra.torch_backend.backend2 + device = "cpu" +else: + import extra.torch_backend.backend + device = "tiny" + +class TestTorchBackend(unittest.TestCase): + def test_randperm_generator_out(self): + n = 10 + out = torch.empty(n, dtype=torch.long, device=device) + res = torch.randperm(n, out=out).cpu().numpy() + np.testing.assert_equal(set(res), set(range(n))) + np.testing.assert_equal(out.cpu().numpy(), res) + + res2 = torch.randperm(n).cpu().numpy() + np.testing.assert_equal(set(res2), set(range(n))) + + def test_numpy_ones(self): + a = torch.ones(4, device=device) + np.testing.assert_equal(a.cpu().numpy(), [1,1,1,1]) + + def test_numpy_ones(self): + a = torch.ones(4, dtype=torch.int32, device=device) + assert a.dtype == torch.int32 + np.testing.assert_equal(a.cpu().numpy(), [1,1,1,1]) + + def test_plus(self): + a = torch.ones(4, device=device) + b = torch.ones(4, device=device) + c = a+b + np.testing.assert_equal(c.cpu().numpy(), [2,2,2,2]) + + def test_expand(self): + a = torch.Tensor([1,2,3,4]).to(device) + out = a.reshape(4,1).expand(4,4) + np.testing.assert_equal(out.cpu().numpy(), [[1,1,1,1],[2,2,2,2],[3,3,3,3],[4,4,4,4]]) + + def test_reshape(self): + a = torch.Tensor([[1,2],[3,4]]).to(device) + np.testing.assert_equal(a.reshape(4).cpu().numpy(), [1,2,3,4]) + np.testing.assert_equal(a.reshape(2,1,2).cpu().numpy(), [[[1,2]],[[3,4]]]) + np.testing.assert_equal(a.unsqueeze(1).cpu().numpy(), [[[1,2]],[[3,4]]]) + np.testing.assert_equal(a.unsqueeze(1).unsqueeze(1).cpu().numpy(), [[[[1,2]]],[[[3,4]]]]) + np.testing.assert_equal(a.unsqueeze(1).unsqueeze(1).squeeze().cpu().numpy(), [[1,2],[3,4]]) + + def test_permute(self): + a = torch.Tensor([[1,2],[3,4]]).to(device) + print(a.stride()) + null = a.permute(0,1) + perm = a.permute(1,0) + back = perm.permute(1,0) + np.testing.assert_equal(a.cpu().numpy(), [[1,2],[3,4]]) + np.testing.assert_equal(null.cpu().numpy(), [[1,2],[3,4]]) + np.testing.assert_equal(perm.cpu().numpy(), [[1,3],[2,4]]) + np.testing.assert_equal(back.cpu().numpy(), [[1,2],[3,4]]) + + def test_shrink(self): + a = torch.Tensor([1,2,3,4]).to(device) + np.testing.assert_equal(a[:3].cpu().numpy(), [1,2,3]) + np.testing.assert_equal(a[1:].cpu().numpy(), [2,3,4]) + + def test_as_strided(self): + a = torch.arange(70, device=device).reshape(1,1,10,7) + a = a.as_strided((1,1,10,5), (0,0,7,1), storage_offset=0) + a = a.as_strided((1,1,5,5), (50,50,7,1), storage_offset=21) + np.testing.assert_equal(a.cpu().numpy().sum(-1), [[[115,150,185,220,255]]]) + + def test_plus_inplace(self): + a = torch.ones(4, device=device) + b = torch.ones(4, device=device) + a += b + a += b + np.testing.assert_equal(a.cpu().numpy(), [3,3,3,3]) + + def test_exp2(self): + a = torch.ones(4, device=device) + b = a.exp2() + np.testing.assert_equal(b.cpu().numpy(), [2,2,2,2]) + + def test_amax(self): + x = torch.tensor([[[ 1.5, 2.3, 3.1, 4.7], + [ 5.2, 6.8, 7.4, 12.9], + [ 9.0, 12.3, 11.6, 10.1]], + [[13.2, 16.9, 15.5, 14.1], + [17.1, 24.9, 19.8, 20.2], + [21.0, 22.3, 23.6, 18.4]]], device=device) + + y1 = torch.amax(x) + expected = np.array([24.9], dtype=np.float32) + np.testing.assert_equal(y1.cpu().numpy(), expected) + + y2 = torch.amax(x, dim=(1,2)) + expected = np.array([12.9, 24.9], dtype=np.float32) + np.testing.assert_equal(y2.cpu().numpy(), expected) + + y3 = torch.amax(x, dim=2) + expected = np.array([[4.7, 12.9, 12.3], [16.9, 24.9, 23.6]], dtype=np.float32) + np.testing.assert_equal(y3.cpu().numpy(), expected) + + def test_isfinite(self): + a = torch.ones(4, device=device) + np.testing.assert_equal(torch.isfinite(a).cpu().numpy(), [True, True, True, True]) + + def test_eq(self): + a = torch.ones(4, device=device) + b = torch.ones(4, device=device) + c = a == b + print(c.cpu()) + + def test_maxpool2d_backward(self): + x = torch.arange(3*3, device=device).reshape(1, 1, 3, 3).requires_grad_(True) + torch.nn.functional.max_pool2d(x, kernel_size=2, stride=1).sum().backward() + np.testing.assert_equal(x.grad.squeeze().cpu().numpy(), [[0, 0, 0], [0, 1, 1], [0, 1, 1]]) + + def test_copy_cast(self): + x = torch.zeros(4, device=device, dtype=torch.int64) + y = torch.ones(4, device=device, dtype=torch.float32).to(dtype=torch.int64) + res1 = x ^ y # an operation that only works on int types + print(res1.cpu()) + y = y.cpu().float().to(device=device, dtype=torch.int64) + res2 = x ^ y + print(res2.cpu()) + + def test_topk(self): + # test topk return_types + a = torch.tensor([1, 3, 2, 4], device=device) + out = torch.topk(a, k=2) + np.testing.assert_equal(out.values.cpu().numpy(), [4, 3]) + np.testing.assert_equal(out.indices.cpu().numpy(), [3, 1]) + + def test_masked_select(self): + a = torch.tensor([4, 3, 2, 1], device=device) + mask = torch.tensor([True, False, True, False], device=device) + out = torch.masked_select(a, mask) + np.testing.assert_equal(out.cpu().numpy(), [4, 2]) + mask = torch.tensor(True, device=device) + out = torch.masked_select(a, mask) + np.testing.assert_equal(out.cpu().numpy(), [4, 3, 2, 1]) + + def test_isin_tensor_tensor_out(self): + a = torch.tensor([1, 2, 3], device=device) + b = torch.tensor([2, 4], device=device) + expected_base = torch.tensor([False, True, False], device=device) + for assume_unique in [False, True]: + for invert, expected in [(False, expected_base), (True, ~expected_base)]: + out = torch.empty_like(a, dtype=torch.bool) + res = torch.ops.aten.isin.Tensor_Tensor_out(a, b, invert=invert, assume_unique=assume_unique, out=out) + np.testing.assert_equal(out.cpu().numpy(), expected.cpu().numpy()) + + def test_uniform(self): + for torch_dtype in [torch.float32, torch.float16]: + a = torch.rand(10, 10, device=device, dtype=torch_dtype) + self.assertEqual(a.dtype, torch_dtype) + + def test_normal(self): + for torch_dtype in [torch.float32, torch.float16]: + a = torch.randn(10, 10, device=device, dtype=torch_dtype) + self.assertEqual(a.dtype, torch_dtype) + + def test_equal(self): + tensor_a = torch.tensor([[1, 2], [3, 4]], device=device) + tensor_b = torch.tensor([[1, 2], [3, 4]], device=device) + tensor_c = torch.tensor([[1, 2], [1, 2]], device=device) + assert torch.equal(tensor_a, tensor_b) + assert not torch.equal(tensor_a, tensor_c) + + @unittest.skip("meh") + def test_str(self): + a = torch.ones(4, device=device) + print(str(a)) + + @unittest.skip("failed") + def test_floor_div(self): + a = torch.tensor([10., 7., 5.], device=device) + b = torch.tensor([3., 2., 2.], device=device) + result = a // b + np.testing.assert_equal(result.cpu().numpy(), [3., 3., 2.]) + + def test_mnist_index(self): + with Context(FUSE_ARANGE=1, SPLIT_REDUCEOP=0): + GlobalCounters.reset() + from tinygrad.nn.datasets import mnist + X_train, Y_train, _, _ = mnist() + X_train = torch.tensor(X_train.float().numpy(), device=device) + Y_train = torch.tensor(Y_train.cast('int64').numpy(), device=device) + samples = torch.randint(0, X_train.shape[0], (32,)) + X,Y = X_train[samples], Y_train[samples] + X.cpu(), Y.cpu() + self.assertLessEqual(GlobalCounters.global_ops, 10_000_000) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/extra/torch_backend/test_compile.py b/tinygrad_repo/extra/torch_backend/test_compile.py new file mode 100644 index 0000000000..9becdbf397 --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/test_compile.py @@ -0,0 +1,36 @@ +# https://pytorch.org/tutorials/intermediate/torch_compile_tutorial.html +import torch +import torch._dynamo +from extra.torch_backend.backend import unwrap, wrap + +from torch._dynamo.backends.registry import register_backend +from torch._functorch.aot_autograd import aot_module_simplified + +from tinygrad import Tensor, TinyJit + +@register_backend +def tiny(gm:torch.fx.GraphModule, sample_inputs): + def my_compiler(gm:torch.fx.GraphModule, sample_inputs): + # TODO: the jit should capture the graph directly, not need three runs. this is a planned tinygrad refactor after becomes_map + @TinyJit + def tiny_function(*args:Tensor): + outs = gm(*[wrap(x) for x in args]) + for x in outs: unwrap(x).realize() + return outs + # TODO: this should be able to pass in .tiny() Tensors, not need to convert them. it tries to access Storage if you pass in. + def torch_function(*args:torch.Tensor): return tiny_function(*[unwrap(x.tiny()) for x in args]) + return torch_function + return aot_module_simplified(gm, sample_inputs, decompositions={}, fw_compiler=my_compiler) + +if __name__ == "__main__": + def foo(x, y): + a = torch.sin(x) + b = torch.cos(y) + return a + b + + print("calling compile") + opt_foo1 = torch.compile(foo, backend="tiny") + print("compiled") + for i in range(5): + out = opt_foo1(torch.randn(10, 10), torch.randn(10, 10)) + print(out.device) diff --git a/tinygrad_repo/extra/torch_backend/test_inplace.py b/tinygrad_repo/extra/torch_backend/test_inplace.py new file mode 100644 index 0000000000..e6f171f05f --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/test_inplace.py @@ -0,0 +1,71 @@ +import unittest +import torch +import tinygrad.frontend.torch +torch.set_default_device("tiny") +import numpy as np + +class TestTorchBackendInplace(unittest.TestCase): + def test_zero(self): + a = torch.ones(4) + a.zero_() + np.testing.assert_equal(a.cpu().numpy(), [0,0,0,0]) + + def test_view_zero(self): + a = torch.ones(4) + a.view((2, 2)).zero_() + np.testing.assert_equal(a.cpu().numpy(), [0,0,0,0]) + + def test_slice_zero(self): + a = torch.ones(4) + a[2:].zero_() + np.testing.assert_equal(a.cpu().numpy(), [1,1,0,0]) + + def test_slice_permute_zero(self): + a = torch.ones((3,2)) + a.permute(1,0)[1:].zero_() + np.testing.assert_equal(a.cpu().numpy(), [[1,0],[1,0],[1,0]]) + + def test_slice_fill(self): + a = torch.zeros(4) + a[2:].fill_(2) + np.testing.assert_equal(a.cpu().numpy(), [0,0,2,2]) + + def test_slice_mul(self): + a = torch.ones(4) + a[:2] *= 3 + a[2:] *= 2 + np.testing.assert_equal(a.cpu().numpy(), [3,3,2,2]) + + def test_stacked_mul(self): + a = torch.ones((3,3)) + b = a[1:,1:].permute(1,0) + c = b[1:,:] + b *= 2 + c *= 3 + np.testing.assert_equal(a.cpu().numpy(), [[1,1,1],[1,2,6],[1,2,6]]) + + def test_flatten_reshape_add(self): + a = torch.zeros((2,2,12,32)) + b = a.flatten() + c = b.reshape((48,32)) + a += 1 + b += 1 + c += 1 + np.testing.assert_equal(c.cpu().numpy(), torch.full((48,32),3).cpu().numpy()) + + def test_noncontig(self): + a = torch.empty_strided((4,4),(1,4), dtype=torch.int64) + # self.assertFalse(a.is_contiguous()) # TODO: we are contiguous when it's not required + a.zero_() + b = a.view((4,4)) + b[1:3,:] += 1 + np.testing.assert_equal(a.cpu().numpy(), [[0]*4,[1]*4,[1]*4,[0]*4]) + + def test_detach(self): + a = torch.zeros(4) + d = a.detach() + d += torch.arange(4) + np.testing.assert_array_equal(a.cpu(), torch.arange(4).cpu()) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/extra/torch_backend/test_multigpu.py b/tinygrad_repo/extra/torch_backend/test_multigpu.py new file mode 100644 index 0000000000..9a21898132 --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/test_multigpu.py @@ -0,0 +1,29 @@ +import unittest +from tinygrad.helpers import getenv +import torch +import tinygrad.frontend.torch +torch.set_default_device("tiny") +import numpy as np + +@unittest.skipIf(getenv("GPUS",1)<=1, "only single GPU") +class TestTorchBackendMultiGPU(unittest.TestCase): + def test_transfer(self): + a = torch.Tensor([[1,2],[3,4]]).to("tiny:0") + b = torch.Tensor([[3,2],[1,0]]).to("tiny:1") + self.assertNotEqual(a.device, b.device) + np.testing.assert_array_equal(a.cpu(), a.to("tiny:1").cpu()) + np.testing.assert_array_equal(b.cpu(), b.to("tiny:1").cpu()) + + def test_basic_ops(self): + a = torch.Tensor([[1,2],[3,4]]).to("tiny:0") + b = torch.Tensor([[3,2],[1,0]]).to("tiny:1") + c1 = a + b.to("tiny:0") + c2 = b + a.to("tiny:1") + np.testing.assert_array_equal(c1.cpu(), torch.full((2,2),4).cpu()) + np.testing.assert_array_equal(c1.cpu(), c2.cpu()) + + # TODO: torch.distributed functions + +if __name__ == "__main__": + unittest.main() + diff --git a/tinygrad_repo/extra/torch_backend/torch_tests.py b/tinygrad_repo/extra/torch_backend/torch_tests.py new file mode 100644 index 0000000000..cd8505c094 --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/torch_tests.py @@ -0,0 +1,43 @@ +import sys +import unittest +import torch +import extra.torch_backend.backend + +from torch.testing._internal.common_utils import TestCase, is_privateuse1_backend_available +assert is_privateuse1_backend_available() and torch._C._get_privateuse1_backend_name() == "tiny" +from torch.testing._internal.common_device_type import ops, onlyOn, instantiate_device_type_tests +from torch.testing._internal.common_methods_invocations import unary_ufuncs, binary_ufuncs, reduction_ops, shape_funcs + +def to_cpu(arg): return arg.to(device="cpu") if isinstance(arg, torch.Tensor) else arg +def filter_funcs(ufuncs): return [x for x in ufuncs if not x.name.startswith("_refs") and not x.name.startswith("special")] + +class TestTinyBackend(TestCase): + def _test(self, device, dtype, op): + samples = op.sample_inputs(device, dtype) + for sample in samples: + tiny_results = op(sample.input, *sample.args, **sample.kwargs) + tiny_results = sample.output_process_fn_grad(tiny_results) + + cpu_sample = sample.transform(to_cpu) + cpu_results = op(cpu_sample.input, *cpu_sample.args, **cpu_sample.kwargs) + cpu_results = cpu_sample.output_process_fn_grad(cpu_results) + + self.assertEqual(tiny_results, cpu_results, atol=1e-3, rtol=1e-3) + + @ops(filter_funcs(unary_ufuncs), allowed_dtypes=[torch.float]) + def test_unary(self, device, dtype, op): self._test(device, dtype, op) + + @ops(filter_funcs(binary_ufuncs), allowed_dtypes=[torch.float]) + def test_binary(self, device, dtype, op): self._test(device, dtype, op) + + @ops(filter_funcs(reduction_ops), allowed_dtypes=[torch.float]) + def test_reduction(self, device, dtype, op): self._test(device, dtype, op) + + # none of these pass + #@ops(shape_funcs) + #def test_shape(self, device, dtype, op): self._test(device, dtype, op) + +instantiate_device_type_tests(TestTinyBackend, globals(), only_for=["tiny"]) + +if __name__ == "__main__": + unittest.main(verbosity=2) diff --git a/tinygrad_repo/extra/torch_backend/wrapped_tensor.cpp b/tinygrad_repo/extra/torch_backend/wrapped_tensor.cpp new file mode 100644 index 0000000000..0df27d02da --- /dev/null +++ b/tinygrad_repo/extra/torch_backend/wrapped_tensor.cpp @@ -0,0 +1,144 @@ +#include +#include +#include +#include +#include + +// register guard +namespace at { +namespace detail { +//C10_REGISTER_GUARD_IMPL(PrivateUse1, c10::impl::NoOpDeviceGuardImpl); +// NOTE: pytorch's no-op class throws error on backwards with events/streams +// TODO: why are there events in autograd? +struct CustomNoOpDeviceGuardImpl : public c10::impl::DeviceGuardImplInterface +{ + static const DeviceType D = DeviceType::PrivateUse1; + CustomNoOpDeviceGuardImpl() = default; + DeviceType type() const override { + return D; + } + Device exchangeDevice(Device) const override { + return Device(D, 0); // no-op + } + Device getDevice() const override { + return Device(D, 0); + } + void setDevice(Device) const override { + // no-op + } + void uncheckedSetDevice(Device) const noexcept override { + // no-op + } + Stream getStream(Device) const noexcept override { + // no-op + return Stream(Stream::DEFAULT, Device(D, 0)); + } + Stream getDefaultStream(Device) const override { + // no-op + return Stream(Stream::DEFAULT, Device(D, 0)); + } + Stream getStreamFromGlobalPool(Device, bool isHighPriority = false) + const override { + // no-op + (void)isHighPriority; + return Stream(Stream::DEFAULT, Device(D, 0)); + } + Stream getNewStream(Device, int priority = 0) const override { + // no-op + (void)priority; + return Stream(Stream::DEFAULT, Device(D, 0)); + } + // NB: These do NOT set the current device + Stream exchangeStream(Stream) const noexcept override { + // no-op + return Stream(Stream::DEFAULT, Device(D, 0)); + } + DeviceIndex deviceCount() const noexcept override { + return 1; + } + // Event-related functions + void record( + void** /*event*/, + const Stream& /*stream*/, + const DeviceIndex /*device_index*/, + const EventFlag /*flag*/) const override { + //TORCH_CHECK(false, D, " backend doesn't support events."); + } + void block(void* /*event*/, const Stream& /*stream*/) const override { + //TORCH_CHECK(false, D, " backend doesn't support events.") + } + bool queryEvent(void* /*event*/) const override { + //TORCH_CHECK(false, D, " backend doesn't support events.") + return true; + } + void destroyEvent(void* /*event*/, const DeviceIndex /*device_index*/) + const noexcept override {} + // Stream-related functions + bool queryStream(const Stream& /*stream*/) const override { + return true; + } + void synchronizeStream(const Stream& /*stream*/) const override { + // Don't wait for anything. + } +}; +C10_REGISTER_GUARD_IMPL(PrivateUse1, CustomNoOpDeviceGuardImpl); +} + +template +struct TinyOpaqueTensorImpl : public OpaqueTensorImpl { + TinyOpaqueTensorImpl( + at::DispatchKeySet key_set, + const caffe2::TypeMeta data_type, + c10::Device device, + OpaqueHandle opaque_handle, + c10::IntArrayRef sizes, + c10::IntArrayRef strides, + int64_t storage_offset) + : OpaqueTensorImpl(key_set, data_type, device, opaque_handle, sizes) { + this->sizes_and_strides_.set_strides(strides); + this->storage_offset_ = storage_offset; + } +}; +} + +struct OpenRegHooksInterface : public at::PrivateUse1HooksInterface { + // NOTE: no idea what this is + bool hasPrimaryContext(c10::DeviceIndex device_index) const override { return true; } +}; + +int register_hook() { + at::RegisterPrivateUse1HooksInterface(new OpenRegHooksInterface()); + return 0; +} +int temp_register_hook = register_hook(); + +at::Tensor wrap_tensor(py::object &py_obj, c10::ScalarType dtype, c10::DeviceIndex device_index) { + // TODO: we have to get the dtype and the shape from the tinygrad Tensor + std::vector sizes = py_obj.attr("shape").cast>(); + + py::list views = py_obj.attr("lazydata").attr("st").attr("views"); + std::vector strides = views[views.size() - 1].attr("strides").cast>(); + int64_t storage_offset = 0; + for (auto& v: views) { + storage_offset += v.attr("offset").cast(); // TODO: is this correct? + } + + return at::detail::make_tensor>>( + at::DispatchKeySet(at::DispatchKey::PrivateUse1), + c10::scalarTypeToTypeMeta(dtype), + at::Device(at::kPrivateUse1, device_index), + std::make_shared(py_obj.release().ptr(), getPyInterpreter()), + sizes, strides, storage_offset); +} + +py::object unwrap_tensor(const at::Tensor &tensor) { + auto* impl = tensor.unsafeGetTensorImpl(); + auto* opaque_impl = static_cast>*>(impl); + std::shared_ptr tiny = opaque_impl->opaque_handle(); + return py::reinterpret_borrow(tiny->ptr(getPyInterpreter())); +} + +PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { + m.def("wrap", &wrap_tensor); + m.def("unwrap", &unwrap_tensor); +} diff --git a/tinygrad_repo/extra/torch_hook/hook_cuda.py b/tinygrad_repo/extra/torch_hook/hook_cuda.py new file mode 100644 index 0000000000..2e5ad907a0 --- /dev/null +++ b/tinygrad_repo/extra/torch_hook/hook_cuda.py @@ -0,0 +1,214 @@ +import ctypes, struct, platform, pathlib, os, binascii, itertools +from hexdump import hexdump +from tinygrad.helpers import to_mv, DEBUG, getenv, colored, time_to_str +from tinygrad.runtime.autogen import libc, cuda +from tinygrad.device import CPUProgram, Device +from tinygrad.runtime.support.elf import elf_loader +from tinygrad.runtime.ops_cuda import cu_time_execution + +print(f"hooking CUDA runtime, running with {Device.DEFAULT}") + +# TODO: regen and make cuda 12 default? +cuda.cuFuncGetParamInfo = cuda._libraries['libcuda.so'].cuFuncGetParamInfo +cuda.cuFuncGetParamInfo.restype = cuda.CUresult +cuda.cuFuncGetParamInfo.argtypes = [cuda.CUfunction, cuda.size_t, ctypes.POINTER(ctypes.c_uint64), ctypes.POINTER(ctypes.c_uint64)] + +ignore_dispatch = [False] # default valus is False +def push_ignore_dispatch(val): + global ignore_dispatch + ignore_dispatch.append(val) + +def pop_ignore_dispatch(): + global ignore_dispatch + ignore_dispatch.pop() + +hooked = {} +def _hook(fxn_address_value, tramp): + page_address = (fxn_address_value//0x1000)*0x1000 + ret = libc.mprotect(page_address, 0x2000, 7) + assert ret == 0 + libc.memcpy(fxn_address_value, tramp, len(tramp)) + ret = libc.mprotect(page_address, 0x2000, 5) + assert ret == 0 + CPUProgram.rt_lib["__clear_cache"](fxn_address_value, fxn_address_value + len(tramp)) + +def install_hook(c_function, python_function): + python_function_addr = ctypes.cast(ctypes.byref(python_function), ctypes.POINTER(ctypes.c_ulong)).contents.value + # AARCH64 trampoline to ioctl + if (processor:=platform.processor()) == "aarch64": + # 0x0000000000000000: 70 00 00 10 adr x16, #0xc + # 0x0000000000000004: 10 02 40 F9 ldr x16, [x16] + # 0x0000000000000008: 00 02 1F D6 br x16 + tramp = b"\x70\x00\x00\x10\x10\x02\x40\xf9\x00\x02\x1f\xd6" + tramp += struct.pack("Q", python_function_addr) + elif processor == "x86_64": + # 0x0000000000000000: 49 BB aa aa aa aa aa aa aa aa movabs r11,
+ # 0x000000000000000a: 41 FF E3 jmp r11 + tramp = b"\x49\xBB" + struct.pack("Q", python_function_addr) + b"\x41\xFF\xE3" + else: + raise Exception(f"processor {processor} not supported") + tramp = ctypes.create_string_buffer(tramp) + + # get real function address + fxn_address = ctypes.cast(ctypes.byref(c_function), ctypes.POINTER(ctypes.c_ulong)) + fxn_address_value = fxn_address.contents.value + #print(f"** hooking function at 0x{fxn_address_value}") + + orig_save = (ctypes.c_char*len(tramp))() + libc.memcpy(orig_save, fxn_address_value, len(tramp)) + _hook(fxn_address_value, tramp) + + def original(*args): + _hook(fxn_address_value, orig_save) + ret = c_function(*args) + _hook(fxn_address_value, tramp) + return ret + return original + +allocated_memory_enum = 0 +allocated_memory = {} +function_names = {} +tiny_devs = {} + +seen_modules = set() + +global_events = [] +class HookEvent: pass +class HookMemAllocEvent(HookEvent): + def __init__(self, cuda_address, bytesize, enum): self.cuda_address, self.bytesize, self.enum = cuda_address, bytesize, enum + def __repr__(self): return f"tensor alloc: {self.enum}: {self.cuda_address:#x} - {self.bytesize:#x} bytes" +class HookConstParamEvent(HookEvent): + def __init__(self, value): self.value = value + def __repr__(self): return f"const({self.value:#x})" +class HookTensorParamEvent(HookEvent): + def __init__(self, cuda_address, offset, enum): self.cuda_address, self.offset, self.enum = cuda_address, offset, enum + def __repr__(self): return f"tensor{self.enum}({self.cuda_address:#x}, {self.offset=:#x})" +class HookKernelCallEvent(HookEvent): + def __init__(self, grid, block, tm, ptm, name, params): self.grid, self.block, self.tm, self.ptm, self.name, self.params = grid, block, tm, ptm, name, params + def __repr__(self): return f"kernel call <<{self.grid}>> <<{self.block}>> {self.ptm}\n | {self.params}\n | {self.name}" + +def collect_events(clear=False): + global global_events + x = global_events + if clear: global_events = [] + return x + +@ctypes.CFUNCTYPE(*([cuda.cuDeviceGet.restype] + cuda.cuDeviceGet.argtypes)) +def cuDeviceGet(device, ordinal): + tiny_devs[ordinal] = Device[f"{Device.DEFAULT}:{ordinal}"] + device.contents.value = ordinal + return cuda.CUDA_SUCCESS + +@ctypes.CFUNCTYPE(*([cuda.cuMemHostAlloc.restype] + cuda.cuMemHostAlloc.argtypes)) +def cuMemHostAlloc(pp, bytesize, flags): + print(f"cuMemHostAlloc {bytesize}") + return hooked["cuMemHostAlloc"](pp, bytesize, flags) + +@ctypes.CFUNCTYPE(*([cuda.cuModuleLoadData.restype] + cuda.cuModuleLoadData.argtypes)) +def cuModuleLoadData(module, image): + ret = hooked["cuModuleLoadData"](module, image) + module_address = ctypes.addressof(module.contents.contents) + seen_modules.add(module_address) + return ret + +@ctypes.CFUNCTYPE(*([cuda.cuModuleGetFunction.restype] + cuda.cuModuleGetFunction.argtypes)) +def cuModuleGetFunction(hfunc, hmod, name): + ret = hooked["cuModuleGetFunction"](hfunc, hmod, name) + python_name = ctypes.string_at(name).decode() + + # pip install git+https://github.com/wbenny/pydemangler.git + import pydemangler + demangled_name = pydemangler.demangle(python_name) + if demangled_name is not None: python_name = demangled_name + + # print(f"called cuModuleGetFunction 0x{ctypes.addressof(hmod.contents):X} {python_name}") + function_names[ctypes.addressof(hfunc.contents.contents)] = python_name + return ret + +@ctypes.CFUNCTYPE(*([cuda.cuMemAlloc_v2.restype] + cuda.cuMemAlloc_v2.argtypes)) +def cuMemAlloc_v2(dptr, bytesize): + global allocated_memory_enum, text_prefix + + ret = hooked["cuMemAlloc_v2"](dptr, bytesize) + cuda_address = dptr.contents.value + allocated_memory[cuda_address] = (bytesize, allocated_memory_enum) + + global_events.append(HookMemAllocEvent(cuda_address, bytesize, allocated_memory_enum)) + if DEBUG >= 3: print(global_events[-1]) + + allocated_memory_enum += 1 + return ret + +@ctypes.CFUNCTYPE(*([cuda.cuLaunchKernel.restype] + cuda.cuLaunchKernel.argtypes)) +def cuLaunchKernel(f, gridDimX, gridDimY, gridDimZ, blockDimX, blockDimY, blockDimZ, sharedMemBytes, hStream, kernelParams, extra): + global ignore_dispatch + + name = function_names[ctypes.addressof(f.contents)] + if ignore_dispatch[-1]: + if DEBUG >= 4: print(f"ignoring dispatch {name}") + return 0 + + tm = cu_time_execution(lambda: + hooked["cuLaunchKernel"](f, gridDimX, gridDimY, gridDimZ, blockDimX, blockDimY, blockDimZ, sharedMemBytes, hStream, kernelParams, extra), True) + + ptm = colored(time_to_str(tm, w=9), "yellow" if tm > 0.01 else "green") + + params = [] + while True: + ret = cuda.cuFuncGetParamInfo(f, len(params), ctypes.byref(paramOffset:=ctypes.c_size_t()), ctypes.byref(paramSize:=ctypes.c_size_t())) + if ret != 0: break + params.append((paramOffset.value, paramSize.value)) + + ev_params = [] + if extra: params_ptr = to_mv(extra, 5*8).cast("Q") + else: params_ptr = to_mv(kernelParams, len(params)*8).cast("Q") + + for i,(off,sz) in enumerate(params): + sz_to_let = {1: 'B', 2: 'H', 4: 'I', 8: 'Q'} + if sz >= 8: + for j in range(sz//8): + if extra: value = to_mv(params_ptr[1] + off, sz).cast("Q")[0] + else: value = to_mv(params_ptr[i] + j*8, 8).cast('Q')[0] + + has_in_allocated_mem, lcoff, alnum = False, 0, -1 + for taddr, (tsz, talnum) in allocated_memory.items(): + if taddr <= value < taddr + tsz: + has_in_allocated_mem = True + lcoff = value - taddr + alnum = talnum + break + + if has_in_allocated_mem: ev_params.append(HookTensorParamEvent(value, lcoff, alnum)) + else: ev_params.append(HookConstParamEvent(value)) + else: + if extra: value = to_mv(params_ptr[1] + off, sz).cast(sz_to_let[sz])[0] + else: value = to_mv(params_ptr[i], sz).cast(sz_to_let[sz])[0] + ev_params.append(HookConstParamEvent(value)) + + global_events.append(HookKernelCallEvent((gridDimX, gridDimY, gridDimZ), (blockDimX, blockDimY, blockDimZ), tm, ptm, name, ev_params)) + if DEBUG >= 3: print(global_events[-1]) + + return 0 + +def create_hook(func_name, restype, argtypes): + def hook_template(*args): + # print(func_name, flush=True) + return hooked[func_name](*args) + return ctypes.CFUNCTYPE(restype, *argtypes)(hook_template) + +def install_hooks(): + hooked['cuModuleGetFunction'] = install_hook(cuda.cuModuleGetFunction, cuModuleGetFunction) + hooked['cuLaunchKernel'] = install_hook(cuda.cuLaunchKernel, cuLaunchKernel) + + # memory stuff + hooked['cuMemAlloc_v2'] = install_hook(cuda.cuMemAlloc_v2, cuMemAlloc_v2) + hooked['cuMemHostAlloc'] = install_hook(cuda.cuMemHostAlloc, cuMemHostAlloc) + + # module loading + not used module loading + hooked['cuModuleLoadData'] = install_hook(cuda.cuModuleLoadData, cuModuleLoadData) + +NVPROFILER = os.environ.get("NV_COMPUTE_PROFILER_PERFWORKS_DIR", None) # realize and wait each aten call +if NVPROFILER is None: install_hooks() +else: + print("Detected NSIGHT Profiled, hooking not avail.") + cuda._libraries['libcuda.so'] = ctypes.CDLL(NVPROFILER + "/libcuda-injection.so") diff --git a/tinygrad_repo/extra/torch_hook/hook_torch.py b/tinygrad_repo/extra/torch_hook/hook_torch.py new file mode 100644 index 0000000000..f3b8113b4a --- /dev/null +++ b/tinygrad_repo/extra/torch_hook/hook_torch.py @@ -0,0 +1,150 @@ +import ctypes, struct, platform, pathlib, os, binascii, itertools +from hexdump import hexdump +from tinygrad.device import Device +from tinygrad import Tensor +from tinygrad.dtype import _from_torch_dtype +from tinygrad.helpers import to_mv, DEBUG, getenv, colored, time_to_str + +import extra.torch_hook.hook_cuda as hook_cuda + +# settings to profile gemm in the __main__ example: TINY_MIRROR=1;CUDA=1;RUN_ONLY=9 +# nvprof sample command (this will sample all kernels): +# ncu --export ~/nvprof_data --force-overwrite --rule AchievedOccupancy --rule Compute --rule LaunchConfiguration --rule Memory --rule PMSamplingData --rule SOLBottleneck --rule TheoreticalOccupancy --rule WorkloadImbalance python3 extra/torch_hook/hook_torch.py +# or just run nsight compute from the host to the machine. + +TINY_MIRROR = getenv("TINY_MIRROR", 1) # should mirror aten ops to tiny backend +RUN_ONLY = getenv("RUN_ONLY", -1) # run only a specific aten call +REALIZE = getenv("REALIZE", 1) # realize and wait each aten call +WRAP_TINY = getenv("WRAP_TINY", TINY_MIRROR) # reuse cuda tensors +FULL_KERN_NAME = getenv("FULL_KERN_NAME", 0) # print full kernel name + +print("importing torch...") +import torch +print("importing torch done:", torch.__version__, torch.__file__) + +if TINY_MIRROR: + print("importing tiny torch") + import extra.torch_backend.backend as tiny_torch + print("importing tiny torch done") + +torch.set_default_device("cuda") + +cuda_to_tiny_mappings = {} + +enumerator_aten_calls = itertools.count(0) +from torch.utils._python_dispatch import TorchDispatchMode +class DispatchLog(TorchDispatchMode): + def __torch_dispatch__(self, func, types, args, kwargs=None): + txt_args = [] + should_call_tiny = kwargs.get('device') is not None and kwargs['device'].type == "cuda" + + def can_print_arg(arg): + return args is None or isinstance(arg, (str, int, float, bool)) + + def create_tiny_mapping(arg): + if WRAP_TINY: + tt = Tensor.from_blob(arg.data_ptr(), arg.shape, dtype=_from_torch_dtype(arg.dtype)) + cuda_to_tiny_mappings[arg] = tiny_torch.wrap(tt) + + for i,arg in enumerate(args): + if torch.is_tensor(arg): + if arg.device.type == "cuda": + should_call_tiny = True + if WRAP_TINY: create_tiny_mapping(arg) + txt_args.append(f"tensor({arg.shape} {arg.device} {arg.dtype})") + elif can_print_arg(arg): txt_args.append(f'{arg}') + else: txt_args.append(f"{type(arg)}") + for k,v in (kwargs or {}).items(): + if torch.is_tensor(v): + if arg.device.type == "cuda": + should_call_tiny = True + if WRAP_TINY: create_tiny_mapping(arg) + txt_args.append(f"{k}:tensor({v.shape} {v.device} {v.dtype})") + elif can_print_arg(arg): txt_args.append(f'{k}:{arg}"') + else: txt_args.append(f"{type(arg)}") + + # magenta-colored kerenls mirrored to tiny backend. + aten_id = next(enumerator_aten_calls) + should_call_tiny = TINY_MIRROR and should_call_tiny + print(colored(f"#{aten_id} {func}", "magenta" if should_call_tiny else "cyan") + "("+", ".join(txt_args)+")", flush=True) + + # ignore dispatches if needed + hook_cuda.push_ignore_dispatch(RUN_ONLY >= 0 and RUN_ONLY != aten_id) + orig_x = func(*args, **(kwargs or {})) + + def print_events(evs, name, out_addr): + for ev in evs: + if isinstance(ev, hook_cuda.HookKernelCallEvent): + txt_params = [] + for param in ev.params: + if isinstance(param, hook_cuda.HookTensorParamEvent): + is_out = param.cuda_address == out_addr + txt_params += [f"{'result ' if is_out else ''}Tensor{param.enum}({param.cuda_address:#x})"] + + just_kern_name = ev.name + if not FULL_KERN_NAME: + just_kern_name = ev.name.replace("(anonymous namespace)", "").replace("void ", "").split("<")[0].split("(")[0].split("::")[-1] + print(f"\t {name} kernel {just_kern_name} {ev.grid} {ev.block} {ev.ptm}\n\t\t({', '.join(txt_params)})") + else: print("\t", name, ev) + + if REALIZE: + torch.cuda.synchronize() + cuda_events = hook_cuda.collect_events(clear=True) + print_events(cuda_events, colored("cuda", "cyan"), orig_x.data_ptr() if torch.is_tensor(orig_x) else 0x0) + + if should_call_tiny: + # replace with tiny tensor + tiny_args, tiny_kwargs = [], {} + for arg in args: + if torch.is_tensor(arg): tiny_args.append(cuda_to_tiny_mappings[arg]) + else: tiny_args.append(arg) + + for k,v in (kwargs or {}).items(): + if torch.is_tensor(v): tiny_kwargs[k] = cuda_to_tiny_mappings[v] + else: tiny_kwargs[k] = v + if 'device' in tiny_kwargs and kwargs['device'].type == "cuda": + tiny_kwargs['device'] = torch.device("tiny") + + tiny_x = func(*tiny_args, **tiny_kwargs) + + # TODO: this is a hack, any way to do this better? + if REALIZE: + out_addr = 0x0 + _ = tiny_x.cpu().numpy() + if torch.is_tensor(tiny_x) and tiny_x.device.type == "tiny": + tt = tiny_torch.unwrap(tiny_x) + try: out_addr = tt.lazydata.buffer._buf.value + except Exception: pass + tiny_events = hook_cuda.collect_events(clear=True) + print_events(tiny_events, colored("tiny", "magenta"), out_addr) + + if not WRAP_TINY: cuda_to_tiny_mappings[orig_x] = tiny_x + + hook_cuda.pop_ignore_dispatch() + return orig_x +DispatchLog().__enter__() + +if __name__ == "__main__": + if getenv("RESNET"): + import torchvision.models as models + model = models.resnet18(pretrained=True) + model = model.cuda() + model.eval() + + if getenv("COMPILE"): model = torch.compile(model) + + X = torch.rand(getenv("BS", 1), 3, 288, 288, device='cuda') + model(X) + + print("\n\n\n****** second run ******\n") + model(X) + else: + a = torch.randn(64, 64) + b = torch.randn(64, 64) + a += 1 + b += 2 + a = a.exp2() + b = b.exp2() + a += b + c = a @ b + print("tensor math done", c.cpu().numpy()) diff --git a/tinygrad_repo/extra/usbgpu/.gitignore b/tinygrad_repo/extra/usbgpu/.gitignore new file mode 100644 index 0000000000..b18935f35c --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/.gitignore @@ -0,0 +1,2 @@ +Software/ +fw.zip \ No newline at end of file diff --git a/tinygrad_repo/extra/usbgpu/legacy/nvme_speed.py b/tinygrad_repo/extra/usbgpu/legacy/nvme_speed.py new file mode 100644 index 0000000000..88a9b5250f --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/legacy/nvme_speed.py @@ -0,0 +1,23 @@ +import array, time, ctypes, struct, random +from hexdump import hexdump +from tinygrad.runtime.support.usb import ASM24Controller, WriteOp, ScsiWriteOp +from tinygrad.runtime.autogen import pci +from tinygrad.helpers import Timing +from tinygrad import Device + +usb = ASM24Controller() + +def real_scsi_write(): + self.exec_ops([ScsiWriteOp(buf, lba)]) + +for i in range(256): + xxx = (ctypes.c_uint8 * 4096)() + dfg = random.randint(0, 255) + for i in range(len(xxx)): xxx[i] = dfg + # print(dfg, usb.read(0xf000, 0x10)) + st = time.perf_counter_ns() + usb.scsi_write(bytes(xxx), lba=0x1000 + i) + en = time.perf_counter_ns() + print("mb/s is ", (0x1000) / (en - st) * 1e9 / 1024 / 1024) + +exit(0) diff --git a/tinygrad_repo/extra/usbgpu/legacy/patch_exp.py b/tinygrad_repo/extra/usbgpu/legacy/patch_exp.py new file mode 100755 index 0000000000..9b39037acc --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/legacy/patch_exp.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python3 +import sys +import zlib + +def patch(input_filepath, output_filepath, patches): + with open(input_filepath, 'rb') as infile: data = bytearray(infile.read()) + + for offset, expected_bytes, new_bytes in patches: + if len(expected_bytes) != len(new_bytes): + print(len(expected_bytes), len(new_bytes)) + raise ValueError("Expected bytes and new bytes must be the same length") + + if offset + len(new_bytes) > len(data): return False + current_bytes = data[offset:offset + len(expected_bytes)] + assert bytes(current_bytes) == expected_bytes, f"Expected {expected_bytes} at offset {offset:x}, but got {current_bytes}" + data[offset:offset + len(new_bytes)] = new_bytes + + checksum = sum(data[4:-6]) & 0xff + crc32 = zlib.crc32(data[4:-6]).to_bytes(4, 'little') + data[-5] = checksum + data[-4] = crc32[0] + data[-3] = crc32[1] + data[-2] = crc32[2] + data[-1] = crc32[3] + + with open(output_filepath, 'wb') as outfile: + outfile.write(data) + + return True + +patches = [ + # (0x3903 + 1 + 4, b'\x8a', b'\x8b'), + # (0x3cf9 + 1 + 4, b'\x8a', b'\x8b'), # this is the one which triggered... + + (0x2a0d + 1 + 4, b'\x0a', b'\x05'), # write handle exit with code 5 (?) + # (0x40e1 + 4, b'\x90\x06\xe6\x04\xf0\x78\x0d\xe6\xfe\x24\x71\x12\x1b\x0b\x60\x0b\x74\x08', b'\x7f\x00\x12\x53\x21\x12\x1c\xfc\x74\x01\xf6\x90\x90\x94\x74\x10\xf0\x22') + # (0x29ad + 1 + 4, b'\x09', b'\x05'), # write handle exit with code 5 (?) + # (0x40ef + 0 + 4, b'\x60', b'\x70'), # jz -> jnz + # (0x40e1 + 0 + 4, b'\x90', b'\x22'), # jmp -> ret + # (0x40fa + 0 + 4, b'\x80', b'\x22'), + # (0x40e1 + 0 + 4, b'\x90\x06\xe6\x04\xf0', b'\x7f\x00\x02\x41\x7c'), # jmp -> ret +] + +next_traphandler = 0 +def add_traphandler(addr, sec): + global next_traphandler, patches + + trap_addr = 0x6000 + next_traphandler * 0x20 + return_addr = addr + len(sec) + cntr_addr = 0x3000 + next_traphandler + patches += [ + (addr + 4, sec, b'\x02' + trap_addr.to_bytes(2, 'big') + b'\x22'*(len(sec)-3)), + (trap_addr + 4, b'\x00' * (21 + len(sec)), + b'\xc0\xe0\xc0\x82\xc0\x83\x90' + cntr_addr.to_bytes(2, 'big') + b'\xe0\x04\xf0\xd0\x83\xd0\x82\xd0\xe0' + sec + b'\x02' + return_addr.to_bytes(2, 'big')), + ] + next_traphandler += 1 + +# add_traphandler(0x0206, b'\xed\x54\x06') # fill_scsi_resp +# add_traphandler(0x40d9, b'\x78\x6a\xe6') # fill_scsi_to_usb_transport +# add_traphandler(0x4d44, b'\x78\x6a\xe6') # FUN_CODE_4d44 +# add_traphandler(0x4784, b'\x78\x6a\xe6') # FUN_CODE_4784 +# add_traphandler(0x3e81, b'\x90\xc5\x16') # FUN_CODE_3e81 +# add_traphandler(0x32a5, b'\x78\x6a\xe6') # FUN_CODE_32a5 +# add_traphandler(0x2a10, b'\x90\xc4\x51') # FUN_CODE_2a10 +# add_traphandler(0x2608, b'\x12\x16\x87') # FUN_CODE_2608 +# add_traphandler(0x0e78, b'\x90\xc8\x02') # main usb entry +# add_traphandler(0x102f, b'\x12\x18\x0d') # possible scsi entry parser +# add_traphandler(0x1198, b'\x12\x18\x0d') # close_to_scsi_parse_1_and_set_c47a_to_0xff caller to scsi +# add_traphandler(0x180d, b'\x90\x0a\x7d') # close_to_scsi_parse +# add_traphandler(0x1114, b'\x75\x37\x00') # entry into if ((DAT_EXTMEM_c802 >> 2 & 1) != 0) { in main usb entry +# add_traphandler(0x113a, b'\x90\x90\x00') # exit from scsi parse loop +# add_traphandler(0x117b, b'\xd0\x07\xd0\x06') # exit from main usb entry + + +# add_traphandler(0x2f81, b'\x90\x0a\x59') # main loop? 8 +# add_traphandler(0xc7a7, b'\x90\x09\xfa') # call smth in write path 9 +# add_traphandler(0x2fcb, b'\x90\x0a\x59') # if ((DAT_EXTMEM_0ae2 != 0) && (DAT_EXTMEM_0ae2 != 0x10)) { +# add_traphandler(0x2fc0, b'\x90\x0a\xe2') # submain loop 11 +# add_traphandler(0x30be, b'\x90\x0a\x5a') # aft sub loop 12 +# add_traphandler(0x3076, b'\x12\x03\x59') # call to call_wait_for_nvme??(); 13 +# add_traphandler(0x30ad, b'\x12\x04\xe4') # call to call_wait_for_nvme??(); 14 + +# add_traphandler(0x2608, b'\x12\x16\x87') # FUN_CODE_2608 +# add_traphandler(0x10ee, b'\x90\x04\x64') # iniside trap handler +# add_traphandler(0x10e0, b'\x90\xc8\x06') # iniside trap handler +# add_traphandler(0x4977, b'\x90\x0a\xa8') # waiter for nvme??? + +assert patch(sys.argv[1], sys.argv[2], patches) is True diff --git a/tinygrad_repo/extra/usbgpu/legacy/wr_speed.py b/tinygrad_repo/extra/usbgpu/legacy/wr_speed.py new file mode 100644 index 0000000000..e157022d97 --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/legacy/wr_speed.py @@ -0,0 +1,22 @@ +import array, time, ctypes, struct, random +from hexdump import hexdump +from tinygrad.runtime.support.usb import ASMController, WriteOp +from tinygrad.runtime.autogen import pci +from tinygrad.helpers import Timing +from tinygrad import Device + +usb = ASMController() + +xxx = (ctypes.c_uint8 * 4096)() +dfg = random.randint(0, 255) +for i in range(len(xxx)): xxx[i] = dfg + +print(dfg, usb.read(0xf000, 0x10)) + +with Timing(): + for i in range(64): usb.scsi_write(xxx) + +with Timing(): + for i in range(64): usb.read(0xf000, 0x1000) + +exit(0) diff --git a/tinygrad_repo/extra/usbgpu/patch.py b/tinygrad_repo/extra/usbgpu/patch.py new file mode 100755 index 0000000000..e9e62682d8 --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/patch.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python3 +import sys, os, zlib, struct, hashlib +from hexdump import hexdump +from tinygrad.helpers import DEBUG, getenv, fetch +from tinygrad.runtime.support.usb import USB3 + +def patch(input_filepath, file_hash, patches): + with open(input_filepath, 'rb') as infile: data = bytearray(infile.read()) + + if_hash = hashlib.md5(data).hexdigest() + if if_hash != file_hash: + raise ValueError(f"File hash mismatch: expected {file_hash}, got {if_hash}") + + for offset, expected_bytes, new_bytes in patches: + if len(expected_bytes) != len(new_bytes): + raise ValueError("Expected bytes and new bytes must be the same length") + + if offset + len(new_bytes) > len(data): return False + current_bytes = data[offset:offset + len(expected_bytes)] + assert bytes(current_bytes) == expected_bytes, f"Expected {expected_bytes} at offset {offset:x}, but got {current_bytes}" + data[offset:offset + len(new_bytes)] = new_bytes + + checksum = sum(data[4:-6]) & 0xff + crc32 = zlib.crc32(data[4:-6]).to_bytes(4, 'little') + data[-5] = checksum + data[-4] = crc32[0] + data[-3] = crc32[1] + data[-2] = crc32[2] + data[-1] = crc32[3] + return data + +path = os.path.dirname(os.path.abspath(__file__)) +file_hash = "5284e618d96ef804c06f47f3b73656b7" +file_path = os.path.join(path, "Software/AS_USB4_240417_85_00_00.bin") + +if not os.path.exists(file_path): + url = "https://web.archive.org/web/20250430124720/https://www.station-drivers.com/index.php/en/component/remository/func-download/6341/chk,3ef8b04704a18eb2fc57ff60382379ad/no_html,1/lang,en-gb/" + os.system(f'curl -o "{path}/fw.zip" "{url}"') + os.system(f'unzip -o "{path}/fw.zip" "Software/AS_USB4_240417_85_00_00.bin" -d "{path}"') + +patches = [(0x2a0d + 1 + 4, b'\x0a', b'\x05')] +patched_fw = patch(file_path, file_hash, patches) + +vendor, device = [int(x, base=16) for x in getenv("USBDEV", "174C:2464").split(":")] +try: dev = USB3(vendor, device, 0x81, 0x83, 0x02, 0x04) +except RuntimeError as e: + raise RuntimeError(f'{e}. You can set USBDEV environment variable to your device\'s vendor and device ID (e.g., USBDEV="174C:2464")') from e + +config1 = bytes([ + 0xFF, 0xFF, 0xFF, 0xFF, 0x41, 0x41, 0x41, 0x41, 0x42, 0x42, 0x42, 0x42, 0x30, 0x30, 0x36, 0x30, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0x69, 0x6E, 0x79, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0x69, 0x6E, 0x79, + 0xFF, 0xFF, 0xFF, 0xFF, 0x55, 0x53, 0x42, 0x20, 0x33, 0x2E, 0x32, 0x20, 0x50, 0x43, 0x49, 0x65, + 0x20, 0x54, 0x69, 0x6E, 0x79, 0x45, 0x6E, 0x63, 0x6C, 0x6F, 0x73, 0x75, 0x72, 0x65, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x54, 0x69, 0x6E, 0x79, 0x45, 0x6E, 0x63, 0x6C, 0x6F, 0x73, 0x75, 0x72, + 0x65, 0xFF, 0xFF, 0xFF, 0xD1, 0xAD, 0x01, 0x00, 0x00, 0x01, 0xCF, 0xFF, 0x02, 0xFF, 0x5A, 0x94]) + +config2 = bytes([ + 0xFF, 0xFF, 0xFF, 0xFF, 0x47, 0x6F, 0x70, 0x6F, 0x64, 0x20, 0x47, 0x72, 0x6F, 0x75, 0x70, 0x20, + 0x4C, 0x69, 0x6D, 0x69, 0x74, 0x65, 0x64, 0x2E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x55, 0x53, 0x42, 0x34, + 0x20, 0x4E, 0x56, 0x4D, 0x65, 0x20, 0x53, 0x53, 0x44, 0x20, 0x50, 0x72, 0x6F, 0x20, 0x45, 0x6E, + 0x63, 0x6C, 0x6F, 0x73, 0x75, 0x72, 0x65, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x8C, 0xBF, 0xFF, 0x97, 0xC1, 0xF3, 0xFF, 0xFF, 0x01, 0x2D, 0x66, 0xD6, + 0x66, 0x06, 0x00, 0xC0, 0x87, 0x01, 0x5A, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xCA, 0x01, 0x66, 0xD6, + 0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x01, 0x00, 0xA5, 0x67]) + +part1 = patched_fw[:0xff00] +part2 = patched_fw[0xff00:] + +# config patch +cdb = struct.pack('>BBB12x', 0xe1, 0x50, 0x0) +dev.send_batch(cdbs=[cdb], odata=[config1]) + +cdb = struct.pack('>BBB12x', 0xe1, 0x50, 0x1) +dev.send_batch(cdbs=[cdb], odata=[config2]) + +cdb = struct.pack('>BBI', 0xe3, 0x50, len(part1)) +dev.send_batch(cdbs=[cdb], odata=[part1]) + +cdb = struct.pack('>BBI', 0xe3, 0xd0, len(part2)) +dev.send_batch(cdbs=[cdb], odata=[part2]) + +cdb = struct.pack('>BB13x', 0xe8, 0x51) +dev.send_batch(cdbs=[cdb]) + +print("done, you can disconnect the controller!") diff --git a/tinygrad_repo/extra/usbgpu/scan_pci.py b/tinygrad_repo/extra/usbgpu/scan_pci.py new file mode 100644 index 0000000000..4eb60c40fa --- /dev/null +++ b/tinygrad_repo/extra/usbgpu/scan_pci.py @@ -0,0 +1,67 @@ +import array, time +from hexdump import hexdump +from tinygrad.runtime.support.usb import ASM24Controller +from tinygrad.runtime.autogen import pci + +usb = ASM24Controller() + +def print_cfg(bus, dev): + cfg = [] + for i in range(0, 256, 4): + cfg.append(usb.pcie_cfg_req(i, bus=bus, dev=dev, fn=0, value=None, size=4)) + + print("bus={}, dev={}".format(bus, dev)) + dmp = bytearray(array.array('I', cfg)) + hexdump(dmp) + return dmp + +def rescan_bus(bus, gpu_bus): + print("set PCI_SUBORDINATE_BUS bus={} to {}".format(bus, gpu_bus)) + usb.pcie_cfg_req(pci.PCI_SUBORDINATE_BUS, bus=bus, dev=0, fn=0, value=gpu_bus, size=1) + usb.pcie_cfg_req(pci.PCI_SECONDARY_BUS, bus=bus, dev=0, fn=0, value=bus+1, size=1) + usb.pcie_cfg_req(pci.PCI_PRIMARY_BUS, bus=bus, dev=0, fn=0, value=max(0, bus-1), size=1) + + print("rescan bus={}".format(bus)) + usb.pcie_cfg_req(pci.PCI_BRIDGE_CONTROL, bus=bus, dev=0, fn=0, value=pci.PCI_BRIDGE_CTL_BUS_RESET, size=1) + time.sleep(0.1) + usb.pcie_cfg_req(pci.PCI_BRIDGE_CONTROL, bus=bus, dev=0, fn=0, value=pci.PCI_BRIDGE_CTL_PARITY|pci.PCI_BRIDGE_CTL_SERR, size=1) + + usb.pcie_cfg_req(pci.PCI_MEMORY_BASE, bus=bus, dev=0, fn=0, value=0x1000, size=2) + usb.pcie_cfg_req(pci.PCI_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0x2000, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_BASE, bus=bus, dev=0, fn=0, value=0x2000, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0xffff, size=2) + +print_cfg(0, 0) +rescan_bus(0, gpu_bus=4) + +print_cfg(1, 0) +rescan_bus(1, gpu_bus=4) + +time.sleep(0.1) +print_cfg(2, 0) + +def setup_bus(bus, gpu_bus): + print("setup bus={}".format(bus)) + usb.pcie_cfg_req(pci.PCI_SUBORDINATE_BUS, bus=bus, dev=0, fn=0, value=gpu_bus, size=1) + usb.pcie_cfg_req(pci.PCI_SECONDARY_BUS, bus=bus, dev=0, fn=0, value=bus+1, size=1) + usb.pcie_cfg_req(pci.PCI_PRIMARY_BUS, bus=bus, dev=0, fn=0, value=max(0, bus-1), size=1) + + usb.pcie_cfg_req(pci.PCI_BRIDGE_CONTROL, bus=bus, dev=0, fn=0, value=pci.PCI_BRIDGE_CTL_BUS_RESET, size=1) + usb.pcie_cfg_req(pci.PCI_BRIDGE_CONTROL, bus=bus, dev=0, fn=0, value=pci.PCI_BRIDGE_CTL_PARITY|pci.PCI_BRIDGE_CTL_SERR, size=1) + usb.pcie_cfg_req(pci.PCI_COMMAND, bus=bus, dev=0, fn=0, value=pci.PCI_COMMAND_IO | pci.PCI_COMMAND_MEMORY | pci.PCI_COMMAND_MASTER, size=1) + + usb.pcie_cfg_req(pci.PCI_MEMORY_BASE, bus=bus, dev=0, fn=0, value=0x1000, size=2) + usb.pcie_cfg_req(pci.PCI_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0x2000, size=2) + + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_BASE, bus=bus, dev=0, fn=0, value=0x2000, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0xffff, size=2) + +setup_bus(2, gpu_bus=4) +print_cfg(3, 0) + +setup_bus(3, gpu_bus=4) +dmp = print_cfg(4, 0) +print(dmp[0:4]) +assert dmp[0:4] in (b"\x02\x10\x80\x74", b"\x02\x10\x4c\x74", b"\x02\x10\x50\x75"), "GPU NOT FOUND!" + +print("GPU FOUND!") diff --git a/tinygrad_repo/extra/viz_sz.py b/tinygrad_repo/extra/viz_sz.py new file mode 100644 index 0000000000..e02e73ba40 --- /dev/null +++ b/tinygrad_repo/extra/viz_sz.py @@ -0,0 +1,9 @@ +files = ["./tinygrad/viz/js/index.js", "./tinygrad/viz/js/worker.js"] +for fp in files: + with open(fp) as f: content = f.read() + cnt = 0 + for i,line in enumerate(content.splitlines()): + if not (line:=line.strip()) or line.startswith("//"): continue + #print(f"{i} {line}") + cnt += 1 + print(f"{fp.split('/')[-1]} - {cnt} lines") diff --git a/tinygrad_repo/extra/webgpu/webgpu.h b/tinygrad_repo/extra/webgpu/webgpu.h new file mode 100644 index 0000000000..0614d45d31 --- /dev/null +++ b/tinygrad_repo/extra/webgpu/webgpu.h @@ -0,0 +1,4265 @@ +// BSD 3-Clause License +// +// Copyright (c) 2019, "WebGPU native" developers +// All rights reserved. +// +// 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 the copyright holder 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. + +#ifdef __EMSCRIPTEN__ +#error "Do not include this header. Emscripten already provides headers needed for WebGPU." +#endif + +#ifndef WEBGPU_H_ +#define WEBGPU_H_ + +#define WGPU_BREAKING_CHANGE_STRING_VIEW_LABELS +#define WGPU_BREAKING_CHANGE_STRING_VIEW_OUTPUT_STRUCTS +#define WGPU_BREAKING_CHANGE_STRING_VIEW_CALLBACKS + +#if defined(WGPU_SHARED_LIBRARY) +# if defined(_WIN32) +# if defined(WGPU_IMPLEMENTATION) +# define WGPU_EXPORT __declspec(dllexport) +# else +# define WGPU_EXPORT __declspec(dllimport) +# endif +# else // defined(_WIN32) +# if defined(WGPU_IMPLEMENTATION) +# define WGPU_EXPORT __attribute__((visibility("default"))) +# else +# define WGPU_EXPORT +# endif +# endif // defined(_WIN32) +#else // defined(WGPU_SHARED_LIBRARY) +# define WGPU_EXPORT +#endif // defined(WGPU_SHARED_LIBRARY) + +#if !defined(WGPU_OBJECT_ATTRIBUTE) +#define WGPU_OBJECT_ATTRIBUTE +#endif +#if !defined(WGPU_ENUM_ATTRIBUTE) +#define WGPU_ENUM_ATTRIBUTE +#endif +#if !defined(WGPU_STRUCTURE_ATTRIBUTE) +#define WGPU_STRUCTURE_ATTRIBUTE +#endif +#if !defined(WGPU_FUNCTION_ATTRIBUTE) +#define WGPU_FUNCTION_ATTRIBUTE +#endif +#if !defined(WGPU_NULLABLE) +#define WGPU_NULLABLE +#endif + +#define WGPU_BREAKING_CHANGE_DROP_DESCRIPTOR + +#include +#include + +#if defined(__cplusplus) +# if __cplusplus >= 201103L +# define WGPU_MAKE_INIT_STRUCT(type, value) (type value) +# else +# define WGPU_MAKE_INIT_STRUCT(type, value) value +# endif +#elif defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L +# define WGPU_MAKE_INIT_STRUCT(type, value) ((type) value) +#else +# define WGPU_MAKE_INIT_STRUCT(type, value) value +#endif + +#define WGPU_ARRAY_LAYER_COUNT_UNDEFINED UINT32_MAX +#define WGPU_COPY_STRIDE_UNDEFINED UINT32_MAX +#define WGPU_DEPTH_SLICE_UNDEFINED UINT32_MAX +#define WGPU_LIMIT_U32_UNDEFINED UINT32_MAX +#define WGPU_LIMIT_U64_UNDEFINED UINT64_MAX +#define WGPU_MIP_LEVEL_COUNT_UNDEFINED UINT32_MAX +#define WGPU_QUERY_SET_INDEX_UNDEFINED UINT32_MAX +#define WGPU_STRLEN SIZE_MAX +#define WGPU_WHOLE_MAP_SIZE SIZE_MAX +#define WGPU_WHOLE_SIZE UINT64_MAX + +typedef uint64_t WGPUFlags; +typedef uint32_t WGPUBool; + +typedef struct WGPUAdapterImpl* WGPUAdapter WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUBindGroupImpl* WGPUBindGroup WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUBindGroupLayoutImpl* WGPUBindGroupLayout WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUBufferImpl* WGPUBuffer WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUCommandBufferImpl* WGPUCommandBuffer WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUCommandEncoderImpl* WGPUCommandEncoder WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUComputePassEncoderImpl* WGPUComputePassEncoder WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUComputePipelineImpl* WGPUComputePipeline WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUDeviceImpl* WGPUDevice WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUExternalTextureImpl* WGPUExternalTexture WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUInstanceImpl* WGPUInstance WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUPipelineLayoutImpl* WGPUPipelineLayout WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUQuerySetImpl* WGPUQuerySet WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUQueueImpl* WGPUQueue WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPURenderBundleImpl* WGPURenderBundle WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPURenderBundleEncoderImpl* WGPURenderBundleEncoder WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPURenderPassEncoderImpl* WGPURenderPassEncoder WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPURenderPipelineImpl* WGPURenderPipeline WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUSamplerImpl* WGPUSampler WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUShaderModuleImpl* WGPUShaderModule WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUSharedBufferMemoryImpl* WGPUSharedBufferMemory WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUSharedFenceImpl* WGPUSharedFence WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUSharedTextureMemoryImpl* WGPUSharedTextureMemory WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUSurfaceImpl* WGPUSurface WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUTextureImpl* WGPUTexture WGPU_OBJECT_ATTRIBUTE; +typedef struct WGPUTextureViewImpl* WGPUTextureView WGPU_OBJECT_ATTRIBUTE; + +// Structure forward declarations +struct WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER; +struct WGPUAdapterPropertiesD3D; +struct WGPUAdapterPropertiesSubgroups; +struct WGPUAdapterPropertiesVk; +struct WGPUBindGroupEntry; +struct WGPUBlendComponent; +struct WGPUBufferBindingLayout; +struct WGPUBufferHostMappedPointer; +struct WGPUBufferMapCallbackInfo; +struct WGPUColor; +struct WGPUColorTargetStateExpandResolveTextureDawn; +struct WGPUCompilationInfoCallbackInfo; +struct WGPUComputePassTimestampWrites; +struct WGPUCopyTextureForBrowserOptions; +struct WGPUCreateComputePipelineAsyncCallbackInfo; +struct WGPUCreateRenderPipelineAsyncCallbackInfo; +struct WGPUDawnWGSLBlocklist; +struct WGPUDawnAdapterPropertiesPowerPreference; +struct WGPUDawnBufferDescriptorErrorInfoFromWireClient; +struct WGPUDawnEncoderInternalUsageDescriptor; +struct WGPUDawnExperimentalImmediateDataLimits; +struct WGPUDawnExperimentalSubgroupLimits; +struct WGPUDawnRenderPassColorAttachmentRenderToSingleSampled; +struct WGPUDawnShaderModuleSPIRVOptionsDescriptor; +struct WGPUDawnTexelCopyBufferRowAlignmentLimits; +struct WGPUDawnTextureInternalUsageDescriptor; +struct WGPUDawnTogglesDescriptor; +struct WGPUDawnWireWGSLControl; +struct WGPUDeviceLostCallbackInfo; +struct WGPUDrmFormatProperties; +struct WGPUExtent2D; +struct WGPUExtent3D; +struct WGPUExternalTextureBindingEntry; +struct WGPUExternalTextureBindingLayout; +struct WGPUFormatCapabilities; +struct WGPUFuture; +struct WGPUInstanceFeatures; +struct WGPULimits; +struct WGPUMemoryHeapInfo; +struct WGPUMultisampleState; +struct WGPUOrigin2D; +struct WGPUOrigin3D; +struct WGPUPipelineLayoutStorageAttachment; +struct WGPUPopErrorScopeCallbackInfo; +struct WGPUPrimitiveState; +struct WGPUQueueWorkDoneCallbackInfo; +struct WGPURenderPassDepthStencilAttachment; +struct WGPURenderPassDescriptorExpandResolveRect; +struct WGPURenderPassMaxDrawCount; +struct WGPURenderPassTimestampWrites; +struct WGPURequestAdapterCallbackInfo; +struct WGPURequestAdapterOptions; +struct WGPURequestDeviceCallbackInfo; +struct WGPUSamplerBindingLayout; +struct WGPUShaderModuleCompilationOptions; +struct WGPUShaderSourceSPIRV; +struct WGPUSharedBufferMemoryBeginAccessDescriptor; +struct WGPUSharedBufferMemoryEndAccessState; +struct WGPUSharedBufferMemoryProperties; +struct WGPUSharedFenceDXGISharedHandleDescriptor; +struct WGPUSharedFenceDXGISharedHandleExportInfo; +struct WGPUSharedFenceMTLSharedEventDescriptor; +struct WGPUSharedFenceMTLSharedEventExportInfo; +struct WGPUSharedFenceExportInfo; +struct WGPUSharedFenceSyncFDDescriptor; +struct WGPUSharedFenceSyncFDExportInfo; +struct WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor; +struct WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo; +struct WGPUSharedFenceVkSemaphoreZirconHandleDescriptor; +struct WGPUSharedFenceVkSemaphoreZirconHandleExportInfo; +struct WGPUSharedTextureMemoryD3DSwapchainBeginState; +struct WGPUSharedTextureMemoryDXGISharedHandleDescriptor; +struct WGPUSharedTextureMemoryEGLImageDescriptor; +struct WGPUSharedTextureMemoryIOSurfaceDescriptor; +struct WGPUSharedTextureMemoryAHardwareBufferDescriptor; +struct WGPUSharedTextureMemoryBeginAccessDescriptor; +struct WGPUSharedTextureMemoryDmaBufPlane; +struct WGPUSharedTextureMemoryEndAccessState; +struct WGPUSharedTextureMemoryOpaqueFDDescriptor; +struct WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor; +struct WGPUSharedTextureMemoryVkImageLayoutBeginState; +struct WGPUSharedTextureMemoryVkImageLayoutEndState; +struct WGPUSharedTextureMemoryZirconHandleDescriptor; +struct WGPUStaticSamplerBindingLayout; +struct WGPUStencilFaceState; +struct WGPUStorageTextureBindingLayout; +struct WGPUStringView; +struct WGPUSupportedFeatures; +struct WGPUSurfaceCapabilities; +struct WGPUSurfaceConfiguration; +struct WGPUSurfaceDescriptorFromWindowsCoreWindow; +struct WGPUSurfaceDescriptorFromWindowsSwapChainPanel; +struct WGPUSurfaceSourceXCBWindow; +struct WGPUSurfaceSourceAndroidNativeWindow; +struct WGPUSurfaceSourceMetalLayer; +struct WGPUSurfaceSourceWaylandSurface; +struct WGPUSurfaceSourceWindowsHWND; +struct WGPUSurfaceSourceXlibWindow; +struct WGPUSurfaceTexture; +struct WGPUTextureBindingLayout; +struct WGPUTextureBindingViewDimensionDescriptor; +struct WGPUTextureDataLayout; +struct WGPUUncapturedErrorCallbackInfo; +struct WGPUVertexAttribute; +struct WGPUYCbCrVkDescriptor; +struct WGPUAHardwareBufferProperties; +struct WGPUAdapterInfo; +struct WGPUAdapterPropertiesMemoryHeaps; +struct WGPUBindGroupDescriptor; +struct WGPUBindGroupLayoutEntry; +struct WGPUBlendState; +struct WGPUBufferDescriptor; +struct WGPUCommandBufferDescriptor; +struct WGPUCommandEncoderDescriptor; +struct WGPUCompilationMessage; +struct WGPUComputePassDescriptor; +struct WGPUConstantEntry; +struct WGPUDawnCacheDeviceDescriptor; +struct WGPUDepthStencilState; +struct WGPUDrmFormatCapabilities; +struct WGPUExternalTextureDescriptor; +struct WGPUFutureWaitInfo; +struct WGPUImageCopyBuffer; +struct WGPUImageCopyExternalTexture; +struct WGPUImageCopyTexture; +struct WGPUInstanceDescriptor; +struct WGPUPipelineLayoutDescriptor; +struct WGPUPipelineLayoutPixelLocalStorage; +struct WGPUQuerySetDescriptor; +struct WGPUQueueDescriptor; +struct WGPURenderBundleDescriptor; +struct WGPURenderBundleEncoderDescriptor; +struct WGPURenderPassColorAttachment; +struct WGPURenderPassStorageAttachment; +struct WGPURequiredLimits; +struct WGPUSamplerDescriptor; +struct WGPUShaderModuleDescriptor; +struct WGPUShaderSourceWGSL; +struct WGPUSharedBufferMemoryDescriptor; +struct WGPUSharedFenceDescriptor; +struct WGPUSharedTextureMemoryAHardwareBufferProperties; +struct WGPUSharedTextureMemoryDescriptor; +struct WGPUSharedTextureMemoryDmaBufDescriptor; +struct WGPUSharedTextureMemoryProperties; +struct WGPUSupportedLimits; +struct WGPUSurfaceDescriptor; +struct WGPUSurfaceSourceCanvasHTMLSelector_Emscripten; +struct WGPUTextureDescriptor; +struct WGPUTextureViewDescriptor; +struct WGPUVertexBufferLayout; +struct WGPUBindGroupLayoutDescriptor; +struct WGPUColorTargetState; +struct WGPUCompilationInfo; +struct WGPUComputeState; +struct WGPUDeviceDescriptor; +struct WGPURenderPassDescriptor; +struct WGPURenderPassPixelLocalStorage; +struct WGPUVertexState; +struct WGPUComputePipelineDescriptor; +struct WGPUFragmentState; +struct WGPURenderPipelineDescriptor; + +typedef enum WGPUWGSLFeatureName { + WGPUWGSLFeatureName_ReadonlyAndReadwriteStorageTextures = 0x00000001, + WGPUWGSLFeatureName_Packed4x8IntegerDotProduct = 0x00000002, + WGPUWGSLFeatureName_UnrestrictedPointerParameters = 0x00000003, + WGPUWGSLFeatureName_PointerCompositeAccess = 0x00000004, + WGPUWGSLFeatureName_ChromiumTestingUnimplemented = 0x00050000, + WGPUWGSLFeatureName_ChromiumTestingUnsafeExperimental = 0x00050001, + WGPUWGSLFeatureName_ChromiumTestingExperimental = 0x00050002, + WGPUWGSLFeatureName_ChromiumTestingShippedWithKillswitch = 0x00050003, + WGPUWGSLFeatureName_ChromiumTestingShipped = 0x00050004, + WGPUWGSLFeatureName_Force32 = 0x7FFFFFFF +} WGPUWGSLFeatureName WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUAdapterType { + WGPUAdapterType_DiscreteGPU = 0x00000001, + WGPUAdapterType_IntegratedGPU = 0x00000002, + WGPUAdapterType_CPU = 0x00000003, + WGPUAdapterType_Unknown = 0x00000004, + WGPUAdapterType_Force32 = 0x7FFFFFFF +} WGPUAdapterType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUAddressMode { + WGPUAddressMode_Undefined = 0x00000000, + WGPUAddressMode_ClampToEdge = 0x00000001, + WGPUAddressMode_Repeat = 0x00000002, + WGPUAddressMode_MirrorRepeat = 0x00000003, + WGPUAddressMode_Force32 = 0x7FFFFFFF +} WGPUAddressMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUAlphaMode { + WGPUAlphaMode_Opaque = 0x00000001, + WGPUAlphaMode_Premultiplied = 0x00000002, + WGPUAlphaMode_Unpremultiplied = 0x00000003, + WGPUAlphaMode_Force32 = 0x7FFFFFFF +} WGPUAlphaMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBackendType { + WGPUBackendType_Undefined = 0x00000000, + WGPUBackendType_Null = 0x00000001, + WGPUBackendType_WebGPU = 0x00000002, + WGPUBackendType_D3D11 = 0x00000003, + WGPUBackendType_D3D12 = 0x00000004, + WGPUBackendType_Metal = 0x00000005, + WGPUBackendType_Vulkan = 0x00000006, + WGPUBackendType_OpenGL = 0x00000007, + WGPUBackendType_OpenGLES = 0x00000008, + WGPUBackendType_Force32 = 0x7FFFFFFF +} WGPUBackendType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBlendFactor { + WGPUBlendFactor_Undefined = 0x00000000, + WGPUBlendFactor_Zero = 0x00000001, + WGPUBlendFactor_One = 0x00000002, + WGPUBlendFactor_Src = 0x00000003, + WGPUBlendFactor_OneMinusSrc = 0x00000004, + WGPUBlendFactor_SrcAlpha = 0x00000005, + WGPUBlendFactor_OneMinusSrcAlpha = 0x00000006, + WGPUBlendFactor_Dst = 0x00000007, + WGPUBlendFactor_OneMinusDst = 0x00000008, + WGPUBlendFactor_DstAlpha = 0x00000009, + WGPUBlendFactor_OneMinusDstAlpha = 0x0000000A, + WGPUBlendFactor_SrcAlphaSaturated = 0x0000000B, + WGPUBlendFactor_Constant = 0x0000000C, + WGPUBlendFactor_OneMinusConstant = 0x0000000D, + WGPUBlendFactor_Src1 = 0x0000000E, + WGPUBlendFactor_OneMinusSrc1 = 0x0000000F, + WGPUBlendFactor_Src1Alpha = 0x00000010, + WGPUBlendFactor_OneMinusSrc1Alpha = 0x00000011, + WGPUBlendFactor_Force32 = 0x7FFFFFFF +} WGPUBlendFactor WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBlendOperation { + WGPUBlendOperation_Undefined = 0x00000000, + WGPUBlendOperation_Add = 0x00000001, + WGPUBlendOperation_Subtract = 0x00000002, + WGPUBlendOperation_ReverseSubtract = 0x00000003, + WGPUBlendOperation_Min = 0x00000004, + WGPUBlendOperation_Max = 0x00000005, + WGPUBlendOperation_Force32 = 0x7FFFFFFF +} WGPUBlendOperation WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBufferBindingType { + WGPUBufferBindingType_BindingNotUsed = 0x00000000, + WGPUBufferBindingType_Uniform = 0x00000001, + WGPUBufferBindingType_Storage = 0x00000002, + WGPUBufferBindingType_ReadOnlyStorage = 0x00000003, + WGPUBufferBindingType_Force32 = 0x7FFFFFFF +} WGPUBufferBindingType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBufferMapAsyncStatus { + WGPUBufferMapAsyncStatus_Success = 0x00000001, + WGPUBufferMapAsyncStatus_InstanceDropped = 0x00000002, + WGPUBufferMapAsyncStatus_ValidationError = 0x00000003, + WGPUBufferMapAsyncStatus_Unknown = 0x00000004, + WGPUBufferMapAsyncStatus_DeviceLost = 0x00000005, + WGPUBufferMapAsyncStatus_DestroyedBeforeCallback = 0x00000006, + WGPUBufferMapAsyncStatus_UnmappedBeforeCallback = 0x00000007, + WGPUBufferMapAsyncStatus_MappingAlreadyPending = 0x00000008, + WGPUBufferMapAsyncStatus_OffsetOutOfRange = 0x00000009, + WGPUBufferMapAsyncStatus_SizeOutOfRange = 0x0000000A, + WGPUBufferMapAsyncStatus_Force32 = 0x7FFFFFFF +} WGPUBufferMapAsyncStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUBufferMapState { + WGPUBufferMapState_Unmapped = 0x00000001, + WGPUBufferMapState_Pending = 0x00000002, + WGPUBufferMapState_Mapped = 0x00000003, + WGPUBufferMapState_Force32 = 0x7FFFFFFF +} WGPUBufferMapState WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCallbackMode { + WGPUCallbackMode_WaitAnyOnly = 0x00000001, + WGPUCallbackMode_AllowProcessEvents = 0x00000002, + WGPUCallbackMode_AllowSpontaneous = 0x00000003, + WGPUCallbackMode_Force32 = 0x7FFFFFFF +} WGPUCallbackMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCompareFunction { + WGPUCompareFunction_Undefined = 0x00000000, + WGPUCompareFunction_Never = 0x00000001, + WGPUCompareFunction_Less = 0x00000002, + WGPUCompareFunction_Equal = 0x00000003, + WGPUCompareFunction_LessEqual = 0x00000004, + WGPUCompareFunction_Greater = 0x00000005, + WGPUCompareFunction_NotEqual = 0x00000006, + WGPUCompareFunction_GreaterEqual = 0x00000007, + WGPUCompareFunction_Always = 0x00000008, + WGPUCompareFunction_Force32 = 0x7FFFFFFF +} WGPUCompareFunction WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCompilationInfoRequestStatus { + WGPUCompilationInfoRequestStatus_Success = 0x00000001, + WGPUCompilationInfoRequestStatus_InstanceDropped = 0x00000002, + WGPUCompilationInfoRequestStatus_Error = 0x00000003, + WGPUCompilationInfoRequestStatus_DeviceLost = 0x00000004, + WGPUCompilationInfoRequestStatus_Unknown = 0x00000005, + WGPUCompilationInfoRequestStatus_Force32 = 0x7FFFFFFF +} WGPUCompilationInfoRequestStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCompilationMessageType { + WGPUCompilationMessageType_Error = 0x00000001, + WGPUCompilationMessageType_Warning = 0x00000002, + WGPUCompilationMessageType_Info = 0x00000003, + WGPUCompilationMessageType_Force32 = 0x7FFFFFFF +} WGPUCompilationMessageType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCompositeAlphaMode { + WGPUCompositeAlphaMode_Auto = 0x00000000, + WGPUCompositeAlphaMode_Opaque = 0x00000001, + WGPUCompositeAlphaMode_Premultiplied = 0x00000002, + WGPUCompositeAlphaMode_Unpremultiplied = 0x00000003, + WGPUCompositeAlphaMode_Inherit = 0x00000004, + WGPUCompositeAlphaMode_Force32 = 0x7FFFFFFF +} WGPUCompositeAlphaMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCreatePipelineAsyncStatus { + WGPUCreatePipelineAsyncStatus_Success = 0x00000001, + WGPUCreatePipelineAsyncStatus_InstanceDropped = 0x00000002, + WGPUCreatePipelineAsyncStatus_ValidationError = 0x00000003, + WGPUCreatePipelineAsyncStatus_InternalError = 0x00000004, + WGPUCreatePipelineAsyncStatus_DeviceLost = 0x00000005, + WGPUCreatePipelineAsyncStatus_DeviceDestroyed = 0x00000006, + WGPUCreatePipelineAsyncStatus_Unknown = 0x00000007, + WGPUCreatePipelineAsyncStatus_Force32 = 0x7FFFFFFF +} WGPUCreatePipelineAsyncStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUCullMode { + WGPUCullMode_Undefined = 0x00000000, + WGPUCullMode_None = 0x00000001, + WGPUCullMode_Front = 0x00000002, + WGPUCullMode_Back = 0x00000003, + WGPUCullMode_Force32 = 0x7FFFFFFF +} WGPUCullMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUDeviceLostReason { + WGPUDeviceLostReason_Unknown = 0x00000001, + WGPUDeviceLostReason_Destroyed = 0x00000002, + WGPUDeviceLostReason_InstanceDropped = 0x00000003, + WGPUDeviceLostReason_FailedCreation = 0x00000004, + WGPUDeviceLostReason_Force32 = 0x7FFFFFFF +} WGPUDeviceLostReason WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUErrorFilter { + WGPUErrorFilter_Validation = 0x00000001, + WGPUErrorFilter_OutOfMemory = 0x00000002, + WGPUErrorFilter_Internal = 0x00000003, + WGPUErrorFilter_Force32 = 0x7FFFFFFF +} WGPUErrorFilter WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUErrorType { + WGPUErrorType_NoError = 0x00000001, + WGPUErrorType_Validation = 0x00000002, + WGPUErrorType_OutOfMemory = 0x00000003, + WGPUErrorType_Internal = 0x00000004, + WGPUErrorType_Unknown = 0x00000005, + WGPUErrorType_DeviceLost = 0x00000006, + WGPUErrorType_Force32 = 0x7FFFFFFF +} WGPUErrorType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUExternalTextureRotation { + WGPUExternalTextureRotation_Rotate0Degrees = 0x00000001, + WGPUExternalTextureRotation_Rotate90Degrees = 0x00000002, + WGPUExternalTextureRotation_Rotate180Degrees = 0x00000003, + WGPUExternalTextureRotation_Rotate270Degrees = 0x00000004, + WGPUExternalTextureRotation_Force32 = 0x7FFFFFFF +} WGPUExternalTextureRotation WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUFeatureLevel { + WGPUFeatureLevel_Undefined = 0x00000000, + WGPUFeatureLevel_Compatibility = 0x00000001, + WGPUFeatureLevel_Core = 0x00000002, + WGPUFeatureLevel_Force32 = 0x7FFFFFFF +} WGPUFeatureLevel WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUFeatureName { + WGPUFeatureName_DepthClipControl = 0x00000001, + WGPUFeatureName_Depth32FloatStencil8 = 0x00000002, + WGPUFeatureName_TimestampQuery = 0x00000003, + WGPUFeatureName_TextureCompressionBC = 0x00000004, + WGPUFeatureName_TextureCompressionETC2 = 0x00000005, + WGPUFeatureName_TextureCompressionASTC = 0x00000006, + WGPUFeatureName_IndirectFirstInstance = 0x00000007, + WGPUFeatureName_ShaderF16 = 0x00000008, + WGPUFeatureName_RG11B10UfloatRenderable = 0x00000009, + WGPUFeatureName_BGRA8UnormStorage = 0x0000000A, + WGPUFeatureName_Float32Filterable = 0x0000000B, + WGPUFeatureName_Float32Blendable = 0x0000000C, + WGPUFeatureName_Subgroups = 0x0000000D, + WGPUFeatureName_SubgroupsF16 = 0x0000000E, + WGPUFeatureName_DawnInternalUsages = 0x00050000, + WGPUFeatureName_DawnMultiPlanarFormats = 0x00050001, + WGPUFeatureName_DawnNative = 0x00050002, + WGPUFeatureName_ChromiumExperimentalTimestampQueryInsidePasses = 0x00050003, + WGPUFeatureName_ImplicitDeviceSynchronization = 0x00050004, + WGPUFeatureName_ChromiumExperimentalImmediateData = 0x00050005, + WGPUFeatureName_TransientAttachments = 0x00050006, + WGPUFeatureName_MSAARenderToSingleSampled = 0x00050007, + WGPUFeatureName_DualSourceBlending = 0x00050008, + WGPUFeatureName_D3D11MultithreadProtected = 0x00050009, + WGPUFeatureName_ANGLETextureSharing = 0x0005000A, + WGPUFeatureName_PixelLocalStorageCoherent = 0x0005000B, + WGPUFeatureName_PixelLocalStorageNonCoherent = 0x0005000C, + WGPUFeatureName_Unorm16TextureFormats = 0x0005000D, + WGPUFeatureName_Snorm16TextureFormats = 0x0005000E, + WGPUFeatureName_MultiPlanarFormatExtendedUsages = 0x0005000F, + WGPUFeatureName_MultiPlanarFormatP010 = 0x00050010, + WGPUFeatureName_HostMappedPointer = 0x00050011, + WGPUFeatureName_MultiPlanarRenderTargets = 0x00050012, + WGPUFeatureName_MultiPlanarFormatNv12a = 0x00050013, + WGPUFeatureName_FramebufferFetch = 0x00050014, + WGPUFeatureName_BufferMapExtendedUsages = 0x00050015, + WGPUFeatureName_AdapterPropertiesMemoryHeaps = 0x00050016, + WGPUFeatureName_AdapterPropertiesD3D = 0x00050017, + WGPUFeatureName_AdapterPropertiesVk = 0x00050018, + WGPUFeatureName_R8UnormStorage = 0x00050019, + WGPUFeatureName_FormatCapabilities = 0x0005001A, + WGPUFeatureName_DrmFormatCapabilities = 0x0005001B, + WGPUFeatureName_Norm16TextureFormats = 0x0005001C, + WGPUFeatureName_MultiPlanarFormatNv16 = 0x0005001D, + WGPUFeatureName_MultiPlanarFormatNv24 = 0x0005001E, + WGPUFeatureName_MultiPlanarFormatP210 = 0x0005001F, + WGPUFeatureName_MultiPlanarFormatP410 = 0x00050020, + WGPUFeatureName_SharedTextureMemoryVkDedicatedAllocation = 0x00050021, + WGPUFeatureName_SharedTextureMemoryAHardwareBuffer = 0x00050022, + WGPUFeatureName_SharedTextureMemoryDmaBuf = 0x00050023, + WGPUFeatureName_SharedTextureMemoryOpaqueFD = 0x00050024, + WGPUFeatureName_SharedTextureMemoryZirconHandle = 0x00050025, + WGPUFeatureName_SharedTextureMemoryDXGISharedHandle = 0x00050026, + WGPUFeatureName_SharedTextureMemoryD3D11Texture2D = 0x00050027, + WGPUFeatureName_SharedTextureMemoryIOSurface = 0x00050028, + WGPUFeatureName_SharedTextureMemoryEGLImage = 0x00050029, + WGPUFeatureName_SharedFenceVkSemaphoreOpaqueFD = 0x0005002A, + WGPUFeatureName_SharedFenceSyncFD = 0x0005002B, + WGPUFeatureName_SharedFenceVkSemaphoreZirconHandle = 0x0005002C, + WGPUFeatureName_SharedFenceDXGISharedHandle = 0x0005002D, + WGPUFeatureName_SharedFenceMTLSharedEvent = 0x0005002E, + WGPUFeatureName_SharedBufferMemoryD3D12Resource = 0x0005002F, + WGPUFeatureName_StaticSamplers = 0x00050030, + WGPUFeatureName_YCbCrVulkanSamplers = 0x00050031, + WGPUFeatureName_ShaderModuleCompilationOptions = 0x00050032, + WGPUFeatureName_DawnLoadResolveTexture = 0x00050033, + WGPUFeatureName_DawnPartialLoadResolveTexture = 0x00050034, + WGPUFeatureName_MultiDrawIndirect = 0x00050035, + WGPUFeatureName_ClipDistances = 0x00050036, + WGPUFeatureName_DawnTexelCopyBufferRowAlignment = 0x00050037, + WGPUFeatureName_FlexibleTextureViews = 0x00050038, + WGPUFeatureName_Force32 = 0x7FFFFFFF +} WGPUFeatureName WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUFilterMode { + WGPUFilterMode_Undefined = 0x00000000, + WGPUFilterMode_Nearest = 0x00000001, + WGPUFilterMode_Linear = 0x00000002, + WGPUFilterMode_Force32 = 0x7FFFFFFF +} WGPUFilterMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUFrontFace { + WGPUFrontFace_Undefined = 0x00000000, + WGPUFrontFace_CCW = 0x00000001, + WGPUFrontFace_CW = 0x00000002, + WGPUFrontFace_Force32 = 0x7FFFFFFF +} WGPUFrontFace WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUIndexFormat { + WGPUIndexFormat_Undefined = 0x00000000, + WGPUIndexFormat_Uint16 = 0x00000001, + WGPUIndexFormat_Uint32 = 0x00000002, + WGPUIndexFormat_Force32 = 0x7FFFFFFF +} WGPUIndexFormat WGPU_ENUM_ATTRIBUTE; +typedef enum WGPULoadOp { + WGPULoadOp_Undefined = 0x00000000, + WGPULoadOp_Load = 0x00000001, + WGPULoadOp_Clear = 0x00000002, + WGPULoadOp_ExpandResolveTexture = 0x00050003, + WGPULoadOp_Force32 = 0x7FFFFFFF +} WGPULoadOp WGPU_ENUM_ATTRIBUTE; +typedef enum WGPULoggingType { + WGPULoggingType_Verbose = 0x00000001, + WGPULoggingType_Info = 0x00000002, + WGPULoggingType_Warning = 0x00000003, + WGPULoggingType_Error = 0x00000004, + WGPULoggingType_Force32 = 0x7FFFFFFF +} WGPULoggingType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUMapAsyncStatus { + WGPUMapAsyncStatus_Success = 0x00000001, + WGPUMapAsyncStatus_InstanceDropped = 0x00000002, + WGPUMapAsyncStatus_Error = 0x00000003, + WGPUMapAsyncStatus_Aborted = 0x00000004, + WGPUMapAsyncStatus_Unknown = 0x00000005, + WGPUMapAsyncStatus_Force32 = 0x7FFFFFFF +} WGPUMapAsyncStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUMipmapFilterMode { + WGPUMipmapFilterMode_Undefined = 0x00000000, + WGPUMipmapFilterMode_Nearest = 0x00000001, + WGPUMipmapFilterMode_Linear = 0x00000002, + WGPUMipmapFilterMode_Force32 = 0x7FFFFFFF +} WGPUMipmapFilterMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUOptionalBool { + WGPUOptionalBool_False = 0x00000000, + WGPUOptionalBool_True = 0x00000001, + WGPUOptionalBool_Undefined = 0x00000002, + WGPUOptionalBool_Force32 = 0x7FFFFFFF +} WGPUOptionalBool WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUPopErrorScopeStatus { + WGPUPopErrorScopeStatus_Success = 0x00000001, + WGPUPopErrorScopeStatus_InstanceDropped = 0x00000002, + WGPUPopErrorScopeStatus_Force32 = 0x7FFFFFFF +} WGPUPopErrorScopeStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUPowerPreference { + WGPUPowerPreference_Undefined = 0x00000000, + WGPUPowerPreference_LowPower = 0x00000001, + WGPUPowerPreference_HighPerformance = 0x00000002, + WGPUPowerPreference_Force32 = 0x7FFFFFFF +} WGPUPowerPreference WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUPresentMode { + WGPUPresentMode_Fifo = 0x00000001, + WGPUPresentMode_FifoRelaxed = 0x00000002, + WGPUPresentMode_Immediate = 0x00000003, + WGPUPresentMode_Mailbox = 0x00000004, + WGPUPresentMode_Force32 = 0x7FFFFFFF +} WGPUPresentMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUPrimitiveTopology { + WGPUPrimitiveTopology_Undefined = 0x00000000, + WGPUPrimitiveTopology_PointList = 0x00000001, + WGPUPrimitiveTopology_LineList = 0x00000002, + WGPUPrimitiveTopology_LineStrip = 0x00000003, + WGPUPrimitiveTopology_TriangleList = 0x00000004, + WGPUPrimitiveTopology_TriangleStrip = 0x00000005, + WGPUPrimitiveTopology_Force32 = 0x7FFFFFFF +} WGPUPrimitiveTopology WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUQueryType { + WGPUQueryType_Occlusion = 0x00000001, + WGPUQueryType_Timestamp = 0x00000002, + WGPUQueryType_Force32 = 0x7FFFFFFF +} WGPUQueryType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUQueueWorkDoneStatus { + WGPUQueueWorkDoneStatus_Success = 0x00000001, + WGPUQueueWorkDoneStatus_InstanceDropped = 0x00000002, + WGPUQueueWorkDoneStatus_Error = 0x00000003, + WGPUQueueWorkDoneStatus_Unknown = 0x00000004, + WGPUQueueWorkDoneStatus_DeviceLost = 0x00000005, + WGPUQueueWorkDoneStatus_Force32 = 0x7FFFFFFF +} WGPUQueueWorkDoneStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPURequestAdapterStatus { + WGPURequestAdapterStatus_Success = 0x00000001, + WGPURequestAdapterStatus_InstanceDropped = 0x00000002, + WGPURequestAdapterStatus_Unavailable = 0x00000003, + WGPURequestAdapterStatus_Error = 0x00000004, + WGPURequestAdapterStatus_Unknown = 0x00000005, + WGPURequestAdapterStatus_Force32 = 0x7FFFFFFF +} WGPURequestAdapterStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPURequestDeviceStatus { + WGPURequestDeviceStatus_Success = 0x00000001, + WGPURequestDeviceStatus_InstanceDropped = 0x00000002, + WGPURequestDeviceStatus_Error = 0x00000003, + WGPURequestDeviceStatus_Unknown = 0x00000004, + WGPURequestDeviceStatus_Force32 = 0x7FFFFFFF +} WGPURequestDeviceStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUSType { + WGPUSType_ShaderSourceSPIRV = 0x00000001, + WGPUSType_ShaderSourceWGSL = 0x00000002, + WGPUSType_RenderPassMaxDrawCount = 0x00000003, + WGPUSType_SurfaceSourceMetalLayer = 0x00000004, + WGPUSType_SurfaceSourceWindowsHWND = 0x00000005, + WGPUSType_SurfaceSourceXlibWindow = 0x00000006, + WGPUSType_SurfaceSourceWaylandSurface = 0x00000007, + WGPUSType_SurfaceSourceAndroidNativeWindow = 0x00000008, + WGPUSType_SurfaceSourceXCBWindow = 0x00000009, + WGPUSType_AdapterPropertiesSubgroups = 0x0000000A, + WGPUSType_TextureBindingViewDimensionDescriptor = 0x00020000, + WGPUSType_SurfaceSourceCanvasHTMLSelector_Emscripten = 0x00040000, + WGPUSType_SurfaceDescriptorFromWindowsCoreWindow = 0x00050000, + WGPUSType_ExternalTextureBindingEntry = 0x00050001, + WGPUSType_ExternalTextureBindingLayout = 0x00050002, + WGPUSType_SurfaceDescriptorFromWindowsSwapChainPanel = 0x00050003, + WGPUSType_DawnTextureInternalUsageDescriptor = 0x00050004, + WGPUSType_DawnEncoderInternalUsageDescriptor = 0x00050005, + WGPUSType_DawnInstanceDescriptor = 0x00050006, + WGPUSType_DawnCacheDeviceDescriptor = 0x00050007, + WGPUSType_DawnAdapterPropertiesPowerPreference = 0x00050008, + WGPUSType_DawnBufferDescriptorErrorInfoFromWireClient = 0x00050009, + WGPUSType_DawnTogglesDescriptor = 0x0005000A, + WGPUSType_DawnShaderModuleSPIRVOptionsDescriptor = 0x0005000B, + WGPUSType_RequestAdapterOptionsLUID = 0x0005000C, + WGPUSType_RequestAdapterOptionsGetGLProc = 0x0005000D, + WGPUSType_RequestAdapterOptionsD3D11Device = 0x0005000E, + WGPUSType_DawnRenderPassColorAttachmentRenderToSingleSampled = 0x0005000F, + WGPUSType_RenderPassPixelLocalStorage = 0x00050010, + WGPUSType_PipelineLayoutPixelLocalStorage = 0x00050011, + WGPUSType_BufferHostMappedPointer = 0x00050012, + WGPUSType_DawnExperimentalSubgroupLimits = 0x00050013, + WGPUSType_AdapterPropertiesMemoryHeaps = 0x00050014, + WGPUSType_AdapterPropertiesD3D = 0x00050015, + WGPUSType_AdapterPropertiesVk = 0x00050016, + WGPUSType_DawnWireWGSLControl = 0x00050017, + WGPUSType_DawnWGSLBlocklist = 0x00050018, + WGPUSType_DrmFormatCapabilities = 0x00050019, + WGPUSType_ShaderModuleCompilationOptions = 0x0005001A, + WGPUSType_ColorTargetStateExpandResolveTextureDawn = 0x0005001B, + WGPUSType_RenderPassDescriptorExpandResolveRect = 0x0005001C, + WGPUSType_SharedTextureMemoryVkDedicatedAllocationDescriptor = 0x0005001D, + WGPUSType_SharedTextureMemoryAHardwareBufferDescriptor = 0x0005001E, + WGPUSType_SharedTextureMemoryDmaBufDescriptor = 0x0005001F, + WGPUSType_SharedTextureMemoryOpaqueFDDescriptor = 0x00050020, + WGPUSType_SharedTextureMemoryZirconHandleDescriptor = 0x00050021, + WGPUSType_SharedTextureMemoryDXGISharedHandleDescriptor = 0x00050022, + WGPUSType_SharedTextureMemoryD3D11Texture2DDescriptor = 0x00050023, + WGPUSType_SharedTextureMemoryIOSurfaceDescriptor = 0x00050024, + WGPUSType_SharedTextureMemoryEGLImageDescriptor = 0x00050025, + WGPUSType_SharedTextureMemoryInitializedBeginState = 0x00050026, + WGPUSType_SharedTextureMemoryInitializedEndState = 0x00050027, + WGPUSType_SharedTextureMemoryVkImageLayoutBeginState = 0x00050028, + WGPUSType_SharedTextureMemoryVkImageLayoutEndState = 0x00050029, + WGPUSType_SharedTextureMemoryD3DSwapchainBeginState = 0x0005002A, + WGPUSType_SharedFenceVkSemaphoreOpaqueFDDescriptor = 0x0005002B, + WGPUSType_SharedFenceVkSemaphoreOpaqueFDExportInfo = 0x0005002C, + WGPUSType_SharedFenceSyncFDDescriptor = 0x0005002D, + WGPUSType_SharedFenceSyncFDExportInfo = 0x0005002E, + WGPUSType_SharedFenceVkSemaphoreZirconHandleDescriptor = 0x0005002F, + WGPUSType_SharedFenceVkSemaphoreZirconHandleExportInfo = 0x00050030, + WGPUSType_SharedFenceDXGISharedHandleDescriptor = 0x00050031, + WGPUSType_SharedFenceDXGISharedHandleExportInfo = 0x00050032, + WGPUSType_SharedFenceMTLSharedEventDescriptor = 0x00050033, + WGPUSType_SharedFenceMTLSharedEventExportInfo = 0x00050034, + WGPUSType_SharedBufferMemoryD3D12ResourceDescriptor = 0x00050035, + WGPUSType_StaticSamplerBindingLayout = 0x00050036, + WGPUSType_YCbCrVkDescriptor = 0x00050037, + WGPUSType_SharedTextureMemoryAHardwareBufferProperties = 0x00050038, + WGPUSType_AHardwareBufferProperties = 0x00050039, + WGPUSType_DawnExperimentalImmediateDataLimits = 0x0005003A, + WGPUSType_DawnTexelCopyBufferRowAlignmentLimits = 0x0005003B, + WGPUSType_Force32 = 0x7FFFFFFF +} WGPUSType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUSamplerBindingType { + WGPUSamplerBindingType_BindingNotUsed = 0x00000000, + WGPUSamplerBindingType_Filtering = 0x00000001, + WGPUSamplerBindingType_NonFiltering = 0x00000002, + WGPUSamplerBindingType_Comparison = 0x00000003, + WGPUSamplerBindingType_Force32 = 0x7FFFFFFF +} WGPUSamplerBindingType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUSharedFenceType { + WGPUSharedFenceType_VkSemaphoreOpaqueFD = 0x00000001, + WGPUSharedFenceType_SyncFD = 0x00000002, + WGPUSharedFenceType_VkSemaphoreZirconHandle = 0x00000003, + WGPUSharedFenceType_DXGISharedHandle = 0x00000004, + WGPUSharedFenceType_MTLSharedEvent = 0x00000005, + WGPUSharedFenceType_Force32 = 0x7FFFFFFF +} WGPUSharedFenceType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUStatus { + WGPUStatus_Success = 0x00000001, + WGPUStatus_Error = 0x00000002, + WGPUStatus_Force32 = 0x7FFFFFFF +} WGPUStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUStencilOperation { + WGPUStencilOperation_Undefined = 0x00000000, + WGPUStencilOperation_Keep = 0x00000001, + WGPUStencilOperation_Zero = 0x00000002, + WGPUStencilOperation_Replace = 0x00000003, + WGPUStencilOperation_Invert = 0x00000004, + WGPUStencilOperation_IncrementClamp = 0x00000005, + WGPUStencilOperation_DecrementClamp = 0x00000006, + WGPUStencilOperation_IncrementWrap = 0x00000007, + WGPUStencilOperation_DecrementWrap = 0x00000008, + WGPUStencilOperation_Force32 = 0x7FFFFFFF +} WGPUStencilOperation WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUStorageTextureAccess { + WGPUStorageTextureAccess_BindingNotUsed = 0x00000000, + WGPUStorageTextureAccess_WriteOnly = 0x00000001, + WGPUStorageTextureAccess_ReadOnly = 0x00000002, + WGPUStorageTextureAccess_ReadWrite = 0x00000003, + WGPUStorageTextureAccess_Force32 = 0x7FFFFFFF +} WGPUStorageTextureAccess WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUStoreOp { + WGPUStoreOp_Undefined = 0x00000000, + WGPUStoreOp_Store = 0x00000001, + WGPUStoreOp_Discard = 0x00000002, + WGPUStoreOp_Force32 = 0x7FFFFFFF +} WGPUStoreOp WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUSurfaceGetCurrentTextureStatus { + WGPUSurfaceGetCurrentTextureStatus_Success = 0x00000001, + WGPUSurfaceGetCurrentTextureStatus_Timeout = 0x00000002, + WGPUSurfaceGetCurrentTextureStatus_Outdated = 0x00000003, + WGPUSurfaceGetCurrentTextureStatus_Lost = 0x00000004, + WGPUSurfaceGetCurrentTextureStatus_OutOfMemory = 0x00000005, + WGPUSurfaceGetCurrentTextureStatus_DeviceLost = 0x00000006, + WGPUSurfaceGetCurrentTextureStatus_Error = 0x00000007, + WGPUSurfaceGetCurrentTextureStatus_Force32 = 0x7FFFFFFF +} WGPUSurfaceGetCurrentTextureStatus WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUTextureAspect { + WGPUTextureAspect_Undefined = 0x00000000, + WGPUTextureAspect_All = 0x00000001, + WGPUTextureAspect_StencilOnly = 0x00000002, + WGPUTextureAspect_DepthOnly = 0x00000003, + WGPUTextureAspect_Plane0Only = 0x00050000, + WGPUTextureAspect_Plane1Only = 0x00050001, + WGPUTextureAspect_Plane2Only = 0x00050002, + WGPUTextureAspect_Force32 = 0x7FFFFFFF +} WGPUTextureAspect WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUTextureDimension { + WGPUTextureDimension_Undefined = 0x00000000, + WGPUTextureDimension_1D = 0x00000001, + WGPUTextureDimension_2D = 0x00000002, + WGPUTextureDimension_3D = 0x00000003, + WGPUTextureDimension_Force32 = 0x7FFFFFFF +} WGPUTextureDimension WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUTextureFormat { + WGPUTextureFormat_Undefined = 0x00000000, + WGPUTextureFormat_R8Unorm = 0x00000001, + WGPUTextureFormat_R8Snorm = 0x00000002, + WGPUTextureFormat_R8Uint = 0x00000003, + WGPUTextureFormat_R8Sint = 0x00000004, + WGPUTextureFormat_R16Uint = 0x00000005, + WGPUTextureFormat_R16Sint = 0x00000006, + WGPUTextureFormat_R16Float = 0x00000007, + WGPUTextureFormat_RG8Unorm = 0x00000008, + WGPUTextureFormat_RG8Snorm = 0x00000009, + WGPUTextureFormat_RG8Uint = 0x0000000A, + WGPUTextureFormat_RG8Sint = 0x0000000B, + WGPUTextureFormat_R32Float = 0x0000000C, + WGPUTextureFormat_R32Uint = 0x0000000D, + WGPUTextureFormat_R32Sint = 0x0000000E, + WGPUTextureFormat_RG16Uint = 0x0000000F, + WGPUTextureFormat_RG16Sint = 0x00000010, + WGPUTextureFormat_RG16Float = 0x00000011, + WGPUTextureFormat_RGBA8Unorm = 0x00000012, + WGPUTextureFormat_RGBA8UnormSrgb = 0x00000013, + WGPUTextureFormat_RGBA8Snorm = 0x00000014, + WGPUTextureFormat_RGBA8Uint = 0x00000015, + WGPUTextureFormat_RGBA8Sint = 0x00000016, + WGPUTextureFormat_BGRA8Unorm = 0x00000017, + WGPUTextureFormat_BGRA8UnormSrgb = 0x00000018, + WGPUTextureFormat_RGB10A2Uint = 0x00000019, + WGPUTextureFormat_RGB10A2Unorm = 0x0000001A, + WGPUTextureFormat_RG11B10Ufloat = 0x0000001B, + WGPUTextureFormat_RGB9E5Ufloat = 0x0000001C, + WGPUTextureFormat_RG32Float = 0x0000001D, + WGPUTextureFormat_RG32Uint = 0x0000001E, + WGPUTextureFormat_RG32Sint = 0x0000001F, + WGPUTextureFormat_RGBA16Uint = 0x00000020, + WGPUTextureFormat_RGBA16Sint = 0x00000021, + WGPUTextureFormat_RGBA16Float = 0x00000022, + WGPUTextureFormat_RGBA32Float = 0x00000023, + WGPUTextureFormat_RGBA32Uint = 0x00000024, + WGPUTextureFormat_RGBA32Sint = 0x00000025, + WGPUTextureFormat_Stencil8 = 0x00000026, + WGPUTextureFormat_Depth16Unorm = 0x00000027, + WGPUTextureFormat_Depth24Plus = 0x00000028, + WGPUTextureFormat_Depth24PlusStencil8 = 0x00000029, + WGPUTextureFormat_Depth32Float = 0x0000002A, + WGPUTextureFormat_Depth32FloatStencil8 = 0x0000002B, + WGPUTextureFormat_BC1RGBAUnorm = 0x0000002C, + WGPUTextureFormat_BC1RGBAUnormSrgb = 0x0000002D, + WGPUTextureFormat_BC2RGBAUnorm = 0x0000002E, + WGPUTextureFormat_BC2RGBAUnormSrgb = 0x0000002F, + WGPUTextureFormat_BC3RGBAUnorm = 0x00000030, + WGPUTextureFormat_BC3RGBAUnormSrgb = 0x00000031, + WGPUTextureFormat_BC4RUnorm = 0x00000032, + WGPUTextureFormat_BC4RSnorm = 0x00000033, + WGPUTextureFormat_BC5RGUnorm = 0x00000034, + WGPUTextureFormat_BC5RGSnorm = 0x00000035, + WGPUTextureFormat_BC6HRGBUfloat = 0x00000036, + WGPUTextureFormat_BC6HRGBFloat = 0x00000037, + WGPUTextureFormat_BC7RGBAUnorm = 0x00000038, + WGPUTextureFormat_BC7RGBAUnormSrgb = 0x00000039, + WGPUTextureFormat_ETC2RGB8Unorm = 0x0000003A, + WGPUTextureFormat_ETC2RGB8UnormSrgb = 0x0000003B, + WGPUTextureFormat_ETC2RGB8A1Unorm = 0x0000003C, + WGPUTextureFormat_ETC2RGB8A1UnormSrgb = 0x0000003D, + WGPUTextureFormat_ETC2RGBA8Unorm = 0x0000003E, + WGPUTextureFormat_ETC2RGBA8UnormSrgb = 0x0000003F, + WGPUTextureFormat_EACR11Unorm = 0x00000040, + WGPUTextureFormat_EACR11Snorm = 0x00000041, + WGPUTextureFormat_EACRG11Unorm = 0x00000042, + WGPUTextureFormat_EACRG11Snorm = 0x00000043, + WGPUTextureFormat_ASTC4x4Unorm = 0x00000044, + WGPUTextureFormat_ASTC4x4UnormSrgb = 0x00000045, + WGPUTextureFormat_ASTC5x4Unorm = 0x00000046, + WGPUTextureFormat_ASTC5x4UnormSrgb = 0x00000047, + WGPUTextureFormat_ASTC5x5Unorm = 0x00000048, + WGPUTextureFormat_ASTC5x5UnormSrgb = 0x00000049, + WGPUTextureFormat_ASTC6x5Unorm = 0x0000004A, + WGPUTextureFormat_ASTC6x5UnormSrgb = 0x0000004B, + WGPUTextureFormat_ASTC6x6Unorm = 0x0000004C, + WGPUTextureFormat_ASTC6x6UnormSrgb = 0x0000004D, + WGPUTextureFormat_ASTC8x5Unorm = 0x0000004E, + WGPUTextureFormat_ASTC8x5UnormSrgb = 0x0000004F, + WGPUTextureFormat_ASTC8x6Unorm = 0x00000050, + WGPUTextureFormat_ASTC8x6UnormSrgb = 0x00000051, + WGPUTextureFormat_ASTC8x8Unorm = 0x00000052, + WGPUTextureFormat_ASTC8x8UnormSrgb = 0x00000053, + WGPUTextureFormat_ASTC10x5Unorm = 0x00000054, + WGPUTextureFormat_ASTC10x5UnormSrgb = 0x00000055, + WGPUTextureFormat_ASTC10x6Unorm = 0x00000056, + WGPUTextureFormat_ASTC10x6UnormSrgb = 0x00000057, + WGPUTextureFormat_ASTC10x8Unorm = 0x00000058, + WGPUTextureFormat_ASTC10x8UnormSrgb = 0x00000059, + WGPUTextureFormat_ASTC10x10Unorm = 0x0000005A, + WGPUTextureFormat_ASTC10x10UnormSrgb = 0x0000005B, + WGPUTextureFormat_ASTC12x10Unorm = 0x0000005C, + WGPUTextureFormat_ASTC12x10UnormSrgb = 0x0000005D, + WGPUTextureFormat_ASTC12x12Unorm = 0x0000005E, + WGPUTextureFormat_ASTC12x12UnormSrgb = 0x0000005F, + WGPUTextureFormat_R16Unorm = 0x00050000, + WGPUTextureFormat_RG16Unorm = 0x00050001, + WGPUTextureFormat_RGBA16Unorm = 0x00050002, + WGPUTextureFormat_R16Snorm = 0x00050003, + WGPUTextureFormat_RG16Snorm = 0x00050004, + WGPUTextureFormat_RGBA16Snorm = 0x00050005, + WGPUTextureFormat_R8BG8Biplanar420Unorm = 0x00050006, + WGPUTextureFormat_R10X6BG10X6Biplanar420Unorm = 0x00050007, + WGPUTextureFormat_R8BG8A8Triplanar420Unorm = 0x00050008, + WGPUTextureFormat_R8BG8Biplanar422Unorm = 0x00050009, + WGPUTextureFormat_R8BG8Biplanar444Unorm = 0x0005000A, + WGPUTextureFormat_R10X6BG10X6Biplanar422Unorm = 0x0005000B, + WGPUTextureFormat_R10X6BG10X6Biplanar444Unorm = 0x0005000C, + WGPUTextureFormat_External = 0x0005000D, + WGPUTextureFormat_Force32 = 0x7FFFFFFF +} WGPUTextureFormat WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUTextureSampleType { + WGPUTextureSampleType_BindingNotUsed = 0x00000000, + WGPUTextureSampleType_Float = 0x00000001, + WGPUTextureSampleType_UnfilterableFloat = 0x00000002, + WGPUTextureSampleType_Depth = 0x00000003, + WGPUTextureSampleType_Sint = 0x00000004, + WGPUTextureSampleType_Uint = 0x00000005, + WGPUTextureSampleType_Force32 = 0x7FFFFFFF +} WGPUTextureSampleType WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUTextureViewDimension { + WGPUTextureViewDimension_Undefined = 0x00000000, + WGPUTextureViewDimension_1D = 0x00000001, + WGPUTextureViewDimension_2D = 0x00000002, + WGPUTextureViewDimension_2DArray = 0x00000003, + WGPUTextureViewDimension_Cube = 0x00000004, + WGPUTextureViewDimension_CubeArray = 0x00000005, + WGPUTextureViewDimension_3D = 0x00000006, + WGPUTextureViewDimension_Force32 = 0x7FFFFFFF +} WGPUTextureViewDimension WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUVertexFormat { + WGPUVertexFormat_Uint8 = 0x00000001, + WGPUVertexFormat_Uint8x2 = 0x00000002, + WGPUVertexFormat_Uint8x4 = 0x00000003, + WGPUVertexFormat_Sint8 = 0x00000004, + WGPUVertexFormat_Sint8x2 = 0x00000005, + WGPUVertexFormat_Sint8x4 = 0x00000006, + WGPUVertexFormat_Unorm8 = 0x00000007, + WGPUVertexFormat_Unorm8x2 = 0x00000008, + WGPUVertexFormat_Unorm8x4 = 0x00000009, + WGPUVertexFormat_Snorm8 = 0x0000000A, + WGPUVertexFormat_Snorm8x2 = 0x0000000B, + WGPUVertexFormat_Snorm8x4 = 0x0000000C, + WGPUVertexFormat_Uint16 = 0x0000000D, + WGPUVertexFormat_Uint16x2 = 0x0000000E, + WGPUVertexFormat_Uint16x4 = 0x0000000F, + WGPUVertexFormat_Sint16 = 0x00000010, + WGPUVertexFormat_Sint16x2 = 0x00000011, + WGPUVertexFormat_Sint16x4 = 0x00000012, + WGPUVertexFormat_Unorm16 = 0x00000013, + WGPUVertexFormat_Unorm16x2 = 0x00000014, + WGPUVertexFormat_Unorm16x4 = 0x00000015, + WGPUVertexFormat_Snorm16 = 0x00000016, + WGPUVertexFormat_Snorm16x2 = 0x00000017, + WGPUVertexFormat_Snorm16x4 = 0x00000018, + WGPUVertexFormat_Float16 = 0x00000019, + WGPUVertexFormat_Float16x2 = 0x0000001A, + WGPUVertexFormat_Float16x4 = 0x0000001B, + WGPUVertexFormat_Float32 = 0x0000001C, + WGPUVertexFormat_Float32x2 = 0x0000001D, + WGPUVertexFormat_Float32x3 = 0x0000001E, + WGPUVertexFormat_Float32x4 = 0x0000001F, + WGPUVertexFormat_Uint32 = 0x00000020, + WGPUVertexFormat_Uint32x2 = 0x00000021, + WGPUVertexFormat_Uint32x3 = 0x00000022, + WGPUVertexFormat_Uint32x4 = 0x00000023, + WGPUVertexFormat_Sint32 = 0x00000024, + WGPUVertexFormat_Sint32x2 = 0x00000025, + WGPUVertexFormat_Sint32x3 = 0x00000026, + WGPUVertexFormat_Sint32x4 = 0x00000027, + WGPUVertexFormat_Unorm10_10_10_2 = 0x00000028, + WGPUVertexFormat_Unorm8x4BGRA = 0x00000029, + WGPUVertexFormat_Force32 = 0x7FFFFFFF +} WGPUVertexFormat WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUVertexStepMode { + WGPUVertexStepMode_Undefined = 0x00000000, + WGPUVertexStepMode_Vertex = 0x00000001, + WGPUVertexStepMode_Instance = 0x00000002, + WGPUVertexStepMode_Force32 = 0x7FFFFFFF +} WGPUVertexStepMode WGPU_ENUM_ATTRIBUTE; +typedef enum WGPUWaitStatus { + WGPUWaitStatus_Success = 0x00000001, + WGPUWaitStatus_TimedOut = 0x00000002, + WGPUWaitStatus_UnsupportedTimeout = 0x00000003, + WGPUWaitStatus_UnsupportedCount = 0x00000004, + WGPUWaitStatus_UnsupportedMixedSources = 0x00000005, + WGPUWaitStatus_Unknown = 0x00000006, + WGPUWaitStatus_Force32 = 0x7FFFFFFF +} WGPUWaitStatus WGPU_ENUM_ATTRIBUTE; + +typedef WGPUFlags WGPUBufferUsage; +static const WGPUBufferUsage WGPUBufferUsage_None = 0x0000000000000000; +static const WGPUBufferUsage WGPUBufferUsage_MapRead = 0x0000000000000001; +static const WGPUBufferUsage WGPUBufferUsage_MapWrite = 0x0000000000000002; +static const WGPUBufferUsage WGPUBufferUsage_CopySrc = 0x0000000000000004; +static const WGPUBufferUsage WGPUBufferUsage_CopyDst = 0x0000000000000008; +static const WGPUBufferUsage WGPUBufferUsage_Index = 0x0000000000000010; +static const WGPUBufferUsage WGPUBufferUsage_Vertex = 0x0000000000000020; +static const WGPUBufferUsage WGPUBufferUsage_Uniform = 0x0000000000000040; +static const WGPUBufferUsage WGPUBufferUsage_Storage = 0x0000000000000080; +static const WGPUBufferUsage WGPUBufferUsage_Indirect = 0x0000000000000100; +static const WGPUBufferUsage WGPUBufferUsage_QueryResolve = 0x0000000000000200; +typedef WGPUFlags WGPUColorWriteMask; +static const WGPUColorWriteMask WGPUColorWriteMask_None = 0x0000000000000000; +static const WGPUColorWriteMask WGPUColorWriteMask_Red = 0x0000000000000001; +static const WGPUColorWriteMask WGPUColorWriteMask_Green = 0x0000000000000002; +static const WGPUColorWriteMask WGPUColorWriteMask_Blue = 0x0000000000000004; +static const WGPUColorWriteMask WGPUColorWriteMask_Alpha = 0x0000000000000008; +static const WGPUColorWriteMask WGPUColorWriteMask_All = 0x000000000000000F; +typedef WGPUFlags WGPUHeapProperty; +static const WGPUHeapProperty WGPUHeapProperty_DeviceLocal = 0x0000000000000001; +static const WGPUHeapProperty WGPUHeapProperty_HostVisible = 0x0000000000000002; +static const WGPUHeapProperty WGPUHeapProperty_HostCoherent = 0x0000000000000004; +static const WGPUHeapProperty WGPUHeapProperty_HostUncached = 0x0000000000000008; +static const WGPUHeapProperty WGPUHeapProperty_HostCached = 0x0000000000000010; +typedef WGPUFlags WGPUMapMode; +static const WGPUMapMode WGPUMapMode_None = 0x0000000000000000; +static const WGPUMapMode WGPUMapMode_Read = 0x0000000000000001; +static const WGPUMapMode WGPUMapMode_Write = 0x0000000000000002; +typedef WGPUFlags WGPUShaderStage; +static const WGPUShaderStage WGPUShaderStage_None = 0x0000000000000000; +static const WGPUShaderStage WGPUShaderStage_Vertex = 0x0000000000000001; +static const WGPUShaderStage WGPUShaderStage_Fragment = 0x0000000000000002; +static const WGPUShaderStage WGPUShaderStage_Compute = 0x0000000000000004; +typedef WGPUFlags WGPUTextureUsage; +static const WGPUTextureUsage WGPUTextureUsage_None = 0x0000000000000000; +static const WGPUTextureUsage WGPUTextureUsage_CopySrc = 0x0000000000000001; +static const WGPUTextureUsage WGPUTextureUsage_CopyDst = 0x0000000000000002; +static const WGPUTextureUsage WGPUTextureUsage_TextureBinding = 0x0000000000000004; +static const WGPUTextureUsage WGPUTextureUsage_StorageBinding = 0x0000000000000008; +static const WGPUTextureUsage WGPUTextureUsage_RenderAttachment = 0x0000000000000010; +static const WGPUTextureUsage WGPUTextureUsage_TransientAttachment = 0x0000000000000020; +static const WGPUTextureUsage WGPUTextureUsage_StorageAttachment = 0x0000000000000040; +typedef void (*WGPUBufferMapCallback)(WGPUBufferMapAsyncStatus status, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCallback)(void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCompilationInfoCallback)(WGPUCompilationInfoRequestStatus status, struct WGPUCompilationInfo const * compilationInfo, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCreateComputePipelineAsyncCallback)(WGPUCreatePipelineAsyncStatus status, WGPUComputePipeline pipeline, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCreateRenderPipelineAsyncCallback)(WGPUCreatePipelineAsyncStatus status, WGPURenderPipeline pipeline, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef size_t (*WGPUDawnLoadCacheDataFunction)(void const * key, size_t keySize, void * value, size_t valueSize, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUDawnStoreCacheDataFunction)(void const * key, size_t keySize, void const * value, size_t valueSize, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUDeviceLostCallback)(WGPUDeviceLostReason reason, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUDeviceLostCallbackNew)(WGPUDevice const * device, WGPUDeviceLostReason reason, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUErrorCallback)(WGPUErrorType type, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPULoggingCallback)(WGPULoggingType type, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUPopErrorScopeCallback)(WGPUPopErrorScopeStatus status, WGPUErrorType type, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProc)(void) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUQueueWorkDoneCallback)(WGPUQueueWorkDoneStatus status, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPURequestAdapterCallback)(WGPURequestAdapterStatus status, WGPUAdapter adapter, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPURequestDeviceCallback)(WGPURequestDeviceStatus status, WGPUDevice device, struct WGPUStringView message, void * userdata) WGPU_FUNCTION_ATTRIBUTE; + +// Callback function pointers +typedef void (*WGPUBufferMapCallback2)(WGPUMapAsyncStatus status, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCompilationInfoCallback2)(WGPUCompilationInfoRequestStatus status, struct WGPUCompilationInfo const * compilationInfo, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCreateComputePipelineAsyncCallback2)(WGPUCreatePipelineAsyncStatus status, WGPUComputePipeline pipeline, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUCreateRenderPipelineAsyncCallback2)(WGPUCreatePipelineAsyncStatus status, WGPURenderPipeline pipeline, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUDeviceLostCallback2)(WGPUDevice const * device, WGPUDeviceLostReason reason, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUPopErrorScopeCallback2)(WGPUPopErrorScopeStatus status, WGPUErrorType type, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUQueueWorkDoneCallback2)(WGPUQueueWorkDoneStatus status, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPURequestAdapterCallback2)(WGPURequestAdapterStatus status, WGPUAdapter adapter, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPURequestDeviceCallback2)(WGPURequestDeviceStatus status, WGPUDevice device, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUUncapturedErrorCallback)(WGPUDevice const * device, WGPUErrorType type, struct WGPUStringView message, void* userdata1, void* userdata2) WGPU_FUNCTION_ATTRIBUTE; + +typedef struct WGPUChainedStruct { + struct WGPUChainedStruct const * next; + WGPUSType sType; +} WGPUChainedStruct WGPU_STRUCTURE_ATTRIBUTE; + +typedef struct WGPUChainedStructOut { + struct WGPUChainedStructOut * next; + WGPUSType sType; +} WGPUChainedStructOut WGPU_STRUCTURE_ATTRIBUTE; + + +#define WGPU_COMMA , + +typedef struct WGPUBufferMapCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUBufferMapCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUBufferMapCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BUFFER_MAP_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUBufferMapCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUCompilationInfoCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUCompilationInfoCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUCompilationInfoCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPILATION_INFO_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUCompilationInfoCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUCreateComputePipelineAsyncCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUCreateComputePipelineAsyncCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUCreateComputePipelineAsyncCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_CREATE_COMPUTE_PIPELINE_ASYNC_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUCreateComputePipelineAsyncCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUCreateRenderPipelineAsyncCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUCreateRenderPipelineAsyncCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUCreateRenderPipelineAsyncCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_CREATE_RENDER_PIPELINE_ASYNC_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUCreateRenderPipelineAsyncCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUDeviceLostCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUDeviceLostCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUDeviceLostCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DEVICE_LOST_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUDeviceLostCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUPopErrorScopeCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUPopErrorScopeCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUPopErrorScopeCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_POP_ERROR_SCOPE_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUPopErrorScopeCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUQueueWorkDoneCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPUQueueWorkDoneCallback2 callback; + void* userdata1; + void* userdata2; +} WGPUQueueWorkDoneCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_QUEUE_WORK_DONE_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUQueueWorkDoneCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPURequestAdapterCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPURequestAdapterCallback2 callback; + void* userdata1; + void* userdata2; +} WGPURequestAdapterCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUEST_ADAPTER_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPURequestAdapterCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPURequestDeviceCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUCallbackMode mode; + WGPURequestDeviceCallback2 callback; + void* userdata1; + void* userdata2; +} WGPURequestDeviceCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUEST_DEVICE_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPURequestDeviceCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUUncapturedErrorCallbackInfo2 { + WGPUChainedStruct const* nextInChain; + WGPUUncapturedErrorCallback callback; + void* userdata1; + void* userdata2; +} WGPUUncapturedErrorCallbackInfo2 WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_UNCAPTURED_ERROR_CALLBACK_INFO_2_INIT WGPU_MAKE_INIT_STRUCT(WGPUUncapturedErrorCallbackInfo2, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata1=*/nullptr WGPU_COMMA \ + /*.userdata2=*/nullptr WGPU_COMMA \ +}) + + +typedef struct WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER { + WGPUBool unused; +} WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_INTERNAL__HAVE_EMDAWNWEBGPU_HEADER_INIT WGPU_MAKE_INIT_STRUCT(WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER, { \ + /*.unused=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUAdapterInfo +typedef struct WGPUAdapterPropertiesD3D { + WGPUChainedStructOut chain; + uint32_t shaderModel; +} WGPUAdapterPropertiesD3D WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ADAPTER_PROPERTIES_D3D_INIT WGPU_MAKE_INIT_STRUCT(WGPUAdapterPropertiesD3D, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_AdapterPropertiesD3D} WGPU_COMMA \ + /*.shaderModel=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUAdapterInfo +typedef struct WGPUAdapterPropertiesSubgroups { + WGPUChainedStructOut chain; + uint32_t subgroupMinSize; + uint32_t subgroupMaxSize; +} WGPUAdapterPropertiesSubgroups WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ADAPTER_PROPERTIES_SUBGROUPS_INIT WGPU_MAKE_INIT_STRUCT(WGPUAdapterPropertiesSubgroups, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_AdapterPropertiesSubgroups} WGPU_COMMA \ + /*.subgroupMinSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.subgroupMaxSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +// Can be chained in WGPUAdapterInfo +typedef struct WGPUAdapterPropertiesVk { + WGPUChainedStructOut chain; + uint32_t driverVersion; +} WGPUAdapterPropertiesVk WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ADAPTER_PROPERTIES_VK_INIT WGPU_MAKE_INIT_STRUCT(WGPUAdapterPropertiesVk, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_AdapterPropertiesVk} WGPU_COMMA \ + /*.driverVersion=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUBindGroupEntry { + WGPUChainedStruct const * nextInChain; + uint32_t binding; + WGPU_NULLABLE WGPUBuffer buffer; + uint64_t offset; + uint64_t size; + WGPU_NULLABLE WGPUSampler sampler; + WGPU_NULLABLE WGPUTextureView textureView; +} WGPUBindGroupEntry WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BIND_GROUP_ENTRY_INIT WGPU_MAKE_INIT_STRUCT(WGPUBindGroupEntry, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.binding=*/{} WGPU_COMMA \ + /*.buffer=*/nullptr WGPU_COMMA \ + /*.offset=*/0 WGPU_COMMA \ + /*.size=*/WGPU_WHOLE_SIZE WGPU_COMMA \ + /*.sampler=*/nullptr WGPU_COMMA \ + /*.textureView=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUBlendComponent { + WGPUBlendOperation operation; + WGPUBlendFactor srcFactor; + WGPUBlendFactor dstFactor; +} WGPUBlendComponent WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BLEND_COMPONENT_INIT WGPU_MAKE_INIT_STRUCT(WGPUBlendComponent, { \ + /*.operation=*/WGPUBlendOperation_Add WGPU_COMMA \ + /*.srcFactor=*/WGPUBlendFactor_One WGPU_COMMA \ + /*.dstFactor=*/WGPUBlendFactor_Zero WGPU_COMMA \ +}) + +typedef struct WGPUBufferBindingLayout { + WGPUChainedStruct const * nextInChain; + WGPUBufferBindingType type; + WGPUBool hasDynamicOffset; + uint64_t minBindingSize; +} WGPUBufferBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BUFFER_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUBufferBindingLayout, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.type=*/WGPUBufferBindingType_BindingNotUsed WGPU_COMMA \ + /*.hasDynamicOffset=*/false WGPU_COMMA \ + /*.minBindingSize=*/0 WGPU_COMMA \ +}) + +// Can be chained in WGPUBufferDescriptor +typedef struct WGPUBufferHostMappedPointer { + WGPUChainedStruct chain; + void * pointer; + WGPUCallback disposeCallback; + void * userdata; +} WGPUBufferHostMappedPointer WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BUFFER_HOST_MAPPED_POINTER_INIT WGPU_MAKE_INIT_STRUCT(WGPUBufferHostMappedPointer, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_BufferHostMappedPointer} WGPU_COMMA \ + /*.pointer=*/{} WGPU_COMMA \ + /*.disposeCallback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUBufferMapCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUBufferMapCallback callback; + void * userdata; +} WGPUBufferMapCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BUFFER_MAP_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUBufferMapCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUColor { + double r; + double g; + double b; + double a; +} WGPUColor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COLOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUColor, { \ + /*.r=*/{} WGPU_COMMA \ + /*.g=*/{} WGPU_COMMA \ + /*.b=*/{} WGPU_COMMA \ + /*.a=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUColorTargetState +typedef struct WGPUColorTargetStateExpandResolveTextureDawn { + WGPUChainedStruct chain; + WGPUBool enabled; +} WGPUColorTargetStateExpandResolveTextureDawn WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COLOR_TARGET_STATE_EXPAND_RESOLVE_TEXTURE_DAWN_INIT WGPU_MAKE_INIT_STRUCT(WGPUColorTargetStateExpandResolveTextureDawn, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ColorTargetStateExpandResolveTextureDawn} WGPU_COMMA \ + /*.enabled=*/false WGPU_COMMA \ +}) + +typedef struct WGPUCompilationInfoCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUCompilationInfoCallback callback; + void * userdata; +} WGPUCompilationInfoCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPILATION_INFO_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUCompilationInfoCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUComputePassTimestampWrites { + WGPUQuerySet querySet; + uint32_t beginningOfPassWriteIndex; + uint32_t endOfPassWriteIndex; +} WGPUComputePassTimestampWrites WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPUTE_PASS_TIMESTAMP_WRITES_INIT WGPU_MAKE_INIT_STRUCT(WGPUComputePassTimestampWrites, { \ + /*.querySet=*/{} WGPU_COMMA \ + /*.beginningOfPassWriteIndex=*/WGPU_QUERY_SET_INDEX_UNDEFINED WGPU_COMMA \ + /*.endOfPassWriteIndex=*/WGPU_QUERY_SET_INDEX_UNDEFINED WGPU_COMMA \ +}) + +typedef struct WGPUCopyTextureForBrowserOptions { + WGPUChainedStruct const * nextInChain; + WGPUBool flipY; + WGPUBool needsColorSpaceConversion; + WGPUAlphaMode srcAlphaMode; + WGPU_NULLABLE float const * srcTransferFunctionParameters; + WGPU_NULLABLE float const * conversionMatrix; + WGPU_NULLABLE float const * dstTransferFunctionParameters; + WGPUAlphaMode dstAlphaMode; + WGPUBool internalUsage; +} WGPUCopyTextureForBrowserOptions WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COPY_TEXTURE_FOR_BROWSER_OPTIONS_INIT WGPU_MAKE_INIT_STRUCT(WGPUCopyTextureForBrowserOptions, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.flipY=*/false WGPU_COMMA \ + /*.needsColorSpaceConversion=*/false WGPU_COMMA \ + /*.srcAlphaMode=*/WGPUAlphaMode_Unpremultiplied WGPU_COMMA \ + /*.srcTransferFunctionParameters=*/nullptr WGPU_COMMA \ + /*.conversionMatrix=*/nullptr WGPU_COMMA \ + /*.dstTransferFunctionParameters=*/nullptr WGPU_COMMA \ + /*.dstAlphaMode=*/WGPUAlphaMode_Unpremultiplied WGPU_COMMA \ + /*.internalUsage=*/false WGPU_COMMA \ +}) + +typedef struct WGPUCreateComputePipelineAsyncCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUCreateComputePipelineAsyncCallback callback; + void * userdata; +} WGPUCreateComputePipelineAsyncCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_CREATE_COMPUTE_PIPELINE_ASYNC_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUCreateComputePipelineAsyncCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUCreateRenderPipelineAsyncCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUCreateRenderPipelineAsyncCallback callback; + void * userdata; +} WGPUCreateRenderPipelineAsyncCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_CREATE_RENDER_PIPELINE_ASYNC_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUCreateRenderPipelineAsyncCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUInstanceDescriptor +typedef struct WGPUDawnWGSLBlocklist { + WGPUChainedStruct chain; + size_t blocklistedFeatureCount; + const char* const * blocklistedFeatures; +} WGPUDawnWGSLBlocklist WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_WGSL_BLOCKLIST_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnWGSLBlocklist, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnWGSLBlocklist} WGPU_COMMA \ + /*.blocklistedFeatureCount=*/0 WGPU_COMMA \ + /*.blocklistedFeatures=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUAdapterInfo +typedef struct WGPUDawnAdapterPropertiesPowerPreference { + WGPUChainedStructOut chain; + WGPUPowerPreference powerPreference; +} WGPUDawnAdapterPropertiesPowerPreference WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_ADAPTER_PROPERTIES_POWER_PREFERENCE_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnAdapterPropertiesPowerPreference, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnAdapterPropertiesPowerPreference} WGPU_COMMA \ + /*.powerPreference=*/WGPUPowerPreference_Undefined WGPU_COMMA \ +}) + +// Can be chained in WGPUBufferDescriptor +typedef struct WGPUDawnBufferDescriptorErrorInfoFromWireClient { + WGPUChainedStruct chain; + WGPUBool outOfMemory; +} WGPUDawnBufferDescriptorErrorInfoFromWireClient WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_BUFFER_DESCRIPTOR_ERROR_INFO_FROM_WIRE_CLIENT_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnBufferDescriptorErrorInfoFromWireClient, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnBufferDescriptorErrorInfoFromWireClient} WGPU_COMMA \ + /*.outOfMemory=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUCommandEncoderDescriptor +typedef struct WGPUDawnEncoderInternalUsageDescriptor { + WGPUChainedStruct chain; + WGPUBool useInternalUsages; +} WGPUDawnEncoderInternalUsageDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_ENCODER_INTERNAL_USAGE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnEncoderInternalUsageDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnEncoderInternalUsageDescriptor} WGPU_COMMA \ + /*.useInternalUsages=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUSupportedLimits +typedef struct WGPUDawnExperimentalImmediateDataLimits { + WGPUChainedStructOut chain; + uint32_t maxImmediateDataRangeByteSize; +} WGPUDawnExperimentalImmediateDataLimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_EXPERIMENTAL_IMMEDIATE_DATA_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnExperimentalImmediateDataLimits, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnExperimentalImmediateDataLimits} WGPU_COMMA \ + /*.maxImmediateDataRangeByteSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +// Can be chained in WGPUSupportedLimits +typedef struct WGPUDawnExperimentalSubgroupLimits { + WGPUChainedStructOut chain; + uint32_t minSubgroupSize; + uint32_t maxSubgroupSize; +} WGPUDawnExperimentalSubgroupLimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_EXPERIMENTAL_SUBGROUP_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnExperimentalSubgroupLimits, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnExperimentalSubgroupLimits} WGPU_COMMA \ + /*.minSubgroupSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxSubgroupSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +// Can be chained in WGPURenderPassColorAttachment +typedef struct WGPUDawnRenderPassColorAttachmentRenderToSingleSampled { + WGPUChainedStruct chain; + uint32_t implicitSampleCount; +} WGPUDawnRenderPassColorAttachmentRenderToSingleSampled WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_RENDER_PASS_COLOR_ATTACHMENT_RENDER_TO_SINGLE_SAMPLED_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnRenderPassColorAttachmentRenderToSingleSampled, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnRenderPassColorAttachmentRenderToSingleSampled} WGPU_COMMA \ + /*.implicitSampleCount=*/1 WGPU_COMMA \ +}) + +// Can be chained in WGPUShaderModuleDescriptor +typedef struct WGPUDawnShaderModuleSPIRVOptionsDescriptor { + WGPUChainedStruct chain; + WGPUBool allowNonUniformDerivatives; +} WGPUDawnShaderModuleSPIRVOptionsDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_SHADER_MODULE_SPIRV_OPTIONS_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnShaderModuleSPIRVOptionsDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnShaderModuleSPIRVOptionsDescriptor} WGPU_COMMA \ + /*.allowNonUniformDerivatives=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUSupportedLimits +typedef struct WGPUDawnTexelCopyBufferRowAlignmentLimits { + WGPUChainedStructOut chain; + uint32_t minTexelCopyBufferRowAlignment; +} WGPUDawnTexelCopyBufferRowAlignmentLimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_TEXEL_COPY_BUFFER_ROW_ALIGNMENT_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnTexelCopyBufferRowAlignmentLimits, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnTexelCopyBufferRowAlignmentLimits} WGPU_COMMA \ + /*.minTexelCopyBufferRowAlignment=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +// Can be chained in WGPUTextureDescriptor +typedef struct WGPUDawnTextureInternalUsageDescriptor { + WGPUChainedStruct chain; + WGPUTextureUsage internalUsage; +} WGPUDawnTextureInternalUsageDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_TEXTURE_INTERNAL_USAGE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnTextureInternalUsageDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnTextureInternalUsageDescriptor} WGPU_COMMA \ + /*.internalUsage=*/WGPUTextureUsage_None WGPU_COMMA \ +}) + +// Can be chained in WGPUInstanceDescriptor +// Can be chained in WGPURequestAdapterOptions +// Can be chained in WGPUDeviceDescriptor +typedef struct WGPUDawnTogglesDescriptor { + WGPUChainedStruct chain; + size_t enabledToggleCount; + const char* const * enabledToggles; + size_t disabledToggleCount; + const char* const * disabledToggles; +} WGPUDawnTogglesDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_TOGGLES_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnTogglesDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnTogglesDescriptor} WGPU_COMMA \ + /*.enabledToggleCount=*/0 WGPU_COMMA \ + /*.enabledToggles=*/{} WGPU_COMMA \ + /*.disabledToggleCount=*/0 WGPU_COMMA \ + /*.disabledToggles=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUInstanceDescriptor +typedef struct WGPUDawnWireWGSLControl { + WGPUChainedStruct chain; + WGPUBool enableExperimental; + WGPUBool enableUnsafe; + WGPUBool enableTesting; +} WGPUDawnWireWGSLControl WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_WIRE_WGSL_CONTROL_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnWireWGSLControl, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnWireWGSLControl} WGPU_COMMA \ + /*.enableExperimental=*/false WGPU_COMMA \ + /*.enableUnsafe=*/false WGPU_COMMA \ + /*.enableTesting=*/false WGPU_COMMA \ +}) + +typedef struct WGPUDeviceLostCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUDeviceLostCallbackNew callback; + void * userdata; +} WGPUDeviceLostCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DEVICE_LOST_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUDeviceLostCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/WGPUCallbackMode_WaitAnyOnly WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUDrmFormatProperties { + uint64_t modifier; + uint32_t modifierPlaneCount; +} WGPUDrmFormatProperties WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DRM_FORMAT_PROPERTIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUDrmFormatProperties, { \ + /*.modifier=*/{} WGPU_COMMA \ + /*.modifierPlaneCount=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUExtent2D { + uint32_t width; + uint32_t height; +} WGPUExtent2D WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_EXTENT_2D_INIT WGPU_MAKE_INIT_STRUCT(WGPUExtent2D, { \ + /*.width=*/{} WGPU_COMMA \ + /*.height=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUExtent3D { + uint32_t width; + uint32_t height; + uint32_t depthOrArrayLayers; +} WGPUExtent3D WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_EXTENT_3D_INIT WGPU_MAKE_INIT_STRUCT(WGPUExtent3D, { \ + /*.width=*/{} WGPU_COMMA \ + /*.height=*/1 WGPU_COMMA \ + /*.depthOrArrayLayers=*/1 WGPU_COMMA \ +}) + +// Can be chained in WGPUBindGroupEntry +typedef struct WGPUExternalTextureBindingEntry { + WGPUChainedStruct chain; + WGPUExternalTexture externalTexture; +} WGPUExternalTextureBindingEntry WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_EXTERNAL_TEXTURE_BINDING_ENTRY_INIT WGPU_MAKE_INIT_STRUCT(WGPUExternalTextureBindingEntry, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ExternalTextureBindingEntry} WGPU_COMMA \ + /*.externalTexture=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUBindGroupLayoutEntry +typedef struct WGPUExternalTextureBindingLayout { + WGPUChainedStruct chain; +} WGPUExternalTextureBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_EXTERNAL_TEXTURE_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUExternalTextureBindingLayout, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ExternalTextureBindingLayout} WGPU_COMMA \ +}) + +typedef struct WGPUFormatCapabilities { + WGPUChainedStructOut * nextInChain; +} WGPUFormatCapabilities WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_FORMAT_CAPABILITIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUFormatCapabilities, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUFuture { + uint64_t id; +} WGPUFuture WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_FUTURE_INIT WGPU_MAKE_INIT_STRUCT(WGPUFuture, { \ + /*.id=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUInstanceFeatures { + WGPUChainedStruct const * nextInChain; + WGPUBool timedWaitAnyEnable; + size_t timedWaitAnyMaxCount; +} WGPUInstanceFeatures WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_INSTANCE_FEATURES_INIT WGPU_MAKE_INIT_STRUCT(WGPUInstanceFeatures, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.timedWaitAnyEnable=*/false WGPU_COMMA \ + /*.timedWaitAnyMaxCount=*/0 WGPU_COMMA \ +}) + +typedef struct WGPULimits { + uint32_t maxTextureDimension1D; + uint32_t maxTextureDimension2D; + uint32_t maxTextureDimension3D; + uint32_t maxTextureArrayLayers; + uint32_t maxBindGroups; + uint32_t maxBindGroupsPlusVertexBuffers; + uint32_t maxBindingsPerBindGroup; + uint32_t maxDynamicUniformBuffersPerPipelineLayout; + uint32_t maxDynamicStorageBuffersPerPipelineLayout; + uint32_t maxSampledTexturesPerShaderStage; + uint32_t maxSamplersPerShaderStage; + uint32_t maxStorageBuffersPerShaderStage; + uint32_t maxStorageTexturesPerShaderStage; + uint32_t maxUniformBuffersPerShaderStage; + uint64_t maxUniformBufferBindingSize; + uint64_t maxStorageBufferBindingSize; + uint32_t minUniformBufferOffsetAlignment; + uint32_t minStorageBufferOffsetAlignment; + uint32_t maxVertexBuffers; + uint64_t maxBufferSize; + uint32_t maxVertexAttributes; + uint32_t maxVertexBufferArrayStride; + uint32_t maxInterStageShaderComponents; + uint32_t maxInterStageShaderVariables; + uint32_t maxColorAttachments; + uint32_t maxColorAttachmentBytesPerSample; + uint32_t maxComputeWorkgroupStorageSize; + uint32_t maxComputeInvocationsPerWorkgroup; + uint32_t maxComputeWorkgroupSizeX; + uint32_t maxComputeWorkgroupSizeY; + uint32_t maxComputeWorkgroupSizeZ; + uint32_t maxComputeWorkgroupsPerDimension; + uint32_t maxStorageBuffersInVertexStage; + uint32_t maxStorageTexturesInVertexStage; + uint32_t maxStorageBuffersInFragmentStage; + uint32_t maxStorageTexturesInFragmentStage; +} WGPULimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPULimits, { \ + /*.maxTextureDimension1D=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxTextureDimension2D=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxTextureDimension3D=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxTextureArrayLayers=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxBindGroups=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxBindGroupsPlusVertexBuffers=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxBindingsPerBindGroup=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxDynamicUniformBuffersPerPipelineLayout=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxDynamicStorageBuffersPerPipelineLayout=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxSampledTexturesPerShaderStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxSamplersPerShaderStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageBuffersPerShaderStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageTexturesPerShaderStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxUniformBuffersPerShaderStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxUniformBufferBindingSize=*/WGPU_LIMIT_U64_UNDEFINED WGPU_COMMA \ + /*.maxStorageBufferBindingSize=*/WGPU_LIMIT_U64_UNDEFINED WGPU_COMMA \ + /*.minUniformBufferOffsetAlignment=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.minStorageBufferOffsetAlignment=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxVertexBuffers=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxBufferSize=*/WGPU_LIMIT_U64_UNDEFINED WGPU_COMMA \ + /*.maxVertexAttributes=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxVertexBufferArrayStride=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxInterStageShaderComponents=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxInterStageShaderVariables=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxColorAttachments=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxColorAttachmentBytesPerSample=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeWorkgroupStorageSize=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeInvocationsPerWorkgroup=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeWorkgroupSizeX=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeWorkgroupSizeY=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeWorkgroupSizeZ=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxComputeWorkgroupsPerDimension=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageBuffersInVertexStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageTexturesInVertexStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageBuffersInFragmentStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ + /*.maxStorageTexturesInFragmentStage=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +typedef struct WGPUMemoryHeapInfo { + WGPUHeapProperty properties; + uint64_t size; +} WGPUMemoryHeapInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_MEMORY_HEAP_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUMemoryHeapInfo, { \ + /*.properties=*/{} WGPU_COMMA \ + /*.size=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUMultisampleState { + WGPUChainedStruct const * nextInChain; + uint32_t count; + uint32_t mask; + WGPUBool alphaToCoverageEnabled; +} WGPUMultisampleState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_MULTISAMPLE_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUMultisampleState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.count=*/1 WGPU_COMMA \ + /*.mask=*/0xFFFFFFFF WGPU_COMMA \ + /*.alphaToCoverageEnabled=*/false WGPU_COMMA \ +}) + +typedef struct WGPUOrigin2D { + uint32_t x; + uint32_t y; +} WGPUOrigin2D WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ORIGIN_2D_INIT WGPU_MAKE_INIT_STRUCT(WGPUOrigin2D, { \ + /*.x=*/0 WGPU_COMMA \ + /*.y=*/0 WGPU_COMMA \ +}) + +typedef struct WGPUOrigin3D { + uint32_t x; + uint32_t y; + uint32_t z; +} WGPUOrigin3D WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ORIGIN_3D_INIT WGPU_MAKE_INIT_STRUCT(WGPUOrigin3D, { \ + /*.x=*/0 WGPU_COMMA \ + /*.y=*/0 WGPU_COMMA \ + /*.z=*/0 WGPU_COMMA \ +}) + +typedef struct WGPUPipelineLayoutStorageAttachment { + uint64_t offset; + WGPUTextureFormat format; +} WGPUPipelineLayoutStorageAttachment WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_PIPELINE_LAYOUT_STORAGE_ATTACHMENT_INIT WGPU_MAKE_INIT_STRUCT(WGPUPipelineLayoutStorageAttachment, { \ + /*.offset=*/0 WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUPopErrorScopeCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUPopErrorScopeCallback callback; + WGPUErrorCallback oldCallback; + void * userdata; +} WGPUPopErrorScopeCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_POP_ERROR_SCOPE_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUPopErrorScopeCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/WGPUCallbackMode_WaitAnyOnly WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.oldCallback=*/{} WGPU_COMMA \ + /*.userdata=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUPrimitiveState { + WGPUChainedStruct const * nextInChain; + WGPUPrimitiveTopology topology; + WGPUIndexFormat stripIndexFormat; + WGPUFrontFace frontFace; + WGPUCullMode cullMode; + WGPUBool unclippedDepth; +} WGPUPrimitiveState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_PRIMITIVE_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUPrimitiveState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.topology=*/WGPUPrimitiveTopology_TriangleList WGPU_COMMA \ + /*.stripIndexFormat=*/WGPUIndexFormat_Undefined WGPU_COMMA \ + /*.frontFace=*/WGPUFrontFace_CCW WGPU_COMMA \ + /*.cullMode=*/WGPUCullMode_None WGPU_COMMA \ + /*.unclippedDepth=*/false WGPU_COMMA \ +}) + +typedef struct WGPUQueueWorkDoneCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPUQueueWorkDoneCallback callback; + void * userdata; +} WGPUQueueWorkDoneCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_QUEUE_WORK_DONE_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUQueueWorkDoneCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPURenderPassDepthStencilAttachment { + WGPUTextureView view; + WGPULoadOp depthLoadOp; + WGPUStoreOp depthStoreOp; + float depthClearValue; + WGPUBool depthReadOnly; + WGPULoadOp stencilLoadOp; + WGPUStoreOp stencilStoreOp; + uint32_t stencilClearValue; + WGPUBool stencilReadOnly; +} WGPURenderPassDepthStencilAttachment WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_DEPTH_STENCIL_ATTACHMENT_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassDepthStencilAttachment, { \ + /*.view=*/{} WGPU_COMMA \ + /*.depthLoadOp=*/WGPULoadOp_Undefined WGPU_COMMA \ + /*.depthStoreOp=*/WGPUStoreOp_Undefined WGPU_COMMA \ + /*.depthClearValue=*/NAN WGPU_COMMA \ + /*.depthReadOnly=*/false WGPU_COMMA \ + /*.stencilLoadOp=*/WGPULoadOp_Undefined WGPU_COMMA \ + /*.stencilStoreOp=*/WGPUStoreOp_Undefined WGPU_COMMA \ + /*.stencilClearValue=*/0 WGPU_COMMA \ + /*.stencilReadOnly=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPURenderPassDescriptor +typedef struct WGPURenderPassDescriptorExpandResolveRect { + WGPUChainedStruct chain; + uint32_t x; + uint32_t y; + uint32_t width; + uint32_t height; +} WGPURenderPassDescriptorExpandResolveRect WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_DESCRIPTOR_EXPAND_RESOLVE_RECT_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassDescriptorExpandResolveRect, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_RenderPassDescriptorExpandResolveRect} WGPU_COMMA \ + /*.x=*/{} WGPU_COMMA \ + /*.y=*/{} WGPU_COMMA \ + /*.width=*/{} WGPU_COMMA \ + /*.height=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPURenderPassDescriptor +typedef struct WGPURenderPassMaxDrawCount { + WGPUChainedStruct chain; + uint64_t maxDrawCount; +} WGPURenderPassMaxDrawCount WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_MAX_DRAW_COUNT_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassMaxDrawCount, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_RenderPassMaxDrawCount} WGPU_COMMA \ + /*.maxDrawCount=*/50000000 WGPU_COMMA \ +}) + +typedef struct WGPURenderPassTimestampWrites { + WGPUQuerySet querySet; + uint32_t beginningOfPassWriteIndex; + uint32_t endOfPassWriteIndex; +} WGPURenderPassTimestampWrites WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_TIMESTAMP_WRITES_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassTimestampWrites, { \ + /*.querySet=*/{} WGPU_COMMA \ + /*.beginningOfPassWriteIndex=*/WGPU_QUERY_SET_INDEX_UNDEFINED WGPU_COMMA \ + /*.endOfPassWriteIndex=*/WGPU_QUERY_SET_INDEX_UNDEFINED WGPU_COMMA \ +}) + +typedef struct WGPURequestAdapterCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPURequestAdapterCallback callback; + void * userdata; +} WGPURequestAdapterCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUEST_ADAPTER_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPURequestAdapterCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPURequestAdapterOptions { + WGPUChainedStruct const * nextInChain; + WGPU_NULLABLE WGPUSurface compatibleSurface; + WGPUFeatureLevel featureLevel; + WGPUPowerPreference powerPreference; + WGPUBackendType backendType; + WGPUBool forceFallbackAdapter; + WGPUBool compatibilityMode; +} WGPURequestAdapterOptions WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUEST_ADAPTER_OPTIONS_INIT WGPU_MAKE_INIT_STRUCT(WGPURequestAdapterOptions, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.compatibleSurface=*/nullptr WGPU_COMMA \ + /*.featureLevel=*/WGPUFeatureLevel_Core WGPU_COMMA \ + /*.powerPreference=*/WGPUPowerPreference_Undefined WGPU_COMMA \ + /*.backendType=*/WGPUBackendType_Undefined WGPU_COMMA \ + /*.forceFallbackAdapter=*/false WGPU_COMMA \ + /*.compatibilityMode=*/false WGPU_COMMA \ +}) + +typedef struct WGPURequestDeviceCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUCallbackMode mode; + WGPURequestDeviceCallback callback; + void * userdata; +} WGPURequestDeviceCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUEST_DEVICE_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPURequestDeviceCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.mode=*/{} WGPU_COMMA \ + /*.callback=*/{} WGPU_COMMA \ + /*.userdata=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSamplerBindingLayout { + WGPUChainedStruct const * nextInChain; + WGPUSamplerBindingType type; +} WGPUSamplerBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SAMPLER_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUSamplerBindingLayout, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.type=*/WGPUSamplerBindingType_BindingNotUsed WGPU_COMMA \ +}) + +// Can be chained in WGPUShaderModuleDescriptor +typedef struct WGPUShaderModuleCompilationOptions { + WGPUChainedStruct chain; + WGPUBool strictMath; +} WGPUShaderModuleCompilationOptions WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHADER_MODULE_COMPILATION_OPTIONS_INIT WGPU_MAKE_INIT_STRUCT(WGPUShaderModuleCompilationOptions, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ShaderModuleCompilationOptions} WGPU_COMMA \ + /*.strictMath=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUShaderModuleDescriptor +typedef struct WGPUShaderSourceSPIRV { + WGPUChainedStruct chain; + uint32_t codeSize; + uint32_t const * code; +} WGPUShaderSourceSPIRV WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHADER_SOURCE_SPIRV_INIT WGPU_MAKE_INIT_STRUCT(WGPUShaderSourceSPIRV, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ShaderSourceSPIRV} WGPU_COMMA \ + /*.codeSize=*/{} WGPU_COMMA \ + /*.code=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedBufferMemoryBeginAccessDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUBool initialized; + size_t fenceCount; + WGPUSharedFence const * fences; + uint64_t const * signaledValues; +} WGPUSharedBufferMemoryBeginAccessDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_BUFFER_MEMORY_BEGIN_ACCESS_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedBufferMemoryBeginAccessDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.initialized=*/{} WGPU_COMMA \ + /*.fenceCount=*/0 WGPU_COMMA \ + /*.fences=*/{} WGPU_COMMA \ + /*.signaledValues=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedBufferMemoryEndAccessState { + WGPUChainedStructOut * nextInChain; + WGPUBool initialized; + size_t fenceCount; + WGPUSharedFence const * fences; + uint64_t const * signaledValues; +} WGPUSharedBufferMemoryEndAccessState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_BUFFER_MEMORY_END_ACCESS_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedBufferMemoryEndAccessState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.initialized=*/{} WGPU_COMMA \ + /*.fenceCount=*/0 WGPU_COMMA \ + /*.fences=*/{} WGPU_COMMA \ + /*.signaledValues=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedBufferMemoryProperties { + WGPUChainedStructOut * nextInChain; + WGPUBufferUsage usage; + uint64_t size; +} WGPUSharedBufferMemoryProperties WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_BUFFER_MEMORY_PROPERTIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedBufferMemoryProperties, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.usage=*/{} WGPU_COMMA \ + /*.size=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceDescriptor +typedef struct WGPUSharedFenceDXGISharedHandleDescriptor { + WGPUChainedStruct chain; + void * handle; +} WGPUSharedFenceDXGISharedHandleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_DXGI_SHARED_HANDLE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceDXGISharedHandleDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceDXGISharedHandleDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceExportInfo +typedef struct WGPUSharedFenceDXGISharedHandleExportInfo { + WGPUChainedStructOut chain; + void * handle; +} WGPUSharedFenceDXGISharedHandleExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_DXGI_SHARED_HANDLE_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceDXGISharedHandleExportInfo, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceDXGISharedHandleExportInfo} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceDescriptor +typedef struct WGPUSharedFenceMTLSharedEventDescriptor { + WGPUChainedStruct chain; + void * sharedEvent; +} WGPUSharedFenceMTLSharedEventDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_MTL_SHARED_EVENT_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceMTLSharedEventDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceMTLSharedEventDescriptor} WGPU_COMMA \ + /*.sharedEvent=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceExportInfo +typedef struct WGPUSharedFenceMTLSharedEventExportInfo { + WGPUChainedStructOut chain; + void * sharedEvent; +} WGPUSharedFenceMTLSharedEventExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_MTL_SHARED_EVENT_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceMTLSharedEventExportInfo, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceMTLSharedEventExportInfo} WGPU_COMMA \ + /*.sharedEvent=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedFenceExportInfo { + WGPUChainedStructOut * nextInChain; + WGPUSharedFenceType type; +} WGPUSharedFenceExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceExportInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.type=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceDescriptor +typedef struct WGPUSharedFenceSyncFDDescriptor { + WGPUChainedStruct chain; + int handle; +} WGPUSharedFenceSyncFDDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_SYNC_FD_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceSyncFDDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceSyncFDDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceExportInfo +typedef struct WGPUSharedFenceSyncFDExportInfo { + WGPUChainedStructOut chain; + int handle; +} WGPUSharedFenceSyncFDExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_SYNC_FD_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceSyncFDExportInfo, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceSyncFDExportInfo} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceDescriptor +typedef struct WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor { + WGPUChainedStruct chain; + int handle; +} WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_VK_SEMAPHORE_OPAQUE_FD_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceVkSemaphoreOpaqueFDDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceExportInfo +typedef struct WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo { + WGPUChainedStructOut chain; + int handle; +} WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_VK_SEMAPHORE_OPAQUE_FD_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceVkSemaphoreOpaqueFDExportInfo} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceDescriptor +typedef struct WGPUSharedFenceVkSemaphoreZirconHandleDescriptor { + WGPUChainedStruct chain; + uint32_t handle; +} WGPUSharedFenceVkSemaphoreZirconHandleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_VK_SEMAPHORE_ZIRCON_HANDLE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceVkSemaphoreZirconHandleDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceVkSemaphoreZirconHandleDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedFenceExportInfo +typedef struct WGPUSharedFenceVkSemaphoreZirconHandleExportInfo { + WGPUChainedStructOut chain; + uint32_t handle; +} WGPUSharedFenceVkSemaphoreZirconHandleExportInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_VK_SEMAPHORE_ZIRCON_HANDLE_EXPORT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceVkSemaphoreZirconHandleExportInfo, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedFenceVkSemaphoreZirconHandleExportInfo} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryBeginAccessDescriptor +typedef struct WGPUSharedTextureMemoryD3DSwapchainBeginState { + WGPUChainedStruct chain; + WGPUBool isSwapchain; +} WGPUSharedTextureMemoryD3DSwapchainBeginState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_D3D_SWAPCHAIN_BEGIN_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryD3DSwapchainBeginState, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryD3DSwapchainBeginState} WGPU_COMMA \ + /*.isSwapchain=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryDXGISharedHandleDescriptor { + WGPUChainedStruct chain; + void * handle; + WGPUBool useKeyedMutex; +} WGPUSharedTextureMemoryDXGISharedHandleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_DXGI_SHARED_HANDLE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryDXGISharedHandleDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryDXGISharedHandleDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ + /*.useKeyedMutex=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryEGLImageDescriptor { + WGPUChainedStruct chain; + void * image; +} WGPUSharedTextureMemoryEGLImageDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_EGL_IMAGE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryEGLImageDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryEGLImageDescriptor} WGPU_COMMA \ + /*.image=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryIOSurfaceDescriptor { + WGPUChainedStruct chain; + void * ioSurface; +} WGPUSharedTextureMemoryIOSurfaceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_IO_SURFACE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryIOSurfaceDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryIOSurfaceDescriptor} WGPU_COMMA \ + /*.ioSurface=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryAHardwareBufferDescriptor { + WGPUChainedStruct chain; + void * handle; + WGPUBool useExternalFormat; +} WGPUSharedTextureMemoryAHardwareBufferDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_A_HARDWARE_BUFFER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryAHardwareBufferDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryAHardwareBufferDescriptor} WGPU_COMMA \ + /*.handle=*/{} WGPU_COMMA \ + /*.useExternalFormat=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedTextureMemoryBeginAccessDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUBool concurrentRead; + WGPUBool initialized; + size_t fenceCount; + WGPUSharedFence const * fences; + uint64_t const * signaledValues; +} WGPUSharedTextureMemoryBeginAccessDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_BEGIN_ACCESS_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryBeginAccessDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.concurrentRead=*/{} WGPU_COMMA \ + /*.initialized=*/{} WGPU_COMMA \ + /*.fenceCount=*/{} WGPU_COMMA \ + /*.fences=*/{} WGPU_COMMA \ + /*.signaledValues=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedTextureMemoryDmaBufPlane { + int fd; + uint64_t offset; + uint32_t stride; +} WGPUSharedTextureMemoryDmaBufPlane WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_DMA_BUF_PLANE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryDmaBufPlane, { \ + /*.fd=*/{} WGPU_COMMA \ + /*.offset=*/{} WGPU_COMMA \ + /*.stride=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedTextureMemoryEndAccessState { + WGPUChainedStructOut * nextInChain; + WGPUBool initialized; + size_t fenceCount; + WGPUSharedFence const * fences; + uint64_t const * signaledValues; +} WGPUSharedTextureMemoryEndAccessState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_END_ACCESS_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryEndAccessState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.initialized=*/{} WGPU_COMMA \ + /*.fenceCount=*/{} WGPU_COMMA \ + /*.fences=*/{} WGPU_COMMA \ + /*.signaledValues=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryOpaqueFDDescriptor { + WGPUChainedStruct chain; + void const * vkImageCreateInfo; + int memoryFD; + uint32_t memoryTypeIndex; + uint64_t allocationSize; + WGPUBool dedicatedAllocation; +} WGPUSharedTextureMemoryOpaqueFDDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_OPAQUE_FD_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryOpaqueFDDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryOpaqueFDDescriptor} WGPU_COMMA \ + /*.vkImageCreateInfo=*/{} WGPU_COMMA \ + /*.memoryFD=*/{} WGPU_COMMA \ + /*.memoryTypeIndex=*/{} WGPU_COMMA \ + /*.allocationSize=*/{} WGPU_COMMA \ + /*.dedicatedAllocation=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor { + WGPUChainedStruct chain; + WGPUBool dedicatedAllocation; +} WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_VK_DEDICATED_ALLOCATION_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryVkDedicatedAllocationDescriptor} WGPU_COMMA \ + /*.dedicatedAllocation=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryBeginAccessDescriptor +typedef struct WGPUSharedTextureMemoryVkImageLayoutBeginState { + WGPUChainedStruct chain; + int32_t oldLayout; + int32_t newLayout; +} WGPUSharedTextureMemoryVkImageLayoutBeginState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_VK_IMAGE_LAYOUT_BEGIN_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryVkImageLayoutBeginState, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryVkImageLayoutBeginState} WGPU_COMMA \ + /*.oldLayout=*/{} WGPU_COMMA \ + /*.newLayout=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryEndAccessState +typedef struct WGPUSharedTextureMemoryVkImageLayoutEndState { + WGPUChainedStructOut chain; + int32_t oldLayout; + int32_t newLayout; +} WGPUSharedTextureMemoryVkImageLayoutEndState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_VK_IMAGE_LAYOUT_END_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryVkImageLayoutEndState, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryVkImageLayoutEndState} WGPU_COMMA \ + /*.oldLayout=*/{} WGPU_COMMA \ + /*.newLayout=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryZirconHandleDescriptor { + WGPUChainedStruct chain; + uint32_t memoryFD; + uint64_t allocationSize; +} WGPUSharedTextureMemoryZirconHandleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_ZIRCON_HANDLE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryZirconHandleDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryZirconHandleDescriptor} WGPU_COMMA \ + /*.memoryFD=*/{} WGPU_COMMA \ + /*.allocationSize=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUBindGroupLayoutEntry +typedef struct WGPUStaticSamplerBindingLayout { + WGPUChainedStruct chain; + WGPUSampler sampler; + uint32_t sampledTextureBinding; +} WGPUStaticSamplerBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_STATIC_SAMPLER_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUStaticSamplerBindingLayout, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_StaticSamplerBindingLayout} WGPU_COMMA \ + /*.sampler=*/{} WGPU_COMMA \ + /*.sampledTextureBinding=*/WGPU_LIMIT_U32_UNDEFINED WGPU_COMMA \ +}) + +typedef struct WGPUStencilFaceState { + WGPUCompareFunction compare; + WGPUStencilOperation failOp; + WGPUStencilOperation depthFailOp; + WGPUStencilOperation passOp; +} WGPUStencilFaceState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_STENCIL_FACE_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUStencilFaceState, { \ + /*.compare=*/WGPUCompareFunction_Always WGPU_COMMA \ + /*.failOp=*/WGPUStencilOperation_Keep WGPU_COMMA \ + /*.depthFailOp=*/WGPUStencilOperation_Keep WGPU_COMMA \ + /*.passOp=*/WGPUStencilOperation_Keep WGPU_COMMA \ +}) + +typedef struct WGPUStorageTextureBindingLayout { + WGPUChainedStruct const * nextInChain; + WGPUStorageTextureAccess access; + WGPUTextureFormat format; + WGPUTextureViewDimension viewDimension; +} WGPUStorageTextureBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_STORAGE_TEXTURE_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUStorageTextureBindingLayout, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.access=*/WGPUStorageTextureAccess_BindingNotUsed WGPU_COMMA \ + /*.format=*/WGPUTextureFormat_Undefined WGPU_COMMA \ + /*.viewDimension=*/WGPUTextureViewDimension_2D WGPU_COMMA \ +}) + +typedef struct WGPUStringView { + WGPU_NULLABLE char const * data; + size_t length; +} WGPUStringView WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_STRING_VIEW_INIT WGPU_MAKE_INIT_STRUCT(WGPUStringView, { \ + /*.data=*/nullptr WGPU_COMMA \ + /*.length=*/WGPU_STRLEN WGPU_COMMA \ +}) + +typedef struct WGPUSupportedFeatures { + size_t featureCount; + WGPUFeatureName const * features; +} WGPUSupportedFeatures WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SUPPORTED_FEATURES_INIT WGPU_MAKE_INIT_STRUCT(WGPUSupportedFeatures, { \ + /*.featureCount=*/{} WGPU_COMMA \ + /*.features=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSurfaceCapabilities { + WGPUChainedStructOut * nextInChain; + WGPUTextureUsage usages; + size_t formatCount; + WGPUTextureFormat const * formats; + size_t presentModeCount; + WGPUPresentMode const * presentModes; + size_t alphaModeCount; + WGPUCompositeAlphaMode const * alphaModes; +} WGPUSurfaceCapabilities WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_CAPABILITIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceCapabilities, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.usages=*/{} WGPU_COMMA \ + /*.formatCount=*/{} WGPU_COMMA \ + /*.formats=*/{} WGPU_COMMA \ + /*.presentModeCount=*/{} WGPU_COMMA \ + /*.presentModes=*/{} WGPU_COMMA \ + /*.alphaModeCount=*/{} WGPU_COMMA \ + /*.alphaModes=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSurfaceConfiguration { + WGPUChainedStruct const * nextInChain; + WGPUDevice device; + WGPUTextureFormat format; + WGPUTextureUsage usage; + size_t viewFormatCount; + WGPUTextureFormat const * viewFormats; + WGPUCompositeAlphaMode alphaMode; + uint32_t width; + uint32_t height; + WGPUPresentMode presentMode; +} WGPUSurfaceConfiguration WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_CONFIGURATION_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceConfiguration, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.device=*/{} WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ + /*.usage=*/WGPUTextureUsage_RenderAttachment WGPU_COMMA \ + /*.viewFormatCount=*/0 WGPU_COMMA \ + /*.viewFormats=*/nullptr WGPU_COMMA \ + /*.alphaMode=*/WGPUCompositeAlphaMode_Auto WGPU_COMMA \ + /*.width=*/{} WGPU_COMMA \ + /*.height=*/{} WGPU_COMMA \ + /*.presentMode=*/WGPUPresentMode_Fifo WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceDescriptorFromWindowsCoreWindow { + WGPUChainedStruct chain; + void * coreWindow; +} WGPUSurfaceDescriptorFromWindowsCoreWindow WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_DESCRIPTOR_FROM_WINDOWS_CORE_WINDOW_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceDescriptorFromWindowsCoreWindow, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceDescriptorFromWindowsCoreWindow} WGPU_COMMA \ + /*.coreWindow=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceDescriptorFromWindowsSwapChainPanel { + WGPUChainedStruct chain; + void * swapChainPanel; +} WGPUSurfaceDescriptorFromWindowsSwapChainPanel WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_DESCRIPTOR_FROM_WINDOWS_SWAP_CHAIN_PANEL_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceDescriptorFromWindowsSwapChainPanel, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceDescriptorFromWindowsSwapChainPanel} WGPU_COMMA \ + /*.swapChainPanel=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceXCBWindow { + WGPUChainedStruct chain; + void * connection; + uint32_t window; +} WGPUSurfaceSourceXCBWindow WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_XCB_WINDOW_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceXCBWindow, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceXCBWindow} WGPU_COMMA \ + /*.connection=*/{} WGPU_COMMA \ + /*.window=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceAndroidNativeWindow { + WGPUChainedStruct chain; + void * window; +} WGPUSurfaceSourceAndroidNativeWindow WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_ANDROID_NATIVE_WINDOW_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceAndroidNativeWindow, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceAndroidNativeWindow} WGPU_COMMA \ + /*.window=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceMetalLayer { + WGPUChainedStruct chain; + void * layer; +} WGPUSurfaceSourceMetalLayer WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_METAL_LAYER_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceMetalLayer, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceMetalLayer} WGPU_COMMA \ + /*.layer=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceWaylandSurface { + WGPUChainedStruct chain; + void * display; + void * surface; +} WGPUSurfaceSourceWaylandSurface WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_WAYLAND_SURFACE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceWaylandSurface, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceWaylandSurface} WGPU_COMMA \ + /*.display=*/{} WGPU_COMMA \ + /*.surface=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceWindowsHWND { + WGPUChainedStruct chain; + void * hinstance; + void * hwnd; +} WGPUSurfaceSourceWindowsHWND WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_WINDOWS_HWND_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceWindowsHWND, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceWindowsHWND} WGPU_COMMA \ + /*.hinstance=*/{} WGPU_COMMA \ + /*.hwnd=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceXlibWindow { + WGPUChainedStruct chain; + void * display; + uint64_t window; +} WGPUSurfaceSourceXlibWindow WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_XLIB_WINDOW_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceXlibWindow, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceXlibWindow} WGPU_COMMA \ + /*.display=*/{} WGPU_COMMA \ + /*.window=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSurfaceTexture { + WGPUTexture texture; + WGPUBool suboptimal; + WGPUSurfaceGetCurrentTextureStatus status; +} WGPUSurfaceTexture WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_TEXTURE_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceTexture, { \ + /*.texture=*/{} WGPU_COMMA \ + /*.suboptimal=*/{} WGPU_COMMA \ + /*.status=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUTextureBindingLayout { + WGPUChainedStruct const * nextInChain; + WGPUTextureSampleType sampleType; + WGPUTextureViewDimension viewDimension; + WGPUBool multisampled; +} WGPUTextureBindingLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_TEXTURE_BINDING_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUTextureBindingLayout, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.sampleType=*/WGPUTextureSampleType_BindingNotUsed WGPU_COMMA \ + /*.viewDimension=*/WGPUTextureViewDimension_2D WGPU_COMMA \ + /*.multisampled=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUTextureDescriptor +typedef struct WGPUTextureBindingViewDimensionDescriptor { + WGPUChainedStruct chain; + WGPUTextureViewDimension textureBindingViewDimension; +} WGPUTextureBindingViewDimensionDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_TEXTURE_BINDING_VIEW_DIMENSION_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUTextureBindingViewDimensionDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_TextureBindingViewDimensionDescriptor} WGPU_COMMA \ + /*.textureBindingViewDimension=*/WGPUTextureViewDimension_Undefined WGPU_COMMA \ +}) + +typedef struct WGPUTextureDataLayout { + WGPUChainedStruct const * nextInChain; + uint64_t offset; + uint32_t bytesPerRow; + uint32_t rowsPerImage; +} WGPUTextureDataLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_TEXTURE_DATA_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUTextureDataLayout, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.offset=*/0 WGPU_COMMA \ + /*.bytesPerRow=*/WGPU_COPY_STRIDE_UNDEFINED WGPU_COMMA \ + /*.rowsPerImage=*/WGPU_COPY_STRIDE_UNDEFINED WGPU_COMMA \ +}) + +typedef struct WGPUUncapturedErrorCallbackInfo { + WGPUChainedStruct const * nextInChain; + WGPUErrorCallback callback; + void * userdata; +} WGPUUncapturedErrorCallbackInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_UNCAPTURED_ERROR_CALLBACK_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUUncapturedErrorCallbackInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.callback=*/nullptr WGPU_COMMA \ + /*.userdata=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUVertexAttribute { + WGPUVertexFormat format; + uint64_t offset; + uint32_t shaderLocation; +} WGPUVertexAttribute WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_VERTEX_ATTRIBUTE_INIT WGPU_MAKE_INIT_STRUCT(WGPUVertexAttribute, { \ + /*.format=*/{} WGPU_COMMA \ + /*.offset=*/{} WGPU_COMMA \ + /*.shaderLocation=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUSamplerDescriptor +// Can be chained in WGPUTextureViewDescriptor +typedef struct WGPUYCbCrVkDescriptor { + WGPUChainedStruct chain; + uint32_t vkFormat; + uint32_t vkYCbCrModel; + uint32_t vkYCbCrRange; + uint32_t vkComponentSwizzleRed; + uint32_t vkComponentSwizzleGreen; + uint32_t vkComponentSwizzleBlue; + uint32_t vkComponentSwizzleAlpha; + uint32_t vkXChromaOffset; + uint32_t vkYChromaOffset; + WGPUFilterMode vkChromaFilter; + WGPUBool forceExplicitReconstruction; + uint64_t externalFormat; +} WGPUYCbCrVkDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_Y_CB_CR_VK_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUYCbCrVkDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_YCbCrVkDescriptor} WGPU_COMMA \ + /*.vkFormat=*/0 WGPU_COMMA \ + /*.vkYCbCrModel=*/0 WGPU_COMMA \ + /*.vkYCbCrRange=*/0 WGPU_COMMA \ + /*.vkComponentSwizzleRed=*/0 WGPU_COMMA \ + /*.vkComponentSwizzleGreen=*/0 WGPU_COMMA \ + /*.vkComponentSwizzleBlue=*/0 WGPU_COMMA \ + /*.vkComponentSwizzleAlpha=*/0 WGPU_COMMA \ + /*.vkXChromaOffset=*/0 WGPU_COMMA \ + /*.vkYChromaOffset=*/0 WGPU_COMMA \ + /*.vkChromaFilter=*/WGPUFilterMode_Nearest WGPU_COMMA \ + /*.forceExplicitReconstruction=*/false WGPU_COMMA \ + /*.externalFormat=*/0 WGPU_COMMA \ +}) + +typedef struct WGPUAHardwareBufferProperties { + WGPUYCbCrVkDescriptor yCbCrInfo; +} WGPUAHardwareBufferProperties WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_A_HARDWARE_BUFFER_PROPERTIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUAHardwareBufferProperties, { \ + /*.yCbCrInfo=*/WGPU_Y_CB_CR_VK_DESCRIPTOR_INIT WGPU_COMMA \ +}) + +typedef struct WGPUAdapterInfo { + WGPUChainedStructOut * nextInChain; + WGPUStringView vendor; + WGPUStringView architecture; + WGPUStringView device; + WGPUStringView description; + WGPUBackendType backendType; + WGPUAdapterType adapterType; + uint32_t vendorID; + uint32_t deviceID; + WGPUBool compatibilityMode; +} WGPUAdapterInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ADAPTER_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUAdapterInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.vendor=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.architecture=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.device=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.description=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.backendType=*/{} WGPU_COMMA \ + /*.adapterType=*/{} WGPU_COMMA \ + /*.vendorID=*/{} WGPU_COMMA \ + /*.deviceID=*/{} WGPU_COMMA \ + /*.compatibilityMode=*/false WGPU_COMMA \ +}) + +// Can be chained in WGPUAdapterInfo +typedef struct WGPUAdapterPropertiesMemoryHeaps { + WGPUChainedStructOut chain; + size_t heapCount; + WGPUMemoryHeapInfo const * heapInfo; +} WGPUAdapterPropertiesMemoryHeaps WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_ADAPTER_PROPERTIES_MEMORY_HEAPS_INIT WGPU_MAKE_INIT_STRUCT(WGPUAdapterPropertiesMemoryHeaps, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_AdapterPropertiesMemoryHeaps} WGPU_COMMA \ + /*.heapCount=*/{} WGPU_COMMA \ + /*.heapInfo=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUBindGroupDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUBindGroupLayout layout; + size_t entryCount; + WGPUBindGroupEntry const * entries; +} WGPUBindGroupDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BIND_GROUP_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUBindGroupDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.layout=*/{} WGPU_COMMA \ + /*.entryCount=*/{} WGPU_COMMA \ + /*.entries=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUBindGroupLayoutEntry { + WGPUChainedStruct const * nextInChain; + uint32_t binding; + WGPUShaderStage visibility; + WGPUBufferBindingLayout buffer; + WGPUSamplerBindingLayout sampler; + WGPUTextureBindingLayout texture; + WGPUStorageTextureBindingLayout storageTexture; +} WGPUBindGroupLayoutEntry WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BIND_GROUP_LAYOUT_ENTRY_INIT WGPU_MAKE_INIT_STRUCT(WGPUBindGroupLayoutEntry, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.binding=*/{} WGPU_COMMA \ + /*.visibility=*/{} WGPU_COMMA \ + /*.buffer=*/WGPU_BUFFER_BINDING_LAYOUT_INIT WGPU_COMMA \ + /*.sampler=*/WGPU_SAMPLER_BINDING_LAYOUT_INIT WGPU_COMMA \ + /*.texture=*/WGPU_TEXTURE_BINDING_LAYOUT_INIT WGPU_COMMA \ + /*.storageTexture=*/WGPU_STORAGE_TEXTURE_BINDING_LAYOUT_INIT WGPU_COMMA \ +}) + +typedef struct WGPUBlendState { + WGPUBlendComponent color; + WGPUBlendComponent alpha; +} WGPUBlendState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BLEND_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUBlendState, { \ + /*.color=*/WGPU_BLEND_COMPONENT_INIT WGPU_COMMA \ + /*.alpha=*/WGPU_BLEND_COMPONENT_INIT WGPU_COMMA \ +}) + +typedef struct WGPUBufferDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUBufferUsage usage; + uint64_t size; + WGPUBool mappedAtCreation; +} WGPUBufferDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BUFFER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUBufferDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.usage=*/{} WGPU_COMMA \ + /*.size=*/{} WGPU_COMMA \ + /*.mappedAtCreation=*/false WGPU_COMMA \ +}) + +typedef struct WGPUCommandBufferDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUCommandBufferDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMMAND_BUFFER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUCommandBufferDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPUCommandEncoderDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUCommandEncoderDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMMAND_ENCODER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUCommandEncoderDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPUCompilationMessage { + WGPUChainedStruct const * nextInChain; + WGPUStringView message; + WGPUCompilationMessageType type; + uint64_t lineNum; + uint64_t linePos; + uint64_t offset; + uint64_t length; + uint64_t utf16LinePos; + uint64_t utf16Offset; + uint64_t utf16Length; +} WGPUCompilationMessage WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPILATION_MESSAGE_INIT WGPU_MAKE_INIT_STRUCT(WGPUCompilationMessage, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.message=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.type=*/{} WGPU_COMMA \ + /*.lineNum=*/{} WGPU_COMMA \ + /*.linePos=*/{} WGPU_COMMA \ + /*.offset=*/{} WGPU_COMMA \ + /*.length=*/{} WGPU_COMMA \ + /*.utf16LinePos=*/{} WGPU_COMMA \ + /*.utf16Offset=*/{} WGPU_COMMA \ + /*.utf16Length=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUComputePassDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPU_NULLABLE WGPUComputePassTimestampWrites const * timestampWrites; +} WGPUComputePassDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPUTE_PASS_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUComputePassDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.timestampWrites=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUConstantEntry { + WGPUChainedStruct const * nextInChain; + WGPUStringView key; + double value; +} WGPUConstantEntry WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_CONSTANT_ENTRY_INIT WGPU_MAKE_INIT_STRUCT(WGPUConstantEntry, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.key=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.value=*/{} WGPU_COMMA \ +}) + +// Can be chained in WGPUDeviceDescriptor +typedef struct WGPUDawnCacheDeviceDescriptor { + WGPUChainedStruct chain; + WGPUStringView isolationKey; + WGPUDawnLoadCacheDataFunction loadDataFunction; + WGPUDawnStoreCacheDataFunction storeDataFunction; + void * functionUserdata; +} WGPUDawnCacheDeviceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DAWN_CACHE_DEVICE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDawnCacheDeviceDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DawnCacheDeviceDescriptor} WGPU_COMMA \ + /*.isolationKey=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.loadDataFunction=*/nullptr WGPU_COMMA \ + /*.storeDataFunction=*/nullptr WGPU_COMMA \ + /*.functionUserdata=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUDepthStencilState { + WGPUChainedStruct const * nextInChain; + WGPUTextureFormat format; + WGPUOptionalBool depthWriteEnabled; + WGPUCompareFunction depthCompare; + WGPUStencilFaceState stencilFront; + WGPUStencilFaceState stencilBack; + uint32_t stencilReadMask; + uint32_t stencilWriteMask; + int32_t depthBias; + float depthBiasSlopeScale; + float depthBiasClamp; +} WGPUDepthStencilState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DEPTH_STENCIL_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUDepthStencilState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ + /*.depthWriteEnabled=*/WGPUOptionalBool_Undefined WGPU_COMMA \ + /*.depthCompare=*/WGPUCompareFunction_Undefined WGPU_COMMA \ + /*.stencilFront=*/WGPU_STENCIL_FACE_STATE_INIT WGPU_COMMA \ + /*.stencilBack=*/WGPU_STENCIL_FACE_STATE_INIT WGPU_COMMA \ + /*.stencilReadMask=*/0xFFFFFFFF WGPU_COMMA \ + /*.stencilWriteMask=*/0xFFFFFFFF WGPU_COMMA \ + /*.depthBias=*/0 WGPU_COMMA \ + /*.depthBiasSlopeScale=*/0.0f WGPU_COMMA \ + /*.depthBiasClamp=*/0.0f WGPU_COMMA \ +}) + +// Can be chained in WGPUFormatCapabilities +typedef struct WGPUDrmFormatCapabilities { + WGPUChainedStructOut chain; + size_t propertiesCount; + WGPUDrmFormatProperties const * properties; +} WGPUDrmFormatCapabilities WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DRM_FORMAT_CAPABILITIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUDrmFormatCapabilities, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_DrmFormatCapabilities} WGPU_COMMA \ + /*.propertiesCount=*/{} WGPU_COMMA \ + /*.properties=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUExternalTextureDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUTextureView plane0; + WGPU_NULLABLE WGPUTextureView plane1; + WGPUOrigin2D cropOrigin; + WGPUExtent2D cropSize; + WGPUExtent2D apparentSize; + WGPUBool doYuvToRgbConversionOnly; + WGPU_NULLABLE float const * yuvToRgbConversionMatrix; + float const * srcTransferFunctionParameters; + float const * dstTransferFunctionParameters; + float const * gamutConversionMatrix; + WGPUBool mirrored; + WGPUExternalTextureRotation rotation; +} WGPUExternalTextureDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_EXTERNAL_TEXTURE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUExternalTextureDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.plane0=*/{} WGPU_COMMA \ + /*.plane1=*/nullptr WGPU_COMMA \ + /*.cropOrigin=*/WGPU_ORIGIN_2D_INIT WGPU_COMMA \ + /*.cropSize=*/WGPU_EXTENT_2D_INIT WGPU_COMMA \ + /*.apparentSize=*/WGPU_EXTENT_2D_INIT WGPU_COMMA \ + /*.doYuvToRgbConversionOnly=*/false WGPU_COMMA \ + /*.yuvToRgbConversionMatrix=*/nullptr WGPU_COMMA \ + /*.srcTransferFunctionParameters=*/{} WGPU_COMMA \ + /*.dstTransferFunctionParameters=*/{} WGPU_COMMA \ + /*.gamutConversionMatrix=*/{} WGPU_COMMA \ + /*.mirrored=*/false WGPU_COMMA \ + /*.rotation=*/WGPUExternalTextureRotation_Rotate0Degrees WGPU_COMMA \ +}) + +typedef struct WGPUFutureWaitInfo { + WGPUFuture future; + WGPUBool completed; +} WGPUFutureWaitInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_FUTURE_WAIT_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUFutureWaitInfo, { \ + /*.future=*/WGPU_FUTURE_INIT WGPU_COMMA \ + /*.completed=*/false WGPU_COMMA \ +}) + +typedef struct WGPUImageCopyBuffer { + WGPUTextureDataLayout layout; + WGPUBuffer buffer; +} WGPUImageCopyBuffer WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_IMAGE_COPY_BUFFER_INIT WGPU_MAKE_INIT_STRUCT(WGPUImageCopyBuffer, { \ + /*.layout=*/WGPU_TEXTURE_DATA_LAYOUT_INIT WGPU_COMMA \ + /*.buffer=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUImageCopyExternalTexture { + WGPUChainedStruct const * nextInChain; + WGPUExternalTexture externalTexture; + WGPUOrigin3D origin; + WGPUExtent2D naturalSize; +} WGPUImageCopyExternalTexture WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_IMAGE_COPY_EXTERNAL_TEXTURE_INIT WGPU_MAKE_INIT_STRUCT(WGPUImageCopyExternalTexture, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.externalTexture=*/{} WGPU_COMMA \ + /*.origin=*/WGPU_ORIGIN_3D_INIT WGPU_COMMA \ + /*.naturalSize=*/WGPU_EXTENT_2D_INIT WGPU_COMMA \ +}) + +typedef struct WGPUImageCopyTexture { + WGPUTexture texture; + uint32_t mipLevel; + WGPUOrigin3D origin; + WGPUTextureAspect aspect; +} WGPUImageCopyTexture WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_IMAGE_COPY_TEXTURE_INIT WGPU_MAKE_INIT_STRUCT(WGPUImageCopyTexture, { \ + /*.texture=*/{} WGPU_COMMA \ + /*.mipLevel=*/0 WGPU_COMMA \ + /*.origin=*/WGPU_ORIGIN_3D_INIT WGPU_COMMA \ + /*.aspect=*/WGPUTextureAspect_All WGPU_COMMA \ +}) + +typedef struct WGPUInstanceDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUInstanceFeatures features; +} WGPUInstanceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_INSTANCE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUInstanceDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.features=*/WGPU_INSTANCE_FEATURES_INIT WGPU_COMMA \ +}) + +typedef struct WGPUPipelineLayoutDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + size_t bindGroupLayoutCount; + WGPU_NULLABLE WGPUBindGroupLayout const * bindGroupLayouts; + uint32_t immediateDataRangeByteSize; +} WGPUPipelineLayoutDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_PIPELINE_LAYOUT_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUPipelineLayoutDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.bindGroupLayoutCount=*/{} WGPU_COMMA \ + /*.bindGroupLayouts=*/nullptr WGPU_COMMA \ + /*.immediateDataRangeByteSize=*/0 WGPU_COMMA \ +}) + +// Can be chained in WGPUPipelineLayoutDescriptor +typedef struct WGPUPipelineLayoutPixelLocalStorage { + WGPUChainedStruct chain; + uint64_t totalPixelLocalStorageSize; + size_t storageAttachmentCount; + WGPUPipelineLayoutStorageAttachment const * storageAttachments; +} WGPUPipelineLayoutPixelLocalStorage WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_PIPELINE_LAYOUT_PIXEL_LOCAL_STORAGE_INIT WGPU_MAKE_INIT_STRUCT(WGPUPipelineLayoutPixelLocalStorage, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_PipelineLayoutPixelLocalStorage} WGPU_COMMA \ + /*.totalPixelLocalStorageSize=*/{} WGPU_COMMA \ + /*.storageAttachmentCount=*/0 WGPU_COMMA \ + /*.storageAttachments=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUQuerySetDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUQueryType type; + uint32_t count; +} WGPUQuerySetDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_QUERY_SET_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUQuerySetDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.type=*/{} WGPU_COMMA \ + /*.count=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUQueueDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUQueueDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_QUEUE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUQueueDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPURenderBundleDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPURenderBundleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_BUNDLE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderBundleDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPURenderBundleEncoderDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + size_t colorFormatCount; + WGPUTextureFormat const * colorFormats; + WGPUTextureFormat depthStencilFormat; + uint32_t sampleCount; + WGPUBool depthReadOnly; + WGPUBool stencilReadOnly; +} WGPURenderBundleEncoderDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_BUNDLE_ENCODER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderBundleEncoderDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.colorFormatCount=*/{} WGPU_COMMA \ + /*.colorFormats=*/{} WGPU_COMMA \ + /*.depthStencilFormat=*/WGPUTextureFormat_Undefined WGPU_COMMA \ + /*.sampleCount=*/1 WGPU_COMMA \ + /*.depthReadOnly=*/false WGPU_COMMA \ + /*.stencilReadOnly=*/false WGPU_COMMA \ +}) + +typedef struct WGPURenderPassColorAttachment { + WGPUChainedStruct const * nextInChain; + WGPU_NULLABLE WGPUTextureView view; + uint32_t depthSlice; + WGPU_NULLABLE WGPUTextureView resolveTarget; + WGPULoadOp loadOp; + WGPUStoreOp storeOp; + WGPUColor clearValue; +} WGPURenderPassColorAttachment WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_COLOR_ATTACHMENT_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassColorAttachment, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.view=*/nullptr WGPU_COMMA \ + /*.depthSlice=*/WGPU_DEPTH_SLICE_UNDEFINED WGPU_COMMA \ + /*.resolveTarget=*/nullptr WGPU_COMMA \ + /*.loadOp=*/{} WGPU_COMMA \ + /*.storeOp=*/{} WGPU_COMMA \ + /*.clearValue=*/WGPU_COLOR_INIT WGPU_COMMA \ +}) + +typedef struct WGPURenderPassStorageAttachment { + WGPUChainedStruct const * nextInChain; + uint64_t offset; + WGPUTextureView storage; + WGPULoadOp loadOp; + WGPUStoreOp storeOp; + WGPUColor clearValue; +} WGPURenderPassStorageAttachment WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_STORAGE_ATTACHMENT_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassStorageAttachment, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.offset=*/0 WGPU_COMMA \ + /*.storage=*/{} WGPU_COMMA \ + /*.loadOp=*/{} WGPU_COMMA \ + /*.storeOp=*/{} WGPU_COMMA \ + /*.clearValue=*/WGPU_COLOR_INIT WGPU_COMMA \ +}) + +typedef struct WGPURequiredLimits { + WGPUChainedStruct const * nextInChain; + WGPULimits limits; +} WGPURequiredLimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_REQUIRED_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPURequiredLimits, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.limits=*/WGPU_LIMITS_INIT WGPU_COMMA \ +}) + +typedef struct WGPUSamplerDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUAddressMode addressModeU; + WGPUAddressMode addressModeV; + WGPUAddressMode addressModeW; + WGPUFilterMode magFilter; + WGPUFilterMode minFilter; + WGPUMipmapFilterMode mipmapFilter; + float lodMinClamp; + float lodMaxClamp; + WGPUCompareFunction compare; + uint16_t maxAnisotropy; +} WGPUSamplerDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SAMPLER_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSamplerDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.addressModeU=*/WGPUAddressMode_ClampToEdge WGPU_COMMA \ + /*.addressModeV=*/WGPUAddressMode_ClampToEdge WGPU_COMMA \ + /*.addressModeW=*/WGPUAddressMode_ClampToEdge WGPU_COMMA \ + /*.magFilter=*/WGPUFilterMode_Nearest WGPU_COMMA \ + /*.minFilter=*/WGPUFilterMode_Nearest WGPU_COMMA \ + /*.mipmapFilter=*/WGPUMipmapFilterMode_Nearest WGPU_COMMA \ + /*.lodMinClamp=*/0.0f WGPU_COMMA \ + /*.lodMaxClamp=*/32.0f WGPU_COMMA \ + /*.compare=*/WGPUCompareFunction_Undefined WGPU_COMMA \ + /*.maxAnisotropy=*/1 WGPU_COMMA \ +}) + +typedef struct WGPUShaderModuleDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUShaderModuleDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHADER_MODULE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUShaderModuleDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +// Can be chained in WGPUShaderModuleDescriptor +typedef struct WGPUShaderSourceWGSL { + WGPUChainedStruct chain; + WGPUStringView code; +} WGPUShaderSourceWGSL WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHADER_SOURCE_WGSL_INIT WGPU_MAKE_INIT_STRUCT(WGPUShaderSourceWGSL, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_ShaderSourceWGSL} WGPU_COMMA \ + /*.code=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPUSharedBufferMemoryDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUSharedBufferMemoryDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_BUFFER_MEMORY_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedBufferMemoryDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPUSharedFenceDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUSharedFenceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_FENCE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedFenceDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryProperties +typedef struct WGPUSharedTextureMemoryAHardwareBufferProperties { + WGPUChainedStructOut chain; + WGPUYCbCrVkDescriptor yCbCrInfo; +} WGPUSharedTextureMemoryAHardwareBufferProperties WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_A_HARDWARE_BUFFER_PROPERTIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryAHardwareBufferProperties, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryAHardwareBufferProperties} WGPU_COMMA \ + /*.yCbCrInfo=*/WGPU_Y_CB_CR_VK_DESCRIPTOR_INIT WGPU_COMMA \ +}) + +typedef struct WGPUSharedTextureMemoryDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUSharedTextureMemoryDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +// Can be chained in WGPUSharedTextureMemoryDescriptor +typedef struct WGPUSharedTextureMemoryDmaBufDescriptor { + WGPUChainedStruct chain; + WGPUExtent3D size; + uint32_t drmFormat; + uint64_t drmModifier; + size_t planeCount; + WGPUSharedTextureMemoryDmaBufPlane const * planes; +} WGPUSharedTextureMemoryDmaBufDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_DMA_BUF_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryDmaBufDescriptor, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SharedTextureMemoryDmaBufDescriptor} WGPU_COMMA \ + /*.size=*/WGPU_EXTENT_3D_INIT WGPU_COMMA \ + /*.drmFormat=*/{} WGPU_COMMA \ + /*.drmModifier=*/{} WGPU_COMMA \ + /*.planeCount=*/{} WGPU_COMMA \ + /*.planes=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSharedTextureMemoryProperties { + WGPUChainedStructOut * nextInChain; + WGPUTextureUsage usage; + WGPUExtent3D size; + WGPUTextureFormat format; +} WGPUSharedTextureMemoryProperties WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SHARED_TEXTURE_MEMORY_PROPERTIES_INIT WGPU_MAKE_INIT_STRUCT(WGPUSharedTextureMemoryProperties, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.usage=*/{} WGPU_COMMA \ + /*.size=*/WGPU_EXTENT_3D_INIT WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUSupportedLimits { + WGPUChainedStructOut * nextInChain; + WGPULimits limits; +} WGPUSupportedLimits WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SUPPORTED_LIMITS_INIT WGPU_MAKE_INIT_STRUCT(WGPUSupportedLimits, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.limits=*/WGPU_LIMITS_INIT WGPU_COMMA \ +}) + +typedef struct WGPUSurfaceDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; +} WGPUSurfaceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +// Can be chained in WGPUSurfaceDescriptor +typedef struct WGPUSurfaceSourceCanvasHTMLSelector_Emscripten { + WGPUChainedStruct chain; + WGPUStringView selector; +} WGPUSurfaceSourceCanvasHTMLSelector_Emscripten WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_SURFACE_SOURCE_CANVAS_HTML_SELECTOR__EMSCRIPTEN_INIT WGPU_MAKE_INIT_STRUCT(WGPUSurfaceSourceCanvasHTMLSelector_Emscripten, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_SurfaceSourceCanvasHTMLSelector_Emscripten} WGPU_COMMA \ + /*.selector=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ +}) + +typedef struct WGPUTextureDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUTextureUsage usage; + WGPUTextureDimension dimension; + WGPUExtent3D size; + WGPUTextureFormat format; + uint32_t mipLevelCount; + uint32_t sampleCount; + size_t viewFormatCount; + WGPUTextureFormat const * viewFormats; +} WGPUTextureDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_TEXTURE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUTextureDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.usage=*/{} WGPU_COMMA \ + /*.dimension=*/WGPUTextureDimension_2D WGPU_COMMA \ + /*.size=*/WGPU_EXTENT_3D_INIT WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ + /*.mipLevelCount=*/1 WGPU_COMMA \ + /*.sampleCount=*/1 WGPU_COMMA \ + /*.viewFormatCount=*/0 WGPU_COMMA \ + /*.viewFormats=*/nullptr WGPU_COMMA \ +}) + +typedef struct WGPUTextureViewDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPUTextureFormat format; + WGPUTextureViewDimension dimension; + uint32_t baseMipLevel; + uint32_t mipLevelCount; + uint32_t baseArrayLayer; + uint32_t arrayLayerCount; + WGPUTextureAspect aspect; + WGPUTextureUsage usage; +} WGPUTextureViewDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_TEXTURE_VIEW_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUTextureViewDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.format=*/WGPUTextureFormat_Undefined WGPU_COMMA \ + /*.dimension=*/WGPUTextureViewDimension_Undefined WGPU_COMMA \ + /*.baseMipLevel=*/0 WGPU_COMMA \ + /*.mipLevelCount=*/WGPU_MIP_LEVEL_COUNT_UNDEFINED WGPU_COMMA \ + /*.baseArrayLayer=*/0 WGPU_COMMA \ + /*.arrayLayerCount=*/WGPU_ARRAY_LAYER_COUNT_UNDEFINED WGPU_COMMA \ + /*.aspect=*/WGPUTextureAspect_All WGPU_COMMA \ + /*.usage=*/WGPUTextureUsage_None WGPU_COMMA \ +}) + +typedef struct WGPUVertexBufferLayout { + uint64_t arrayStride; + WGPUVertexStepMode stepMode; + size_t attributeCount; + WGPUVertexAttribute const * attributes; +} WGPUVertexBufferLayout WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_VERTEX_BUFFER_LAYOUT_INIT WGPU_MAKE_INIT_STRUCT(WGPUVertexBufferLayout, { \ + /*.arrayStride=*/{} WGPU_COMMA \ + /*.stepMode=*/{} WGPU_COMMA \ + /*.attributeCount=*/{} WGPU_COMMA \ + /*.attributes=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUBindGroupLayoutDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + size_t entryCount; + WGPUBindGroupLayoutEntry const * entries; +} WGPUBindGroupLayoutDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_BIND_GROUP_LAYOUT_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUBindGroupLayoutDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.entryCount=*/{} WGPU_COMMA \ + /*.entries=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUColorTargetState { + WGPUChainedStruct const * nextInChain; + WGPUTextureFormat format; + WGPU_NULLABLE WGPUBlendState const * blend; + WGPUColorWriteMask writeMask; +} WGPUColorTargetState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COLOR_TARGET_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUColorTargetState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.format=*/{} WGPU_COMMA \ + /*.blend=*/nullptr WGPU_COMMA \ + /*.writeMask=*/WGPUColorWriteMask_All WGPU_COMMA \ +}) + +typedef struct WGPUCompilationInfo { + WGPUChainedStruct const * nextInChain; + size_t messageCount; + WGPUCompilationMessage const * messages; +} WGPUCompilationInfo WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPILATION_INFO_INIT WGPU_MAKE_INIT_STRUCT(WGPUCompilationInfo, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.messageCount=*/{} WGPU_COMMA \ + /*.messages=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUComputeState { + WGPUChainedStruct const * nextInChain; + WGPUShaderModule module; + WGPUStringView entryPoint; + size_t constantCount; + WGPUConstantEntry const * constants; +} WGPUComputeState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPUTE_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUComputeState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.module=*/{} WGPU_COMMA \ + /*.entryPoint=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.constantCount=*/0 WGPU_COMMA \ + /*.constants=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUDeviceDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + size_t requiredFeatureCount; + WGPUFeatureName const * requiredFeatures; + WGPU_NULLABLE WGPURequiredLimits const * requiredLimits; + WGPUQueueDescriptor defaultQueue; + WGPUDeviceLostCallbackInfo2 deviceLostCallbackInfo2; + WGPUUncapturedErrorCallbackInfo2 uncapturedErrorCallbackInfo2; +} WGPUDeviceDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_DEVICE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUDeviceDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.requiredFeatureCount=*/0 WGPU_COMMA \ + /*.requiredFeatures=*/nullptr WGPU_COMMA \ + /*.requiredLimits=*/nullptr WGPU_COMMA \ + /*.defaultQueue=*/WGPU_QUEUE_DESCRIPTOR_INIT WGPU_COMMA \ + /*.deviceLostCallbackInfo2=*/{} WGPU_COMMA \ + /*.uncapturedErrorCallbackInfo2=*/{} WGPU_COMMA \ +}) + +typedef struct WGPURenderPassDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + size_t colorAttachmentCount; + WGPURenderPassColorAttachment const * colorAttachments; + WGPU_NULLABLE WGPURenderPassDepthStencilAttachment const * depthStencilAttachment; + WGPU_NULLABLE WGPUQuerySet occlusionQuerySet; + WGPU_NULLABLE WGPURenderPassTimestampWrites const * timestampWrites; +} WGPURenderPassDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.colorAttachmentCount=*/{} WGPU_COMMA \ + /*.colorAttachments=*/{} WGPU_COMMA \ + /*.depthStencilAttachment=*/nullptr WGPU_COMMA \ + /*.occlusionQuerySet=*/nullptr WGPU_COMMA \ + /*.timestampWrites=*/nullptr WGPU_COMMA \ +}) + +// Can be chained in WGPURenderPassDescriptor +typedef struct WGPURenderPassPixelLocalStorage { + WGPUChainedStruct chain; + uint64_t totalPixelLocalStorageSize; + size_t storageAttachmentCount; + WGPURenderPassStorageAttachment const * storageAttachments; +} WGPURenderPassPixelLocalStorage WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PASS_PIXEL_LOCAL_STORAGE_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPassPixelLocalStorage, { \ + /*.chain=*/{/*.nextInChain*/nullptr WGPU_COMMA /*.sType*/WGPUSType_RenderPassPixelLocalStorage} WGPU_COMMA \ + /*.totalPixelLocalStorageSize=*/{} WGPU_COMMA \ + /*.storageAttachmentCount=*/0 WGPU_COMMA \ + /*.storageAttachments=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUVertexState { + WGPUChainedStruct const * nextInChain; + WGPUShaderModule module; + WGPUStringView entryPoint; + size_t constantCount; + WGPUConstantEntry const * constants; + size_t bufferCount; + WGPUVertexBufferLayout const * buffers; +} WGPUVertexState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_VERTEX_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUVertexState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.module=*/{} WGPU_COMMA \ + /*.entryPoint=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.constantCount=*/0 WGPU_COMMA \ + /*.constants=*/{} WGPU_COMMA \ + /*.bufferCount=*/0 WGPU_COMMA \ + /*.buffers=*/{} WGPU_COMMA \ +}) + +typedef struct WGPUComputePipelineDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPU_NULLABLE WGPUPipelineLayout layout; + WGPUComputeState compute; +} WGPUComputePipelineDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_COMPUTE_PIPELINE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPUComputePipelineDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.layout=*/nullptr WGPU_COMMA \ + /*.compute=*/WGPU_COMPUTE_STATE_INIT WGPU_COMMA \ +}) + +typedef struct WGPUFragmentState { + WGPUChainedStruct const * nextInChain; + WGPUShaderModule module; + WGPUStringView entryPoint; + size_t constantCount; + WGPUConstantEntry const * constants; + size_t targetCount; + WGPUColorTargetState const * targets; +} WGPUFragmentState WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_FRAGMENT_STATE_INIT WGPU_MAKE_INIT_STRUCT(WGPUFragmentState, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.module=*/{} WGPU_COMMA \ + /*.entryPoint=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.constantCount=*/0 WGPU_COMMA \ + /*.constants=*/{} WGPU_COMMA \ + /*.targetCount=*/{} WGPU_COMMA \ + /*.targets=*/{} WGPU_COMMA \ +}) + +typedef struct WGPURenderPipelineDescriptor { + WGPUChainedStruct const * nextInChain; + WGPUStringView label; + WGPU_NULLABLE WGPUPipelineLayout layout; + WGPUVertexState vertex; + WGPUPrimitiveState primitive; + WGPU_NULLABLE WGPUDepthStencilState const * depthStencil; + WGPUMultisampleState multisample; + WGPU_NULLABLE WGPUFragmentState const * fragment; +} WGPURenderPipelineDescriptor WGPU_STRUCTURE_ATTRIBUTE; + +#define WGPU_RENDER_PIPELINE_DESCRIPTOR_INIT WGPU_MAKE_INIT_STRUCT(WGPURenderPipelineDescriptor, { \ + /*.nextInChain=*/nullptr WGPU_COMMA \ + /*.label=*/WGPU_STRING_VIEW_INIT WGPU_COMMA \ + /*.layout=*/nullptr WGPU_COMMA \ + /*.vertex=*/WGPU_VERTEX_STATE_INIT WGPU_COMMA \ + /*.primitive=*/WGPU_PRIMITIVE_STATE_INIT WGPU_COMMA \ + /*.depthStencil=*/nullptr WGPU_COMMA \ + /*.multisample=*/WGPU_MULTISAMPLE_STATE_INIT WGPU_COMMA \ + /*.fragment=*/nullptr WGPU_COMMA \ +}) + +// WGPURenderPassDescriptorMaxDrawCount is deprecated. +// Use WGPURenderPassMaxDrawCount instead. +typedef WGPURenderPassMaxDrawCount WGPURenderPassDescriptorMaxDrawCount; + +// WGPUShaderModuleSPIRVDescriptor is deprecated. +// Use WGPUShaderSourceSPIRV instead. +typedef WGPUShaderSourceSPIRV WGPUShaderModuleSPIRVDescriptor; + +// WGPUShaderModuleWGSLDescriptor is deprecated. +// Use WGPUShaderSourceWGSL instead. +typedef WGPUShaderSourceWGSL WGPUShaderModuleWGSLDescriptor; + +// WGPUSurfaceDescriptorFromAndroidNativeWindow is deprecated. +// Use WGPUSurfaceSourceAndroidNativeWindow instead. +typedef WGPUSurfaceSourceAndroidNativeWindow WGPUSurfaceDescriptorFromAndroidNativeWindow; + +// WGPUSurfaceDescriptorFromCanvasHTMLSelector is deprecated. +// Use WGPUSurfaceSourceCanvasHTMLSelector_Emscripten instead. +typedef WGPUSurfaceSourceCanvasHTMLSelector_Emscripten WGPUSurfaceDescriptorFromCanvasHTMLSelector; + +// WGPUSurfaceDescriptorFromMetalLayer is deprecated. +// Use WGPUSurfaceSourceMetalLayer instead. +typedef WGPUSurfaceSourceMetalLayer WGPUSurfaceDescriptorFromMetalLayer; + +// WGPUSurfaceDescriptorFromWaylandSurface is deprecated. +// Use WGPUSurfaceSourceWaylandSurface instead. +typedef WGPUSurfaceSourceWaylandSurface WGPUSurfaceDescriptorFromWaylandSurface; + +// WGPUSurfaceDescriptorFromWindowsHWND is deprecated. +// Use WGPUSurfaceSourceWindowsHWND instead. +typedef WGPUSurfaceSourceWindowsHWND WGPUSurfaceDescriptorFromWindowsHWND; + +// WGPUSurfaceDescriptorFromXcbWindow is deprecated. +// Use WGPUSurfaceSourceXCBWindow instead. +typedef WGPUSurfaceSourceXCBWindow WGPUSurfaceDescriptorFromXcbWindow; + +// WGPUSurfaceDescriptorFromXlibWindow is deprecated. +// Use WGPUSurfaceSourceXlibWindow instead. +typedef WGPUSurfaceSourceXlibWindow WGPUSurfaceDescriptorFromXlibWindow; + +#ifdef __cplusplus +extern "C" { +#endif + +#if !defined(WGPU_SKIP_PROCS) + +// TODO(374150686): Remove these Emscripten specific declarations from the +// header once they are fully deprecated. +#ifdef __EMSCRIPTEN__ +WGPU_EXPORT WGPUDevice emscripten_webgpu_get_device(void); +#endif + +typedef void (*WGPUProcAdapterInfoFreeMembers)( WGPUAdapterInfo value) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcAdapterPropertiesMemoryHeapsFreeMembers)( WGPUAdapterPropertiesMemoryHeaps value) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUInstance (*WGPUProcCreateInstance)( WGPU_NULLABLE WGPUInstanceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDrmFormatCapabilitiesFreeMembers)( WGPUDrmFormatCapabilities value) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcGetInstanceFeatures)( WGPUInstanceFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUProc (*WGPUProcGetProcAddress)( WGPUStringView procName) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedBufferMemoryEndAccessStateFreeMembers)( WGPUSharedBufferMemoryEndAccessState value) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedTextureMemoryEndAccessStateFreeMembers)( WGPUSharedTextureMemoryEndAccessState value) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSupportedFeaturesFreeMembers)( WGPUSupportedFeatures value) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceCapabilitiesFreeMembers)( WGPUSurfaceCapabilities value) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Adapter +typedef WGPUDevice (*WGPUProcAdapterCreateDevice)(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcAdapterGetFeatures)(WGPUAdapter adapter, WGPUSupportedFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcAdapterGetFormatCapabilities)(WGPUAdapter adapter, WGPUTextureFormat format, WGPUFormatCapabilities * capabilities) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcAdapterGetInfo)(WGPUAdapter adapter, WGPUAdapterInfo * info) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUInstance (*WGPUProcAdapterGetInstance)(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcAdapterGetLimits)(WGPUAdapter adapter, WGPUSupportedLimits * limits) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBool (*WGPUProcAdapterHasFeature)(WGPUAdapter adapter, WGPUFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcAdapterRequestDevice)(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * descriptor, WGPURequestDeviceCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcAdapterRequestDevice2)(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * options, WGPURequestDeviceCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcAdapterRequestDeviceF)(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * options, WGPURequestDeviceCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcAdapterAddRef)(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcAdapterRelease)(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of BindGroup +typedef void (*WGPUProcBindGroupSetLabel)(WGPUBindGroup bindGroup, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBindGroupAddRef)(WGPUBindGroup bindGroup) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBindGroupRelease)(WGPUBindGroup bindGroup) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of BindGroupLayout +typedef void (*WGPUProcBindGroupLayoutSetLabel)(WGPUBindGroupLayout bindGroupLayout, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBindGroupLayoutAddRef)(WGPUBindGroupLayout bindGroupLayout) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBindGroupLayoutRelease)(WGPUBindGroupLayout bindGroupLayout) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Buffer +typedef void (*WGPUProcBufferDestroy)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void const * (*WGPUProcBufferGetConstMappedRange)(WGPUBuffer buffer, size_t offset, size_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBufferMapState (*WGPUProcBufferGetMapState)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void * (*WGPUProcBufferGetMappedRange)(WGPUBuffer buffer, size_t offset, size_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef uint64_t (*WGPUProcBufferGetSize)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBufferUsage (*WGPUProcBufferGetUsage)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBufferMapAsync)(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcBufferMapAsync2)(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcBufferMapAsyncF)(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBufferSetLabel)(WGPUBuffer buffer, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBufferUnmap)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBufferAddRef)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcBufferRelease)(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of CommandBuffer +typedef void (*WGPUProcCommandBufferSetLabel)(WGPUCommandBuffer commandBuffer, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandBufferAddRef)(WGPUCommandBuffer commandBuffer) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandBufferRelease)(WGPUCommandBuffer commandBuffer) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of CommandEncoder +typedef WGPUComputePassEncoder (*WGPUProcCommandEncoderBeginComputePass)(WGPUCommandEncoder commandEncoder, WGPU_NULLABLE WGPUComputePassDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPURenderPassEncoder (*WGPUProcCommandEncoderBeginRenderPass)(WGPUCommandEncoder commandEncoder, WGPURenderPassDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderClearBuffer)(WGPUCommandEncoder commandEncoder, WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderCopyBufferToBuffer)(WGPUCommandEncoder commandEncoder, WGPUBuffer source, uint64_t sourceOffset, WGPUBuffer destination, uint64_t destinationOffset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderCopyBufferToTexture)(WGPUCommandEncoder commandEncoder, WGPUImageCopyBuffer const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderCopyTextureToBuffer)(WGPUCommandEncoder commandEncoder, WGPUImageCopyTexture const * source, WGPUImageCopyBuffer const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderCopyTextureToTexture)(WGPUCommandEncoder commandEncoder, WGPUImageCopyTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUCommandBuffer (*WGPUProcCommandEncoderFinish)(WGPUCommandEncoder commandEncoder, WGPU_NULLABLE WGPUCommandBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderInjectValidationError)(WGPUCommandEncoder commandEncoder, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderInsertDebugMarker)(WGPUCommandEncoder commandEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderPopDebugGroup)(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderPushDebugGroup)(WGPUCommandEncoder commandEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderResolveQuerySet)(WGPUCommandEncoder commandEncoder, WGPUQuerySet querySet, uint32_t firstQuery, uint32_t queryCount, WGPUBuffer destination, uint64_t destinationOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderSetLabel)(WGPUCommandEncoder commandEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderWriteBuffer)(WGPUCommandEncoder commandEncoder, WGPUBuffer buffer, uint64_t bufferOffset, uint8_t const * data, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderWriteTimestamp)(WGPUCommandEncoder commandEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderAddRef)(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcCommandEncoderRelease)(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of ComputePassEncoder +typedef void (*WGPUProcComputePassEncoderDispatchWorkgroups)(WGPUComputePassEncoder computePassEncoder, uint32_t workgroupCountX, uint32_t workgroupCountY, uint32_t workgroupCountZ) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderDispatchWorkgroupsIndirect)(WGPUComputePassEncoder computePassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderEnd)(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderInsertDebugMarker)(WGPUComputePassEncoder computePassEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderPopDebugGroup)(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderPushDebugGroup)(WGPUComputePassEncoder computePassEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderSetBindGroup)(WGPUComputePassEncoder computePassEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderSetLabel)(WGPUComputePassEncoder computePassEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderSetPipeline)(WGPUComputePassEncoder computePassEncoder, WGPUComputePipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderWriteTimestamp)(WGPUComputePassEncoder computePassEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderAddRef)(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePassEncoderRelease)(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of ComputePipeline +typedef WGPUBindGroupLayout (*WGPUProcComputePipelineGetBindGroupLayout)(WGPUComputePipeline computePipeline, uint32_t groupIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePipelineSetLabel)(WGPUComputePipeline computePipeline, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePipelineAddRef)(WGPUComputePipeline computePipeline) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcComputePipelineRelease)(WGPUComputePipeline computePipeline) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Device +typedef WGPUBindGroup (*WGPUProcDeviceCreateBindGroup)(WGPUDevice device, WGPUBindGroupDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBindGroupLayout (*WGPUProcDeviceCreateBindGroupLayout)(WGPUDevice device, WGPUBindGroupLayoutDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBuffer (*WGPUProcDeviceCreateBuffer)(WGPUDevice device, WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUCommandEncoder (*WGPUProcDeviceCreateCommandEncoder)(WGPUDevice device, WGPU_NULLABLE WGPUCommandEncoderDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUComputePipeline (*WGPUProcDeviceCreateComputePipeline)(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceCreateComputePipelineAsync)(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDeviceCreateComputePipelineAsync2)(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDeviceCreateComputePipelineAsyncF)(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBuffer (*WGPUProcDeviceCreateErrorBuffer)(WGPUDevice device, WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUExternalTexture (*WGPUProcDeviceCreateErrorExternalTexture)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUShaderModule (*WGPUProcDeviceCreateErrorShaderModule)(WGPUDevice device, WGPUShaderModuleDescriptor const * descriptor, WGPUStringView errorMessage) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTexture (*WGPUProcDeviceCreateErrorTexture)(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUExternalTexture (*WGPUProcDeviceCreateExternalTexture)(WGPUDevice device, WGPUExternalTextureDescriptor const * externalTextureDescriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUPipelineLayout (*WGPUProcDeviceCreatePipelineLayout)(WGPUDevice device, WGPUPipelineLayoutDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUQuerySet (*WGPUProcDeviceCreateQuerySet)(WGPUDevice device, WGPUQuerySetDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPURenderBundleEncoder (*WGPUProcDeviceCreateRenderBundleEncoder)(WGPUDevice device, WGPURenderBundleEncoderDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPURenderPipeline (*WGPUProcDeviceCreateRenderPipeline)(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceCreateRenderPipelineAsync)(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDeviceCreateRenderPipelineAsync2)(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDeviceCreateRenderPipelineAsyncF)(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUSampler (*WGPUProcDeviceCreateSampler)(WGPUDevice device, WGPU_NULLABLE WGPUSamplerDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUShaderModule (*WGPUProcDeviceCreateShaderModule)(WGPUDevice device, WGPUShaderModuleDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTexture (*WGPUProcDeviceCreateTexture)(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceDestroy)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceForceLoss)(WGPUDevice device, WGPUDeviceLostReason type, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcDeviceGetAHardwareBufferProperties)(WGPUDevice device, void * handle, WGPUAHardwareBufferProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUAdapter (*WGPUProcDeviceGetAdapter)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcDeviceGetAdapterInfo)(WGPUDevice device, WGPUAdapterInfo * adapterInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceGetFeatures)(WGPUDevice device, WGPUSupportedFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcDeviceGetLimits)(WGPUDevice device, WGPUSupportedLimits * limits) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDeviceGetLostFuture)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUQueue (*WGPUProcDeviceGetQueue)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBool (*WGPUProcDeviceHasFeature)(WGPUDevice device, WGPUFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUSharedBufferMemory (*WGPUProcDeviceImportSharedBufferMemory)(WGPUDevice device, WGPUSharedBufferMemoryDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUSharedFence (*WGPUProcDeviceImportSharedFence)(WGPUDevice device, WGPUSharedFenceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUSharedTextureMemory (*WGPUProcDeviceImportSharedTextureMemory)(WGPUDevice device, WGPUSharedTextureMemoryDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceInjectError)(WGPUDevice device, WGPUErrorType type, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDevicePopErrorScope)(WGPUDevice device, WGPUErrorCallback oldCallback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDevicePopErrorScope2)(WGPUDevice device, WGPUPopErrorScopeCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcDevicePopErrorScopeF)(WGPUDevice device, WGPUPopErrorScopeCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDevicePushErrorScope)(WGPUDevice device, WGPUErrorFilter filter) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceSetLabel)(WGPUDevice device, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceSetLoggingCallback)(WGPUDevice device, WGPULoggingCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceTick)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceValidateTextureDescriptor)(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceAddRef)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcDeviceRelease)(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of ExternalTexture +typedef void (*WGPUProcExternalTextureDestroy)(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcExternalTextureExpire)(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcExternalTextureRefresh)(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcExternalTextureSetLabel)(WGPUExternalTexture externalTexture, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcExternalTextureAddRef)(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcExternalTextureRelease)(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Instance +typedef WGPUSurface (*WGPUProcInstanceCreateSurface)(WGPUInstance instance, WGPUSurfaceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef size_t (*WGPUProcInstanceEnumerateWGSLLanguageFeatures)(WGPUInstance instance, WGPUWGSLFeatureName * features) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBool (*WGPUProcInstanceHasWGSLLanguageFeature)(WGPUInstance instance, WGPUWGSLFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcInstanceProcessEvents)(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcInstanceRequestAdapter)(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcInstanceRequestAdapter2)(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcInstanceRequestAdapterF)(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUWaitStatus (*WGPUProcInstanceWaitAny)(WGPUInstance instance, size_t futureCount, WGPUFutureWaitInfo * futures, uint64_t timeoutNS) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcInstanceAddRef)(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcInstanceRelease)(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of PipelineLayout +typedef void (*WGPUProcPipelineLayoutSetLabel)(WGPUPipelineLayout pipelineLayout, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcPipelineLayoutAddRef)(WGPUPipelineLayout pipelineLayout) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcPipelineLayoutRelease)(WGPUPipelineLayout pipelineLayout) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of QuerySet +typedef void (*WGPUProcQuerySetDestroy)(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcQuerySetGetCount)(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUQueryType (*WGPUProcQuerySetGetType)(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQuerySetSetLabel)(WGPUQuerySet querySet, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQuerySetAddRef)(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQuerySetRelease)(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Queue +typedef void (*WGPUProcQueueCopyExternalTextureForBrowser)(WGPUQueue queue, WGPUImageCopyExternalTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize, WGPUCopyTextureForBrowserOptions const * options) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueCopyTextureForBrowser)(WGPUQueue queue, WGPUImageCopyTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize, WGPUCopyTextureForBrowserOptions const * options) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueOnSubmittedWorkDone)(WGPUQueue queue, WGPUQueueWorkDoneCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcQueueOnSubmittedWorkDone2)(WGPUQueue queue, WGPUQueueWorkDoneCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcQueueOnSubmittedWorkDoneF)(WGPUQueue queue, WGPUQueueWorkDoneCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueSetLabel)(WGPUQueue queue, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueSubmit)(WGPUQueue queue, size_t commandCount, WGPUCommandBuffer const * commands) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueWriteBuffer)(WGPUQueue queue, WGPUBuffer buffer, uint64_t bufferOffset, void const * data, size_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueWriteTexture)(WGPUQueue queue, WGPUImageCopyTexture const * destination, void const * data, size_t dataSize, WGPUTextureDataLayout const * dataLayout, WGPUExtent3D const * writeSize) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueAddRef)(WGPUQueue queue) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcQueueRelease)(WGPUQueue queue) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of RenderBundle +typedef void (*WGPUProcRenderBundleSetLabel)(WGPURenderBundle renderBundle, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleAddRef)(WGPURenderBundle renderBundle) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleRelease)(WGPURenderBundle renderBundle) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of RenderBundleEncoder +typedef void (*WGPUProcRenderBundleEncoderDraw)(WGPURenderBundleEncoder renderBundleEncoder, uint32_t vertexCount, uint32_t instanceCount, uint32_t firstVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderDrawIndexed)(WGPURenderBundleEncoder renderBundleEncoder, uint32_t indexCount, uint32_t instanceCount, uint32_t firstIndex, int32_t baseVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderDrawIndexedIndirect)(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderDrawIndirect)(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPURenderBundle (*WGPUProcRenderBundleEncoderFinish)(WGPURenderBundleEncoder renderBundleEncoder, WGPU_NULLABLE WGPURenderBundleDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderInsertDebugMarker)(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderPopDebugGroup)(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderPushDebugGroup)(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderSetBindGroup)(WGPURenderBundleEncoder renderBundleEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderSetIndexBuffer)(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer buffer, WGPUIndexFormat format, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderSetLabel)(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderSetPipeline)(WGPURenderBundleEncoder renderBundleEncoder, WGPURenderPipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderSetVertexBuffer)(WGPURenderBundleEncoder renderBundleEncoder, uint32_t slot, WGPU_NULLABLE WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderAddRef)(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderBundleEncoderRelease)(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of RenderPassEncoder +typedef void (*WGPUProcRenderPassEncoderBeginOcclusionQuery)(WGPURenderPassEncoder renderPassEncoder, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderDraw)(WGPURenderPassEncoder renderPassEncoder, uint32_t vertexCount, uint32_t instanceCount, uint32_t firstVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderDrawIndexed)(WGPURenderPassEncoder renderPassEncoder, uint32_t indexCount, uint32_t instanceCount, uint32_t firstIndex, int32_t baseVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderDrawIndexedIndirect)(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderDrawIndirect)(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderEnd)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderEndOcclusionQuery)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderExecuteBundles)(WGPURenderPassEncoder renderPassEncoder, size_t bundleCount, WGPURenderBundle const * bundles) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderInsertDebugMarker)(WGPURenderPassEncoder renderPassEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderMultiDrawIndexedIndirect)(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset, uint32_t maxDrawCount, WGPU_NULLABLE WGPUBuffer drawCountBuffer, uint64_t drawCountBufferOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderMultiDrawIndirect)(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset, uint32_t maxDrawCount, WGPU_NULLABLE WGPUBuffer drawCountBuffer, uint64_t drawCountBufferOffset) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderPixelLocalStorageBarrier)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderPopDebugGroup)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderPushDebugGroup)(WGPURenderPassEncoder renderPassEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetBindGroup)(WGPURenderPassEncoder renderPassEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetBlendConstant)(WGPURenderPassEncoder renderPassEncoder, WGPUColor const * color) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetIndexBuffer)(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer buffer, WGPUIndexFormat format, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetLabel)(WGPURenderPassEncoder renderPassEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetPipeline)(WGPURenderPassEncoder renderPassEncoder, WGPURenderPipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetScissorRect)(WGPURenderPassEncoder renderPassEncoder, uint32_t x, uint32_t y, uint32_t width, uint32_t height) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetStencilReference)(WGPURenderPassEncoder renderPassEncoder, uint32_t reference) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetVertexBuffer)(WGPURenderPassEncoder renderPassEncoder, uint32_t slot, WGPU_NULLABLE WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderSetViewport)(WGPURenderPassEncoder renderPassEncoder, float x, float y, float width, float height, float minDepth, float maxDepth) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderWriteTimestamp)(WGPURenderPassEncoder renderPassEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderAddRef)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPassEncoderRelease)(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of RenderPipeline +typedef WGPUBindGroupLayout (*WGPUProcRenderPipelineGetBindGroupLayout)(WGPURenderPipeline renderPipeline, uint32_t groupIndex) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPipelineSetLabel)(WGPURenderPipeline renderPipeline, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPipelineAddRef)(WGPURenderPipeline renderPipeline) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcRenderPipelineRelease)(WGPURenderPipeline renderPipeline) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Sampler +typedef void (*WGPUProcSamplerSetLabel)(WGPUSampler sampler, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSamplerAddRef)(WGPUSampler sampler) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSamplerRelease)(WGPUSampler sampler) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of ShaderModule +typedef void (*WGPUProcShaderModuleGetCompilationInfo)(WGPUShaderModule shaderModule, WGPUCompilationInfoCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcShaderModuleGetCompilationInfo2)(WGPUShaderModule shaderModule, WGPUCompilationInfoCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUFuture (*WGPUProcShaderModuleGetCompilationInfoF)(WGPUShaderModule shaderModule, WGPUCompilationInfoCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcShaderModuleSetLabel)(WGPUShaderModule shaderModule, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcShaderModuleAddRef)(WGPUShaderModule shaderModule) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcShaderModuleRelease)(WGPUShaderModule shaderModule) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of SharedBufferMemory +typedef WGPUStatus (*WGPUProcSharedBufferMemoryBeginAccess)(WGPUSharedBufferMemory sharedBufferMemory, WGPUBuffer buffer, WGPUSharedBufferMemoryBeginAccessDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBuffer (*WGPUProcSharedBufferMemoryCreateBuffer)(WGPUSharedBufferMemory sharedBufferMemory, WGPU_NULLABLE WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcSharedBufferMemoryEndAccess)(WGPUSharedBufferMemory sharedBufferMemory, WGPUBuffer buffer, WGPUSharedBufferMemoryEndAccessState * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcSharedBufferMemoryGetProperties)(WGPUSharedBufferMemory sharedBufferMemory, WGPUSharedBufferMemoryProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBool (*WGPUProcSharedBufferMemoryIsDeviceLost)(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedBufferMemorySetLabel)(WGPUSharedBufferMemory sharedBufferMemory, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedBufferMemoryAddRef)(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedBufferMemoryRelease)(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of SharedFence +typedef void (*WGPUProcSharedFenceExportInfo)(WGPUSharedFence sharedFence, WGPUSharedFenceExportInfo * info) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedFenceAddRef)(WGPUSharedFence sharedFence) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedFenceRelease)(WGPUSharedFence sharedFence) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of SharedTextureMemory +typedef WGPUStatus (*WGPUProcSharedTextureMemoryBeginAccess)(WGPUSharedTextureMemory sharedTextureMemory, WGPUTexture texture, WGPUSharedTextureMemoryBeginAccessDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTexture (*WGPUProcSharedTextureMemoryCreateTexture)(WGPUSharedTextureMemory sharedTextureMemory, WGPU_NULLABLE WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcSharedTextureMemoryEndAccess)(WGPUSharedTextureMemory sharedTextureMemory, WGPUTexture texture, WGPUSharedTextureMemoryEndAccessState * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcSharedTextureMemoryGetProperties)(WGPUSharedTextureMemory sharedTextureMemory, WGPUSharedTextureMemoryProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUBool (*WGPUProcSharedTextureMemoryIsDeviceLost)(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedTextureMemorySetLabel)(WGPUSharedTextureMemory sharedTextureMemory, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedTextureMemoryAddRef)(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSharedTextureMemoryRelease)(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Surface +typedef void (*WGPUProcSurfaceConfigure)(WGPUSurface surface, WGPUSurfaceConfiguration const * config) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUStatus (*WGPUProcSurfaceGetCapabilities)(WGPUSurface surface, WGPUAdapter adapter, WGPUSurfaceCapabilities * capabilities) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceGetCurrentTexture)(WGPUSurface surface, WGPUSurfaceTexture * surfaceTexture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfacePresent)(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceSetLabel)(WGPUSurface surface, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceUnconfigure)(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceAddRef)(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcSurfaceRelease)(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of Texture +typedef WGPUTextureView (*WGPUProcTextureCreateErrorView)(WGPUTexture texture, WGPU_NULLABLE WGPUTextureViewDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTextureView (*WGPUProcTextureCreateView)(WGPUTexture texture, WGPU_NULLABLE WGPUTextureViewDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureDestroy)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcTextureGetDepthOrArrayLayers)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTextureDimension (*WGPUProcTextureGetDimension)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTextureFormat (*WGPUProcTextureGetFormat)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcTextureGetHeight)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcTextureGetMipLevelCount)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcTextureGetSampleCount)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef WGPUTextureUsage (*WGPUProcTextureGetUsage)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef uint32_t (*WGPUProcTextureGetWidth)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureSetLabel)(WGPUTexture texture, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureAddRef)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureRelease)(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; + +// Procs of TextureView +typedef void (*WGPUProcTextureViewSetLabel)(WGPUTextureView textureView, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureViewAddRef)(WGPUTextureView textureView) WGPU_FUNCTION_ATTRIBUTE; +typedef void (*WGPUProcTextureViewRelease)(WGPUTextureView textureView) WGPU_FUNCTION_ATTRIBUTE; + + +#endif // !defined(WGPU_SKIP_PROCS) + +#if !defined(WGPU_SKIP_DECLARATIONS) + +WGPU_EXPORT void wgpuAdapterInfoFreeMembers(WGPUAdapterInfo value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuAdapterPropertiesMemoryHeapsFreeMembers(WGPUAdapterPropertiesMemoryHeaps value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUInstance wgpuCreateInstance(WGPU_NULLABLE WGPUInstanceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDrmFormatCapabilitiesFreeMembers(WGPUDrmFormatCapabilities value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuGetInstanceFeatures(WGPUInstanceFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUProc wgpuGetProcAddress(WGPUStringView procName) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedBufferMemoryEndAccessStateFreeMembers(WGPUSharedBufferMemoryEndAccessState value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedTextureMemoryEndAccessStateFreeMembers(WGPUSharedTextureMemoryEndAccessState value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSupportedFeaturesFreeMembers(WGPUSupportedFeatures value) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceCapabilitiesFreeMembers(WGPUSurfaceCapabilities value) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Adapter +WGPU_EXPORT WGPUDevice wgpuAdapterCreateDevice(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuAdapterGetFeatures(WGPUAdapter adapter, WGPUSupportedFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuAdapterGetFormatCapabilities(WGPUAdapter adapter, WGPUTextureFormat format, WGPUFormatCapabilities * capabilities) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuAdapterGetInfo(WGPUAdapter adapter, WGPUAdapterInfo * info) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUInstance wgpuAdapterGetInstance(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuAdapterGetLimits(WGPUAdapter adapter, WGPUSupportedLimits * limits) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBool wgpuAdapterHasFeature(WGPUAdapter adapter, WGPUFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuAdapterRequestDevice(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * descriptor, WGPURequestDeviceCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuAdapterRequestDevice2(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * options, WGPURequestDeviceCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuAdapterRequestDeviceF(WGPUAdapter adapter, WGPU_NULLABLE WGPUDeviceDescriptor const * options, WGPURequestDeviceCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuAdapterAddRef(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuAdapterRelease(WGPUAdapter adapter) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of BindGroup +WGPU_EXPORT void wgpuBindGroupSetLabel(WGPUBindGroup bindGroup, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBindGroupAddRef(WGPUBindGroup bindGroup) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBindGroupRelease(WGPUBindGroup bindGroup) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of BindGroupLayout +WGPU_EXPORT void wgpuBindGroupLayoutSetLabel(WGPUBindGroupLayout bindGroupLayout, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBindGroupLayoutAddRef(WGPUBindGroupLayout bindGroupLayout) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBindGroupLayoutRelease(WGPUBindGroupLayout bindGroupLayout) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Buffer +WGPU_EXPORT void wgpuBufferDestroy(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void const * wgpuBufferGetConstMappedRange(WGPUBuffer buffer, size_t offset, size_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBufferMapState wgpuBufferGetMapState(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void * wgpuBufferGetMappedRange(WGPUBuffer buffer, size_t offset, size_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint64_t wgpuBufferGetSize(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBufferUsage wgpuBufferGetUsage(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBufferMapAsync(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuBufferMapAsync2(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuBufferMapAsyncF(WGPUBuffer buffer, WGPUMapMode mode, size_t offset, size_t size, WGPUBufferMapCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBufferSetLabel(WGPUBuffer buffer, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBufferUnmap(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBufferAddRef(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuBufferRelease(WGPUBuffer buffer) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of CommandBuffer +WGPU_EXPORT void wgpuCommandBufferSetLabel(WGPUCommandBuffer commandBuffer, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandBufferAddRef(WGPUCommandBuffer commandBuffer) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandBufferRelease(WGPUCommandBuffer commandBuffer) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of CommandEncoder +WGPU_EXPORT WGPUComputePassEncoder wgpuCommandEncoderBeginComputePass(WGPUCommandEncoder commandEncoder, WGPU_NULLABLE WGPUComputePassDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPURenderPassEncoder wgpuCommandEncoderBeginRenderPass(WGPUCommandEncoder commandEncoder, WGPURenderPassDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderClearBuffer(WGPUCommandEncoder commandEncoder, WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderCopyBufferToBuffer(WGPUCommandEncoder commandEncoder, WGPUBuffer source, uint64_t sourceOffset, WGPUBuffer destination, uint64_t destinationOffset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderCopyBufferToTexture(WGPUCommandEncoder commandEncoder, WGPUImageCopyBuffer const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderCopyTextureToBuffer(WGPUCommandEncoder commandEncoder, WGPUImageCopyTexture const * source, WGPUImageCopyBuffer const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderCopyTextureToTexture(WGPUCommandEncoder commandEncoder, WGPUImageCopyTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUCommandBuffer wgpuCommandEncoderFinish(WGPUCommandEncoder commandEncoder, WGPU_NULLABLE WGPUCommandBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderInjectValidationError(WGPUCommandEncoder commandEncoder, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderInsertDebugMarker(WGPUCommandEncoder commandEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderPopDebugGroup(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderPushDebugGroup(WGPUCommandEncoder commandEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderResolveQuerySet(WGPUCommandEncoder commandEncoder, WGPUQuerySet querySet, uint32_t firstQuery, uint32_t queryCount, WGPUBuffer destination, uint64_t destinationOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderSetLabel(WGPUCommandEncoder commandEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderWriteBuffer(WGPUCommandEncoder commandEncoder, WGPUBuffer buffer, uint64_t bufferOffset, uint8_t const * data, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderWriteTimestamp(WGPUCommandEncoder commandEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderAddRef(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuCommandEncoderRelease(WGPUCommandEncoder commandEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of ComputePassEncoder +WGPU_EXPORT void wgpuComputePassEncoderDispatchWorkgroups(WGPUComputePassEncoder computePassEncoder, uint32_t workgroupCountX, uint32_t workgroupCountY, uint32_t workgroupCountZ) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderDispatchWorkgroupsIndirect(WGPUComputePassEncoder computePassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderEnd(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderInsertDebugMarker(WGPUComputePassEncoder computePassEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderPopDebugGroup(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderPushDebugGroup(WGPUComputePassEncoder computePassEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderSetBindGroup(WGPUComputePassEncoder computePassEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderSetLabel(WGPUComputePassEncoder computePassEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderSetPipeline(WGPUComputePassEncoder computePassEncoder, WGPUComputePipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderWriteTimestamp(WGPUComputePassEncoder computePassEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderAddRef(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePassEncoderRelease(WGPUComputePassEncoder computePassEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of ComputePipeline +WGPU_EXPORT WGPUBindGroupLayout wgpuComputePipelineGetBindGroupLayout(WGPUComputePipeline computePipeline, uint32_t groupIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePipelineSetLabel(WGPUComputePipeline computePipeline, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePipelineAddRef(WGPUComputePipeline computePipeline) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuComputePipelineRelease(WGPUComputePipeline computePipeline) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Device +WGPU_EXPORT WGPUBindGroup wgpuDeviceCreateBindGroup(WGPUDevice device, WGPUBindGroupDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBindGroupLayout wgpuDeviceCreateBindGroupLayout(WGPUDevice device, WGPUBindGroupLayoutDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBuffer wgpuDeviceCreateBuffer(WGPUDevice device, WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUCommandEncoder wgpuDeviceCreateCommandEncoder(WGPUDevice device, WGPU_NULLABLE WGPUCommandEncoderDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUComputePipeline wgpuDeviceCreateComputePipeline(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceCreateComputePipelineAsync(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDeviceCreateComputePipelineAsync2(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDeviceCreateComputePipelineAsyncF(WGPUDevice device, WGPUComputePipelineDescriptor const * descriptor, WGPUCreateComputePipelineAsyncCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBuffer wgpuDeviceCreateErrorBuffer(WGPUDevice device, WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUExternalTexture wgpuDeviceCreateErrorExternalTexture(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUShaderModule wgpuDeviceCreateErrorShaderModule(WGPUDevice device, WGPUShaderModuleDescriptor const * descriptor, WGPUStringView errorMessage) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTexture wgpuDeviceCreateErrorTexture(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUExternalTexture wgpuDeviceCreateExternalTexture(WGPUDevice device, WGPUExternalTextureDescriptor const * externalTextureDescriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUPipelineLayout wgpuDeviceCreatePipelineLayout(WGPUDevice device, WGPUPipelineLayoutDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUQuerySet wgpuDeviceCreateQuerySet(WGPUDevice device, WGPUQuerySetDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPURenderBundleEncoder wgpuDeviceCreateRenderBundleEncoder(WGPUDevice device, WGPURenderBundleEncoderDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPURenderPipeline wgpuDeviceCreateRenderPipeline(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceCreateRenderPipelineAsync(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDeviceCreateRenderPipelineAsync2(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDeviceCreateRenderPipelineAsyncF(WGPUDevice device, WGPURenderPipelineDescriptor const * descriptor, WGPUCreateRenderPipelineAsyncCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUSampler wgpuDeviceCreateSampler(WGPUDevice device, WGPU_NULLABLE WGPUSamplerDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUShaderModule wgpuDeviceCreateShaderModule(WGPUDevice device, WGPUShaderModuleDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTexture wgpuDeviceCreateTexture(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceDestroy(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceForceLoss(WGPUDevice device, WGPUDeviceLostReason type, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuDeviceGetAHardwareBufferProperties(WGPUDevice device, void * handle, WGPUAHardwareBufferProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUAdapter wgpuDeviceGetAdapter(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuDeviceGetAdapterInfo(WGPUDevice device, WGPUAdapterInfo * adapterInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceGetFeatures(WGPUDevice device, WGPUSupportedFeatures * features) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuDeviceGetLimits(WGPUDevice device, WGPUSupportedLimits * limits) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDeviceGetLostFuture(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUQueue wgpuDeviceGetQueue(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBool wgpuDeviceHasFeature(WGPUDevice device, WGPUFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUSharedBufferMemory wgpuDeviceImportSharedBufferMemory(WGPUDevice device, WGPUSharedBufferMemoryDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUSharedFence wgpuDeviceImportSharedFence(WGPUDevice device, WGPUSharedFenceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUSharedTextureMemory wgpuDeviceImportSharedTextureMemory(WGPUDevice device, WGPUSharedTextureMemoryDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceInjectError(WGPUDevice device, WGPUErrorType type, WGPUStringView message) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDevicePopErrorScope(WGPUDevice device, WGPUErrorCallback oldCallback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDevicePopErrorScope2(WGPUDevice device, WGPUPopErrorScopeCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuDevicePopErrorScopeF(WGPUDevice device, WGPUPopErrorScopeCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDevicePushErrorScope(WGPUDevice device, WGPUErrorFilter filter) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceSetLabel(WGPUDevice device, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceSetLoggingCallback(WGPUDevice device, WGPULoggingCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceTick(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceValidateTextureDescriptor(WGPUDevice device, WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceAddRef(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuDeviceRelease(WGPUDevice device) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of ExternalTexture +WGPU_EXPORT void wgpuExternalTextureDestroy(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuExternalTextureExpire(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuExternalTextureRefresh(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuExternalTextureSetLabel(WGPUExternalTexture externalTexture, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuExternalTextureAddRef(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuExternalTextureRelease(WGPUExternalTexture externalTexture) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Instance +WGPU_EXPORT WGPUSurface wgpuInstanceCreateSurface(WGPUInstance instance, WGPUSurfaceDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT size_t wgpuInstanceEnumerateWGSLLanguageFeatures(WGPUInstance instance, WGPUWGSLFeatureName * features) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBool wgpuInstanceHasWGSLLanguageFeature(WGPUInstance instance, WGPUWGSLFeatureName feature) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuInstanceProcessEvents(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuInstanceRequestAdapter(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuInstanceRequestAdapter2(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuInstanceRequestAdapterF(WGPUInstance instance, WGPU_NULLABLE WGPURequestAdapterOptions const * options, WGPURequestAdapterCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUWaitStatus wgpuInstanceWaitAny(WGPUInstance instance, size_t futureCount, WGPUFutureWaitInfo * futures, uint64_t timeoutNS) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuInstanceAddRef(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuInstanceRelease(WGPUInstance instance) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of PipelineLayout +WGPU_EXPORT void wgpuPipelineLayoutSetLabel(WGPUPipelineLayout pipelineLayout, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuPipelineLayoutAddRef(WGPUPipelineLayout pipelineLayout) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuPipelineLayoutRelease(WGPUPipelineLayout pipelineLayout) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of QuerySet +WGPU_EXPORT void wgpuQuerySetDestroy(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuQuerySetGetCount(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUQueryType wgpuQuerySetGetType(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQuerySetSetLabel(WGPUQuerySet querySet, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQuerySetAddRef(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQuerySetRelease(WGPUQuerySet querySet) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Queue +WGPU_EXPORT void wgpuQueueCopyExternalTextureForBrowser(WGPUQueue queue, WGPUImageCopyExternalTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize, WGPUCopyTextureForBrowserOptions const * options) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueCopyTextureForBrowser(WGPUQueue queue, WGPUImageCopyTexture const * source, WGPUImageCopyTexture const * destination, WGPUExtent3D const * copySize, WGPUCopyTextureForBrowserOptions const * options) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueOnSubmittedWorkDone(WGPUQueue queue, WGPUQueueWorkDoneCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuQueueOnSubmittedWorkDone2(WGPUQueue queue, WGPUQueueWorkDoneCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuQueueOnSubmittedWorkDoneF(WGPUQueue queue, WGPUQueueWorkDoneCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueSetLabel(WGPUQueue queue, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueSubmit(WGPUQueue queue, size_t commandCount, WGPUCommandBuffer const * commands) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueWriteBuffer(WGPUQueue queue, WGPUBuffer buffer, uint64_t bufferOffset, void const * data, size_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueWriteTexture(WGPUQueue queue, WGPUImageCopyTexture const * destination, void const * data, size_t dataSize, WGPUTextureDataLayout const * dataLayout, WGPUExtent3D const * writeSize) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueAddRef(WGPUQueue queue) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuQueueRelease(WGPUQueue queue) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of RenderBundle +WGPU_EXPORT void wgpuRenderBundleSetLabel(WGPURenderBundle renderBundle, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleAddRef(WGPURenderBundle renderBundle) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleRelease(WGPURenderBundle renderBundle) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of RenderBundleEncoder +WGPU_EXPORT void wgpuRenderBundleEncoderDraw(WGPURenderBundleEncoder renderBundleEncoder, uint32_t vertexCount, uint32_t instanceCount, uint32_t firstVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderDrawIndexed(WGPURenderBundleEncoder renderBundleEncoder, uint32_t indexCount, uint32_t instanceCount, uint32_t firstIndex, int32_t baseVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderDrawIndexedIndirect(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderDrawIndirect(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPURenderBundle wgpuRenderBundleEncoderFinish(WGPURenderBundleEncoder renderBundleEncoder, WGPU_NULLABLE WGPURenderBundleDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderInsertDebugMarker(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderPopDebugGroup(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderPushDebugGroup(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderSetBindGroup(WGPURenderBundleEncoder renderBundleEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderSetIndexBuffer(WGPURenderBundleEncoder renderBundleEncoder, WGPUBuffer buffer, WGPUIndexFormat format, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderSetLabel(WGPURenderBundleEncoder renderBundleEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderSetPipeline(WGPURenderBundleEncoder renderBundleEncoder, WGPURenderPipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderSetVertexBuffer(WGPURenderBundleEncoder renderBundleEncoder, uint32_t slot, WGPU_NULLABLE WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderAddRef(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderBundleEncoderRelease(WGPURenderBundleEncoder renderBundleEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of RenderPassEncoder +WGPU_EXPORT void wgpuRenderPassEncoderBeginOcclusionQuery(WGPURenderPassEncoder renderPassEncoder, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderDraw(WGPURenderPassEncoder renderPassEncoder, uint32_t vertexCount, uint32_t instanceCount, uint32_t firstVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderDrawIndexed(WGPURenderPassEncoder renderPassEncoder, uint32_t indexCount, uint32_t instanceCount, uint32_t firstIndex, int32_t baseVertex, uint32_t firstInstance) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderDrawIndexedIndirect(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderDrawIndirect(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderEnd(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderEndOcclusionQuery(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderExecuteBundles(WGPURenderPassEncoder renderPassEncoder, size_t bundleCount, WGPURenderBundle const * bundles) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderInsertDebugMarker(WGPURenderPassEncoder renderPassEncoder, WGPUStringView markerLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderMultiDrawIndexedIndirect(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset, uint32_t maxDrawCount, WGPU_NULLABLE WGPUBuffer drawCountBuffer, uint64_t drawCountBufferOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderMultiDrawIndirect(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer indirectBuffer, uint64_t indirectOffset, uint32_t maxDrawCount, WGPU_NULLABLE WGPUBuffer drawCountBuffer, uint64_t drawCountBufferOffset) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderPixelLocalStorageBarrier(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderPopDebugGroup(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderPushDebugGroup(WGPURenderPassEncoder renderPassEncoder, WGPUStringView groupLabel) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetBindGroup(WGPURenderPassEncoder renderPassEncoder, uint32_t groupIndex, WGPU_NULLABLE WGPUBindGroup group, size_t dynamicOffsetCount, uint32_t const * dynamicOffsets) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetBlendConstant(WGPURenderPassEncoder renderPassEncoder, WGPUColor const * color) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetIndexBuffer(WGPURenderPassEncoder renderPassEncoder, WGPUBuffer buffer, WGPUIndexFormat format, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetLabel(WGPURenderPassEncoder renderPassEncoder, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetPipeline(WGPURenderPassEncoder renderPassEncoder, WGPURenderPipeline pipeline) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetScissorRect(WGPURenderPassEncoder renderPassEncoder, uint32_t x, uint32_t y, uint32_t width, uint32_t height) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetStencilReference(WGPURenderPassEncoder renderPassEncoder, uint32_t reference) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetVertexBuffer(WGPURenderPassEncoder renderPassEncoder, uint32_t slot, WGPU_NULLABLE WGPUBuffer buffer, uint64_t offset, uint64_t size) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderSetViewport(WGPURenderPassEncoder renderPassEncoder, float x, float y, float width, float height, float minDepth, float maxDepth) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderWriteTimestamp(WGPURenderPassEncoder renderPassEncoder, WGPUQuerySet querySet, uint32_t queryIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderAddRef(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPassEncoderRelease(WGPURenderPassEncoder renderPassEncoder) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of RenderPipeline +WGPU_EXPORT WGPUBindGroupLayout wgpuRenderPipelineGetBindGroupLayout(WGPURenderPipeline renderPipeline, uint32_t groupIndex) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPipelineSetLabel(WGPURenderPipeline renderPipeline, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPipelineAddRef(WGPURenderPipeline renderPipeline) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuRenderPipelineRelease(WGPURenderPipeline renderPipeline) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Sampler +WGPU_EXPORT void wgpuSamplerSetLabel(WGPUSampler sampler, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSamplerAddRef(WGPUSampler sampler) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSamplerRelease(WGPUSampler sampler) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of ShaderModule +WGPU_EXPORT void wgpuShaderModuleGetCompilationInfo(WGPUShaderModule shaderModule, WGPUCompilationInfoCallback callback, void * userdata) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuShaderModuleGetCompilationInfo2(WGPUShaderModule shaderModule, WGPUCompilationInfoCallbackInfo2 callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUFuture wgpuShaderModuleGetCompilationInfoF(WGPUShaderModule shaderModule, WGPUCompilationInfoCallbackInfo callbackInfo) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuShaderModuleSetLabel(WGPUShaderModule shaderModule, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuShaderModuleAddRef(WGPUShaderModule shaderModule) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuShaderModuleRelease(WGPUShaderModule shaderModule) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of SharedBufferMemory +WGPU_EXPORT WGPUStatus wgpuSharedBufferMemoryBeginAccess(WGPUSharedBufferMemory sharedBufferMemory, WGPUBuffer buffer, WGPUSharedBufferMemoryBeginAccessDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBuffer wgpuSharedBufferMemoryCreateBuffer(WGPUSharedBufferMemory sharedBufferMemory, WGPU_NULLABLE WGPUBufferDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuSharedBufferMemoryEndAccess(WGPUSharedBufferMemory sharedBufferMemory, WGPUBuffer buffer, WGPUSharedBufferMemoryEndAccessState * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuSharedBufferMemoryGetProperties(WGPUSharedBufferMemory sharedBufferMemory, WGPUSharedBufferMemoryProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBool wgpuSharedBufferMemoryIsDeviceLost(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedBufferMemorySetLabel(WGPUSharedBufferMemory sharedBufferMemory, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedBufferMemoryAddRef(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedBufferMemoryRelease(WGPUSharedBufferMemory sharedBufferMemory) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of SharedFence +WGPU_EXPORT void wgpuSharedFenceExportInfo(WGPUSharedFence sharedFence, WGPUSharedFenceExportInfo * info) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedFenceAddRef(WGPUSharedFence sharedFence) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedFenceRelease(WGPUSharedFence sharedFence) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of SharedTextureMemory +WGPU_EXPORT WGPUStatus wgpuSharedTextureMemoryBeginAccess(WGPUSharedTextureMemory sharedTextureMemory, WGPUTexture texture, WGPUSharedTextureMemoryBeginAccessDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTexture wgpuSharedTextureMemoryCreateTexture(WGPUSharedTextureMemory sharedTextureMemory, WGPU_NULLABLE WGPUTextureDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuSharedTextureMemoryEndAccess(WGPUSharedTextureMemory sharedTextureMemory, WGPUTexture texture, WGPUSharedTextureMemoryEndAccessState * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuSharedTextureMemoryGetProperties(WGPUSharedTextureMemory sharedTextureMemory, WGPUSharedTextureMemoryProperties * properties) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUBool wgpuSharedTextureMemoryIsDeviceLost(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedTextureMemorySetLabel(WGPUSharedTextureMemory sharedTextureMemory, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedTextureMemoryAddRef(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSharedTextureMemoryRelease(WGPUSharedTextureMemory sharedTextureMemory) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Surface +WGPU_EXPORT void wgpuSurfaceConfigure(WGPUSurface surface, WGPUSurfaceConfiguration const * config) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUStatus wgpuSurfaceGetCapabilities(WGPUSurface surface, WGPUAdapter adapter, WGPUSurfaceCapabilities * capabilities) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceGetCurrentTexture(WGPUSurface surface, WGPUSurfaceTexture * surfaceTexture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfacePresent(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceSetLabel(WGPUSurface surface, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceUnconfigure(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceAddRef(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuSurfaceRelease(WGPUSurface surface) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of Texture +WGPU_EXPORT WGPUTextureView wgpuTextureCreateErrorView(WGPUTexture texture, WGPU_NULLABLE WGPUTextureViewDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTextureView wgpuTextureCreateView(WGPUTexture texture, WGPU_NULLABLE WGPUTextureViewDescriptor const * descriptor) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureDestroy(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuTextureGetDepthOrArrayLayers(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTextureDimension wgpuTextureGetDimension(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTextureFormat wgpuTextureGetFormat(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuTextureGetHeight(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuTextureGetMipLevelCount(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuTextureGetSampleCount(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT WGPUTextureUsage wgpuTextureGetUsage(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT uint32_t wgpuTextureGetWidth(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureSetLabel(WGPUTexture texture, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureAddRef(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureRelease(WGPUTexture texture) WGPU_FUNCTION_ATTRIBUTE; + +// Methods of TextureView +WGPU_EXPORT void wgpuTextureViewSetLabel(WGPUTextureView textureView, WGPUStringView label) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureViewAddRef(WGPUTextureView textureView) WGPU_FUNCTION_ATTRIBUTE; +WGPU_EXPORT void wgpuTextureViewRelease(WGPUTextureView textureView) WGPU_FUNCTION_ATTRIBUTE; + + +#endif // !defined(WGPU_SKIP_DECLARATIONS) + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif // WEBGPU_H_ diff --git a/tinygrad_repo/mkdocs.yml b/tinygrad_repo/mkdocs.yml index 871ca8a148..d06f81c201 100644 --- a/tinygrad_repo/mkdocs.yml +++ b/tinygrad_repo/mkdocs.yml @@ -22,11 +22,14 @@ nav: - Runtime: runtime.md - Developer: - Intro: developer/developer.md - - Function (autodiff): developer/function.md + - Speed: developer/speed.md - UOp: developer/uop.md + - Grouper: + - developer/kernelize.md - Runtime: - developer/runtime.md - HCQ: developer/hcq.md + - AM Driver: developer/am.md - tinybox: tinybox.md #- tinygrad: reference/ diff --git a/tinygrad_repo/setup.py b/tinygrad_repo/setup.py index d4048c756b..a5fe80b3bd 100644 --- a/tinygrad_repo/setup.py +++ b/tinygrad_repo/setup.py @@ -7,16 +7,27 @@ directory = Path(__file__).resolve().parent with open(directory / 'README.md', encoding='utf-8') as f: long_description = f.read() +testing_minimal = [ + "numpy", + "torch", + "pytest", + "pytest-xdist", + "hypothesis", + "z3-solver", + "ml_dtypes" +] + setup(name='tinygrad', - version='0.10.0', + version='0.10.3', description='You like pytorch? You like micrograd? You love tinygrad! <3', author='George Hotz', license='MIT', long_description=long_description, long_description_content_type='text/markdown', - packages = ['tinygrad', 'tinygrad.runtime.autogen', 'tinygrad.codegen', 'tinygrad.nn', 'tinygrad.renderer', 'tinygrad.engine', - 'tinygrad.runtime', 'tinygrad.runtime.support', 'tinygrad.runtime.graph', 'tinygrad.shape'], - package_data = {'tinygrad': ['py.typed']}, + packages = ['tinygrad', 'tinygrad.runtime.autogen', 'tinygrad.runtime.autogen.am', 'tinygrad.codegen', 'tinygrad.nn', + 'tinygrad.renderer', 'tinygrad.engine', 'tinygrad.viz', 'tinygrad.runtime', 'tinygrad.runtime.support', + 'tinygrad.runtime.support.am', 'tinygrad.runtime.graph', 'tinygrad.shape', 'tinygrad.uop'], + package_data = {'tinygrad': ['py.typed'], 'tinygrad.viz': ['index.html', 'perfetto.html', 'assets/**/*', 'lib/**/*']}, classifiers=[ "Programming Language :: Python :: 3", "License :: OSI Approved :: MIT License" @@ -24,7 +35,6 @@ setup(name='tinygrad', install_requires=[], python_requires='>=3.10', extras_require={ - 'llvm': ["llvmlite"], 'arm': ["unicorn"], 'triton': ["triton-nightly>=2.1.0.dev20231014192330"], 'linting': [ @@ -33,18 +43,20 @@ setup(name='tinygrad', "typing-extensions", "pre-commit", "ruff", - "types-tqdm", - ], - #'mlperf': ["mlperf-logging @ git+https://github.com/mlperf/logging.git@4.1.0-rc3"], - 'testing': [ "numpy", - "torch", - "jax", + ], + #'mlperf': ["mlperf-logging @ git+https://github.com/mlperf/logging.git@5.0.0-rc3"], + 'testing_minimal': testing_minimal, + 'testing_unit': testing_minimal + [ + "tqdm", + "safetensors", + "tabulate", # for sz.py + ], + 'testing': testing_minimal + [ "pillow", - "pytest", - "pytest-xdist", - "onnx==1.16.0", + "onnx==1.17.0", "onnx2torch", + "onnxruntime", "opencv-python", "tabulate", "tqdm", @@ -55,12 +67,15 @@ setup(name='tinygrad', "blobfile", "librosa", "networkx", - "hypothesis", "nibabel", "bottle", - "ggml-python" + "ggml-python", + "capstone", + "pycocotools", + "boto3", + "pandas", + "influxdb3-python" ], - 'webgpu': ["wgpu"], 'docs': [ "mkdocs", "mkdocs-material", @@ -73,6 +88,6 @@ setup(name='tinygrad', 'testing_tf': [ "tensorflow==2.15.1", "tensorflow_addons", - ] + ], }, include_package_data=True) diff --git a/tinygrad_repo/sz.py b/tinygrad_repo/sz.py index d224831a48..3bd5abf5cd 100755 --- a/tinygrad_repo/sz.py +++ b/tinygrad_repo/sz.py @@ -10,18 +10,24 @@ TOKEN_WHITELIST = [token.OP, token.NAME, token.NUMBER, token.STRING] def is_docstring(t): return t.type == token.STRING and t.string.startswith('"""') and t.line.strip().startswith('"""') +def is_js_token(s): return len(s) and not s.startswith('//') + def gen_stats(base_path="."): table = [] for path, _, files in os.walk(os.path.join(base_path, "tinygrad")): for name in files: - if not name.endswith(".py"): continue - if 'tinygrad/runtime/autogen' in path.replace('\\', '/'): continue + if not (name.endswith(".py") or name.endswith(".js")): continue + if any(s in path.replace('\\', '/') for s in ['tinygrad/runtime/autogen', 'tinygrad/viz/assets']): continue filepath = os.path.join(path, name) relfilepath = os.path.relpath(filepath, base_path).replace('\\', '/') - with tokenize.open(filepath) as file_: - tokens = [t for t in tokenize.generate_tokens(file_.readline) if t.type in TOKEN_WHITELIST and not is_docstring(t)] - token_count, line_count = len(tokens), len(set([x for t in tokens for x in range(t.start[0], t.end[0]+1)])) - if line_count > 0: table.append([relfilepath, line_count, token_count/line_count]) + if name.endswith(".js"): + with open(filepath) as file_: lines = [line.strip() for line in file_.readlines()] + token_count, line_count = sum(len(line.split()) for line in lines if is_js_token(line)), sum(1 for line in lines if is_js_token(line)) + else: + with tokenize.open(filepath) as file_: + tokens = [t for t in tokenize.generate_tokens(file_.readline) if t.type in TOKEN_WHITELIST and not is_docstring(t)] + token_count, line_count = len(tokens), len(set([x for t in tokens for x in range(t.start[0], t.end[0]+1)])) + if line_count > 0: table.append([relfilepath, line_count, token_count/line_count]) return table def gen_diff(table_old, table_new): @@ -69,7 +75,8 @@ if __name__ == "__main__": print("```") else: print(tabulate([headers] + sorted(table, key=lambda x: -x[1]), headers="firstrow", floatfmt=".1f")+"\n") - for dir_name, group in itertools.groupby(sorted([(x[0].rsplit("/", 1)[0], x[1], x[2]) for x in table]), key=lambda x:x[0]): + groups = sorted([('/'.join(x[0].rsplit("/", 1)[0].split("/")[0:2]), x[1], x[2]) for x in table]) + for dir_name, group in itertools.groupby(groups, key=lambda x:x[0]): print(f"{dir_name:30s} : {sum([x[1] for x in group]):6d}") total_lines = sum([x[1] for x in table]) print(f"\ntotal line count: {total_lines}") diff --git a/tinygrad_repo/test/external/external_becnhmark_am.py b/tinygrad_repo/test/external/external_becnhmark_am.py new file mode 100644 index 0000000000..6ac8bbfdb0 --- /dev/null +++ b/tinygrad_repo/test/external/external_becnhmark_am.py @@ -0,0 +1,9 @@ +from tinygrad.helpers import Profiling +from tinygrad import Device + +if __name__ == "__main__": + am = Device["AMD"] + + # kfd is 0.55ms! + with Profiling("allocation 127.7mb"): + am.allocator.alloc(int(127.7*1024*1024)) diff --git a/tinygrad_repo/test/external/external_benchmark_bert_matmuls.py b/tinygrad_repo/test/external/external_benchmark_bert_matmuls.py new file mode 100644 index 0000000000..b83e6d4809 --- /dev/null +++ b/tinygrad_repo/test/external/external_benchmark_bert_matmuls.py @@ -0,0 +1,18 @@ +from tinygrad import Tensor, dtypes +dtypes.default_float = dtypes.float16 +from tinygrad.dtype import to_dtype +from tinygrad.helpers import getenv + +if __name__ == "__main__": + # matmuls in bert layers + BS = getenv("BS", 96//6) + acc_dtype = to_dtype(getenv("ACC_DTYPE", "half")) + tensors = [ + (Tensor.empty(BS, 512, 1024), Tensor.empty(1024, 1024).T), # linear to get qkv + (Tensor.empty(BS, 512, 16, 64).permute(0,2,1,3), Tensor.empty(BS, 512, 16, 64).permute(0,2,3,1)), # q@k + (Tensor.empty(BS, 16, 512, 512), Tensor.empty(BS, 512, 16, 64).permute(0,2,1,3)), # qk@v + ] + for t0, t1 in tensors: + print(f"{t0.shape=}, {t0.lazydata.st.real_strides()=}, {t1.shape=}, {t1.lazydata.st.real_strides()=}") + for _ in range(5): + t0.dot(t1, dtype=acc_dtype).realize() diff --git a/tinygrad_repo/test/external/external_benchmark_bert_softmax.py b/tinygrad_repo/test/external/external_benchmark_bert_softmax.py new file mode 100644 index 0000000000..176e2061a4 --- /dev/null +++ b/tinygrad_repo/test/external/external_benchmark_bert_softmax.py @@ -0,0 +1,18 @@ +from tinygrad import Tensor, dtypes, Context, GlobalCounters +dtypes.default_float = dtypes.float16 +from tinygrad.dtype import to_dtype +from tinygrad.helpers import getenv +from test.test_softmax_fusion import single_kernel_softmax + +if __name__ == "__main__": + # softmax in bert layers + BS = getenv("BS", 96//6) + acc_dtype = to_dtype(getenv("ACC_DTYPE", "half")) + t = Tensor.empty(BS, 16, 512, 512) + t.softmax(-1, dtype="half").realize() + + # test single kernel softmax + GlobalCounters.reset() + with Context(DONT_GROUP_REDUCES=1): + single_kernel_softmax(t, -1, acc_dtype).realize() + diff --git a/tinygrad_repo/test/external/external_benchmark_disk_raw.py b/tinygrad_repo/test/external/external_benchmark_disk_raw.py new file mode 100644 index 0000000000..6566ae4109 --- /dev/null +++ b/tinygrad_repo/test/external/external_benchmark_disk_raw.py @@ -0,0 +1,7 @@ +import pathlib +from tinygrad import Tensor, Device, Context + +if __name__ == "__main__": + with Context(DEBUG=2): + disk_llama = Tensor(pathlib.Path("/raid/weights/LLaMA-3/8B/consolidated.00.pth")) + device_llama = disk_llama.to(Device.DEFAULT).realize() diff --git a/tinygrad_repo/test/external/external_benchmark_hcopt.py b/tinygrad_repo/test/external/external_benchmark_hcopt.py index 252b0531c6..c2ed276e2e 100644 --- a/tinygrad_repo/test/external/external_benchmark_hcopt.py +++ b/tinygrad_repo/test/external/external_benchmark_hcopt.py @@ -1,11 +1,12 @@ import random from tinygrad.helpers import getenv -from tinygrad.engine.search import time_linearizer, beam_search, bufs_from_lin -from extra.optimization.helpers import load_worlds, ast_str_to_lin +from tinygrad.engine.search import beam_search, bufs_from_lin +from tinygrad.codegen.heuristic import hand_coded_optimizations +from extra.optimization.helpers import load_worlds, ast_str_to_lin, time_linearizer def optimize_kernel(k): # TODO: update this - return k.hand_coded_optimizations() + return hand_coded_optimizations(k) if __name__ == '__main__': hcopt_wins = beam_wins = tie = 0 @@ -19,7 +20,8 @@ if __name__ == '__main__': k = ast_str_to_lin(world) rawbufs = bufs_from_lin(k) - k_hcopt = optimize_kernel(k.copy()) + k_hcopt = k.copy() + k_hcopt.apply_opts(optimize_kernel(k_hcopt)) k_beam = beam_search(k.copy(), rawbufs, getenv("BEAM", 2)) disable_cache = bool(getenv("NOCACHE", 0)) diff --git a/tinygrad_repo/test/external/external_benchmark_kernel_launch.py b/tinygrad_repo/test/external/external_benchmark_kernel_launch.py new file mode 100644 index 0000000000..5744ba0923 --- /dev/null +++ b/tinygrad_repo/test/external/external_benchmark_kernel_launch.py @@ -0,0 +1,38 @@ +import time +from tinygrad import Tensor, TinyJit, Device, Context +from tinygrad.helpers import Profiling, Timing, GlobalCounters + +# python3 test/test_speed_v_torch.py TestSpeed.test_add_a + +@TinyJit +def plus(a:Tensor, b:Tensor): return a+b + +if __name__ == "__main__": + a = Tensor([1]).realize() + b = Tensor([1]).realize() + for i in range(5): + with Timing(prefix=f"{i}:"): + c = plus(a,b) + Device[c.device].synchronize() + assert c.item() == 2 + for i in range(5): + st = time.perf_counter() + c = plus(a,b) + et = time.perf_counter() - st + Device[c.device].synchronize() + print(f"nosync {i}: {et*1e6:.2f} us") + for i in range(5): + st = time.perf_counter() + c = plus(a,b) + Device[c.device].synchronize() + et = time.perf_counter() - st + print(f"precise {i}: {et*1e6:.2f} us") + assert GlobalCounters.time_sum_s == 0 + with Context(DEBUG=2): + st = time.perf_counter() + c = plus(a,b) + Device[c.device].synchronize() + et = time.perf_counter() - st + print(f"kernel {GlobalCounters.time_sum_s*1e3:.2f} ms / full {et*1e3:.2f} ms -- {et/(GlobalCounters.time_sum_s+1e-12):.2f} x") + with Profiling(): + c = plus(a,b) diff --git a/tinygrad_repo/test/external/external_benchmark_multitensor_allreduce.py b/tinygrad_repo/test/external/external_benchmark_multitensor_allreduce.py index e3ed9c5aab..e2fd001a0d 100644 --- a/tinygrad_repo/test/external/external_benchmark_multitensor_allreduce.py +++ b/tinygrad_repo/test/external/external_benchmark_multitensor_allreduce.py @@ -1,33 +1,20 @@ -import time -from tinygrad import Tensor, Device, GlobalCounters, TinyJit -from tinygrad.ops import Ops, UOp -from tinygrad.multi import MultiLazyBuffer, all_reduce -from tinygrad.engine.schedule import create_schedule -from tinygrad.engine.realize import run_schedule +from tinygrad import Tensor, Device, GlobalCounters, TinyJit, dtypes from tinygrad.helpers import getenv, Context, RING, DEBUG -from typing import List, Union -def realize(x: Union[UOp, List[UOp]]): - x = x if isinstance(x, list) else [x] - run_schedule(create_schedule(x)) - for lb in x: Device[lb.device].synchronize() - -def test(devs: List[str], N: int, iters:int = 10): - def _wrapped(op: Ops, t: Tensor) -> Tensor: - return Tensor(MultiLazyBuffer(all_reduce(op, t.lazydata.lbs), 0), device=devs) - _jitted = TinyJit(_wrapped) if getenv("USEJIT", 1) == 1 else _wrapped +def test(devs: list[str], N: int, iters:int = 10): + @TinyJit + def f(t: Tensor) -> Tensor: t.sum(0).realize() secs, gflops, gbs = 0, 0, 0 - for i in range(-2, iters): - lbs = [Tensor.full((N,), float(1+i), device=d).contiguous().lazydata for i,d in enumerate(devs)] - realize(lbs) + for i in range(-3, iters): + t = Tensor.empty((len(devs), N)) + t = t.shard(devs, 0).realize() GlobalCounters.reset() - start = time.time() - realize(_jitted(Ops.ADD, Tensor(MultiLazyBuffer(lbs, 0), device=devs)).lazydata.lbs) - if i < 0: continue # warm up jit - i_secs = time.time() - start + f(t) + for d in devs: Device[d].synchronize() - if DEBUG >= 2: i_secs = GlobalCounters.time_sum_s + if i < 0: continue # warm up jit + i_secs = GlobalCounters.time_sum_s i_gflops = GlobalCounters.global_ops/i_secs/10**9 i_gbs = (N*4)/i_secs/10**9 print(f"{'ring_allreduce' if RING >= 2 else 'naive_allreduce'} iter {i+1}/{iters}: {i_secs:.6f} sec {i_gflops:.2f} GFLOP/s {i_gbs:.2f} GB/s") @@ -37,34 +24,32 @@ def test(devs: List[str], N: int, iters:int = 10): return (gflops/iters, gbs/iters, secs/iters) -def run(sz, n_gpus=6, iters=10): - dev = Device.DEFAULT - devs = tuple([f"{dev}:{x}" for x in range(n_gpus)]) - N = sz // 4 # float32 is 4 bytes - - with Context(RING=2): - (ring_gflops, ring_gbs, ring_secs) = test(devs, N, iters=iters) - with Context(RING=0): - (naive_gflops, naive_gbs, naive_secs) = test(devs, N, iters=iters) - return (ring_gflops, ring_gbs, ring_secs), (naive_gflops, naive_gbs, naive_secs) +def run(sz, n_gpus=6, iters=10, use_ring=False): + devs = tuple([f"{Device.DEFAULT}:{x}" for x in range(n_gpus)]) + N = sz // dtypes.float32.itemsize + with Context(RING=(2 if use_ring else 0), DEBUG=max(DEBUG.value, 2)): return test(devs, N, iters=iters) def main(): + ONLY_RING = getenv("ONLY_RING", 0) n_gpus = getenv("GPUS", 6) + iters = getenv("ITERS", 10) if getenv("BENCHMARK_SPLIT"): l, r = 0, 512 while r - l > 1: m = (l + r) // 2 - (ring_gflops, ring_gbs, ring_secs), (naive_gflops, naive_gbs, naive_secs) = run(m * 1024 * 4, n_gpus=n_gpus, iters=100) + (ring_gflops, ring_gbs, ring_secs) = run(m * 1024 * 4, n_gpus=n_gpus, iters=100, use_ring=True) + (naive_gflops, naive_gbs, naive_secs) = run(m * 1024 * 4, n_gpus=n_gpus, iters=100, use_ring=False) if ring_secs > naive_secs: l = m else: r = m print("Better split", r * 1024, "elements") else: sz = getenv("SZ", 1000) * 10**6 # size of data on each gpu print(f"Using {sz/10**9:.2f} GB of numbers on each of {n_gpus} GPUs, {n_gpus*sz/10**9:.2f} GB total.") - (ring_gflops, ring_gbs, ring_secs), (naive_gflops, naive_gbs, naive_secs) = run(sz) + (ring_gflops, ring_gbs, ring_secs) = run(sz, use_ring=True, n_gpus=n_gpus, iters=iters) + if not ONLY_RING: (naive_gflops, naive_gbs, naive_secs) = run(sz, use_ring=False, n_gpus=n_gpus, iters=iters) print(f"Ring:\n {ring_secs:.6f} seconds/iter\n {ring_gflops:.2f} GFLOP/s\n {ring_gbs:.2f} GB/s") - print(f"Naive:\n {naive_secs:.6f} seconds/iter\n {naive_gflops:.2f} GFLOP/s\n {naive_gbs:.2f} GB/s") + if not ONLY_RING: print(f"Naive:\n {naive_secs:.6f} seconds/iter\n {naive_gflops:.2f} GFLOP/s\n {naive_gbs:.2f} GB/s") if __name__ == "__main__": main() diff --git a/tinygrad_repo/test/external/external_benchmark_openpilot.py b/tinygrad_repo/test/external/external_benchmark_openpilot.py index 2811ec891c..7316a11bb0 100644 --- a/tinygrad_repo/test/external/external_benchmark_openpilot.py +++ b/tinygrad_repo/test/external/external_benchmark_openpilot.py @@ -2,20 +2,18 @@ import time, sys, hashlib from pathlib import Path import onnx from onnx.helper import tensor_dtype_to_np_dtype -from extra.onnx import get_run_onnx +from tinygrad.frontend.onnx import OnnxRunner from tinygrad import Tensor, dtypes, TinyJit from tinygrad.helpers import IMAGE, GlobalCounters, fetch, colored, getenv, trange from tinygrad.tensor import _from_np_dtype import numpy as np +from extra.bench_log import BenchEvent, WallTimeEvent OPENPILOT_MODEL = sys.argv[1] if len(sys.argv) > 1 else "https://github.com/commaai/openpilot/raw/v0.9.4/selfdrive/modeld/models/supercombo.onnx" if __name__ == "__main__": - Tensor.no_grad = True - Tensor.training = False - onnx_model = onnx.load(onnx_path := fetch(OPENPILOT_MODEL)) - run_onnx = get_run_onnx(onnx_model) + run_onnx = OnnxRunner(onnx_model) Tensor.manual_seed(100) input_shapes = {inp.name:tuple(x.dim_value for x in inp.type.tensor_type.shape.dim) for inp in onnx_model.graph.input} @@ -36,10 +34,11 @@ if __name__ == "__main__": for _ in range(20): GlobalCounters.reset() st = time.perf_counter_ns() - # Need to cast non-image inputs from numpy, this is only realistic way to run model - inputs = {**{k:v for k,v in new_inputs_junk.items() if 'img' in k}, - **{k:Tensor(v) for k,v in new_inputs_junk_numpy.items() if 'img' not in k}} - ret = next(iter(run_onnx_jit(**inputs).values())).cast(dtypes.float32).numpy() + with WallTimeEvent(BenchEvent.STEP): + # Need to cast non-image inputs from numpy, this is only realistic way to run model + inputs = {**{k:v for k,v in new_inputs_junk.items() if 'img' in k}, + **{k:Tensor(v) for k,v in new_inputs_junk_numpy.items() if 'img' not in k}} + ret = next(iter(run_onnx_jit(**inputs).values())).cast(dtypes.float32).numpy() print(f"jitted: {(time.perf_counter_ns() - st)*1e-6:7.4f} ms") suffix = "" diff --git a/tinygrad_repo/test/external/external_benchmark_schedule.py b/tinygrad_repo/test/external/external_benchmark_schedule.py index 9ffe213cb8..6b606eeb23 100644 --- a/tinygrad_repo/test/external/external_benchmark_schedule.py +++ b/tinygrad_repo/test/external/external_benchmark_schedule.py @@ -1,12 +1,11 @@ from typing import List from extra.models.resnet import ResNet50 -from tinygrad import Tensor, Device, nn +from tinygrad import Tensor, nn from tinygrad.helpers import Profiling, Timing, getenv, BEAM, NOOPT, DEBUG, Context, ansilen -from tinygrad.ops import Ops +from tinygrad.uop.ops import Ops from tinygrad.codegen.kernel import Kernel -from tinygrad.codegen.lowerer import rewrite_shapetracker_with_index -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.codegen.uopgraph import full_graph_rewrite +from tinygrad.codegen.heuristic import hand_coded_optimizations +from tinygrad.codegen import get_rewrites_for_renderer, apply_rewrites from tinygrad.engine.search import beam_search, bufs_from_lin if __name__ == "__main__": @@ -14,9 +13,10 @@ if __name__ == "__main__": for p in nn.state.get_parameters(mdl): p.replace(Tensor.empty(p.shape)) img = Tensor.empty(64, 3, 224, 224) - PROFILE = getenv("PROFILE", 0) + PROFILE = getenv("PYPROFILE", 0) FORWARD_ONLY = getenv("FORWARD_ONLY", 0) SCHEDULE_ONLY = getenv("SCHEDULE_ONLY", 0) + LINEARIZE = bool(getenv("LINEARIZE", 1)) with Timing("all "): with Timing("***** model tensor in "): @@ -37,21 +37,17 @@ if __name__ == "__main__": if BEAM: with Context(DEBUG=max(2, DEBUG.value)): k = beam_search(k, bufs_from_lin(k), BEAM.value) elif NOOPT: pass - else: k.hand_coded_optimizations() + else: k.apply_opts(hand_coded_optimizations(k)) kernels.append(k) - with Timing("***** model lower in "): uops = [rewrite_shapetracker_with_index(k.get_optimized_ast(), k.opts) for k in kernels] + with Timing("***** model prep in "): + kernels = [(k, k.get_optimized_ast(), get_rewrites_for_renderer(k.opts, linearizer=LINEARIZE)) for k in kernels] + with Profiling(PROFILE, fn="/tmp/rewrite.prof"): with Timing("***** model rewrite in "): rewritten_uops = [] - for i,(k,u) in enumerate(zip(kernels, uops)): + for i,(k,u,rewrites) in enumerate(kernels): with Timing(f"rewrite {i:2d} {k.name}{' '*(50-ansilen(k.name))}", enabled=getenv("VERBOSE", 0)): - rewritten_uops.append(full_graph_rewrite(u, k.opts)) + rewritten_uops.append(apply_rewrites(u, rewrites)) uops = rewritten_uops - if getenv("LINEARIZE", 1): - with Profiling(PROFILE >= 2): - with Timing("***** model linearize in "): uops = [linearize_uop(u) for u in uops] - print(sum(len(u) for u in uops)) - if getenv("SRC", 0): - renderer = Device[Device.DEFAULT].renderer - for k,u in zip(kernels, uops): print(renderer.render(k.name, u)) + if LINEARIZE: print(sum(len(u.arg.lst) for u in uops)) diff --git a/tinygrad_repo/test/external/external_benchmark_sdxl_softmax.py b/tinygrad_repo/test/external/external_benchmark_sdxl_softmax.py new file mode 100644 index 0000000000..35cf06b0b0 --- /dev/null +++ b/tinygrad_repo/test/external/external_benchmark_sdxl_softmax.py @@ -0,0 +1,27 @@ +from tinygrad import Tensor, dtypes, GlobalCounters + +if __name__ == "__main__": + t = Tensor.empty(81920, 4096, dtype=dtypes.half) + GlobalCounters.reset() + t.softmax(-1, dtype="half").realize() + GlobalCounters.reset() + t.softmax(-1, dtype="half", _single_kernel=True).realize() + + from tinygrad.codegen.kernel import Kernel, Opt, OptOps + from tinygrad.helpers import get_single_element + GlobalCounters.reset() + si = get_single_element(t.softmax(-1, dtype="half", _single_kernel=True).schedule()) + k = Kernel(si.ast) + #k.apply_opt(Opt(OptOps.UPCAST, 0, 4)) + k.apply_opt(Opt(OptOps.UPCAST, 1, 4)) + k.apply_opt(Opt(OptOps.LOCAL, 1, 32)) + #k.apply_opt(Opt(OptOps.LOCAL, 0, 8)) + k.apply_opt(Opt(OptOps.UNROLL, 1, 4)) + k.apply_opt(Opt(OptOps.UNROLL, 0, 4)) + #k.apply_opt(Opt(OptOps.GROUP, 1, 256)) + #k.apply_opt(Opt(OptOps.GROUP, 0, 32)) + #k.apply_opt(Opt(OptOps.GROUP, 1, 32)) + #k.apply_opt(Opt(OptOps.GROUP, 0, 32)) + from tinygrad.engine.realize import CompiledRunner, ExecItem + run = CompiledRunner(prg:=k.to_program()) + ExecItem(run, si.bufs).run() diff --git a/tinygrad_repo/test/external/external_debug_metal_sd_conv.py b/tinygrad_repo/test/external/external_debug_metal_sd_conv.py index 2e9315c5ba..cbdd93f88b 100644 --- a/tinygrad_repo/test/external/external_debug_metal_sd_conv.py +++ b/tinygrad_repo/test/external/external_debug_metal_sd_conv.py @@ -3,7 +3,7 @@ from tinygrad.codegen.kernel import Kernel, Opt, OptOps from tinygrad.dtype import dtypes from tinygrad.engine.realize import CompiledRunner from tinygrad.engine.search import bufs_from_lin -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import View @@ -29,10 +29,10 @@ ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=4, src=()), x17,)),)),)),)) -opts = [Opt(op=OptOps.UPCAST, axis=3, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UNROLL, axis=2, amt=0), Opt(op=OptOps.UNROLL, axis=1, amt=0), Opt(op=OptOps.LOCAL, axis=1, amt=8), Opt(op=OptOps.LOCAL, axis=2, amt=8), Opt(op=OptOps.LOCAL, axis=2, amt=2)] +opts = [Opt(op=OptOps.UPCAST, axis=3, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UNROLL, axis=2, arg=0), Opt(op=OptOps.UNROLL, axis=1, arg=0), Opt(op=OptOps.LOCAL, axis=1, arg=8), Opt(op=OptOps.LOCAL, axis=2, arg=8), Opt(op=OptOps.LOCAL, axis=2, arg=2)] k = Kernel(ast) -for opt in opts: k.apply_opt(opt) +k.apply_opts(opts) bufs = bufs_from_lin(k) prg = CompiledRunner(k.to_program()) diff --git a/tinygrad_repo/test/external/external_fuzz_am_interrupts.py b/tinygrad_repo/test/external/external_fuzz_am_interrupts.py new file mode 100644 index 0000000000..2ed5724288 --- /dev/null +++ b/tinygrad_repo/test/external/external_fuzz_am_interrupts.py @@ -0,0 +1,39 @@ +import subprocess +import random +import time +from concurrent.futures import ThreadPoolExecutor, as_completed + +def run_test(i, full_run=False): + print(f"\rRunning iteration {i}...", end=" ", flush=True) + + p = subprocess.Popen(['python3', 'test/test_tiny.py', 'TestTiny.test_plus'], stdout=subprocess.PIPE, stderr=subprocess.PIPE) + + if not full_run: + time.sleep(random.uniform(0, 1200) / 1000) + p.kill() + _, stderr = p.communicate() + else: + _, stderr = p.communicate() + + if full_run: + stderr_text = stderr.decode() + print(stderr_text) + assert "Ran 1 test in" in stderr_text and "OK" in stderr_text + +max_workers = 4 +with ThreadPoolExecutor(max_workers=max_workers) as executor: + futures = [] + for i in range(1000000): + if i % 100 == 0: + for future in as_completed(futures): + try: future.result() + except Exception as e: + print(f"\nError in iteration: {e}") + futures = [] + + run_test(i, True) + else: + future = executor.submit(run_test, i, False) + futures.append(future) + + if len(futures) > max_workers * 2: futures = [f for f in futures if not f.done()] \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_fuzz_ampt.py b/tinygrad_repo/test/external/external_fuzz_ampt.py new file mode 100644 index 0000000000..0a280aaeee --- /dev/null +++ b/tinygrad_repo/test/external/external_fuzz_ampt.py @@ -0,0 +1,108 @@ +import random +from tinygrad.helpers import round_up +from tinygrad.runtime.support.am.amdev import AMPageTableTraverseContext +from test.external.external_test_am import helper_read_entry_components, FakeAM + +class AMPTFuzzer: + def __init__(self, total_size): + self.total_size = total_size + self.alloc_payload = 0 + self.d = FakeAM() + + self.allocations: dict[int, tuple[int, int]] = {} # ptr -> (size, pattern) + + self.min_alloc_size = 0x1000 + self.max_alloc_size = int(total_size * 0.1) + self.alloc_probability = 0.7 + + def generate_pattern(self, ptr: int, size: int) -> int: return random.randint(0, 0xff) + + def fill_memory(self, va, size: int, pattern: int): + ctx = AMPageTableTraverseContext(self.d, self.d.mm.root_page_table, va.va_addr) + pages = list(ctx.next(size)) + + for _offset, _pt, _pte_idx, _n_ptes, _pte_covers in pages: + _vaddr = va.va_addr + _offset + + for i in range(_n_ptes): + pte = helper_read_entry_components(_pt.entries[_pte_idx + i]) + self.d.vram[pte['paddr']] = pattern # Mark this page + assert pte['valid'] == 1 + + # If page has contigous fragment, all range should be this valid memory + frags_cnt = pte['fragment'] + contig_range = (1 << (frags_cnt + 12)) + start_vaddr = _vaddr & ~(contig_range - 1) + start_paddr = pte['paddr'] - (_vaddr - start_vaddr) + contig_ptes = contig_range // _pte_covers + assert contig_ptes > 0 + + ctx = AMPageTableTraverseContext(self.d, self.d.mm.root_page_table, start_vaddr) + frags_l = list(ctx.next(contig_range)) + for f_offset, f_pt, f_pte_idx, f_n_ptes, f_pte_covers in frags_l: + for j in range(f_n_ptes): + f_pte = helper_read_entry_components(f_pt.entries[f_pte_idx + j]) + assert f_pte['valid'] == 1 + assert f_pte['paddr'] == start_paddr+f_offset+j*f_pte_covers, f"paddr {f_pte['paddr']:#x} not {start_paddr+f_offset+j*f_pte_covers:#x}" + + _vaddr += _pte_covers + _offset += _pte_covers + + return pages + + def verify_memory(self, pages, pattern: int) -> bool: + for _offset, _pt, _pte_idx, _n_ptes, _pte_covers in pages: + for i in range(_n_ptes): + pte = helper_read_entry_components(_pt.entries[_pte_idx + i]) + if self.d.vram[pte['paddr']] != pattern: return False + if pte['valid'] == 0: return False + + return True + + def random_alloc(self): + if self.total_size - self.alloc_payload < self.min_alloc_size: return None + + size = random.randint(self.min_alloc_size, min(self.max_alloc_size, self.total_size - self.alloc_payload)) + size = round_up(size, (2 << 20) if size > (4 << 20) else (4 << 10)) + + try: ptr = self.d.mm.valloc(size) + except MemoryError: + print(f"Failed to allocate {size} bytes. Payload size is {self.alloc_payload}, so fragmenation is {(size / self.total_size)*100.0:.2f}%") + return None + + pattern = self.generate_pattern(ptr, size) + pages = self.fill_memory(ptr, size, pattern) + self.allocations[ptr.va_addr] = (size, pattern, pages, ptr) + self.alloc_payload += size + print(f"Allocated {size} bytes at {ptr.va_addr:x}, pattern: {pattern:02x}") + return ptr + + def random_free(self) -> bool: + if not self.allocations: return False + + ptr = random.choice(list(self.allocations.keys())) + size, pattern, pages, vm = self.allocations[ptr] + + # Verify pattern before freeing + if not self.verify_memory(pages, pattern): + raise RuntimeError(f"Memory corruption detected at {vm.va_addr:x}!") + + print(f"Freeing {size} bytes at {vm.va_addr:x}, pattern verified: {pattern:02x}") + self.alloc_payload -= size + self.d.mm.vfree(vm) + del self.allocations[ptr] + return True + + def run(self): + for i in range(10000000): + if (random.random() < self.alloc_probability or not self.allocations): self.random_alloc() + else: self.random_free() + + print("\nCleaning up remaining allocations...") + while self.allocations: self.random_free() + + print("Fuzzing completed successfully!") + +if __name__ == "__main__": + fuzzer = AMPTFuzzer(1 << 30) + fuzzer.run() diff --git a/tinygrad_repo/test/external/external_fuzz_hcq_signals.py b/tinygrad_repo/test/external/external_fuzz_hcq_signals.py new file mode 100644 index 0000000000..cc667c79f1 --- /dev/null +++ b/tinygrad_repo/test/external/external_fuzz_hcq_signals.py @@ -0,0 +1,31 @@ +import random +from tinygrad import Device +from tinygrad.helpers import getenv, DEBUG + +def main(): + seed = getenv("SEED", 1337) + n_gpus = getenv("GPUS", 3) + iters = getenv("ITERS", 10000000) + only_compute = bool(getenv("ONLY_COMPUTE", 0)) + + print(f"{n_gpus} GPUs for {iters} iterations, {only_compute=}, seed {seed}") + devs = tuple([Device[f"{Device.DEFAULT}:{x}"] for x in range(n_gpus)]) + + for i in range(iters): + dev = random.choice(devs) + q_t = random.choice([dev.hw_copy_queue_t, dev.hw_compute_queue_t] if not only_compute else [dev.hw_compute_queue_t]) + + deps_sigs = random.randint(0, len(devs)) + wait_devs = random.sample(devs, deps_sigs) + + q = q_t() + for d in wait_devs: q.wait(d.timeline_signal, d.timeline_value - 1) + q.wait(dev.timeline_signal, dev.timeline_value - 1).signal(dev.timeline_signal, dev.timeline_value).submit(dev) + dev.timeline_value += 1 + + if sync:=random.randint(0, 10) < 3: dev.synchronize() + if DEBUG >= 2: print(f"{i}: {q_t} {dev.device_id} timeline {dev.timeline_value}, wait for {[d.device_id for d in wait_devs]}, {sync=}") + elif i % 100 == 0: print(f"\rCompleted {i} iterations", end='') + +if __name__ == "__main__": + main() diff --git a/tinygrad_repo/test/external/external_fuzz_tlsf.py b/tinygrad_repo/test/external/external_fuzz_tlsf.py new file mode 100644 index 0000000000..512ced0b59 --- /dev/null +++ b/tinygrad_repo/test/external/external_fuzz_tlsf.py @@ -0,0 +1,79 @@ +import random +from typing import Dict, Optional +from tinygrad.helpers import getenv +from tinygrad.runtime.support.allocator import TLSFAllocator + +class AllocatorFuzzer: + def __init__(self, total_size): + self.total_size = total_size + self.alloc_payload = 0 + self.mv = memoryview(bytearray(total_size)) + self.alloctor = TLSFAllocator(total_size, block_size=16) + + self.allocations: Dict[int, tuple[int, int]] = {} # ptr -> (size, pattern) + + self.min_alloc_size = 16 + self.max_alloc_size = int(total_size * 0.3) + self.alloc_probability = 0.7 + + def generate_pattern(self, ptr: int, size: int) -> int: return (ptr * 31 + size * 17) & 0xFF + + def fill_memory(self, ptr: int, size: int, pattern: int): + for i in range(min(size, 32)): + self.mv[ptr + i] = pattern + self.mv[ptr + (size - 1 - i)] = pattern + + def verify_memory(self, ptr: int, size: int, pattern: int) -> bool: + for i in range(min(size, 32)): + assert self.mv[ptr + i] == pattern + assert self.mv[ptr + (size - 1 - i)] == pattern + return True + + def random_alloc(self) -> Optional[int]: + size = random.randint(self.min_alloc_size, min(self.max_alloc_size, self.total_size - self.alloc_payload)) + + try: + ptr = self.alloctor.alloc(size) + except MemoryError: + print(f"Failed to allocate {size} bytes. Payload size is {self.alloc_payload}, so fragmenation is {(size / self.total_size)*100.0:.2f}%") + return None + + pattern = self.generate_pattern(ptr, size) + self.fill_memory(ptr, size, pattern) + self.allocations[ptr] = (size, pattern) + self.alloc_payload += size + print(f"Allocated {size} bytes at {ptr:x}, pattern: {pattern:02x}") + return ptr + + def random_free(self) -> bool: + if not self.allocations: return False + + ptr = random.choice(list(self.allocations.keys())) + size, pattern = self.allocations[ptr] + + # Verify pattern before freeing + if not self.verify_memory(ptr, size, pattern): + raise RuntimeError(f"Memory corruption detected at {ptr:x}!") + + print(f"Freeing {size} bytes at {ptr:x}, pattern verified: {pattern:02x}") + self.alloc_payload -= size + self.alloctor.free(ptr) + del self.allocations[ptr] + return True + + def run(self): + for i in range(getenv("ITERS", 100000)): + if (random.random() < self.alloc_probability or not self.allocations): self.random_alloc() + else: self.random_free() + + print("\nCleaning up remaining allocations...") + while self.allocations: self.random_free() + + print("Fuzzing completed successfully!") + +if __name__ == "__main__": + SEED = getenv("SEED", 42) + random.seed(SEED) + + fuzzer = AllocatorFuzzer(1 << 30) + fuzzer.run() diff --git a/tinygrad_repo/test/external/external_model_benchmark.py b/tinygrad_repo/test/external/external_model_benchmark.py index 1ebe97641e..5b1199e1e4 100644 --- a/tinygrad_repo/test/external/external_model_benchmark.py +++ b/tinygrad_repo/test/external/external_model_benchmark.py @@ -6,9 +6,10 @@ import onnx from onnx.helper import tensor_dtype_to_np_dtype import onnxruntime as ort from onnx2torch import convert -from extra.onnx import get_run_onnx +from tinygrad.frontend.onnx import OnnxRunner from tinygrad.helpers import OSX, DEBUG, fetch from tinygrad import Tensor, Device +from tinygrad.device import CompileError MODELS = { "resnet50": "https://github.com/onnx/models/raw/main/validated/vision/classification/resnet/model/resnet50-caffe2-v1-9.onnx", @@ -64,7 +65,7 @@ def benchmark_model(m, devices, validate_outs=False): try: Device.DEFAULT = device inputs = {k:Tensor(inp) for k,inp in np_inputs.items()} - tinygrad_model = get_run_onnx(onnx_model) + tinygrad_model = OnnxRunner(onnx_model) benchmark(m, f"tinygrad_{device.lower()}_jitless", lambda: {k:v.numpy() for k,v in tinygrad_model(inputs).items()}) from tinygrad.engine.jit import TinyJit @@ -72,10 +73,10 @@ def benchmark_model(m, devices, validate_outs=False): 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()}) # noqa: F821 del inputs, tinygrad_model, tinygrad_jitted_model - except RuntimeError as e: + except CompileError as e: # TODO: we don't run the dm model on METAL for now if Device.DEFAULT == "METAL": - assert "buffer count limit" in str(e) + assert "no 'buffer' resource location available" in str(e) return else: raise e @@ -114,7 +115,7 @@ def benchmark_model(m, devices, validate_outs=False): rtol, atol = 2e-3, 2e-3 # tolerance for fp16 models Device.DEFAULT = device inputs = {k:Tensor(inp) for k,inp in np_inputs.items()} - tinygrad_model = get_run_onnx(onnx_model) + tinygrad_model = OnnxRunner(onnx_model) tinygrad_out = tinygrad_model(inputs) ort_sess = ort.InferenceSession(str(fn), ort_options, ["CPUExecutionProvider"]) @@ -137,7 +138,7 @@ def assert_allclose(tiny_out:dict, onnx_out:dict, rtol=1e-5, atol=1e-5): 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__": - devices = [Device.DEFAULT] if getenv("NOCLANG") else [Device.DEFAULT, "CLANG"] + devices = [Device.DEFAULT] if getenv("NOCLANG") else [Device.DEFAULT, "CPU"] if getenv("MODEL", "") != "": benchmark_model(getenv("MODEL", ""), devices, True) else: for m in MODELS: benchmark_model(m, devices, True) diff --git a/tinygrad_repo/test/external/external_multi_gpu.py b/tinygrad_repo/test/external/external_multi_gpu.py index 00c02b41cb..e5dd836c88 100644 --- a/tinygrad_repo/test/external/external_multi_gpu.py +++ b/tinygrad_repo/test/external/external_multi_gpu.py @@ -19,8 +19,8 @@ if __name__ == "__main__": with Timing("GPU initial sync: "): sync() with Timing("CPU creation: ", on_exit=lambda x: f", {(sz*4*2)/x:.2f} GB/sec"): - c0 = (Tensor.ones(sz, device="clang")/2).realize() - c1 = (Tensor.ones(sz, device="clang")/4).realize() + c0 = (Tensor.ones(sz, device="CPU")/2).realize() + c1 = (Tensor.ones(sz, device="CPU")/4).realize() print(c0.lazydata.base.realized) print(c1.lazydata.base.realized) diff --git a/tinygrad_repo/test/external/external_test_am.py b/tinygrad_repo/test/external/external_test_am.py new file mode 100644 index 0000000000..46014359ec --- /dev/null +++ b/tinygrad_repo/test/external/external_test_am.py @@ -0,0 +1,180 @@ +import unittest +from tinygrad.runtime.support.am.amdev import AMMemoryManager, AMPageTableTraverseContext +from tinygrad.runtime.support.am.ip import AM_GMC +from tinygrad.runtime.support.hcq import MMIOInterface +from tinygrad.runtime.autogen.am import am +from tinygrad.helpers import mv_address + +class FakeGMC(AM_GMC): + def __init__(self, adev): + self.adev = adev + self.vm_base = 0x0 + self.address_space_mask = (1 << 44) - 1 + def init_hw(self): pass + def flush_tlb(self, *args, **kwargs): pass + +class FakePCIDev: + def __init__(self): self.regions = [(0xc12300000000, 0xc12400000000, 0x0)] + +class FakeAM: + def __init__(self): + self.is_booting, self.smi_dev = True, False + self.pcidev = FakePCIDev() + self.vram_mv = memoryview(bytearray(4 << 30)) + self.vram = MMIOInterface(mv_address(self.vram_mv), self.vram_mv.nbytes) + self.gmc = FakeGMC(self) + self.mm = AMMemoryManager(self, vram_size=4 << 30) + self.is_booting = False + self.ip_ver = {am.GC_HWIP: (11, 0, 0)} + def paddr2cpu(self, paddr:int) -> int: return paddr + mv_address(self.vram) + def paddr2mc(self, paddr:int) -> int: return paddr + +# * PTE format: +# * 63:59 reserved +# * 58:57 reserved +# * 56 F +# * 55 L +# * 54 reserved +# * 53:52 SW +# * 51 T +# * 50:48 mtype +# * 47:12 4k physical page base address +# * 11:7 fragment +# * 6 write +# * 5 read +# * 4 exe +# * 3 Z +# * 2 snooped +# * 1 system +# * 0 valid +def helper_read_entry_components(entry_val): + return {"paddr": entry_val & 0x0000FFFFFFFFF000, "fragment":(entry_val >> 7) & 0x1f, "valid": entry_val & 0x1, + "read": (entry_val >> 5) & 0x1, "write": (entry_val >> 6) & 0x1, "exec": (entry_val >> 4) & 0x1, + "mtype": (entry_val >> 48) & 0x7, "T": (entry_val >> 51) & 0x1, "L": (entry_val >> 55) & 0x1, "F": (entry_val >> 56) & 0x1} + +class TestAMPageTable(unittest.TestCase): + @classmethod + def setUpClass(cls): + cls.d = [FakeAM() for _ in range(2)] + + def test_page_table_walkers(self): + mm = self.d[0].mm + + for va,sz in [(0x10000, 0x3000), (0x11000, 0x300000), (0x10000, 0x2000), (0x11000, 0x5000), + (0x2000000, 0x2000), (0x4000000, 0x4000000), (0x38000, 0x303000), (0x8000, 0x1000)]: + exteranl_va = va + AMMemoryManager.va_allocator.base + mm.map_range(vaddr=exteranl_va, size=sz, paddrs=[(va, sz)]) + + ctx = AMPageTableTraverseContext(self.d[0], mm.root_page_table, exteranl_va) + results = list(ctx.next(sz)) + + total_covered = 0 + for tup in results: + _offset, _pt, _pte_idx, _n_ptes, _pte_covers = tup + total_covered += _n_ptes * _pte_covers + + assert total_covered == sz, f"Expected total coverage {total_covered} to be {sz}" + + for tup in results: + _offset, _pt, _pte_idx, _n_ptes, _pte_covers = tup + for i in range(_n_ptes): + pte = helper_read_entry_components(_pt.entries[_pte_idx + i]) + assert pte['paddr'] == va + _offset + i * _pte_covers, f"Expected paddr {pte['paddr']:#x} to be {va + _offset + i * _pte_covers:#x}" + assert pte['valid'] == 1 + + mm.unmap_range(va, sz) + + for tup in results: + _offset, _pt, _pte_idx, _n_ptes, _pte_covers = tup + for i in range(_n_ptes): + pte = helper_read_entry_components(_pt.entries[_pte_idx + i]) + assert pte['paddr'] == 0 + assert pte['valid'] == 0 + + def test_double_map(self): + mm0 = self.d[0].mm + + for va,sz in [(0x10000, 0x3000), (0x1000000, 0x1000000), (0x12000, 0x4000)]: + exteranl_va = va + AMMemoryManager.va_allocator.base + mm0.map_range(vaddr=exteranl_va, size=sz, paddrs=[(va, sz)]) + + with self.assertRaises(AssertionError): + mm0.map_range(vaddr=exteranl_va, size=0x1000, paddrs=[(va, sz)]) + + with self.assertRaises(AssertionError): + mm0.map_range(vaddr=exteranl_va, size=0x100000, paddrs=[(va, sz)]) + + with self.assertRaises(AssertionError): + mm0.map_range(vaddr=exteranl_va + 0x1000, size=0x1000, paddrs=[(va, sz)]) + + with self.assertRaises(AssertionError): + mm0.map_range(vaddr=exteranl_va + 0x2000, size=0x100000, paddrs=[(va, sz)]) + + mm0.unmap_range(vaddr=exteranl_va, size=sz) + + # Finally can map and check paddrs + mm0.map_range(vaddr=exteranl_va + 0x2000, size=0x100000, paddrs=[(0xdead0000, 0x1000), (0xdead1000, 0xff000)]) + + ctx = AMPageTableTraverseContext(self.d[0], mm0.root_page_table, exteranl_va + 0x2000) + for tup in ctx.next(0x100000): + _offset, _pt, _pte_idx, _n_ptes, _pte_covers = tup + for i in range(_n_ptes): + pte = helper_read_entry_components(_pt.entries[_pte_idx + i]) + assert pte['paddr'] == 0xdead0000 + _offset + i * _pte_covers, f"paddr {pte['paddr']:#x} not {0xdead0000 + _offset + i * _pte_covers:#x}" + assert pte['valid'] == 1 + + mm0.unmap_range(vaddr=exteranl_va + 0x2000, size=0x100000) + + def test_try_bad_unmap(self): + mm0 = self.d[0].mm + + with self.assertRaises(AssertionError): + mm0.unmap_range(0x10000, 0x3000) + + mm0.map_range(0x10000, 0x3000, paddrs=[(0x10000, 0x3000)]) + mm0.unmap_range(0x10000, 0x3000) + + with self.assertRaises(AssertionError): + mm0.unmap_range(0x10000, 0x3000) + + mm0.map_range(0x10000, 0x3000, paddrs=[(0x10000, 0x3000)]) + mm0.unmap_range(0x10000, 0x3000) + + with self.assertRaises(AssertionError): + mm0.unmap_range(0x10000, 0x3000) + + def test_free_pt(self): + mm0 = self.d[0].mm + + # offset from start + for off in [0, 0x3000, 0x10000]: + mm0.map_range(0x1000000 + off, (2 << 20) - off, paddrs=[(0x10000, 0x1000)] * (512 - off // 0x1000)) + mm0.unmap_range(0x1000000 + off, (2 << 20) - off) + mm0.map_range(0x1000000, 2 << 20, paddrs=[(0x10000, 2 << 20)]) + mm0.unmap_range(0x1000000, 2 << 20) + + # offset from end + for off in [0x1000, 0x20000]: + mm0.map_range(0x1000000, (2 << 20) - off, paddrs=[(0x10000, 0x1000)] * (512 - off // 0x1000)) + mm0.unmap_range(0x1000000, (2 << 20) - off) + mm0.map_range(0x1000000, 2 << 20, paddrs=[(0x10000, 2 << 20)]) + mm0.unmap_range(0x1000000, 2 << 20) + + def test_frag_size(self): + mm0 = self.d[0].mm + + def must_cover_checker(va, sz): + ans = (1 << (mm0._frag_size(va=va, sz=sz, must_cover=True) + 12)) + assert va % ans == 0 and sz % ans == 0 and (va % (2 * ans) != 0 or sz % (2 * ans) != 0), f"va {va:#x} sz {sz:#x} ans {ans:#x}" + + def not_cover_checker(va, sz): + ans = (1 << (mm0._frag_size(va=va, sz=sz, must_cover=False) + 12)) + assert va % ans == 0 and ans <= sz and (va % (2 * ans) != 0 or (2 * ans) > sz), f"va {va:#x} sz {sz:#x} ans {ans:#x}" + + for va, sz in [(0x0, 0x1000), (0x1000, 0x2000), (0x1000, 0x3000), (0x2000, 0x2000), (0x4000, 0x8000), (0x8000, 0x4000), (0x10000, 0x4000), + (0x0, 0x4000), (0x10000, 0x4000), (0x10000, 0x40000), (0x10001000, 0x40000), (0x100001000, 0x3000)]: + must_cover_checker(va, sz) + not_cover_checker(va, sz) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/external/external_test_datasets.py b/tinygrad_repo/test/external/external_test_datasets.py index 005336b68c..8fd3c77623 100644 --- a/tinygrad_repo/test/external/external_test_datasets.py +++ b/tinygrad_repo/test/external/external_test_datasets.py @@ -1,21 +1,31 @@ from extra.datasets.kits19 import iterate, preprocess -from examples.mlperf.dataloader import batch_load_unet3d +from examples.mlperf.dataloader import batch_load_unet3d, batch_load_retinanet +from test.external.mlperf_retinanet.coco_utils import get_openimages +from test.external.mlperf_retinanet.openimages import postprocess_targets +from test.external.mlperf_retinanet.presets import DetectionPresetTrain, DetectionPresetEval +from test.external.mlperf_retinanet.model.transform import GeneralizedRCNNTransform from test.external.mlperf_unet3d.kits19 import PytTrain, PytVal from tinygrad.helpers import temp from pathlib import Path +from pycocotools.coco import COCO +import json import nibabel as nib import numpy as np import os +import PIL import random import tempfile +import torch import unittest class ExternalTestDatasets(unittest.TestCase): def _set_seed(self): np.random.seed(42) random.seed(42) + torch.manual_seed(42) +class TestKiTS19Dataset(ExternalTestDatasets): def _create_samples(self, val, num_samples=2): self._set_seed() @@ -38,7 +48,7 @@ class ExternalTestDatasets(unittest.TestCase): return preproc_pth, list(preproc_pth.glob("*_x.npy")), list(preproc_pth.glob("*_y.npy")) - def _create_kits19_ref_dataloader(self, preproc_img_pths, preproc_lbl_pths, val): + def _create_ref_dataloader(self, preproc_img_pths, preproc_lbl_pths, val): if val: dataset = PytVal(preproc_img_pths, preproc_lbl_pths) else: @@ -46,18 +56,18 @@ class ExternalTestDatasets(unittest.TestCase): return iter(dataset) - def _create_kits19_tinygrad_dataloader(self, preproc_pth, val, batch_size=1, shuffle=False, seed=42, use_old_dataloader=False): + def _create_tinygrad_dataloader(self, preproc_pth, val, batch_size=1, shuffle=False, seed=42, use_old_dataloader=False): if use_old_dataloader: dataset = iterate(list(Path(tempfile.gettempdir()).glob("case_*")), preprocessed_dir=preproc_pth, val=val, shuffle=shuffle, bs=batch_size) else: - dataset = iter(batch_load_unet3d(preproc_pth, batch_size=batch_size, val=val, shuffle=shuffle, seed=seed)) + dataset = batch_load_unet3d(preproc_pth, batch_size=batch_size, val=val, shuffle=shuffle, seed=seed) return iter(dataset) - def test_kits19_training_set(self): + def test_training_set(self): preproc_pth, preproc_img_pths, preproc_lbl_pths = self._create_samples(False) - ref_dataset = self._create_kits19_ref_dataloader(preproc_img_pths, preproc_lbl_pths, False) - tinygrad_dataset = self._create_kits19_tinygrad_dataloader(preproc_pth, False) + ref_dataset = self._create_ref_dataloader(preproc_img_pths, preproc_lbl_pths, False) + tinygrad_dataset = self._create_tinygrad_dataloader(preproc_pth, False) for ref_sample, tinygrad_sample in zip(ref_dataset, tinygrad_dataset): self._set_seed() @@ -65,14 +75,97 @@ class ExternalTestDatasets(unittest.TestCase): np.testing.assert_equal(tinygrad_sample[0][:, 0].numpy(), ref_sample[0]) np.testing.assert_equal(tinygrad_sample[1][:, 0].numpy(), ref_sample[1]) - def test_kits19_validation_set(self): + def test_validation_set(self): preproc_pth, preproc_img_pths, preproc_lbl_pths = self._create_samples(True) - ref_dataset = self._create_kits19_ref_dataloader(preproc_img_pths, preproc_lbl_pths, True) - tinygrad_dataset = self._create_kits19_tinygrad_dataloader(preproc_pth, True, use_old_dataloader=True) + ref_dataset = self._create_ref_dataloader(preproc_img_pths, preproc_lbl_pths, True) + tinygrad_dataset = self._create_tinygrad_dataloader(preproc_pth, True, use_old_dataloader=True) for ref_sample, tinygrad_sample in zip(ref_dataset, tinygrad_dataset): np.testing.assert_equal(tinygrad_sample[0][:, 0], ref_sample[0]) np.testing.assert_equal(tinygrad_sample[1], ref_sample[1]) +class TestOpenImagesDataset(ExternalTestDatasets): + @classmethod + def setUpClass(cls): + cls.img_mean = [0.485, 0.456, 0.406] + cls.img_std = [0.229, 0.224, 0.225] + cls.img_size = (800, 800) + + def _create_samples(self, subset): + os.makedirs((base_dir := Path(tempfile.gettempdir() + "/openimages")) / f"{subset}/data", exist_ok=True) + os.makedirs(base_dir / Path(f"{subset}/labels"), exist_ok=True) + + lbls, img_size = ["cls_1", "cls_2"], (447, 1024) + cats = [{"id": i, "name": c, "supercategory": None} for i, c in enumerate(lbls)] + imgs = [ + { + "id": i, "file_name": f"img_{i}.jpg", + "height": img_size[0], "width": img_size[1], + "subset": subset, "license": None, "coco_url": None + } + for i in range(len(lbls)) + ] + annots = [ + { + "id": i, "image_id": i, + "category_id": 0, "bbox": [23.217183744, 31.75409775, 964.1241282560001, 326.09017434000003], + "area": 314391.4050683996, "IsOccluded": 0, + "IsInside": 0, "IsDepiction": 0, + "IsTruncated": 0, "IsGroupOf": 0, + "iscrowd": 0 + } + for i in range(len(lbls)) + ] + info = {"dataset": "openimages_mlperf", "version": "v6"} + coco_annotations = {"info": info, "licenses": [], "categories": cats, "images": imgs, "annotations": annots} + + with open(ann_file:=base_dir / Path(f"{subset}/labels/openimages-mlperf.json"), "w") as fp: + json.dump(coco_annotations, fp) + + for i in range(len(lbls)): + img = PIL.Image.new("RGB", img_size[::-1]) + img.save(base_dir / Path(f"{subset}/data/img_{i}.jpg")) + + return base_dir, ann_file + + def _create_ref_dataloader(self, base_dir, ann_file, subset): + self._set_seed() + transforms = DetectionPresetTrain("hflip") if subset == "train" else DetectionPresetEval() + return iter(get_openimages(ann_file.stem, base_dir, subset, transforms)) + + def _create_tinygrad_dataloader(self, base_dir, ann_file, subset, batch_size=1, seed=42): + return iter(batch_load_retinanet(COCO(ann_file), subset == "validation", base_dir, batch_size=batch_size, shuffle=False, seed=seed)) + + def _normalize_img(self, img): + return ((img / 255.0) - np.array(self.img_mean)) / np.array(self.img_std) + + def test_training_set(self): + base_dir, ann_file = self._create_samples((subset:="train")) + transform = GeneralizedRCNNTransform(self.img_size, self.img_mean, self.img_std) + anchors = torch.ones((120087, 4)) + + tinygrad_dataloader = self._create_tinygrad_dataloader(base_dir, ann_file, subset) + ref_dataloader = self._create_ref_dataloader(base_dir, ann_file, subset) + + for ((tinygrad_img, tinygrad_boxes, tinygrad_labels, _, _, _), (ref_img, ref_tgt)) in zip(tinygrad_dataloader, ref_dataloader): + ref_img, ref_tgt = transform(ref_img.unsqueeze(0), [ref_tgt]) + ref_tgt = postprocess_targets(ref_tgt, anchors.unsqueeze(0)) + ref_boxes, ref_labels = ref_tgt[0]["boxes"], ref_tgt[0]["labels"] + + np.testing.assert_allclose(self._normalize_img(tinygrad_img.numpy()), ref_img.tensors.transpose(1, 3).numpy()) + np.testing.assert_equal(tinygrad_boxes[0].numpy(), ref_boxes.numpy()) + np.testing.assert_equal(tinygrad_labels[0].numpy(), ref_labels.numpy()) + + def test_validation_set(self): + base_dir, ann_file = self._create_samples((subset:="validation")) + transform = GeneralizedRCNNTransform(self.img_size, self.img_mean, self.img_std) + + tinygrad_dataloader = self._create_tinygrad_dataloader(base_dir, ann_file, subset) + ref_dataloader = self._create_ref_dataloader(base_dir, ann_file, "val") + + for ((tinygrad_img, _, _, _), (ref_img, _)) in zip(tinygrad_dataloader, ref_dataloader): + ref_img, _ = transform(ref_img.unsqueeze(0)) + np.testing.assert_allclose(self._normalize_img(tinygrad_img.numpy()), ref_img.tensors.transpose(1, 3).numpy()) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/external/external_test_example.py b/tinygrad_repo/test/external/external_test_example.py index 5830d7716f..86c3958c80 100644 --- a/tinygrad_repo/test/external/external_test_example.py +++ b/tinygrad_repo/test/external/external_test_example.py @@ -7,7 +7,7 @@ def multidevice_test(fxn): exclude_devices = getenv("EXCLUDE_DEVICES", "").split(",") def ret(self): for device in Device._devices: - if device in ["DISK", "NPY", "FAKE"]: continue + if device in ["REMOTE", "DISK", "NPY", "FAKE", "DSP", "NULL"]: continue if not CI: print(device) if device in exclude_devices: if not CI: print(f"WARNING: {device} test is excluded") @@ -23,10 +23,10 @@ def multidevice_test(fxn): class TestExample(unittest.TestCase): @multidevice_test - def test_convert_to_clang(self, device): + def test_convert_to_cpu(self, device): a = Tensor([[1,2],[3,4]], device=device) assert a.numpy().shape == (2,2) - b = a.to("CLANG") + b = a.to("CPU") assert b.numpy().shape == (2,2) @multidevice_test diff --git a/tinygrad_repo/test/external/external_test_hcq.py b/tinygrad_repo/test/external/external_test_hcq.py index 74dec06e6b..0303948bd1 100644 --- a/tinygrad_repo/test/external/external_test_hcq.py +++ b/tinygrad_repo/test/external/external_test_hcq.py @@ -2,7 +2,6 @@ import unittest, ctypes, struct, time, array from tinygrad import Device, Tensor, dtypes from tinygrad.helpers import to_mv, CI from tinygrad.device import Buffer, BufferSpec -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import get_runner def _time_queue(q, d): @@ -21,7 +20,7 @@ class TestHCQ(unittest.TestCase): #TestHCQ.d1: AMDDevice = Device["AMD:1"] TestHCQ.a = Tensor([0.,1.], device=Device.DEFAULT).realize() TestHCQ.b = self.a + 1 - si = create_schedule([self.b.lazydata])[-1] + si = self.b.schedule()[-1] TestHCQ.runner = get_runner(TestHCQ.d0.device, si.ast) TestHCQ.b.lazydata.buffer.allocate() # wow that's a lot of abstraction layers diff --git a/tinygrad_repo/test/external/external_test_hcq_fuzz_failures.py b/tinygrad_repo/test/external/external_test_hcq_fuzz_failures.py index 9370b7661d..09b3633d56 100644 --- a/tinygrad_repo/test/external/external_test_hcq_fuzz_failures.py +++ b/tinygrad_repo/test/external/external_test_hcq_fuzz_failures.py @@ -6,7 +6,7 @@ import unittest, random import numpy as np from tinygrad.codegen.kernel import Kernel, KernelOptError from tinygrad.device import is_dtype_supported -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.engine.search import Opt, OptOps from tinygrad import Device, dtypes, Tensor from test.external.fuzz_linearizer import compare_linearizer, compare_states, get_fuzz_rawbuf_like @@ -18,13 +18,12 @@ def helper_test_lin(lin: Kernel, opts, failed_platforms, validate_device, rtol=1 if any(b.dtype.base == dtypes.half for b in lin.membufs) and not is_dtype_supported(dtypes.half): return if any(b.dtype.base == dtypes.bfloat16 for b in lin.membufs) and not is_dtype_supported(dtypes.bfloat16): return - for opt in opts: - try: - lin.apply_opt(opt) - except KernelOptError: - # it's considered fixed if we invalidated the opts - assert Device.DEFAULT not in failed_platforms, f"unexpected success on {Device.DEFAULT}" - return + try: + lin.apply_opts(opts) + except KernelOptError: + # it's considered fixed if we invalidated the opts + assert Device.DEFAULT not in failed_platforms, f"unexpected success on {Device.DEFAULT}" + return (msg, rawbufs, var_vals, ground_truth, state1) = compare_linearizer(lin, rtol=rtol, atol=atol) if msg in ["PASS", "KernelOptError"]: @@ -55,7 +54,7 @@ class TestHCQFuzzFailures(unittest.TestCase): def test_failure_1(self): ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( UOp(Ops.STORE, dtypes.void, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=0, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=0, mask=None, contiguous=True),)), src=()), UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 2, 4)), arg=1, src=()), x39:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=0, mask=((0, 1), (0, 6)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), x39,)),)),)), UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 2, 4)), arg=3, src=()), x46:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-6, mask=((0, 1), (6, 12)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=4, src=()), x46,)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=5, src=()), x54:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (12, 13)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=6, src=()), x54,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=7, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-13, mask=((0, 1), (13, 17)), contiguous=False),)), src=()),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=8, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-17, mask=((0, 1), (17, 21)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=9, src=()), x68:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (21, 22)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=10, src=()), x68,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=11, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-22, mask=((0, 1), (22, 26)), contiguous=False),)), src=()),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=12, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-26, mask=((0, 1), (26, 30)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=13, src=()), x82:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (30, 31)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=14, src=()), x82,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=15, src=()), x90:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (31, 32)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=16, src=()), x90,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=17, src=()), x98:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (32, 33)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=18, src=()), x98,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=19, src=()), x106:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (33, 34)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=20, src=()), x106,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=21, src=()), x114:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (34, 35)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=22, src=()), x114,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=23, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-35, mask=((0, 1), (35, 39)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=24, src=()), x125:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (39, 40)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=25, src=()), x125,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=26, src=()), x133:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (40, 41)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=27, src=()), x133,)),)),)),)),)), UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 2, 4)), arg=28, src=()), x140:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-41, mask=((0, 1), (41, 47)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=29, src=()), x140,)),)),)),)), UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 2, 4)), arg=30, src=()), x147:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-47, mask=((0, 1), (47, 53)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=31, src=()), x147,)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=32, src=()), x155:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (53, 54)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=33, src=()), x155,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=34, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-54, mask=((0, 1), (54, 58)), contiguous=False),)), src=()),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=35, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-58, mask=((0, 1), (58, 62)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=36, src=()), x169:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (62, 63)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=37, src=()), x169,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=38, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-63, mask=((0, 1), (63, 67)), contiguous=False),)), src=()),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=39, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-67, mask=((0, 1), (67, 71)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=40, src=()), x183:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (71, 72)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=41, src=()), x183,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=42, src=()), x191:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (72, 73)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=43, src=()), x191,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=44, src=()), x199:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (73, 74)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=45, src=()), x199,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=46, src=()), x207:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (74, 75)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=47, src=()), x207,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=48, src=()), x215:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (75, 76)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=49, src=()), x215,)),)),)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=50, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-76, mask=((0, 1), (76, 80)), contiguous=False),)), src=()),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=51, src=()), x226:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (80, 81)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=52, src=()), x226,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=53, src=()), x234:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (81, 82)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=54, src=()), x234,)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=55, src=()), x243:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (82, 83)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=56, src=()), x243,)),)),)), UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 1, 4)), arg=57, src=()), x250:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 0), offset=0, mask=((0, 1), (83, 84)), contiguous=False),)), src=()),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=58, src=()), x250,)),)),)),)),)),)), UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.imageh((1, 128, 4)), arg=59, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 596), strides=(0, 1), offset=-84, mask=((0, 1), (84, 596)), contiguous=False),)), src=()),)),)),)),)),)) # noqa: E501 - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=4)] + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=4)] helper_test_lin(Kernel(ast), opts, failed_platforms=[], validate_device=Device["GPU"]) if __name__ == '__main__': diff --git a/tinygrad_repo/test/external/external_test_losses.py b/tinygrad_repo/test/external/external_test_losses.py index 6775f595fd..cd8efde21c 100644 --- a/tinygrad_repo/test/external/external_test_losses.py +++ b/tinygrad_repo/test/external/external_test_losses.py @@ -1,20 +1,40 @@ from tinygrad import Tensor +from test.external.mlperf_retinanet.focal_loss import sigmoid_focal_loss as ref_sigmoid_focal_loss from test.external.mlperf_unet3d.dice import DiceCELoss -from examples.mlperf.losses import dice_ce_loss +from examples.mlperf.losses import dice_ce_loss, sigmoid_focal_loss, l1_loss import numpy as np import torch import unittest class ExternalTestLosses(unittest.TestCase): - def _test_losses(self, tinygrad_metrics, orig_metrics, pred, label): - tinygrad_metrics_res = tinygrad_metrics(Tensor(pred), Tensor(label)).numpy() - orig_metrics_res = orig_metrics(torch.from_numpy(pred), torch.from_numpy(label)).numpy() - np.testing.assert_allclose(tinygrad_metrics_res, orig_metrics_res, atol=1e-4) + def setUp(self): + np.random.seed(42) - def test_dice_ce(self): + def _assert_loss(self, pred, tgt, tinygrad_metrics, ref_metrics, rtol=1e-07, atol=0, **kwargs): + tinygrad_metrics_res = tinygrad_metrics(Tensor(pred), Tensor(tgt), **kwargs) + ref_metrics_res = ref_metrics(torch.from_numpy(pred), torch.from_numpy(tgt), **kwargs) + np.testing.assert_allclose(tinygrad_metrics_res.numpy(), ref_metrics_res.numpy(), rtol=rtol, atol=atol) + + def test_dice_ce_loss(self): pred, label = np.random.rand(1, 3, 128, 128, 128).astype(np.float32), np.ones((1, 1, 128, 128, 128)).astype(np.uint8) - self._test_losses(dice_ce_loss, DiceCELoss(True, True, "NCDHW", False), pred, label) + tinygrad_metrics_res, ref_metrics_res = dice_ce_loss, DiceCELoss(True, True, "NCDHW", False) + self._assert_loss(pred, label, tinygrad_metrics_res, ref_metrics_res, atol=1e-4) + + def test_sigmoid_focal_loss(self): + def _apply_logit(p): return np.log(p / (1 - p)) + pred, tgt = _apply_logit(np.random.rand(5,2).astype(np.float32)), np.random.randint(0, 2, (5, 2)).astype(np.float32) + for reduction in ["mean", "sum", "none"]: + for alpha, gamma in zip([-1, 0.58], [0, 2]): + self._assert_loss(pred, tgt, sigmoid_focal_loss, ref_sigmoid_focal_loss, rtol=1e-4, alpha=alpha, gamma=gamma, reduction=reduction) + + def test_l1_loss(self): + N, C, H, W = 3, 4, 5, 6 + shapes = ((N, C), (N, C, H), (N, C, H, W)) + for reduction in ["mean", "sum", "none"]: + for shape in shapes: + pred, tgt = np.random.randint(shape).astype(np.float32), np.random.randint(shape) + self._assert_loss(pred, tgt, l1_loss, torch.nn.functional.l1_loss, reduction=reduction) if __name__ == '__main__': unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_test_nv.py b/tinygrad_repo/test/external/external_test_nv.py index a9b9f3f2db..b488e86725 100644 --- a/tinygrad_repo/test/external/external_test_nv.py +++ b/tinygrad_repo/test/external/external_test_nv.py @@ -1,7 +1,6 @@ import unittest, struct, array, ctypes from tinygrad import Device, dtypes, Tensor from tinygrad.helpers import to_mv -from tinygrad.engine.schedule import create_schedule from tinygrad.runtime.ops_nv import NVDevice, HWQueue from tinygrad.engine.search import Opt, OptOps from test.test_linearizer_failures import helper_test_lin @@ -9,7 +8,7 @@ from tinygrad.engine.realize import get_runner, CompiledRunner from test.external.fuzz_linearizer import get_fuzz_rawbufs from tinygrad.codegen.kernel import Kernel -from tinygrad.ops import LazyOp, Ops, ReduceOps, BufferOps, MemBuffer +from tinygrad.uop.ops import LazyOp, Ops, ReduceOps, BufferOps, MemBuffer from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import View @@ -20,22 +19,22 @@ class TestNV(unittest.TestCase): TestNV.d0: NVDevice = Device["NV"] TestNV.a = Tensor([0.,1.], device="NV").realize() TestNV.b = self.a + 1 - si = create_schedule([self.b.lazydata])[-1] + si = self.b.schedule()[-1] TestNV.d0_runner = get_runner(TestNV.d0.device, si.ast) TestNV.b.lazydata.buffer.allocate() TestNV.addr = struct.pack("QQ", TestNV.b.lazydata.buffer._buf.va_addr, TestNV.a.lazydata.buffer._buf.va_addr) def test_oor_kernels(self): ast = LazyOp(op=BufferOps.STORE, src=(LazyOp(op=Ops.CAST, src=(LazyOp(op=ReduceOps.SUM, src=(LazyOp(op=Ops.CAST, src=(LazyOp(op=Ops.MUL, src=(LazyOp(op=BufferOps.LOAD, src=(), arg=MemBuffer(idx=1, dtype=dtypes.half, st=ShapeTracker(views=(View(shape=(1, 256, 1, 512, 4, 16, 4, 16), strides=(0, 100352, 0, 196, 0, 14, 0, 1), offset=-15, mask=((0, 1), (0, 256), (0, 1), (0, 512), (0, 4), (1, 15), (0, 4), (1, 15)), contiguous=False), View(shape=(256, 1, 512, 7, 7, 512, 3, 3), strides=(2097152, 0, 0, 128, 2, 4096, 1088, 17), offset=0, mask=None, contiguous=False))))), LazyOp(op=BufferOps.LOAD, src=(), arg=MemBuffer(idx=2, dtype=dtypes.half, st=ShapeTracker(views=(View(shape=(256, 1, 512, 7, 7, 512, 3, 3), strides=(25088, 0, 49, 7, 1, 0, 0, 0), offset=0, mask=None, contiguous=False),))))), arg=None),), arg=(dtypes.float, False)),), arg=((0, 3, 4), dtypes.float)),), arg=(dtypes.half, False)),), arg=MemBuffer(idx=0, dtype=dtypes.half, st=ShapeTracker(views=(View(shape=(1, 1, 512, 1, 1, 512, 3, 3), strides=(0, 0, 4608, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=True),)))) # noqa: E501 - opts = [Opt(op=OptOps.TC, axis=6, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.LOCAL, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=2, amt=3), Opt(op=OptOps.UPCAST, axis=1, amt=2)] # noqa: E501 + opts = [Opt(op=OptOps.TC, axis=6, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.LOCAL, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=2, arg=3), Opt(op=OptOps.UPCAST, axis=1, arg=2)] # noqa: E501 helper_test_lin(Kernel(ast), opts=opts, failed_platforms=["NV"]) def test_error_on_huge_dims(self): ast = LazyOp(op=BufferOps.STORE, src=(LazyOp(op=ReduceOps.SUM, src=(LazyOp(op=Ops.CAST, src=(LazyOp(op=Ops.MUL, src=(LazyOp(op=BufferOps.LOAD, src=(), arg=MemBuffer(idx=1, dtype=dtypes.half, st=ShapeTracker(views=(View(shape=(1, 1, 1024, 683), strides=(0, 0, 0, 1), offset=0, mask=None, contiguous=False),)))), LazyOp(op=BufferOps.LOAD, src=(), arg=MemBuffer(idx=2, dtype=dtypes.half, st=ShapeTracker(views=(View(shape=(1, 1, 1024, 683), strides=(0, 0, 683, 1), offset=0, mask=None, contiguous=True),))))), arg=None),), arg=dtypes.float),), arg=(3,)),), arg=MemBuffer(idx=0, dtype=dtypes.float, st=ShapeTracker(views=(View(shape=(1, 1, 1024, 1), strides=(0, 0, 1, 0), offset=0, mask=None, contiguous=True),)))) # noqa: E501 - opts = [Opt(op=OptOps.GROUP, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=1, amt=32), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.LOCAL, axis=0, amt=2)] # noqa: E501 + opts = [Opt(op=OptOps.GROUP, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=1, arg=32), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.LOCAL, axis=0, arg=2)] # noqa: E501 with self.assertRaises(RuntimeError) as cm: lin = Kernel(ast) - for opt in opts: lin.apply_opt(opt) + lin.apply_opts(opts) rawbufs = get_fuzz_rawbufs(lin) prg = CompiledRunner(lin.to_program()) prg(rawbufs, {}, wait=True) @@ -65,4 +64,3 @@ class TestNV(unittest.TestCase): 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 index 13a07b8853..b6ccd009d3 100644 --- a/tinygrad_repo/test/external/external_test_onnx_backend.py +++ b/tinygrad_repo/test/external/external_test_onnx_backend.py @@ -10,7 +10,7 @@ from tinygrad.device import is_dtype_supported # pip3 install tabulate pytest_plugins = 'onnx.backend.test.report', -from extra.onnx import get_run_onnx +from tinygrad.frontend.onnx import OnnxRunner class TinygradModel(BackendRep): def __init__(self, run_onnx, input_names): @@ -20,7 +20,7 @@ class TinygradModel(BackendRep): def run(self, inputs: Any, **kwargs: Any) -> Tuple[Any, ...]: real_inputs = dict(zip(self.input_names, inputs)) - ret = self.fxn(real_inputs, debug=True) + ret = self.fxn(real_inputs, debug=2) 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): @@ -30,7 +30,7 @@ class TinygradBackend(Backend): 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) + run_onnx = OnnxRunner(model) return TinygradModel(run_onnx, net_feed_input) @classmethod @@ -40,12 +40,32 @@ class TinygradBackend(Backend): backend_test = onnx.backend.test.BackendTest(TinygradBackend, __name__) -# TODO: there isn't an AttributeProto for `epsilon` in the NodeProto for 'test_adam_multiple_cpu' -# [x.name for x in n.attribute] -> ['alpha', 'beta', 'norm_coefficient'] -# but in their documentation https://github.com/onnx/onnx/blob/main/docs/Operators.md#examples-176, it states there being an epsilon of 1e-2 -# test passes with epsilon = 1e-2 +# BUG: buggy onnx tests backend_test.exclude('test_adam_multiple_cpu') +# BUG: ORT fails these with runtime error +backend_test.exclude('test_PReLU_1d_multiparam_cpu') +backend_test.exclude('test_PReLU_2d_multiparam_cpu') +backend_test.exclude('test_PReLU_3d_multiparam_cpu') + +# BUG: we don't match ORT here due to some div inaccuracy with floats +backend_test.exclude('test_dynamicquantizelinear_cpu') +backend_test.exclude('test_dynamicquantizelinear_expanded_cpu') + +# BUG: ORT fails these with numerical error but we match ORT numerically +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_qlinearmatmul_2D_int8_float16 +backend_test.exclude('test_qlinearmatmul_2D_int8_float16_cpu') +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_qlinearmatmul_3D_int8_float16 +backend_test.exclude('test_qlinearmatmul_3D_int8_float16_cpu') +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_qlinearmatmul_2D_int8_float32 +backend_test.exclude('test_qlinearmatmul_2D_int8_float32_cpu') +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_qlinearmatmul_3D_int8_float32 +backend_test.exclude('test_qlinearmatmul_3D_int8_float32_cpu') +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_maxunpool_export_with_output_shape +backend_test.exclude('test_maxunpool_export_with_output_shape_cpu') +# tested in external_test_onnx_ops.py::TestMainOnnxOps.test_averagepool_3d_dilations_large_count_include_pad_is_1_ceil_mode_is_True +backend_test.exclude('test_averagepool_3d_dilations_large_count_include_pad_is_1_ceil_mode_is_True_cpu') + # about different dtypes if not is_dtype_supported(dtypes.float64): backend_test.exclude('float64') @@ -73,18 +93,28 @@ backend_test.exclude('cast_no_saturate') backend_test.exclude('test_dequantizelinear_e4m3fn_float16_cpu') backend_test.exclude('test_max_float16_cpu') backend_test.exclude('test_min_float16_cpu') - -backend_test.exclude('test_convinteger_*') -backend_test.exclude('test_matmulinteger_*') +backend_test.exclude('test_mod_mixed_sign_float16_cpu') backend_test.exclude('test_dequantizelinear_int4_cpu') backend_test.exclude('test_dequantizelinear_uint4_cpu') +backend_test.exclude('test_quantizelinear_int4_cpu') +backend_test.exclude('test_quantizelinear_uint4_cpu') + +# no support for FLOAT8 +backend_test.exclude('test_quantizelinear_e4m3fn_cpu') +backend_test.exclude('test_quantizelinear_e5m2_cpu') +backend_test.exclude('test_quantizelinear_e4m3fn_cpu') +backend_test.exclude('test_quantizelinear_e5m2_cpu') +backend_test.exclude('test_dequantizelinear_e4m3fn_cpu') +backend_test.exclude('test_dequantizelinear_e4m3fn_zero_point_cpu') +backend_test.exclude('test_dequantizelinear_e5m2_cpu') # we don't support indexes backend_test.exclude('test_nonzero_*') -# no support for mod -backend_test.exclude('test_mod_*') +# no support for int pow +backend_test.exclude('test_pow_types_int32_int32_cpu') +backend_test.exclude('test_pow_types_int64_int64_cpu') # no boolean ops (2d, 3d, 4d) backend_test.exclude('test_bitshift_*') @@ -94,12 +124,6 @@ backend_test.exclude('string') backend_test.exclude('test_strnorm_*') backend_test.exclude('test_regex_*') -# 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_*') @@ -134,7 +158,6 @@ 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_*') @@ -152,16 +175,16 @@ backend_test.exclude('test_resize_upsample_sizes_cubic_*') # unsure how to imple backend_test.exclude('test_ai_onnx_ml_tree_ensemble_*') # https://github.com/onnx/onnx/blob/main/onnx/reference/ops/aionnxml/op_tree_ensemble.py#L121 # rest of the failing tests +backend_test.exclude('test_resize_tf_crop_and_resize_cpu') # tf_crop_and_resize not implemented +backend_test.exclude('test_resize_tf_crop_and_resize_axes_2_3_cpu') # tf_crop_and_resize not implemented +backend_test.exclude('test_resize_tf_crop_and_resize_axes_3_2_cpu') # tf_crop_and_resize not implemented +backend_test.exclude('test_resize_tf_crop_and_resize_extrapolation_value_cpu') # tf_crop_and_resize value not implemented 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_ai_onnx_ml_label_encoder_tensor_value_only_mapping_cpu') # bad data type string backend_test.exclude('test_ai_onnx_ml_label_encoder_tensor_mapping_cpu') # bad data type string -backend_test.exclude('test_group_normalization_*') # numerical inaccuracy problem. Current Group Normalization OP fails test -backend_test.exclude('test_scatter_elements_with_reduction_min_cpu') # min not yet supported backend_test.exclude('test_scatternd_min_cpu') # min not yet supported -backend_test.exclude('test_scatter_elements_with_reduction_max_cpu') # max not yet supported backend_test.exclude('test_scatternd_max_cpu') # max not yet supported if Device.DEFAULT in ['GPU', 'METAL']: diff --git a/tinygrad_repo/test/external/external_test_onnx_ops.py b/tinygrad_repo/test/external/external_test_onnx_ops.py new file mode 100644 index 0000000000..adc63edda0 --- /dev/null +++ b/tinygrad_repo/test/external/external_test_onnx_ops.py @@ -0,0 +1,356 @@ +# inputs, attributes, and outputs for tests are found here: +# https://github.com/onnx/onnx/blob/main/docs/Operators.md +# https://github.com/microsoft/onnxruntime/blob/main/docs/ContribOperators.md + +from typing import Any +import unittest, onnx, tempfile +from tinygrad import dtypes +from tinygrad.frontend.onnx import OnnxRunner +import numpy as np +from extra.onnx_helpers import validate + +class TestOnnxOps(unittest.TestCase): + DOMAIN = None + def helper_build_model(self, op:str, inps:dict[str, np.ndarray], opts:dict[str, Any], outs:list[str]): + onnx_inputs = [onnx.helper.make_tensor_value_info(name, onnx.helper.np_dtype_to_tensor_dtype(arr.dtype), arr.shape) for name, arr in inps.items()] + onnx_outputs = [onnx.helper.make_empty_tensor_value_info(name) for name in outs] + nodes = [onnx.helper.make_node(op, list(inps), list(outs), domain=self.DOMAIN, **opts)] + graph = onnx.helper.make_graph(nodes, f"test_{op.lower()}", onnx_inputs, onnx_outputs) + model = onnx.helper.make_model(graph, producer_name=f"test_{op.lower()}") + return model + + def helper_test_single_op(self, op:str, inps:dict[str, np.ndarray], opts:dict[str, Any], outs:list[str], rtol=1e-3, atol=1e-6): + model = self.helper_build_model(op, inps, opts, outs) + with tempfile.NamedTemporaryFile() as tmp: + onnx.save(model, tmp.name) + validate(tmp.name, inps, rtol, atol) + +class TestMainOnnxOps(TestOnnxOps): + DOMAIN = "" + def test_reshape(self): + inputs = {"in": np.arange(6, dtype=np.float32), "shape": np.array([2,3], dtype=np.int64)} + attributes = {} + outputs = ["out"] + self.helper_test_single_op("Reshape", inputs, attributes, outputs) + + def test_squeeze(self): + # axes is None + inputs = {"data": np.random.randn(1, 3, 1, 1).astype(np.float32)} + attributes = {} + outputs = ["squeezed"] + self.helper_test_single_op("Squeeze", inputs, attributes, outputs) + + def test_conv(self): + # test VALID auto_pad + inputs = { + "x": np.random.randn(1, 3, 384, 384).astype(np.float32), + "w": np.random.randn(1152, 3, 14, 14).astype(np.float32), + "b": np.random.randn(1152).astype(np.float32) + } + attributes = {'auto_pad': 'VALID', 'dilations': (1, 1), 'group': 1, 'kernel_shape': (14, 14), 'strides': (14, 14)} + outputs = ["y"] + self.helper_test_single_op("Conv", inputs, attributes, outputs, atol=1e-4) + + def test_gather(self): + # test const negative indices + inputs = { + "input": np.random.randn(1, 3, 3).astype(np.float32), + "indices": np.array(-2, dtype=np.int64), + } + attributes = {'axis': 1} + outputs = ["y"] + self.helper_test_single_op("Gather", inputs, attributes, outputs) + + def test_maxunpool_export_with_output_shape(self): + # https://github.com/onnx/onnx/blob/main/docs/Operators.md#examples-91 + xT = np.array([[[[5, 6], [7, 8]]]], dtype=np.float32) + xI = np.array([[[[5, 7], [13, 15]]]], dtype=np.int64) + output_shape = np.array((1, 1, 5, 5), dtype=np.int64) + inputs = {"x": xT, "indices": xI, "output_shape": output_shape} + attributes = {"kernel_shape": [2, 2], "strides": [2, 2]} + outputs = ["y"] + self.helper_test_single_op("MaxUnpool", inputs, attributes, outputs) + + def test_averagepool_3d_dilations_large_count_include_pad_is_1_ceil_mode_is_True(self): + # https://github.com/onnx/onnx/blob/main/docs/Operators.md#examples-13 + inputs = {"x": np.random.randn(1, 1, 32, 32, 32).astype(np.float32)} + attributes = {"kernel_shape": (5, 5, 5), "strides": (3, 3, 3), "dilations": (2, 2, 2), "count_include_pad": 1, "ceil_mode": True} + outputs = ["y"] + self.helper_test_single_op("AveragePool", inputs, attributes, outputs) + + def test_isinf(self): + # https://github.com/onnx/onnx/blob/main/docs/Operators.md#isinf + # attributes are int but output expects bool + x = np.array([-1.2, np.nan, np.inf, 2.8, -np.inf, np.inf], dtype=np.float32) + inputs = {"x": x} + attributes = {"detect_negative":1, "detect_positive":1} + outputs = ["y"] + model = self.helper_build_model("IsInf", inputs, attributes, outputs) + outputs = OnnxRunner(model)(inputs) + assert outputs["y"].dtype is dtypes.bool + + def test_quantize_linear(self): + test_cases = [ + {"test_case": "round_half_to_even", "qdtype": np.int8, "qzero_point": 0, "x": [-1.5, -0.5, 0.5, 1.5], "scale": 1.0}, + {"test_case": "round_to_even_before_add_zero_point", "qdtype": np.uint8, "qzero_point": 1, "x": [0.5, 1.5], "scale": 1.0}, + ] + for case in test_cases: + with self.subTest(test_case=case["test_case"]): + inputs = { + "x": np.array([case["x"]], dtype=np.float32), + "y_scale": np.array(case["scale"], dtype=np.float32), + "y_zero_point": np.array(case["qzero_point"], dtype=case["qdtype"]) + } + self.helper_test_single_op("QuantizeLinear", inputs, {}, ["y"]) + + def test_dynamic_quantize_linear(self): + test_cases = [ + {"name": "round_half_to_even", "x": np.array([0, 0.5, 1.5, 255], dtype=np.float32)}, + {"name": "round_zero_point_half_down_to_even", "x": np.array([-1, 509], dtype=np.float32)}, + {"name": "round_zero_point_half_up_to_even", "x": np.array([-11, 499], dtype=np.float32)}, + # other tests from https://github.com/onnx/onnx/blob/main/docs/Operators.md#examples-45 + {"name": "max_adjusted", "x": np.array([-1.0, -2.1, -1.3, -2.5, -3.34, -4.0], dtype=np.float32)}, + {"name": "min_adjusted", "x": np.array([1, 2.1, 1.3, 2.5, 3.34, 4.0, 1.5, 2.6, 3.9, 4.0, 3.0, 2.345], dtype=np.float32).reshape((3, 4))}, + ] + for case in test_cases: + with self.subTest(test_case=case["name"]): + self.helper_test_single_op("DynamicQuantizeLinear", {"x": case["x"]}, {}, ["y", "y_scale", "y_zero_point"]) + + def test_qlinear_conv(self): + for dtype, zero_point in [(np.uint8, 128), (np.int8, 0)]: + for b in (np.ones([32], dtype=np.int32), np.zeros([32], dtype=np.int32)): + with self.subTest(dtype=dtype, zero_point=zero_point): + dtype_min, dtype_max = np.iinfo(dtype).min, np.iinfo(dtype).max + inputs = { + "x": np.random.randint(dtype_min, dtype_max + 1, [1, 3, 224, 224], dtype=dtype), + "x_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "x_zero_point": np.array(zero_point, dtype=dtype), + "w": np.random.randint(dtype_min, dtype_max + 1, [32, 3, 3, 3], dtype=dtype), + "w_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "w_zero_point": np.array(zero_point, dtype=dtype), + "y_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "y_zero_point": np.array(zero_point, dtype=dtype), + "b": b + } + attributes = {'auto_pad': 'NOTSET', 'dilations': (1, 1), 'group': 1, 'kernel_shape': (3, 3), 'pads': (1, 1, 1, 1), 'strides': (2, 2)} + outputs = ["out"] + self.helper_test_single_op("QLinearConv", inputs, attributes, outputs, atol=1) # occasionally inaccurate + + def test_qlinear_matmul(self): + for dtype, zero_point in [(np.uint8, 128), (np.int8, 0)]: + with self.subTest(dtype=dtype, zero_point=zero_point): + dtype_min, dtype_max = np.iinfo(dtype).min, np.iinfo(dtype).max + inputs = { + "A": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "A_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "A_zero_point": np.array(zero_point, dtype=dtype), + "B": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "B_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "B_zero_point": np.array(zero_point, dtype=dtype), + "Y_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "Y_zero_point": np.array(zero_point, dtype=dtype) + } + attributes = {} + outputs = ["Y"] + self.helper_test_single_op("QLinearMatMul", inputs, attributes, outputs) + + for name,val in (("round_half_down_to_even", 1), ("round_half_up_to_even", 3)): + with self.subTest(test_case=name, val=val): + inputs = { + "A": np.array([val], dtype=np.int8), + "A_scale": np.array(0.5, dtype=np.float32), + "A_zero_point": np.array(0, dtype=np.int8), + "B": np.array([1], dtype=np.int8), + "B_scale": np.array(1, dtype=np.float32), + "B_zero_point": np.array(0, dtype=np.int8), + "Y_scale": np.array(1, dtype=np.float32), + "Y_zero_point": np.array(0, dtype=np.int8) + } + attributes = {} + outputs = ["Y"] + self.helper_test_single_op("QLinearMatMul", inputs, attributes, outputs) + + def _run_qlinearmatmul_test(self, quant_type, dtype, dims): + # https://github.com/onnx/onnx/blob/main/docs/Operators.md#examples-111 + if dims == 2: + a = np.array([[208, 236, 0, 238], [3, 214, 255, 29]]) + b = np.array([[152, 51, 244], [60, 26, 255], [0, 127, 246], [127, 254, 247]]) + else: + a = np.array([[[208, 236, 0, 238], [3, 214, 255, 29]], [[208, 236, 0, 238], [3, 214, 255, 29]]]) + b = np.array([[[152, 51, 244], [60, 26, 255], [0, 127, 246], [127, 254, 247]], [[152, 51, 244], [60, 26, 255], [0, 127, 246], [127, 254, 247]]]) + a_zero_point = np.array([113]) + b_zero_point = np.array([114]) + y_zero_point = np.array([118]) + if quant_type == np.int8: + a, b, a_zero_point, b_zero_point, y_zero_point = (x - 127 for x in (a, b, a_zero_point, b_zero_point, y_zero_point)) + a, b, a_zero_point, b_zero_point, y_zero_point = (x.astype(quant_type) for x in (a, b, a_zero_point, b_zero_point, y_zero_point)) + inputs = { + "a": a, "a_scale": np.array([0.0066], dtype=dtype), "a_zero_point": a_zero_point, + "b": b, "b_scale": np.array([0.00705], dtype=dtype), "b_zero_point": b_zero_point, + "y_scale": np.array([0.0107], dtype=dtype), "y_zero_point": y_zero_point + } + self.helper_test_single_op("QLinearMatMul", inputs, {}, ["y"],) + def test_qlinearmatmul_2D_int8_float16(self): self._run_qlinearmatmul_test(np.int8, np.float16, 2) + def test_qlinearmatmul_3D_int8_float16(self): self._run_qlinearmatmul_test(np.int8, np.float16, 3) + def test_qlinearmatmul_2D_int8_float32(self): self._run_qlinearmatmul_test(np.int8, np.float32, 2) + def test_qlinearmatmul_3D_int8_float32(self): self._run_qlinearmatmul_test(np.int8, np.float32, 3) + +class TestContribOnnxOps(TestOnnxOps): + DOMAIN = "com.microsoft" + def test_attention(self): + batch_size, seq_len, input_hidden_size = 2, 8, 256 + num_heads, head_size = 4, 64 + hidden_size = num_heads * head_size + v_hidden_size = hidden_size + + # for mask_index + right_padding_mask = np.random.randint(1, seq_len + 1, size=(batch_size,), dtype=np.int32) + end_positions = np.random.randint(1, seq_len + 1, size=(batch_size,), dtype=np.int32) + start_positions = np.array([np.random.randint(0, end) for end in end_positions], dtype=np.int32) + left_padding_mask = np.concatenate([end_positions, start_positions]) + + base_inps = { + "input": np.random.randn(batch_size, seq_len, input_hidden_size).astype(np.float32), + "weights": np.random.randn(input_hidden_size, hidden_size * 3).astype(np.float32), + # bias is required in ORT (segfaults otherwise), eventhough docs says it's optional + "bias": np.random.randn(hidden_size * 2 + v_hidden_size).astype(np.float32), + } + base_opts = {"num_heads": num_heads} + + test_cases = [ + ({}, {}), + ({}, {"scale": 0.1}), + ({}, {"scale": 1.0}), + ({}, {"unidirectional": 1}), + ({"mask_index": right_padding_mask}, {}), + ({"mask_index": left_padding_mask}, {}), + ({"mask_index": np.random.randint(0, seq_len, size=(batch_size, seq_len), dtype=np.int32)}, {"mask_filter_value": -5000.0}), + ({"mask_index": np.random.randint(0, seq_len, size=(batch_size, seq_len, seq_len), dtype=np.int32)}, {"mask_filter_value": -np.inf}), + # BUG: when `mask_index` is used with `unidirectional`, the first value must be True + # otherwise this will trigger a different ORT behavior where start consecutive Falses will be turned True + # e.g. mask_index = [[0, 0, 1, 0, 1, 1, 1, 1], [0, 0, 1, 0, 1, 1, 1, 1]] + # will need mask[:, :, 0:1, 0:1] = True + ({"mask_index": np.array([[1, 0, 1, 0, 1, 1, 1, 1], [1, 0, 1, 0, 1, 1, 1, 1]], dtype=np.int32)}, {"unidirectional": 1}), + ({ "weights": np.random.randn(input_hidden_size, hidden_size + hidden_size + 128).astype(np.float32), + "bias": np.random.randn(hidden_size + hidden_size + 128).astype(np.float32)}, + {"qkv_hidden_sizes": [hidden_size, hidden_size, 128]}), + # TODO: past is not tested. ORT gives type error for input + ] + + for i, (extra_inps, extra_opts) in enumerate(test_cases): + with self.subTest(f"test_attention_{i}"): + inps = {**base_inps, **extra_inps} + opts = {**base_opts, **extra_opts} + outputs = ["output", "present"] if "past" in inps else ["output"] + self.helper_test_single_op("Attention", inps, opts, outputs, atol=1e-4) + + def test_skip_layer_normalization(self): + shape = (2, 8, 32) + for has_beta in [True, False]: + for has_bias in [True, False]: + with self.subTest(has_beta=has_beta, has_bias=has_bias): + hidden_size = shape[-1] + inputs = { + "input": np.random.randn(*shape).astype(np.float32), + "skip": np.random.randn(*shape).astype(np.float32), + "gamma": np.random.randn(hidden_size).astype(np.float32), + } + if has_beta: inputs["beta"] = np.random.randn(hidden_size).astype(np.float32) + if has_bias: inputs["bias"] = np.random.randn(hidden_size).astype(np.float32) + attributes = {"epsilon": 1e-12} + outputs = ["output", "mean", "inv_std_var", "input_skip_bias_sum"] + self.helper_test_single_op("SkipLayerNormalization", inputs, attributes, outputs) + + def test_bias_gelu(self): + shape = (2,3,4) + inputs = { + "A": np.random.randn(*shape).astype(np.float32), + "B": np.random.randn(shape[-1]).astype(np.float32) + } + attributes = {} + outputs = ["C"] + self.helper_test_single_op("BiasGelu", inputs, attributes, outputs) + + def test_qlinear_add(self): + for dtype, zero_point in [(np.uint8, 128), (np.int8, 0)]: + with self.subTest(dtype=dtype, zero_point=zero_point): + dtype_min, dtype_max = np.iinfo(dtype).min, np.iinfo(dtype).max + inputs = { + "A": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "A_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "A_zero_point": np.array(zero_point, dtype=dtype), + "B": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "B_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "B_zero_point": np.array(zero_point, dtype=dtype), + "C_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "C_zero_point": np.array(zero_point, dtype=dtype) + } + attributes = {} + outputs = ["C"] + self.helper_test_single_op("QLinearAdd", inputs, attributes, outputs, atol=1) # TODO: look into why this is inaccurate + + with self.subTest(test_case="round_half_to_even"): + inputs = { + "A": np.array([1, 1, 1, 1], dtype=np.int8), + "A_scale": np.array(1, dtype=np.float32), + "A_zero_point": np.array(0, dtype=np.int8), + "B": np.array([1, 5, -3, -7], dtype=np.int8), + "B_scale": np.array(1, dtype=np.float32), + "B_zero_point": np.array(0, dtype=np.int8), + "C_scale": np.array(4, dtype=np.float32), + "C_zero_point": np.array(0, dtype=np.int8) + } + attributes = {} + outputs = ["C"] + self.helper_test_single_op("QLinearAdd", inputs, attributes, outputs) + + def test_qlinear_mul(self): + for dtype, zero_point in [(np.uint8, 128), (np.int8, 0)]: + with self.subTest(dtype=dtype, zero_point=zero_point): + dtype_min, dtype_max = np.iinfo(dtype).min, np.iinfo(dtype).max + inputs = { + "A": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "A_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "A_zero_point": np.array(zero_point, dtype=dtype), + "B": np.random.randint(dtype_min, dtype_max + 1, [10, 10], dtype=dtype), + "B_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "B_zero_point": np.array(zero_point, dtype=dtype), + "C_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "C_zero_point": np.array(zero_point, dtype=dtype) + } + attributes = {} + outputs = ["C"] + self.helper_test_single_op("QLinearMul", inputs, attributes, outputs) + + with self.subTest(test_case="round_half_to_even"): + inputs = { + "A": np.array([1, 1, 1, 1], dtype=np.int8), + "A_scale": np.array(1, dtype=np.float32), + "A_zero_point": np.array(0, dtype=np.int8), + "B": np.array([2, 6, -2, -6], dtype=np.int8), + "B_scale": np.array(1, dtype=np.float32), + "B_zero_point": np.array(0, dtype=np.int8), + "C_scale": np.array(4, dtype=np.float32), + "C_zero_point": np.array(0, dtype=np.int8) + } + attributes = {} + outputs = ["C"] + self.helper_test_single_op("QLinearMul", inputs, attributes, outputs) + + def test_qlinear_global_average_pool(self): + for dtype, zero_point in [(np.uint8, 128), (np.int8, 0)]: + with self.subTest(dtype=dtype, zero_point=zero_point): + dtype_min, dtype_max = np.iinfo(dtype).min, np.iinfo(dtype).max + inputs = { + "X": np.random.randint(dtype_min, dtype_max + 1, [1, 3, 32, 32], dtype=dtype), + "x_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "x_zero_point": np.array(zero_point, dtype=dtype), + "y_scale": np.array(np.random.uniform(0.01, 0.1), dtype=np.float32), + "y_zero_point": np.array(zero_point, dtype=dtype) + } + attributes = {"channels_last": 0} + outputs = ["C"] + self.helper_test_single_op("QLinearGlobalAveragePool", inputs, attributes, outputs) + +if __name__ == "__main__": + unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_test_speed_llama.py b/tinygrad_repo/test/external/external_test_speed_llama.py index 00b6df53c6..3d468e6257 100644 --- a/tinygrad_repo/test/external/external_test_speed_llama.py +++ b/tinygrad_repo/test/external/external_test_speed_llama.py @@ -4,7 +4,7 @@ from examples.llama import Transformer, MODEL_PARAMS from tinygrad.tensor import Tensor from tinygrad import Device from tinygrad.nn.state import get_state_dict -from tinygrad.device import Allocator +from tinygrad.device import Allocator, Compiled from tinygrad.engine.realize import method_cache from tinygrad.helpers import Profiling @@ -12,7 +12,7 @@ class FakeProgram: def __init__(self, name:str, prg:bytes): pass def __call__(self, *bufs, global_size, local_size, vals=(), wait=False): pass -class FakeAllocator(Allocator): +class FakeAllocator(Allocator[Compiled]): def _alloc(self, sz, options): return None def _copyin(self, dest, src:memoryview): pass @@ -22,7 +22,7 @@ class TestLLaMASpeed(unittest.TestCase): backup_allocator = Device[Device.DEFAULT].allocator backup_compiler = Device[Device.DEFAULT].compiler Device[Device.DEFAULT].runtime = FakeProgram - Device[Device.DEFAULT].allocator = FakeAllocator() + Device[Device.DEFAULT].allocator = FakeAllocator(Device.default) print("testing llama python run time") model = Transformer(**MODEL_PARAMS["1"]["7B"]["args"]) diff --git a/tinygrad_repo/test/external/external_test_tlsf.py b/tinygrad_repo/test/external/external_test_tlsf.py new file mode 100644 index 0000000000..aa780fdd50 --- /dev/null +++ b/tinygrad_repo/test/external/external_test_tlsf.py @@ -0,0 +1,78 @@ +import unittest +from tinygrad.runtime.support.allocator import TLSFAllocator + +class TestTLSFAllocator(unittest.TestCase): + def setUp(self): + self.allocator = TLSFAllocator(1024, block_size=16) + + def test_basic_alloc_free(self): + addr1 = self.allocator.alloc(32) + self.assertEqual(addr1, 0) + + addr2 = self.allocator.alloc(64) + self.assertEqual(addr2, 32) + + self.allocator.free(addr1) + addr3 = self.allocator.alloc(32) + self.assertEqual(addr3, 0) + + def test_block_size_alignment(self): + addr1 = self.allocator.alloc(20) + addr2 = self.allocator.alloc(35) + + self.assertEqual(addr1 % 16, 0) + self.assertEqual(addr2 % 16, 0) + + def test_merge_blocks(self): + addr1 = self.allocator.alloc(32) + addr2 = self.allocator.alloc(32) + self.allocator.alloc(32) + + self.allocator.free(addr1) + self.allocator.free(addr2) + addr4 = self.allocator.alloc(64) + self.assertEqual(addr4, addr1) + + def test_split_blocks(self): + addr1 = self.allocator.alloc(128) + self.allocator.free(addr1) + + addr2 = self.allocator.alloc(32) + self.assertEqual(addr2, addr1) + + addr3 = self.allocator.alloc(32) + self.assertEqual(addr3, addr1 + 32) + + def test_out_of_memory(self): + with self.assertRaises(MemoryError): + self.allocator.alloc(2048) + + def test_fragmentation_handling(self): + addrs = [] + for _ in range(5): + addrs.append(self.allocator.alloc(32)) + + # Free alternate blocks + for i in range(0, len(addrs), 2): + self.allocator.free(addrs[i]) + + def test_custom_start_address(self): + allocator = TLSFAllocator(1024, start_addr=1000) + addr1 = allocator.alloc(32) + self.assertEqual(addr1, 1000) + + addr2 = allocator.alloc(64) + self.assertEqual(addr2, 1032) + + def test_block_tracking(self): + addr1 = self.allocator.alloc(32) + addr2 = self.allocator.alloc(64) + + self.assertTrue(addr1 in [addr - self.allocator.start_addr for addr in self.allocator.blocks]) + self.assertTrue(addr2 in [addr - self.allocator.start_addr for addr in self.allocator.blocks]) + + self.allocator.free(addr1) + self.assertTrue(addr1 in [addr - self.allocator.start_addr for addr in self.allocator.blocks]) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/external/external_test_train_gpt2.py b/tinygrad_repo/test/external/external_test_train_gpt2.py new file mode 100644 index 0000000000..6d3a1cb9c1 --- /dev/null +++ b/tinygrad_repo/test/external/external_test_train_gpt2.py @@ -0,0 +1,55 @@ +# ruff: noqa: E501 +import unittest + +from tinygrad.uop.ops import UOp, Ops +from tinygrad.engine.search import Opt, OptOps +from tinygrad.dtype import dtypes +from tinygrad.shape.shapetracker import ShapeTracker +from tinygrad.shape.view import View +from tinygrad.codegen.kernel import Kernel + +from test.external.fuzz_linearizer import run_linearizer + +class TestTrainGpt2Kernel(unittest.TestCase): + def test_1(self): + # kernel 244 + ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(206045184), arg=0, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 50304, 1), strides=(51511296, 50304, 1, 0), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (3,)), src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(3145728), arg=1, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 50304, 768), strides=(786432, 768, 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(38633472), arg=2, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 50304, 768), strides=(0, 0, 768, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) + + opts = [Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=3), Opt(op=OptOps.LOCAL, axis=0, arg=2)] + kernel = Kernel(ast) + kernel.apply_opts(opts) + run_linearizer(kernel) + + def test_2(self): + # kernel 254 + ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(3145728), arg=0, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 1, 768), strides=(786432, 768, 0, 1), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (2,)), src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(38633472), arg=1, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 50304, 768), strides=(0, 0, 768, 1), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(205852672), arg=2, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1024, 50304, 768), strides=(51463168, 50257, 1, 0), offset=0, mask=((0, 4), (0, 1024), (0, 50257), (0, 768)), contiguous=False),)), src=()),)),)),)),)),)) + + opts = [Opt(op=OptOps.LOCAL, axis=1, arg=16), Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=2, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=3, arg=4)] + kernel = Kernel(ast) + kernel.apply_opts(opts) + run_linearizer(kernel) + +if __name__ == "__main__": + unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_test_usb_asm24.py b/tinygrad_repo/test/external/external_test_usb_asm24.py new file mode 100644 index 0000000000..3df81b28e1 --- /dev/null +++ b/tinygrad_repo/test/external/external_test_usb_asm24.py @@ -0,0 +1,73 @@ +import unittest, time +from tinygrad.runtime.support.usb import ASM24Controller +from tinygrad.helpers import Timing +from tinygrad import Tensor, Device +import numpy as np + +class TestASMController(unittest.TestCase): + @classmethod + def setUpClass(cls): + cls.ctrl = ASM24Controller() + + def test_write_and_read(self): + base = 0xF000 + data = b"hello!" + self.ctrl.write(base, data) + out = self.ctrl.read(base, len(data)) + self.assertEqual(out, data) + + def test_scsi_write_and_read_from_f000(self): + payload = bytes([0x5B]) * 4096 + self.ctrl.scsi_write(payload, lba=0) + back = self.ctrl.read(0xF000, len(payload)) + self.assertEqual(back, payload) + + def test_scsi_write_speed_4k(self): + payload = bytes([0x5A]) * 4096 + start = time.perf_counter() + self.ctrl.scsi_write(payload, lba=0) + dur_ms = (time.perf_counter() - start) * 1000 + print(f"scsi_write 4K took {dur_ms:.3f} ms") + + def test_read_speed_4k(self): + payload = bytes([0xA5]) * 4096 + self.ctrl.write(0xF000, payload) + start = time.perf_counter() + out = self.ctrl.read(0xF000, 4096) + dur_ms = (time.perf_counter() - start) * 1000 + print(f"read 4K took {dur_ms:.3f} ms") + self.assertEqual(out, payload) + +class TestDevCopySpeeds(unittest.TestCase): + @classmethod + def setUpClass(cls): + cls.sz = 512 + cls.dev = Device["AMD"] + if not cls.dev.is_usb(): raise unittest.SkipTest("only test this on USB devices") + + def testCopyCPUtoDefault(self): + for _ in range(10): + t = Tensor.ones(self.sz, self.sz, device="CPU").contiguous().realize() + with Timing(f"copyin of {t.nbytes()/1e6:.2f} MB: ", on_exit=lambda ns: f" @ {t.nbytes()/ns * 1e3:.2f} MB/s"): # noqa: F821 + t.to(Device.DEFAULT).realize() + Device[Device.DEFAULT].synchronize() + del t + + def testCopyDefaulttoCPU(self): + t = Tensor.ones(self.sz, self.sz).contiguous().realize() + for _ in range(10): + with Timing(f"copyout of {t.nbytes()/1e6:.2f} MB: ", on_exit=lambda ns: f" @ {t.nbytes()/ns * 1e3:.2f} MB/s"): + t.to('CPU').realize() + + def testValidateCopies(self): + t = Tensor.randn(self.sz, self.sz, device="CPU").contiguous().realize() + x = t.to(Device.DEFAULT).realize() + Device[Device.DEFAULT].synchronize() + + y = x.to('CPU').realize() + + np.testing.assert_equal(t.numpy(), y.numpy()) + del x, y, t + +if __name__ == "__main__": + unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_test_valid_remove.py b/tinygrad_repo/test/external/external_test_valid_remove.py index 1467139daf..65f8112e96 100644 --- a/tinygrad_repo/test/external/external_test_valid_remove.py +++ b/tinygrad_repo/test/external/external_test_valid_remove.py @@ -2,7 +2,7 @@ import unittest from tinygrad import Device -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.engine.search import Opt, OptOps from tinygrad.dtype import dtypes from tinygrad.shape.shapetracker import ShapeTracker @@ -51,10 +51,10 @@ class TestOpenpilotValidhack(unittest.TestCase): x19,)), x29,)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=3, amt=4), Opt(op=OptOps.UNROLL, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.NOLOCALS, axis=None, amt=None)] + opts = [Opt(op=OptOps.UPCAST, axis=3, arg=4), Opt(op=OptOps.UNROLL, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.NOLOCALS, axis=None, arg=None)] kernel = Kernel(ast) - for opt in opts: kernel.apply_opt(opt) + kernel.apply_opts(opts) p = kernel.to_program() print(p.src) @@ -108,10 +108,10 @@ class TestOpenpilotValidhack(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.imagef((1, 128, 4)), arg=3, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 10, 512), strides=(0, 0, 1), offset=0, mask=((0, 1), (9, 10), (0, 512)), contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.NOLOCALS, axis=None, amt=None)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.NOLOCALS, axis=None, arg=None)] kernel = Kernel(ast) - for opt in opts: kernel.apply_opt(opt) + kernel.apply_opts(opts) p = kernel.to_program() # ((idx1<1)?read_imagef(data1, smp, (int2)(idx0,0)):(float4)(0.0f,0.0f,0.0f,0.0f)) diff --git a/tinygrad_repo/test/external/external_test_yolov8.py b/tinygrad_repo/test/external/external_test_yolov8.py index a215aa0675..5506fae7f0 100644 --- a/tinygrad_repo/test/external/external_test_yolov8.py +++ b/tinygrad_repo/test/external/external_test_yolov8.py @@ -1,5 +1,6 @@ import numpy as np -from examples.yolov8 import YOLOv8, get_variant_multiples, preprocess, postprocess, label_predictions +from examples.yolov8 import YOLOv8, get_variant_multiples, preprocess, label_predictions, postprocess +from tinygrad import Tensor import unittest import io, cv2 import onnxruntime as ort @@ -28,9 +29,8 @@ class TestYOLOv8(unittest.TestCase): img = cv2.imdecode(np.frombuffer(fetch(test_image_urls[i]).read_bytes(), 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} + labels = label_predictions(predictions.numpy()) + assert labels == {5: 1, 0: 4, 11: 1} if i == 0 else labels == {0: 12, 29: 1, 32: 1} def test_forward_pass_torch_onnx(self): variant = 'n' @@ -58,12 +58,16 @@ class TestYOLOv8(unittest.TestCase): 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) + tiny_output = TinyYolov8(input_image).numpy() + onnx_output = postprocess(Tensor(onnx_output[0])).numpy() + #invalid boxes are multiplied by zero in postprocess + onnx_output = onnx_output[onnx_output[:, 4] != 0] + tiny_output = tiny_output[tiny_output[:, 4] != 0] # 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) + np.testing.assert_allclose(onnx_output, tiny_output, atol=5e-4, rtol=0.025) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/external/external_uop_gc.py b/tinygrad_repo/test/external/external_uop_gc.py new file mode 100644 index 0000000000..03f6169b7f --- /dev/null +++ b/tinygrad_repo/test/external/external_uop_gc.py @@ -0,0 +1,72 @@ +import gc +from tinygrad import Tensor, UOp, Device +from tinygrad.shape.shapetracker import views_to_indexed_uops +from tinygrad.engine.realize import method_cache, get_kernel + +def uops_allocated(): return sum([isinstance(x, UOp) for x in gc.get_objects()]) +def print_uops(): + for x in gc.get_objects(): + if isinstance(x, UOp): print(x) + +def start(): pass +def single_tensor(): Tensor([2]) +def two_plus_two(): Tensor([2])+Tensor([2]) +def two_plus_two_schedule(): (Tensor([2])+Tensor([2])).schedule() +def two_plus_two_kernel(): + si = (Tensor([2])+Tensor([2])).schedule()[-1] + get_kernel(Device.default.renderer, si.ast) +def two_plus_two_linearize(): + si = (Tensor([2])+Tensor([2])).schedule()[-1] + k = get_kernel(Device.default.renderer, si.ast) + k.get_optimized_ast() + #k.linearize() +def two_plus_two_realize(): (Tensor([2])+Tensor([2])).realize() +def two_plus_two_item(): (Tensor([2])+Tensor([2])).item() +def gradient_test(): + x = Tensor.eye(3, requires_grad=True) + y = Tensor([[2.0,0,-2.0]], requires_grad=True) + z = y.matmul(x).sum() + z.backward() +def realized_eye(): + Tensor.eye(3, requires_grad=True).realize() +def realized_list(): + Tensor([[2.0,0,-2.0]], requires_grad=True).realize() +def kernel_matmul(): + x = Tensor.eye(3, requires_grad=True) + y = Tensor([[2.0,0,-2.0]], requires_grad=True) + z = y.matmul(x) + si = z.schedule()[-1] + get_kernel(Device.default.renderer, si.ast) +def realized_matmul(): + x = Tensor.eye(3, requires_grad=True) + y = Tensor([[2.0,0,-2.0]], requires_grad=True) + z = y.matmul(x) + Tensor.realize(z) +def realized_gradient(): + x = Tensor.eye(3, requires_grad=True) + y = Tensor([[2.0,0,-2.0]], requires_grad=True) + z = y.matmul(x).sum() + z.backward() + Tensor.realize(x, y, z, x.grad, y.grad) +tests = [start, single_tensor, two_plus_two, two_plus_two_schedule, two_plus_two_kernel, + two_plus_two_linearize, two_plus_two_realize, two_plus_two_item, gradient_test, + realized_eye, realized_list, kernel_matmul, realized_matmul, realized_gradient] + +if __name__ == "__main__": + gc.disable() + start_uops = uops_allocated() + # there's a few consts created as default values + print_uops() + for t in tests: + t() + + # these caches will keep uops alive + method_cache.clear() + views_to_indexed_uops.cache_clear() + + new_uops = uops_allocated() + gc.collect() + new_uops_gc = uops_allocated() + print(f"{t.__name__:30s}: {new_uops:3d} -> {new_uops_gc:3d}") + assert new_uops == start_uops + #print_uops() diff --git a/tinygrad_repo/test/external/fuzz_fast_idiv.py b/tinygrad_repo/test/external/fuzz_fast_idiv.py new file mode 100644 index 0000000000..c7bf90b841 --- /dev/null +++ b/tinygrad_repo/test/external/fuzz_fast_idiv.py @@ -0,0 +1,33 @@ +import random +from z3 import Int, Solver, sat +from tinygrad import dtypes, Device +from tinygrad.uop.ops import UOp, Ops, UPat, graph_rewrite, PatternMatcher +from tinygrad.codegen.devectorizer import fast_idiv +random.seed(42) + +z3_renderer = PatternMatcher([ + (UPat((Ops.DEFINE_VAR, Ops.SPECIAL), name="x"), lambda x: UOp(Ops.NOOP, arg=x.arg[0])), + # Because fast_idiv only works for non-negative integers we can emulate machine arithmetic with modulo operations. + (UPat(Ops.SHR, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"(({x.src[0].arg}/(2**{x.src[1].arg}))%{dtypes.max(x.dtype)+1})")), + (UPat(Ops.MUL, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"(({x.src[0].arg}*{x.src[1].arg})%{dtypes.max(x.dtype)+1})")), + (UPat((Ops.CONST, Ops.VCONST), name="x"), lambda x: UOp(Ops.NOOP, arg=str(x.arg))), + (UPat(Ops.CAST, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"{x.src[0].arg}")), +]) + +def render(self) -> str: + ret = graph_rewrite(self.simplify(), z3_renderer) + return ret.arg if ret.op is Ops.NOOP else str(ret) + +if __name__ == "__main__": + x = Int('x') + for _ in range(10_000): + dt = random.choice(dtypes.ints) + u = UOp(Ops.DEFINE_VAR, dt, arg=('x', 0, random.randint(1, dtypes.max(dt))), src=()) + d = random.randint(1, max(1, u.arg[2])) + + expr = fast_idiv(Device[Device.DEFAULT].renderer, u, d) + if expr is None: continue + solver = Solver() + solver.add(x>=u.arg[1], x<=u.arg[2]) + if solver.check(eval(render(expr)) != x/d) == sat: + assert False, f"Failed: {render(expr)} != x//{d} at x={solver.model()[x]}\nx={u}\nd={d}" diff --git a/tinygrad_repo/test/external/fuzz_graph.py b/tinygrad_repo/test/external/fuzz_graph.py index 0fa0b55b02..7992e21778 100644 --- a/tinygrad_repo/test/external/fuzz_graph.py +++ b/tinygrad_repo/test/external/fuzz_graph.py @@ -4,7 +4,6 @@ from tinygrad.device import Buffer, Device from tinygrad.helpers import Context, getenv, from_mv from tinygrad.dtype import dtypes from tinygrad.tensor import Tensor, _to_np_dtype -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import ExecItem, BufferXfer, get_runner from tinygrad.engine.jit import apply_graph_to_jit @@ -17,9 +16,9 @@ def gen_prg(device, inputs_cnt): with Context(DEBUG=0): fst = [Tensor.randn(BUF_LEN, dtype=dtypes.int).realize() for i in range(inputs_cnt)] s = fst[0] - for i in range(1, inputs_cnt): s = s.xor(fst[i]) + for i in range(1, inputs_cnt): s = s.bitwise_xor(fst[i]) - si = create_schedule([s.lazydata])[-1] + si = s.schedule()[-1] prg = get_runner(device, si.ast) cached_prgs[(device, inputs_cnt)] = prg return prg @@ -122,7 +121,7 @@ if __name__ == "__main__": np.random.seed(SEED) next_graph_id = 0 - while True: + for i in range(getenv("ITERS", 1000)): print("Running graph", next_graph_id) jis, all_buffers, input_buffers = gen_graph() fuzz_graph(jis, all_buffers, input_buffers) diff --git a/tinygrad_repo/test/external/fuzz_linearizer.py b/tinygrad_repo/test/external/fuzz_linearizer.py index 101b473f1a..8a03176306 100644 --- a/tinygrad_repo/test/external/fuzz_linearizer.py +++ b/tinygrad_repo/test/external/fuzz_linearizer.py @@ -1,5 +1,5 @@ import random, traceback, ctypes, argparse, os -from typing import List, Tuple, DefaultDict, Any +from typing import Any import numpy as np from collections import defaultdict from extra.optimization.helpers import load_worlds, ast_str_to_lin, kern_str_to_lin @@ -25,7 +25,7 @@ from tinygrad.codegen.kernel import Opt, OptOps from tinygrad.engine.search import get_kernel_actions, bufs_from_lin from tinygrad.engine.realize import CompiledRunner from tinygrad.helpers import getenv, from_mv, prod, colored, Context, DEBUG, Timing -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.device import is_dtype_supported def on_linearizer_will_run(): pass @@ -50,11 +50,9 @@ if getenv("VALIDATE_HCQ"): else: print(colored("VALIDATE_HCQ options is ignored", 'red')) -def tuplize_uops(uops:List[UOp]) -> Tuple: +def tuplize_uops(uops:list[UOp]) -> tuple: return tuple([(x.op, x.dtype, tuple(uops.index(x) for x in x.src), x.arg) for x in uops]) -device = Device[Device.DEFAULT] - def get_fuzz_rawbufs(lin): rawbufs = bufs_from_lin(lin) @@ -89,9 +87,9 @@ def get_fuzz_rawbuf_like(old_rawbuf, zero=False, copy=False, size=None, force_de rawbuf.copyin(mv) return rawbuf -def run_linearizer(lin: Kernel, rawbufs=None, var_vals=None) -> Tuple[str, Any]: # (error msg, run state) +def run_linearizer(lin: Kernel, rawbufs=None, var_vals=None) -> tuple[str, Any]: # (error msg, run state) if rawbufs is None: rawbufs = bufs_from_lin(lin) - if var_vals is None: var_vals = {v: v.min for v in lin.ast[0].vars()} + if var_vals is None: var_vals = {v: v.min for v in lin.vars} # TODO: images needs required_optimization try: @@ -134,7 +132,6 @@ def compare_linearizer(lin: Kernel, rawbufs=None, var_vals=None, ground_truth=No if ground_truth is None and not has_bf16: unoptimized = Kernel(lin.ast) - unoptimized.required_optimizations() if run_linearizer(unoptimized, rawbufs, var_vals)[0] != "PASS": return ("BASELINE_ERROR", rawbufs, var_vals, ground_truth, None) ground_truth = np.frombuffer(rawbufs[0].as_buffer(), _to_np_dtype(rawbufs[0].dtype)).copy() @@ -169,7 +166,7 @@ def fuzz_linearizer(lin: Kernel, rtol=1e-2, atol=1e-2, opts_list=None): print(lin.colored_shape()) seen_uops = {} last_lins = [lin] - failures:DefaultDict[str, List[Tuple[Tuple[UOp,...],List[Opt]]]] = defaultdict(list) + failures:defaultdict[str, list[tuple[tuple[UOp, ...], list[Opt]]]] = defaultdict(list) rawbufs, var_vals, ground_truth, validate_rawbufs = None, None, None, None FUZZ_ALL_ACTIONS = getenv("FUZZ_ALL_ACTIONS", 0) diff --git a/tinygrad_repo/test/external/fuzz_schedule.py b/tinygrad_repo/test/external/fuzz_schedule.py index 5703aa8b80..34f3313ada 100644 --- a/tinygrad_repo/test/external/fuzz_schedule.py +++ b/tinygrad_repo/test/external/fuzz_schedule.py @@ -5,7 +5,7 @@ from tinygrad.device import Buffer from tinygrad.engine.realize import capturing, lower_schedule_item from tinygrad.helpers import DEBUG, MULTIOUTPUT, colored, getenv from tinygrad.engine.schedule import LBScheduleItem, _graph_schedule, ScheduleItem -from tinygrad.ops import Ops, UOp +from tinygrad.uop.ops import Ops, UOp from tinygrad.tensor import Tensor, _to_np_dtype ctx_vars = { MULTIOUTPUT: (0, 1) } diff --git a/tinygrad_repo/test/external/fuzz_shapetracker.py b/tinygrad_repo/test/external/fuzz_shapetracker.py index 0a10d581ff..ba11fa1ebd 100644 --- a/tinygrad_repo/test/external/fuzz_shapetracker.py +++ b/tinygrad_repo/test/external/fuzz_shapetracker.py @@ -38,17 +38,10 @@ def do_shrink(st): if DEBUG >= 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_flip(st): - c = random.randint(0, len(st.shape)-1) - stride = tuple(-1 if i==c else 1 for i in range(len(st.shape))) - if DEBUG >= 1: print("st.stride(", stride, ")") - st.stride(stride) + flip = tuple(random.random() < 0.5 for _ in st.shape) + if DEBUG >= 1: print("st.flip(", flip, ")") + st.flip(flip) def do_expand(st): c = [i for i,s in enumerate(st.shape) if s==1] @@ -58,7 +51,7 @@ def do_expand(st): if DEBUG >= 1: print("st.expand(", expand, ")") st.expand(expand) -shapetracker_ops = [do_permute, do_pad, do_shrink, do_reshape_split_one, do_reshape_combine_two, do_stride, do_expand] +shapetracker_ops = [do_permute, do_pad, do_shrink, do_reshape_split_one, do_reshape_combine_two, do_flip, do_expand] if __name__ == "__main__": random.seed(42) diff --git a/tinygrad_repo/test/external/fuzz_shapetracker_math.py b/tinygrad_repo/test/external/fuzz_shapetracker_math.py index 663259a743..c7364ae3e5 100644 --- a/tinygrad_repo/test/external/fuzz_shapetracker_math.py +++ b/tinygrad_repo/test/external/fuzz_shapetracker_math.py @@ -1,12 +1,11 @@ import random -from typing import Tuple from tinygrad.helpers import getenv, DEBUG, colored, trange from tinygrad.shape.shapetracker import ShapeTracker from test.external.fuzz_shapetracker import shapetracker_ops from test.external.fuzz_shapetracker import do_permute, do_reshape_split_one, do_reshape_combine_two, do_flip, do_pad from test.unit.test_shapetracker_math import st_equal, MultiShapeTracker -def fuzz_plus() -> Tuple[ShapeTracker, ShapeTracker]: +def fuzz_plus() -> tuple[ShapeTracker, ShapeTracker]: m = MultiShapeTracker([ShapeTracker.from_shape((random.randint(1, 10), random.randint(1, 10), random.randint(1, 10)))]) for _ in range(4): random.choice(shapetracker_ops)(m) backup = m.sts[0] @@ -18,7 +17,7 @@ def fuzz_plus() -> Tuple[ShapeTracker, ShapeTracker]: # shrink and expand aren't invertible, and stride is only invertible in the flip case invertible_shapetracker_ops = [do_permute, do_reshape_split_one, do_reshape_combine_two, do_flip, do_pad] -def fuzz_invert() -> Tuple[ShapeTracker, ShapeTracker]: +def fuzz_invert() -> tuple[ShapeTracker, ShapeTracker]: start = ShapeTracker.from_shape((random.randint(1, 10), random.randint(1, 10), random.randint(1, 10))) m = MultiShapeTracker([start]) for _ in range(8): random.choice(invertible_shapetracker_ops)(m) diff --git a/tinygrad_repo/test/external/fuzz_shapetracker_size.py b/tinygrad_repo/test/external/fuzz_shapetracker_size.py new file mode 100644 index 0000000000..dc76f3aecd --- /dev/null +++ b/tinygrad_repo/test/external/fuzz_shapetracker_size.py @@ -0,0 +1,13 @@ +from tinygrad.shape.shapetracker import ShapeTracker +from test.external.fuzz_shapetracker import shapetracker_ops as st_ops +from test.unit.test_shapetracker_math import MultiShapeTracker +from tinygrad.helpers import getenv +import random + +random.seed(getenv("SEED", 42)) +for i in range(getenv("CNT", 2000)): + if getenv("DEBUG", 0) >= 1: print() + N = random.randint(1, 10000) + mst = MultiShapeTracker([ShapeTracker.from_shape((N,))]) # st_ops don't mutate regular shapetrackers for some reason + for j in range(20): random.choice(st_ops)(mst) + assert mst.sts[0].real_size() <= N, f"{N=}, real_size={mst.sts[0].real_size()}, st={mst.sts[0]}" diff --git a/tinygrad_repo/test/external/fuzz_symbolic.py b/tinygrad_repo/test/external/fuzz_symbolic.py index 42798bd181..8d2242a0c8 100644 --- a/tinygrad_repo/test/external/fuzz_symbolic.py +++ b/tinygrad_repo/test/external/fuzz_symbolic.py @@ -1,7 +1,7 @@ import itertools import random from tinygrad import Variable, dtypes -from tinygrad.ops import UOp +from tinygrad.uop.ops import UOp from tinygrad.helpers import DEBUG random.seed(42) @@ -42,7 +42,7 @@ def gt(expr, rng=None): return expr > rng, rng # NOTE: you have to replace these for this test to pass -from tinygrad.ops import python_alu, Ops +from tinygrad.uop.ops import python_alu, Ops python_alu[Ops.MOD] = lambda x,y: x%y python_alu[Ops.IDIV] = lambda x,y: x//y @@ -70,7 +70,7 @@ if __name__ == "__main__": v = [v1,v2,v3] rn = 0 for t,r in zip(tape, rngs): rn, _ = t(rn, r) - num = eval(expr.render()) + num = eval(expr.render(simplify=False)) if num != rn: unsimplified_num = eval(expr.render(simplify=False)) assert unsimplified_num == rn, "UNSIMPLIFIED MISMATCH!" diff --git a/tinygrad_repo/test/external/fuzz_uops.py b/tinygrad_repo/test/external/fuzz_uops.py index 8aec783708..87d73e7cb5 100644 --- a/tinygrad_repo/test/external/fuzz_uops.py +++ b/tinygrad_repo/test/external/fuzz_uops.py @@ -3,11 +3,11 @@ from collections import defaultdict import numpy as np from dataclasses import replace from typing import DefaultDict, Dict, List, Tuple -from tinygrad.ops import UOp, print_uops, Ops +from tinygrad.uop.ops import UOp, print_uops, Ops from tinygrad.device import Buffer, Device from tinygrad.engine.realize import CompiledRunner from tinygrad.helpers import DEBUG, colored -from tinygrad.ops import Variable +from tinygrad.uop.ops import Variable from tinygrad.tensor import _to_np_dtype from test.external.fuzz_schedule import FUZZ_SCHEDULE_MAX_PATHS, find_all_toposorts @@ -52,7 +52,7 @@ class UOpsFuzzerRunner(CompiledRunner): # setup prg uops = list(path) if DEBUG >= 5: print_uops(uops) - self.p = replace(self.p, name=(name:=f"{init_name}fuzz{i}"), src=Device[self.p.device].renderer.render(name, uops), uops=uops) + self.p = replace(self.p, name=(name:=f"{init_name}fuzz{i}"), src=Device[self.p.device].renderer.render(uops), uops=uops) if DEBUG >= 4: print(self.p.src) self.lib = Device[self.p.device].compiler.compile_cached(self.p.src) self.clprg = Device[self.p.device].runtime(name, self.lib) diff --git a/tinygrad_repo/test/external/mlperf_retinanet/coco_utils.py b/tinygrad_repo/test/external/mlperf_retinanet/coco_utils.py new file mode 100644 index 0000000000..756bd6955d --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/coco_utils.py @@ -0,0 +1,89 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/coco_utils.py + +import os +import torch +import torchvision + +from test.external.mlperf_retinanet import transforms as T + +class ConvertCocoPolysToMask(object): + def __init__(self, filter_iscrowd=True): + self.filter_iscrowd = filter_iscrowd + + def __call__(self, image, target): + w, h = image.size + + image_id = target["image_id"] + image_id = torch.tensor([image_id]) + + anno = target["annotations"] + + if self.filter_iscrowd: + anno = [obj for obj in anno if obj['iscrowd'] == 0] + + boxes = [obj["bbox"] for obj in anno] + # guard against no boxes via resizing + boxes = torch.as_tensor(boxes, dtype=torch.float32).reshape(-1, 4) + boxes[:, 2:] += boxes[:, :2] + boxes[:, 0::2].clamp_(min=0, max=w) + boxes[:, 1::2].clamp_(min=0, max=h) + + classes = [obj["category_id"] for obj in anno] + classes = torch.tensor(classes, dtype=torch.int64) + + keypoints = None + if anno and "keypoints" in anno[0]: + keypoints = [obj["keypoints"] for obj in anno] + keypoints = torch.as_tensor(keypoints, dtype=torch.float32) + num_keypoints = keypoints.shape[0] + if num_keypoints: + keypoints = keypoints.view(num_keypoints, -1, 3) + + keep = (boxes[:, 3] > boxes[:, 1]) & (boxes[:, 2] > boxes[:, 0]) + boxes = boxes[keep] + classes = classes[keep] + + target = {} + target["boxes"] = boxes + target["labels"] = classes + target["image_id"] = image_id + + # for conversion to coco api + area = torch.tensor([obj["area"] for obj in anno]) + iscrowd = torch.tensor([obj["iscrowd"] for obj in anno]) + target["area"] = area + target["iscrowd"] = iscrowd + + return image, target + +class CocoDetection(torchvision.datasets.CocoDetection): + def __init__(self, img_folder, ann_file, transforms): + super(CocoDetection, self).__init__(img_folder, ann_file) + self._transforms = transforms + + def __getitem__(self, idx): + img, target = super(CocoDetection, self).__getitem__(idx) + image_id = self.ids[idx] + target = dict(image_id=image_id, annotations=target) + if self._transforms is not None: + img, target = self._transforms(img, target) + return img, target + +def get_openimages(name, root, image_set, transforms): + PATHS = { + "train": os.path.join(root, "train"), + "val": os.path.join(root, "validation"), + } + + t = [ConvertCocoPolysToMask(filter_iscrowd=False)] + + if transforms is not None: + t.append(transforms) + transforms = T.Compose(t) + + img_folder = os.path.join(PATHS[image_set], "data") + ann_file = os.path.join(PATHS[image_set], "labels", f"{name}.json") + + dataset = CocoDetection(img_folder, ann_file, transforms=transforms) + + return dataset \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/focal_loss.py b/tinygrad_repo/test/external/mlperf_retinanet/focal_loss.py new file mode 100644 index 0000000000..7167b58a1d --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/focal_loss.py @@ -0,0 +1,51 @@ +# Copied from https://github.com/mlcommons/training/blob/cdd928d4596c142c15a7d86b2eeadbac718c8da2/single_stage_detector/ssd/model/focal_loss.py + +import torch +import torch.nn.functional as F + + +def sigmoid_focal_loss( + inputs: torch.Tensor, + targets: torch.Tensor, + alpha: float = 0.25, + gamma: float = 2, + reduction: str = "none", +): + """ + Original implementation from https://github.com/facebookresearch/fvcore/blob/master/fvcore/nn/focal_loss.py . + Loss used in RetinaNet for dense detection: https://arxiv.org/abs/1708.02002. + + Args: + inputs: A float tensor of arbitrary shape. + The predictions for each example. + targets: A float tensor with the same shape as inputs. Stores the binary + classification label for each element in inputs + (0 for the negative class and 1 for the positive class). + alpha: (optional) Weighting factor in range (0,1) to balance + positive vs negative examples or -1 for ignore. Default = 0.25 + gamma: Exponent of the modulating factor (1 - p_t) to + balance easy vs hard examples. + reduction: 'none' | 'mean' | 'sum' + 'none': No reduction will be applied to the output. + 'mean': The output will be averaged. + 'sum': The output will be summed. + Returns: + Loss tensor with the reduction option applied. + """ + p = torch.sigmoid(inputs) + ce_loss = F.binary_cross_entropy_with_logits( + inputs, targets, reduction="none" + ) + p_t = p * targets + (1 - p) * (1 - targets) + loss = ce_loss * ((1 - p_t) ** gamma) + + if alpha >= 0: + alpha_t = alpha * targets + (1 - alpha) * (1 - targets) + loss = alpha_t * loss + + if reduction == "mean": + loss = loss.mean() + elif reduction == "sum": + loss = loss.sum() + + return loss \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/model/boxes.py b/tinygrad_repo/test/external/mlperf_retinanet/model/boxes.py new file mode 100644 index 0000000000..96dbceeb95 --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/model/boxes.py @@ -0,0 +1,65 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/model/boxes.py + +import torch +from torch import Tensor +from typing import Tuple + +def _upcast(t: Tensor) -> Tensor: + # Protects from numerical overflows in multiplications by upcasting to the equivalent higher type + if t.is_floating_point(): + return t if t.dtype in (torch.float32, torch.float64) else t.float() + else: + return t if t.dtype in (torch.int32, torch.int64) else t.int() + + +def box_area(boxes: Tensor) -> Tensor: + """ + Computes the area of a set of bounding boxes, which are specified by their + (x1, y1, x2, y2) coordinates. + + Args: + boxes (Tensor[N, 4]): boxes for which the area will be computed. They + are expected to be in (x1, y1, x2, y2) format with + ``0 <= x1 < x2`` and ``0 <= y1 < y2``. + + Returns: + Tensor[N]: the area for each box + """ + boxes = _upcast(boxes) + return (boxes[:, 2] - boxes[:, 0]) * (boxes[:, 3] - boxes[:, 1]) + + +# implementation from https://github.com/kuangliu/torchcv/blob/master/torchcv/utils/box.py +# with slight modifications +def _box_inter_union(boxes1: Tensor, boxes2: Tensor) -> Tuple[Tensor, Tensor]: + area1 = box_area(boxes1) + area2 = box_area(boxes2) + + lt = torch.max(boxes1[:, None, :2], boxes2[:, :2]) # [N,M,2] + rb = torch.min(boxes1[:, None, 2:], boxes2[:, 2:]) # [N,M,2] + + wh = _upcast(rb - lt).clamp(min=0) # [N,M,2] + inter = wh[:, :, 0] * wh[:, :, 1] # [N,M] + + union = area1[:, None] + area2 - inter + + return inter, union + + +def box_iou(boxes1: Tensor, boxes2: Tensor) -> Tensor: + """ + Return intersection-over-union (Jaccard index) between two sets of boxes. + + Both sets of boxes are expected to be in ``(x1, y1, x2, y2)`` format with + ``0 <= x1 < x2`` and ``0 <= y1 < y2``. + + Args: + boxes1 (Tensor[N, 4]): first set of boxes + boxes2 (Tensor[M, 4]): second set of boxes + + Returns: + Tensor[N, M]: the NxM matrix containing the pairwise IoU values for every element in boxes1 and boxes2 + """ + inter, union = _box_inter_union(boxes1, boxes2) + iou = inter / union + return iou \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/model/image_list.py b/tinygrad_repo/test/external/mlperf_retinanet/model/image_list.py new file mode 100644 index 0000000000..f7a4cf2eb9 --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/model/image_list.py @@ -0,0 +1,27 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/model/image_list.py + +import torch +from torch import Tensor +from typing import List, Tuple + + +class ImageList(object): + """ + Structure that holds a list of images (of possibly + varying sizes) as a single tensor. + This works by padding the images to the same size, + and storing in a field the original sizes of each image + """ + + def __init__(self, tensors: Tensor, image_sizes: List[Tuple[int, int]]): + """ + Args: + tensors (tensor) + image_sizes (list[tuple[int, int]]) + """ + self.tensors = tensors + self.image_sizes = image_sizes + + def to(self, device: torch.device) -> 'ImageList': + cast_tensor = self.tensors.to(device) + return ImageList(cast_tensor, self.image_sizes) \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/model/transform.py b/tinygrad_repo/test/external/mlperf_retinanet/model/transform.py new file mode 100644 index 0000000000..b68e8cfb2d --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/model/transform.py @@ -0,0 +1,163 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/model/transform.py + +import torch + +from torch import nn, Tensor +from typing import List, Tuple, Dict, Optional + +from test.external.mlperf_retinanet.model.image_list import ImageList + +@torch.jit.unused +def _get_shape_onnx(image: Tensor) -> Tensor: + from torch.onnx import operators + return operators.shape_as_tensor(image)[-2:] + +def _resize_image_and_masks(image: Tensor, + target: Optional[Dict[str, Tensor]] = None, + image_size: Optional[Tuple[int, int]] = None, + ) -> Tuple[Tensor, Optional[Dict[str, Tensor]]]: + image = torch.nn.functional.interpolate(image[None], size=image_size, scale_factor=None, mode='bilinear', + recompute_scale_factor=None, align_corners=False)[0] + + if target is None: + return image, target + + if "masks" in target: + mask = target["masks"] + mask = torch.nn.functional.interpolate(mask[:, None].float(), size=image_size, scale_factor=None, + recompute_scale_factor=None)[:, 0].byte() + target["masks"] = mask + return image, target + +class GeneralizedRCNNTransform(nn.Module): + """ + Performs input / target transformation before feeding the data to a GeneralizedRCNN + model. + + The transformations it perform are: + - input normalization (mean subtraction and std division) + - input / target resizing to match image_size + + It returns a ImageList for the inputs, and a List[Dict[Tensor]] for the targets + """ + + def __init__(self, image_size: Optional[Tuple[int, int]], + image_mean: List[float], image_std: List[float],): + super(GeneralizedRCNNTransform, self).__init__() + self.image_size = image_size + self.image_mean = image_mean + self.image_std = image_std + + def forward(self, + images: List[Tensor], + targets: Optional[List[Dict[str, Tensor]]] = None + ) -> Tuple[ImageList, Optional[List[Dict[str, Tensor]]]]: + images = list(img for img in images) + if targets is not None: + # make a copy of targets to avoid modifying it in-place + # once torchscript supports dict comprehension + # this can be simplified as follows + # targets = [{k: v for k,v in t.items()} for t in targets] + targets_copy: List[Dict[str, Tensor]] = [] + for t in targets: + data: Dict[str, Tensor] = {} + for k, v in t.items(): + data[k] = v + targets_copy.append(data) + targets = targets_copy + for i in range(len(images)): + image = images[i] + target_index = targets[i] if targets is not None else None + + if image.dim() != 3: + raise ValueError("images is expected to be a list of 3d tensors " + "of shape [C, H, W], got {}".format(image.shape)) + image = self.normalize(image) + image, target_index = self.resize(image, target_index) + images[i] = image + if targets is not None and target_index is not None: + targets[i] = target_index + + image_sizes = [img.shape[-2:] for img in images] + images = torch.stack(images) + image_sizes_list: List[Tuple[int, int]] = [] + for image_size in image_sizes: + assert len(image_size) == 2 + image_sizes_list.append((image_size[0], image_size[1])) + + image_list = ImageList(images, image_sizes_list) + return image_list, targets + + def normalize(self, image: Tensor) -> Tensor: + if not image.is_floating_point(): + raise TypeError( + f"Expected input images to be of floating type (in range [0, 1]), " + f"but found type {image.dtype} instead" + ) + dtype, device = image.dtype, image.device + mean = torch.as_tensor(self.image_mean, dtype=dtype, device=device) + std = torch.as_tensor(self.image_std, dtype=dtype, device=device) + return (image - mean[:, None, None]) / std[:, None, None] + + def torch_choice(self, k: List[int]) -> int: + """ + Implements `random.choice` via torch ops so it can be compiled with + TorchScript. Remove if https://github.com/pytorch/pytorch/issues/25803 + is fixed. + """ + index = int(torch.empty(1).uniform_(0., float(len(k))).item()) + return k[index] + + def resize(self, + image: Tensor, + target: Optional[Dict[str, Tensor]] = None, + ) -> Tuple[Tensor, Optional[Dict[str, Tensor]]]: + h, w = image.shape[-2:] + image, target = _resize_image_and_masks(image, target, self.image_size) + + if target is None: + return image, target + + bbox = target["boxes"] + bbox = resize_boxes(bbox, (h, w), image.shape[-2:]) + target["boxes"] = bbox + + return image, target + + def postprocess(self, + result: List[Dict[str, Tensor]], + image_shapes: List[Tuple[int, int]], + original_image_sizes: List[Tuple[int, int]] + ) -> List[Dict[str, Tensor]]: + if self.training: + return result + for i, (pred, im_s, o_im_s) in enumerate(zip(result, image_shapes, original_image_sizes)): + boxes = pred["boxes"] + boxes = resize_boxes(boxes, im_s, o_im_s) + result[i]["boxes"] = boxes + return result + + def __repr__(self) -> str: + format_string = self.__class__.__name__ + '(' + _indent = '\n ' + format_string += "{0}Normalize(mean={1}, std={2})".format(_indent, self.image_mean, self.image_std) + format_string += "{0}Resize(height={1}, width={2}, mode='bilinear')".format(_indent, self.image_size[0], + self.image_size[1]) + format_string += '\n)' + return format_string + +def resize_boxes(boxes: Tensor, original_size: List[int], new_size: List[int]) -> Tensor: + ratios = [ + torch.tensor(s, dtype=torch.float32, device=boxes.device) / + torch.tensor(s_orig, dtype=torch.float32, device=boxes.device) + for s, s_orig in zip(new_size, original_size) + ] + ratio_height, ratio_width = ratios + xmin, ymin, xmax, ymax = boxes.unbind(1) + + xmin = xmin * ratio_width + xmax = xmax * ratio_width + ymin = ymin * ratio_height + ymax = ymax * ratio_height + res = torch.stack((xmin, ymin, xmax, ymax), dim=1) + return res \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/model/utils.py b/tinygrad_repo/test/external/mlperf_retinanet/model/utils.py new file mode 100644 index 0000000000..33c64c16cb --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/model/utils.py @@ -0,0 +1,123 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/model/utils.py + +import torch + +class Matcher(object): + """ + This class assigns to each predicted "element" (e.g., a box) a ground-truth + element. Each predicted element will have exactly zero or one matches; each + ground-truth element may be assigned to zero or more predicted elements. + + Matching is based on the MxN match_quality_matrix, that characterizes how well + each (ground-truth, predicted)-pair match. For example, if the elements are + boxes, the matrix may contain box IoU overlap values. + + The matcher returns a tensor of size N containing the index of the ground-truth + element m that matches to prediction n. If there is no match, a negative value + is returned. + """ + + BELOW_LOW_THRESHOLD = -1 + BETWEEN_THRESHOLDS = -2 + + __annotations__ = { + 'BELOW_LOW_THRESHOLD': int, + 'BETWEEN_THRESHOLDS': int, + } + + def __init__(self, high_threshold, low_threshold, allow_low_quality_matches=False): + # type: (float, float, bool) -> None + """ + Args: + high_threshold (float): quality values greater than or equal to + this value are candidate matches. + low_threshold (float): a lower quality threshold used to stratify + matches into three levels: + 1) matches >= high_threshold + 2) BETWEEN_THRESHOLDS matches in [low_threshold, high_threshold) + 3) BELOW_LOW_THRESHOLD matches in [0, low_threshold) + allow_low_quality_matches (bool): if True, produce additional matches + for predictions that have only low-quality match candidates. See + set_low_quality_matches_ for more details. + """ + self.BELOW_LOW_THRESHOLD = -1 + self.BETWEEN_THRESHOLDS = -2 + assert low_threshold <= high_threshold + self.high_threshold = high_threshold + self.low_threshold = low_threshold + self.allow_low_quality_matches = allow_low_quality_matches + + def __call__(self, match_quality_matrix): + """ + Args: + match_quality_matrix (Tensor[float]): an MxN tensor, containing the + pairwise quality between M ground-truth elements and N predicted elements. + + Returns: + matches (Tensor[int64]): an N tensor where N[i] is a matched gt in + [0, M - 1] or a negative value indicating that prediction i could not + be matched. + """ + if match_quality_matrix.numel() == 0: + # empty targets or proposals not supported during training + if match_quality_matrix.shape[0] == 0: + raise ValueError( + "No ground-truth boxes available for one of the images " + "during training") + + raise ValueError( + "No proposal boxes available for one of the images " + "during training") + + # match_quality_matrix is M (gt) x N (predicted) + # Max over gt elements (dim 0) to find best gt candidate for each prediction + matched_vals, matches = match_quality_matrix.max(dim=0) + if self.allow_low_quality_matches: + all_matches = matches.clone() + else: + all_matches = None + + # Assign candidate matches with low quality to negative (unassigned) values + below_low_threshold = matched_vals < self.low_threshold + between_thresholds = (matched_vals >= self.low_threshold) & ( + matched_vals < self.high_threshold + ) + matches[below_low_threshold] = self.BELOW_LOW_THRESHOLD + matches[between_thresholds] = self.BETWEEN_THRESHOLDS + + if self.allow_low_quality_matches: + assert all_matches is not None + self.set_low_quality_matches_(matches, all_matches, match_quality_matrix) + + return matches + + def set_low_quality_matches_(self, matches, all_matches, match_quality_matrix): + """ + Produce additional matches for predictions that have only low-quality matches. + Specifically, for each ground-truth find the set of predictions that have + maximum overlap with it (including ties); for each prediction in that set, if + it is unmatched, then match it to the ground-truth with which it has the highest + quality value. + """ + # For each gt, find the prediction with which it has highest quality + highest_quality_foreach_gt, _ = match_quality_matrix.max(dim=1) + # Find highest quality match available, even if it is low, including ties + gt_pred_pairs_of_highest_quality = torch.where( + match_quality_matrix == highest_quality_foreach_gt[:, None] + ) + # Example gt_pred_pairs_of_highest_quality: + # tensor([[ 0, 39796], + # [ 1, 32055], + # [ 1, 32070], + # [ 2, 39190], + # [ 2, 40255], + # [ 3, 40390], + # [ 3, 41455], + # [ 4, 45470], + # [ 5, 45325], + # [ 5, 46390]]) + # Each row is a (gt index, prediction index) + # Note how gt items 1, 2, 3, and 5 each have two ties + + pred_inds_to_update = gt_pred_pairs_of_highest_quality[1] + matches[pred_inds_to_update] = all_matches[pred_inds_to_update] \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/openimages.py b/tinygrad_repo/test/external/mlperf_retinanet/openimages.py new file mode 100644 index 0000000000..d77c99d784 --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/openimages.py @@ -0,0 +1,25 @@ +from test.external.mlperf_retinanet.model.boxes import box_iou +from test.external.mlperf_retinanet.model.utils import Matcher + +import torch + +# This applies the filtering in https://github.com/mlcommons/training/blob/cdd928d4596c142c15a7d86b2eeadbac718c8da2/single_stage_detector/ssd/model/retinanet.py#L117 +# and https://github.com/mlcommons/training/blob/cdd928d4596c142c15a7d86b2eeadbac718c8da2/single_stage_detector/ssd/model/retinanet.py#L203 +# to match with tinygrad's dataloader implementation. +def postprocess_targets(targets, anchors): + proposal_matcher, matched_idxs = Matcher(0.5, 0.4, allow_low_quality_matches=True), [] + for anchors_per_image, targets_per_image in zip(anchors, targets): + if targets_per_image['boxes'].numel() == 0: + matched_idxs.append(torch.full((anchors_per_image.size(0),), -1, dtype=torch.int64, + device=anchors_per_image.device)) + continue + + match_quality_matrix = box_iou(targets_per_image['boxes'], anchors_per_image) + matched_idxs.append(proposal_matcher(match_quality_matrix)) + + for targets_per_image, matched_idxs_per_image in zip(targets, matched_idxs): + foreground_idxs_per_image = matched_idxs_per_image >= 0 + targets_per_image["boxes"] = targets_per_image["boxes"][matched_idxs_per_image[foreground_idxs_per_image]] + targets_per_image["labels"] = targets_per_image["labels"][matched_idxs_per_image[foreground_idxs_per_image]] + + return targets diff --git a/tinygrad_repo/test/external/mlperf_retinanet/presets.py b/tinygrad_repo/test/external/mlperf_retinanet/presets.py new file mode 100644 index 0000000000..fb918581b4 --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/presets.py @@ -0,0 +1,24 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/presets.py + +from test.external.mlperf_retinanet import transforms as T + +class DetectionPresetTrain: + def __init__(self, data_augmentation, hflip_prob=0.5, mean=(123., 117., 104.)): + if data_augmentation == 'hflip': + self.transforms = T.Compose([ + T.RandomHorizontalFlip(p=hflip_prob), + T.ToTensor(), + ]) + else: + raise ValueError(f'Unknown data augmentation policy "{data_augmentation}"') + + def __call__(self, img, target): + return self.transforms(img, target) + + +class DetectionPresetEval: + def __init__(self): + self.transforms = T.ToTensor() + + def __call__(self, img, target): + return self.transforms(img, target) \ No newline at end of file diff --git a/tinygrad_repo/test/external/mlperf_retinanet/transforms.py b/tinygrad_repo/test/external/mlperf_retinanet/transforms.py new file mode 100644 index 0000000000..0a35347d1c --- /dev/null +++ b/tinygrad_repo/test/external/mlperf_retinanet/transforms.py @@ -0,0 +1,77 @@ +# Copied from https://github.com/mlcommons/training/blob/637c82f9e699cd6caf108f92efb2c1d446b630e0/single_stage_detector/ssd/transforms.py + +import torch +import torchvision + +from torch import nn, Tensor +from torchvision.transforms import functional as F +from torchvision.transforms import transforms as T +from typing import List, Tuple, Dict, Optional + +from PIL import Image +Image.MAX_IMAGE_PIXELS = None +from typing import Any + +try: + import accimage +except ImportError: + accimage = None + +@torch.jit.unused +def _is_pil_image(img: Any) -> bool: + if accimage is not None: + return isinstance(img, (Image.Image, accimage.Image)) + else: + return isinstance(img, Image.Image) + +def get_image_size_tensor(img: Tensor) -> List[int]: + # Returns (w, h) of tensor image + torchvision.transforms._functional_tensor._assert_image_tensor(img) + return [img.shape[-1], img.shape[-2]] + +@torch.jit.unused +def get_image_size_pil(img: Any) -> List[int]: + if _is_pil_image(img): + return list(img.size) + raise TypeError("Unexpected type {}".format(type(img))) + +def get_image_size(img: Tensor) -> List[int]: + """Returns the size of an image as [width, height]. + Args: + img (PIL Image or Tensor): The image to be checked. + Returns: + List[int]: The image size. + """ + if isinstance(img, torch.Tensor): + return get_image_size_tensor(img) + + return get_image_size_pil(img) + +class Compose(object): + def __init__(self, transforms): + self.transforms = transforms + + def __call__(self, image, target): + for t in self.transforms: + image, target = t(image, target) + return image, target + + +class RandomHorizontalFlip(T.RandomHorizontalFlip): + def forward(self, image: Tensor, + target: Optional[Dict[str, Tensor]] = None) -> Tuple[Tensor, Optional[Dict[str, Tensor]]]: + if torch.rand(1) < self.p: + image = F.hflip(image) + if target is not None: + width, _ = get_image_size(image) + target["boxes"][:, [0, 2]] = width - target["boxes"][:, [2, 0]] + if "masks" in target: + target["masks"] = target["masks"].flip(-1) + return image, target + + +class ToTensor(nn.Module): + def forward(self, image: Tensor, + target: Optional[Dict[str, Tensor]] = None) -> Tuple[Tensor, Optional[Dict[str, Tensor]]]: + image = F.to_tensor(image) + return image, target \ No newline at end of file diff --git a/tinygrad_repo/test/external/process_replay/README.md b/tinygrad_repo/test/external/process_replay/README.md index 67eb70762d..acb3fa545e 100644 --- a/tinygrad_repo/test/external/process_replay/README.md +++ b/tinygrad_repo/test/external/process_replay/README.md @@ -12,6 +12,8 @@ To run process replay locally: (optional: clear previous process replay runs with `test/external/process_replay/reset.py`) -1. Run tests with `RUN_PROCESS_REPLAY=1` in your branch. This will capture the kernels. +1. Run tests with `CAPTURE_PROCESS_REPLAY=1` in your branch. This will pickle process inputs to CACHEDB. 2. Checkout master 3. Run `test/external/process_replay/process_replay.py` + +For reference, see `test/external/process_replay/local.sh`. diff --git a/tinygrad_repo/test/external/process_replay/helpers.py b/tinygrad_repo/test/external/process_replay/helpers.py deleted file mode 100644 index 8b9db50494..0000000000 --- a/tinygrad_repo/test/external/process_replay/helpers.py +++ /dev/null @@ -1,17 +0,0 @@ -from dataclasses import dataclass -import traceback, subprocess -from typing import Dict, Optional, Tuple -from tinygrad.helpers import ContextVar, getenv - -@dataclass(frozen=True) -class ProcessReplayContext: - loc: str - head_sha: str - run_id: Optional[int] -def get_process_replay_ctx() -> Tuple[ProcessReplayContext, Dict]: - stack = filter(lambda x: "tinygrad" in x.filename and not any(n in x.filename for n in ["engine/schedule.py", "engine/realize.py", \ - "codegen/kernel.py", "unittest"]), traceback.extract_stack()[:-1]) - loc = "\n".join(traceback.format_list(stack)) - try: head_sha = subprocess.check_output(["git", "rev-parse", "HEAD"]).strip().decode() - except Exception: head_sha = "" - return ProcessReplayContext(loc, head_sha, getenv("GITHUB_RUN_ID") or None), {k:v.value for k,v in ContextVar._cache.items()} diff --git a/tinygrad_repo/test/external/process_replay/local.sh b/tinygrad_repo/test/external/process_replay/local.sh new file mode 100755 index 0000000000..c13e220c83 --- /dev/null +++ b/tinygrad_repo/test/external/process_replay/local.sh @@ -0,0 +1,9 @@ +#!/bin/bash + +HEAD=$(git rev-parse --abbrev-ref HEAD) +python test/external/process_replay/reset.py +CAPTURE_PROCESS_REPLAY=1 python test/test_ops.py TestOps.test_add +git checkout master +git checkout $HEAD -- test/external/process_replay/process_replay.py +ASSERT_PROCESS_REPLAY=1 python test/external/process_replay/process_replay.py +git checkout $HEAD diff --git a/tinygrad_repo/test/external/process_replay/process_replay.py b/tinygrad_repo/test/external/process_replay/process_replay.py index e76945148f..81609d0b65 100755 --- a/tinygrad_repo/test/external/process_replay/process_replay.py +++ b/tinygrad_repo/test/external/process_replay/process_replay.py @@ -1,14 +1,12 @@ #!/usr/bin/env python3 # compare kernels created by HEAD against master -from collections import defaultdict -import os, multiprocessing, logging, pickle, sqlite3, difflib, functools, warnings -from typing import Callable, List, Set, Tuple, Union, cast +import os, multiprocessing, logging, pickle, sqlite3, difflib, functools, warnings, itertools +from typing import Callable, cast from tinygrad.helpers import VERSION, Context, ContextVar, colored, db_connection, getenv, tqdm -from tinygrad.engine.schedule import ScheduleContext, schedule_uop +from tinygrad.engine.grouper import get_becomes_map from tinygrad.codegen.kernel import Kernel, Opt from tinygrad.renderer import Renderer -from tinygrad.ops import UOp -from test.helpers import print_diff +from tinygrad.uop.ops import UOp, Ops # *** process replay settings @@ -17,9 +15,13 @@ PAGE_SIZE = getenv("PAGE_SIZE", 100) REF = os.getenv("GITHUB_REF_NAME", "") MAX_DIFF_PCT = getenv("PROCESS_REPLAY_MAX_DIFF_PCT", 20) TABLE_NAME = f"process_replay_{VERSION}" -os.environ["RUN_PROCESS_REPLAY"] = "0" +os.environ["CAPTURE_PROCESS_REPLAY"] = "0" early_stop = multiprocessing.Event() logging.basicConfig(level=logging.INFO, format="%(message)s") +MAX_LINES = 500 +def trunc_log(x): + if len(lines:=repr(x).splitlines()) > MAX_LINES: lines = lines[:MAX_LINES]+[f"WARN: truncated string with {len(lines)} lines"] + logging.info("\n".join(lines)) # user config ASSERT_DIFF = int((flag:="[pr]") in os.getenv("COMMIT_MESSAGE", flag) or flag in os.getenv("PR_TITLE", flag)) @@ -30,23 +32,27 @@ class ProcessReplayWarning(Warning): pass # *** recreators -def recreate_sched(ast:UOp, assigns:Set[UOp]) -> UOp: - # NOTE: process replay isn't meant to actually schedule anything - return schedule_uop(ast, ScheduleContext(assigns=assigns, tensor_uops=defaultdict(list))).ast -def recreate_kernel(ast:UOp, opts:Renderer, applied_opts:List[Opt], name:str, _) -> str: +def recreate_sched(big_sink:UOp) -> list[UOp]: + UOp.unique_num = itertools.count(max([u.arg for u in big_sink.toposort() if u.op is Ops.UNIQUE], default=0)+1) + becomes_map = get_becomes_map(big_sink) + sched_sink = big_sink.substitute(becomes_map) + return [u.arg.ast for u in sched_sink.toposort() if u.op is Ops.KERNEL] + +def recreate_kernel(ast:UOp, opts:Renderer, applied_opts:list[Opt], name:str, _) -> str: k = Kernel(ast, opts=opts) for opt in applied_opts: k.apply_opt(opt) # NOTE: replay with the captured renderer, not the one in master - return k.opts.render(name, cast(List,k.to_program().uops)) + return k.opts.render(cast(list,k.to_program(name).uops)) # *** diff a "good" recreation against the generated version -def diff(offset:int, name:str, fxn:Callable) -> Union[Tuple[int, int], bool]: - if early_stop.is_set(): return True +def diff(offset:int, name:str, fxn:Callable) -> None: + if ASSERT_DIFF: warnings.filterwarnings("error", category=ProcessReplayWarning) + if early_stop.is_set(): return None conn = db_connection() cur = conn.cursor() cur.execute(f"SELECT val FROM '{name}_{TABLE_NAME}' LIMIT ? OFFSET ?", (PAGE_SIZE, offset)) - additions, deletions, changed = 0, 0, 0 + changed = 0 for row in cur.fetchall(): if changed > MAX_DIFF_PCT: warnings.warn(f"detected changes in over {MAX_DIFF_PCT}% of {name}s. skipping further diff generation.") @@ -60,27 +66,26 @@ def diff(offset:int, name:str, fxn:Callable) -> Union[Tuple[int, int], bool]: continue # try recreate try: - with Context(**{k:v for k,v in args[-2].items() if k in ContextVar._cache and k != "DEBUG"}): good = fxn(*args[:-2]) + ctx_vars = {k:v.value for k,v in args[-2].items() if k != "DEBUG" and (var:=ContextVar._cache.get(k)) is not None and var.value != v.value} + with Context(**ctx_vars): good = fxn(*args[:-2]) if good is None: continue except Exception as e: changed += 1 + if ctx_vars: logging.info(ctx_vars) + for x in args[:-2]: trunc_log(x) warnings.warn(f"FAILED TO RECREATE KERNEL {e}", ProcessReplayWarning) - for x in args[:-1]: logging.info(x) continue # diff kernels - try: assert args[-1] == good + try: assert str(args[-1]) == str(good) except AssertionError: changed += 1 - logging.info("PROCESS REPLAY DETECTED CHANGE") - for x in args[:-1]: logging.info(x) - print_diff(good, args[-1]) + if ctx_vars: logging.info(ctx_vars) + for x in args[:-2]: trunc_log(x) changes = list(difflib.unified_diff(str(good).splitlines(), str(args[-1]).splitlines())) - additions += len([x for x in changes if x.startswith("+")]) - deletions += len([x for x in changes if x.startswith("-")]) - if ASSERT_DIFF: return additions, deletions + logging.info("\n".join(colored(line, "red" if line.startswith("-") else "green" if line.startswith("+") else None) for line in changes)) + warnings.warn("PROCESS REPLAY DETECTED CHANGE", ProcessReplayWarning) conn.commit() cur.close() - return additions, deletions # *** generic runner for executing fxn across all rows of a table in parallel @@ -95,16 +100,10 @@ def _pmap(name:str, fxn:Callable, maxtasksperchild:int=16) -> None: cur.close() with multiprocessing.get_context("spawn").Pool(multiprocessing.cpu_count(), maxtasksperchild=maxtasksperchild) as pool: inputs = list(range(0, row_count, PAGE_SIZE)) - ret: List[Union[bool, Tuple[int, int]]] = list(tqdm(pool.imap_unordered(functools.partial(diff, name=name, fxn=fxn), inputs), total=len(inputs))) + list(tqdm(pool.imap_unordered(functools.partial(diff, name=name, fxn=fxn), inputs), total=len(inputs))) pool.close() pool.join() pool.terminate() - changed = [bool(x[0] or x[1]) if isinstance(x, tuple) else x for x in ret] - insertion, deletions = [x[0] for x in ret if isinstance(x, tuple)], [x[1] for x in ret if isinstance(x, tuple)] - logging.info(f"{sum(changed)} kernels changed") - if sum(insertion) != 0: logging.info(colored(f"{sum(insertion)} insertions(+)", "green")) - if sum(deletions) != 0: logging.info(colored(f"{sum(deletions)} deletions(-)", "red")) - if any(changed): warnings.warn("process replay detected changes", ProcessReplayWarning) # *** main loop @@ -113,10 +112,11 @@ if __name__ == "__main__": logging.info("skipping process replay.") exit(0) - if ASSERT_DIFF: warnings.filterwarnings("error", category=ProcessReplayWarning) + print(f"running process replay with {ASSERT_DIFF=}") for name,fxn in [("schedule", recreate_sched), ("kernel", recreate_kernel)]: logging.info(f"***** {name} diff") try: _pmap(name, fxn) + except ProcessReplayWarning: exit(1) except Exception as e: if ASSERT_DIFF: raise e logging.error(f"{name} diff err {e}") diff --git a/tinygrad_repo/test/external/speed_beam_v_hcopt.py b/tinygrad_repo/test/external/speed_beam_v_hcopt.py index 447a891ea7..1bd107f6d7 100644 --- a/tinygrad_repo/test/external/speed_beam_v_hcopt.py +++ b/tinygrad_repo/test/external/speed_beam_v_hcopt.py @@ -1,7 +1,8 @@ from tinygrad import Device from tinygrad.helpers import getenv, DEBUG, BEAM -from tinygrad.engine.search import beam_search, time_linearizer, bufs_from_lin -from extra.optimization.helpers import load_worlds, ast_str_to_lin +from tinygrad.engine.search import beam_search, bufs_from_lin +from tinygrad.codegen.heuristic import hand_coded_optimizations +from extra.optimization.helpers import load_worlds, ast_str_to_lin, time_linearizer if __name__ == "__main__": filter_reduce = bool(getenv("FILTER_REDUCE")) @@ -18,18 +19,16 @@ if __name__ == "__main__": def new_lin(): return ast_str_to_lin(ast, opts=dev.renderer) k = new_lin() - # k.required_optimizations() - if not (used_tensor_cores:=k.apply_tensor_cores(getenv("TC", 1))): k.hand_coded_optimizations() + if not (used_tensor_cores:=k.apply_tensor_cores(getenv("TC", 1))): k.apply_opts(hand_coded_optimizations(k)) assert BEAM > 0 lins = [(("tc" if used_tensor_cores else "hc"), k)] if used_tensor_cores: lins.append(("hc", new_lin())) - lins[-1][1].hand_coded_optimizations() + lins[-1][1].apply_opts(hand_coded_optimizations(lins[-1][1])) kb = new_lin() - # kb.required_optimizations() test_rawbuffers = bufs_from_lin(kb) # allocate scratch buffers for optimization lins.append((f"beam{BEAM.value}", beam_search(kb, test_rawbuffers, BEAM.value, bool(getenv("BEAM_ESTIMATE", 1))))) timed = sorted([(nm, tk, time_linearizer(tk, test_rawbuffers, allow_test_size=False, clear_l2=True)) for nm, tk in lins], key=lambda x: x[2]) diff --git a/tinygrad_repo/test/external/speed_compare_amd_am.py b/tinygrad_repo/test/external/speed_compare_amd_am.py new file mode 100644 index 0000000000..760833d48c --- /dev/null +++ b/tinygrad_repo/test/external/speed_compare_amd_am.py @@ -0,0 +1,157 @@ +from tinygrad import Device, dtypes +from tinygrad.helpers import getenv, colorize_float, DEBUG +from extra.optimization.helpers import load_worlds, ast_str_to_lin +from test.external.fuzz_linearizer import get_fuzz_rawbufs +from tinygrad.codegen.heuristic import hand_coded_optimizations +from tinygrad.engine.search import bufs_from_lin +from tinygrad.engine.realize import CompiledRunner +from tinygrad.tensor import _to_np_dtype +from tinygrad.runtime.ops_amd import AMDDevice +from contextlib import contextmanager +import numpy as np +import os, random, statistics + +am_signal_pages, am_signal_pool, am_devices = [], [], [] +amd_signal_pages, amd_signal_pool, amd_devices = [], [], [] + +def rebind_vfio(pcibus="0000:44:00.0"): + print("rebind ", pcibus) + os.system("sudo rmmod amdgpu") + os.system("sudo modprobe vfio-pci") + + base = f"/sys/bus/pci/devices/{pcibus}" + if os.path.exists(f"{base}/driver"): + with open(f"{base}/driver/unbind", "w") as f: f.write(pcibus) + with open(f"{base}/driver_override", "w") as f: f.write("vfio-pci") + with open("/sys/bus/pci/drivers_probe", "w") as f: f.write(pcibus) + + os.system("sudo modprobe amdgpu") + os.system("rocm-smi --setprofile compute") + os.system("rocm-smi --setperflevel high") + +@contextmanager +def run_amd(): + global amd_signal_pages, amd_signal_pool, amd_devices + AMDDevice.driverless = False + AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices = amd_signal_pages, amd_signal_pool, amd_devices + yield + amd_signal_pages, amd_signal_pool, amd_devices = AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices + AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices = [], [], [] + +@contextmanager +def run_am(): + global am_signal_pages, am_signal_pool, am_devices + AMDDevice.driverless = True + AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices = am_signal_pages, am_signal_pool, am_devices + yield + am_signal_pages, am_signal_pool, am_devices = AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices + AMDDevice.signal_pages, AMDDevice.signal_pool, AMDDevice.devices = [], [], [] + +if __name__ == "__main__": + CHECK_CPU = getenv("CHECK_CPU", 0) + SEED = getenv("SEED", 42) + CNT = getenv("CNT", 7) + random.seed(SEED) + np.random.seed(SEED) + + # TODO: NUM=780 is super slow + # NUM=1907 is broken on AMD and AM have some mismatches (0 vs 1) + # kfd feels so bad when taking gpu out while it's running... Need hacks to rebind it before running. + rebind_vfio(pcibus="0000:44:00.0") + + ast_strs = load_worlds(filter_reduce=False, filter_novariable=True) + + with run_am(): + amdev = Device["AMD:1"] + + with run_amd(): + amddev = Device["AMD"] + + if CHECK_CPU: cpudev = Device["CPU"] + + single = getenv("NUM", -1) + if single != -1: ast_strs = ast_strs[single:single+1] + + average_tm_amd, average_tm_am = 0, 0 + for num,ast in enumerate(ast_strs): + with run_amd(): + amdlin = ast_str_to_lin(ast, opts=amddev.renderer) + amdlin.apply_opts(hand_coded_optimizations(amdlin)) + has_bf16 = any(b.dtype == dtypes.bfloat16 for b in amdlin.membufs) + + amd_prg = CompiledRunner(amdlin.to_program()) + amdbufs = bufs_from_lin(amdlin) + test_amdbufs = get_fuzz_rawbufs(amdlin) if not has_bf16 else amdbufs + if not has_bf16: contents = [buf.as_buffer() for buf in test_amdbufs] + + with run_am(): + rdr = amdev.renderer + rdr.device = "AMD:1" + amlin = ast_str_to_lin(ast, opts=amdev.renderer) + amlin.apply_opts(hand_coded_optimizations(amlin)) + am_prg = CompiledRunner(amlin.to_program()) + ambufs = bufs_from_lin(amlin) + test_ambufs = get_fuzz_rawbufs(amlin) if not has_bf16 else ambufs + if not has_bf16: + for i,rawbuf in enumerate(test_ambufs): rawbuf.copyin(contents[i]) + + if CHECK_CPU: + cpu_rdr = cpudev.renderer + cpu_rdr.device = "CPU" + cpulin = ast_str_to_lin(ast, opts=cpu_rdr) + cpulin.apply_opts(hand_coded_optimizations(cpulin)) + cpu_prg = CompiledRunner(cpulin.to_program()) + cpubufs = bufs_from_lin(cpulin) + test_cpubufs = get_fuzz_rawbufs(cpulin) if not has_bf16 else ambufs + if not has_bf16: + for i,rawbuf in enumerate(test_cpubufs): rawbuf.copyin(contents[i]) + + # warmup + tm_amd, tm_am, failed = [], [], False + with run_amd(): + try: + amd_prg(test_amdbufs, {}, wait=True) + for i in range(CNT): tm_amd.append(amd_prg(amdbufs, {}, wait=True)) + except RuntimeError: + print("AMD FAILED") + tm_amd = [1e9] + failed = True + + with run_am(): + try: + am_prg(test_ambufs, {}, wait=True) + for i in range(CNT): tm_am.append(am_prg(ambufs, {}, wait=True)) + except RuntimeError: + print("AM FAILED") + tm_am = [1e9] + failed = True + + if CHECK_CPU: + cpu_prg(test_cpubufs, {}, wait=True) + for i in range(1): cpu_prg(cpubufs, {}, wait=True) + + if not failed and not has_bf16: + with run_amd(): + curesult = np.frombuffer(test_amdbufs[0].as_buffer(), _to_np_dtype(test_amdbufs[0].dtype)) + + with run_am(): + amresult = np.frombuffer(test_ambufs[0].as_buffer(), _to_np_dtype(test_ambufs[0].dtype)) + + if CHECK_CPU: + cpuresult = np.frombuffer(test_cpubufs[0].as_buffer(), _to_np_dtype(test_cpubufs[0].dtype)) + np.testing.assert_allclose(amresult, cpuresult, rtol=1e-2, atol=1e-2) + np.testing.assert_allclose(curesult, cpuresult, rtol=1e-2, atol=1e-2) + + try: + np.testing.assert_allclose(curesult, amresult, rtol=1e-2, atol=1e-2) + except AssertionError as e: + print("AM and AMD results do not match") + print(e) + + bam = statistics.median(tm_am) + bamd = statistics.median(tm_amd) + average_tm_amd += bamd + average_tm_am += bam + ratio = bam/bamd + print(f"{average_tm_am/average_tm_amd:5.2f}x -- {num:4d} {colorize_float(ratio)} {bam*1e6:7.2f} vs {bamd*1e6:7.2f} us", amlin.name) + if DEBUG > 3 and ratio > 1.04: print(f"AM slower {ratio}", amlin.ast, amlin.applied_opts) diff --git a/tinygrad_repo/test/external/speed_compare_cuda_nv.py b/tinygrad_repo/test/external/speed_compare_cuda_nv.py index 85773b93dc..3ce1a74a31 100644 --- a/tinygrad_repo/test/external/speed_compare_cuda_nv.py +++ b/tinygrad_repo/test/external/speed_compare_cuda_nv.py @@ -2,6 +2,7 @@ from tinygrad import Device, dtypes from tinygrad.helpers import getenv, colorize_float from extra.optimization.helpers import load_worlds, ast_str_to_lin from test.external.fuzz_linearizer import get_fuzz_rawbufs +from tinygrad.codegen.heuristic import hand_coded_optimizations from tinygrad.engine.search import bufs_from_lin from tinygrad.engine.realize import CompiledRunner from tinygrad.tensor import _to_np_dtype @@ -21,7 +22,7 @@ if __name__ == "__main__": for num,ast in enumerate(ast_strs): # cuda compile culin = ast_str_to_lin(ast, opts=cudev.renderer) - culin.hand_coded_optimizations() + culin.apply_opts(hand_coded_optimizations(culin)) has_bf16 = any(b.dtype == dtypes.bfloat16 for b in culin.membufs) cuda_prg = CompiledRunner(culin.to_program()) @@ -31,7 +32,7 @@ if __name__ == "__main__": rdr = nvdev.renderer rdr.device = "NV" nvlin = ast_str_to_lin(ast, opts=rdr) - nvlin.hand_coded_optimizations() + nvlin.apply_opts(hand_coded_optimizations(nvlin)) nv_prg = CompiledRunner(nvlin.to_program()) nvbufs = bufs_from_lin(nvlin) test_nvbufs = get_fuzz_rawbufs(nvlin) if not has_bf16 else nvbufs diff --git a/tinygrad_repo/test/external/speed_compare_cuda_ptx.py b/tinygrad_repo/test/external/speed_compare_cuda_ptx.py index a4a3b8b095..32b586a1d5 100644 --- a/tinygrad_repo/test/external/speed_compare_cuda_ptx.py +++ b/tinygrad_repo/test/external/speed_compare_cuda_ptx.py @@ -1,6 +1,7 @@ import itertools from tinygrad import Device from tinygrad.engine.realize import CompiledRunner +from tinygrad.codegen.heuristic import hand_coded_optimizations from tinygrad.helpers import getenv, colorize_float from extra.optimization.helpers import load_worlds, ast_str_to_lin from tinygrad.engine.search import bufs_from_lin @@ -23,7 +24,7 @@ if __name__ == "__main__": # cuda compile dev.compiler = CUDACompiler(dev.arch) lin = ast_str_to_lin(ast, opts=dev.renderer) - lin.hand_coded_optimizations() + lin.apply_opts(hand_coded_optimizations(lin)) cuda_prg = CompiledRunner(lin.to_program()) bufs = bufs_from_lin(lin) @@ -31,7 +32,7 @@ if __name__ == "__main__": # ptx compile dev.compiler = PTXCompiler(dev.arch) lin = ast_str_to_lin(ast, opts=ptx) - lin.hand_coded_optimizations() + lin.apply_opts(hand_coded_optimizations(lin)) lin.linearize() ptx_prg = CompiledRunner(lin.to_program()) diff --git a/tinygrad_repo/test/external/speed_v_theoretical.py b/tinygrad_repo/test/external/speed_v_theoretical.py index 2729362123..d02f87fa28 100644 --- a/tinygrad_repo/test/external/speed_v_theoretical.py +++ b/tinygrad_repo/test/external/speed_v_theoretical.py @@ -46,7 +46,7 @@ class TestKernelSpeed(unittest.TestCase): b = self._get_tensor(K, N) if i >= 3: GlobalCounters.time_sum_s = 0 - with Context(DEBUG=max(DEBUG, 2)): c = f(a, b) + with Context(DEBUG=max(DEBUG.value, 2)): c = f(a, b) tms.append(GlobalCounters.time_sum_s) else: c = f(a, b) @@ -90,12 +90,12 @@ class TestKernelSpeed(unittest.TestCase): def test_conv_3x3_256_32_32_256_256(self): self._test_conv_3x3(256, 32, 32, 256, 256, nv_tflops=27, amd_tflops=20) # theoretical is nv_tflops=165, amd_tflops=123 - def test_gemm_4096(self): self._test_matmul(4096, nv_tflops=115, amd_tflops=80) - def test_gemm_8192(self): self._test_matmul(8192, nv_tflops=130, amd_tflops=75) + def test_gemm_4096(self): self._test_matmul(4096, nv_tflops=115, amd_tflops=65) + def test_gemm_8192(self): self._test_matmul(8192, nv_tflops=125, amd_tflops=65) # theoretical is nv_gbs=1008, amd_gbs=960 def test_gemv_16384_4096(self): self._test_matmul(16384, 4096, 1, nv_gbs=840, amd_gbs=750) - def test_gemv_4096_16384(self): self._test_matmul(4096, 16384, 1, nv_gbs=830, amd_gbs=760) + def test_gemv_4096_16384(self): self._test_matmul(4096, 16384, 1, nv_gbs=830, amd_gbs=750) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/external/verify_kernel.py b/tinygrad_repo/test/external/verify_kernel.py index e8c99e7415..55ebb6849b 100644 --- a/tinygrad_repo/test/external/verify_kernel.py +++ b/tinygrad_repo/test/external/verify_kernel.py @@ -1,10 +1,9 @@ import argparse from collections import defaultdict -from extra.optimization.helpers import kern_str_to_lin +from extra.optimization.helpers import kern_str_to_lin, time_linearizer from test.external.fuzz_linearizer import compare_linearizer from tinygrad.helpers import colored from tinygrad.codegen.kernel import Kernel -from tinygrad.engine.search import time_linearizer # Use this with the LOGKERNS options to verify that all executed kernels are valid and evaluate to the same ground truth results @@ -37,8 +36,7 @@ if __name__ == "__main__": with open(args.pkl, 'rb') as file: (ast, applied_opts,) = pickle.load(file) lin = Kernel(ast) - for opt in applied_opts: - lin.apply_opt(opt) + lin.apply_opts(applied_opts) test_lins = [lin] else: @@ -53,7 +51,6 @@ if __name__ == "__main__": print(test_lin.ast) print(test_lin.applied_opts) unoptimized_lin = Kernel(test_lin.ast) - unoptimized_lin.required_optimizations() print(f"{unoptimized_lin.colored_shape()} -> {test_lin.colored_shape()}") (msg,rb,vv,gt) = compare_linearizer(test_lin, None, None, None, rtol=args.rtol, atol=args.atol) if msg != "PASS": diff --git a/tinygrad_repo/test/helpers.py b/tinygrad_repo/test/helpers.py index ffbb8453a4..9a34198a42 100644 --- a/tinygrad_repo/test/helpers.py +++ b/tinygrad_repo/test/helpers.py @@ -1,21 +1,20 @@ -import time, logging, difflib -from typing import Callable, Optional, Tuple +import time, struct +from typing import Any, Callable, Optional import numpy as np -from tinygrad import Tensor, dtypes -from tinygrad.ops import UOp, Ops, sint +from tinygrad import Tensor, dtypes, Device +from tinygrad.uop.ops import UOp, Ops, sint from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.tensor import _to_np_dtype from tinygrad.engine.realize import Runner from tinygrad.dtype import ConstType, DType from tinygrad.nn.state import get_parameters -from tinygrad.helpers import T, getenv, colored -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.codegen.uopgraph import full_graph_rewrite -from tinygrad.runtime.ops_python import PythonProgram, PythonRenderer, PythonCompiler, PythonAllocator +from tinygrad.helpers import T, unwrap, CI +from tinygrad.codegen import full_rewrite +from tinygrad.runtime.ops_python import PythonProgram, PythonRenderer, PythonCompiler def derandomize_model(model): for p in get_parameters(model): - p.lazydata = Tensor.empty(p.shape, device=p.device, dtype=p.dtype).lazydata + p.replace(Tensor.empty(p.shape, device=p.device, dtype=p.dtype)) p.realize() def assert_jit_cache_len(fxn, expected_len): @@ -40,30 +39,33 @@ def rand_for_dtype(dt:DType, size:int): return np.random.choice([True, False], size=size) return np.random.uniform(-10, 10, size=size).astype(_to_np_dtype(dt)) -def print_diff(s0, s1, unified=getenv("UNIFIED_DIFF",1)): - if not logging.getLogger().hasHandlers(): logging.basicConfig(level=logging.INFO, format="%(message)s") - if unified: - lines = list(difflib.unified_diff(str(s0).splitlines(), str(s1).splitlines())) - diff = "\n".join(colored(line, "red" if line.startswith("-") else "green" if line.startswith("+") else None) for line in lines) - else: - import ocdiff - diff = ocdiff.console_diff(str(s0), str(s1)) - logging.info(diff) - -def ast_const(dtype:DType, val:ConstType, shape:Tuple[sint, ...]=(), st:Optional[ShapeTracker]=None, st_src:Optional[Tuple[UOp]]=None) -> UOp: +def ast_const(dtype:DType, val:ConstType, shape:tuple[sint, ...]=(), st:Optional[ShapeTracker]=None, st_src:Optional[tuple[UOp]]=None) -> UOp: if st_src is None: st_src = (st.to_uop() if st is not None else ShapeTracker.from_shape(()).reshape((1,)*len(shape)).expand(shape).to_uop(),) - return UOp(Ops.VALID, dtypes.bool, st_src).where(UOp.const(dtype, val), UOp.const(dtype, 0)) + st = unwrap(st_src[0].st) + if all(v.mask is None for v in st.views): return UOp.const(dtype, val).replace(src=(st.to_uop(),)) + return UOp.const(dtype, val).valid(st) -def timeit(fxn:Callable[..., T], *args, **kwargs) -> Tuple[T, float]: +def timeit(fxn:Callable[..., T], *args, **kwargs) -> tuple[T, float]: st = time.perf_counter_ns() ret = fxn(*args, **kwargs) return ret, (time.perf_counter_ns()-st)*1e-6 -def eval_uop(uop:UOp): +def eval_uop(uop:UOp, inputs:list[tuple[DType, list[Any]]]|None=None): + allocator = Device['PYTHON'].allocator + bufs = [] + for buf_dt, data in inputs or []: + bufs.append(buf:=allocator.alloc(len(data) * buf_dt.itemsize)) + allocator._copyin(buf, memoryview(struct.pack(str(len(data)) + buf_dt.fmt, *data))) g = UOp(Ops.DEFINE_GLOBAL, uop.dtype.ptr(), arg=0, src=()) - rw = full_graph_rewrite(UOp.store(g.index(UOp.const(dtypes.int, 0)), uop).sink(), PythonRenderer) - prog = PythonProgram("run", PythonCompiler().compile(PythonRenderer().render("run", linearize_uop(rw)))) - buf = PythonAllocator().alloc(uop.dtype.itemsize) - prog(buf) - return buf.cast(uop.dtype.fmt).tolist()[0] + lst = full_rewrite(UOp.store(g.index(UOp.const(dtypes.int, 0)), uop).sink(), PythonRenderer) + prog = PythonProgram("run", PythonCompiler().compile(PythonRenderer().render(lst))) + prog(out_buf:=allocator.alloc(uop.dtype.itemsize), *bufs) + return out_buf.cast(uop.dtype.fmt).tolist()[0] + +def not_support_multi_device(): + # GPU and CUDA don't support multi device if in CI + return CI and REAL_DEV in ("GPU", "CUDA") + +# NOTE: This will open REMOTE if it's the default device +REAL_DEV = (Device.DEFAULT if Device.DEFAULT != "REMOTE" else Device['REMOTE'].properties.real_device) diff --git a/tinygrad_repo/test/imported/test_indexing.py b/tinygrad_repo/test/imported/test_indexing.py index 2d433634a2..271aeb586b 100644 --- a/tinygrad_repo/test/imported/test_indexing.py +++ b/tinygrad_repo/test/imported/test_indexing.py @@ -1,6 +1,6 @@ # test cases are modified from pytorch test_indexing.py https://github.com/pytorch/pytorch/blob/597d3fb86a2f3b8d6d8ee067e769624dcca31cdb/test/test_indexing.py -import unittest, random, copy, warnings +import unittest, random, warnings import numpy as np from tinygrad import Tensor, dtypes, Device, TinyJit @@ -21,14 +21,15 @@ def consec(shape, start=1): # creates strided tensor with base set to reference tensor's base, equivalent to torch.set_() def set_(reference: Tensor, shape, strides, offset): + raise NotImplementedError("need to implement without calling lazydata.view") if reference.lazydata.base.realized is None: reference.realize() assert reference.lazydata.base.realized, "base has to be realized before setting it to strided's base" strided = Tensor(reference.lazydata.view(ShapeTracker((View.create(shape=shape, strides=strides, offset=offset),)))) assert strided.lazydata.st.real_strides() == strides, "real_strides should equal strides for strided" return strided -def clone(original:Tensor): return copy.copy(original) -def copy_(src:Tensor, other:Tensor) -> Tensor: return copy.copy(src) +def clone(original:Tensor): return original.clone() +def copy_(src:Tensor, other:Tensor) -> Tensor: return src.clone() # this is fine for tested usecases since as geohotstan understands, # data_ptr is used to compare if operations needed between tensors is the same def data_ptr(tensor:Tensor): return tensor.lazydata @@ -180,7 +181,7 @@ class TestIndexing(unittest.TestCase): # self.assertRaises(TypeError, delitem) # TODO: LLVM is quite fast, why are other compiled backends slow? - @unittest.skipIf(CI and Device.DEFAULT in ["CLANG", "GPU", "METAL", "NV", "AMD"], "slow") + @unittest.skipIf(CI and Device.DEFAULT in ["CPU", "GPU", "METAL", "NV", "AMD"], "slow") def test_advancedindex(self): # integer array indexing @@ -220,28 +221,29 @@ class TestIndexing(unittest.TestCase): # Tensor with stride != 1 # strided is [1, 3, 5, 7] - reference = consec((10,)) - strided = set_(reference, (4,), (2,), 0) + # # TODO: set stride + # reference = consec((10,)) + # strided = set_(reference, (4,), (2,), 0) - numpy_testing_assert_equal_helper(strided[[0]], np.array([1])) - numpy_testing_assert_equal_helper(strided[ri([0]), ], np.array([1])) - numpy_testing_assert_equal_helper(strided[ri([3]), ], np.array([7])) - numpy_testing_assert_equal_helper(strided[[1, 2]], np.array([3, 5])) - numpy_testing_assert_equal_helper(strided[ri([1, 2]), ], np.array([3, 5])) - numpy_testing_assert_equal_helper(strided[ri([[2, 1], [0, 3]]), ], - np.array([[5, 3], [1, 7]])) + # numpy_testing_assert_equal_helper(strided[[0]], np.array([1])) + # numpy_testing_assert_equal_helper(strided[ri([0]), ], np.array([1])) + # numpy_testing_assert_equal_helper(strided[ri([3]), ], np.array([7])) + # numpy_testing_assert_equal_helper(strided[[1, 2]], np.array([3, 5])) + # numpy_testing_assert_equal_helper(strided[ri([1, 2]), ], np.array([3, 5])) + # numpy_testing_assert_equal_helper(strided[ri([[2, 1], [0, 3]]), ], + # np.array([[5, 3], [1, 7]])) # stride is [4, 8] - strided = set_(reference, (2,), (4,), offset=4) + # strided = set_(reference, (2,), (4,), offset=4) - numpy_testing_assert_equal_helper(strided[[0]], np.array([5])) - numpy_testing_assert_equal_helper(strided[ri([0]), ], np.array([5])) - numpy_testing_assert_equal_helper(strided[ri([1]), ], np.array([9])) - numpy_testing_assert_equal_helper(strided[[0, 1]], np.array([5, 9])) - numpy_testing_assert_equal_helper(strided[ri([0, 1]), ], np.array([5, 9])) - numpy_testing_assert_equal_helper(strided[ri([[0, 1], [1, 0]]), ], - np.array([[5, 9], [9, 5]])) + # numpy_testing_assert_equal_helper(strided[[0]], np.array([5])) + # numpy_testing_assert_equal_helper(strided[ri([0]), ], np.array([5])) + # numpy_testing_assert_equal_helper(strided[ri([1]), ], np.array([9])) + # numpy_testing_assert_equal_helper(strided[[0, 1]], np.array([5, 9])) + # numpy_testing_assert_equal_helper(strided[ri([0, 1]), ], np.array([5, 9])) + # numpy_testing_assert_equal_helper(strided[ri([[0, 1], [1, 0]]), ], + # np.array([[5, 9], [9, 5]])) # reference is 1 2 # 3 4 @@ -335,63 +337,56 @@ class TestIndexing(unittest.TestCase): # strided is [[1 3 5 7], # [9 11 13 15]] - reference = Tensor.arange(0., 24).reshape(3, 8) - strided = set_(reference, (2,4), (8,2), 1) - - numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([0])], - np.array([1, 9])) - numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([1])], - np.array([3, 11])) - numpy_testing_assert_equal_helper(strided[ri([0]), ri([0])], - np.array([1])) - numpy_testing_assert_equal_helper(strided[ri([1]), ri([3])], - np.array([15])) - numpy_testing_assert_equal_helper(strided[[ri([0, 0]), ri([0, 3])]], - np.array([1, 7])) - numpy_testing_assert_equal_helper(strided[[ri([1]), ri([0, 1, 1, 0, 3])]], - np.array([9, 11, 11, 9, 15])) - numpy_testing_assert_equal_helper(strided[[ri([0, 0, 1, 1]), ri([0, 1, 0, 0])]], - np.array([1, 3, 9, 9])) - - rows = ri([[0, 0], - [1, 1]]) - columns = [0], - numpy_testing_assert_equal_helper(strided[rows, columns], - np.array([[1, 1], [9, 9]])) - - rows = ri([[0, 1], - [1, 0]]) - columns = ri([1, 2]) - numpy_testing_assert_equal_helper(strided[rows, columns], - np.array([[3, 13], [11, 5]])) - rows = ri([[0, 0], - [1, 1]]) - columns = ri([[0, 1], - [1, 2]]) - numpy_testing_assert_equal_helper(strided[rows, columns], - np.array([[1, 3], [11, 13]])) + # # TODO: set stride + # reference = Tensor.arange(0., 24).reshape(3, 8) + # strided = set_(reference, (2,4), (8,2), 1) + + # numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([0])], np.array([1, 9])) + # numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([1])], np.array([3, 11])) + # numpy_testing_assert_equal_helper(strided[ri([0]), ri([0])], np.array([1])) + # numpy_testing_assert_equal_helper(strided[ri([1]), ri([3])], np.array([15])) + # numpy_testing_assert_equal_helper(strided[[ri([0, 0]), ri([0, 3])]], np.array([1, 7])) + # numpy_testing_assert_equal_helper(strided[[ri([1]), ri([0, 1, 1, 0, 3])]], np.array([9, 11, 11, 9, 15])) + # numpy_testing_assert_equal_helper(strided[[ri([0, 0, 1, 1]), ri([0, 1, 0, 0])]], np.array([1, 3, 9, 9])) + + # rows = ri([[0, 0], + # [1, 1]]) + # columns = [0], + # numpy_testing_assert_equal_helper(strided[rows, columns], np.array([[1, 1], [9, 9]])) + + # rows = ri([[0, 1], + # [1, 0]]) + # columns = ri([1, 2]) + # numpy_testing_assert_equal_helper(strided[rows, columns], np.array([[3, 13], [11, 5]])) + # rows = ri([[0, 0], + # [1, 1]]) + # columns = ri([[0, 1], + # [1, 2]]) + # numpy_testing_assert_equal_helper(strided[rows, columns], np.array([[1, 3], [11, 13]])) # setting values # strided is [[10, 11], # [17, 18]] - reference = Tensor.arange(0., 24).reshape(3, 8) - strided = set_(reference, (2,2), (7,1), 10) + # # TODO: set stride + # reference = Tensor.arange(0., 24).reshape(3, 8) + # strided = set_(reference, (2,2), (7,1), 10) + + # numpy_testing_assert_equal_helper(strided[ri([0]), ri([1])], np.array([11])) - numpy_testing_assert_equal_helper(strided[ri([0]), ri([1])], - np.array([11])) # TODO non contiguous setitem ''' strided[ri([0]), ri([1])] = -1 numpy_testing_assert_equal_helper(strided[ri([0]), ri([1])], Tensor([-1])) ''' - reference = Tensor.arange(0., 24).reshape(3, 8) - strided = set_(reference, (2,2), (7,1), 10) + # # TODO: set stride + # reference = Tensor.arange(0., 24).reshape(3, 8) + # strided = set_(reference, (2,2), (7,1), 10) + + # numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([1, 0])], np.array([11, 17])) - numpy_testing_assert_equal_helper(strided[ri([0, 1]), ri([1, 0])], - np.array([11, 17])) # TODO non contiguous setitem ''' strided[ri([0, 1]), ri([1, 0])] = Tensor([-1, 2]) @@ -399,15 +394,16 @@ class TestIndexing(unittest.TestCase): Tensor([-1, 2])) ''' - reference = Tensor.arange(0., 24).realize().reshape(3, 8) - strided = set_(reference, (2,2), (7,1), 10) + # # TODO: set stride + # reference = Tensor.arange(0., 24).realize().reshape(3, 8) + # strided = set_(reference, (2,2), (7,1), 10) + + # rows = ri([[0], + # [1]]) + # columns = ri([[0, 1], + # [0, 1]]) + # numpy_testing_assert_equal_helper(strided[rows, columns], np.array([[10, 11], [17, 18]])) - rows = ri([[0], - [1]]) - columns = ri([[0, 1], - [0, 1]]) - numpy_testing_assert_equal_helper(strided[rows, columns], - np.array([[10, 11], [17, 18]])) # TODO non contiguous setitem ''' strided[rows, columns] = Tensor([[4, 6], [2, 3]]) @@ -1052,12 +1048,13 @@ class TestIndexing(unittest.TestCase): a = src[0].mul(src[1]) self.assertEqual(a[0,1].item(), 2) + @unittest.skipUnless(is_dtype_supported(dtypes.int64), "need dtypes.int64") def test_getitem_scalars(self): zero = Tensor(0, dtype=dtypes.int64) one = Tensor(1, dtype=dtypes.int64) # non-scalar indexed with scalars - a = Tensor.randn(2, 3) + a = Tensor.randn(2, 3).realize() numpy_testing_assert_equal_helper(a[0], a[zero]) numpy_testing_assert_equal_helper(a[0][1], a[zero][one]) numpy_testing_assert_equal_helper(a[0, 1], a[zero, one]) @@ -1069,7 +1066,7 @@ class TestIndexing(unittest.TestCase): numpy_testing_assert_equal_helper(a[1], a[one.cast(dtypes.int16)]) # scalar indexed with scalar - r = Tensor.randn() + r = Tensor.randn().realize() with self.assertRaises(IndexError): r[:] with self.assertRaises(IndexError): @@ -1116,6 +1113,7 @@ class TestIndexing(unittest.TestCase): self.assertEqual(data_ptr(a[1]), data_ptr(a[one.cast(dtypes.int32)])) self.assertEqual(data_ptr(a[1]), data_ptr(a[one.cast(dtypes.int16)])) + @unittest.skip("does not fold now") def test_getitem_scalars_simple_folding(self): a = Tensor.randn(2, 3) zero = Tensor(0, dtype=dtypes.int64) diff --git a/tinygrad_repo/extra/mockgpu/amd/amddriver.py b/tinygrad_repo/test/mockgpu/amd/amddriver.py similarity index 63% rename from tinygrad_repo/extra/mockgpu/amd/amddriver.py rename to tinygrad_repo/test/mockgpu/amd/amddriver.py index 07b41fbfab..9073eefd70 100644 --- a/tinygrad_repo/extra/mockgpu/amd/amddriver.py +++ b/tinygrad_repo/test/mockgpu/amd/amddriver.py @@ -1,9 +1,9 @@ -import pathlib, re, ctypes, mmap, collections, struct, functools, os, copy +import pathlib, re, ctypes, mmap, collections, functools, copy, os import tinygrad.runtime.autogen.kfd as kfd -from typing import Optional, Any +import tinygrad.runtime.autogen.am.am as am from tinygrad.helpers import from_mv -from extra.mockgpu.driver import VirtDriver, VirtFileDesc, TextFileDesc, DirFileDesc, VirtFile -from extra.mockgpu.amd.amdgpu import AMDGPU, gpu_props +from test.mockgpu.driver import VirtDriver, VirtFileDesc, TextFileDesc, DirFileDesc, VirtFile +from test.mockgpu.amd.amdgpu import AMDGPU, gpu_props libc = ctypes.CDLL(ctypes.util.find_library("c")) libc.mmap.argtypes = [ctypes.c_void_p, ctypes.c_size_t, ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_long] @@ -13,7 +13,7 @@ def ioctls_from_header(): # hdrpy = (pathlib.Path(__file__).parent.parent.parent.parent / "tinygrad" / "runtime" / "autogen" / "kfd.py").read_text() # pattern = r'# (AMDKFD_IOC_[A-Z0-9_]+)\s=\s_(IOW?R?).*\(( 0x[0-9a-fA-F]+) ,\s+struct\s([A-Za-z0-9_]+)\s+\)' # matches = re.findall(pattern, hdrpy, re.MULTILINE) - hdr = (pathlib.Path(__file__).parent.parent.parent / "hip_gpu_driver" / "kfd_ioctl.h").read_text().replace("\\\n", "") + hdr = (pathlib.Path(__file__).parent.parent.parent.parent / "extra" / "hip_gpu_driver" / "kfd_ioctl.h").read_text().replace("\\\n", "") pattern = r'#define\s+(AMDKFD_IOC_[A-Z0-9_]+)\s+AMDKFD_(IOW?R?)\((0x[0-9a-fA-F]+),\s+struct\s([A-Za-z0-9_]+)\)' matches = re.findall(pattern, hdr, re.MULTILINE) return type("KFD_IOCTLS", (object, ), {name: int(nr, 0x10) for name, _, nr, _ in matches}), \ @@ -39,8 +39,9 @@ class AMDDriver(VirtDriver): def __init__(self, gpus=6): super().__init__() + # NOTE: gpu ids start from one (id 0 is skipped in KFDIface._is_usable_gpu) self.tracked_files += [VirtFile('/dev/kfd', functools.partial(KFDFileDesc, driver=self))] + \ - [VirtFile('/sys/devices/virtual/kfd/kfd/topology/nodes', functools.partial(DirFileDesc, child_names=[str(i) for i in range(gpus)]))] + [VirtFile('/sys/devices/virtual/kfd/kfd/topology/nodes', functools.partial(DirFileDesc, child_names=[str(i+1) for i in range(gpus)]))] self.gpus = {} self.next_fd = (1 << 30) @@ -50,8 +51,9 @@ class AMDDriver(VirtDriver): self.object_by_handle = {} self.doorbells = {} self.next_doorbell = collections.defaultdict(int) + self.mmu_event_ids = [] - for i in range(gpus): self._prepare_gpu(i) + for i in range(gpus): self._prepare_gpu(i+1) def _alloc_fd(self): my_fd = self.next_fd @@ -77,10 +79,28 @@ class AMDDriver(VirtDriver): self.doorbells[gpu_id] = memoryview(bytearray(0x2000)) self.gpus[gpu_id] = AMDGPU(gpu_id) self.tracked_files += [ + VirtFile('/sys/module/amdgpu', functools.partial(TextFileDesc, text="1")), VirtFile(f'/sys/devices/virtual/kfd/kfd/topology/nodes/{gpu_id}', functools.partial(DirFileDesc, child_names=['gpu_id', 'properties'])), VirtFile(f'/sys/devices/virtual/kfd/kfd/topology/nodes/{gpu_id}/gpu_id', functools.partial(TextFileDesc, text=f"{gpu_id}")), VirtFile(f'/sys/devices/virtual/kfd/kfd/topology/nodes/{gpu_id}/properties', functools.partial(TextFileDesc, text=gpu_props.format(drm_render_minor=gpu_id))), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0', + functools.partial(DirFileDesc, child_names=[str(am.GC_HWID), str(am.SDMA0_HWID), str(am.NBIF_HWID)])), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.GC_HWID}/0/major', functools.partial(TextFileDesc, text='11')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.GC_HWID}/0/minor', functools.partial(TextFileDesc, text='0')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.GC_HWID}/0/revision', functools.partial(TextFileDesc, text='0')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.GC_HWID}/0/base_addr', + functools.partial(TextFileDesc, text='0x00001260\n0x0000A000\n0x0001C000\n0x02402C00')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.SDMA0_HWID}/0/major', functools.partial(TextFileDesc, text='6')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.SDMA0_HWID}/0/minor', functools.partial(TextFileDesc, text='0')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.SDMA0_HWID}/0/revision', functools.partial(TextFileDesc, text='0')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.SDMA0_HWID}/0/base_addr', + functools.partial(TextFileDesc, text='0x00001260\n0x0000A000\n0x0001C000\n0x02402C00')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.NBIF_HWID}/0/major', functools.partial(TextFileDesc, text='4')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.NBIF_HWID}/0/minor', functools.partial(TextFileDesc, text='3')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.NBIF_HWID}/0/revision', functools.partial(TextFileDesc, text='0')), + VirtFile(f'/sys/class/drm/renderD{gpu_id}/device/ip_discovery/die/0/{am.NBIF_HWID}/0/base_addr', + functools.partial(TextFileDesc, text='0x00000000\n0x00000014\n0x00000D20\n0x00010400\n0x0241B000\n0x04040000')), VirtFile(f'/dev/dri/renderD{gpu_id}', functools.partial(DRMFileDesc, driver=self, gpu=f"{self.gpus[gpu_id]}")), ] @@ -114,6 +134,8 @@ class AMDDriver(VirtDriver): elif nr == kfd_ioctls.AMDKFD_IOC_CREATE_EVENT: struct.event_slot_index = self._alloc_next_event_slot() struct.event_id = struct.event_slot_index + + if struct.event_type == kfd.KFD_IOC_EVENT_MEMORY: self.mmu_event_ids.append(struct.event_id) elif nr == kfd_ioctls.AMDKFD_IOC_CREATE_QUEUE: gpu = self.gpus[struct.gpu_id] if struct.queue_type == kfd.KFD_IOC_QUEUE_TYPE_SDMA: @@ -126,7 +148,12 @@ class AMDDriver(VirtDriver): struct.doorbell_offset = self._alloc_doorbell(struct.gpu_id) self.track_address(struct.doorbell_offset, struct.doorbell_offset + 8, lambda mv,off: None, lambda mv, off: self._emulate_execute()) elif nr == kfd_ioctls.AMDKFD_IOC_WAIT_EVENTS: - pass + evs = (kfd.struct_kfd_event_data * struct.num_events).from_address(struct.events_ptr) + for ev in evs: + if ev.event_id in self.mmu_event_ids and "MOCKGPU_EMU_FAULTADDR" in os.environ: + ev.memory_exception_data.gpu_id = 1 + ev.memory_exception_data.va = int(os.environ["MOCKGPU_EMU_FAULTADDR"], 16) + ev.memory_exception_data.failure.NotPresent = 1 else: name = "unknown" for k,v in kfd_ioctls.__dict__.items(): @@ -141,6 +168,4 @@ class AMDDriver(VirtDriver): any_progress = False for gpu in self.gpus.values(): for q in gpu.queues: - if (prev_rptr:=q.rptr[0]) != q.wptr[0]: - q.execute() - any_progress |= (prev_rptr != q.rptr[0]) + if q.executing: any_progress |= q.execute() > 0 diff --git a/tinygrad_repo/extra/mockgpu/amd/amdgpu.py b/tinygrad_repo/test/mockgpu/amd/amdgpu.py similarity index 75% rename from tinygrad_repo/extra/mockgpu/amd/amdgpu.py rename to tinygrad_repo/test/mockgpu/amd/amdgpu.py index b9cd7dcfe6..8cc8b03a7c 100644 --- a/tinygrad_repo/extra/mockgpu/amd/amdgpu.py +++ b/tinygrad_repo/test/mockgpu/amd/amdgpu.py @@ -1,13 +1,12 @@ import ctypes, time -from extra.mockgpu.gpu import VirtGPU -from tinygrad.helpers import to_mv, init_c_struct_t, mv_address +from test.mockgpu.gpu import VirtGPU +from tinygrad.helpers import to_mv, init_c_struct_t import tinygrad.runtime.autogen.amd_gpu as amd_gpu SDMA_MAX_COPY_SIZE = 0x400000 -BASE_ADDR = 0x00001260 PACKET3_SET_SH_REG_START = 0x2c00 -SUB = PACKET3_SET_SH_REG_START - BASE_ADDR +SUB = PACKET3_SET_SH_REG_START - amd_gpu.GC_BASE__INST0_SEG0 regCOMPUTE_PGM_LO = 0x1bac - SUB regCOMPUTE_USER_DATA_0 = 0x1be0 - SUB @@ -19,13 +18,15 @@ WAIT_REG_MEM_FUNCTION_ALWAYS = 0 WAIT_REG_MEM_FUNCTION_EQ = 3 # == WAIT_REG_MEM_FUNCTION_GEQ = 5 # >= -REMU_PATHS = ["libremu.so", "/usr/local/lib/libremu.so"] +REMU_PATHS = ["extra/remu/target/release/libremu.so", "libremu.so", "/usr/local/lib/libremu.so", + "extra/remu/target/release/libremu.dylib", "libremu.dylib", "/usr/local/lib/libremu.dylib", "/opt/homebrew/lib/libremu.dylib"] def _try_dlopen_remu(): for path in REMU_PATHS: try: remu = ctypes.CDLL(path) remu.run_asm.restype = ctypes.c_int32 - remu.run_asm.argtypes = [ctypes.c_void_p, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_void_p] + remu.run_asm.argtypes = [ctypes.c_void_p, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, + ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_void_p] except OSError: pass else: return remu print("Could not find libremu.so") @@ -55,15 +56,19 @@ def create_sdma_packets(): return type("SDMA_PKTS", (object, ), structs) sdma_pkts = create_sdma_packets() -class AMDQueue(): +class AMDQueue: def __init__(self, base, size, rptr, wptr): self.queue, self.size = to_mv(base, size).cast("I"), size - self.rptr = to_mv(rptr, 8).cast("Q") - self.wptr = to_mv(wptr, 8).cast("Q") + self.rptr = to_mv(rptr, 8).cast("Q") if isinstance(rptr, int) else rptr + self.wptr = to_mv(wptr, 8).cast("Q") if isinstance(wptr, int) else wptr + + @property + def executing(self): return self.rptr[0] < self.wptr[0] class PM4Executor(AMDQueue): def __init__(self, gpu, base, size, rptr, wptr): self.gpu = gpu + self.ib_executor: PM4Executor|None = None super().__init__(base, size, rptr, wptr) def _next_dword(self): @@ -71,9 +76,17 @@ class PM4Executor(AMDQueue): self.rptr[0] += 1 return x + @property + def executing(self): return self.rptr[0] < self.wptr[0] or self.ib_executor is not None + def execute(self): - while self.rptr[0] < self.wptr[0]: - cont = True + prev_rptr, executed_in_ib, cont = self.rptr[0], 0, True + while self.executing and cont: + if self.ib_executor is not None: + executed_in_ib += self.ib_executor.execute() + if self.ib_executor.executing: break + self.ib_executor = None + continue # this continue is needed if PACKET3_INDIRECT_BUFFER is the last packet and rptr == wptr header = self._next_dword() packet_type = header >> 30 op = (header >> 8) & 0xFF @@ -87,7 +100,7 @@ class PM4Executor(AMDQueue): elif op == amd_gpu.PACKET3_INDIRECT_BUFFER: self._exec_indirect_buffer(n) elif op == amd_gpu.PACKET3_EVENT_WRITE: self._exec_event_write(n) else: raise RuntimeError(f"PM4: Unknown opcode: {op}") - if not cont: return + return (self.rptr[0] - prev_rptr) + executed_in_ib def _exec_acquire_mem(self, n): assert n == 6 @@ -98,14 +111,14 @@ class PM4Executor(AMDQueue): mem_event_type = (self._next_dword() >> 0) & 0xff selectors = self._next_dword() mem_data_sel = (selectors >> 29) & 0b111 - int_sel = (selectors >> 24) & 0b11 - mem_dst_sel = (selectors >> 16) & 0b1 + # int_sel = (selectors >> 24) & 0b11 + # mem_dst_sel = (selectors >> 16) & 0b1 addr_lo = self._next_dword() addr_hi = self._next_dword() val_lo = self._next_dword() val_hi = self._next_dword() val = val_lo + (val_hi << 32) - ev = self._next_dword() + _ = self._next_dword() # ev ptr = to_mv(addr_lo + (addr_hi << 32), 8) if mem_data_sel == 1 or mem_data_sel == 2: ptr.cast('Q')[0] = val @@ -120,24 +133,22 @@ class PM4Executor(AMDQueue): addr_lo = self._next_dword() addr_hi = self._next_dword() val = self._next_dword() - mask = self._next_dword() - timeout = self._next_dword() + _ = self._next_dword() # mask + _ = self._next_dword() # timeout mem_function = (info >> 0) & 0b111 mem_space = (info >> 4) & 0b1 - mem_op = (info >> 6) & 0b1 - mem_engine = (info >> 8) & 0b1 + _ = (info >> 6) & 0b1 # memop + _ = (info >> 8) & 0b1 # mem_engine - if mem_space == 0: read_op = lambda: val - elif mem_space == 1: read_op = lambda: to_mv(addr_lo + (addr_hi << 32), 4).cast('I')[0] + if mem_space == 0: mval = val + elif mem_space == 1: mval = to_mv(addr_lo + (addr_hi << 32), 4).cast('I')[0] - if mem_function == WAIT_REG_MEM_FUNCTION_GEQ: cmp = lambda x,y: x >= y - elif mem_function == WAIT_REG_MEM_FUNCTION_EQ: cmp = lambda x,y: x == y + if mem_function == WAIT_REG_MEM_FUNCTION_GEQ: can_cont = bool(mval >= val) + elif mem_function == WAIT_REG_MEM_FUNCTION_EQ: can_cont = bool(mval == val) else: raise RuntimeError(f"Do not support {mem_function=}") - mval = read_op() - can_cont = cmp(mval, val) - if not can_cont: self.rptr[0] = self.rptr[0] - 7 # revert packet, need to wait again + if not can_cont: self.rptr[0] = self.rptr[0] - 7 # revert this packet, need to wait again return can_cont def _exec_set_sh_reg(self, n): @@ -149,7 +160,7 @@ class PM4Executor(AMDQueue): def _exec_dispatch_direct(self, n): assert n == 3 gl = [self._next_dword() for _ in range(3)] - flags = self._next_dword() + _ = self._next_dword() # flags prg_addr = (self.gpu.regs[regCOMPUTE_PGM_LO] + (self.gpu.regs[regCOMPUTE_PGM_LO + 1] << 32)) << 8 args_addr = self.gpu.regs[regCOMPUTE_USER_DATA_0] + (self.gpu.regs[regCOMPUTE_USER_DATA_0 + 1] << 32) @@ -157,7 +168,7 @@ class PM4Executor(AMDQueue): prg_sz = 0 for st,sz in self.gpu.mapped_ranges: - if st <= prg_addr <= st+sz: prg_sz = sz - (prg_addr - st) + if st <= prg_addr < st+sz: prg_sz = sz - (prg_addr - st) assert prg_sz > 0, "Invalid prg ptr (not found in mapped ranges)" err = remu.run_asm(prg_addr, prg_sz, *gl, *lc, args_addr) @@ -172,8 +183,7 @@ class PM4Executor(AMDQueue): wptr = memoryview(bytearray(8)).cast('Q') rptr[0] = 0 wptr[0] = buf_sz - PM4Executor(self.gpu, (addr_hi << 32) | addr_lo, buf_sz * 4, mv_address(rptr), mv_address(wptr)).execute() - assert rptr[0] == wptr[0], "not everything executed in amdgpu" + self.ib_executor = PM4Executor(self.gpu, (addr_hi << 32) | addr_lo, buf_sz * 4, rptr, wptr) def _exec_event_write(self, n): assert n == 0 @@ -185,8 +195,8 @@ class SDMAExecutor(AMDQueue): super().__init__(base, size, rptr, wptr) def execute(self): - while self.rptr[0] < self.wptr[0]: - cont = True + prev_rptr, cont = self.rptr[0], True + while self.executing and cont: header = self.queue[(self.rptr[0] // 4) % (self.size // 4)] op = (header >> 0) & 0xff if op == 0: self.rptr[0] += 4 @@ -197,7 +207,7 @@ class SDMAExecutor(AMDQueue): elif op == amd_gpu.SDMA_OP_COPY: self._execute_copy() elif op == amd_gpu.SDMA_OP_TIMESTAMP: self._execute_timestamp() else: raise RuntimeError(f"Unknown SDMA op {op}") - if not cont: return + return self.rptr[0] - prev_rptr def _execute_fence(self): struct = sdma_pkts.fence.from_address(self.base + self.rptr[0] % self.size) @@ -211,16 +221,15 @@ class SDMAExecutor(AMDQueue): def _execute_poll_regmem(self): struct = sdma_pkts.poll_regmem.from_address(self.base + self.rptr[0] % self.size) - if struct.mem_poll == 0: read_op = lambda: struct.value - elif struct.mem_poll == 1: read_op = lambda: to_mv(struct.addr, 4).cast('I')[0] + if struct.mem_poll == 0: mval = struct.value & struct.mask + elif struct.mem_poll == 1: mval = to_mv(struct.addr, 4).cast('I')[0] & struct.mask - if struct.func == WAIT_REG_MEM_FUNCTION_GEQ: cmp = lambda x,y: x >= y - elif struct.func == WAIT_REG_MEM_FUNCTION_EQ: cmp = lambda x,y: x == y - elif struct.func == WAIT_REG_MEM_FUNCTION_ALWAYS: cmp = lambda x,y: True + if struct.func == WAIT_REG_MEM_FUNCTION_GEQ: can_cont = bool(mval >= struct.value) + elif struct.func == WAIT_REG_MEM_FUNCTION_EQ: can_cont = bool(mval == struct.value) + elif struct.func == WAIT_REG_MEM_FUNCTION_ALWAYS: can_cont = True else: raise RuntimeError(f"Do not support {struct.func=}") - mval = read_op() & struct.mask - if not cmp(mval, struct.value): return False + if not can_cont: return False self.rptr[0] += ctypes.sizeof(struct) return True @@ -239,7 +248,8 @@ class SDMAExecutor(AMDQueue): def _execute_copy(self): struct = sdma_pkts.copy_linear.from_address(self.base + self.rptr[0] % self.size) - ctypes.memmove(struct.dst_addr, struct.src_addr, struct.count + 1) + count_cnt = to_mv(self.base + self.rptr[0] + 4, 4).cast('I')[0] & 0x3FFFFFFF + ctypes.memmove(struct.dst_addr, struct.src_addr, count_cnt + 1) self.rptr[0] += ctypes.sizeof(struct) class AMDGPU(VirtGPU): diff --git a/tinygrad_repo/test/mockgpu/cuda/cuda.py b/tinygrad_repo/test/mockgpu/cuda/cuda.py new file mode 100644 index 0000000000..a5dd5fe0c8 --- /dev/null +++ b/tinygrad_repo/test/mockgpu/cuda/cuda.py @@ -0,0 +1,170 @@ +from __future__ import annotations +from typing import Any +import ctypes, time +from tinygrad.runtime.autogen import cuda as orig_cuda +from tinygrad.helpers import mv_address + +for attr in dir(orig_cuda): + if not attr.startswith('__'): + globals()[attr] = getattr(orig_cuda, attr) + +try: + gpuocelot_lib = ctypes.CDLL(ctypes.util.find_library("gpuocelot")) + gpuocelot_lib.ptx_run.argtypes = [ctypes.c_char_p, ctypes.c_int, ctypes.POINTER(ctypes.c_void_p), ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_int] # noqa: E501 +except Exception: pass + +# Global state +class CUDAState: + def __init__(self): + self.memory: dict[int, memoryview] = {} + self.events: dict[int, float] = {} # Event ID -> timestamp + self.modules: dict[int, memoryview] = {} # Module ID -> code + self.current_context: int|None = None + self.contexts: dict[int, dict] = {} # Context ID -> context data + self.devices: dict[int, dict] = {} # Device ID -> device data + self.next_ptr = 1000 # For memory allocation + self.next_event_id = 1 + self.next_module_id = 1 + self.next_context_id = 1 + +cuda_state = CUDAState() + +# Helper functions +def check_context(): + if cuda_state.current_context is None: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + return orig_cuda.CUDA_SUCCESS + +# CUDA API simulation +def cuInit(flags: int) -> int: + return orig_cuda.CUDA_SUCCESS + +def cuDeviceGet(device, ordinal: int) -> int: + if ordinal < 0: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + device._obj.value = ordinal + cuda_state.devices[ordinal] = {"compute_capability": (3, 5)} + return orig_cuda.CUDA_SUCCESS + +def cuCtxCreate_v2(pctx, flags: int, dev: int) -> int: + ctx_id = cuda_state.next_context_id + cuda_state.next_context_id += 1 + cuda_state.contexts[ctx_id] = {"device": dev, "flags": flags} + pctx._obj.value = ctx_id + return orig_cuda.CUDA_SUCCESS + +def cuCtxSetCurrent(context) -> int: + if context.value not in cuda_state.contexts: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + cuda_state.current_context = context.value + return orig_cuda.CUDA_SUCCESS + +def cuMemAlloc_v2(dptr, bytesize: int) -> int: + x = memoryview(bytearray(bytesize)) + dptr._obj.value = mv_address(x) + cuda_state.memory[dptr._obj.value] = x + return orig_cuda.CUDA_SUCCESS + +def cuMemFree_v2(dptr) -> int: + if dptr.value in cuda_state.memory: + del cuda_state.memory[dptr.value] + return orig_cuda.CUDA_SUCCESS + return orig_cuda.CUDA_ERROR_INVALID_VALUE + +def cuMemcpyHtoDAsync_v2(dst, src: ctypes.c_void_p, bytesize: int, stream: Any) -> int: + ctypes.memmove(dst.value, src, bytesize) + return orig_cuda.CUDA_SUCCESS + +def cuMemcpyDtoH_v2(dst: ctypes.c_void_p, src, bytesize: int) -> int: + ctypes.memmove(dst, src.value, bytesize) + return orig_cuda.CUDA_SUCCESS + +def cuEventCreate(phEvent, flags: int) -> int: + event_id = cuda_state.next_event_id + cuda_state.next_event_id += 1 + cuda_state.events[event_id] = 0.0 + phEvent._obj.value = event_id + return orig_cuda.CUDA_SUCCESS + +def cuEventRecord(hEvent, hStream: Any) -> int: + if hEvent.value not in cuda_state.events: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + cuda_state.events[hEvent.value] = time.perf_counter_ns() + return orig_cuda.CUDA_SUCCESS + +def cuEventSynchronize(hEvent) -> int: + if hEvent.value not in cuda_state.events: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + return orig_cuda.CUDA_SUCCESS + +def cuEventElapsedTime(pMilliseconds, hStart, hEnd) -> int: + if hStart.value not in cuda_state.events or hEnd.value not in cuda_state.events: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + elapsed = (cuda_state.events[hEnd.value] - cuda_state.events[hStart.value]) * 1e-6 + pMilliseconds._obj.value = elapsed + return orig_cuda.CUDA_SUCCESS + +def cuEventDestroy_v2(hEvent) -> int: + if hEvent.value in cuda_state.events: + del cuda_state.events[hEvent.value] + return orig_cuda.CUDA_SUCCESS + +def cuModuleLoadData(module, image: bytes) -> int: + module_id = cuda_state.next_module_id + cuda_state.next_module_id += 1 + cuda_state.modules[module_id] = memoryview(bytearray(image)) + module._obj.value = module_id + return orig_cuda.CUDA_SUCCESS + +def cuModuleGetFunction(hfunc, hmod, name: bytes) -> int: + if hmod.value not in cuda_state.modules: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + hfunc._obj.value = mv_address(cuda_state.modules[hmod.value]) + return orig_cuda.CUDA_SUCCESS + +def cuModuleUnload(hmod) -> int: + if hmod.value in cuda_state.modules: + del cuda_state.modules[hmod.value] + return orig_cuda.CUDA_SUCCESS + +def cuLaunchKernel(f, gx: int, gy: int, gz: int, lx: int, ly: int, lz: int, sharedMemBytes: int, + hStream: Any, kernelParams: Any, extra: Any) -> int: + cargs = [ctypes.cast(getattr(extra, field[0]), ctypes.c_void_p) for field in extra._fields_] + gpuocelot_lib.ptx_run(ctypes.cast(f.value, ctypes.c_char_p), len(cargs), (ctypes.c_void_p*len(cargs))(*cargs), lx, ly, lz, gx, gy, gz, 0) + return orig_cuda.CUDA_SUCCESS + +def cuDeviceComputeCapability(major, minor, dev: int) -> int: + if dev not in cuda_state.devices: + return orig_cuda.CUDA_ERROR_INVALID_VALUE + major._obj.value = 3 + minor._obj.value = 5 + return orig_cuda.CUDA_SUCCESS + +def cuDeviceCanAccessPeer(canAccessPeer, dev: int, peerDev: int) -> int: + canAccessPeer._obj.value = 1 # Always allow peer access in simulation + return orig_cuda.CUDA_SUCCESS + +def cuCtxEnablePeerAccess(peerContext, flags: int) -> int: + return orig_cuda.CUDA_SUCCESS + +def cuMemHostAlloc(pp, bytesize: int, flags: int) -> int: + return cuMemAlloc_v2(pp, bytesize) + +def cuMemFreeHost(p: ctypes.c_void_p) -> int: return cuMemFree_v2(p) + +def cuMemcpyDtoDAsync_v2(dst, src, bytesize: int, stream: Any) -> int: + ctypes.memmove(dst.value, src.value, bytesize) + return orig_cuda.CUDA_SUCCESS + +def cuFuncSetAttribute(hfunc, attrib: int, value: int) -> int: + return orig_cuda.CUDA_SUCCESS + +def cuStreamWaitEvent(stream: Any, event, flags: int) -> int: return orig_cuda.CUDA_SUCCESS +def cuCtxSynchronize() -> int: return orig_cuda.CUDA_SUCCESS + +def cuGetErrorString(error: int, pStr) -> int: + error_str = orig_cuda.cudaError_enum__enumvalues.get(error, "Unknown CUDA error").encode() + buf = ctypes.create_string_buffer(error_str) + # Set the pointer to point to our error string buffer + pStr._obj.value = ctypes.cast(buf, ctypes.POINTER(ctypes.c_char)) + return orig_cuda.CUDA_SUCCESS diff --git a/tinygrad_repo/test/mockgpu/driver.py b/tinygrad_repo/test/mockgpu/driver.py new file mode 100644 index 0000000000..7be165cb06 --- /dev/null +++ b/tinygrad_repo/test/mockgpu/driver.py @@ -0,0 +1,39 @@ +from typing import Any +from dataclasses import dataclass + +class VirtFileDesc: + def __init__(self, fd): self.fd, self.off = fd, 0 + def ioctl(self, fd, req, argp): raise NotImplementedError() + def mmap(self, st, sz, prot, flags, fd, off): raise NotImplementedError() + def close(self, fd): return 0 + +class TextFileDesc(VirtFileDesc): + def __init__(self, fd, text): + super().__init__(fd) + self.content = text + + def ioctl(self, fd, req, argp): return 0 + def read_contents(self, size=None): + ret = self.content[self.off:self.off+(size or len(self.content))] + self.off += (size or len(self.content)) + return ret + def seek(self, offset): self.off += offset +class DirFileDesc(VirtFileDesc): + def __init__(self, fd, child_names): + super().__init__(fd) + self.child_names = child_names + + def ioctl(self, fd, req, argp): return 0 + def list_contents(self): return self.child_names + +@dataclass(frozen=True) +class VirtFile: + path: str + fdcls: Any # TODO: fix this Union[VirtFileDesc, functools.partial[VirtFileDesc]] + +class VirtDriver: + def __init__(self): + self.tracked_files = [] + self.tracked_addresses = [] + def track_address(self, staddr, enaddr, rcb, wcb): self.tracked_addresses.append((staddr, enaddr, rcb, wcb)) + def open(self, name, flags, mode, fdcls): raise NotImplementedError() diff --git a/tinygrad_repo/extra/mockgpu/gpu.py b/tinygrad_repo/test/mockgpu/gpu.py similarity index 100% rename from tinygrad_repo/extra/mockgpu/gpu.py rename to tinygrad_repo/test/mockgpu/gpu.py diff --git a/tinygrad_repo/test/mockgpu/mockgpu.py b/tinygrad_repo/test/mockgpu/mockgpu.py new file mode 100644 index 0000000000..9e60fa3979 --- /dev/null +++ b/tinygrad_repo/test/mockgpu/mockgpu.py @@ -0,0 +1,101 @@ +import ctypes, ctypes.util, time, os, builtins, fcntl +from tinygrad.runtime.support.hcq import FileIOInterface +from test.mockgpu.nv.nvdriver import NVDriver +from test.mockgpu.amd.amddriver import AMDDriver +start = time.perf_counter() + +# *** ioctl lib *** +libc = ctypes.CDLL(ctypes.util.find_library("c")) +libc.mmap.argtypes = [ctypes.c_void_p, ctypes.c_size_t, ctypes.c_int, ctypes.c_int, ctypes.c_int, ctypes.c_long] +libc.mmap.restype = ctypes.c_void_p + +drivers = [AMDDriver(), NVDriver()] +tracked_fds = {} + +orignal_memoryview = builtins.memoryview +class TrackedMemoryView: + def __init__(self, data, rcb, wcb): + self.mv = orignal_memoryview(data) + self.rcb, self.wcb = rcb, wcb + + def __getitem__(self, index): + self.rcb(self.mv, index) + return self.mv[index] + + def __setitem__(self, index, value): + self.mv[index] = value + self.wcb(self.mv, index) + + def cast(self, new_type, **kwargs): + self.mv = self.mv.cast('B').cast(new_type, **kwargs) + return self + + @property + def nbytes(self): return self.mv.nbytes + def __len__(self): return len(self.mv) + def __repr__(self): return repr(self.mv) + +def _memoryview(cls, mem): + if isinstance(mem, int) or isinstance(mem, ctypes.Array): + addr = ctypes.addressof(mem) if isinstance(mem, ctypes.Array) else mem + for d in drivers: + for st,en,rcb,wcb in d.tracked_addresses: + if st <= addr <= en: return TrackedMemoryView(mem, rcb, wcb) + return orignal_memoryview(mem) +builtins.memoryview = type("memoryview", (), {'__new__': _memoryview}) # type: ignore + +def _open(path, flags): + for d in drivers: + for x in d.tracked_files: + if path == x.path: + virtfd = d.open(path, flags, 0o777, x) + tracked_fds[virtfd.fd] = virtfd + return virtfd.fd + return os.open(path, flags, 0o777) if os.path.exists(path) else None + +class MockFileIOInterface(FileIOInterface): + def __init__(self, path:str="", flags:int=os.O_RDONLY, fd:int|None=None): + self.path = path + self.fd = fd or _open(path, flags) + + def __del__(self): + if self.fd in tracked_fds: + tracked_fds[self.fd].close(self.fd) + tracked_fds.pop(self.fd) + else: os.close(self.fd) + + def ioctl(self, request, arg): + if self.fd in tracked_fds: + return tracked_fds[self.fd].ioctl(self.fd, request, ctypes.addressof(arg)) + return fcntl.ioctl(self.fd, request, arg) + + def mmap(self, start, sz, prot, flags, offset): + if self.fd in tracked_fds: + return tracked_fds[self.fd].mmap(start, sz, prot, flags, self.fd, offset) + return libc.mmap(start, sz, prot, flags, self.fd, offset) + + def read(self, size=None, binary=False, offset=None): + if binary: raise NotImplementedError() + if self.fd in tracked_fds: + return tracked_fds[self.fd].read_contents(size) + with open(self.fd, "rb" if binary else "r", closefd=False) as file: + if file.tell() >= os.fstat(self.fd).st_size: file.seek(0) + return file.read(size) + + def listdir(self): + if self.fd in tracked_fds: + return tracked_fds[self.fd].list_contents() + return os.listdir(self.path) + + def write(self, content, binary=False, offset=None): raise NotImplementedError() + def seek(self, offset): + if self.fd in tracked_fds: + tracked_fds[self.fd].seek(offset) + else: + os.lseek(self.fd, offset, os.SEEK_CUR) + @staticmethod + def exists(path): return _open(path, os.O_RDONLY) is not None + @staticmethod + def readlink(path): raise NotImplementedError() + @staticmethod + def eventfd(initval, flags=None): NotImplementedError() diff --git a/tinygrad_repo/extra/mockgpu/nv/nvdriver.py b/tinygrad_repo/test/mockgpu/nv/nvdriver.py similarity index 91% rename from tinygrad_repo/extra/mockgpu/nv/nvdriver.py rename to tinygrad_repo/test/mockgpu/nv/nvdriver.py index eddd720d38..d7c330c600 100644 --- a/tinygrad_repo/extra/mockgpu/nv/nvdriver.py +++ b/tinygrad_repo/test/mockgpu/nv/nvdriver.py @@ -1,9 +1,9 @@ -import pathlib, re, ctypes, mmap, collections, struct, functools, os, copy +import ctypes, mmap, collections, functools, os import tinygrad.runtime.autogen.nv_gpu as nv_gpu -from typing import Optional, Any +from typing import Any from tinygrad.helpers import to_mv -from extra.mockgpu.driver import VirtDriver, VirtFileDesc, TextFileDesc, DirFileDesc, VirtFile -from extra.mockgpu.nv.nvgpu import NVGPU +from test.mockgpu.driver import VirtDriver, VirtFileDesc, VirtFile +from test.mockgpu.nv.nvgpu import NVGPU MAP_FIXED = 0x10 libc = ctypes.CDLL(ctypes.util.find_library("c")) @@ -45,7 +45,8 @@ class NVDevFileDesc(VirtFileDesc): def ioctl(self, fd, request, argp): return self.driver.dev_ioctl(self.gpu, request, argp) def mmap(self, start, sz, prot, flags, fd, offset): start = libc.mmap(start, sz, prot, flags|mmap.MAP_ANONYMOUS, -1, 0) - if self._mapping_userland: self.driver.track_address(start, start+sz, lambda mv,off: None, lambda mv, off: self.driver._gpu_mmio_write(mv, off, self.gpu)) + if self._mapping_userland: + self.driver.track_address(start, start+sz, lambda mv,off: None, lambda mv, off: self.driver._gpu_mmio_write(mv, off, self.gpu)) return start class NVDriver(VirtDriver): @@ -58,7 +59,7 @@ class NVDriver(VirtDriver): self.root_handle = None self.gpus = {} - self.next_fd = (1 << 30) + self.next_fd = (1 << 29) self.next_handle = 1 self.object_by_handle = {} @@ -88,7 +89,7 @@ class NVDriver(VirtDriver): def rm_alloc(self, argp): struct = nv_gpu.NVOS21_PARAMETERS.from_address(argp) - params_ptr = struct.pAllocParms if struct.pAllocParms else None + params_ptr = struct.pAllocParms if struct.hClass == nv_gpu.NV01_ROOT_CLIENT: self.root_handle = struct.hObjectNew = self._alloc_handle() elif struct.hClass == nv_gpu.NV01_DEVICE_0: params:Any = nv_gpu.NV0080_ALLOC_PARAMETERS.from_address(params_ptr) @@ -137,7 +138,7 @@ class NVDriver(VirtDriver): def rm_control(self, argp): struct = nv_gpu.NVOS54_PARAMETERS.from_address(argp) - params_ptr = struct.params if struct.params else None + params_ptr = struct.params if struct.cmd == nv_gpu.NV0000_CTRL_CMD_GPU_GET_ID_INFO_V2: params:Any = nv_gpu.NV0000_CTRL_GPU_GET_ID_INFO_V2_PARAMS.from_address(params_ptr) params.deviceInstance = params.gpuId # emulate them to be the same @@ -171,7 +172,7 @@ class NVDriver(VirtDriver): assert struct.hObject in self.object_by_handle and isinstance(self.object_by_handle[struct.hObject], NVSubDevice) gpu = self.object_by_handle[struct.hObject].device params = nv_gpu.NV2080_CTRL_GPU_GET_GID_INFO_PARAMS.from_address(params_ptr) - if params.flags != nv_gpu.NV2080_GPU_CMD_GPU_GET_GID_FLAGS_FORMAT_BINARY: raise RuntimeError(f"Unknown format") + if params.flags != nv_gpu.NV2080_GPU_CMD_GPU_GET_GID_FLAGS_FORMAT_BINARY: raise RuntimeError("Unknown format") bts = gpu.gpu_uuid(sz=params.length) for i in range(params.length): params.data[i] = bts[i] elif struct.cmd == nv_gpu.NVC36F_CTRL_CMD_GPFIFO_GET_WORK_SUBMIT_TOKEN: @@ -182,6 +183,15 @@ class NVDriver(VirtDriver): elif struct.cmd == nv_gpu.NVA06C_CTRL_CMD_GPFIFO_SCHEDULE: pass elif struct.cmd == nv_gpu.NV2080_CTRL_CMD_PERF_BOOST: pass elif struct.cmd == nv_gpu.NV2080_CTRL_CMD_FB_FLUSH_GPU_CACHE: pass + elif struct.cmd == nv_gpu.NV83DE_CTRL_CMD_DEBUG_READ_ALL_SM_ERROR_STATES: + params = nv_gpu.NV83DE_CTRL_DEBUG_READ_ALL_SM_ERROR_STATES_PARAMS.from_address(params_ptr) + params.mmuFault.valid = bool("MOCKGPU_EMU_FAULTADDR" in os.environ) + elif struct.cmd == nv_gpu.NV83DE_CTRL_CMD_DEBUG_READ_MMU_FAULT_INFO: + params = nv_gpu.struct_NV83DE_CTRL_DEBUG_READ_MMU_FAULT_INFO_PARAMS.from_address(params_ptr) + params.count = 1 + params.mmuFaultInfoList[0].faultAddress = int(os.environ['MOCKGPU_EMU_FAULTADDR'], base=16) + params.mmuFaultInfoList[0].faultType = 1 + params.mmuFaultInfoList[0].accessType = 1 else: raise RuntimeError(f"Unknown {struct.cmd} to rm_control") return 0 @@ -243,5 +253,5 @@ class NVDriver(VirtDriver): any_progress = False for gpu in self.gpus.values(): for q in gpu.queues: - if (prev_rptr:=q.ctrl.GPGet) != q.ctrl.GPPut: + if q.ctrl.GPGet != q.ctrl.GPPut: any_progress |= q.execute() \ No newline at end of file diff --git a/tinygrad_repo/extra/mockgpu/nv/nvgpu.py b/tinygrad_repo/test/mockgpu/nv/nvgpu.py similarity index 97% rename from tinygrad_repo/extra/mockgpu/nv/nvgpu.py rename to tinygrad_repo/test/mockgpu/nv/nvgpu.py index 3bb401de5f..63c03998e8 100644 --- a/tinygrad_repo/extra/mockgpu/nv/nvgpu.py +++ b/tinygrad_repo/test/mockgpu/nv/nvgpu.py @@ -1,7 +1,7 @@ import ctypes, ctypes.util, time import tinygrad.runtime.autogen.nv_gpu as nv_gpu from enum import Enum, auto -from extra.mockgpu.gpu import VirtGPU +from test.mockgpu.gpu import VirtGPU from tinygrad.helpers import to_mv, init_c_struct_t def make_qmd_struct_type(): @@ -55,7 +55,7 @@ class GPFIFO: def _reset_buf_state(self): self.buf, self.buf_ptr = None, 0 def _set_buf_state(self, gpfifo_entry): - ptr = ((gpfifo_entry >> 2) & 0xfffffffff) << 2 + ptr = ((gpfifo_entry >> 2) & 0x3fffffffff) << 2 sz = ((gpfifo_entry >> 42) & 0x1fffff) << 2 self.buf = to_mv(ptr, sz).cast("I") self.buf_sz = sz // 4 @@ -77,7 +77,7 @@ class GPFIFO: def execute_buf(self) -> bool: while self.buf_ptr < self.buf_sz: init_off = self.buf_ptr - typ, size, subc, mthd = self._next_header() + _, size, _, mthd = self._next_header() cmd_end_off = self.buf_ptr + size while self.buf_ptr < cmd_end_off: @@ -92,7 +92,7 @@ class GPFIFO: qmd = qmd_struct_t.from_address(qmd_addr) prg_addr = qmd.program_address_lower + (qmd.program_address_upper << 32) const0 = to_mv(qmd.constant_buffer_addr_lower_0 + (qmd.constant_buffer_addr_upper_0 << 32), 0x160).cast('I') - args_cnt, vals_cnt = const0[0], const0[1] + args_cnt, vals_cnt = const0[80], const0[81] args_addr = qmd.constant_buffer_addr_lower_0 + (qmd.constant_buffer_addr_upper_0 << 32) + 0x160 args = to_mv(args_addr, args_cnt*8).cast('Q') vals = to_mv(args_addr + args_cnt*8, vals_cnt*4).cast('I') @@ -151,7 +151,7 @@ class GPFIFO: assert lanes == 1, f"unsupported lanes > 1 in _exec_nvc6c0_dma: {lanes}" flags = self._next_dword() assert flags == 0x41, f"unsupported flags in _exec_nvc6c0_dma: {flags}" - typ, dsize, subc, mthd = self._next_header() + typ, dsize, _, mthd = self._next_header() assert typ == 6 and mthd == nv_gpu.NVC6C0_LOAD_INLINE_DATA, f"Expected inline data not found after nvc6c0_dma, {typ=} {mthd=}" copy_data = [self._next_dword() for _ in range(dsize)] assert len(copy_data) * 4 == sz, f"different copy sizes in _exec_nvc6c0_dma: {len(copy_data) * 4} != {sz}" diff --git a/tinygrad_repo/test/mockgpu/usb.py b/tinygrad_repo/test/mockgpu/usb.py new file mode 100644 index 0000000000..460b46100e --- /dev/null +++ b/tinygrad_repo/test/mockgpu/usb.py @@ -0,0 +1,16 @@ +class MockUSB: + def __init__(self, mem): + self.mem = mem + + def read(self, address, size): + return bytes(self.mem[address:address+size]) + + def write(self, address, data, ignore_cache=False): + self.mem[address:address+len(data)] = data + + def pcie_mem_req(self, address, value=None, size=1): + if value is None: return int.from_bytes(self.mem[address:address+size], "little") + else: self.mem[address:address+size] = value.to_bytes(size, "little") + + def pcie_mem_write(self, address, values, size): + for i, value in enumerate(values): self.pcie_mem_req(address + i * size, value, size) diff --git a/tinygrad_repo/test/models/test_mnist.py b/tinygrad_repo/test/models/test_mnist.py index e51555f507..2f5e939862 100644 --- a/tinygrad_repo/test/models/test_mnist.py +++ b/tinygrad_repo/test/models/test_mnist.py @@ -49,7 +49,7 @@ class TinyConvNet: x = x.reshape(shape=[x.shape[0], -1]) return x.dot(self.l1) -@unittest.skipIf(CI and Device.DEFAULT == "CLANG", "slow") +@unittest.skipIf(CI and Device.DEFAULT == "CPU", "slow") class TestMNIST(unittest.TestCase): def test_sgd_onestep(self): np.random.seed(1337) diff --git a/tinygrad_repo/test/models/test_onnx.py b/tinygrad_repo/test/models/test_onnx.py index ae995d3772..d1b7def35e 100644 --- a/tinygrad_repo/test/models/test_onnx.py +++ b/tinygrad_repo/test/models/test_onnx.py @@ -7,7 +7,7 @@ try: import onnx except ModuleNotFoundError: raise unittest.SkipTest("onnx not installed, skipping onnx test") -from extra.onnx import get_run_onnx +from tinygrad.frontend.onnx import OnnxRunner from tinygrad.tensor import Tensor from tinygrad.helpers import CI, fetch, temp @@ -26,7 +26,7 @@ np.random.seed(1337) class TestOnnxModel(unittest.TestCase): def test_benchmark_openpilot_model(self): onnx_model = onnx.load(fetch(OPENPILOT_MODEL)) - run_onnx = get_run_onnx(onnx_model) + run_onnx = OnnxRunner(onnx_model) def get_inputs(): np_inputs = { "input_imgs": np.random.randn(*(1, 12, 128, 256)), @@ -70,7 +70,7 @@ class TestOnnxModel(unittest.TestCase): def test_openpilot_model(self): onnx_model = onnx.load(fetch(OPENPILOT_MODEL)) - run_onnx = get_run_onnx(onnx_model) + run_onnx = OnnxRunner(onnx_model) print("got run_onnx") inputs = { "input_imgs": np.random.randn(*(1, 12, 128, 256)), @@ -97,7 +97,7 @@ class TestOnnxModel(unittest.TestCase): 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) + np.testing.assert_allclose(tinygrad_out, torch_out, atol=1e-4, rtol=1e-2) @unittest.skip("slow") def test_efficientnet(self): @@ -124,7 +124,7 @@ class TestOnnxModel(unittest.TestCase): onnx_model = onnx.load(fn) print("onnx loaded") from test.models.test_efficientnet import chicken_img, car_img, preprocess, _LABELS - run_onnx = get_run_onnx(onnx_model) + run_onnx = OnnxRunner(onnx_model) def run(img): inputs = {input_name: preprocess(img, new=input_new)} diff --git a/tinygrad_repo/test/models/test_real_world.py b/tinygrad_repo/test/models/test_real_world.py index c22ed5bb73..fd19e728b3 100644 --- a/tinygrad_repo/test/models/test_real_world.py +++ b/tinygrad_repo/test/models/test_real_world.py @@ -14,6 +14,7 @@ from examples.hlb_cifar10 import SpeedyResNet, hyp from examples.llama import Transformer as LLaMaTransformer from examples.stable_diffusion import UNetModel, unet_params from extra.models.unet import ResBlock +from extra.models.bert import BertForPretraining global_mem_used = 0 def helper_test(nm, gen, model, max_memory_allowed, max_kernels_allowed, all_jitted=False): @@ -33,7 +34,7 @@ def helper_test(nm, gen, model, max_memory_allowed, max_kernels_allowed, all_jit kernels_used = len(model.jit_cache) if hasattr(model, "jit_cache") else None print(f"{nm}: used {mem_used/1e9:.2f} GB and {kernels_used} kernels in {min(tms)/1e6:.2f} ms") assert mem_used/1e9 < max_memory_allowed, f"{nm} used more than {max_memory_allowed:.2f} GB - {mem_used/1e9:.2} GB used" - assert not kernels_used or kernels_used <= max_kernels_allowed, f"{nm} used more than {max_kernels_allowed} kernels" + assert not kernels_used or kernels_used <= max_kernels_allowed, f"{nm} used more than {max_kernels_allowed} kernels, it used {kernels_used}" if all_jitted: assert kernels_used > 0 and kernels_used == GlobalCounters.kernel_count or (kernels_used <= GlobalCounters.kernel_count and getattr(Device[Device.DEFAULT], "graph", None)), f"only {kernels_used} out of {GlobalCounters.kernel_count} were jitted" # noqa: E501 @@ -48,7 +49,7 @@ class TestRealWorld(unittest.TestCase): def tearDown(self): dtypes.default_float = self.old_float - @unittest.skipIf(CI and Device.DEFAULT == "CLANG", "slow, covered by METAL") + @unittest.skipIf(CI and Device.DEFAULT == "CPU", "slow, covered by METAL") @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need dtypes.float16") def test_stable_diffusion(self): params = unet_params @@ -60,7 +61,7 @@ class TestRealWorld(unittest.TestCase): derandomize_model(model) @TinyJit def test(t, t2): return model(t, Tensor([801]), t2).realize() - helper_test("test_sd", lambda: (Tensor.randn(1, 4, 64, 64),Tensor.randn(1, 77, params["ctx_dim"])), test, 18.0, 513) + helper_test("test_sd", lambda: (Tensor.randn(1, 4, 64, 64),Tensor.randn(1, 77, params["ctx_dim"])), test, 18.0, 515) def test_unet_resblock(self): model = [ResBlock(16, 24, 16) for _ in range(4)] @@ -95,7 +96,7 @@ class TestRealWorld(unittest.TestCase): with Context(JIT=0): return model(t, v).realize() helper_test("test_gpt2", lambda: (Tensor([[1,]]),Variable("pos", 1, 100).bind(1)), test, 0.23 if CI else 0.9, 137 if CI else 396, all_jitted=True) - @unittest.skipIf(CI and Device.DEFAULT == "CLANG", "slow") + @unittest.skipIf(CI and Device.DEFAULT == "CPU", "slow") def test_train_mnist(self): from examples.beautiful_mnist import Model with Tensor.train(): @@ -111,9 +112,9 @@ class TestRealWorld(unittest.TestCase): loss.backward() optimizer.step() - helper_test("train_mnist", lambda: (Tensor.randn(BS, 1, 28, 28),), train, 0.07, 63) + helper_test("train_mnist", lambda: (Tensor.randn(BS, 1, 28, 28),), train, 0.07, 93) - @unittest.skipIf(CI and Device.DEFAULT in {"CLANG", "GPU", "LLVM"}, "slow") + @unittest.skipIf(CI and Device.DEFAULT in {"CPU", "GPU", "LLVM"}, "slow") def test_train_cifar(self): with Tensor.train(): model = SpeedyResNet(Tensor.ones((12,3,2,2))) @@ -128,7 +129,7 @@ class TestRealWorld(unittest.TestCase): loss.backward() optimizer.step() - helper_test("train_cifar", lambda: (Tensor.randn(BS, 3, 32, 32),), train, (1.0/48)*BS, 123) + helper_test("train_cifar", lambda: (Tensor.randn(BS, 3, 32, 32),), train, (1.0/48)*BS, 126) @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need dtypes.float16") def test_train_cifar_hyp(self): @@ -143,5 +144,32 @@ class TestRealWorld(unittest.TestCase): final_div_factor=1./(initial_div_factor*final_lr_ratio), total_steps=4) assert not np.isnan(lr_scheduler.min_lr), "lr too small or initial_div_facotr too big for half" + def test_bert(self): + with Tensor.train(): + args_tiny = {"attention_probs_dropout_prob": 0.0, "hidden_dropout_prob": 0.0, "vocab_size": 30522, "type_vocab_size": 2, + "max_position_embeddings": 512, "hidden_size": 128, "intermediate_size": 512, "num_attention_heads": 2, "num_hidden_layers": 2} + model = BertForPretraining(**args_tiny) + optimizer = optim.LAMB(get_parameters(model)) + + @TinyJit + def train(input_ids:Tensor, segment_ids:Tensor, attention_mask:Tensor, + masked_positions:Tensor, masked_lm_ids:Tensor, masked_lm_weights:Tensor, next_sentence_labels:Tensor): + lm_logits, seq_relationship_logits = model(input_ids, attention_mask, masked_positions, segment_ids) + loss = model.loss(lm_logits, seq_relationship_logits, masked_lm_ids, masked_lm_weights, next_sentence_labels) + optimizer.zero_grad() + loss.backward() + optimizer.step() + + from examples.mlperf.helpers import get_fake_data_bert + data = get_fake_data_bert(BS=4) + for v in data.values(): v.to_(Device.DEFAULT) + + helper_test("train_bert", lambda: (data["input_ids"], data["segment_ids"], data["input_mask"], data["masked_lm_positions"], \ + data["masked_lm_ids"], data["masked_lm_weights"], data["next_sentence_labels"]), train, 0.25, 346) + + def test_bert_fuse_arange(self): + with Context(FUSE_ARANGE=1): + self.test_bert() + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/models/test_resnet.py b/tinygrad_repo/test/models/test_resnet.py index f6eb0401aa..f71d689056 100644 --- a/tinygrad_repo/test/models/test_resnet.py +++ b/tinygrad_repo/test/models/test_resnet.py @@ -9,6 +9,13 @@ class TestResnet(unittest.TestCase): model = resnet.ResNeXt50_32X4D() model.load_from_pretrained() + def test_model_load_no_fc_layer(self): + model = resnet.ResNet18(num_classes=None) + model.load_from_pretrained() + + model = resnet.ResNeXt50_32X4D(num_classes=None) + model.load_from_pretrained() + if __name__ == '__main__': unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/models/test_train.py b/tinygrad_repo/test/models/test_train.py index 6020a8e777..605e6f6de1 100644 --- a/tinygrad_repo/test/models/test_train.py +++ b/tinygrad_repo/test/models/test_train.py @@ -40,6 +40,7 @@ class TestTrain(unittest.TestCase): check_gc() @unittest.skipIf(CI, "slow") + @unittest.skipIf(Device.DEFAULT in ["METAL", "WEBGPU"], "too many buffers for webgpu and metal") def test_efficientnet(self): model = EfficientNet(0) X = np.zeros((BS,3,224,224), dtype=np.float32) @@ -56,6 +57,7 @@ class TestTrain(unittest.TestCase): train_one_step(model,X,Y) check_gc() + @unittest.skipIf(Device.DEFAULT in ["METAL", "WEBGPU"], "too many buffers for webgpu and metal") def test_transformer(self): # this should be small GPT-2, but the param count is wrong # (real ff_dim is 768*4) diff --git a/tinygrad_repo/test/models/test_whisper.py b/tinygrad_repo/test/models/test_whisper.py index 458e8b69c5..7e4b95bb94 100644 --- a/tinygrad_repo/test/models/test_whisper.py +++ b/tinygrad_repo/test/models/test_whisper.py @@ -1,7 +1,7 @@ import unittest import pathlib from examples.whisper import init_whisper, load_file_waveform, transcribe_file, transcribe_waveform -from tinygrad.helpers import CI, fetch +from tinygrad.helpers import CI, fetch, Context from tinygrad import Device, dtypes from tinygrad.device import is_dtype_supported @@ -16,7 +16,7 @@ TRANSCRIPTION_2 = "a slightly longer audio file so that we can test batch transc TEST_FILE_3_URL = 'https://homepage.ntu.edu.tw/~karchung/miniconversations/mc45.mp3' TRANSCRIPTION_3 = "Just lie back and relax. Is the level of pressure about right? Yes, it's fine, and I'd like conditioner please. Sure. I'm going to start the second lathering now. Would you like some Q-tips? How'd you like it cut? I'd like my bangs and the back trimmed, and I'd like the rest thinned out a bit and layered. Where would you like the part? On the left, right about here. Here, have a look. What do you think? It's fine. Here's a thousand anti-dollars. It's 30-ant extra for the rants. Here's your change and receipt. Thank you, and please come again. So how do you like it? It could have been worse, but you'll notice that I didn't ask her for her card. Hmm, yeah. Maybe you can try that place over there next time." # noqa: E501 -@unittest.skipIf(CI and Device.DEFAULT in ["CLANG"], "slow") +@unittest.skipIf(CI and Device.DEFAULT in ["CPU"], "slow") @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need float16 support") class TestWhisper(unittest.TestCase): @classmethod @@ -24,15 +24,25 @@ class TestWhisper(unittest.TestCase): model, enc = init_whisper("tiny.en", batch_size=2) cls.model = model cls.enc = enc + # TODO: whisper has out of bounds access somewhere + cls.context = Context(IGNORE_OOB=1) + cls.context.__enter__() @classmethod def tearDownClass(cls): + cls.context.__exit__(None, None, None) del cls.model del cls.enc def test_transcribe_file1(self): self.assertEqual(transcribe_file(self.model, self.enc, TEST_FILE_1), TRANSCRIPTION_1) + @unittest.expectedFailure # Test for out of bounds access + @unittest.skip("TODO: flaky") + def test_transcribe_file1_OOB(self): + with Context(IGNORE_OOB=0): + self.assertEqual(transcribe_file(self.model, self.enc, TEST_FILE_1), TRANSCRIPTION_1) + @unittest.skipIf(CI or Device.DEFAULT == "LLVM", "too many tests for CI") def test_transcribe_file2(self): self.assertEqual(transcribe_file(self.model, self.enc, TEST_FILE_2), TRANSCRIPTION_2) diff --git a/tinygrad_repo/test/test_amd_llvm.py b/tinygrad_repo/test/test_amd_llvm.py new file mode 100644 index 0000000000..9fb9fa333c --- /dev/null +++ b/tinygrad_repo/test/test_amd_llvm.py @@ -0,0 +1,52 @@ +import unittest +import numpy as np +from tinygrad import Device +from tinygrad.device import CompileError +from tinygrad.helpers import flat_mv +if Device.DEFAULT=="AMD": + from tinygrad.runtime.ops_amd import AMDAllocator, AMDDevice, AMDProgram + from tinygrad.runtime.support.compiler_amd import AMDLLVMCompiler + +@unittest.skipUnless(Device.DEFAULT == "AMD", "Runs only on AMD") +class TestAMDLLVM(unittest.TestCase): + def test_compiler(self): + src = ''' +; https://github.com/llvm/llvm-project/blob/main/llvm/test/CodeGen/AMDGPU/imm.ll +define amdgpu_kernel void @i64_imm_inline_lo(ptr addrspace(1) %out) { +entry: + store i64 1311768464867721221, ptr addrspace(1) %out ; 0x1234567800000005 + ret void +} + ''' + device = AMDDevice() + compiler = AMDLLVMCompiler("gfx1100") + obj = compiler.compile(src) + allocator = AMDAllocator(device) + a = allocator.alloc(1*8) + prog = AMDProgram(device, "test", obj) + prog(a, wait=True) + na = np.empty(1, np.uint64) + allocator._copyout(flat_mv(na.data), a) + assert na == [0x1234567800000005] + + def test_compiler_diag_error(self): + src = """ +@local_temp0 = internal unnamed_addr addrspace(3) global [{N} x float*] undef, align 16 +define amdgpu_kernel void @test(float* noalias align 32 %data0, half* noalias align 32 %data1, float* noalias align 32 %data2) #0 +{{ + %local_temp0 = addrspacecast [{N} x float*] addrspace(3)* @local_temp0 to [{N} x float*]* + %v178 = getelementptr inbounds float, float* %local_temp0, i32 1 + %v133 = getelementptr inbounds float, float* %data2, i32 1 + %v134 = load float, float* %v133 + store float %v134, float* %v178 + ret void +}} +""" + compiler = AMDLLVMCompiler("gfx1100") + compiler.compile(src.format(N=65536//8)) + with self.assertRaises(CompileError): + # llvm diagnostic: :0:0: local memory (65544) exceeds limit (65536) in function 'test' + compiler.compile(src.format(N=65536//8+1)) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_arange.py b/tinygrad_repo/test/test_arange.py index d8a215faab..0eec281f0c 100644 --- a/tinygrad_repo/test/test_arange.py +++ b/tinygrad_repo/test/test_arange.py @@ -1,12 +1,12 @@ import unittest, contextlib import numpy as np -from tinygrad import Tensor, GlobalCounters, dtypes, nn, Device +from tinygrad import Tensor, GlobalCounters, dtypes, nn, Device, Variable from tinygrad.helpers import CI, Context, getenv from tinygrad.engine.realize import run_schedule from tinygrad.codegen.kernel import Opt, OptOps, Kernel, KernelOptError from tinygrad.engine.realize import CompiledRunner, ExecItem from tinygrad.engine.search import get_kernel_actions -from tinygrad.ops import Ops +from tinygrad.uop.ops import Ops class TestArange(unittest.TestCase): def _get_flops(self, N, opts=None): @@ -25,23 +25,31 @@ class TestArange(unittest.TestCase): return p.estimates.ops def test_complexity(self, opts=None, limit=None): - # add 1 to avoid divide by 0. arange is 0 flops now! - f1 = self._get_flops(256, opts) + 1 - f2 = self._get_flops(2560, opts) + 1 + f1 = self._get_flops(256, opts) + f2 = self._get_flops(2560, opts) print(f"{f1=}, {f2=}") - assert (f1 < 5000 and f2 < 5000) or (f2 / f1 < 15), f"bad complexity, flops {f2/f1:.1f}X while inputs 10X" + # add 1 to avoid divide by 0. arange is 0 flops now! + assert (f1 < 6000 and f2 < 6000) or ((f2+1) / (f1+1) < 16), f"bad complexity, flops {(f2+1) / (f1+1):.1f}X while inputs 10X" if limit is not None and not getenv("PTX"): # PTX counts index ALU in flops assert f1 <= limit, f"{f1=}, {limit=}" - def test_complexity_w_upcast(self): return self.test_complexity([Opt(OptOps.UPCAST, 0, 4)], limit=1) - def test_complexity_w_unroll2(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 2)], limit=1) - def test_complexity_w_unroll4(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 4)], limit=1) - def test_complexity_w_unroll8(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 8)], limit=1) - def test_complexity_w_upcast_and_unroll(self): return self.test_complexity([Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UNROLL, 0, 4)], limit=1) + def test_complexity_w_upcast(self): return self.test_complexity([Opt(OptOps.UPCAST, 0, 4)], limit=0) + def test_complexity_w_unroll2(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 2)], limit=0) + def test_complexity_w_unroll4(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 4)], limit=0) + def test_complexity_w_unroll8(self): return self.test_complexity([Opt(OptOps.UNROLL, 0, 8)], limit=0) + def test_complexity_w_upcast_and_unroll(self): return self.test_complexity([Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UNROLL, 0, 4)], limit=0) - @unittest.skip("doesn't work yet") - def test_complexity_w_local_and_padto(self): return self.test_complexity([Opt(OptOps.LOCAL, 0, 16), Opt(op=OptOps.PADTO, axis=1, amt=32)]) + if Device.default.renderer.has_local: + # TODO: fix limit + def test_complexity_w_group(self): return self.test_complexity([Opt(OptOps.GROUP, 0, 16)], limit=81920) + def test_complexity_w_group_top(self): return self.test_complexity([Opt(OptOps.GROUPTOP, 0, 16)], limit=106496) + + def test_complexity_w_local(self): return self.test_complexity([Opt(OptOps.LOCAL, 0, 16)], limit=0) + @unittest.skip("doesn't work yet. TODO: this absolutely should work") + def test_complexity_w_local_unroll4(self): return self.test_complexity([Opt(OptOps.LOCAL, 0, 16), Opt(OptOps.UNROLL, 0, 4)], limit=0) + @unittest.skip("doesn't work yet") + def test_complexity_w_local_and_padto(self): return self.test_complexity([Opt(OptOps.LOCAL, 0, 16), Opt(OptOps.PADTO, axis=1, arg=32)]) def test_all_opts(self, opts=None, exclude=None): k = Kernel(Tensor.arange(256).schedule()[-1].ast) @@ -59,75 +67,102 @@ class TestArange(unittest.TestCase): self.test_complexity(opts) def test_all_opts_w_local(self): with contextlib.suppress(KernelOptError): - return self.test_all_opts([Opt(OptOps.LOCAL, 0, 16)], [Opt(op=OptOps.PADTO, axis=1, amt=32)]) + return self.test_all_opts([Opt(OptOps.LOCAL, 0, 16)], [Opt(op=OptOps.PADTO, axis=1, arg=32)]) def test_all_opts_w_upcast(self): return self.test_all_opts([Opt(OptOps.UPCAST, 0, 4)]) - def test_all_opts_w_unroll(self): return self.test_all_opts([Opt(OptOps.UNROLL, 0, 4)], [Opt(op=OptOps.GROUP, axis=0, amt=0)]) + def test_all_opts_w_unroll(self): return self.test_all_opts([Opt(OptOps.UNROLL, 0, 4)], [Opt(op=OptOps.GROUP, axis=0, arg=0)]) def test_all_opts_w_upcast_and_unroll(self): - return self.test_all_opts([Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UNROLL, 0, 4)], [Opt(op=OptOps.GROUP, axis=0, amt=0)]) + return self.test_all_opts([Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UNROLL, 0, 4)], [Opt(op=OptOps.GROUP, axis=0, arg=0)]) + +class TestRand(unittest.TestCase): + def test_fused_rand_less_ops(self, noopt=1): + GlobalCounters.reset() + with Context(FUSE_ARANGE=0, NOOPT=noopt): + out = Tensor.rand(16384) + out.realize() + unfused_ops = GlobalCounters.global_ops + + GlobalCounters.reset() + with Context(FUSE_ARANGE=1, NOOPT=noopt): + out = Tensor.rand(16384) + out.realize() + print(f"fused {GlobalCounters.global_ops} unfused {unfused_ops}") + self.assertLessEqual(GlobalCounters.global_ops, unfused_ops*2) + def test_fused_rand_less_ops_opt(self): self.test_fused_rand_less_ops(0) + +DSET, DDIM = 2048, 32 class TestIndexing(unittest.TestCase): - @unittest.expectedFailure def test_arange_2_reduce(self): needle = Tensor.zeros(16384, dtype=dtypes.int).contiguous() needle[1337] = 1 needle.realize() with Context(NOOPT=1, FUSE_ARANGE=1): GlobalCounters.reset() - # TODO: it should work without these reshapes - out = ((Tensor.arange(1,16385).reshape(16384,1)-1)*needle.reshape(16384,1)).sum() + out = ((Tensor.arange(1,16385)-1)*needle).sum() sched = out.schedule() - assert len(sched) == 1 + self.assertEqual(len(sched), 1) run_schedule(sched) - assert out.item() == 1337, f"expected 1337, got {out.item()}" + self.assertEqual(out.item(), 1337) @unittest.skipIf(getenv("PTX"), "broken on ptx for some reason") def test_manual_index(self): - dataset = Tensor.rand(16384, 256).realize() + dataset = Tensor.rand(DSET, DDIM).realize() idxs = Tensor([0,3,5,6]).realize() real_index = dataset.numpy()[idxs.numpy()] print("*** indexing ***") with Context(NOOPT=1, FUSE_ARANGE=1): GlobalCounters.reset() - rng = Tensor.ones(4, 256, 16384, dtype=dtypes.int)._cumalu(axis=-1, op=Ops.ADD, _include_initial=True).reshape(4, 256, 16384, 1) - idxs = idxs.reshape(4,1,1,1).expand(4, 256, 16384, 1) - reshape_dataset = dataset.T.reshape(1, 256, 16384, 1).expand(4, 256, 16384, 1) - full = (rng==idxs).where(reshape_dataset, Tensor.zeros(4, 256, 16384, 1)) + rng = Tensor.ones(4, DDIM, DSET, dtype=dtypes.int)._cumalu(axis=-1, op=Ops.ADD, _include_initial=True).reshape(4, DDIM, DSET, 1) + idxs = idxs.reshape(4,1,1,1).expand(4, DDIM, DSET, 1) + reshape_dataset = dataset.T.reshape(1, DDIM, DSET, 1).expand(4, DDIM, DSET, 1) + full = (rng==idxs).where(reshape_dataset, Tensor.zeros(4, DDIM, DSET, 1)) X = full.sum(axis=(2,3)) sched = X.schedule() - assert len(sched) == 1 + self.assertEqual(len(sched), 1) run_schedule(sched) - assert GlobalCounters.global_ops < 4*16384, f"too many ops {GlobalCounters.global_ops}" + assert GlobalCounters.global_ops < 4*DSET, f"too many ops {GlobalCounters.global_ops}" np.testing.assert_allclose(real_index, X.numpy()) + def test_index_variable(self): + dataset = Tensor.rand(DSET, DDIM).realize() + v = Variable("v", 0, DDIM-1) + with Context(NOOPT=1, FUSE_ARANGE=1, SPLIT_REDUCEOP=0): + GlobalCounters.reset() + vb = Tensor(v.bind(12)) + comp = dataset[vb].numpy() + # no global ops because they are all indexing + self.assertEqual(GlobalCounters.global_ops, 0) + np.testing.assert_allclose(comp, dataset.numpy()[12]) + def test_index(self): - dataset = Tensor.rand(16384, 256).realize() + dataset = Tensor.rand(DSET, DDIM).realize() idxs = Tensor([0,3,5,6]).realize() real_index = dataset.numpy()[idxs.numpy()] print("*** indexing ***") with Context(NOOPT=1): GlobalCounters.reset() X = dataset[idxs] - assert X.shape == (4,256) + assert X.shape == (4,DDIM) sched = X.schedule() # TODO: enable these asserts when the scheduler can handle this - #assert len(sched) == 1, f"{len(sched)} != 1" + #self.assertEqual(len(sched), 1) run_schedule(sched) - #assert GlobalCounters.global_ops < 4*16384, f"too many ops {GlobalCounters.global_ops}" + #assert GlobalCounters.global_ops < 4*DSET, f"too many ops {GlobalCounters.global_ops}" np.testing.assert_allclose(real_index, X.numpy()) def test_index_fused(self, noopt=1): - dataset = Tensor.rand(16384, 256).realize() + dataset = Tensor.rand(DSET, DDIM).realize() idxs = Tensor([0,3,5,6]).realize() real_index = dataset.numpy()[idxs.numpy()] print("*** indexing ***") with Context(NOOPT=noopt, FUSE_ARANGE=1): GlobalCounters.reset() X = dataset[idxs] - assert X.shape == (4,256) + assert X.shape == (4,DDIM) sched = X.schedule() - assert len(sched) == 2 + self.assertEqual(len(sched), 2) run_schedule(sched) - assert GlobalCounters.global_ops < 4*16384, f"too many ops {GlobalCounters.global_ops} != {4*16384}" + assert GlobalCounters.global_ops < 4*DSET, f"too many ops {GlobalCounters.global_ops} != {4*DSET}" np.testing.assert_allclose(real_index, X.numpy()) @unittest.skip("not ready") def test_index_fused_opt(self): self.test_index_fused(0) @@ -140,10 +175,10 @@ class TestIndexing(unittest.TestCase): np.testing.assert_equal(X.numpy(), 0) @unittest.skipIf(getenv("PTX"), "broken on ptx for some reason") - def test_index_mnist(self, noopt=1, op_limit=512*784*13): + def test_index_mnist(self, noopt=1, op_limit=512*784*13, split_reduceop=0): from tinygrad.nn.datasets import mnist X_train, Y_train, _, _ = mnist() - with Context(NOOPT=noopt, FUSE_ARANGE=1, SPLIT_REDUCEOP=0): + with Context(NOOPT=noopt, FUSE_ARANGE=1, SPLIT_REDUCEOP=split_reduceop): samples = Tensor.randint(getenv("BS", 512), high=X_train.shape[0]).realize() GlobalCounters.reset() x = X_train[samples].numpy() @@ -151,15 +186,22 @@ class TestIndexing(unittest.TestCase): assert GlobalCounters.global_ops < op_limit, f"too many ops {GlobalCounters.global_ops} != {op_limit}" np.testing.assert_allclose(X_train.numpy()[samples.numpy()], x) np.testing.assert_allclose(Y_train.numpy()[samples.numpy()], y) - @unittest.skip("not ready") + + # TODO: fix these on WEBGPU, it looks like it has to do with packed stuff + @unittest.skipIf(getenv("WEBGPU"), "broken on webgpu for some reason") def test_index_mnist_opt(self): self.test_index_mnist(0) + @unittest.skipIf(getenv("WEBGPU"), "broken on webgpu for some reason") + def test_index_mnist_split(self): self.test_index_mnist(1, split_reduceop=1) + @unittest.skipIf(getenv("WEBGPU"), "broken on webgpu for some reason") + def test_index_mnist_opt_split(self): self.test_index_mnist(0, split_reduceop=1) - @unittest.skipIf(getenv("PTX") or Device.DEFAULT == "WEBGPU", "broken on ptx and WebGPU for some reason") + @unittest.skipIf(getenv("PTX"), "broken on ptx for some reason") def test_llama_embedding(self, noopt=1, op_limit=65536): # llama3 is 128256 vocab_size, embed_size = (10, 3) if CI else (32000, 4096) emb = nn.Embedding(vocab_size, embed_size) - emb_w = emb.weight.numpy() + # TODO: why is a new realize needed here + emb_w = emb.weight.realize().numpy() x = Tensor([1,2,3,4]) with Context(NOOPT=noopt, FUSE_ARANGE=1): GlobalCounters.reset() diff --git a/tinygrad_repo/test/test_assign.py b/tinygrad_repo/test/test_assign.py index f5d42ee73c..6f8a7b8039 100644 --- a/tinygrad_repo/test/test_assign.py +++ b/tinygrad_repo/test/test_assign.py @@ -2,6 +2,8 @@ import unittest import numpy as np from tinygrad import dtypes, Tensor, TinyJit, GlobalCounters, Variable +from tinygrad.device import is_dtype_supported +from tinygrad.helpers import temp N = 200 # has to be bigger than the cache to fail @@ -201,6 +203,7 @@ class TestAssign(unittest.TestCase): np.testing.assert_equal(b0.numpy(), 128) np.testing.assert_equal(b1.numpy(), 608) + @unittest.skip("TODO: bring this assert back") def test_crossunder_assign(self): # NOTE: should *not* raise AssertionError from numpy with self.assertRaisesRegex(RuntimeError, "cycle"): @@ -282,6 +285,7 @@ class TestAssign(unittest.TestCase): #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)) + @unittest.skip("multi output not supported anymore") def test_simple_assignment_multioutput(self): a = Tensor.randn(32, 32).realize() b = Tensor.full((32, ), 1.).contiguous().realize() @@ -320,6 +324,7 @@ class TestAssign(unittest.TestCase): b.assign(r + b.permute(1, 0)) b.realize() + @unittest.skip("multi output not supported anymore") def test_permuted_reduceop_multioutput_dual_use(self): a = Tensor.randn(32, 32, 32).realize() b = Tensor.full((32, 32), 1.).contiguous().realize() @@ -332,6 +337,7 @@ class TestAssign(unittest.TestCase): c.assign(r + b_perm) Tensor.realize(b, c) + @unittest.skip("multi output not supported anymore") def test_permuted_reduceop_multioutput_dual_use_possible(self): a = Tensor.randn(32, 32, 32, dtype=dtypes.int).realize() b = Tensor.arange(32 * 32).reshape(32, 32).realize() @@ -365,6 +371,14 @@ class TestAssign(unittest.TestCase): # TODO: is there a way to sneak in a permute such that it returns the wrong answer? + @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + def test_setitem_half(self): + a = Tensor.full((8,), 1.0, dtype=dtypes.half).contiguous().realize() + b = Tensor.full((4,), 2.0, dtype=dtypes.half).contiguous().realize() + assign = a[:4].assign(b) + assign.realize() + np.testing.assert_allclose(a.numpy(), [2., 2., 2., 2., 1., 1., 1., 1.]) + @unittest.skip("don't use output buffer, and mismatch dtype no longer supported") def test_cast_assignment(self): a = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) @@ -376,5 +390,9 @@ class TestAssign(unittest.TestCase): assert oba1 is None and oba2 is None np.testing.assert_allclose(a.numpy(), np.arange(N*N,dtype=np.int32).reshape((N,N))) + def test_disk_assignment(self): + a = Tensor.empty(5, device=f"disk:{temp('disk_assignment')}").assign(Tensor.ones(5)).numpy() + np.testing.assert_equal(a, np.ones(5)) + if __name__ == "__main__": unittest.main() diff --git a/tinygrad_repo/test/test_const_folding.py b/tinygrad_repo/test/test_const_folding.py index 287bac476f..f1f054da63 100644 --- a/tinygrad_repo/test/test_const_folding.py +++ b/tinygrad_repo/test/test_const_folding.py @@ -1,14 +1,16 @@ -import unittest, math +import unittest, itertools, math +from typing import Any from tinygrad import Tensor, Device, dtypes -from tinygrad.ops import Ops -from tinygrad.engine.schedule import create_schedule -from tinygrad.helpers import CI +from tinygrad.dtype import DType +from tinygrad.uop.ops import Ops, UOp +from tinygrad.codegen import full_rewrite_to_sink import numpy as np from tinygrad.device import is_dtype_supported +from test.helpers import not_support_multi_device def _check_ast_count(desired_count:int, t:Tensor): # NOTE: this has side effect because everything can be scheduled only once - schedule = create_schedule(t.lazydata.lbs) + schedule = t.schedule() asts = [s for s in schedule if s.ast.op is Ops.SINK] assert len(asts) == desired_count, f"{len(asts)} != {desired_count}" @@ -95,19 +97,50 @@ class TestBinaryOpsConstFolding(unittest.TestCase): _check_ast_count(0, Tensor([1.0, 2, 3, 4]) ** Tensor.ones(4)) def test_literal_one_pow(self): _check_ast_count(0, 1 ** Tensor([1.0, 2, 3, 4])) - # this fails because of DETACH, it shouldn't - @unittest.expectedFailure def test_tensor_one_pow(self): _check_ast_count(0, Tensor.ones(4) ** Tensor([1.0, 2, 3, 4])) +class TestBitcastConstFolding(unittest.TestCase): + def test_scalar_bitcast(self): + def t(cases: dict[DType, Any]): + for (from_dt, from_v), (to_dt, to_v) in itertools.product(cases.items(), cases.items()): + if not math.isnan(from_v): + r = full_rewrite_to_sink(UOp.const(from_dt, from_v).bitcast(to_dt).sink()).src[0] + self.assertEqual(r.op, Ops.CONST, msg:=f"{from_dt} -> {to_dt} ({from_v} -> {to_v})") + self.assertEqual(r.dtype, to_dt, msg) + np.testing.assert_equal(r.arg, to_v, msg) + + t({dtypes.int8: 0, dtypes.uint8: 0, dtypes.bool: False}) + t({dtypes.int8: 1, dtypes.uint8: 1, dtypes.bool: True}) + + t({dtypes.int8: -1, dtypes.uint8: 2**8-1}) + t({dtypes.int16: -1, dtypes.uint16: 2**16-1, dtypes.float16: float('nan')}) + t({dtypes.int32: -1, dtypes.uint32: 2**32-1, dtypes.float32: float('nan')}) + t({dtypes.int64: -1, dtypes.uint64: 2**64-1, dtypes.float64: float('nan')}) + + t({dtypes.int8: -2**7, dtypes.uint8: 2**7}) + t({dtypes.int16: -2**15, dtypes.uint16: 2**15}) + t({dtypes.int32: -2**31, dtypes.uint32: 2**31}) + t({dtypes.int64: -2**63, dtypes.uint64: 2**63}) + + t({dtypes.int16: 13496, dtypes.uint16: 13496, dtypes.float16: 0.294921875}) + t({dtypes.int32: 1050081145, dtypes.uint32: 1050081145, dtypes.float32: 0.29485681653022766}) + t({dtypes.int64: 4598983288165178391, dtypes.uint64: 4598983288165178391, dtypes.float64: 0.29485681936461233}) + + def test_vec_bitcast(self): + r = full_rewrite_to_sink(UOp.const(dtypes.int32.vec(3), (-1, -2**31, 75)).bitcast(dtypes.uint32.vec(3)).sink()).src[0] + self.assertEqual(r.op, Ops.VECTORIZE) + self.assertEqual(r.dtype, dtypes.uint32.vec(3)) + self.assertEqual(tuple(x.arg for x in r.src), (2**32-1, 2**31, 75)) + # folds advance indexing into basic indexing class TestIndexingConstFolding(unittest.TestCase): def test_scalar_index(self): t = Tensor.arange(16).float().reshape(1,1,4,4).realize() - _check_ast_count(0, t[:,:,Tensor(1),:]) - # NOTE: this is no longer supported because the 1+2 isn't folding early. - #_check_ast_count(0, t[:,:,Tensor(1)+2,:]) - _check_ast_count(0, t[:,:,Tensor(1),Tensor(0)]) + # TODO: fold these + _check_ast_count(2, t[:,:,Tensor(1),:]) + _check_ast_count(2, t[:,:,Tensor(1)+2,:]) + _check_ast_count(2, t[:,:,Tensor(1),Tensor(0)]) @unittest.expectedFailure def test_const_tensor_index(self): @@ -186,7 +219,7 @@ class TestReduceOpsConstFolding(unittest.TestCase): # contiguous folded const can still schedule a = Tensor.empty(1, 0).sum().contiguous() _check_ast_count(2, a+2) - self.assertIsNotNone(a.lazydata.base.realized) + self.assertIs(a.lazydata.base.op, Ops.BUFFER) np.testing.assert_equal((Tensor.empty(1, 0).sum().contiguous()+2).numpy(), 2) # otherwise we just fuse it _check_ast_count(1, (Tensor.empty(1, 0).sum()+2).contiguous()) @@ -213,11 +246,11 @@ class TestReduceOpsConstFolding(unittest.TestCase): t = Tensor.ones(16, dtype=dt).reshape(4, 4) assert t.sum().dtype == t.contiguous().sum().dtype -@unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU CI") +@unittest.skipIf(not_support_multi_device(), "no multi") class TestMultiConstFolding(unittest.TestCase): def test_multi_const_folding_literal(self): ds = tuple(f"{Device.DEFAULT}:{i}" for i in range(4)) - t = Tensor.arange(16).float().realize().to(ds) + t = Tensor.arange(16).float().to(ds).realize() # non const folding case creates one ast on each shard _check_ast_count(4, t + 1) @@ -242,9 +275,9 @@ class TestMultiConstFolding(unittest.TestCase): def test_multi_const_folding_tensor(self): ds = tuple(f"{Device.DEFAULT}:{i}" for i in range(4)) - t = Tensor.arange(16).float().realize().to(ds) - zero = Tensor.zeros(16).realize().to(ds) - one = Tensor.ones(16).realize().to(ds) + t = Tensor.arange(16).float().to(ds).realize() + zero = Tensor.zeros(16).to(ds).realize() + one = Tensor.ones(16).to(ds).realize() # const folded _check_ast_count(0, t + zero) @@ -257,12 +290,11 @@ class TestMultiConstFolding(unittest.TestCase): np.testing.assert_equal((t * zero).numpy(), [0] * 16) np.testing.assert_equal((t * one).numpy(), np.arange(16)) - @unittest.expectedFailure def test_multi_todo_pow(self): ds = tuple(f"{Device.DEFAULT}:{i}" for i in range(4)) - t = Tensor.arange(16).float().realize().to(ds) - zero = Tensor.zeros(16).realize().to(ds) - one = Tensor.ones(16).realize().to(ds) + t = Tensor.arange(16).float().to(ds).realize() + zero = Tensor.zeros(16).to(ds).realize() + one = Tensor.ones(16).to(ds).realize() # TODO: fix pow folding _check_ast_count(0, t ** zero) diff --git a/tinygrad_repo/test/test_conv_shapetracker.py b/tinygrad_repo/test/test_conv_shapetracker.py index 36e9956d1e..e812827ac1 100644 --- a/tinygrad_repo/test/test_conv_shapetracker.py +++ b/tinygrad_repo/test/test_conv_shapetracker.py @@ -1,9 +1,8 @@ #!/usr/bin/env python import unittest -from tinygrad.ops import Ops +from tinygrad.uop.ops import Ops from tinygrad.tensor import Tensor from tinygrad.nn import Conv2d -from tinygrad.engine.schedule import create_schedule from tinygrad.shape.shapetracker import ShapeTracker, View from tinygrad.helpers import prod from test.unit.test_shapetracker import shapetracker_getitem @@ -11,13 +10,12 @@ from test.unit.test_shapetracker import shapetracker_getitem class TestConvShapetracker(unittest.TestCase): def test_conv_3x3_one_view(self): conv = Conv2d(16, 32, (3, 3)) - # first run to init the weights, they are scheduled. - create_schedule([conv(Tensor.empty(1, 16, 10, 10)).lazydata]) + conv(Tensor.empty(1, 16, 10, 10)).schedule() # run it again to get the kernels - sched = [si for si in create_schedule([conv(Tensor.empty(1, 16, 10, 10)).lazydata]) if si.ast.op is Ops.SINK] + sched = [si for si in conv(Tensor.empty(1, 16, 10, 10)).schedule() if si.ast.op is Ops.SINK] assert len(sched) == 1, f"conv should only have one kernel, getting {len(sched)}" - for st in [x.st_arg for x in sched[0].ast.toposort if x.op is Ops.LOAD]: + for st in [x.st_arg for x in sched[0].ast.toposort() if x.op is Ops.LOAD]: assert len(st.views) == 1 def test_conv_2x2_backward_one_view(self): @@ -26,11 +24,10 @@ class TestConvShapetracker(unittest.TestCase): conv(X).mean().backward() si = X.grad.schedule()[-1] print(si) - ldb = [x for x in si.ast.toposort if x.op is Ops.LOAD][0] + ldb = [x for x in si.ast.toposort() if x.op is Ops.LOAD][0] st: ShapeTracker = ldb.st_arg.simplify() - # NOTE: st.real_size() is broken - print(si.inputs[0].size) - #self.assertEqual(si.inputs[0].size, st.real_size()) + print(si.bufs[1].size) + self.assertEqual(si.bufs[1].size, st.real_size()) for v in st.views: print(v) # same st @@ -48,7 +45,7 @@ class TestConvShapetracker(unittest.TestCase): for v in test_st.views: print(v) for i in range(prod(st.shape)): i1, i2 = shapetracker_getitem(st, i), shapetracker_getitem(test_st, i) - print(i, i1, i2, si.inputs[0].size, i1==i2) + print(i, i1, i2, si.bufs[1].size, i1==i2) #self.assertEqual(i1, i2) with self.assertRaises(AssertionError): diff --git a/tinygrad_repo/test/test_copy_speed.py b/tinygrad_repo/test/test_copy_speed.py index 185c0e357c..5d0cc69c26 100644 --- a/tinygrad_repo/test/test_copy_speed.py +++ b/tinygrad_repo/test/test_copy_speed.py @@ -24,7 +24,7 @@ class TestCopySpeed(unittest.TestCase): s.unlink() def testCopyCPUtoDefault(self): - t = Tensor.rand(N, N, device="clang").realize() + t = Tensor.ones(N, N, device="CPU").contiguous().realize() print(f"buffer: {t.nbytes()*1e-9:.2f} GB") for _ in range(3): with Timing("sync: ", on_exit=lambda ns: f" @ {t.nbytes()/ns:.2f} GB/s"): @@ -35,7 +35,7 @@ class TestCopySpeed(unittest.TestCase): def testCopyCPUtoDefaultFresh(self): print("fresh copy") for _ in range(3): - t = Tensor.rand(N, N, device="clang").realize() + t = Tensor.ones(N, N, device="CPU").contiguous().realize() with Timing("sync: ", on_exit=lambda ns: f" @ {t.nbytes()/ns:.2f} GB/s"): # noqa: F821 with Timing("queue: "): t.to(Device.DEFAULT).realize() @@ -43,18 +43,18 @@ class TestCopySpeed(unittest.TestCase): del t def testCopyDefaulttoCPU(self): - t = Tensor.rand(N, N).realize() + t = Tensor.ones(N, N).contiguous().realize() print(f"buffer: {t.nbytes()*1e-9:.2f} GB") for _ in range(3): with Timing("sync: ", on_exit=lambda ns: f" @ {t.nbytes()/ns:.2f} GB/s"): - t.to('clang').realize() + t.to('CPU').realize() @unittest.skipIf(CI, "CI doesn't have 6 GPUs") @unittest.skipIf(Device.DEFAULT != "GPU", "only test this on GPU") def testCopyCPUto6GPUs(self): from tinygrad.runtime.ops_gpu import CLDevice if len(CLDevice.device_ids) != 6: raise unittest.SkipTest("computer doesn't have 6 GPUs") - t = Tensor.rand(N, N, device="clang").realize() + t = Tensor.ones(N, N, device="CPU").contiguous().realize() print(f"buffer: {t.nbytes()*1e-9:.2f} GB") for _ in range(3): with Timing("sync: ", on_exit=lambda ns: f" @ {t.nbytes()/ns:.2f} GB/s ({t.nbytes()*6/ns:.2f} GB/s total)"): diff --git a/tinygrad_repo/test/test_device_speed.py b/tinygrad_repo/test/test_device_speed.py index f599d691cf..efb790c9f5 100644 --- a/tinygrad_repo/test/test_device_speed.py +++ b/tinygrad_repo/test/test_device_speed.py @@ -6,7 +6,7 @@ class TestDeviceSpeed(unittest.TestCase): @classmethod def setUpClass(cls): cls.dev = Device[Device.DEFAULT] - cls.empty = Device[Device.DEFAULT].renderer.render("test", []) + cls.empty = Device[Device.DEFAULT].renderer.render([]) def test_empty_compile(self): with Timing("compiler "): diff --git a/tinygrad_repo/test/test_dtype.py b/tinygrad_repo/test/test_dtype.py index 329f7bd871..b41a9663a3 100644 --- a/tinygrad_repo/test/test_dtype.py +++ b/tinygrad_repo/test/test_dtype.py @@ -4,11 +4,13 @@ import torch from typing import Any, List from tinygrad.device import is_dtype_supported from tinygrad.helpers import getenv, DEBUG, CI -from tinygrad.dtype import DType, DTYPES_DICT, ImageDType, PtrDType, least_upper_float, least_upper_dtype, truncate_fp16, to_dtype +from tinygrad.dtype import DType, DTYPES_DICT, ImageDType, PtrDType, least_upper_float, least_upper_dtype, truncate_fp16, truncate_bf16, to_dtype +from tinygrad.dtype import truncate, fp8_to_float, float_to_fp8 from tinygrad import Device, Tensor, dtypes from tinygrad.tensor import _to_np_dtype -from hypothesis import given, settings, strategies as strat +from hypothesis import assume, given, settings, strategies as strat from test.helpers import rand_for_dtype +import ml_dtypes import pytest pytestmark = pytest.mark.filterwarnings("ignore") @@ -19,6 +21,8 @@ core_dtypes = list(DTYPES_DICT.values()) if Device.DEFAULT == "CPU": core_dtypes.remove(dtypes.bfloat16) # NOTE: this is for teenygrad, don't remove dtype_ints = [dt for dt in core_dtypes if dtypes.is_int(dt) and is_dtype_supported(dt)] dtype_floats = [dt for dt in core_dtypes if dtypes.is_float(dt) and is_dtype_supported(dt)] +FP8E4M3_MAX = 448.0 +FP8E5M2_MAX = 57344.0 def get_available_cast_dtypes(dtype: DType) -> List[DType]: if not is_dtype_supported(dtype): return [] @@ -56,6 +60,8 @@ def _test_cast(a:Tensor, target_dtype:DType): _test_op(lambda: a.cast(target_dtype), target_dtype, list(a.numpy().astype(_to_np_dtype(target_dtype)))) def _test_bitcast(a:Tensor, target_dtype:DType, target=None): if target_dtype == dtypes.bfloat16: raise unittest.SkipTest("no test for bf16 bitcast yet") + if getenv("PTX") and a.dtype == dtypes.int8 and target_dtype.itemsize != a.dtype.itemsize: + raise unittest.SkipTest("shape changing bitcast of int8 broken on PTX") _test_op(lambda: a.bitcast(target_dtype), target_dtype, target or a.numpy().view(_to_np_dtype(target_dtype)).tolist()) class TestDType(unittest.TestCase): @@ -107,7 +113,7 @@ class TestDType(unittest.TestCase): fields = dtypes.fields() self.assertIn("float", fields) self.assertIn("float32", fields) - self.assertEqual(len(fields), 24) + self.assertEqual(len(fields), 26) self.assertTrue(all(isinstance(value, DType) for value in fields.values())) self.assertTrue(all(issubclass(_to_np_dtype(value), np.generic) for value in fields.values() if _to_np_dtype(value) is not None)) @@ -140,6 +146,43 @@ def _test_ops(a_dtype:DType, b_dtype:DType, target_dtype=None): _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 TestFp8s(unittest.TestCase): + def test_fp8e4m3_creation(self): assert Tensor([-1, 1, 2], dtype=dtypes.fp8e4m3).dtype == dtypes.fp8e4m3 + def test_fp8e5m2_creation(self): assert Tensor([-1, 1, 2], dtype=dtypes.fp8e5m2).dtype == dtypes.fp8e5m2 + +class TestFp8sConversions(unittest.TestCase): + @given(strat.floats(width=32, allow_subnormal=True, allow_nan=False, allow_infinity=False, min_value=-FP8E4M3_MAX, max_value=FP8E4M3_MAX)) + def test_float_to_fp8e4m3(self, x): np.testing.assert_equal(float_to_fp8(x, dtypes.fp8e4m3), ml_dtypes.float8_e4m3fn(x).tobytes()[0]) + + def test_float_to_fp8e4m3_extreme_values(self): + np.testing.assert_equal(float_to_fp8(FP8E4M3_MAX, dtypes.fp8e4m3), 126) + np.testing.assert_equal(float_to_fp8(FP8E4M3_MAX*1.01, dtypes.fp8e4m3), 126) + np.testing.assert_equal(float_to_fp8(math.inf, dtypes.fp8e4m3), 126) + np.testing.assert_equal(float_to_fp8(-FP8E4M3_MAX, dtypes.fp8e4m3), 254) + np.testing.assert_equal(float_to_fp8(-FP8E4M3_MAX*1.01, dtypes.fp8e4m3), 254) + np.testing.assert_equal(float_to_fp8(-math.inf, dtypes.fp8e4m3), 254) + np.testing.assert_equal(float_to_fp8(math.nan, dtypes.fp8e4m3), 127) + np.testing.assert_equal(float_to_fp8(-math.nan, dtypes.fp8e4m3), 255) + + @given(strat.floats(width=32, allow_subnormal=True, allow_nan=False, allow_infinity=False, min_value=-FP8E5M2_MAX, max_value=FP8E5M2_MAX)) + def test_float_to_fp8e5m2(self, x): np.testing.assert_equal(float_to_fp8(x, dtypes.fp8e5m2), ml_dtypes.float8_e5m2(x).tobytes()[0]) + + def test_float_to_fp8e5m2_extreme_values(self): + np.testing.assert_equal(float_to_fp8(FP8E5M2_MAX, dtypes.fp8e5m2), 123) + np.testing.assert_equal(float_to_fp8(FP8E5M2_MAX*1.01, dtypes.fp8e5m2), 123) + np.testing.assert_equal(float_to_fp8(math.inf, dtypes.fp8e5m2), 123) + np.testing.assert_equal(float_to_fp8(-FP8E5M2_MAX, dtypes.fp8e5m2), 251) + np.testing.assert_equal(float_to_fp8(-FP8E5M2_MAX*1.01, dtypes.fp8e5m2), 251) + np.testing.assert_equal(float_to_fp8(-math.inf, dtypes.fp8e5m2), 251) + np.testing.assert_equal(float_to_fp8(math.nan, dtypes.fp8e5m2), 126) + np.testing.assert_equal(float_to_fp8(-math.nan, dtypes.fp8e5m2), 254) + + @given(strat.integers(min_value=0, max_value=255)) + def test_fp8e4m3_to_float(self, x): np.testing.assert_equal(fp8_to_float(x, dtypes.fp8e4m3), np.uint8(x).view(ml_dtypes.float8_e4m3fn).item()) + + @given(strat.integers(min_value=0, max_value=255)) + def test_fp8e5m2_to_float(self, x): np.testing.assert_equal(fp8_to_float(x, dtypes.fp8e5m2), np.uint8(x).view(ml_dtypes.float8_e5m2).item()) + @unittest.skipUnless(is_dtype_supported(dtypes.bfloat16), "bfloat16 not supported") class TestBFloat16(unittest.TestCase): def test_bf16_creation_numpy(self): @@ -245,6 +288,11 @@ class TestInt8DType(TestDType): def test_int8_to_uint16_negative(self): _test_op(lambda: Tensor([-1, -2, -3, -4], dtype=dtypes.int8).cast(dtypes.uint16), dtypes.uint16, [2**16-1, 2**16-2, 2**16-3, 2**16-4]) + @unittest.skipIf(getenv("PTX"), "broken in ptx") + def test_bitcast_alt(self): + a = Tensor([72, -90, 27, 40, -53, 70, 96, 51], dtype=dtypes.int8).bitcast(dtypes.short) + self.assertListEqual(a.tolist(), [-22968, 10267, 18123, 13152]) + class TestUint8DType(TestDType): DTYPE = dtypes.uint8 @unittest.skipIf(getenv("CUDA",0)==1 or getenv("PTX", 0)==1, "cuda saturation works differently") @@ -255,7 +303,9 @@ class TestUint8DType(TestDType): class TestBitCast(unittest.TestCase): @given(strat.sampled_from(dtype_ints + dtype_floats), strat.sampled_from(dtype_ints + dtype_floats)) def test_shape_change_bitcast(self, dt1, dt2): - if dt2 == dtypes.bfloat16: raise unittest.SkipTest("no test for bf16 bitcast yet") + # NOTE: this has to be assume to prevent hypothesis from skipping all samples + assume(dt2 != dtypes.bfloat16 and dt1 != dtypes.bfloat16) # no test for bf16 bitcast yet + assume(not (getenv("PTX") and dt1 == dtypes.int8)) # TODO: bitcasting int8 fails in PTX data = rand_for_dtype(dt1, 32).reshape(2, 2, 8) _test_op(lambda: Tensor(data, dtype=dt1).bitcast(dt2), dt2, data.view(_to_np_dtype(dt2)).tolist()) @@ -318,6 +368,11 @@ class TestPtrDType(unittest.TestCase): dt = dtypes.float.vec(4).ptr().vec(4) self.assertEqual(dt, eval(str(dt))) + def test_vec_ptr_sz(self): + dt = dtypes.float.ptr(1024).vec(4) + self.assertEqual(dt, eval(str(dt))) + self.assertEqual(str(dt), "dtypes.float.ptr(1024).vec(4)") + def test_vcount(self): dt = dtypes.float.ptr().vec(4) self.assertEqual(dt.vcount, 4) @@ -385,6 +440,10 @@ class TestHelpers(unittest.TestCase): def test_bf16_is_float(self): assert dtypes.is_float(dtypes.bfloat16) + def test_fp8s_are_float(self): + assert dtypes.is_float(dtypes.fp8e4m3) + assert dtypes.is_float(dtypes.fp8e5m2) + @given(strat.sampled_from([d for d in DTYPES_DICT.values() if dtypes.is_float(d) or dtypes.is_int(d)]), strat.integers(min_value=2, max_value=8)) def test_scalar(self, dtype, amt): assert dtype.vec(amt).scalar() == dtype @@ -425,6 +484,30 @@ class TestHelpers(unittest.TestCase): self.assertEqual(truncate_fp16(65519.999), 65504) self.assertEqual(truncate_fp16(65520), math.inf) + def test_truncate_bf16(self): + self.assertEqual(truncate_bf16(1), 1) + self.assertAlmostEqual(truncate_bf16(1.1), 1.09375, places=7) + for a in [1234, 23456, -777.777]: + self.assertEqual(truncate_bf16(a), torch.tensor([a], dtype=torch.bfloat16).item()) + # TODO: torch bfloat 1.1 gives 1.1015625 instead of 1.09375 + max_bf16 = torch.finfo(torch.bfloat16).max + self.assertEqual(truncate_bf16(max_bf16), max_bf16) + self.assertEqual(truncate_bf16(min_bf16:=-max_bf16), min_bf16) + self.assertEqual(truncate_bf16(max_bf16 * 1.00001), math.inf) + self.assertEqual(truncate_bf16(min_bf16 * 1.00001), -math.inf) + + @given(strat.floats(width=32, allow_subnormal=True, allow_nan=True, allow_infinity=True)) + def test_truncate_fp8e4m3(self, x): + if x > FP8E4M3_MAX: np.testing.assert_equal(truncate[dtypes.fp8e4m3](x), FP8E4M3_MAX) + elif x < -FP8E4M3_MAX: np.testing.assert_equal(truncate[dtypes.fp8e4m3](x), -FP8E4M3_MAX) + else: np.testing.assert_equal(truncate[dtypes.fp8e4m3](x), ml_dtypes.float8_e4m3fn(x)) + + @given(strat.floats(width=32, allow_subnormal=True, allow_nan=True, allow_infinity=True)) + def test_truncate_fp8e5m2(self, x): + if x > FP8E5M2_MAX: np.testing.assert_equal(truncate[dtypes.fp8e5m2](x), FP8E5M2_MAX) + elif x < -FP8E5M2_MAX: np.testing.assert_equal(truncate[dtypes.fp8e5m2](x), -FP8E5M2_MAX) + else: np.testing.assert_equal(truncate[dtypes.fp8e5m2](x), ml_dtypes.float8_e5m2(x)) + class TestTypeSpec(unittest.TestCase): def setUp(self): self.old_default_int, self.old_default_float = dtypes.default_int, dtypes.default_float @@ -436,7 +519,7 @@ class TestTypeSpec(unittest.TestCase): dtypes.default_int = default_int assert dtypes.default_int == default_int - for default_float in [dtypes.float16, dtypes.bfloat16, dtypes.float32, dtypes.float64]: + for default_float in [*dtypes.fp8s, dtypes.float16, dtypes.bfloat16, dtypes.float32, dtypes.float64]: dtypes.default_float = default_float assert dtypes.default_float == default_float @@ -472,7 +555,7 @@ class TestTypeSpec(unittest.TestCase): with self.assertRaises(AttributeError): Tensor([1, 2, 3], dtype="nonexistdtype") with self.assertRaises(AttributeError): Tensor([1, 2, 3], dtype="") - np.testing.assert_equal(Tensor(n).sum(acc_dtype="int16").numpy(), Tensor(n).sum(acc_dtype=dtypes.int16).numpy()) + np.testing.assert_equal(Tensor(n).sum(dtype="int16").numpy(), Tensor(n).sum(dtype=dtypes.int16).numpy()) @given(strat.sampled_from(dtype_ints), strat.sampled_from(dtype_floats)) def test_creation(self, default_int, default_float): @@ -610,10 +693,7 @@ class TestTypePromotion(unittest.TestCase): assert least_upper_dtype(dtypes.bool, dtypes.float64) == dtypes.float64 assert least_upper_dtype(dtypes.float16, dtypes.int64) == dtypes.float16 assert least_upper_dtype(dtypes.float16, dtypes.uint64) == dtypes.float16 - - @given(strat.sampled_from(dtype_floats)) - def test_float_to_float(self, dt): - assert least_upper_float(dt) == dt + assert least_upper_dtype(dtypes.fp8e4m3, dtypes.fp8e5m2) == dtypes.half class TestAutoCastType(unittest.TestCase): def setUp(self): @@ -621,6 +701,16 @@ class TestAutoCastType(unittest.TestCase): def tearDown(self): dtypes.default_int, dtypes.default_float = self.old_default_int, self.old_default_float + @given(strat.sampled_from(dtype_floats), strat.sampled_from(dtype_floats)) + def test_least_upper_float_input_is_float(self, input_dtype, default_float): + dtypes.default_float = default_float + self.assertEqual(least_upper_float(input_dtype), input_dtype) + + @given(strat.sampled_from(dtype_ints), strat.sampled_from(dtype_floats)) + def test_least_upper_float_input_is_int(self, input_dtype, default_float): + dtypes.default_float = default_float + self.assertEqual(least_upper_float(input_dtype), default_float) + @given(strat.sampled_from([d for d in core_dtypes if dtypes.is_int(d) and is_dtype_supported(d)])) def test_int_to_float_unary_func(self, dtype): for func in [ @@ -645,6 +735,11 @@ class TestAutoCastType(unittest.TestCase): assert (Tensor.ones(4, 4, dtype=dt) + 2).dtype == (dt if dtypes.is_float(dt) or dtypes.is_int(dt) else dtypes.default_int) assert (Tensor.ones(4, 4, dtype=dt) + True).dtype == dt + @given(strat.sampled_from(dtype_floats)) + def test_int_div_int(self, default_float): + dtypes.default_float = default_float + self.assertEqual(Tensor([1]).div(Tensor([2])).dtype, default_float) + def test_sum(self): assert (Tensor([0, 1], dtype=dtypes.bool)).sum().dtype == dtypes.int32 assert (Tensor([0, 1], dtype=dtypes.int8)).sum().dtype == dtypes.int32 @@ -661,21 +756,21 @@ class TestAutoCastType(unittest.TestCase): assert (Tensor([0, 1], dtype=dtypes.float64)).sum().dtype == dtypes.float64 @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need float16") - def test_sum_acc_dtype(self): + def test_sum_dtype_arg(self): t = Tensor([40000, 40000], dtype=dtypes.float16) # default float16 sum returns in float16, overflowed in this case assert t.sum().dtype == dtypes.float16 assert math.isinf(t.sum().numpy().item()) - # specifiying acc_dtype and it's not downcasted - assert t.sum(acc_dtype=dtypes.float32).dtype == dtypes.float32 - np.testing.assert_allclose(t.sum(acc_dtype=dtypes.float32).numpy(), 80000) + # specifiying dtype and it's not downcasted + assert t.sum(dtype=dtypes.float32).dtype == dtypes.float32 + np.testing.assert_allclose(t.sum(dtype=dtypes.float32).numpy(), 80000) - def test_prod_acc_dtype(self): + def test_prod_dtype_arg(self): t = Tensor([100, 200], dtype=dtypes.int32) assert t.prod().dtype == dtypes.int32 np.testing.assert_allclose(t.prod().numpy(), 20000) - assert t.prod(acc_dtype=dtypes.float32).dtype == dtypes.float32 - np.testing.assert_allclose(t.prod(acc_dtype=dtypes.float32).numpy(), 20000) + assert t.prod(dtype=dtypes.float32).dtype == dtypes.float32 + np.testing.assert_allclose(t.prod(dtype=dtypes.float32).numpy(), 20000) def test_mean(self): assert (Tensor([0, 1], dtype=dtypes.bool)).mean().dtype == dtypes.float32 @@ -711,9 +806,20 @@ class TestAutoCastType(unittest.TestCase): def test_matmul(self, dt1, dt2, acc_dt): t1 = Tensor([0, 1], dtype=dt1) t2 = Tensor([0, 1], dtype=dt2) - assert (t1 @ t2).dtype == least_upper_dtype(dt1, dt2) - # if acc_dtype is specified, return in acc_dtype - assert (t1.matmul(t2, acc_dtype=acc_dt).dtype == acc_dt) + self.assertEqual(t1.matmul(t2).dtype, least_upper_dtype(t1.dtype, t2.dtype)) + # if dtype is specified, return in dtype + self.assertEqual(t1.matmul(t2, dtype=acc_dt).dtype, acc_dt) + + @given(strat.sampled_from(core_dtypes), strat.sampled_from(core_dtypes), strat.sampled_from(core_dtypes), strat.sampled_from(core_dtypes)) + def test_linear(self, dt1, dt2, dt3, acc_dt): + x = Tensor([0, 1], dtype=dt1) + w = Tensor([0, 1], dtype=dt2) + b = Tensor([0, 1], dtype=dt3) + self.assertEqual(x.linear(w).dtype, least_upper_dtype(x.dtype, w.dtype)) + self.assertEqual(x.linear(w, b).dtype, least_upper_dtype(least_upper_dtype(x.dtype, w.dtype), b.dtype)) + # if dtype is specified, return in dtype + self.assertEqual(x.linear(w, dtype=acc_dt).dtype, acc_dt) + self.assertEqual(x.linear(w, b, dtype=acc_dt).dtype, acc_dt) @staticmethod def check_where_alternate_input_other(input_, other, data_type): @@ -786,7 +892,9 @@ class TestAutoCastType(unittest.TestCase): t.reshape(2, 1).expand(2, 10001).max().backward() np.testing.assert_allclose(t.grad.numpy(), [1, 0]) - @unittest.skipIf(Device.DEFAULT=="PYTHON", "very slow") + @unittest.skipIf(Device.DEFAULT == "PYTHON", "very slow") + @unittest.skipIf(CI and Device.DEFAULT == "AMD", "very slow") + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "Binding size is larger than the maximum storage buffer binding size") @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") def test_mean_half_precision_underflow(self): N = 10000 @@ -802,6 +910,7 @@ class TestAutoCastType(unittest.TestCase): t.square().mean().backward() np.testing.assert_allclose(t.grad.numpy().flatten(), [60000 * 2 / (N*N)] * N*N) + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "Precision error") @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") def test_softmax_dtype(self): data = [1, 2, 3] diff --git a/tinygrad_repo/test/test_dtype_alu.py b/tinygrad_repo/test/test_dtype_alu.py index 3cda8c7e24..20d5f59b13 100644 --- a/tinygrad_repo/test/test_dtype_alu.py +++ b/tinygrad_repo/test/test_dtype_alu.py @@ -6,9 +6,8 @@ import numpy as np from hypothesis import given, strategies as strat, settings, HealthCheck from tinygrad.dtype import DType from tinygrad.helpers import CI, getenv -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import run_schedule -from tinygrad.ops import GroupOp +from tinygrad.uop.ops import GroupOp from tinygrad.tensor import _to_np_dtype from tinygrad.device import is_dtype_supported import pytest, math @@ -24,10 +23,10 @@ dtypes_bool = (dtypes.bool,) binary_operations = [operator.add, operator.sub, operator.mul, operator.lt, operator.eq] # TODO: LLVM comparing with nan is incorrect -if Device.DEFAULT == "LLVM": +if Device.DEFAULT == "LLVM" or getenv("AMD_LLVM", 0): binary_operations.remove(operator.lt) -integer_binary_operations = binary_operations + [(Tensor.xor, np.bitwise_xor), (Tensor.bitwise_and, np.bitwise_and), +integer_binary_operations = binary_operations + [(Tensor.bitwise_xor, np.bitwise_xor), (Tensor.bitwise_and, np.bitwise_and), (Tensor.bitwise_or, np.bitwise_or)] unary_operations = [(Tensor.exp, np.exp), (Tensor.log, np.log), (Tensor.sin, np.sin), (Tensor.sqrt, np.sqrt), (Tensor.reciprocal, np.reciprocal)] @@ -42,7 +41,7 @@ unary_operations = [(Tensor.exp, np.exp), (Tensor.log, np.log), (Tensor.sin, np. #binary_operations += [(Tensor.maximum, np.maximum)] # TODO: CI CUDA segfaults on sin, WEBGPU sin is not precise enough for large numbers -if (getenv("MOCKGPU") and Device.DEFAULT == "NV") or Device.DEFAULT == "WEBGPU": unary_operations.remove((Tensor.sin, np.sin)) +if (getenv("MOCKGPU") and Device.DEFAULT in {"NV", "CUDA"}) or Device.DEFAULT == "WEBGPU": unary_operations.remove((Tensor.sin, np.sin)) class ht: float64 = strat.floats(width=64, allow_subnormal=False) @@ -63,25 +62,27 @@ def universal_test(a, b, dtype, op): # The 'nan' cases only fail with Vulkan WebGPU backend (CI) if (math.isnan(a) or math.isnan(b)) and Device.DEFAULT == "WEBGPU" and CI: return if not isinstance(op, tuple): op = (op, op) - tensor_value = (op[0](Tensor([a], dtype=dtype), Tensor([b], dtype=dtype))).numpy() - numpy_value = op[1](np.array([a]).astype(_to_np_dtype(dtype)), np.array([b]).astype(_to_np_dtype(dtype))) - if dtype is dtypes.bfloat16: np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-3, rtol=1e-2) + ta, tb = Tensor([a], dtype=dtype), Tensor([b], dtype=dtype) + tensor_value = (op[0](ta, tb)).numpy() + numpy_value = op[1](ta.numpy(), tb.numpy()) + if dtype == dtypes.bfloat16: np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-3, rtol=1e-2) elif dtype in dtypes_float: np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-10) else: np.testing.assert_equal(tensor_value, numpy_value) def universal_test_unary(a, dtype, op): if not isinstance(op, tuple): op = (op, op) - out: Tensor = op[0](Tensor([a], dtype=dtype)) - sched = create_schedule([out.lazydata]) + ta = Tensor([a], dtype=dtype) + out: Tensor = op[0](ta) + sched = out.schedule() ast = sched[-1].ast run_schedule(sched) tensor_value = out.numpy() - numpy_value = op[1](np.array([a]).astype(_to_np_dtype(dtype))) - if dtype in (*dtypes_float, dtypes.bfloat16): - np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-3, rtol=1e-2) + numpy_value = op[1](ta.numpy()) + if dtype in (dtypes.float16, dtypes.bfloat16): np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-3, rtol=1e-2) + elif dtype in dtypes_float: np.testing.assert_allclose(tensor_value, numpy_value, atol=1e-6, rtol=1e-5) else: np.testing.assert_equal(tensor_value, numpy_value) if op[0] != Tensor.reciprocal: # reciprocal is not supported in most backends - op = [x for x in ast.toposort if x.op in GroupOp.Unary][0] + op = [x for x in ast.toposort() if x.op in GroupOp.Unary][0] assert op.dtype == dtype def universal_test_cast(a, in_dtype, dtype): @@ -89,9 +90,8 @@ def universal_test_cast(a, in_dtype, dtype): numpy_value = np.array([a], dtype=_to_np_dtype(in_dtype)).astype(_to_np_dtype(dtype)) np.testing.assert_equal(tensor_value.numpy(), numpy_value) +@unittest.skipIf(Device.DEFAULT == "WEBGPU", "Inf and nan cases are wrong on WebGPU") def universal_test_midcast(a, b, c, op1, op2, d1:DType, d2:DType): - # the 'inf' and 'nan' cases are wrong on WEBGPU - if (any(map(math.isnan, [a, b, c])) or math.isinf(c)) and Device.DEFAULT == "WEBGPU": return if not isinstance(op1, tuple): op1 = (op1, op1) if not isinstance(op2, tuple): op2 = (op2, op2) at, bt, ct = Tensor([a], dtype=d1), Tensor([b], dtype=d1), Tensor([c], dtype=d2) @@ -125,7 +125,7 @@ class TestDTypeALU(unittest.TestCase): @unittest.skipUnless(is_dtype_supported(dtypes.bfloat16, Device.DEFAULT), f"no bfloat16 on {Device.DEFAULT}") @given(ht.bfloat16, strat.sampled_from(unary_operations)) - @unittest.skipIf(Device.DEFAULT == "AMD", "broken on AMD") + @unittest.skipIf(Device.DEFAULT in ["AMD"], "broken on AMD?") def test_bfloat16_unary(self, a, op): universal_test_unary(a, dtypes.bfloat16, op) @given(ht.uint8, ht.uint8, strat.sampled_from(integer_binary_operations)) @@ -163,7 +163,7 @@ class TestDTypeALU(unittest.TestCase): def test_int32_midcast_float(self, a, b, c, op1, op2): universal_test_midcast(a, b, c, op1, op2, dtypes.int32, dtypes.float32) # Metal and CUDA and HIP behave differently than numpy in CI for overflows - skip_overflow = CI and Device.DEFAULT in {"AMD", "NV"} + skip_overflow = CI and Device.DEFAULT in {"AMD", "NV", "CUDA"} @given(strat.floats(width=32, min_value=0, max_value=10.0) if skip_overflow else ht.float32, strat.floats(width=32, min_value=0, max_value=10.0) if skip_overflow else ht.float32, ht.int32, strat.sampled_from(binary_operations), strat.sampled_from(integer_binary_operations)) @@ -193,12 +193,13 @@ class TestDTypeALU(unittest.TestCase): overflow_strat = float_strat.filter(lambda x: x > dtypes.max(unsigned_dtype) and x <= dtypes.max(dtypes.int32)) universal_test_cast(a.draw(overflow_strat), float_dtype, unsigned_dtype) + @settings(suppress_health_check=[HealthCheck.filter_too_much]) @given(strat.data(), strat.sampled_from(dtypes_float), strat.sampled_from((dtypes.uint8, dtypes.uint16))) def test_float_cast_to_unsigned_underflow(self, a, float_dtype, unsigned_dtype): if not is_dtype_supported(float_dtype, Device.DEFAULT): float_dtype = dtypes.float32 float_strat = {dtypes.float16: ht.float16, dtypes.float32: ht.float32, dtypes.float64: ht.float64}[float_dtype] - overflow_strat = float_strat.filter(lambda x: x < 0 and x >= dtypes.min(dtypes.int32)) - universal_test_cast(a.draw(overflow_strat), float_dtype, unsigned_dtype) + underflow_strat = float_strat.filter(lambda x: x < 0 and x >= dtypes.min(dtypes.int32)) + universal_test_cast(a.draw(underflow_strat), float_dtype, unsigned_dtype) @unittest.expectedFailure def test_unsafe_cast_float_to_int_failure(self): diff --git a/tinygrad_repo/test/test_edgecases.py b/tinygrad_repo/test/test_edgecases.py new file mode 100644 index 0000000000..945a252522 --- /dev/null +++ b/tinygrad_repo/test/test_edgecases.py @@ -0,0 +1,303 @@ +# end to end tests of tinygrad that you think might be edge cases. +# using the documentation, write code you think should work. +# you can compare the outputs to torch or numpy, or just tinygrad assert/raise while doing things that should be valid + +# i'm not interested in tests that currently pass, i'm only interested in tests that you think should pass but don't. +# mark them with @unittest.expectedFailure +# all the tests in here didn't pass until bugs were fixed +# get creative! think about things that failed in pytorch or tensorflow for a long time until they were fixed. +# every test should surface a unique bug. if tinygrad throws an error saying something is not supported, this is probably not a bug. +# the tests don't have to test the same parts of the code that these current ones test, more diversity is better + +# focus on making tinygrad throw runtime errors or assertions for valid things, or find clear numerical mismatches from pytorch +# confirm any bugs found are valid by doing the same thing in pytorch in the test. +# for any failing tests, explain in a comment why tinygrad is wrong and what the desired behavior should be. +# don't worry about running mypy or linters. focus on writing more of these tests and running them to confirm broken behavior. +# surface level bugs, like issues with empty tensors, input validation, or nans, are not that interesting. +# focus on bugs that would frustrate real users. + +# these are not bugs, these are desired behavior. don't add failing tests for them: +# tinygrad only accepts tinygrad dtypes or strings of the tinygrad dtype. +# boolean indexing, or anything with unknown output shape of tensor at compile time isn't supported. +# invalid indexing in things like gather and one_hot is not an error in tinygrad. nothing that depends on the value is +# repeat_interleave doesn't support a tensor as the dim. check tinygrad type signature before claiming something is a bug + +import unittest +import numpy as np +import torch +from tinygrad import Tensor, dtypes, nn + +class TestNaNEdgeCases(unittest.TestCase): + # we don't need more of these. it's unclear if torch's behavior is desired here + + @unittest.expectedFailure + def test_max_nan(self): + # Reductions with NaN should propagate NaN like PyTorch. + arr = [1.0, float('nan'), 3.0] + torch_out = torch.tensor(arr).max().item() + out = Tensor(arr).max().numpy() + if np.isnan(torch_out): + self.assertTrue(np.isnan(out)) + else: + np.testing.assert_equal(out, torch_out) + + @unittest.skip("passes on webgpu") + @unittest.expectedFailure + def test_argmax_nan(self): + # PyTorch returns the index of the NaN, tinygrad returns the index of the maximum value. + arr = [1.0, float('nan'), 3.0] + torch_idx = torch.tensor(arr).argmax().item() + idx = Tensor(arr).argmax().item() + self.assertEqual(idx, torch_idx) + + @unittest.expectedFailure + def test_sort_with_nan(self): + # Sorting a tensor containing NaN should keep NaN at the end like PyTorch. + arr = [1.0, float('nan'), 3.0] + torch_vals, torch_idxs = torch.tensor(arr).sort() + vals, idxs = Tensor(arr).sort() + np.testing.assert_equal(vals.numpy(), torch_vals.numpy()) + np.testing.assert_equal(idxs.numpy(), torch_idxs.numpy().astype(np.int32)) + +class TestEmptyTensorEdgeCases(unittest.TestCase): + # we don't need more of these + + @unittest.expectedFailure + def test_sort_empty(self): + # Sorting an empty tensor works in PyTorch and should return empty + # values and indices. tinygrad raises an error instead. + torch_vals, torch_idxs = torch.tensor([]).sort() + values, indices = Tensor([]).sort() + np.testing.assert_equal(values.numpy(), torch_vals.numpy()) + np.testing.assert_equal(indices.numpy(), torch_idxs.numpy().astype(np.int32)) + + @unittest.expectedFailure + def test_max_empty(self): + # Max on an empty tensor should also raise an error. + with self.assertRaises(RuntimeError): + torch.tensor([]).max() + with self.assertRaises(RuntimeError): + Tensor([]).max() + + @unittest.expectedFailure + def test_argmax_empty(self): + # Argmax on an empty tensor should raise an error like torch does. + with self.assertRaises(RuntimeError): + torch.tensor([]).argmax() + with self.assertRaises(RuntimeError): + Tensor([]).argmax() + + @unittest.expectedFailure + def test_masked_select_empty(self): + # Masked select on empty tensors should return an empty tensor. + torch_out = torch.tensor([], dtype=torch.float32).masked_select(torch.tensor([], dtype=torch.bool)) + out = Tensor([], dtype=dtypes.float32).masked_select(Tensor([], dtype=dtypes.bool)) + np.testing.assert_equal(out.numpy(), torch_out.numpy()) + +class TestRollEdgeCases(unittest.TestCase): + # we don't need more of these + + @unittest.expectedFailure + def test_roll_mismatched_dims(self): + with self.assertRaises(RuntimeError): + torch.roll(torch.arange(9).reshape(3, 3), 1, dims=(0, 1)) + with self.assertRaises(RuntimeError): + Tensor.arange(9).reshape(3, 3).roll(1, dims=(0, 1)) + + @unittest.expectedFailure + def test_roll_extra_shift(self): + # tinygrad ignores extra shift values instead of raising + with self.assertRaises(RuntimeError): + torch.roll(torch.arange(10), (1, 2), dims=0) + with self.assertRaises(RuntimeError): + Tensor.arange(10).roll((1, 2), dims=0) + +class TestDropoutProbabilityEdgeCases(unittest.TestCase): + # we don't need more of these + + @unittest.expectedFailure + def test_dropout_rate_one(self): + # out is full of NaNs it should be 0s + with Tensor.train(): + out = Tensor.ones(100).dropout(1.0) + np.testing.assert_allclose(out.numpy(), np.zeros(100)) + + @unittest.expectedFailure + def test_dropout_invalid_prob(self): + # negative dropout probability should raise an error + with self.assertRaises(ValueError): + torch.nn.functional.dropout(torch.ones(10), -0.1, True) + with Tensor.train(): + out = Tensor.ones(10).dropout(-0.1) + np.testing.assert_allclose(out.numpy(), np.ones(10)) + +class TestInputValidation(unittest.TestCase): + # we don't need more of these, input validation bugs are not very interesting, many are WONTFIX + + @unittest.expectedFailure + def test_repeat_negative(self): + # repeating with a negative value should error like PyTorch + with self.assertRaises(RuntimeError): + torch.tensor([1, 2, 3]).repeat(-1, 2) + with self.assertRaises(RuntimeError): + Tensor([1, 2, 3]).repeat(-1, 2) + + @unittest.expectedFailure + def test_negative_weight_decay(self): + with self.assertRaises(ValueError): + torch.optim.AdamW([torch.tensor([1.], requires_grad=True)], lr=0.1, weight_decay=-0.1) + with self.assertRaises(ValueError): + nn.optim.AdamW([Tensor([1.], requires_grad=True)], lr=0.1, weight_decay=-0.1) + + @unittest.expectedFailure + def test_negative_lr(self): + with self.assertRaises(ValueError): + torch.optim.SGD([torch.tensor([1.], requires_grad=True)], lr=-0.1) + with self.assertRaises(ValueError): + nn.optim.SGD([Tensor([1.], requires_grad=True)], lr=-0.1) + + @unittest.expectedFailure + def test_negative_momentum(self): + with self.assertRaises(ValueError): + torch.optim.SGD([torch.tensor([1.], requires_grad=True)], lr=0.1, momentum=-0.1) + with self.assertRaises(ValueError): + nn.optim.SGD([Tensor([1.], requires_grad=True)], lr=0.1, momentum=-0.1) + +class TestZeroFolding(unittest.TestCase): + # we don't need more of these + + # folding rules treat x/x, x//x and x%x as constants even when x can be zero + @unittest.expectedFailure + def test_divide_by_self_with_zero(self): + x = Tensor([0.0, 1.0]) + torch_out = torch.tensor([0.0, 1.0]) / torch.tensor([0.0, 1.0]) + out = (x / x).numpy() + np.testing.assert_allclose(out, torch_out.numpy(), equal_nan=True) + + @unittest.expectedFailure + def test_floordiv_by_self_with_zero(self): + x = Tensor([0]) + with self.assertRaises(RuntimeError): + torch.tensor([0]) // torch.tensor([0]) + with self.assertRaises(RuntimeError): + (x // x).numpy() + + @unittest.expectedFailure + def test_mod_by_self_with_zero(self): + x = Tensor([0]) + with self.assertRaises(RuntimeError): + torch.tensor([0]) % torch.tensor([0]) + with self.assertRaises(RuntimeError): + (x % x).numpy() + +class TestArangeUOpValidationIssue(unittest.TestCase): + # these fail with UOp verification error. + # we don't need more of these involving arange + + @unittest.expectedFailure + def test_large_arange_sum(self): + # Summing a huge arange should either succeed or raise a MemoryError. + n = 2**31 + 3 + expected = (n - 1) * n // 2 + out = Tensor.arange(n).sum().item() + self.assertEqual(out, expected) + + @unittest.expectedFailure + def test_large_arange_index(self): + # Indexing a huge arange should return the correct value instead of failing + # with a UOp verification error. + n = 2**31 + 3 + out = Tensor.arange(n)[0].item() + self.assertEqual(out, 0) + + @unittest.expectedFailure + def test_large_arange_permute(self): + # Permuting a huge tensor should not trigger UOp verification failures. + n = 2**31 + 3 + out = Tensor.arange(n).reshape(n, 1).permute(1, 0) + self.assertEqual(out.shape, (1, n)) + out.realize() + +class TestAssignIssues(unittest.TestCase): + # these are good failures. i'm not sure we need more, but we need to fix these. + + @unittest.expectedFailure + def test_assign_permuted_view_constant(self): + # assigning to a permuted view should modify the underlying tensor + arr = np.arange(6).reshape(2, 3).astype(np.float32) + torch_tensor = torch.tensor(arr) + torch_tensor.t().copy_(torch.tensor([[5.0, 6.0], [7.0, 8.0], [9.0, 10.0]])) + t = Tensor(arr).contiguous().realize() + t.permute(1, 0).assign(Tensor([[5.0, 6.0], [7.0, 8.0], [9.0, 10.0]])) + np.testing.assert_allclose(t.numpy(), torch_tensor.numpy()) + + @unittest.expectedFailure + def test_assign_shrink_view_constant(self): + # assigning to a shrunk view should update the base tensor + arr = np.arange(9).reshape(3, 3).astype(np.float32) + torch_tensor = torch.tensor(arr) + torch_tensor[1:3, 1:3] = torch.ones(2, 2) + t = Tensor(arr).contiguous().realize() + t.shrink(((1, 3), (1, 3))).assign(Tensor.ones(2, 2)) + np.testing.assert_allclose(t.numpy(), torch_tensor.numpy()) + + @unittest.expectedFailure + def test_assign_broadcast(self): + # broadcasting during assign should behave like PyTorch + torch_tensor = torch.zeros(3, 5) + torch_tensor[:] = torch.arange(5) + t = Tensor.zeros(3, 5) + t.assign(Tensor.arange(5)) + np.testing.assert_allclose(t.numpy(), torch_tensor.numpy()) + +class TestUOpValidationIssue(unittest.TestCase): + # these fail with UOp verification error. + # we want more of these with diverse errors! + + @unittest.expectedFailure + def test_tensor_index_overflow(self): + # Advanced indexing on tensors expanded past int32 should not error, but + # tinygrad fails with a UOp verification error. + val = Tensor([1]) + big = val.expand(2**31 + 3) + idx = Tensor([0, 2**31 + 2]) + np.testing.assert_equal(big[idx].numpy(), np.array([1, 1])) + + def test_float_floordiv_scalar(self): + with self.assertRaisesRegex(RuntimeError, "UOp verification failed"): + (Tensor.arange(4, dtype=dtypes.float32) // 2).realize() + + def test_float_floordiv_tensor(self): + with self.assertRaisesRegex(RuntimeError, "UOp verification failed"): + (Tensor.arange(4, dtype=dtypes.float32) // Tensor.ones(4, dtype=dtypes.float32)).realize() + +class TestEdgeCases(unittest.TestCase): + # add tests exposing new and diverse kinds of bugs that might impact real users here + + @unittest.expectedFailure + def test_circular_pad_negative(self): + # negative pads with circular mode should wrap like PyTorch + arr = np.arange(9).reshape(1, 1, 3, 3).astype(np.float32) + torch_out = torch.nn.functional.pad(torch.tensor(arr), (1, -1, 1, -1), mode='circular') + out = Tensor(arr).pad((1, -1, 1, -1), mode='circular') + np.testing.assert_equal(out.numpy(), torch_out.numpy()) + + @unittest.expectedFailure + def test_arange_float_step(self): + # float steps should match PyTorch exactly + torch_out = torch.arange(0, 2, 0.3).numpy() + out = Tensor.arange(0, 2, 0.3).numpy() + np.testing.assert_allclose(out, torch_out) + + @unittest.skip("this is flaky") + @unittest.expectedFailure + def test_topk_ties_indices(self): + # topk should match PyTorch tie-breaking behavior when values are equal + arr = [1.0, 1.0, 1.0, 1.0] + _, ti = torch.tensor(arr).topk(2) + _, i = Tensor(arr).topk(2) + np.testing.assert_equal(i.numpy(), ti.numpy().astype(np.int32)) + + +if __name__ == "__main__": + unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_fusion_op.py b/tinygrad_repo/test/test_fusion_op.py index b979ef2b2f..255479cc48 100644 --- a/tinygrad_repo/test/test_fusion_op.py +++ b/tinygrad_repo/test/test_fusion_op.py @@ -2,7 +2,6 @@ import unittest import time import numpy as np from tinygrad import Tensor, dtypes -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import lower_schedule_item, run_schedule class TestFusionOp(unittest.TestCase): @@ -17,7 +16,7 @@ class TestFusionOp(unittest.TestCase): def test_expand_fuse(self): bt = Tensor(np.ones((10, 1)), dtype=dtypes.float32) out = (bt*2).expand(10,10).sum(1) - sched = create_schedule([out.lazydata]) + sched = out.schedule() run_schedule(sched) outd = out.tolist() assert all(x == 20.0 for x in outd) @@ -26,7 +25,7 @@ class TestFusionOp(unittest.TestCase): st = time.perf_counter() a = Tensor([1,2,3,4]) for _ in range(24): a = a + a - sched = create_schedule([a.lazydata]) + sched = a.schedule() ei = lower_schedule_item(sched[-1]) self.assertLess(time.perf_counter()-st, 2.0) assert len(ei.prg.p.src.splitlines()) < 250 @@ -35,13 +34,13 @@ class TestFusionOp(unittest.TestCase): st = time.perf_counter() a = Tensor([1,2,3,4]) for _ in range(24): a = a + a - sched1 = create_schedule([a.lazydata]) + sched1 = a.schedule() b = Tensor([1,2,3,4]) for _ in range(24): b = b + b - sched2 = create_schedule([b.lazydata]) + sched2 = b.schedule() c = Tensor([1,2,3,4]) for _ in range(23): c = c + c - sched3 = create_schedule([c.lazydata]) + sched3 = c.schedule() self.assertEqual(sched1[-1].ast, sched2[-1].ast) with self.assertRaises(AssertionError): self.assertEqual(sched1[-1].ast, sched3[-1].ast) self.assertLess(time.perf_counter()-st, 2.0) @@ -49,10 +48,10 @@ class TestFusionOp(unittest.TestCase): def test_recursive_pad(self): st = time.perf_counter() val = 1.0 - a = Tensor(val).realize() + a = Tensor(val) for _ in range(24): a = Tensor.stack(a, a)[0] - r = a.item() - self.assertEqual(r, val) + sched = a.schedule() + self.assertEqual(len(sched), 1) self.assertLess(time.perf_counter()-st, 2.0) def test_recursive_reshape(self): diff --git a/tinygrad_repo/test/test_fuzz_shape_ops.py b/tinygrad_repo/test/test_fuzz_shape_ops.py index 721f4ecda7..b90d98cb03 100644 --- a/tinygrad_repo/test/test_fuzz_shape_ops.py +++ b/tinygrad_repo/test/test_fuzz_shape_ops.py @@ -38,7 +38,7 @@ def apply(tor, ten, tor_fn, ten_fn=None): except: ten, ok = None, not ok # noqa: E722 return tor, ten, ok -@unittest.skipIf(CI and Device.DEFAULT == "CLANG", "slow") +@unittest.skipIf(CI and Device.DEFAULT in ("CPU", "NV"), "slow") class TestShapeOps(unittest.TestCase): @settings.get_profile(__file__) @given(st_shape(), st_int32, st.one_of(st_int32, st.lists(st_int32))) diff --git a/tinygrad_repo/test/test_gc.py b/tinygrad_repo/test/test_gc.py index 010f59039f..e32053c8c8 100644 --- a/tinygrad_repo/test/test_gc.py +++ b/tinygrad_repo/test/test_gc.py @@ -4,13 +4,15 @@ import unittest import numpy as np from tinygrad.device import Buffer from tinygrad.engine.realize import run_schedule -from tinygrad.ops import UOp +from tinygrad.uop.ops import UOp from tinygrad.tensor import Tensor def tensors_allocated(): + gc.collect() return sum([isinstance(x, Tensor) for x in gc.get_objects()]) def bufs_allocated(): + gc.collect() return sum([isinstance(x, Buffer) for x in gc.get_objects()]) class TestGC(unittest.TestCase): @@ -31,7 +33,7 @@ class TestGC(unittest.TestCase): base = tensors_allocated() a = Tensor(np.zeros((4, 4), dtype=np.float32), requires_grad=True) b = Tensor.rand(4, 4, requires_grad=True) - assert (tensors_allocated()-base == 5) + assert (tensors_allocated()-base == 4) (a*b).mean().backward() assert (tensors_allocated()-base == 6) del b @@ -71,11 +73,41 @@ class TestGC(unittest.TestCase): x = Tensor.ones(4,4).contiguous().realize()+1 self.assertEqual(bufs_allocated()-init, 1) # try commenting this part out, it's green! - x.lazydata.toposort + x.lazydata.toposort() del x if bufs_allocated()-init != 0: - print(inspect.getclosurevars(UOp.toposort.fget)) + print(inspect.getclosurevars(UOp.toposort().fget)) raise AssertionError(f"never gced {[x for x in gc.get_objects() if isinstance(x, Buffer)]}") + def test_buffer_refcount(self): + init = bufs_allocated() + a = Tensor.empty(10) + self.assertEqual(bufs_allocated()-init, 0) + a.realize() + real_buf = a.lazydata.buffer + # after the Tensor UOp is deleted there shouldn't be any references on the Buffer + self.assertEqual(real_buf.lb_refcount, 1) + self.assertEqual(bufs_allocated()-init, 1) + del a.lazydata + self.assertEqual(real_buf.lb_refcount, 0) + self.assertEqual(bufs_allocated()-init, 1) # keep the buffer alive + del real_buf + self.assertEqual(bufs_allocated()-init, 0) + + def test_assign_refcount(self): + init = bufs_allocated() + a = Tensor.full((4,), 1.).contiguous() + a.realize() + real_buf = a.lazydata.buffer + self.assertEqual(real_buf.lb_refcount, 1) + a.assign(Tensor.full((4,), 2.)) + self.assertIs(a.lazydata.src[0].buffer, real_buf) + # NOTE: this is still 1, we don't count the ASSIGN + self.assertEqual(real_buf.lb_refcount, 1) + a.realize() + del a + self.assertEqual(real_buf.lb_refcount, 0) # no UOps for this Buffer + self.assertEqual(bufs_allocated()-init, 1) # Buffer is alive + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_graph.py b/tinygrad_repo/test/test_graph.py index e55ee912a0..a47756a23f 100644 --- a/tinygrad_repo/test/test_graph.py +++ b/tinygrad_repo/test/test_graph.py @@ -1,11 +1,11 @@ import numpy as np -import unittest, ctypes +import functools, unittest, ctypes from tinygrad.device import Device, Buffer from tinygrad.tensor import Tensor, _to_np_dtype -from tinygrad.engine.schedule import create_schedule from tinygrad.helpers import Context, CI, dedup, from_mv from tinygrad.dtype import dtypes +from tinygrad.engine.jit import MultiGraphRunner from tinygrad.engine.realize import ExecItem, BufferXfer, get_runner, CompiledRunner np.random.seed(1337) @@ -19,9 +19,9 @@ def helper_exec_op(device, outbuf, inbufs): with Context(DEBUG=0): fst = [Tensor.randn(BUF_SIZE, dtype=dtypes.int).realize() for i in range(len(inbufs))] s = fst[0] - for i in range(1, len(inbufs)): s = s.xor(fst[i]) + for i in range(1, len(inbufs)): s = s.bitwise_xor(fst[i]) - si = create_schedule([s.lazydata])[-1] + si = s.schedule()[-1] prg = get_runner(device, si.ast) cached_prgs[(device, len(inbufs))] = prg @@ -39,6 +39,10 @@ def helper_alloc_rawbuffer(device, fill=False): rawbuf.copyin(Tensor(data).realize().lazydata.base.realized.as_buffer()) return rawbuf +def helper_create_offset_rawbuffer(base, offset=0): + x = Buffer(base.device, base.size-offset, base.dtype, base=base, offset=offset) + return x.ensure_allocated() + def helper_run_jit(jis, bufs, out_buffers): for rawbuf in out_buffers: mv = memoryview(bytearray(rawbuf.size * rawbuf.dtype.itemsize)) @@ -71,7 +75,6 @@ def helper_test_graphs(graph_impl, graphs, runs=RUN_CNT): for i in range(len(ground_thruth_bufs)): np.testing.assert_equal(ground_truth_np[i], test_bufs_np[i]) @unittest.skipUnless(Device[Device.DEFAULT].graph is not None, "graph support required") -@unittest.skipIf(CI and Device.DEFAULT=="METAL", "no ICB in CI, creation of graph fails") class TestGraph(unittest.TestCase): def test_order_2_writes_to_same_buf(self): d0 = Device.DEFAULT @@ -103,8 +106,13 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) - @unittest.skipUnless(Device.DEFAULT in {"CUDA", "NV", "AMD"}, "mutidevice graph required") + def skip_if_not_multigraph(self): + graph = g.func if isinstance(g:=Device[Device.DEFAULT].graph, functools.partial) else g + if not issubclass(graph, MultiGraphRunner): self.skipTest("graph is not supported (not MultiGraphRunner)") + def test_order_copy_writed(self): + self.skip_if_not_multigraph() + d0 = Device.DEFAULT b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(4)] @@ -114,8 +122,9 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) - @unittest.skipUnless(Device.DEFAULT in {"CUDA", "NV", "AMD"}, "mutidevice graph required") def test_order_copy_then_read(self): + self.skip_if_not_multigraph() + d0 = Device.DEFAULT b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(4)] @@ -144,8 +153,9 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) - @unittest.skipUnless(Device.DEFAULT in {"CUDA", "NV", "AMD"}, "mutidevice graph required") def test_copies_2_devs(self): + self.skip_if_not_multigraph() + d0, d1 = Device.DEFAULT, f"{Device.DEFAULT}:1" b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(3)] b1 = [helper_alloc_rawbuffer(d1, fill=True) for _ in range(1)] @@ -156,8 +166,9 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) - @unittest.skipUnless(Device.DEFAULT in {"CUDA", "NV", "AMD"}, "mutidevice graph required") def test_copies_after_graph_global(self): + self.skip_if_not_multigraph() + d0, d1, d2, d3 = Device.DEFAULT, f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3" b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(8)] b1 = [helper_alloc_rawbuffer(d1, fill=True) for _ in range(6)] @@ -203,8 +214,9 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) - @unittest.skipUnless(Device.DEFAULT in {"CUDA", "NV", "AMD"}, "mutidevice graph required") def test_graph_after_copies_devs(self): + self.skip_if_not_multigraph() + d0, d1, d2, d3 = Device.DEFAULT, f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3" b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(8)] b1 = [helper_alloc_rawbuffer(d1, fill=True) for _ in range(1)] @@ -230,5 +242,20 @@ class TestGraph(unittest.TestCase): helper_test_graphs(Device[d0].graph, graphs) + def test_graph_offset_bufs(self): + self.skip_if_not_multigraph() + + d0 = Device.DEFAULT + if not hasattr(Device[d0].allocator, "_offset"): self.skipTest("device does not support _offset") + + b0 = [helper_alloc_rawbuffer(d0, fill=True) for _ in range(1)] + b0 += [helper_create_offset_rawbuffer(b0[0]), helper_create_offset_rawbuffer(b0[0])] + + graphs = [ + [helper_copy_op(d0, b0[0], b0[2]), helper_exec_op(d0, b0[1], [b0[0], b0[2]])], + ] + + helper_test_graphs(Device[d0].graph, graphs) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_hcq.py b/tinygrad_repo/test/test_hcq.py index a3aea0be5d..b2ae098a6a 100644 --- a/tinygrad_repo/test/test_hcq.py +++ b/tinygrad_repo/test/test_hcq.py @@ -1,9 +1,9 @@ -import unittest, ctypes, struct +import unittest, ctypes, struct, os, random from tinygrad import Device, Tensor, dtypes -from tinygrad.helpers import CI, getenv +from tinygrad.helpers import getenv, CI, mv_address from tinygrad.device import Buffer, BufferSpec -from tinygrad.runtime.support.hcq import HCQCompiled -from tinygrad.engine.schedule import create_schedule +from tinygrad.runtime.support.hcq import HCQCompiled, HCQBuffer +from tinygrad.runtime.autogen import libc from tinygrad.engine.realize import get_runner, CompiledRunner from tinygrad.codegen.kernel import Kernel, Opt, OptOps from tinygrad import Variable @@ -17,7 +17,7 @@ class TestHCQ(unittest.TestCase): TestHCQ.d0 = Device[Device.DEFAULT] TestHCQ.a = Tensor([0.,1.], device=Device.DEFAULT).realize() TestHCQ.b = self.a + 1 - si = create_schedule([self.b.lazydata])[-1] + si = self.b.schedule()[-1] TestHCQ.runner = get_runner(TestHCQ.d0.device, si.ast) TestHCQ.b.lazydata.buffer.allocate() @@ -46,17 +46,17 @@ class TestHCQ(unittest.TestCase): if queue_type is None: continue virt_val = Variable("sig_val", 0, 0xffffffff, dtypes.uint32) - virt_signal = TestHCQ.d0.signal_t(base_addr=Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64)) + virt_signal = TestHCQ.d0.signal_t(base_buf=HCQBuffer(Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64), 16)) with self.subTest(name=str(queue_type)): q = queue_type().signal(virt_signal, virt_val) - var_vals = {virt_signal.base_addr: TestHCQ.d0.timeline_signal.base_addr, virt_val: TestHCQ.d0.timeline_value} + var_vals = {virt_signal.base_buf.va_addr: TestHCQ.d0.timeline_signal.base_buf.va_addr, virt_val: TestHCQ.d0.timeline_value} q.submit(TestHCQ.d0, var_vals) TestHCQ.d0.timeline_signal.wait(TestHCQ.d0.timeline_value) TestHCQ.d0.timeline_value += 1 - var_vals = {virt_signal.base_addr: TestHCQ.d0.timeline_signal.base_addr, virt_val: TestHCQ.d0.timeline_value} + var_vals = {virt_signal.base_buf.va_addr: TestHCQ.d0.timeline_signal.base_buf.va_addr, virt_val: TestHCQ.d0.timeline_value} q.submit(TestHCQ.d0, var_vals) TestHCQ.d0.timeline_signal.wait(TestHCQ.d0.timeline_value) TestHCQ.d0.timeline_value += 1 @@ -98,14 +98,14 @@ class TestHCQ(unittest.TestCase): with self.subTest(name=str(queue_type)): virt_val = Variable("sig_val", 0, 0xffffffff, dtypes.uint32) - virt_signal = TestHCQ.d0.signal_t(base_addr=Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64)) + virt_signal = TestHCQ.d0.signal_t(base_buf=HCQBuffer(Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64), 16)) fake_signal = TestHCQ.d0.signal_t() q = queue_type().wait(virt_signal, virt_val).signal(TestHCQ.d0.timeline_signal, TestHCQ.d0.timeline_value) fake_signal.value = 0x30 - q.submit(TestHCQ.d0, {virt_signal.base_addr: fake_signal.base_addr, virt_val: fake_signal.value}) + q.submit(TestHCQ.d0, {virt_signal.base_buf.va_addr: fake_signal.base_buf.va_addr, virt_val: fake_signal.value}) TestHCQ.d0.timeline_signal.wait(TestHCQ.d0.timeline_value) TestHCQ.d0.timeline_value += 1 @@ -159,9 +159,9 @@ class TestHCQ(unittest.TestCase): a = Tensor.randint((3, 3, 3), dtype=dtypes.int, device=Device.DEFAULT).realize() b = a + 1 - si = create_schedule([b.lazydata])[-1] + si = b.schedule()[-1] k = Kernel(si.ast, opts=TestHCQ.d0.renderer) - for i in range(3): k.apply_opt(Opt(op=OptOps.LOCAL, axis=0, amt=3)) + for i in range(3): k.apply_opt(Opt(op=OptOps.LOCAL, axis=0, arg=3)) runner = CompiledRunner(k.to_program()) @@ -217,7 +217,30 @@ class TestHCQ(unittest.TestCase): TestHCQ.d0.timeline_value += 1 mv_buf1 = buf1.as_buffer().cast('Q') - for i in range(sz//8): assert mv_buf1[i] == 0x0101010101010101, f"offset {i*8} differs, not all copied, got {hex(mv_buf1[i])}" + assert libc.memcmp(mv_address(mv_buf1), buf2._buf.va_addr, sz) == 0 + + @unittest.skipIf(CI, "skip in CI") + def test_copy_64bit(self): + if TestHCQ.d0.hw_copy_queue_t is None: self.skipTest("device does not support copy queue") + + for sz in [(1 << 32) - 1, (1 << 32), (1 << 32) + 1, (5 << 30), (6 << 30) - 0x4642ee1]: + buf1 = Buffer(Device.DEFAULT, sz, dtypes.int8, options=BufferSpec(nolru=True)).ensure_allocated() + buf2 = Buffer(Device.DEFAULT, sz, dtypes.int8, options=BufferSpec(host=True, nolru=True)).ensure_allocated() + + ctypes.memset(buf2._buf.va_addr, 0x3e, sz) + buf2_q_view = buf2._buf.cpu_view().view(fmt='Q') + for i in range(0, sz//8, 0x1000): + for j in range(32): buf2_q_view[min(max(i + j - 16, 0), (sz // 8) - 1)] = random.randint(0, 0xffffffffffffffff) + + TestHCQ.d0.hw_copy_queue_t().wait(TestHCQ.d0.timeline_signal, TestHCQ.d0.timeline_value - 1) \ + .copy(buf1._buf.va_addr, buf2._buf.va_addr, sz) \ + .signal(TestHCQ.d0.timeline_signal, TestHCQ.d0.timeline_value).submit(TestHCQ.d0) + + TestHCQ.d0.timeline_signal.wait(TestHCQ.d0.timeline_value) + TestHCQ.d0.timeline_value += 1 + + mv_buf1 = buf1.as_buffer() + assert libc.memcmp(mv_address(mv_buf1), buf2._buf.va_addr, sz) == 0 def test_update_copy(self): if TestHCQ.d0.hw_copy_queue_t is None: self.skipTest("device does not support copy queue") @@ -266,7 +289,7 @@ class TestHCQ(unittest.TestCase): if queue_type is None: continue virt_val = Variable("sig_val", 0, 0xffffffff, dtypes.uint32) - virt_signal = TestHCQ.d0.signal_t(base_addr=Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64)) + virt_signal = TestHCQ.d0.signal_t(base_buf=HCQBuffer(Variable("sig_addr", 0, 0xffffffffffffffff, dtypes.uint64), 16)) with self.subTest(name=str(queue_type)): fake_signal = TestHCQ.d0.signal_t() @@ -275,7 +298,7 @@ class TestHCQ(unittest.TestCase): fake_signal.value = 0x30 - q.submit(TestHCQ.d0, {virt_signal.base_addr: fake_signal.base_addr, virt_val: fake_signal.value}) + q.submit(TestHCQ.d0, {virt_signal.base_buf.va_addr: fake_signal.base_buf.va_addr, virt_val: fake_signal.value}) TestHCQ.d0.timeline_signal.wait(TestHCQ.d0.timeline_value) TestHCQ.d0.timeline_value += 1 @@ -312,7 +335,7 @@ class TestHCQ(unittest.TestCase): et = float(sig_en.timestamp - sig_st.timestamp) print(f"exec kernel time: {et:.2f} us") - assert 0.1 <= et <= (7000 if CI else 100) + assert 0.1 <= et <= (15000 if MOCKGPU else 100) def test_speed_copy_bandwidth(self): if TestHCQ.d0.hw_copy_queue_t is None: self.skipTest("device does not support copy queue") @@ -336,7 +359,7 @@ class TestHCQ(unittest.TestCase): gb_s = ((SZ / 1e9) / et_ms) * 1e3 print(f"same device copy: {et_ms:.2f} ms, {gb_s:.2f} GB/s") - assert (0.3 if CI else 10) <= gb_s <= 1000 + assert (0.2 if MOCKGPU else 10) <= gb_s <= 1000 def test_speed_cross_device_copy_bandwidth(self): if TestHCQ.d0.hw_copy_queue_t is None: self.skipTest("device does not support copy queue") @@ -347,7 +370,7 @@ class TestHCQ(unittest.TestCase): SZ = 200_000_000 b = Buffer(f"{Device.DEFAULT}:1", SZ, dtypes.uint8, options=BufferSpec(nolru=True)).allocate() a = Buffer(Device.DEFAULT, SZ, dtypes.uint8, options=BufferSpec(nolru=True)).allocate() - TestHCQ.d0._gpu_map(b._buf) + TestHCQ.d0.allocator.map(b._buf) sig_st, sig_en = TestHCQ.d0.signal_t(), TestHCQ.d0.signal_t() TestHCQ.d0.hw_copy_queue_t().timestamp(sig_st) \ @@ -363,7 +386,7 @@ class TestHCQ(unittest.TestCase): gb_s = ((SZ / 1e9) / et_ms) * 1e3 print(f"cross device copy: {et_ms:.2f} ms, {gb_s:.2f} GB/s") - assert (0.3 if CI else 2) <= gb_s <= 50 + assert (0.2 if MOCKGPU else 2) <= gb_s <= 100 def test_timeline_signal_rollover(self): for queue_type in [TestHCQ.d0.hw_compute_queue_t, TestHCQ.d0.hw_copy_queue_t]: @@ -442,7 +465,7 @@ class TestHCQ(unittest.TestCase): def test_memory_barrier(self): a = Tensor([0, 1], device=Device.DEFAULT, dtype=dtypes.int8).realize() b = a + 1 - runner = get_runner(TestHCQ.d0.device, create_schedule([b.lazydata])[-1].ast) + runner = get_runner(TestHCQ.d0.device, b.schedule()[-1].ast) buf1 = Buffer(Device.DEFAULT, 2, dtypes.int8, options=BufferSpec(nolru=True)).ensure_allocated() buf2 = Buffer(Device.DEFAULT, 2, dtypes.int8, options=BufferSpec(cpu_access=True, nolru=True)).ensure_allocated() @@ -487,5 +510,30 @@ class TestHCQ(unittest.TestCase): assert buf2.as_buffer()[0] == i + @unittest.skipUnless(MOCKGPU, "Emulate this on MOCKGPU to check the path in CI") + def test_on_device_hang(self): + if not hasattr(self.d0, 'on_device_hang'): self.skipTest("device does not have on_device_hang") + + os.environ["MOCKGPU_EMU_FAULTADDR"] = "0xDEADBEE1" + + # Check api calls + with self.assertRaises(RuntimeError) as ctx: + self.d0.on_device_hang() + + assert "0xDEADBEE1" in str(ctx.exception) + os.environ.pop("MOCKGPU_EMU_FAULTADDR") + + def test_multidevice(self): + try: amd_dev = Device["AMD"] + except Exception: self.skipTest("no AMD device, test skipped") + + try: nv_dev = Device["NV"] + except Exception: self.skipTest("no NV device, test skipped") + + x = amd_dev.signal_t() + y = nv_dev.signal_t() + assert type(x) is amd_dev.signal_t + assert type(y) is nv_dev.signal_t + if __name__ == "__main__": unittest.main() diff --git a/tinygrad_repo/test/test_hcq_iface.py b/tinygrad_repo/test/test_hcq_iface.py new file mode 100644 index 0000000000..bf32bf637c --- /dev/null +++ b/tinygrad_repo/test/test_hcq_iface.py @@ -0,0 +1,105 @@ +import unittest, array, time +from tinygrad.helpers import mv_address +from tinygrad.runtime.support.hcq import MMIOInterface +from tinygrad.runtime.support.usb import USBMMIOInterface +from test.mockgpu.usb import MockUSB + +class TestHCQIface(unittest.TestCase): + def setUp(self): + self.size = 4 << 10 + self.buffer = bytearray(self.size) + self.mv = memoryview(self.buffer).cast('I') + self.mmio = MMIOInterface(mv_address(self.mv), self.size, fmt='I') + + def test_getitem_setitem(self): + self.mmio[1] = 0xdeadbeef + self.assertEqual(self.mmio[1], 0xdeadbeef) + values = array.array('I', [10, 20, 30, 40]) + self.mmio[2:6] = values + read_slice = self.mmio[2:6] + # self.assertIsInstance(read_slice, array.array) + self.assertEqual(read_slice, values.tolist()) + self.assertEqual(self.mv[2:6].tolist(), values.tolist()) + + def test_view(self): + full = self.mmio.view() + self.assertEqual(len(full), len(self.mmio)) + self.mmio[0] = 0x12345678 + self.assertEqual(full[0], 0x12345678) + + # offset-only view + self.mmio[1] = 0xdeadbeef + off = self.mmio.view(offset=4) + self.assertEqual(off[0], 0xdeadbeef) + + # offset + size view: write into sub-view and confirm underlying buffer + values = array.array('I', [11, 22, 33]) + sub = self.mmio.view(offset=8, size=12) + sub[:] = values + self.assertEqual(sub[:], values.tolist()) + self.assertEqual(self.mv[2:5].tolist(), values.tolist()) + + def test_speed(self): + start = time.perf_counter() + for i in range(10000): + self.mmio[3:100] = array.array('I', [i] * 97) + _ = self.mmio[3:100] + end = time.perf_counter() + + mvstart = time.perf_counter() + for i in range(10000): + self.mv[3:100] = array.array('I', [i] * 97) + _ = self.mv[3:100].tolist() + mvend = time.perf_counter() + print(f"speed: hcq {end - start:.6f}s vs plain mv {mvend - mvstart:.6f}s") + +class TestUSBMMIOInterface(unittest.TestCase): + def setUp(self): + self.size = 256 + self.buffer = bytearray(self.size) + self.usb = MockUSB(self.buffer) + self.mmio = USBMMIOInterface(self.usb, 0, self.size, fmt='B', pcimem=False) + + def test_getitem_setitem_byte(self): + self.mmio[1] = 0xAB + self.assertEqual(self.mmio[1], 0xAB) + self.assertEqual(self.usb.mem[1], 0xAB) + + def test_slice_getitem_setitem(self): + values = [1, 2, 3, 4] + self.mmio[10:14] = values + raw = self.mmio[10:14] + self.assertIsInstance(raw, bytes) + self.assertEqual(list(raw), values) + self.assertEqual(list(self.usb.mem[10:14]), values) + + def test_view(self): + self.mmio[0] = 5 + view = self.mmio.view(offset=1, size=3) + self.assertEqual(view[0], self.usb.mem[1]) + view[:] = [7, 8, 9] + self.assertEqual(list(self.usb.mem[1:4]), [7, 8, 9]) + full_view = self.mmio.view() + self.assertEqual(len(full_view), len(self.mmio)) + self.mmio[2] = 0xFE + self.assertEqual(full_view[2], 0xFE) + + def test_pcimem_byte(self): + usb2 = MockUSB(bytearray(self.size)) + mmio_pci = USBMMIOInterface(usb2, 0, self.size, fmt='B', pcimem=True) + mmio_pci[3] = 0x11 + self.assertEqual(mmio_pci[3], 0x11) + self.assertEqual(usb2.mem[3], 0x11) + + def test_pcimem_slice(self): + usb3 = MockUSB(bytearray(self.size)) + mmio_pci = USBMMIOInterface(usb3, 0, self.size, fmt='B', pcimem=True) + values = [2, 3, 4] + mmio_pci[4:7] = values + raw = mmio_pci[4:7] + self.assertIsInstance(raw, bytes) + self.assertEqual(list(raw), values) + self.assertEqual([mmio_pci[i] for i in range(4, 7)], values) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/test_image_dtype.py b/tinygrad_repo/test/test_image_dtype.py index d2f0e80e04..41b32de81f 100644 --- a/tinygrad_repo/test/test_image_dtype.py +++ b/tinygrad_repo/test/test_image_dtype.py @@ -1,17 +1,23 @@ import unittest import numpy as np from tinygrad import Device, dtypes, Tensor, Context +from tinygrad.device import LRUAllocator, is_dtype_supported from tinygrad.dtype import ImageDType from tinygrad.engine.realize import lower_schedule from tinygrad.helpers import prod, unwrap +from test.helpers import REAL_DEV -@unittest.skipIf(Device.DEFAULT not in ("QCOM", "GPU"), "only images on GPU") +IMAGE_SUPPORTED_DEVICES = ("QCOM", "GPU") + +@unittest.skipUnless(REAL_DEV in IMAGE_SUPPORTED_DEVICES, "Images not supported") class TestImageCopy(unittest.TestCase): def test_image_copyout_1x1(self, img_type=dtypes.imagef): it = Tensor.arange(4).cast(img_type((1,1,4))).realize() buf = it.lazydata.buffer out = buf.as_buffer() np.testing.assert_equal(out.cast(it.dtype.fmt).tolist(), np.arange(4)) + + @unittest.skipUnless(is_dtype_supported(dtypes.half, device="PYTHON"), "need half") def test_imageh_copyout_1x1(self): self.test_image_copyout_1x1(img_type=dtypes.imageh) def test_image_numpy_1x1(self, img_type=dtypes.imagef): @@ -37,15 +43,24 @@ class TestImageCopy(unittest.TestCase): assert (it == it2).sum().item() == prod(sz) -@unittest.skipIf(Device.DEFAULT not in ("QCOM", "GPU"), "only images on GPU") +@unittest.skipUnless(REAL_DEV in IMAGE_SUPPORTED_DEVICES, "Images not supported") class TestImageDType(unittest.TestCase): def test_image_and_back(self): data = Tensor.randn(9*27*4).realize() tst = data.numpy() - it = data.cast(dtypes.imagef((9,27,4))).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() assert isinstance(it.lazydata.base.realized.dtype, ImageDType) np.testing.assert_equal(tst, it.numpy()) + @unittest.expectedFailure # this isn't supported anymore, CAST to ImageDType stays ImageDType + def test_image_cast_and_back_collapses(self): + data = Tensor.randn(9*27*4).realize() + tst = data.numpy() + it = data.cast(dtypes.imagef((9,27,4))).realize() + # the underlying UOp is identical + self.assertIs(it.lazydata.base.realized, data.lazydata.base.realized) + np.testing.assert_equal(tst, it.numpy()) + def test_image_and_back_wrong_shape(self): data = Tensor.randn(9*27*4).realize() tst = data.numpy() @@ -59,7 +74,8 @@ class TestImageDType(unittest.TestCase): np.testing.assert_equal(imgv[0:2], it[0:2].numpy()) def test_mul_stays_image(self): - it = Tensor.randn(4).cast(dtypes.imagef((1,1,4))).realize() + # NOTE: contiguous is needed otherwise this folds + it = Tensor.randn(4).cast(dtypes.imagef((1,1,4))).contiguous().realize() out = (it*2).realize() assert isinstance(out.lazydata.base.realized.dtype, ImageDType) @@ -78,6 +94,7 @@ class TestImageDType(unittest.TestCase): imgv = it.numpy() np.testing.assert_equal(np.maximum(imgv[:, 0], 0), it[:, 0].relu().numpy()) + @unittest.skipUnless(isinstance(Device.default.allocator, LRUAllocator), "Requires LRU") def test_lru_alloc(self): data = Tensor.randn(9*27*4).realize() it = data.cast(dtypes.imagef((9,27,4))).realize() @@ -88,21 +105,23 @@ class TestImageDType(unittest.TestCase): def test_no_lru_alloc(self): data = Tensor.randn(9*27*4).realize() - it = data.cast(dtypes.imagef((9,27,4))).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() b1 = it.lazydata.base.realized._buf del it - it = data.cast(dtypes.imagef((10,27,4))).realize() + it = data.cast(dtypes.imagef((10,27,4))).contiguous().realize() assert it.lazydata.base.realized._buf != b1 def test_no_lru_alloc_dtype(self): data = Tensor.randn(9*27*4).realize() - it = data.cast(dtypes.imagef((9,27,4))).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() b1 = it.lazydata.base.realized._buf del it it = data.cast(dtypes.imageh((9,27,4))).realize() assert it.lazydata.base.realized._buf != b1 # issue caused by: don't realize image to image casts. this is part of a larger problem + #@unittest.expectedFailure + # update: passing after tensor_map def test_lil_model(self): with Context(IMAGE=2): x = Tensor.zeros(1, 1) @@ -111,13 +130,50 @@ class TestImageDType(unittest.TestCase): loss = x.image_dot(w1).image_dot(w2).float().max() loss.backward() sched = unwrap(w1.grad).schedule() - self.assertEqual(len(sched), 10) - for s,ei in zip(sched, lower_schedule(sched[:])): + for s,(_,ei) in zip(sched, lower_schedule(sched[:])): ei.run() - if s.outputs[0].dtype == dtypes.float: - lst = s.outputs[0].as_buffer().cast("f").tolist() + if s.bufs[0].dtype == dtypes.float: + lst = s.bufs[0].as_buffer().cast("f").tolist() print(lst) assert not np.any(np.isnan(lst)) + # NOTE: the w1 grad must realize to a seperate kernel + assert w1.grad.lazydata.is_realized, f"never realized {w1.grad}" + self.assertEqual(w1.grad.lazydata.base.buffer.dtype, dtypes.float32) + self.assertEqual(len(sched), 10) + +@unittest.skipUnless(REAL_DEV in IMAGE_SUPPORTED_DEVICES, "Images not supported") +class TestImageRealization(unittest.TestCase): + def test_image_dtype_expand(self): + data = Tensor.randn(9*27*4).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() + self.assertEqual(it.dtype, dtypes.imagef((9,27,4))) + it_expanded = it.reshape((9,27,4,1)).expand((9,27,4,4)).contiguous().realize() + self.assertEqual(it_expanded.dtype, dtypes.float32) + + def test_image_dtype_expand_and_back(self): + data = Tensor.randn(9*27*4).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() + self.assertEqual(it.dtype, dtypes.imagef((9,27,4))) + it_expanded = it.reshape((9,27,4,1)).expand((9,27,4,4)) + it2 = it_expanded.sum(3).realize() + self.assertEqual(it2.dtype, dtypes.imagef((9,27,4))) + + def test_image_alu_children(self): + data = Tensor.randn(9*27*4).realize() + it = data.cast(dtypes.imagef((9,27,4))).contiguous().realize() + self.assertEqual(it.dtype, dtypes.imagef((9,27,4))) + it_expanded = it.reshape((9,27,4,1)).expand((9,27,4,4)).contiguous() + alu1 = it_expanded+1 + alu2 = it_expanded.sum(3) + it_expanded.realize() + # NOTE: the parent becomes float, but the alu child will stay image until its output cannot fit the image + self.assertEqual(alu1.dtype, dtypes.imagef((9,27,4))) + alu1.realize() + self.assertEqual(alu1.dtype, dtypes.float32) + # alu2 is back in image because it fits the dtype again + self.assertEqual(alu2.dtype, dtypes.imagef((9,27,4))) + alu2.realize() + self.assertEqual(alu2.dtype, dtypes.imagef((9,27,4))) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_interop.py b/tinygrad_repo/test/test_interop.py new file mode 100644 index 0000000000..dafe54319d --- /dev/null +++ b/tinygrad_repo/test/test_interop.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python +import unittest +import torch +import numpy as np + +from tinygrad.helpers import getenv, CI +from tinygrad.tensor import Tensor +from tinygrad.device import Device +from tinygrad.dtype import _from_torch_dtype, _to_torch_dtype + +MOCKGPU = getenv("MOCKGPU") + +@unittest.skipIf(Device.DEFAULT not in ["METAL", "CUDA"] or MOCKGPU, f"no support on {Device.DEFAULT}") +class TestInterop(unittest.TestCase): + def setUp(self): + if Device.DEFAULT == "CUDA": self.torch_device = "cuda" + elif Device.DEFAULT == "METAL": self.torch_device = "mps" + + def test_torch_interop(self): + inp = torch.rand(2, 2, 3, device=torch.device(self.torch_device)) + + if self.torch_device == "mps": torch.mps.synchronize() + else: torch.cuda.synchronize() + + tg_data = Tensor.from_blob(inp.data_ptr(), inp.shape, dtype=_from_torch_dtype(inp.dtype)) + + tg_out = tg_data[:, :, 0] * 0.2989 + tg_data[:, :, 1] * 0.5870 + tg_data[:, :, 2] * 0.1140 + tg_res = tg_out.numpy() + + if self.torch_device == "mps" and CI: + # MPS backend out of memory: https://discuss.pytorch.org/t/mps-back-end-out-of-memory-on-github-action/189773 + # Calculate expected value on cpu. + inp = inp.cpu() + torch_out = inp[:, :, 0] * 0.2989 + inp[:, :, 1] * 0.5870 + inp[:, :, 2] * 0.1140 + + np.testing.assert_allclose(tg_res, torch_out.cpu().numpy(), atol=1e-5, rtol=1e-5) + + def test_torch_interop_write(self): + tg_data = Tensor.randn((4, 4), device=Device.DEFAULT) + + out = torch.empty(4, 4, device=torch.device(self.torch_device), dtype=_to_torch_dtype(tg_data.dtype)) + tg_out = Tensor.from_blob(out.data_ptr(), out.shape, dtype=_from_torch_dtype(out.dtype)) + + tg_out.assign(tg_data).realize() + Device[Device.DEFAULT].synchronize() + + torch_out_np = out.cpu().numpy() + + np.testing.assert_allclose(tg_data.numpy(), torch_out_np, atol=1e-5, rtol=1e-5) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_jit.py b/tinygrad_repo/test/test_jit.py index a90ceab303..1b30ffc3b7 100644 --- a/tinygrad_repo/test/test_jit.py +++ b/tinygrad_repo/test/test_jit.py @@ -3,11 +3,11 @@ import unittest, functools import numpy as np from hypothesis import given, settings, strategies as strat -from test.helpers import assert_jit_cache_len +from test.helpers import assert_jit_cache_len, not_support_multi_device, REAL_DEV from tinygrad.tensor import Tensor from tinygrad.engine.jit import TinyJit from tinygrad.device import Device -from tinygrad.helpers import CI, Context, JIT +from tinygrad.helpers import Context, JIT, GlobalCounters from tinygrad.dtype import dtypes from extra.models.unet import ResBlock @@ -22,7 +22,7 @@ def _simple_test(add, extract=lambda x: x, N=10): class TestJit(unittest.TestCase): @settings(deadline=2e4) - @unittest.skipUnless(Device.DEFAULT in ["LLVM", "CLANG"], f"no support on {Device.DEFAULT}") + @unittest.skipUnless(REAL_DEV in ["LLVM", "CPU"], f"no support on {REAL_DEV}") @given(strat.sampled_from([Tensor.exp2, Tensor.log2, Tensor.sin])) def test_approx_jit_timeout(self, op): with Context(TRANSCENDENTAL=2): @@ -277,6 +277,38 @@ class TestJit(unittest.TestCase): assert len(res3) == 5, "All values should be different, rand works in jit." assert res3 != res2, "Jit rand is diff with diff seeds" + @unittest.expectedFailure # TODO: fix + def test_jit_v_nojit_random_regen(self): + def f(a, b): + rn = Tensor.randn(*a.shape) + rn = rn * a + rn2 = Tensor.randn(*a.shape) + rn2 = rn2 * b + rn = rn + rn2 + rn2 = rn2 + Tensor.randn(*a.shape) + return ((a+b)*rn).realize(), ((a+b)*rn2).realize() + Tensor.manual_seed(0) + a = Tensor.randn(10, 10).realize() # realize these before resetting the random seed + b = Tensor.randn(10, 10).realize() + + Tensor.manual_seed(1234) + without_jit = set() + for _ in range(5): + o1, o2 = f(a, b) + without_jit.add(o1.numpy()[0][0]) + without_jit.add(o2.numpy()[0][0]) + assert len(without_jit) == 10, "All values should be different." + + Tensor.manual_seed(1234) + jf = TinyJit(f) + with_jit = set() + for _ in range(5): + o1, o2 = jf(a, b) + with_jit.add(o1.numpy()[0][0]) + with_jit.add(o2.numpy()[0][0]) + assert len(with_jit) == 10, "All values should be different." + assert with_jit == without_jit, "Jit rand produced different values from no jit." + def test_jit_multiple_random_regen(self): def f(a, b): rn = Tensor.randn(*a.shape) @@ -318,6 +350,7 @@ class TestJit(unittest.TestCase): assert len(res3) == 10, "All values should be different, rand works in jit." assert res3 != res2, "Jit rand is diff with diff seeds" + #@unittest.expectedFailure # requires contiguous folding def test_jit_random_after_unrealized_random(self): @TinyJit def f(): return Tensor.rand() @@ -361,7 +394,6 @@ class TestJit(unittest.TestCase): np.testing.assert_allclose(result_2.numpy(), [6], atol=1e-4, rtol=1e-5) np.testing.assert_allclose(result_3.numpy(), [6], atol=1e-4, rtol=1e-5) - @unittest.skipIf(CI and Device.DEFAULT=="METAL", "no ICB in CI, creation of graph fails") def test_jit_batch_split(self): if Device[Device.DEFAULT].graph is None or JIT >= 2: raise unittest.SkipTest("only test graphs") @@ -406,7 +438,7 @@ class TestJit(unittest.TestCase): ja = jf(a) np.testing.assert_allclose(a.numpy(), ja.numpy(), atol=1e-4, rtol=1e-5) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL", "NV", "AMD"}, "no GPU CI") + @unittest.skipIf(not_support_multi_device(), "no multi") def test_jitted_transfers(self): d0, d1 = f"{Device.DEFAULT}:0", f"{Device.DEFAULT}:1" @@ -423,7 +455,23 @@ class TestJit(unittest.TestCase): np.testing.assert_allclose(a.numpy(), xc.numpy(), atol=1e-4, rtol=1e-5) np.testing.assert_allclose(b.numpy(), yc.numpy(), atol=1e-4, rtol=1e-5) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU/CUDA/METAL in CI, fine to run on AMD/NV") + def test_jit_several_devs(self): + d0, d1 = f"{Device.DEFAULT}:0", "CPU" + + def f(a, b): + x = a.to(d0).realize() + y = b.to(d0).realize() + return x+y.realize(), x*y.realize() + + jf = TinyJit(f) + for _ in range(5): + a = Tensor.randn(10, 10, device=d1).realize() + b = Tensor.randn(10, 10, device=d1).realize() + zc, wc = jf(a, b) + np.testing.assert_allclose((a.numpy()+b.numpy()), zc.numpy(), atol=1e-4, rtol=1e-5) + np.testing.assert_allclose((a.numpy()*b.numpy()), wc.numpy(), atol=1e-4, rtol=1e-5) + + @unittest.skipIf(not_support_multi_device(), "no multi") def test_jitted_view(self): d0, d1 = f"{Device.DEFAULT}:0", f"{Device.DEFAULT}:1" @@ -496,8 +544,8 @@ class TestCopyInsideJit(unittest.TestCase): @TinyJit def add(x,y) -> Tensor: return x.to(Device.DEFAULT)+y for _ in range(5): - # create a Tensor in CLANG - a = Tensor.rand(16,16,device="CLANG").realize() + # create a Tensor on CPU + a = Tensor.rand(16,16,device="CPU").realize() b = Tensor.rand(16,16).realize() out = add(a,b) np.testing.assert_allclose(out.flatten().tolist(), [x+y for x,y in zip(a.flatten().tolist(), b.flatten().tolist())]) @@ -528,15 +576,98 @@ class TestJitPrune(unittest.TestCase): w2_prune = TinyJit(w2, prune=True) for _ in range(3): - a = Tensor.rand(16, device="CLANG").realize() + a = Tensor.rand(16, device="CPU").realize() + out = w2_noprune(a) + np.testing.assert_allclose(out.tolist(), [x*2+y for x,y in zip(weights.tolist(), a.tolist())]) + + for _ in range(3): + a = Tensor.rand(16, device="CPU").realize() + out = w2_prune(a) + np.testing.assert_allclose(out.tolist(), [x*2+y for x,y in zip(weights.tolist(), a.tolist())]) + + def test_prune_w_independent_copy_correct(self): + weights = Tensor.rand(16, device="CPU").realize() + def w2(x) -> Tensor: return (weights*2).contiguous().to(Device.DEFAULT) + x + w2_noprune = TinyJit(w2) + w2_prune = TinyJit(w2, prune=True) + + for _ in range(3): + a = Tensor.rand(16).realize() out = w2_noprune(a) np.testing.assert_allclose(out.tolist(), [x*2+y for x,y in zip(weights.tolist(), a.tolist())]) for _ in range(3): - a = Tensor.rand(16, device="CLANG").realize() + a = Tensor.rand(16).realize() out = w2_prune(a) np.testing.assert_allclose(out.tolist(), [x*2+y for x,y in zip(weights.tolist(), a.tolist())]) + assert len(w2_prune.captured.jit_cache) == 1, "prune should have removed the copy" + +class TestJitFree(unittest.TestCase): + def test_free_intermediates(self): + ext_tensor = Tensor([1,24,23,45,1]) + @TinyJit + def fxn(x:Tensor): + out = (x*2+ext_tensor).reshape(5,1).expand(5, 100).contiguous() + return out.sum() + for i in range(5): + out = fxn(Tensor([i,1,2,3,4])) + self.assertEqual(out.item(), 11400+200*i) + pre_free = GlobalCounters.mem_used + fxn.captured.free_intermediates() + savings_after_free = pre_free - GlobalCounters.mem_used + + # Different allocator implementations have different savings. + expected_savings = 8196 if hasattr(Device[Device.DEFAULT].allocator, '_offset') else 2024 + + self.assertEqual(savings_after_free, expected_savings) + out = fxn(Tensor([11,1,2,3,4])) + self.assertEqual(out.item(), 13600) + + # Try one more time... + pre_free = GlobalCounters.mem_used + fxn.captured.free_intermediates() + fxn.captured.free_intermediates() # 2nd time to validate + savings_after_free = pre_free - GlobalCounters.mem_used + + self.assertEqual(savings_after_free, expected_savings) + out = fxn(Tensor([11,1,2,3,4])) + self.assertEqual(out.item(), 13600) + + def test_updated_not_freed(self): + x = Tensor([1]).realize() + @TinyJit + def fxn(y): + nonlocal x + x += y + return x + for _ in range(5): fxn(Tensor([1])) + self.assertEqual(x.item(), 6) + pre_free = GlobalCounters.mem_used + fxn.captured.free_intermediates() + savings_after_free = pre_free - GlobalCounters.mem_used + self.assertEqual(savings_after_free, 0) + fxn(Tensor([2])) + self.assertEqual(x.item(), 8) + + def test_replan_buffers_memory_layout(self): + if not hasattr(Device[Device.DEFAULT].allocator, '_offset'): raise unittest.SkipTest("replan_buffers_memory_layout useless") + + ext_tensor = Tensor([1,24,23,45,1]) + ext_tensor_2 = Tensor([2,2,2,2,2]) + @TinyJit + def fxn(x:Tensor): + out = (x*ext_tensor_2+ext_tensor).reshape(5,1).expand(5, 100).contiguous() + return out.sum() + for i in range(5): + out = fxn(Tensor([i,1,2,3,4])) + self.assertEqual(out.item(), 11400+200*i) + assert len(set([b.base for item in fxn.captured.jit_cache for b in item.bufs if b is not None])) == 4 + fxn.captured.replan_buffers_memory_layout() + assert len(set([b.base for item in fxn.captured.jit_cache for b in item.bufs if b is not None])) == 2 + + out = fxn(Tensor([11,1,2,3,4])) + self.assertEqual(out.item(), 13600) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_kernel_cache.py b/tinygrad_repo/test/test_kernel_cache.py index 851f4d83fd..164b501a41 100644 --- a/tinygrad_repo/test/test_kernel_cache.py +++ b/tinygrad_repo/test/test_kernel_cache.py @@ -5,7 +5,7 @@ from tinygrad import Device class TestKernelCache(unittest.TestCase): def test_kernel_cache_in_action(self): - if Device.DEFAULT not in ["CLANG"]: + if Device.DEFAULT not in ["CPU"]: self.skipTest("No custom kernel cache is implemented") unique_const = 0.6765677269 @@ -16,14 +16,14 @@ class TestKernelCache(unittest.TestCase): a1 = Tensor.rand(4,4).realize() b1 = Tensor.rand(4,4).realize() - orig_compile_func = Device['CLANG'].compiler - Device['CLANG'].compiler = None # making it not callable + orig_compile_func = Device['CPU'].compiler + Device['CPU'].compiler = None # making it not callable try: x1 = a1 + b1 + unique_const x1.realize() # Same kernel should be from cache. finally: - Device['CLANG'].compiler = orig_compile_func + Device['CPU'].compiler = orig_compile_func if __name__ == "__main__": unittest.main() diff --git a/tinygrad_repo/test/test_linearizer.py b/tinygrad_repo/test/test_linearizer.py index c7c441ebca..6466f7d609 100644 --- a/tinygrad_repo/test/test_linearizer.py +++ b/tinygrad_repo/test/test_linearizer.py @@ -1,4 +1,4 @@ -from typing import List, Tuple, Union +from typing import Union import numpy as np import unittest from dataclasses import replace @@ -6,52 +6,53 @@ from dataclasses import replace from test.helpers import ast_const from tinygrad.codegen.kernel import Opt, OptOps, KernelOptError, Kernel from tinygrad.codegen.lowerer import get_grouped_dims -from tinygrad.ops import UOp, Ops, GroupOp +from tinygrad.uop.ops import UOp, Ops, GroupOp from tinygrad.device import Device, Buffer, is_dtype_supported from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import View -# from tinygrad.ops import Variable from tinygrad.tensor import Tensor, _to_np_dtype -from tinygrad.engine.schedule import BUF_LIMIT, create_schedule from tinygrad.engine.realize import run_schedule, lower_schedule, CompiledRunner +from tinygrad.codegen.heuristic import hand_coded_optimizations from tinygrad.helpers import prod, Context, getenv, CI, flatten, dedup, AMX from tinygrad.dtype import DType, dtypes -def helper_realized_ast(r:Union[Tensor, List[Tensor]]) -> Tuple[UOp, List[Buffer]]: +def helper_realized_ast(r:Union[Tensor, list[Tensor]]) -> tuple[UOp, list[Buffer]]: if isinstance(r, Tensor): r = [r] - s = create_schedule([x.lazydata for x in r]) + s = Tensor.schedule(*r) run_schedule(s[:-1]) # run all kernels except the last one - # now all input LazyBuffers buffers in s[-1] should be realized - # create fresh buffers for the output buffer - bufs = [Buffer((x).device, x.size, x.dtype).allocate() if x in s[-1].outputs else x for x in s[-1].bufs] + assert s[-1].ast.op is Ops.SINK, f"helper_realized_ast expects a SINK {s[-1]}" + # now all input buffers in s[-1] should be realized + # create fresh buffers for the outputs + bufs = [Buffer((x).device, x.size, x.dtype).allocate() if i < len(s[-1].ast.src) else x for i,x in enumerate(s[-1].bufs)] return s[-1].ast, bufs -def helper_tc_allclose(n:int, m:int, k:int, dtype_in:DType, dtype_out:DType, axis:int=0, tc_opt:int=0): - a, b = Tensor.rand(m, k, dtype=dtype_in), Tensor.rand(k, n, dtype=dtype_in) +def helper_tc_allclose(N:int, M:int, K:int, dtype_in:DType, dtype_out:DType, axis:int=0, tc_select:int=-1, tc_opt:int=0, use_tensor_cores:int=1): + a, b = Tensor.rand(M, K, dtype=dtype_in), Tensor.rand(K, N, dtype=dtype_in) np_a, np_b = a.numpy(), b.numpy() - r = a.matmul(b, acc_dtype=dtype_out) - sched = create_schedule([r.lazydata]) - realized_ast = sched[-1].ast - run_schedule(sched) - out = r.numpy() + r = a.matmul(b, dtype=dtype_out) + if dtype_in == dtypes.bfloat16: r = r.float() + realized_ast, bufs = helper_realized_ast(r) k = Kernel(realized_ast) - k.apply_tensor_cores(1, axis=axis, tc_opt=tc_opt) - k.linearize() - assert len([uop for uop in k.uops if uop.op is Ops.WMMA]) > 0, "tensor core not triggered" + k.apply_tensor_cores(use_tensor_cores, axis=axis, tc_select=tc_select, tc_opt=tc_opt) + prg = CompiledRunner(replace(k.to_program(), device=Device.DEFAULT)) + if use_tensor_cores == 1: assert len([uop for uop in k.uops if uop.op is Ops.WMMA]) > 0, "wmma not triggered" + elif use_tensor_cores == 3: assert len([uop for uop in k.uops if uop.op is Ops.DEFINE_LOCAL]) == 2, "local buffers not triggered" assert len([x for x in k.applied_opts if x.op is OptOps.TC]) == 1, "tensor core opt not included" - np_c = np_a @ np_b - if dtype_out == dtypes.half: tc_atol, tc_rtol = 1e-2, 1e-3 - elif dtype_out == dtypes.bfloat16: tc_atol, tc_rtol = 1e-2, 1e-2 + prg.exec(bufs) + if dtype_in == dtypes.half: tc_atol, tc_rtol = 1e-2, 1e-3 + elif dtype_in == dtypes.bfloat16: tc_atol, tc_rtol = 1e-2, 1e-2 else: tc_atol, tc_rtol = 5e-3, 1e-4 - np.testing.assert_allclose(np_c, out, atol=tc_atol, rtol=tc_rtol) - -def helper_tc_ensure_uops_and_opts_count(n: int, m:int, k:int, dtype_in:DType, dtype_out:DType, axis:int=0, tc_opt:int=0, ensure_triggered:bool=True): - a, b = Tensor.rand(m, k, dtype=dtype_in), Tensor.rand(k, n, dtype=dtype_in) - r = a.matmul(b, acc_dtype=dtype_out) - sched = create_schedule([r.lazydata]) + c = bufs[0].numpy().reshape((M,N)) + np.testing.assert_allclose(c, np_a @ np_b, atol=tc_atol, rtol=tc_rtol) + +def helper_tc_ensure_uops_and_opts_count(N: int, M:int, K:int, dtype_in:DType, dtype_out:DType, axis:int=0, tc_select:int=-1, tc_opt:int=0, + ensure_triggered:bool=True): + a, b = Tensor.rand(M, K, dtype=dtype_in), Tensor.rand(K, N, dtype=dtype_in) + r = a.matmul(b, dtype=dtype_out) + sched = r.schedule() realized_ast = sched[-1].ast k = Kernel(realized_ast) - k.apply_tensor_cores(1, axis=axis, tc_opt=tc_opt) + k.apply_tensor_cores(1, axis=axis, tc_select=tc_select, tc_opt=tc_opt) k.linearize() wmmas = len([uop for uop in k.uops if uop.op is Ops.WMMA]) tcs = len([x for x in k.applied_opts if x.op is OptOps.TC]) @@ -64,10 +65,14 @@ def helper_tc_ensure_uops_and_opts_count(n: int, m:int, k:int, dtype_in:DType, d class TestLinearizer(unittest.TestCase): def test_arg_dedup(self): - a, b = Tensor.randn(4), Tensor.randn(4) + # NOTE: this realize exists because Tensor.numpy calls .contiguous() internally + # without contiguous folding, rand.to("CPU") and rand.contiguous().to("CPU") are different UOps. + # this test asserts they are the identical Buffer + # having different buffers is fine for correctness, because the outputs match. + a, b = Tensor.randn(4).realize(), Tensor.randn(4).realize() np_a, np_b = a.numpy(), b.numpy() c = ((a.shrink(((0, 2),)) - a.shrink(((2, 4),))) - (b.shrink(((0, 2),)) - b.shrink(((2, 4),)))) - lowered = list(lower_schedule(create_schedule([c.lazydata]))) + lowered = [x[1] for x in lower_schedule(c.schedule())] for ei in lowered: ei.run() rawbufs = lowered[-1].bufs assert len(rawbufs) == 3 and set(rawbufs[1:]) == {a.lazydata.base.realized, b.lazydata.base.realized} @@ -96,9 +101,9 @@ class TestLinearizer(unittest.TestCase): lin = helper_linearizer_ast(sink, [a_t, b_t], wanna_output=[a_t.numpy()+b_t.numpy(), a_t.numpy()*b_t.numpy()])[0] stores = [u for u in lin.uops if u.op is Ops.STORE] - mutable_bufs = dedup(flatten([[x for x in u.src[0].toposort if x.op is Ops.DEFINE_GLOBAL] for u in stores])) + mutable_bufs = dedup(flatten([[x for x in u.src[0].toposort() if x.op is Ops.DEFINE_GLOBAL] for u in stores])) assert len(mutable_bufs) == len(stores) == 2 - assert [u.arg for u in mutable_bufs] == [0, 1] + self.assertSetEqual(set([u.arg for u in mutable_bufs]), set([0,1])) def _test_no_nested_ranges(self, lins, skip=None): for l in lins: @@ -118,6 +123,8 @@ class TestLinearizer(unittest.TestCase): x = Tensor.randn(4,).realize() helper_linearizer_ast(store.sink(), [x], wanna_output=[x.numpy()+1*-1], opts=[]) + # shapeless CONST in AST is not supported + @unittest.expectedFailure def test_const_alu_indexing_one_const_fine(self): st = ShapeTracker.from_shape((4,)).to_uop() load = UOp.load(UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), st, dtype=dtypes.float) @@ -368,7 +375,6 @@ class TestLinearizer(unittest.TestCase): helper_linearizer_ast(sink, [x], wanna_output=[wanna_output, wanna_output/15]) @unittest.skipIf(CI and Device.DEFAULT in {"AMD"}, "AMD CI doesn't support multiple sync threads yet") - @unittest.expectedFailure def test_multiout_intermediate_multireduce(self): # check how it outputing at different stages of the multireduce works # TODO: Fails because the stores shapes do not match: store1.shape = (27,15,1,5) != store0.shape = (27,1,1,5) @@ -387,14 +393,9 @@ class TestLinearizer(unittest.TestCase): wanna_output0 = (x.numpy()-x.numpy().sum(axis=1, keepdims=True)).sum(axis=1).reshape(27,1,1,5) wanna_output1 = x.numpy().sum(axis=1).reshape(27,1,1,5) - ast = UOp(Ops.SINK, src=(store0, store1)) - k = Kernel(ast) - prg = CompiledRunner(replace(k.to_program(), device=Device.DEFAULT)) - inbufs = [x.lazydata.base.buffer] - outbufs = [Buffer(inbufs[-1].device if inbufs else Device.DEFAULT, out.arg.st.size, out.arg.dtype).allocate() for out in ast.src] - prg.exec(outbufs+inbufs) - np.testing.assert_allclose(np.frombuffer(outbufs[0].as_buffer(), _to_np_dtype(outbufs[0].dtype)).reshape(27,1,1,5), wanna_output0) - np.testing.assert_allclose(np.frombuffer(outbufs[1].as_buffer(), _to_np_dtype(outbufs[1].dtype))[:135].reshape(27,1,1,5), wanna_output1) + sink = UOp(Ops.SINK, src=(store0, store1)) + with self.assertRaises(RuntimeError): # AST is invalid + helper_linearizer_ast(sink, [x], wanna_output=[wanna_output0, wanna_output1]) @unittest.skipIf(CI and Device.DEFAULT in {"AMD"}, "AMD CI doesn't support multiple sync threads yet") def test_complete_unroll_multireduce(self): @@ -516,7 +517,7 @@ class TestLinearizer(unittest.TestCase): first_x = UOp(Ops.LOAD, dtypes.float, (g1, x.lazydata.st.reshape((3, 27, 1, 32)).expand((3, 27, 32, 32)).to_uop())) first_reduce = UOp(Ops.REDUCE_AXIS, dtypes.float, (first_x,), (Ops.ADD, (3,))) neg_mean = first_reduce * ast_const(dtypes.float, -0.03125, (3, 27, 32, 1)) - # store = UOp(UOps.STORE, src=(g0, ShapeTracker.from_shape((3, 27, 32, 1)).to_uop(), mean)) + # store = UOp(Ops.STORE, src=(g0, ShapeTracker.from_shape((3, 27, 32, 1)).to_uop(), mean)) # verify_lazyop(store) second_x = UOp(Ops.LOAD, dtypes.float, (g1, x.lazydata.st.reshape((3, 27, 32, 1)).to_uop())) squares = (second_x+neg_mean)*(second_x+neg_mean) @@ -839,7 +840,8 @@ class TestLinearizer(unittest.TestCase): sink = UOp(Ops.SINK, src=(store,)) load_t = Tensor.full(load.st_arg.shape, 1).contiguous().realize() k = helper_linearizer_ast(sink, [load_t], wanna_output=[load_t.numpy().sum()])[1] - self.assertEqual(k.uops[-1].op, Ops.ENDIF) + self.assertEqual(k.uops[-2].op, Ops.ENDIF) + self.assertEqual(k.uops[-1].op, Ops.SINK) self.assertLess(k.uops.index([x for x in k.uops if x.op is Ops.STORE][-1]), k.uops.index(k.uops[-1])) def test_two_nested_range(self): @@ -849,7 +851,7 @@ class TestLinearizer(unittest.TestCase): ranges = [i for i,u in enumerate(lin.uops) if u.op is Ops.RANGE] assert len(ranges) == 1 # NOTE: it collapses now # RANGE -> LOAD -> RANGE -> ASSIGN - #assert any(x.op is UOps.LOAD for x in lin.uops[ranges[0]:ranges[1]]) + #assert any(x.op is Ops.LOAD for x in lin.uops[ranges[0]:ranges[1]]) def test_three_nested_range(self): a = Tensor.randn(2, ).realize() @@ -860,7 +862,7 @@ class TestLinearizer(unittest.TestCase): # RANGE -> RANGE -> LOAD -> RANGE -> ASSIGN # NOTE: nothing should toposort between the first two ranges #assert ranges[0]+1 == ranges[1] - #assert any(x.op is UOps.LOAD for x in lin.uops[ranges[1]:ranges[2]]) + #assert any(x.op is Ops.LOAD for x in lin.uops[ranges[1]:ranges[2]]) def test_two_nested_range_alt_indexing(self): a = Tensor([2, 2]).realize() @@ -890,14 +892,14 @@ class TestLinearizer(unittest.TestCase): assert len(ranges) == 1 # NOTE: it collapses now #if getenv("PTX"): # LOAD -> RANGE -> CAST -> ALU -> ALU -> LOAD -> ALU -> RANGE -> ALU -> ASSIGN - # assert lin.uops[ranges[0]-2].op is UOps.LOAD + # assert lin.uops[ranges[0]-2].op is Ops.LOAD # assert ranges[1] == ranges[0]+6 - # assert [x.op for x in lin.uops[ranges[1]-2:ranges[1]]] == [UOps.LOAD, UOps.ALU] + # assert [x.op for x in lin.uops[ranges[1]-2:ranges[1]]] == [Ops.LOAD, Ops.ALU] # LOAD -> RANGE -> LOAD -> ALU -> RANGE -> ASSIGN #else: - # assert lin.uops[ranges[0]-2].op is UOps.LOAD + # assert lin.uops[ranges[0]-2].op is Ops.LOAD # assert ranges[1] == ranges[0]+3 - # assert [x.op for x in lin.uops[ranges[1]-2:ranges[1]]] == [UOps.LOAD, UOps.ALU] + # assert [x.op for x in lin.uops[ranges[1]-2:ranges[1]]] == [Ops.LOAD, Ops.ALU] def test_range_outer_op_after_phi(self): a = Tensor.randn(4, 1).realize() @@ -924,7 +926,7 @@ class TestLinearizer(unittest.TestCase): # these are of size 3 to avoid float4 coalesce r = a[:-1] + a[1:] - k = Kernel(create_schedule([r.lazydata])[-1].ast) + k = Kernel(r.schedule()[-1].ast) k.upcast() k.linearize() num_loads = len([uop for uop in k.uops if uop.op is Ops.LOAD]) @@ -947,7 +949,7 @@ class TestLinearizer(unittest.TestCase): sink = UOp(Ops.SINK, src=(store,)) lin = Kernel(sink) lin.linearize() - assert len(lin.uops) <= 9, "too many uops" + assert len(lin.uops) <= 10, "too many uops" def test_upcast_cse(self): # when upcasting, within a subtree, there may be common expressions. @@ -955,7 +957,7 @@ class TestLinearizer(unittest.TestCase): a, b = Tensor.randn(1).realize(), Tensor.randn(1).realize() r = a.expand([2]) + b.expand([2]) - k = Kernel(create_schedule([r.lazydata])[-1].ast) + k = Kernel(r.schedule()[-1].ast) k.upcast() k.linearize() num_ops = len([uop for uop in k.uops if uop.op in GroupOp.ALU]) @@ -966,7 +968,7 @@ class TestLinearizer(unittest.TestCase): x, w = Tensor.randn((1,1,3)).realize(), Tensor.randn((1,1,2)).realize() r = Tensor.conv2d(x,w,padding=1).relu() - k = Kernel(create_schedule([r.lazydata])[-1].ast) + k = Kernel(r.schedule()[-1].ast) k.upcast() k.upcast() k.linearize() @@ -976,6 +978,16 @@ class TestLinearizer(unittest.TestCase): assert len(stores) == 1 assert stores[0].src[-1].dtype == dtypes.float.vec(4) + # NOTE: can reenable, it does work. it just makes BEAM slow + @unittest.expectedFailure + @unittest.skipUnless(Device.DEFAULT == "CPU", "test only for CPU") + def test_upcast_with_locals_cpu(self): + out = Tensor.ones(64,64).contiguous() @ Tensor.ones(64,64).contiguous() + k = Kernel(out.schedule()[-1].ast) + k.apply_opt(Opt(OptOps.LOCAL, axis=0, arg=4)) + prg = k.to_program() + self.assertEqual(len(prg.src.split("for")), 5) + @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test requires locals") @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_shared, "test requires shared") @unittest.skipUnless(Device[Device.DEFAULT].renderer.supports_float4, "test requires float4") @@ -983,24 +995,24 @@ class TestLinearizer(unittest.TestCase): def test_upcast_with_locals(self): x, y = Tensor.rand(1,128), Tensor.rand(128, 128) r = (x@y).relu() - k = Kernel(create_schedule([r.lazydata])[-1].ast) - k.hand_coded_optimizations() + k = Kernel(r.schedule()[-1].ast) + k.apply_opts([Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4)]) k.linearize() stores = [u for u in k.uops if u.op is Ops.STORE] # the first store is to lds and can be upcasted assert stores[0].src[-1].dtype == dtypes.float.vec(4) - assert any(x.op is Ops.DEFINE_LOCAL for x in stores[0].toposort) + assert any(x.op is Ops.DEFINE_LOCAL for x in stores[0].toposort()) # the second store is to gds with no upcasts assert stores[1].src[-1].dtype == dtypes.float - assert any(x.op is Ops.DEFINE_GLOBAL for x in stores[1].toposort) + assert any(x.op is Ops.DEFINE_GLOBAL for x in stores[1].toposort()) def test_zero_fold(self): a, b = Tensor.randn(1).realize(), Tensor.randn(1).realize() r = Tensor.stack(a, b) - k = Kernel(create_schedule([r.lazydata])[-1].ast) + k = Kernel(r.schedule()[-1].ast) k.upcast() k.linearize() num_ops = len([uop for uop in k.uops if uop.op in GroupOp.ALU]) @@ -1011,14 +1023,14 @@ class TestLinearizer(unittest.TestCase): (dtypes.bool, dtypes.int), (dtypes.int16, dtypes.int), (dtypes.float16, dtypes.float), (dtypes.bfloat16, dtypes.float)): if is_dtype_supported(tensor_dtype) and is_dtype_supported(acc_dtype): a = Tensor([1, 2, 3], dtype=tensor_dtype).sum() - k = Kernel(create_schedule([a.lazydata])[-1].ast) + k = Kernel(a.schedule()[-1].ast) k.linearize() local = [uop for uop in k.uops if uop.op is Ops.DEFINE_ACC] assert local[0].dtype == acc_dtype def test_arg_acc_dtype(self): def helper_arg_acc_dtype(c: Tensor, expected_dtype:DType): - k = Kernel(create_schedule([c.lazydata])[-1].ast) + k = Kernel(c.schedule()[-1].ast) k.linearize() local = [uop for uop in k.uops if uop.op is Ops.DEFINE_ACC] assert local[0].dtype == expected_dtype @@ -1034,26 +1046,69 @@ class TestLinearizer(unittest.TestCase): for tensor_dtype, acc_dtype, expected_dtype in tests: if is_dtype_supported(tensor_dtype) and is_dtype_supported(acc_dtype) and is_dtype_supported(expected_dtype): a, b = Tensor.rand(8, 8, dtype=tensor_dtype), Tensor.rand(8, 8, dtype=tensor_dtype) - helper_arg_acc_dtype(a.sum(acc_dtype=acc_dtype), expected_dtype) - helper_arg_acc_dtype(a.matmul(b, acc_dtype=acc_dtype), expected_dtype) - helper_arg_acc_dtype(Tensor.einsum("ki,ij->kj", a, b, acc_dtype=acc_dtype), expected_dtype) + helper_arg_acc_dtype(a.sum(dtype=acc_dtype), expected_dtype) + helper_arg_acc_dtype(a.matmul(b, dtype=acc_dtype), expected_dtype) + helper_arg_acc_dtype(Tensor.einsum("ki,ij->kj", a, b, dtype=acc_dtype), expected_dtype) d, w = Tensor.rand(4, 8, 8, 8, dtype=tensor_dtype), Tensor.rand(8, 8, 2, 2, dtype=tensor_dtype) - helper_arg_acc_dtype(d.conv2d(w, acc_dtype=acc_dtype), expected_dtype) + helper_arg_acc_dtype(d.conv2d(w, dtype=acc_dtype), expected_dtype) + # TODO: don't skip bf16 for real device (METAL, AMD) @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") def test_tensor_cores(self): for tc in Device[Device.DEFAULT].renderer.tensor_cores: - if (getenv("EMULATE_CUDA") or getenv("EMULATE_INTEL") or getenv("EMULATE_METAL")) and \ - (tc.dtype_in == dtypes.bfloat16 or tc.dtype_out == dtypes.bfloat16): continue - if CI and Device.DEFAULT == "METAL" and (tc.dtype_in == dtypes.bfloat16 or tc.dtype_out == dtypes.bfloat16): continue + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue # for AMX, tc.dims[2] == 1 so reduceop is None thus tensor_cores are not triggered helper_tc_allclose(tc.dims[0], tc.dims[1], 2 if AMX else tc.dims[2], tc.dtype_in, tc.dtype_out, axis=0, tc_opt=0) + @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") + def test_tensor_cores_emulation(self): + for tc in Device[Device.DEFAULT].renderer.tensor_cores: + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue + # for AMX, tc.dims[2] == 1 so reduceop is None thus tensor_cores are not triggered + helper_tc_allclose(tc.dims[0], tc.dims[1], 2 if AMX else tc.dims[2], tc.dtype_in, tc.dtype_out, axis=0, tc_opt=0, use_tensor_cores=3) + + @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") + def test_tensor_cores_codegen(self): + for tc in Device[Device.DEFAULT].renderer.tensor_cores: + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue + n, m, k = tc.dims[0], tc.dims[1], 2 if AMX else tc.dims[2] + a, b = Tensor.rand(m, k, dtype=tc.dtype_in), Tensor.rand(k, n, dtype=tc.dtype_in) + r = a.matmul(b, dtype=tc.dtype_out) + sched = r.schedule() + realized_ast = sched[-1].ast + kernel = Kernel(realized_ast) + kernel.apply_tensor_cores(1, axis=0, tc_select=-1, tc_opt=2) + kernel.linearize() + prg = kernel.to_program() + if Device.DEFAULT == "LLVM": + assert "0x201000" in prg.src + elif Device.DEFAULT == "AMD" and getenv("AMD_LLVM", 0): + assert "@llvm.amdgcn.wmma" in prg.src + elif Device[Device.DEFAULT].renderer.suffix == "PTX": + assert "mma.sync.aligned" in prg.src + else: + assert "__WMMA_" in prg.src + + @unittest.skipIf(Device.DEFAULT in ("AMD", "AMD_LLVM") or (Device.DEFAULT == "PYTHON" and getenv("EMULATE_AMD")), "broken for AMD") @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") def test_tensor_cores_padded(self): for tc in Device[Device.DEFAULT].renderer.tensor_cores: - if (getenv("EMULATE_CUDA") or getenv("EMULATE_METAL")) and (tc.dtype_in == dtypes.bfloat16 or tc.dtype_out == dtypes.bfloat16): continue - if CI and Device.DEFAULT == "METAL" and (tc.dtype_in == dtypes.bfloat16 or tc.dtype_out == dtypes.bfloat16): continue + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue + helper_tc_allclose(tc.dims[0]+(pad:=1), tc.dims[1]+pad, tc.dims[2]+pad, tc.dtype_in, tc.dtype_out, tc_opt=2) + + # AMD compiler bug: AMD miscompiles non-zero padded tc kernels with -O3, producing wrong results, nans or hang (see #9606) + # Internal bug: zero-stride dimensions combined with a mask may produce wrong index/valid for pad == 1 on AMD + @unittest.skipUnless(Device.DEFAULT in ("AMD", "AMD_LLVM") or (Device.DEFAULT == "PYTHON" and getenv("EMULATE_AMD")), "test for AMD's tc") + @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") + @unittest.expectedFailure + def test_tensor_cores_padded_amd(self): + for tc in Device[Device.DEFAULT].renderer.tensor_cores: + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue + helper_tc_allclose(tc.dims[0]+(pad:=1), tc.dims[1]+pad, tc.dims[2]+pad, tc.dtype_in, tc.dtype_out, tc_opt=2) + + @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") + def test_tensor_cores_padded_uops(self): + for tc in Device[Device.DEFAULT].renderer.tensor_cores: pad = 1 # check that TC is triggered for TC_OPT=2 @@ -1072,20 +1127,17 @@ class TestLinearizer(unittest.TestCase): if not AMX: # AMX tc.dims[2] == 1 helper_tc_ensure_uops_and_opts_count(tc.dims[0], tc.dims[1], tc.dims[2]//4, tc.dtype_in, tc.dtype_out, tc_opt=2, ensure_triggered=False) - # check correctness - helper_tc_allclose(tc.dims[0]+pad, tc.dims[1]+pad, tc.dims[2]+pad, tc.dtype_in, tc.dtype_out, tc_opt=2) - @unittest.skipIf(CI and Device.DEFAULT in {"AMD"}, "AMD CI is really slow here") @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") def test_tensor_cores_multi_reduce(self): for tc in Device[Device.DEFAULT].renderer.tensor_cores: - if tc.dtype_in == dtypes.bfloat16 or tc.dtype_out == dtypes.bfloat16: continue + if not is_dtype_supported(tc.dtype_in) or not is_dtype_supported(tc.dtype_out): continue # this will be a M=G16, N=G32, M=G16, M=G16, K=R16, K=R16, K=R16 with 9 choices of TC MNK axes golden_result = None for axis in range(9): a = Tensor.rand(16, 16, 29, 29, dtype=tc.dtype_in).realize() b = Tensor.rand(32, 16, 16, 16, dtype=tc.dtype_in).realize() - c = a.conv2d(b, padding=1, acc_dtype=tc.dtype_out) + c = a.conv2d(b, padding=1, dtype=tc.dtype_out) realized_ast, real_bufs = helper_realized_ast(c) k = Kernel(realized_ast) @@ -1095,6 +1147,8 @@ class TestLinearizer(unittest.TestCase): assert len([x for x in k.applied_opts if x.op is OptOps.TC]) == 1, "tensor core opt not included" prg = CompiledRunner(k.to_program()) + # TODO: support this even if numpy doesn't + if _to_np_dtype(real_bufs[0].dtype) is None: continue real_bufs[0].copyin(np.zeros((real_bufs[0].size, ), dtype=_to_np_dtype(real_bufs[0].dtype)).data) # Zero to check that all values are filled prg.exec(real_bufs) result = np.frombuffer(real_bufs[0].as_buffer(), _to_np_dtype(real_bufs[0].dtype)) @@ -1106,24 +1160,26 @@ class TestLinearizer(unittest.TestCase): # check that get_kernel_actions produces all 9 options from tinygrad.engine.search import get_kernel_actions tc_actions = [k for i, k in get_kernel_actions(Kernel(realized_ast), False).items() if k.applied_opts[0].op == OptOps.TC] - assert len(tc_actions) == 9, f"get_kernel_actions should contain 9 possible TC actions, only got {len(tc_actions)}" + + available_tc = len([x for x in Device[Device.DEFAULT].renderer.tensor_cores if x.dtype_in == tc.dtype_in and x.dtype_out == tc.dtype_out]) + assert len(tc_actions) == 9 * available_tc, f"should contain 9 possible TC actions for every available TC, got {len(tc_actions)}" @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") def test_tensor_cores_unroll_phi(self): tc = Device[Device.DEFAULT].renderer.tensor_cores[0] x, y = Tensor.rand(128, 128, dtype=tc.dtype_in), Tensor.rand(128, 128, dtype=tc.dtype_in) - r = x.matmul(y, acc_dtype=tc.dtype_out) + r = x.matmul(y, dtype=tc.dtype_out) k = helper_linearizer_opt(r, [[Opt(OptOps.UNROLL, 0, 4)]], apply_tc=True, atol=3e-2, rtol=1e-3)[-1] for u in k.uops: if u.op is Ops.WMMA: assert u.src[-1].src[0].op != Ops.ASSIGN @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") - @unittest.skipIf(Device.DEFAULT in {"CLANG"}, "CLANG does not support using a different type for accumulation") + @unittest.skipIf(Device.DEFAULT in {"CPU", "LLVM"}, "CPU does not support using a different type for accumulation") def test_tensor_cores_unroll_casted_phi(self): tc = [tc for tc in Device[Device.DEFAULT].renderer.tensor_cores if tc.dtype_in != tc.dtype_out][0] x, y = Tensor.rand(128, 128, dtype=tc.dtype_in), Tensor.rand(128, 128, dtype=tc.dtype_in) - r = x.matmul(y, acc_dtype=tc.dtype_out) + r = x.matmul(y, dtype=tc.dtype_out) k = helper_linearizer_opt(r, [[Opt(OptOps.UNROLL, 0, 4)]], apply_tc=True, atol=3e-2, rtol=1e-3)[-1] for u in k.uops: if u.op is Ops.WMMA: @@ -1131,12 +1187,12 @@ class TestLinearizer(unittest.TestCase): assert u.src[-1].src[0].op != Ops.ASSIGN @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") - @unittest.skipIf(Device.DEFAULT in {"CLANG"}, "CLANG does not support using a different type for accumulation") + @unittest.skipIf(Device.DEFAULT in {"CPU", "LLVM"}, "CPU does not support using a different type for accumulation") def test_tensor_cores_unroll_casted_phi_with_children(self): # all ASSIGN children are outside the loop tc = [tc for tc in Device[Device.DEFAULT].renderer.tensor_cores if tc.dtype_in != tc.dtype_out][0] x, y = Tensor.rand(128, 128, dtype=tc.dtype_in), Tensor.rand(128, 128, dtype=tc.dtype_in) - r = x.matmul(y, acc_dtype=tc.dtype_out).relu() + r = x.matmul(y, dtype=tc.dtype_out).relu() k = helper_linearizer_opt(r, [[Opt(OptOps.UNROLL, 0, 4)]], apply_tc=True, atol=3e-2, rtol=1e-3)[-1] for u in k.uops: if u.op is Ops.WMMA: @@ -1158,13 +1214,14 @@ class TestLinearizer(unittest.TestCase): assert end_range < k.uops.index(u) def test_grouped_dims(self): - def _assert_grouped_dims(prefix, dims, max_sizes, reverse_dims, expected_sizes): + def _assert_grouped_dims(prefix, dims, max_sizes, reverse_dims, expected_sizes, assert_same_length = True): idxs = get_grouped_dims(prefix, dims, max_sizes, reverse_dims) - loop_idxs = dedup(flatten([[y for y in x.toposort if y.op is Ops.SPECIAL] for x in idxs])) + loop_idxs = dedup(flatten([[y for y in x.toposort() if y.op is Ops.SPECIAL] for x in idxs])) loop_idxs = sorted(loop_idxs, key=lambda uop: uop.arg[0]) sizes = [x.arg[1] for x in loop_idxs] assert len(idxs) == len(dims), f"expected idxs to have same length as dims {len(dims)}, got {len(idxs)}" - assert len(loop_idxs) == min(len(sizes), len(dims)), f"expected idxs to have length {min(len(sizes), len(dims))}, got {len(loop_idxs)}" + if assert_same_length: + assert len(loop_idxs) == min(len(sizes), len(dims)), f"expected idxs to have length {min(len(sizes), len(dims))}, got {len(loop_idxs)}" assert sizes == expected_sizes, f"expected sizes={expected_sizes}, got {sizes=}" # TODO: add these back after uop symbolic # for i in range(len(dims)): @@ -1181,11 +1238,26 @@ class TestLinearizer(unittest.TestCase): _assert_grouped_dims("gidx", (2,3), (16,16,16), True, [3,2]) _assert_grouped_dims("gidx", (2,3,4), (16,16,16), False, [2,3,4]) - # test splitting globals - # _assert_grouped_dims("gidx", (64,3,4), (16,16,16), False, [16,12,4]) - # _assert_grouped_dims("gidx", (64,3,4), (16,4,16), False, [16,4,12]) - # _assert_grouped_dims("gidx", (64,3,4), (16,16,16), True, [12,16,4]) - # _assert_grouped_dims("gidx", (128,3,4), (16,4,256), False, [16,4,24]) + # test splitting globals: len(dims) == len(max) + _assert_grouped_dims("gidx", (64,3,4), (16,16,16), False, [16,12,4]) + _assert_grouped_dims("gidx", (64,3,4), (16,4,16), False, [16,3,16]) + _assert_grouped_dims("gidx", (64,3,4), (16,16,16), True, [16,3,16]) + _assert_grouped_dims("gidx", (128,3,4), (16,4,256), False, [16,3,32]) + _assert_grouped_dims("gidx", (4,4,512), (16,4,256), False, [8,4,256]) + + # prefer group_dim strategy when possible + _assert_grouped_dims("gidx", (512,4,2), (8192,2,2), False, [2048,2]) + + # test splitting globals: len(dims) < len(max) + # len(dim) -> len(limited) + # 1 -> 2 + _assert_grouped_dims("gidx", (128,), (16,16,256), False, [16,8], False) + # 1 -> 3 + _assert_grouped_dims("gidx", (65536,), (16,16,256), False, [16,16,256], False) + # 2 -> 3 + _assert_grouped_dims("gidx", (128,128), (16,16,256), False, [16,16,64], False) + # test when the only divisor is the square root of dim + _assert_grouped_dims("gidx", (121,), (12,12,12), False, [11,11], False) # collapse on onto the left most axis _assert_grouped_dims("gidx", (2,3,4,5), (16,16,16), False, [6,4,5]) @@ -1198,11 +1270,11 @@ class TestLinearizer(unittest.TestCase): # _assert_grouped_dims("gidx", (Variable("start_pos",1,2),3,4,5), (16,16,16), False, [Variable("start_pos",1,2)*3,4,5]) - # # dim too large and not factorable - # with self.assertRaises(AssertionError): - # get_grouped_dims("gidx", (23,), (16,16,16), False,) - # with self.assertRaises(AssertionError): - # get_grouped_dims("gidx", (128,3,4), (16,4,23), False,) + # dim too large and not factorable + with self.assertRaises(RuntimeError): + get_grouped_dims("gidx", (23,), (16,16,16), False,) + with self.assertRaises(RuntimeError): + get_grouped_dims("gidx", (128,3,4), (16,2,2), False,) # too large for sizes with self.assertRaises(RuntimeError): @@ -1223,33 +1295,14 @@ class TestLinearizer(unittest.TestCase): assert idxs[1].arg == ('gidx1', 5), idxs[1].arg assert idxs[2].arg == ('gidx2', 4), idxs[2].arg - def test_div_collapse(self): - def helper(t, msg, max_ops=0): - sched = [si for si in create_schedule([t.lazydata]) if si.ast.op is Ops.SINK] - assert len(sched) == 1 - - lin = Kernel(sched[0].ast) - assert sum(u.op in {Ops.RECIP, Ops.FDIV} for u in lin.linearize().uops) == max_ops, msg - - a = Tensor.empty((4,4)) - b = Tensor.empty((4,4)) - d = Tensor.empty((4,4)) - - c = (a*b)/b - helper(c, "found Ops.RECIP in (a*b)/b operation") - - c = a/a - helper(c, "found Ops.RECIP in (a/a) operation") - - c = (a/b)/d - helper(c, "found multiple Ops.RECIP in (a/b)/d operation", 1) - def test_sum_collapse(self): t = Tensor([2]).reshape(1, 1).expand(256, 256).sum() - sched = [si for si in create_schedule([t.lazydata]) if si.ast.op is Ops.SINK] + sched = [si for si in t.schedule() if si.ast.op is Ops.SINK] + # sum_collapse is a full collapse now assert len(sched) == 1 - lin = Kernel(sched[0].ast) - assert not any(u.op is Ops.RANGE for u in lin.linearize().uops), "found loop in sum collapse" + assert not any(u.op is Ops.REDUCE_AXIS for u in sched[0].ast.toposort()), "found reduce in sum collapse" + #lin = Kernel(sched[0].ast) + #assert not any(u.op is Ops.RANGE for u in lin.linearize().uops), "found loop in sum collapse" def test_assign_fold(self): a = Tensor.ones(4, 4).contiguous().realize() @@ -1262,13 +1315,12 @@ class TestLinearizer(unittest.TestCase): a = Tensor.ones(4, 4).contiguous().realize() b = a.shrink(((1, 2), None)).pad(((1, 2), None)) a.assign(b.where(2, a)) - sched = create_schedule([a.lazydata]) + sched = a.schedule() assert len(sched) == 1 sched_copy = sched[:] run_schedule(sched) np.testing.assert_equal(a.flatten().numpy(), [1.,1.,1.,1.,2.,2.,2.,2.,1.,1.,1.,1.,1.,1.,1.,1.]) lin = Kernel(sched_copy[-1].ast) - lin.hand_coded_optimizations() lin.linearize() assert not any(u.op == Ops.WHERE for u in lin.uops), "found where where where should be folded" @@ -1308,7 +1360,7 @@ class TestLinearizer(unittest.TestCase): # check that the float4 cast collapses store_vals = [u.src[-1] for u in k.uops if u.op is Ops.STORE] for val in store_vals: - assert val.dtype == dtypes.float.vec(4) # and val.op is not UOps.VECTORIZE + assert val.dtype == dtypes.float.vec(4) # and val.op is not Ops.VECTORIZE @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test requires locals") @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_shared, "test requires shared") @@ -1318,10 +1370,10 @@ class TestLinearizer(unittest.TestCase): helper_linearizer_opt(a, [ [Opt(OptOps.GROUP, 0, 32)], [Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(op=OptOps.LOCAL, axis=0, amt=8)], - [Opt(op=OptOps.LOCAL, axis=0, amt=8), Opt(op=OptOps.UPCAST, axis=0, amt=0)], - [Opt(op=OptOps.LOCAL, axis=0, amt=8), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.GROUP, axis=0, amt=8)], - [Opt(op=OptOps.LOCAL, axis=0, amt=8), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.GROUP, axis=0, amt=8), Opt(op=OptOps.UNROLL, axis=1, amt=4)], # noqa: E501 + [Opt(op=OptOps.LOCAL, axis=0, arg=8)], + [Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=0, arg=0)], + [Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.GROUP, axis=0, arg=8)], + [Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.UNROLL, axis=1, arg=4)], # noqa: E501 ]) @unittest.skipUnless(Device[Device.DEFAULT].renderer.supports_float4, "test requires float4") @@ -1347,7 +1399,7 @@ class TestLinearizer(unittest.TestCase): barrier = [u for u in k.uops if u.op is Ops.BARRIER][0] # check that the float4 cast collapses for all stores for store in local_stores+global_stores: - assert store.src[-1].dtype.count > 1 # and store.src[2].op is not UOps.VECTORIZE + assert store.src[-1].dtype.count > 1 # and store.src[2].op is not Ops.VECTORIZE # # check the children's vins # TODO: src ALU are not the same, should it? # assert barrier.src == tuple(local_stores) @@ -1364,7 +1416,7 @@ class TestLinearizer(unittest.TestCase): # the float4 value stores directly in lds and we skip upcast self.assertEqual(stores[0].src[-1].dtype, dtypes.float.vec(4)) - #assert stores[0].src[-1].op is not UOps.VECTORIZE + #assert stores[0].src[-1].op is not Ops.VECTORIZE # the global store doesn't change assert stores[1].src[-1].dtype == dtypes.float @@ -1381,8 +1433,8 @@ class TestLinearizer(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1), UOp(Ops.VIEW, arg=ShapeTracker(views=(View(shape=(240, 40, 1, 1), strides=(1, 240, 0, 0), offset=0, mask=None, contiguous=False),))),)),)),)) # noqa: E501 opt = [ - Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16), - Opt(op=OptOps.LOCAL, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=3, amt=2) + Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16), + Opt(op=OptOps.LOCAL, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=3, arg=2) ] k = helper_linearizer_ast(ast, [Tensor.randn(240*40).realize()], opts=[opt])[-1] out = [u for u in k.uops if u.op is Ops.STORE][0] @@ -1399,9 +1451,9 @@ class TestLinearizer(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1), UOp(Ops.VIEW, arg=ShapeTracker(views=(View(shape=(8, 32, 1, 1), strides=(1, 8, 0, 0), offset=0, mask=None, contiguous=False),))),)),)),)) # noqa: E501 - opt = [Opt(op=OptOps.LOCAL, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=2, amt=2), Opt(op=OptOps.LOCAL, axis=1, amt=8), - Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=8), - Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=0, amt=2)] + opt = [Opt(op=OptOps.LOCAL, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=2, arg=2), Opt(op=OptOps.LOCAL, axis=1, arg=8), + Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=8), + Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=2)] k = helper_linearizer_ast(ast, [Tensor.randn(8*32).realize()], opts=[opt])[-1] out = [u for u in k.uops if u.op is Ops.STORE][0] assert out.src[-1].op is Ops.VECTORIZE and out.src[-1].dtype.count != 1 @@ -1417,27 +1469,25 @@ class TestFloat4(unittest.TestCase): return (len([uop for uop in k.uops if uop.op is Ops.LOAD and uop.dtype == dtypes.half.vec(4)]), len([uop for uop in k.uops if uop.op is Ops.STORE and uop.src[-1].dtype == dtypes.half.vec(4)])) - # TODO: express opts below as auto opts - def test_float4_basic(self): - a = Tensor.rand(2, 8).realize() - b = Tensor.rand(2, 8).realize() + a = Tensor.empty(2, 8).realize() + b = Tensor.empty(2, 8).realize() c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) - k.hand_coded_optimizations() + k.apply_opts([Opt(op=OptOps.UPCAST, axis=0, arg=4)]) k.linearize() assert TestFloat4.count_float4(k) == (2, 1) - @unittest.skipIf(Device.DEFAULT in {"CLANG"} and AMX, "CLANG with AMX upcasts float up to size 16") + @unittest.skipIf(Device.DEFAULT in {"CPU", "LLVM"} and AMX, "CPU with AMX upcasts float up to size 16") def test_float4_multidim(self): - a = Tensor.rand(2, 8).realize() - b = Tensor.rand(2, 8).realize() + a = Tensor.empty(2, 8).realize() + b = Tensor.empty(2, 8).realize() c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(0, 4) # float4 dimension k.shift_to(0, 2, insert_before=k.shape_len-1) @@ -1448,14 +1498,14 @@ class TestFloat4(unittest.TestCase): assert TestFloat4.count_float4(k) == (4, 2) - @unittest.skipUnless(Device.DEFAULT in {"CLANG"} and AMX, "Only CLANG with AMX upcasts float up to size 16") + @unittest.skipUnless(Device.DEFAULT in {"CPU", "LLVM"} and AMX, "Only CPU with AMX upcasts float up to size 16") def test_float4_multidim_amx(self): def kernel_for_shape(size, shift): - a = Tensor.rand(2, size).realize() - b = Tensor.rand(2, size).realize() + a = Tensor.empty(2, size).realize() + b = Tensor.empty(2, size).realize() c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(0, 4) k.shift_to(0, shift, insert_before=k.shape_len-1) @@ -1473,26 +1523,25 @@ class TestFloat4(unittest.TestCase): for i in range(len(sizes)): assert TestFloat4.count_float4(kernel_for_shape(sizes[i], shifts[i]), excepted_upcast_size[i]) == expected_output[i] - @unittest.skipIf(Device.DEFAULT in {"CLANG"} and AMX, "CLANG with AMX upcasts float up to size 16") def test_float4_unaligned_load(self): - a = Tensor.rand(9).realize().shrink(((1, 9),)) - b = Tensor.rand(9).realize().shrink(((1, 9),)) + a = Tensor.empty(9).realize().shrink(((1, 9),)) + b = Tensor.empty(9).realize().shrink(((1, 9),)) c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) - k.hand_coded_optimizations() # implicit trigger float4 dim + k.apply_opts([Opt(op=OptOps.UPCAST, axis=0, arg=4)]) k.linearize() assert TestFloat4.count_float4(k) == (0, 1) - @unittest.skipIf(Device.DEFAULT in {"CLANG"} and AMX, "CLANG with AMX upcasts float up to size 16") + @unittest.skipIf(Device.DEFAULT in {"CPU", "LLVM"} and AMX, "CPU with AMX upcasts float up to size 16") 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),)) + a = Tensor.empty(2, 9).realize().shrink(((0, 2), (1, 9),)) + b = Tensor.empty(2, 9).realize().shrink(((0, 2), (1, 9),)) c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(len(k.full_unupcasted_shape)-1, 4) # manual trigger float4 dim k.upcast() @@ -1503,14 +1552,14 @@ class TestFloat4(unittest.TestCase): assert TestFloat4.count_float4(k) == (0, 2) - @unittest.skipUnless(Device.DEFAULT in {"CLANG"} and AMX, "Only CLANG with AMX upcasts float up to size 16") + @unittest.skipUnless(Device.DEFAULT in {"CPU", "LLVM"} and AMX, "Only CPU with AMX upcasts float up to size 16") def test_float4_multidim_unaligned_load_amx(self): def kernel_for_shape(size, shift): - a = Tensor.rand(2, size).realize().shrink(((0, 2), (1, size),)) - b = Tensor.rand(2, size).realize().shrink(((0, 2), (1, size),)) + a = Tensor.empty(2, size).realize().shrink(((0, 2), (1, size),)) + b = Tensor.empty(2, size).realize().shrink(((0, 2), (1, size),)) c = a + b - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(len(k.full_unupcasted_shape)-1, 4) # manual trigger float4 dim k.upcast() @@ -1529,13 +1578,13 @@ class TestFloat4(unittest.TestCase): assert TestFloat4.count_float4(kernel_for_shape(sizes[i], shifts[i]), excepted_upcast_size[i]) == expected_output[i] 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))) + a = Tensor.empty(1, 1, 8).realize() + b = Tensor.empty(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 = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.upcast() k.linearize() @@ -1543,15 +1592,15 @@ class TestFloat4(unittest.TestCase): 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))) + a = Tensor.empty(1, 1, 7).realize() + b = Tensor.empty(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. # UPDATE: now we do this fusion - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.upcast() k.upcast() @@ -1560,14 +1609,14 @@ class TestFloat4(unittest.TestCase): assert TestFloat4.count_float4(k) in {(0,1), (1,1)} def test_float4_noncontiguous(self): - a = Tensor.rand(4, 2).realize() - b = Tensor.rand(4, 2).realize() + a = Tensor.empty(4, 2).realize() + b = Tensor.empty(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 = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(0, 4, top=True) # top axes are float4 axes k.upcast() @@ -1576,14 +1625,14 @@ class TestFloat4(unittest.TestCase): 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,)) + a = Tensor.empty(9).realize().shrink(((1, 9),)) + b = Tensor.empty(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 = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(0, 4) # float4 axis k.upcast() @@ -1592,13 +1641,13 @@ class TestFloat4(unittest.TestCase): 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),)) + a = Tensor.empty(8).realize() + b = Tensor.empty(9).realize().shrink(((1, 9),)) c = a + b # should float4 b but not a - s = create_schedule([c.lazydata])[0] + s = c.schedule()[0] k = Kernel(s.ast) k.shift_to(0, 4) # float4 axis k.upcast() @@ -1624,12 +1673,12 @@ class TestFloat4(unittest.TestCase): # TODO: fix this, expected might change but should be positive for expected, opts in [ - ((7, 0), [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=3), Opt(op=OptOps.UNROLL, axis=0, amt=4)]), - ((5, 0), [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4)]), - ((2, 0), [Opt(op=OptOps.UNROLL, axis=0, amt=4)]), + ((7, 0), [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=3), Opt(op=OptOps.UNROLL, axis=0, arg=4)]), + ((5, 0), [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4)]), + ((2, 0), [Opt(op=OptOps.UNROLL, axis=0, arg=4)]), ]: k = Kernel(ast) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) k.linearize() count = TestFloat4.count_half4(k) assert count == expected, f"{count=}, {expected=}" @@ -1655,11 +1704,11 @@ class TestFloat4(unittest.TestCase): UOp(Ops.VIEW, arg=ShapeTracker(views=(View(shape=(1, 1, 128, 512, 512, 1, 1, 1), strides=(0, 0, 1, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),))),)),)),)),)) # noqa: E501 for expected, opts in [ - (1, [Opt(op=OptOps.UPCAST, axis=2, amt=4)]), - (4, [Opt(op=OptOps.UPCAST, axis=2, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4)]), + (1, [Opt(op=OptOps.UPCAST, axis=2, arg=4)]), + (4, [Opt(op=OptOps.UPCAST, axis=2, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4)]), ]: k = Kernel(ast) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) k.linearize() count = len([uop for uop in k.uops if uop.op is Ops.DEFINE_ACC and uop.dtype == dtypes.float.vec(4)]) assert count == expected, f"{count=}, {expected=}" @@ -1678,36 +1727,36 @@ class TestFloat4(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=1), UOp(Ops.VIEW, arg=ShapeTracker(views=(View(shape=(256, 64, 3, 56, 2, 3, 56, 2), strides=(1806336, 28224, 3, 504, 0, 1, 9, 0), offset=0, mask=((0, 256), (0, 64), (0, 3), (0, 56), (0, 1), (0, 3), (0, 56), (0, 1)), contiguous=False), View(shape=(256, 64, 3, 115, 3, 115), strides=(7225344, 112896, 37632, 336, 112, 1), offset=0, mask=((0, 256), (0, 64), (0, 3), (0, 112), (0, 3), (0, 112)), contiguous=False), View(shape=(256, 64, 456, 456), strides=(7617600, 119025, 345, 1), offset=0, mask=((0, 256), (0, 64), (0, 345), (0, 345)), contiguous=False), View(shape=(1, 256, 1, 64, 4, 114, 4, 114), strides=(0, 13307904, 0, 207936, 51984, 456, 114, 1), offset=0, mask=None, contiguous=True)))),)),)),)),)),)),)) # noqa: E501 for expected, opts in [ - (16, [Opt(op=OptOps.LOCAL, axis=1, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=2, amt=2), Opt(op=OptOps.LOCAL, axis=2, amt=3), Opt(op=OptOps.UPCAST, axis=3, amt=4)]), # noqa: E501 - (4, [Opt(op=OptOps.LOCAL, axis=1, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=2, amt=2)]), + (16, [Opt(op=OptOps.LOCAL, axis=1, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=2, arg=2), Opt(op=OptOps.LOCAL, axis=2, arg=3), Opt(op=OptOps.UPCAST, axis=3, arg=4)]), # noqa: E501 + (4, [Opt(op=OptOps.LOCAL, axis=1, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=2, arg=2)]), ]: k = Kernel(ast) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) k.linearize() count = len([uop for uop in k.uops if uop.op is Ops.DEFINE_ACC and uop.dtype == dtypes.float.vec(2)]) assert count == expected, f"{count=}, {expected=}" class TestHandCodedOpts(unittest.TestCase): 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)) + layer_1 = Tensor.cat(*[Tensor.empty(5) for _ in range(4)]) + layer_2 = Tensor.cat(layer_1.unsqueeze(0), Tensor.empty(6, 20)) - s = create_schedule([layer_2.lazydata])[-1] + s = layer_2.schedule()[-1] k = Kernel(s.ast) - k.hand_coded_optimizations() + k.apply_opts(hand_coded_optimizations(k)) 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 - @unittest.skipIf((buf_max:=BUF_LIMIT.get(Device.DEFAULT)) is not None and buf_max <= 37, "this test uses too many bufs") + @unittest.skipIf(Device.DEFAULT == "METAL", "METAL can only run kernels with up to 32 buffers") def test_masked_upcast_wino(self): - monster = Tensor.stack(*[Tensor.stack(*[Tensor.rand(16) for _ in range(6)]) for _ in range(6)]) + monster = Tensor.stack(*[Tensor.stack(*[Tensor.empty(16) for _ in range(6)]) for _ in range(6)]) - s = create_schedule([monster.lazydata])[-1] + s = monster.schedule()[-1] k = Kernel(s.ast) - k.hand_coded_optimizations() + k.apply_opts(hand_coded_optimizations(k)) 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 @@ -1719,11 +1768,11 @@ class TestHandCodedOpts(unittest.TestCase): out.mean().backward() upcasts = [] - wino_schedule = create_schedule([out.lazydata]) + wino_schedule = out.schedule() # collect upcasts of tile transform kernels for i, si in enumerate(wino_schedule): k = Kernel(si.ast) - k.hand_coded_optimizations() + k.apply_opts(hand_coded_optimizations(k)) if k.reduceop is not None: continue # not a tile transform kernel (there is a gemm reduce kernel) if len(k.bufs) < 22: 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])) @@ -1732,10 +1781,10 @@ class TestHandCodedOpts(unittest.TestCase): # this test case's inputs are too small, so one of the 4-stacks became a local, which is fine i guess assert upcasts.count((6, 6)) == 2 #and upcasts.count((4, 4)) == 1 - backward_schedule = create_schedule([x.grad.lazydata, w.grad.lazydata]) + backward_schedule = Tensor.schedule(x.grad, w.grad) for si in backward_schedule: k = Kernel(si.ast) - k.hand_coded_optimizations() + k.apply_opts(hand_coded_optimizations(k)) 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 @@ -1765,33 +1814,34 @@ class TestHandCodedOpts(unittest.TestCase): assert k.local_dims == 1 assert k.upcasted == 1 -def helper_linearizer_ast(ast:UOp, inputs:List[Tensor], *args, **kwargs): +def helper_linearizer_ast(ast:UOp, inputs:list[Tensor], *args, **kwargs): assert isinstance(ast, UOp), "ast must be UOp" inbufs = [x.lazydata.base.buffer for x in inputs] outbufs = [Buffer(inbufs[-1].device if inbufs else Device.DEFAULT, out.st_arg.size, out.src[2].dtype).allocate() \ for out in ast.src] return _helper_linearizer_opt_ast(ast, outbufs+inbufs, *args, **kwargs) -def helper_linearizer_opt(r:Union[Tensor, List[Tensor]], *args, **kwargs): +def helper_linearizer_opt(r:Union[Tensor, list[Tensor]], *args, **kwargs): realized_ast, real_bufs = helper_realized_ast(r) return _helper_linearizer_opt_ast(realized_ast, real_bufs, *args, **kwargs) -def copyout_outputs(lin:Kernel, outbufs:List[Buffer]) -> List[np.ndarray]: +def copyout_outputs(lin:Kernel, outbufs:list[Buffer]) -> list[np.ndarray]: ret = [] for i,x in enumerate(outbufs): - shape: Tuple[int, ...] = lin.ast.src[i].st_arg.shape + shape: tuple[int, ...] = lin.ast.src[i].st_arg.shape ret.append(np.frombuffer(x.as_buffer(), _to_np_dtype(x.dtype)).reshape(shape)) return ret -def reset_bufs(bufs:List[Buffer]): +def reset_bufs(bufs:list[Buffer]): for buf in bufs: buf.copyin(np.zeros((buf.size, ), dtype=_to_np_dtype(buf.dtype)).data) # Zero to check that all values are filled -def _helper_linearizer_opt_ast(realized_ast:UOp, real_bufs:List[Buffer], opts=[], - apply_tc=False, atol=1e-4, rtol=1e-4, color_sizes=[], wanna_output=[]) -> List[Kernel]: - lins: List[Kernel] = [] +def _helper_linearizer_opt_ast(realized_ast:UOp, real_bufs:list[Buffer], opts=[], + apply_tc=False, atol=1e-4, rtol=1e-4, color_sizes=[], wanna_output=[]) -> list[Kernel]: + lins: list[Kernel] = [] outbufs = [real_bufs[x.src[0].arg] for x in realized_ast.src] + device = real_bufs[0].device - def get_prg(k:Kernel): return CompiledRunner(replace(k.to_program(), device=Device.DEFAULT)) + def get_prg(k:Kernel): return CompiledRunner(replace(k.to_program(), device=device)) def check_opt(opts, create_k, expected_color_size): k = create_k() @@ -1799,8 +1849,7 @@ def _helper_linearizer_opt_ast(realized_ast:UOp, real_bufs:List[Buffer], opts=[] if apply_tc: assert k.apply_tensor_cores(1, extra_opts=opts), "no tensor core triggered" else: - for opt in opts: - k.apply_opt(opt) + k.apply_opts(opts) if expected_color_size is not None: cs = list(zip(k.colors(), k.full_shape)) assert cs == expected_color_size, f"expected={expected_color_size} got={cs}" @@ -1821,8 +1870,8 @@ def _helper_linearizer_opt_ast(realized_ast:UOp, real_bufs:List[Buffer], opts=[] # Check correctness of handcoded optimiztions. k = Kernel(realized_ast) + k.apply_opts(hand_coded_optimizations(k)) lins.append(k) - k.hand_coded_optimizations() prg = get_prg(k) reset_bufs(outbufs) prg.exec(real_bufs) @@ -1975,7 +2024,7 @@ class TestKernelOpts(unittest.TestCase): UOp(Ops.VIEW, arg=ShapeTracker(views=(View(shape=(1243, 256), strides=(1, 0), offset=0, mask=None, contiguous=False),))),)),)),)),)),)) # noqa: E501 k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) with self.assertRaises(KernelOptError): - k.apply_opt(Opt(OptOps.TC, 0, 1)) + k.apply_opt(Opt(OptOps.TC, 0, (-1, 1, 1))) @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") def test_tensor_core_opts(self): @@ -1983,9 +2032,9 @@ class TestKernelOpts(unittest.TestCase): Tensor.manual_seed(1552) for tc in Device[Device.DEFAULT].renderer.tensor_cores: # bf16 buffer returns float32 numpy outputs so test would fail. testing opt with half suffices. - if tc.dtype_in == dtypes.bfloat16: continue + if tc.dtype_in != dtypes.half and tc.dtype_out != dtypes.half: continue a, b = Tensor.rand(N, N, dtype=tc.dtype_in), Tensor.rand(N, N, dtype=tc.dtype_in) - r = a.matmul(b, acc_dtype=tc.dtype_out) + r = a.matmul(b, dtype=tc.dtype_out) (atol, rtol) = ((0.25, 0.01) if tc.dtype_out == dtypes.half else (3e-2, 1e-3)) if tc.dtype_in == dtypes.half else (1e-4, 1e-4) helper_linearizer_opt(r, [ [], @@ -2010,9 +2059,9 @@ class TestKernelOpts(unittest.TestCase): Tensor.manual_seed(1552) for tc in Device[Device.DEFAULT].renderer.tensor_cores: # bf16 buffer returns float32 numpy outputs so test would fail. testing opt with half suffices. - if tc.dtype_in == dtypes.bfloat16: continue + if tc.dtype_in != dtypes.half and tc.dtype_out != dtypes.half: continue a, b = Tensor.rand(N, N, dtype=tc.dtype_in), Tensor.rand(N, N, dtype=tc.dtype_in) - r = a.matmul(b, acc_dtype=tc.dtype_out) + r = a.matmul(b, dtype=tc.dtype_out) (atol, rtol) = ((0.25, 0.01) if tc.dtype_out == dtypes.half else (3e-2, 1e-3)) if tc.dtype_in == dtypes.half else (1e-4, 1e-4) helper_linearizer_opt(r, [ [Opt(OptOps.UNROLL, 0, 0)], # check full unroll of reduce with locals @@ -2022,7 +2071,7 @@ class TestKernelOpts(unittest.TestCase): ], apply_tc=True, atol=atol, rtol=rtol) def test_padto_matmul(self): - if (CI and Device.DEFAULT in ["AMD", "NV", "CUDA"]) or Device.DEFAULT == "WEBGPU": + if (CI and Device.DEFAULT in ["AMD", "NV", "CUDA"]): self.skipTest("super slow on CUDA and AMD because of the big grid dims") N = 17 * 17 Tensor.manual_seed(289) @@ -2060,7 +2109,7 @@ class TestKernelOpts(unittest.TestCase): def test_padto_sum_ok(self): N = 18 * 18 # NOTE: this setup prevents 17 * 17 contiguous merged into one dimension - a = Tensor.rand(N, N).shrink(((0, 17), (0, 17))) * 100 + a = Tensor.rand(N, N).realize().shrink(((0, 17), (0, 17))) * 100 b = (Tensor.rand(N, N) < 0.5).realize().shrink(((0, 17), (0, 17))) helper_linearizer_opt(a.sum(0), [ @@ -2078,9 +2127,11 @@ class TestKernelOpts(unittest.TestCase): helper_linearizer_opt(a.sum(0), [[Opt(OptOps.PADTO, axis, 32)],]) helper_linearizer_opt(b.sum(), [[Opt(OptOps.PADTO, axis, 32)],]) helper_linearizer_opt(b.sum(0), [[Opt(OptOps.PADTO, axis, 32)],]) - helper_linearizer_opt(b.sum(acc_dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) - helper_linearizer_opt(b.sum(0, acc_dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) - helper_linearizer_opt(b.sum(1, acc_dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) + helper_linearizer_opt(b.sum(dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) + # TODO: why? + if Device.DEFAULT != "WEBGPU": + helper_linearizer_opt(b.sum(0, dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) + helper_linearizer_opt(b.sum(1, dtype=dtypes.bool), [[Opt(OptOps.PADTO, axis, 32)],]) # having unsafe ops after sum is fine helper_linearizer_opt(a.sum().exp(), [[Opt(OptOps.PADTO, 0, 32)],]) @@ -2123,7 +2174,6 @@ class TestKernelOpts(unittest.TestCase): with self.assertRaises(KernelOptError): helper_linearizer_opt(a.max(0), [[Opt(OptOps.PADTO, 1, 32)],]) - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "max dimensions exceeded on WebGPU") def test_padto_where(self): Tensor.manual_seed(0) N = 17 * 17 @@ -2133,7 +2183,6 @@ class TestKernelOpts(unittest.TestCase): [Opt(OptOps.PADTO, 0, 32), Opt(OptOps.UPCAST, 0, 8),], ]) - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "max dimensions exceeded on WebGPU") def test_padto_where_multioutput(self): Tensor.manual_seed(0) N = 17 * 17 @@ -2157,9 +2206,9 @@ class TestKernelOpts(unittest.TestCase): data1 = Tensor.randn(2, 1, 4, 1, 3, 4, 2, 6, 1, 3).realize() data2 = Tensor.randn(2, 1, 4, 1, 3, 4, 2, 6, 1, 3).realize() helper_linearizer_ast(sink, [data1, data2], opts=[ - [Opt(OptOps.PADTO, 0, 32), Opt(OptOps.GROUP, 0, 4)], - [Opt(OptOps.PADTO, 0, 32), Opt(OptOps.UPCAST, 0, 8)], - [Opt(OptOps.PADTO, 0, 32), Opt(OptOps.UPCAST, 0, 8), Opt(OptOps.GROUP, 0, 4)] + #[Opt(OptOps.PADTO, 0, 32), Opt(OptOps.GROUP, 0, 4)], + #[Opt(OptOps.PADTO, 0, 32), Opt(OptOps.UPCAST, 0, 8)], + #[Opt(OptOps.PADTO, 0, 32), Opt(OptOps.UPCAST, 0, 8), Opt(OptOps.GROUP, 0, 4)] ]) @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test requires locals") diff --git a/tinygrad_repo/test/test_linearizer_dumb.py b/tinygrad_repo/test/test_linearizer_dumb.py index 5cd581aa04..0cbaea3cf8 100644 --- a/tinygrad_repo/test/test_linearizer_dumb.py +++ b/tinygrad_repo/test/test_linearizer_dumb.py @@ -6,7 +6,7 @@ import unittest from test.helpers import ast_const from tinygrad import Device, dtypes from tinygrad.device import is_dtype_supported -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.helpers import getenv from tinygrad.shape.shapetracker import ShapeTracker, View from tinygrad.engine.search import Opt, OptOps @@ -35,10 +35,9 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(64, 1, 512, 7, 7, 1, 1, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), ast_const(dtypes.half, 0.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(64, 1, 512, 7, 7, 1, 1, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=2, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=0), Opt(op=OptOps.UNROLL, axis=1, amt=0)] + opts = [Opt(op=OptOps.TC, axis=2, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=2, arg=0), Opt(op=OptOps.UNROLL, axis=1, arg=0)] k = Kernel(ast, opts=Device["METAL"].renderer) - k.required_optimizations() - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) Device[Device.DEFAULT].compiler.compile_cached(prg.src) @@ -70,10 +69,9 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1001, 1999), strides=(0, 0), offset=0, mask=((0, 1001), (999, 1999)), contiguous=False), View(shape=(1000, 1000), strides=(1, 2000), offset=0, mask=None, contiguous=False))), src=()),)),)), ast_const(dtypes.int, 1000, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1000, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=8)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=8)] k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) - k.required_optimizations() - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) assert prg.uops is not None and not any(uop.op is Ops.MAX for uop in prg.uops), "leftover MAX" @@ -88,15 +86,14 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(26, 49), strides=(0, -1), offset=48, mask=((0, 26), (24, 49)), contiguous=False), View(shape=(25, 25), strides=(1, 50), offset=0, mask=None, contiguous=False))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0)] k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) - k.required_optimizations() - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) if_uops = [u for u in k.uops if u.op is Ops.IF] self.assertIn(len(if_uops), {1,2,3}) - conditions = if_uops[0].src[0].toposort + conditions = if_uops[0].src[0].toposort() self.assertLessEqual(len(conditions), 9) # this was a bug in embedding, someday we should fold this anyway @@ -155,9 +152,9 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=3, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(3, 1, 5), strides=(0, 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=0), Opt(op=OptOps.LOCAL, axis=0, amt=3)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=0), Opt(op=OptOps.LOCAL, axis=0, arg=3)] k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) load_idxs = [x.src[1] for x in k.uops if x.op is Ops.LOAD and x.src[0].arg == 3] @@ -186,9 +183,9 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(3, 6), strides=(6, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=0)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=0)] k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) load_idxs = [x.src[1] for x in k.uops if x.op is Ops.LOAD and x.src[0].arg == 2] @@ -210,9 +207,9 @@ class TestLinearizerDumb(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 5, 13, 1, 1, 1, 4, 1, 4, 3, 3), strides=(260, 13, 1, 0, 0, 0, 65, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.UPCAST, axis=2, amt=0)] + opts = [Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.UPCAST, axis=2, arg=0)] k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) - for opt in opts: k.apply_opt(opt) + k.apply_opts(opts) prg = k.to_program() print(prg.src) store_idxs = [x.src[1] for x in k.uops if x.op is Ops.STORE] diff --git a/tinygrad_repo/test/test_linearizer_failures.py b/tinygrad_repo/test/test_linearizer_failures.py index 80ca7fd6e8..931b738845 100644 --- a/tinygrad_repo/test/test_linearizer_failures.py +++ b/tinygrad_repo/test/test_linearizer_failures.py @@ -3,10 +3,10 @@ import unittest, random import numpy as np from tinygrad.codegen.kernel import Kernel, KernelOptError from tinygrad.device import is_dtype_supported -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.engine.search import Opt, OptOps from tinygrad import Device, dtypes, Tensor -from tinygrad.helpers import CI +from tinygrad.helpers import CI, Context from test.external.fuzz_linearizer import compare_linearizer from test.helpers import ast_const @@ -17,13 +17,12 @@ def helper_test_lin(lin: Kernel, opts, failed_platforms, rtol=1e-2, atol=1e-2): if any(b.dtype.base == dtypes.half for b in lin.membufs) and not is_dtype_supported(dtypes.half): return if any(b.dtype.base == dtypes.bfloat16 for b in lin.membufs) and not is_dtype_supported(dtypes.bfloat16): return - for opt in opts: - try: - lin.apply_opt(opt) - except KernelOptError: - # it's considered fixed if we invalidated the opts - assert Device.DEFAULT not in failed_platforms, f"unexpected success on {Device.DEFAULT}" - return + try: + lin.apply_opts(opts) + except KernelOptError: + # it's considered fixed if we invalidated the opts + assert Device.DEFAULT not in failed_platforms, f"unexpected success on {Device.DEFAULT}" + return compare_result = compare_linearizer(lin, rtol=rtol, atol=atol) if compare_result[0] in ["PASS", "KernelOptError"]: @@ -68,7 +67,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32, 2, 111, 27), strides=(6160, 3080, 28, 1), offset=0, mask=((0, 32), (0, 2), (0, 110), (0, 27)), contiguous=False), View(shape=(32, 2, 37, 9, 2, 2), strides=(5994, 2997, 81, 3, 27, 1), offset=0, mask=None, contiguous=False))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=0, amt=32)] + opts = [Opt(op=OptOps.LOCAL, axis=0, arg=32)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) def test_failure_3(self): @@ -80,7 +79,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32, 8, 16, 16), strides=(2048, 256, 16, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=2), Opt(op=OptOps.UNROLL, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.LOCAL, axis=0, amt=32)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=2), Opt(op=OptOps.UNROLL, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.LOCAL, axis=0, arg=32)] # METAL: AssertionError: Error Domain=AGXMetalG13X Code=3 "Threadgroup memory size (65536) exceeds the maximum threadgroup memory allowed (32768)" UserInfo={NSLocalizedDescription=Threadgroup memory size (65536) exceeds the maximum threadgroup memory allowed (32768)} helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -101,7 +100,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 4, 1, 3, 1, 4, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), x5,)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=0)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=0)] # EXEC_ERROR, it has no global_size helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -116,8 +115,8 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(11, 19), strides=(0, 0), offset=0, mask=((0, 11), (9, 19)), contiguous=False), View(shape=(10, 10), strides=(1, 20), offset=0, mask=None, contiguous=False))), src=()),)),)), ast_const(dtypes.int, 10, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(10, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=0)] - # COMPILE FAILED, KeyError: UOps.CONST + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=2), Opt(op=OptOps.UPCAST, axis=0, arg=0)] + # COMPILE FAILED, KeyError: Ops.CONST helper_test_lin(Kernel(ast), opts, failed_platforms=[]) def test_failure_7(self): @@ -129,7 +128,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(512, 32, 6, 8, 4, 6, 8, 4), strides=(2048, 64, 6291456, 8, 0, 1048576, 1, 0), offset=0, mask=((0, 512), (0, 32), (0, 6), (0, 8), (0, 1), (0, 6), (0, 8), (0, 1)), contiguous=False), View(shape=(512, 32, 6, 35, 6, 35), strides=(1179648, 36864, 6144, 192, 32, 1), offset=0, mask=((0, 512), (0, 32), (0, 6), (0, 32), (0, 6), (0, 32)), contiguous=False), View(shape=(512, 32, 238, 238), strides=(1411200, 44100, 210, 1), offset=0, mask=((0, 512), (0, 32), (0, 210), (0, 210)), contiguous=False), View(shape=(512, 32, 7, 34, 7, 34), strides=(1812608, 56644, 8092, 238, 34, 1), offset=0, mask=None, contiguous=True))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=4)] + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=4)] # test/test_linearizer_failures.py Fatal Python error: Segmentation fault helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -156,7 +155,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=True),)), src=()),)),)), ast_const(dtypes.float, 1e-06, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4)] # fatal error: bracket nesting level exceeded maximum of 256 # note: use -fbracket-depth=N to increase maximum nesting level helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -174,7 +173,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 2, 1, 3, 1, 1, 1, 1, 5, 15, 5, 3, 4), strides=(0, 4500, 0, 0, 0, 0, 0, 0, 900, 60, 12, 4, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=0, amt=32)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=0, arg=32)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) def test_failure_10(self): @@ -290,7 +289,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 4, 1, 3, 4, 2, 6, 1, 3), strides=(0, 0, 0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), x5,)),)),)),)) - opts = [Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.GROUP, axis=0, amt=4)] + opts = [Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.GROUP, axis=0, arg=4)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @unittest.skip("found implicit expand") @@ -315,7 +314,7 @@ class TestLinearizerFailures(unittest.TestCase): x6,)), UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (0, 2, 4, 8)), src=( x5,)),)),)),)),)) - opts = [Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.GROUP, axis=0, amt=4)] + opts = [Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.GROUP, axis=0, arg=4)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) # both kernels are correct from a code standpoint, but generate different results due to precision errors (switching to float results in output matches) @@ -336,7 +335,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=3, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 384, 1), strides=(0, 0, 1, 0), offset=19584, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=4)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=4)] helper_test_lin(Kernel(ast), opts, failed_platforms=["METAL", "GPU", "CUDA"]) def test_failure_14(self): @@ -357,7 +356,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 4, 1, 3, 4, 2, 6, 1, 3), strides=(0, 0, 0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), x5,)),)),)),)) - opts = [Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4)] + opts = [Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4)] # COMPILE_ERROR on METAL in fuzz_linearizer: unused variables and undeclared variables helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -395,7 +394,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=6, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 112, 14, 14, 1, 1, 1), strides=(0, 0, 1, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=2), Opt(op=OptOps.PADTO, axis=1, amt=32), Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.GROUP, axis=0, amt=8), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.LOCAL, axis=1, amt=16)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=2), Opt(op=OptOps.PADTO, axis=1, arg=32), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.LOCAL, axis=1, arg=16)] # COMPILE_ERROR on METAL in fuzz_linearizer ast 115: Error Domain=AGXMetalG14X Code=3 "Compiler encountered an internal error" helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -411,7 +410,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 13, 1024), strides=(0, 1024, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)), ast_const(dtypes.float, 0.0009765625, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 13, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=0), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.GROUP, axis=0, amt=8), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=1, amt=4)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=0), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=1, arg=4)] # COMPILE_ERROR on METAL/GPU (probably HIP/CUDA too) in fuzz_linearizer ast 154: bracket nesting level exceeded maximum of 256 helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -428,7 +427,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 40, 240, 28, 28, 1, 1), strides=(188160, 0, 0, 784, 28, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=1, amt=32), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.GROUPTOP, axis=0, amt=16), Opt(op=OptOps.PADTO, axis=1, amt=32), Opt(op=OptOps.LOCAL, axis=1, amt=4)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=1, arg=32), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.GROUPTOP, axis=0, arg=16), Opt(op=OptOps.PADTO, axis=1, arg=32), Opt(op=OptOps.LOCAL, axis=1, arg=4)] # COMPILE_ERROR on METAL in fuzz_linearizer ast 178: Error Domain=AGXMetalG14X Code=3 "Compiler encountered an internal error" helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -453,7 +452,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=4, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 384, 1), strides=(0, 0, 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.GROUPTOP, axis=0, amt=256), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=3)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.GROUPTOP, axis=0, arg=256), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=3)] # COMPILE_ERROR on METAL in fuzz_linearizer ast 239: Error Domain=AGXMetalG14X Code=3 "Compiler encountered an internal error" helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -470,7 +469,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 4, 4, 9, 7, 3, 3), strides=(252, 0, 0, 63, 7, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=2, amt=3), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.GROUP, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=7), Opt(op=OptOps.UPCAST, axis=2, amt=3), Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.LOCAL, axis=0, amt=2), Opt(op=OptOps.LOCAL, axis=0, amt=3)] + opts = [Opt(op=OptOps.LOCAL, axis=2, arg=3), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.GROUP, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=7), Opt(op=OptOps.UPCAST, axis=2, arg=3), Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.LOCAL, axis=0, arg=3)] # COMPILE_ERROR on METAL in fuzz_linearizer ast 379: Error Domain=AGXMetalG14X Code=3 "Compiler encountered an internal error" helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -485,7 +484,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 4), strides=(0, 1), offset=0, mask=None, contiguous=False),)), src=()),)), ast_const(dtypes.float, 1.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 4), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=0, amt=0)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=0)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) def test_failure_21(self): @@ -495,10 +494,10 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(45, 65), strides=(65, 1), offset=0, mask=None, contiguous=True),)), src=()), ast_const(dtypes.float, 1.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(45, 65), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)) - opts = [Opt(op=OptOps.PADTO, axis=0, amt=32)] + opts = [Opt(op=OptOps.PADTO, axis=0, arg=32)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) - #@unittest.skipIf(Device.DEFAULT in ("LLVM", "METAL", "CLANG"), "flaky") + #@unittest.skipIf(Device.DEFAULT in ("LLVM", "METAL", "CPU"), "flaky") @unittest.skip("flaky everywhere") def test_failure_22(self): ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( @@ -603,7 +602,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(240, 40, 1, 1), strides=(1, 240, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.LOCAL, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=3, amt=2)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.LOCAL, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=3, arg=2)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) def test_failure_24(self): @@ -614,7 +613,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(8, 32, 1, 1), strides=(1, 8, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=2, amt=2), Opt(op=OptOps.LOCAL, axis=1, amt=8), Opt(op=OptOps.UPCAST, axis=2, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=8), Opt(op=OptOps.UPCAST, axis=1, amt=0), Opt(op=OptOps.UPCAST, axis=0, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=2, arg=2), Opt(op=OptOps.LOCAL, axis=1, arg=8), Opt(op=OptOps.UPCAST, axis=2, arg=0), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=2)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) # this is the cause of the GPT2 BEAM instability. bisects to PR#3530 O(n) arange attempt @@ -629,7 +628,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1025, 2047), strides=(0, 0), offset=0, mask=((0, 1025), (1023, 2047)), contiguous=False), View(shape=(1024, 1024), strides=(1, 2048), offset=0, mask=None, contiguous=False))), src=()),)),)), ast_const(dtypes.int, -1, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1024, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=16), Opt(op=OptOps.UNROLL, axis=0, amt=4)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=16), Opt(op=OptOps.UNROLL, axis=0, arg=4)] helper_test_lin(Kernel(ast), opts, failed_platforms=[]) # COMPARE_ERROR from GPT2 kernel - stems from uops.py self.simplify_phi_loops @@ -645,17 +644,17 @@ class TestLinearizerFailures(unittest.TestCase): ast_const(dtypes.int, -1, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) all_failing_opts = [ - [Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.GROUPTOP, axis=0, amt=32), Opt(op=OptOps.UNROLL, axis=0, amt=0)], - [Opt(op=OptOps.GROUPTOP, axis=0, amt=32), Opt(op=OptOps.UNROLL, axis=0, amt=0), Opt(op=OptOps.UPCAST, axis=0, amt=4)], - [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0)], - [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0)], - [Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.UNROLL, axis=0, amt=4)], - [Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0)], - [Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.UNROLL, axis=0, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=4)], - [Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.GROUP, axis=0, amt=8), Opt(op=OptOps.UNROLL, axis=1, amt=4)], - [Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.GROUP, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.UNROLL, axis=1, amt=4)], - [Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.GROUP, axis=0, amt=16), Opt(op=OptOps.UNROLL, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0)], - [Opt(op=OptOps.GROUP, axis=0, amt=8), Opt(op=OptOps.UNROLL, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16), Opt(op=OptOps.UPCAST, axis=0, amt=0)], + [Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.GROUPTOP, axis=0, arg=32), Opt(op=OptOps.UNROLL, axis=0, arg=0)], + [Opt(op=OptOps.GROUPTOP, axis=0, arg=32), Opt(op=OptOps.UNROLL, axis=0, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=4)], + [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0)], + [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0)], + [Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.UNROLL, axis=0, arg=4)], + [Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0)], + [Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.UNROLL, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=4)], + [Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.UNROLL, axis=1, arg=4)], + [Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.GROUP, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.UNROLL, axis=1, arg=4)], + [Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.GROUP, axis=0, arg=16), Opt(op=OptOps.UNROLL, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0)], + [Opt(op=OptOps.GROUP, axis=0, arg=8), Opt(op=OptOps.UNROLL, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16), Opt(op=OptOps.UPCAST, axis=0, arg=0)], ] for opts in all_failing_opts: helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -683,7 +682,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 16, 13, 13), strides=(0, 169, 13, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)) all_failing_opts = [ - [Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=7), Opt(op=OptOps.UPCAST, axis=0, amt=0)], + [Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=7), Opt(op=OptOps.UPCAST, axis=0, arg=0)], ] for opts in all_failing_opts: helper_test_lin(Kernel(ast), opts, failed_platforms=[]) @@ -740,7 +739,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 1, 64, 56, 56, 64, 3, 3), strides=(0, 0, 576, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=1), Opt(op=OptOps.PADTO, axis=2, amt=32)] + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 1, 1)), Opt(op=OptOps.PADTO, axis=2, arg=32)] helper_test_lin(Kernel(ast), opts, failed_platforms=[], atol=1.0) def test_failure_30(self): @@ -758,7 +757,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(256, 1, 12, 31, 31, 3, 2, 2), strides=(0, 0, 12, 0, 0, 4, 2, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.PADTO, axis=3, amt=32), Opt(op=OptOps.LOCAL, axis=3, amt=32), Opt(op=OptOps.UPCAST, axis=3, amt=4), Opt(op=OptOps.UPCAST, axis=3, amt=0)] + opts = [Opt(op=OptOps.PADTO, axis=3, arg=32), Opt(op=OptOps.LOCAL, axis=3, arg=32), Opt(op=OptOps.UPCAST, axis=3, arg=4), Opt(op=OptOps.UPCAST, axis=3, arg=0)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) # from METAL=1 fuzz_linearizer command in test.yml @@ -779,7 +778,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 16, 13, 13), strides=(0, 13, 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), ast_const(dtypes.float, 1.4426950408889634, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 16, 13, 13), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)) - opts = [Opt(op=OptOps.UNROLL, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=1, amt=32)] + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=1, arg=32)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) @unittest.skipIf(CI, "for real AMD GPU") @@ -800,11 +799,11 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(256, 1, 256, 14, 14, 256, 3, 3), strides=(0, 0, 2304, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=2, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=7), Opt(op=OptOps.UNROLL, axis=1, amt=0), Opt(op=OptOps.LOCAL, axis=1, amt=16)] + opts = [Opt(op=OptOps.TC, axis=2, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=2, arg=7), Opt(op=OptOps.UNROLL, axis=1, arg=0), Opt(op=OptOps.LOCAL, axis=1, arg=16)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[], atol=0.1, rtol=0.05) def test_failure_33(self): - # UOps.UNMUL left after linearize + # Ops.UNMUL left after linearize ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( UOp(Ops.STORE, dtypes.void, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=0, src=()), @@ -841,7 +840,7 @@ class TestLinearizerFailures(unittest.TestCase): ast_const(dtypes.float, 1.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32640,), strides=(0,), offset=0, mask=None, contiguous=False),)), src=()),)),)), x10,)),)),)),)),)) - opts = [Opt(op=OptOps.GROUPTOP, axis=0, amt=16)] + opts = [Opt(op=OptOps.GROUPTOP, axis=0, arg=16)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) # from fuzzing on metal @@ -861,14 +860,14 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1, 6, 10, 3, 1, 2, 5), strides=(0, 0, 10, 0, 0, 0, 5, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), ast_const(dtypes.float, 0.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1, 6, 10, 3, 1, 1, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=2), Opt(op=OptOps.UNROLL, axis=0, amt=0)] if unroll else [Opt(op=OptOps.TC, axis=0, amt=2)] + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 2, 1)), Opt(op=OptOps.UNROLL, axis=0, arg=0)] if unroll else [Opt(op=OptOps.TC, axis=0, arg=(-1, 2, 1))] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) def test_failure_35(self): self.test_failure_34(True) # from world fuzz_linearizer: PYTHONPATH=. METAL=1 FUZZ_ALL_ACTIONS=1 DEPTH=1 FUZZ_N=100 FUZZ_NTH=84 python3 ./test/external/fuzz_linearizer.py def test_failure_36(self): - # UOps.UNMUL left after linearize + # Ops.UNMUL left after linearize ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( UOp(Ops.STORE, dtypes.void, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.uchar.ptr(), arg=0, src=()), @@ -881,7 +880,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(6, 9), strides=(0, 0), offset=0, mask=((0, 6), (4, 9)), contiguous=False), View(shape=(5, 5), strides=(1, 10), offset=0, mask=None, contiguous=False))), src=()),)),)),)), ast_const(dtypes.uint, -1, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(5, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=0)] + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=0)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) # BEGIN METAL=1 ./examples/beautiful_mnist.py failures @@ -910,7 +909,7 @@ class TestLinearizerFailures(unittest.TestCase): ast_const(dtypes.float, 0.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(512, 1, 32, 24, 24, 1, 1, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) for axis in [0,1,2,3,4,5]: - opts = [Opt(op=OptOps.TC, axis=axis, amt=2)] + opts = [Opt(op=OptOps.TC, axis=axis, arg=(-1, 2, 1))] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) def test_failure_38(self): @@ -930,7 +929,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 32, 24, 24, 1, 5, 5, 256), strides=(18432, 0, 576, 24, 1, 0, 0, 0, 36864), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) for axis in [0,1,3,4]: - opts = [Opt(op=OptOps.TC, axis=axis, amt=2)] + opts = [Opt(op=OptOps.TC, axis=axis, arg=(-1, 2, 1))] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) @unittest.skip("very slow, similar to test_failure_37") @@ -958,7 +957,7 @@ class TestLinearizerFailures(unittest.TestCase): ast_const(dtypes.float, 0.0, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(10000, 1, 32, 24, 24, 1, 1, 1), strides=(0, 0, 0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) for axis in [0,1,2,3,4,5]: - opts = [Opt(op=OptOps.TC, axis=axis, amt=2)] + opts = [Opt(op=OptOps.TC, axis=axis, arg=(-1, 2, 1))] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) def test_failure_40(self): @@ -975,7 +974,7 @@ class TestLinearizerFailures(unittest.TestCase): ast_const(dtypes.int, -1, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(60000, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) for amt in [16,32]: - opts = [Opt(op=OptOps.GROUPTOP, axis=0, amt=amt), Opt(op=OptOps.UNROLL, axis=0, amt=0)] + opts = [Opt(op=OptOps.GROUPTOP, axis=0, arg=amt), Opt(op=OptOps.UNROLL, axis=0, arg=0)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) # END METAL=1 ./examples/beautiful_mnist.py failures @@ -996,8 +995,8 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(256, 1, 128, 28, 28, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts=[Opt(op=OptOps.TC, axis=5, amt=2), Opt(op=OptOps.UNROLL, axis=0, amt=0)] - helper_test_lin(Kernel(ast), opts=opts, failed_platforms=["AMD", "HIP"]) + opts=[Opt(op=OptOps.TC, axis=5, arg=(-1, 2, 1)), Opt(op=OptOps.UNROLL, axis=0, arg=0)] + helper_test_lin(Kernel(ast), opts=opts, failed_platforms=["AMD", "HIP"], atol=0.02) # llama3 8B failure with BEAM=2 https://github.com/tinygrad/tinygrad/actions/runs/10150118124/job/28066519425#step:14:1, these don't compile @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test needs local") @@ -1011,7 +1010,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(26, 49), strides=(0, -1), offset=48, mask=((0, 26), (24, 49)), contiguous=False), View(shape=(25, 25), strides=(1, 50), offset=0, mask=None, contiguous=False))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.UPCAST, axis=0, amt=2), Opt(op=OptOps.PADTO, axis=0, amt=32)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.UPCAST, axis=0, arg=2), Opt(op=OptOps.PADTO, axis=0, arg=32)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test needs local") @@ -1025,7 +1024,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(26, 49), strides=(0, -1), offset=48, mask=((0, 26), (24, 49)), contiguous=False), View(shape=(25, 25), strides=(1, 50), offset=0, mask=None, contiguous=False))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=0)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=0)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test needs local") @@ -1039,13 +1038,13 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(26, 49), strides=(0, -1), offset=48, mask=((0, 26), (24, 49)), contiguous=False), View(shape=(25, 25), strides=(1, 50), offset=0, mask=None, contiguous=False))), src=()),)),)),)),)) - opts = [Opt(op=OptOps.GROUP, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=0, amt=32), Opt(op=OptOps.LOCAL, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4)] + opts = [Opt(op=OptOps.GROUP, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=0, arg=32), Opt(op=OptOps.LOCAL, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4)] k = helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) assert k is not None ifs = [u for u in k.uops if u.op is Ops.IF] self.assertEqual(len(ifs), 3) #for st in k.uops.sink.src: self.assertEqual(len(st.src), 4) - self.assertLessEqual(len(ifs[0].src[0].toposort), 17) + self.assertLessEqual(len(ifs[0].src[0].toposort()), 17) def test_failure_45(self): ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( @@ -1084,7 +1083,7 @@ class TestLinearizerFailures(unittest.TestCase): x19,)),)), x21,)),)),)),)),)),)),)) # ValueError: size mismatched, can't reshape self.shape=(6, 2, 3, 3) -> new_shape=(6, 2, 3, 1, 2) - opts = [Opt(op=OptOps.UNROLL, axis=2, amt=0)] + opts = [Opt(op=OptOps.UNROLL, axis=2, arg=0)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) def test_failure_46(self): @@ -1117,7 +1116,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=5, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(512, 1), strides=(1, 0), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=2)] + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=2)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) def test_failure_47(self): @@ -1132,7 +1131,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(60001, 119999), strides=(0, 0), offset=0, mask=((0, 60001), (59999, 119999)), contiguous=False), View(shape=(60000, 60000), strides=(1, 120000), offset=0, mask=None, contiguous=False))), src=()),)),)), ast_const(dtypes.int, -1, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(60000, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=3)] + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=3)] helper_test_lin(Kernel(ast), opts=opts, failed_platforms=[]) @unittest.skipUnless(not CI and Device.DEFAULT in ("NV", "CUDA"), "for real NV") @@ -1151,7 +1150,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 64, 56, 56, 256, 1, 1, 256), strides=(0, 0, 3136, 56, 1, 0, 0, 0, 200704), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=2)] + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 0, 1)), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=2)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_49(self): @@ -1168,7 +1167,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(10, 6, 10), strides=(0, 1, 6), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=2)] + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=0, arg=2)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_50(self): @@ -1195,7 +1194,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 20, 20, 20), strides=(0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)), ast_const(dtypes.bool, True, st_src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1, 20, 1, 20), strides=(0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=1, amt=2)] + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=2)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_51(self): @@ -1206,18 +1205,13 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(12, 1024, 1), strides=(1024, 1, 0), offset=0, mask=None, contiguous=True),)), src=()), UOp(Ops.RECIP, dtypes.half, arg=None, src=( UOp(Ops.ADD, dtypes.half, arg=None, src=( - UOp(Ops.WHERE, dtypes.half, arg=None, src=( - x6:=UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(12, 1024, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.CONST, dtypes.half, arg=1.0, src=()), - x9:=UOp(Ops.CONST, dtypes.half, arg=0.0, src=()),)), + UOp(Ops.CONST, dtypes.half, arg=1.0, src=( + x6:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(12, 1024, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), UOp(Ops.EXP2, dtypes.half, arg=None, src=( UOp(Ops.MUL, dtypes.half, arg=None, src=( UOp(Ops.MUL, dtypes.half, arg=None, src=( - UOp(Ops.WHERE, dtypes.half, arg=None, src=( - x6, - UOp(Ops.CONST, dtypes.half, arg=2.0, src=()), - x9,)), + UOp(Ops.CONST, dtypes.half, arg=2.0, src=( + x6,)), UOp(Ops.ADD, dtypes.half, arg=None, src=( UOp(Ops.CAST, dtypes.half, arg=None, src=( UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (2,)), src=( @@ -1232,11 +1226,9 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=3, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(12, 1024, 1), strides=(0, 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), - UOp(Ops.WHERE, dtypes.half, arg=None, src=( - x6, - UOp(Ops.CONST, dtypes.half, arg=-1.4426950408889634, src=()), - x9,)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=2)] + UOp(Ops.CONST, dtypes.half, arg=-1.4426950408889634, src=( + x6,)),)),)),)),)),)),)) + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 2, 1))] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) @unittest.skipIf(CI and Device.DEFAULT in {"METAL"}, "hangs metal gpu CI") @@ -1258,7 +1250,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(256, 1, 64, 112, 112, 3, 7, 7), strides=(0, 0, 147, 0, 0, 49, 7, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=0, amt=2), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=0, amt=16)] + opts = [Opt(op=OptOps.TC, axis=0, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=16)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_53(self): @@ -1283,18 +1275,15 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.WHERE, dtypes.int, arg=None, src=( UOp(Ops.VALID, dtypes.bool, arg=None, src=( UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(50001, 99999), strides=(0, 0), offset=0, mask=((0, 50001), (49999, 99999)), contiguous=False), View(shape=(1024, 50000, 50000), strides=(0, 1, 100000), offset=0, mask=None, contiguous=False))), src=()),)), - UOp(Ops.CONST, dtypes.int, arg=1, src=()), - x20:=UOp(Ops.CONST, dtypes.int, arg=0, src=()),)),)), - UOp(Ops.WHERE, dtypes.int, arg=None, src=( - x22:=UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1024, 50000, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.CONST, dtypes.int, arg=-1, src=()), - x20,)),)),)), - UOp(Ops.WHERE, dtypes.bool, arg=None, src=( - x22, - UOp(Ops.CONST, dtypes.bool, arg=True, src=()), - UOp(Ops.CONST, dtypes.bool, arg=False, src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.GROUPTOP, axis=1, amt=16)] + UOp(Ops.CONST, dtypes.int, arg=1, src=( + x20:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1024, 50000, 50000), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.CONST, dtypes.int, arg=0, src=( + x20,)),)),)), + UOp(Ops.CONST, dtypes.int, arg=-1, src=( + x23:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1024, 50000, 1), strides=(0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.bool, arg=True, src=( + x23,)),)),)),)),)),)),)) + opts = [Opt(op=OptOps.GROUPTOP, axis=1, arg=16)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=["AMD", "GPU", "METAL", "NV", "CUDA"]) @unittest.skipIf(CI and Device.DEFAULT in {"METAL"}, "hangs metal gpu CI") @@ -1315,7 +1304,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(256, 1, 64, 56, 56, 64, 3, 3), strides=(0, 0, 576, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.TC, axis=2, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=7), Opt(op=OptOps.UPCAST, axis=1, amt=2)] + opts = [Opt(op=OptOps.TC, axis=2, arg=(-1, 2, 1)), Opt(op=OptOps.UPCAST, axis=2, arg=7), Opt(op=OptOps.UPCAST, axis=1, arg=2)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=["HIP", "AMD"]) @unittest.skipIf(CI and Device.DEFAULT in {"METAL"}, "hangs metal gpu CI") @@ -1336,7 +1325,7 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.LOAD, dtypes.half, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(W, 1, 64, 56, 56, 64, 3, 3), strides=(0, 0, 576, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)),)),)) - opts = [Opt(op=OptOps.SWAP, axis=1, amt=2)] + opts = [Opt(op=OptOps.SWAP, axis=1, arg=2)] helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_56(self): @@ -1348,11 +1337,8 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.MUL, dtypes.float, arg=None, src=( UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.CMPLT, dtypes.bool, arg=None, src=( - x7:=UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x8:=UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - x10:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=()), - x10,)), + x7:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=( + x8:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), UOp(Ops.MAX, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.MUL, dtypes.float, arg=None, src=( @@ -1364,26 +1350,24 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.MUL, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), - x22:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x8, - UOp(Ops.CONST, dtypes.float, arg=-1.0, src=()), - x10,)),)),)), + x20:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x8,)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=3, src=()), - x22,)),)), + x20,)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=4, src=()), - x22,)),)), + x20,)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=5, src=()), - x22,)),)), + x20,)),)), x7,)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=6, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 5, 2, 5, 2), strides=(1600, 100, 20, 2, 4, 1), offset=0, mask=None, contiguous=False), View(shape=(128, 16, 11, 11), strides=(1600, 100, 10, 1), offset=0, mask=((0, 128), (0, 16), (0, 10), (0, 10)), contiguous=False))), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=2, amt=32)] - helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=["METAL"]) + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=2, arg=32)] + helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) def test_failure_57(self): ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( @@ -1394,11 +1378,8 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.MUL, dtypes.float, arg=None, src=( UOp(Ops.CAST, dtypes.float, arg=None, src=( UOp(Ops.CMPLT, dtypes.bool, arg=None, src=( - x7:=UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x8:=UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - x10:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=()), - x10,)), + x7:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=( + x8:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), UOp(Ops.MAX, dtypes.float, arg=None, src=( UOp(Ops.ADD, dtypes.float, arg=None, src=( UOp(Ops.MUL, dtypes.float, arg=None, src=( @@ -1410,26 +1391,234 @@ class TestLinearizerFailures(unittest.TestCase): UOp(Ops.MUL, dtypes.float, arg=None, src=( UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), - x22:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x8, - UOp(Ops.CONST, dtypes.float, arg=-1.0, src=()), - x10,)),)),)), + x20:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 11, 11), strides=(0, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x8,)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=3, src=()), - x22,)),)), + x20,)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=4, src=()), - x22,)),)), + x20,)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=5, src=()), - x22,)),)), + x20,)),)), x7,)),)),)), UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=6, src=()), UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(128, 16, 5, 2, 5, 2), strides=(1600, 100, 20, 2, 4, 1), offset=0, mask=None, contiguous=False), View(shape=(128, 16, 11, 11), strides=(1600, 100, 10, 1), offset=0, mask=((0, 128), (0, 16), (0, 10), (0, 10)), contiguous=False))), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=0, amt=0), Opt(op=OptOps.PADTO, axis=1, amt=32)] - helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=["METAL"]) + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=0), Opt(op=OptOps.PADTO, axis=1, arg=32)] + helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=[]) + + def test_failure_58(self): + # OUT OF BOUNDS ACCESS in INDEX 0 - 50271 not in 0 - 50257. idx.src[1].render()='gidx0' + ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(50257), arg=0, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(50257, 1), strides=(1, 0), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.ADD, dtypes.int, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.int, arg=(Ops.ADD, (1,)), src=( + UOp(Ops.WHERE, dtypes.int, arg=None, src=( + UOp(Ops.VALID, dtypes.bool, arg=None, src=( + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(50258, 100513), strides=(0, 0), offset=0, mask=((0, 50258), (50256, 100513)), contiguous=False), View(shape=(50257, 50257), strides=(1, 100514), offset=0, mask=None, contiguous=False))), src=()),)), + UOp(Ops.CONST, dtypes.int, arg=1, src=( + x9:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(50257, 50257), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.CONST, dtypes.int, arg=0, src=( + x9,)),)),)), + UOp(Ops.CONST, dtypes.int, arg=-1, src=( + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(50257, 1), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)) + opts = [Opt(op=OptOps.GROUPTOP, axis=0, arg=29), Opt(op=OptOps.PADTO, axis=0, arg=32)] + with Context(IGNORE_OOB=0): + helper_test_lin(Kernel(ast, opts=Device[Device.DEFAULT].renderer), opts=opts, failed_platforms=["METAL", "GPU", "AMD", "NV", "CUDA"]) + + @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test needs local") + def test_failure_59(self): + # stable diffusion with SINGLE_KERNEL_SOFTMAX=1 + ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(268435456), arg=0, src=()), + x2:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 1, 1), strides=(134217728, 16777216, 4096, 1, 0, 0), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.EXP2, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x8:=UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(268435456), arg=1, src=()), + x2,)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.MAX, (5,), True), src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x8, + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 1, 4096), strides=(134217728, 16777216, 4096, 0, 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x14:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 1, 1), strides=(0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=1.4426950408889634, src=( + x14,)),)),)), + UOp(Ops.RECIP, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (4,)), src=( + UOp(Ops.EXP2, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x8, + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 4096, 1), strides=(134217728, 16777216, 4096, 0, 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.MAX, (5,), True), src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x8, + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 4096, 4096), strides=(134217728, 16777216, 4096, 0, 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x28:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 8, 4096, 4096, 4096, 1), strides=(0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=1.4426950408889634, src=( + x28,)),)),)),)),)),)),)),)) + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UNROLL, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=0, arg=8), Opt(op=OptOps.LOCAL, axis=1, arg=16)] + # NOTE: this is slow to run, just confirm it can generate the program without Exception + Kernel(ast, opts=Device[Device.DEFAULT].renderer).apply_opts(opts).to_program() + + @unittest.expectedFailure + @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local, "test needs local") + def test_failure_60(self): + # TestSymbolicOps.test_attention + ast = UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(80), arg=0, src=()), + x2:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), 1, 1), strides=(UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x2:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)), + x2,)), + UOp(Ops.CONST, dtypes.int, arg=4, src=()),)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)), + x1,)), 0, 1, 0, 0), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.EXP2, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(80), arg=1, src=()), + x2,)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.MAX, (5,), True), src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x12:=UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(80), arg=2, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=())), strides=(UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=4, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x1,)), 0, UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=0, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x15:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), 1, 1), strides=(0, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=1.4426950408889634, src=( + x15,)),)),)), + UOp(Ops.RECIP, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (4,)), src=( + UOp(Ops.EXP2, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x12, + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), 1), strides=(UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=4, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x1,)), 0, UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=0, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.MAX, (5,), True), src=( + UOp(Ops.LOAD, dtypes.float, arg=None, src=( + x12, + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=())), strides=(UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=4, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + x0:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x0, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), 0, UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=0, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), 1), offset=0, mask=None, contiguous=False), View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=())), strides=(UOp(Ops. + MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=4, src=()), + x2:=UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x2,)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + x2:=UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x2,)), 0, UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=0, src=()), + x2:=UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x2,)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + x0:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x0, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), 1), offset=0, mask=None, contiguous=False))), src=()),)),)), + UOp(Ops.CONST, dtypes.float, arg=-1.0, src=( + x29:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=())), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False), View(shape=(2, 4, 1, UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()), UOp(Ops.DEFINE_VAR, dtypes.int + , arg=('i', 1, 10), src=()), 1), strides=(UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=4, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x1, + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x1,)), 0, UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.MUL, dtypes.int, arg=None, src=( + UOp(Ops.CONST, dtypes.int, arg=0, src=()), + UOp(Ops.MUL, dtypes.int, arg=None, src=( + x3:=UOp(Ops.CONST, dtypes.int, arg=1, src=()), + UOp(Ops.DEFINE_VAR, dtypes.int, arg=('i', 1, 10), src=()),)),)), + x3,)), 1, 0), offset=0, mask=None, contiguous=False))), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=1.4426950408889634, src=( + x29,)),)),)),)),)),)),)),)) + opts = [Opt(op=OptOps.LOCAL, axis=0, arg=2), Opt(op=OptOps.LOCAL, axis=0, arg=4)] + # NOTE: this is slow to run, just confirm it can generate the program without Exception + Kernel(ast, opts=Device[Device.DEFAULT].renderer).apply_opts(opts).to_program() if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_linearizer_overflows.py b/tinygrad_repo/test/test_linearizer_overflows.py index 2e7265f652..502d544c36 100644 --- a/tinygrad_repo/test/test_linearizer_overflows.py +++ b/tinygrad_repo/test/test_linearizer_overflows.py @@ -4,17 +4,17 @@ from test.helpers import ast_const from tinygrad import dtypes, Device from tinygrad.helpers import CI from tinygrad.codegen.kernel import Kernel -from tinygrad.engine.search import Opt, OptOps -from tinygrad.engine.search import time_linearizer, bufs_from_lin +from tinygrad.engine.search import Opt, OptOps, bufs_from_lin +from extra.optimization.helpers import time_linearizer # stuff needed to unpack a kernel -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import View def _test_overflow(ast, opts): lin = Kernel(ast) - for opt in opts: lin.apply_opt(opt) + lin.apply_opts(opts) lin.linearize() bufs = bufs_from_lin(lin) print(bufs) @@ -59,7 +59,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=4, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(64, 1, 64, 112, 112, 1, 1, 1), strides=(0, 0, 1, 0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), x16,)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.LOCAL, axis=2, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=0, amt=4), Opt(op=OptOps.UPCAST, axis=2, amt=0)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.LOCAL, axis=2, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=2, arg=0)] _test_overflow(ast, opts) # From BEAM on hlb_cifar.py @@ -76,7 +76,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(512, 1, 64, 32, 32, 32, 3, 3), strides=(0, 0, 288, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.LOCAL, axis=2, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=2, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UNROLL, axis=0, amt=0)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.LOCAL, axis=2, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=2, arg=0), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=0)] _test_overflow(ast, opts) # from BEAM on default simple_conv.py (which is quite large): @@ -93,7 +93,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(16, 1, 128, 128, 128, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.LOCAL, axis=2, amt=8), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.LOCAL, axis=2, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=2, arg=2)] _test_overflow(ast, opts) # from BEAM on BS=4 simple_conv.py: @@ -110,7 +110,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(4, 1, 128, 128, 128, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=3, amt=4), Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=2, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=4)] + opts = [Opt(op=OptOps.UPCAST, axis=3, arg=4), Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=2, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=2, arg=4)] _test_overflow(ast, opts) # from BEAM on BS=2 simple_conv.py: @@ -127,7 +127,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(2, 1, 128, 128, 128, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.LOCAL, axis=2, amt=2), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.LOCAL, axis=2, arg=2), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=2, arg=2)] _test_overflow(ast, opts) # from BEAM on BS=3 simple_conv.py: @@ -144,7 +144,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(3, 1, 128, 128, 128, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.UPCAST, axis=3, amt=0), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=2, amt=8), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=3, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.UPCAST, axis=3, arg=0), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=2, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=3, arg=2)] _test_overflow(ast, opts) # from BEAM on BS=3 simple_conv.py: (alt) @@ -161,7 +161,7 @@ class TestLinearizerOverflow(unittest.TestCase): UOp(Ops.LOAD, dtypes.float, arg=None, src=( UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=2, src=()), UOp(Ops.VIEW, None, arg=ShapeTracker(views=(View(shape=(3, 1, 128, 128, 128, 128, 3, 3), strides=(0, 0, 1152, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)),)) - opts = [Opt(op=OptOps.UPCAST, axis=3, amt=4), Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=2, amt=8), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=2, amt=4)] + opts = [Opt(op=OptOps.UPCAST, axis=3, arg=4), Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=2, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=2, arg=4)] _test_overflow(ast, opts) @unittest.skipIf(Device.DEFAULT not in {"GPU", "HSA", "CUDA", "METAL"}, "only backends with locals") @@ -177,7 +177,7 @@ class TestLinearizerOverflowAlt(unittest.TestCase): prod = UOp(Ops.LOAD, dtypes.float, (g1, in_st_1)) * UOp(Ops.LOAD, dtypes.float, (g2, in_st_2)) store = UOp(Ops.STORE, src=(g0, ot_st, UOp(Ops.REDUCE_AXIS, dtypes.float, (prod,), (Ops.ADD, (7, 6, 5))))) ast = UOp(Ops.SINK, src=(store,)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.LOCAL, axis=2, amt=2), Opt(op=OptOps.UPCAST, axis=0, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.LOCAL, axis=2, arg=2), Opt(op=OptOps.UPCAST, axis=0, arg=2)] _test_overflow(ast, opts) def test_overflow_2(self): BS = 2 @@ -189,7 +189,7 @@ class TestLinearizerOverflowAlt(unittest.TestCase): prod = UOp(Ops.LOAD, dtypes.float, (g1, in_st_1)) * UOp(Ops.LOAD, dtypes.float, (g2, in_st_2)) store = UOp(Ops.STORE, src=(g0, ot_st, UOp(Ops.REDUCE_AXIS, dtypes.float, (prod,), (Ops.ADD, (7, 6, 5))))) ast = UOp(Ops.SINK, src=(store,)) - opts = [Opt(op=OptOps.LOCAL, axis=3, amt=16), Opt(op=OptOps.UPCAST, axis=1, amt=4), Opt(op=OptOps.LOCAL, axis=2, amt=16), Opt(op=OptOps.UPCAST, axis=4, amt=4), Opt(op=OptOps.UPCAST, axis=1, amt=2), Opt(op=OptOps.UPCAST, axis=5, amt=2)] + opts = [Opt(op=OptOps.LOCAL, axis=3, arg=16), Opt(op=OptOps.UPCAST, axis=1, arg=4), Opt(op=OptOps.LOCAL, axis=2, arg=16), Opt(op=OptOps.UPCAST, axis=4, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=5, arg=2)] _test_overflow(ast, opts) if __name__ == '__main__': diff --git a/tinygrad_repo/test/test_memory_planner.py b/tinygrad_repo/test/test_memory_planner.py new file mode 100644 index 0000000000..dcd91569bd --- /dev/null +++ b/tinygrad_repo/test/test_memory_planner.py @@ -0,0 +1,124 @@ +import unittest +from tinygrad import dtypes, Device +from tinygrad.device import Buffer +from tinygrad.engine.memory import _internal_memory_planner + +global_map = {} +def b(i, base=None, offset=0, pin=False, size=16): + global global_map + if i in global_map: return global_map[i] + global_map[i] = Buffer(Device.DEFAULT, size, dtypes.int8, base=global_map[base] if base is not None else None, offset=offset) + if pin: global_map[i].ref(1) + return global_map[i] + +def check_assign(buffers:list[list[Buffer]|tuple[Buffer, ...]]): + assigned = _internal_memory_planner(buffers, noopt_buffers=None) + + taken_parts = set() + first_appearance, last_appearance = {}, {} + for i,u in enumerate(buffers): + for buf in u: + if buf.is_allocated() or buf.base.is_allocated() or buf.lb_refcount > 0: continue + if buf.base not in first_appearance: first_appearance[buf.base] = i + last_appearance[buf.base] = i + + for i,u in enumerate(buffers): + for buf in u: + if buf.is_allocated() or buf.base.is_allocated() or buf.lb_refcount > 0: continue + cur, base = assigned.get(buf, buf), assigned.get(buf.base, buf.base) + if buf._base is not None: + assert cur.base == base.base and cur.offset == buf.offset + base.offset, f"failed: {buf} {cur} {base} {buf.offset} {base.offset}" + else: + for part in taken_parts: + assert buf.base == part[3] or part[0] != cur.base or part[1] + part[2] <= cur.offset or part[1] >= cur.offset + buf.nbytes + if first_appearance[buf.base] == i: taken_parts.add((cur.base, cur.offset, buf.nbytes, buf.base)) + if last_appearance[buf.base] == i: taken_parts.remove((cur.base, cur.offset, buf.nbytes, buf.base)) + +class TestMemoryPlanner(unittest.TestCase): + def setUp(self): + global global_map + global_map = {} + + def test_simple_buffer(self): + bs = [ + [b(0), b(1), b(2)], + [b(1), b(2), b(3)], + [b(4), b(3)], + [b(5), b(2)], + ] + check_assign(bs) + + def test_simple_pinned(self): + bs = [ + [b(0, pin=True), b(1), b(2, pin=True)], + [b(1), b(2), b(3)], + [b(4), b(3)], + [b(5), b(2)], + ] + check_assign(bs) + + def test_all_pinned(self): + bs = [ + [b(0, pin=True), b(1, pin=True)], + [b(1), b(2, pin=True)], + [b(4, pin=True), b(3, pin=True)], + ] + check_assign(bs) + + def test_simple_buffer_offset(self): + bs = [ + [b(0, pin=True), b(1, base=0, offset=1, size=8), b(2)], + [b(1), b(2), b(3, base=0, offset=1, size=8)], + [b(4), b(3)], + ] + check_assign(bs) + + def test_buffer_offset(self): + bs = [ + [b(0, pin=True), b(1, base=0, offset=1, size=8), b(2)], + [b(1), b(2), b(3, base=0, offset=1, size=8)], + [b(4), b(3)], + [b(5, base=2, offset=2, size=8), b(3)], + [b(6), b(5), b(0)], + [b(7), b(8, pin=True)], + [b(8), b(9, base=2, offset=2, size=8)], + [b(9), b(3), b(5)], + ] + check_assign(bs) + + def test_buffer_offset2(self): + bs = [ + [b(0, pin=True), b(1), b(2)], + [b(1), b(2), b(3)], + [b(4), b(3)], + [b(5), b(3)], + [b(6), b(5), b(0)], + [b(7), b(8, pin=True)], + [b(8), b(9)], + [b(9), b(3), b(5)], + [b(11), b(0)], + [b(11), b(10), b(5)], + [b(12), b(11), b(0)], + [b(6), b(12), b(7)], + [b(13), b(6), b(11)], + ] + check_assign(bs) + + def test_all_offsets_of_one(self): + bs = [ + [b(0, pin=True), b(1)], + [b(3, base=1, offset=0, size=8), b(2, base=0, offset=0, size=8)], + [b(5, base=1, offset=8, size=8), b(4, base=0, offset=8, size=8)], + [b(7, base=1, offset=4, size=8), b(6, base=0, offset=4, size=8)], + + [b(4), b(5), b(2)], + [b(3), b(7)], + [b(10), b(6), b(7)], + [b(11), b(3), b(2)], + [b(12), b(5), b(4), b(3), b(2)], + [b(13), b(6), b(12), b(7)], + ] + check_assign(bs) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/test_multitensor.py b/tinygrad_repo/test/test_multitensor.py index f0bf7a0b6b..b8dcf3f610 100644 --- a/tinygrad_repo/test/test_multitensor.py +++ b/tinygrad_repo/test/test_multitensor.py @@ -1,15 +1,14 @@ import unittest, functools, random from typing import List -from tinygrad import Tensor, Device, nn, GlobalCounters, TinyJit, dtypes -from tinygrad.ops import Ops -from tinygrad.helpers import CI, getenv, prod, Context +from tinygrad import Tensor, Device, nn, GlobalCounters, TinyJit, dtypes, Variable +from tinygrad.uop.ops import Ops, UOp +from tinygrad.helpers import CI, getenv, prod, Context, OSX from tinygrad.nn.state import get_parameters, get_state_dict -from tinygrad.engine.schedule import create_schedule -from tinygrad.engine.realize import lower_schedule, BufferCopy, CompiledRunner -from tinygrad.multi import all_reduce, MultiLazyBuffer +from tinygrad.engine.realize import lower_schedule, BufferCopy, CompiledRunner, run_schedule import numpy as np from hypothesis import given, strategies as strat, settings from tinygrad.device import is_dtype_supported +from test.helpers import REAL_DEV, not_support_multi_device settings.register_profile("my_profile", max_examples=200, deadline=None, derandomize=getenv("DERANDOMIZE_CI", False)) settings.load_profile("my_profile") @@ -31,26 +30,36 @@ N = 128 def _test_allreduce(t:Tensor): aa = (t[0:64] + t[64:128] + t[128:192] + t[192:256]).repeat([4,1]).realize() ts = t.shard(devices_4, 0).realize() - b = Tensor(MultiLazyBuffer(all_reduce(Ops.ADD, ts.lazydata.lbs), 0)) + b = Tensor(UOp.allreduce(ts.lazydata, Ops.ADD, ts.device)) b.realize() return aa, b -@unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL"), "no GPU CI") +@unittest.skipIf(not_support_multi_device(), "no multi") class TestMultiTensor(unittest.TestCase): def test_to(self): X = Tensor.ones(256).contiguous().realize() X.to_(devices_2) - for lb in X.lazydata.lbs: - assert lb.shape == (256,) + assert X.shape == (256,) (X + X).realize() + def test_gradient(self): + X = Tensor.ones(256).contiguous().realize() + X.to_(devices_2) + grad = X.sum().gradient(X)[0] + grad.realize() + def test_shard(self): X = Tensor.ones(256).contiguous().realize() X.shard_(devices_2, 0) - for lb in X.lazydata.lbs: + for lb in X.lazydata.src: assert lb.shape == (128,) (X + X).realize() + def test_shard_not_multiple(self): + X = Tensor.ones(256).contiguous().realize() + with self.assertRaises(RuntimeError): + X.shard_(devices_3, 0) + def test_tensor_from_multi(self): X = Tensor([1, 2], dtype=dtypes.int).shard_(devices_2, 0) Y = Tensor(X.lazydata) @@ -69,14 +78,14 @@ class TestMultiTensor(unittest.TestCase): X = Tensor.ones(256).contiguous().realize() X.shard_(devices_2, 0) out = (X + X) - sched = create_schedule(out.lazydata.lbs) + sched = out.schedule() names = [] - for si, ei in zip(sched[:], lower_schedule(sched)): + for si, ei in lower_schedule(sched): if isinstance(ei.prg, CompiledRunner): names.append(ei.prg.p.name) ei.run() - assert names[-2] == names[-1], "function was relinearized" + self.assertEqual(len(set(names)), 1), "function was relinearized" - @unittest.skip("this doesn't fold because from_sharded calls contiguous on all lbs") + @unittest.skip("this doesn't fold because shard_ calls contiguous on all lbs") def test_sharded_memory(self): # Buffer may be stuck in track_cross_buffer for x in (d0, d1, d2, d3, d4): Device[x].synchronize() @@ -158,6 +167,7 @@ class TestMultiTensor(unittest.TestCase): strat.sampled_from((Ops.ADD, Ops.MUL, Ops.MAX)), strat.sampled_from((None, 0, 1)), strat.sampled_from((None, 0, 1)), strat.sampled_from((1, 0, -1))) def test_simple_reduce(self, N, devices, rop, shard_axis, reduce_axis, sign): + N = N * len(devices) X = Tensor.rand(N*N).reshape(N, N).mul(sign) n = X.numpy() X.shard_(devices, shard_axis) @@ -199,17 +209,32 @@ class TestMultiTensor(unittest.TestCase): a,b = jit_allreduce(Tensor.rand(256, 256)) np.testing.assert_almost_equal(a.numpy(), b.numpy(), decimal=5) - @unittest.skip("slow") + def test_multitensor_jit_input(self): + @TinyJit + def f(x): return (x+1).contiguous().sum() + for _ in range(5): + tt = Tensor.arange(0, 4).contiguous().realize().shard((d1,d2), 0).realize() + out = f(tt) + assert out.item() == 1+2+3+4 + + def test_multitensor_inside_jit(self): + @TinyJit + def f(x): return (x.shard((d1,d2), 0)+1).contiguous().sum() + for _ in range(5): + tt = Tensor.arange(0, 4).contiguous().realize() + out = f(tt) + assert out.item() == 1+2+3+4 + def test_fuzz_allreduce(self): random.seed(41) - for it in range(100): + for it in range(2): for n in range(2, 4+1): shape = tuple([(n if i == 0 else 1) * random.randint(1, 10) for i in range(random.randint(1, 4))]) t = Tensor.rand(shape).shard_(tuple([d0, d1, d2, d3][:n]), 0) with Context(RING=0): - a = Tensor(MultiLazyBuffer(all_reduce(Ops.ADD, t.lazydata.lbs), 0)) + a = Tensor(UOp.allreduce(t.lazydata, Ops.ADD, t.device)) with Context(RING=2): - b = Tensor(MultiLazyBuffer(all_reduce(Ops.ADD, t.lazydata.lbs), 0)) + b = Tensor(UOp.allreduce(t.lazydata, Ops.ADD, t.device)) diff = a - b mean_err = diff.reshape((prod(diff.shape),)).abs().mean().numpy() max_err = diff.reshape((prod(diff.shape),)).abs().max().numpy() @@ -277,6 +302,17 @@ class TestMultiTensor(unittest.TestCase): optim.step() out.numpy() + def test_backprop_conv_wino(self): + with Context(WINO=1): self.test_backprop_conv() + + def test_backward_sum(self): + x = Tensor([[1.,2,3,4], [5,6,7,8]]).shard(devices_2, axis=0) + w = Tensor([1.,2,3,4], requires_grad=True).shard(devices_2) + out = x * w + out.mean().backward() + tst = w.grad.numpy() + np.testing.assert_allclose(tst, [0.75, 1., 1.25, 1.5]) + def test_lr_scheduler_OneCycleLR(self): from extra.lr_scheduler import OneCycleLR conv = nn.Conv2d(3, 16, 3) @@ -285,12 +321,11 @@ class TestMultiTensor(unittest.TestCase): lr_sched = OneCycleLR(optim, max_lr=0.1, pct_start=0.1, div_factor=100, final_div_factor=0.1, total_steps=10) lr_sched.step() - @unittest.skipUnless(is_dtype_supported(dtypes.long), f"long dtype not supported on {Device.DEFAULT}") def test_embedding(self): B, T, embed_size, vocab_size = 4, 10, 20, 28 layer = nn.Embedding(vocab_size, embed_size) - x = Tensor(np.random.randint(0, vocab_size, (B, T))) + x = Tensor(np.random.randint(0, vocab_size, (B, T), dtype=np.int32)) z = layer(x) layer_sharded = nn.Embedding(vocab_size, embed_size) @@ -323,11 +358,10 @@ class TestMultiTensor(unittest.TestCase): np.testing.assert_allclose(y.numpy(), y_shard.numpy(), atol=1e-6, rtol=1e-6) # NOTE: this is failing on LLVM CI, no idea why. Works locally. - @unittest.skipIf(CI and Device.DEFAULT in ("CUDA", "NV", "LLVM"), "slow") + @unittest.skipIf(CI and REAL_DEV in ("CUDA", "NV", "LLVM"), "slow") + @unittest.skipIf(REAL_DEV == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_data_parallel_resnet(self): - import sys, pathlib - sys.path.append((pathlib.Path(__file__).parent.parent / "extra" / "models").as_posix()) - from resnet import ResNet18 + from extra.models.resnet import ResNet18 fake_image = Tensor.rand((2, 3, 224//8, 224//8)) fake_image_sharded = fake_image.shard(devices_2, axis=0) @@ -337,24 +371,11 @@ class TestMultiTensor(unittest.TestCase): for p in get_parameters(m): p.shard_(devices_2).realize() GlobalCounters.reset() shard_output = m(fake_image_sharded).log_softmax().realize() - assert shard_output.lazydata.lbs[0].shape == (1, 1000) - assert shard_output.lazydata.lbs[1].shape == (1, 1000) shard_output_np = shard_output.numpy() np.testing.assert_allclose(real_output, shard_output_np, atol=1e-6, rtol=1e-6) - @unittest.skipIf(CI and Device.DEFAULT in ("CUDA", "NV", "LLVM"), "slow, and flaky on LLVM") - def test_data_parallel_resnet_train_step(self): - import sys, pathlib - sys.path.append((pathlib.Path(__file__).parent.parent / "extra" / "models").as_posix()) - from resnet import ResNet18 + def _test_model_train_step(self, m, fake_image, labels): from tinygrad.nn.optim import LARS - - fake_image = Tensor.rand((2, 3, 224//8, 224//8)) - fake_image_sharded = fake_image.shard(devices_2, axis=0) - labels = Tensor.randint(2, low=0, high=1000) - labels_sharded = labels.shard(devices_2, axis=0) - - m = ResNet18() optimizer = LARS(get_parameters(m), 0.1) # set requires_grad for all params optimizer.zero_grad() @@ -363,16 +384,61 @@ class TestMultiTensor(unittest.TestCase): output.backward() grad = m.conv1.weight.grad.numpy() + fake_image_sharded = fake_image.shard(devices_2, axis=0) + labels_sharded = labels.shard(devices_2, axis=0) for p in get_parameters(m): p.shard_(devices_2).realize() GlobalCounters.reset() optimizer.zero_grad() shard_output = m(fake_image_sharded).sparse_categorical_crossentropy(labels_sharded, label_smoothing=0.1) - assert shard_output.lazydata.axis is None shard_output.backward() shard_grad = m.conv1.weight.grad.numpy() # sometimes there is zeros in these grads... why? np.testing.assert_allclose(grad, shard_grad, atol=1e-5, rtol=1e-5) + @unittest.skipIf(CI and REAL_DEV in ("CUDA", "NV", "LLVM", "CPU"), "slow, and flaky on LLVM/CPU") + @unittest.skipIf(REAL_DEV == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") + def test_data_parallel_resnet_train_step(self): + from extra.models.resnet import ResNet18 + fake_image = Tensor.rand((2, 3, 224//8, 224//8)) + labels = Tensor.randint(2, low=0, high=1000) + m = ResNet18() + self._test_model_train_step(m, fake_image, labels) + + def test_data_parallel_simple_train_step(self): + class Model: + def __init__(self): self.conv1 = nn.Linear(128,128) + def __call__(self, x): return self.conv1(x) + def load_from_pretrained(self): pass + + fake_image = Tensor.rand((128,)) + labels = Tensor.randint(2, low=0, high=127) + m = Model() + self._test_model_train_step(m, fake_image, labels) + + def test_assign_kv_cache_multi(self): + bsz, max_context = 2, 8 + + class Attn: + @TinyJit + def __call__(self, xk:Tensor, start_pos:UOp): + seqlen = xk.shape[1] + if not hasattr(self, "cache_k"): + self.cache_k = Tensor.zeros(bsz, max_context, 1, 1).shard(devices_2).contiguous().realize() + keys = self.cache_k.shrink((None, (0, start_pos), None, None)).cat(xk, dim=1).contiguous() if start_pos > 0 else xk + self.cache_k.assign(keys.pad((None,(0,max_context-start_pos-seqlen),None,None)).contiguous()).realize() + + attn = Attn() + xk = Tensor.ones(bsz, 3, 1, 1).shard(devices_2).contiguous() + attn(xk, 0) + for i in range(3,6): + # copied from LLaMA + start_pos = Variable("start_pos", 1, max_context).bind(i) + xk = Tensor.ones(bsz, 1, 1, 1).shard(devices_2).contiguous() + attn(xk, start_pos) + + out = attn.cache_k.flatten().numpy() + np.testing.assert_allclose(out, [1.,1.,1.,1.,1.,1.,0.,0.,1.,1.,1.,1.,1.,1.,0.,0.]) + def test_multi_tensor_jit_param(self): @TinyJit def jf(a, b) -> Tensor: @@ -401,7 +467,6 @@ class TestMultiTensor(unittest.TestCase): np.testing.assert_allclose(r.numpy(), np.ones(256)+np.ones(256), atol=1e-4, rtol=1e-5) assert len(jf.jit_cache) > 0 - #@unittest.skipIf(CI and Device.DEFAULT=="METAL", "no ICB in CI, creation of graph fails") @unittest.skip("test broken") def test_multi_device_jit_graph(self): if Device[d0].graph is None or Device[d1].graph is None: raise unittest.SkipTest("only test graphs") @@ -439,6 +504,7 @@ class TestMultiTensor(unittest.TestCase): assert isinstance(jf.jit_cache[4].prg, BufferCopy) assert isinstance(jf.jit_cache[5].prg, graph_d1) + @unittest.skip("no longer supports uneven shard") def test_uneven_shard(self): for N in range(1, 6): X = Tensor.rand(4, 1, 257).contiguous().realize() @@ -451,6 +517,7 @@ class TestMultiTensor(unittest.TestCase): np.testing.assert_equal(X.expand((4, 4, 257)).numpy(), np.tile(n, (1, 4, 1))) np.testing.assert_equal(X.permute((0, 2, 1)).numpy(), np.transpose(n, (0, 2, 1))) + @unittest.skip("no longer supports uneven shard") def test_uneven_multiple_zeros(self): for data in ([1, 2, 3, 4], [1, 2, 3], [1, 2], [1], []): for N in (1, 2, 3, 4): @@ -459,29 +526,28 @@ class TestMultiTensor(unittest.TestCase): X = ((Tensor(data).shard(devices, axis=0) + 1).realize() - 1).realize() np.testing.assert_equal(X.numpy(), data) + @unittest.skip("no longer supports uneven shard") def test_uneven_shard_with_empty(self): N = 4 - X = Tensor.rand(16, 1, 17).contiguous().realize() + X = Tensor.rand(16, 1, 3).contiguous().realize() np_x = X.numpy() devices = tuple(f"{Device.DEFAULT}:{i}" for i in range(N)) # test empty shard - np.testing.assert_equal(X.shard(devices, 0, (2, 2, 12, 0)).numpy(), np_x) + np.testing.assert_equal(X.shard(devices, 0).numpy(), np_x) # test reshape with empty shard - np.testing.assert_equal(X.shard(devices, 0, (2, 2, 12, 0)).reshape(8, 1, 34).numpy(), np_x.reshape(8, 1, 34)) - - # test elementwise with empty shard - np.testing.assert_equal((X.shard(devices, 0, (2, 2, 12, 0)) + X.shard(devices, 0, (0, 0, 1, 15))).numpy(), np_x + np_x) + np.testing.assert_equal(X.shard(devices, 0).reshape(8, 1, 6).numpy(), np_x.reshape(8, 1, 6)) + @unittest.skip("no longer supports uneven shard") def test_multiple_uneven_shard(self): N = 4 X = Tensor.rand(4, 1, 257).contiguous().realize() Y = Tensor.rand(4, 1, 257).contiguous().realize() np_x, np_y = X.numpy(), Y.numpy() devices = tuple(f"{Device.DEFAULT}:{i}" for i in range(N)) - X.shard_(devices, 2, (2, 38, 47, 170)) - Y.shard_(devices, 2, (34, 53, 51, 119)) + X.shard_(devices, 2) + Y.shard_(devices, 2) np.testing.assert_equal(X.numpy(), np_x) np.testing.assert_equal(Y.numpy(), np_y) np.testing.assert_equal((X + Y).numpy(), np_x + np_y) @@ -492,8 +558,8 @@ class TestMultiTensor(unittest.TestCase): for p in get_parameters(bn): p.shard_(devices_4).realize() out = bn(t) - scheds = [sched for sched in create_schedule(out.lazydata.lbs) if sched.outputs[0].device in devices_4 and sched.ast.op is not Ops.COPY] - assert set(out.device for sched in scheds for out in sched.outputs) == set(devices_4), "should have ast on each shard device" + scheds = [sched for sched in out.schedule() if sched.bufs[0].device in devices_4 and sched.ast.op is not Ops.COPY] + assert set(sched.bufs[0].device for sched in scheds) == set(devices_4), "should have ast on each shard device" asts = [sched.ast for sched in scheds] assert len(asts) # test case to show that ast can be different on devices @@ -524,21 +590,22 @@ class TestMultiTensor(unittest.TestCase): t5 = t0.reshape((2, 13, 3, 5, 7)) t6 = t0.reshape((13, 2, 3, 7, 5)) t7 = t0.reshape((1, 13, 2, 3, 1, 7, 5)) - np.testing.assert_allclose(t5.numpy().flatten(), t0.numpy().flatten()) assert t5.lazydata.axis == 2 - np.testing.assert_allclose(t6.numpy().flatten(), t0.numpy().flatten()) assert t6.lazydata.axis == 2 - np.testing.assert_allclose(t7.numpy().flatten(), t0.numpy().flatten()) assert t7.lazydata.axis == 3 + np.testing.assert_allclose(t5.numpy().flatten(), t0.numpy().flatten()) + np.testing.assert_allclose(t6.numpy().flatten(), t0.numpy().flatten()) + np.testing.assert_allclose(t7.numpy().flatten(), t0.numpy().flatten()) # test no left join with self.assertRaises((AssertionError, ValueError)): - t0.reshape((26*15,7)) + t0.reshape((26*15,7)).schedule() + @unittest.skip("no longer supports uneven shard") def test_reshape_on_axis_uneven(self): def reshape_helper(t0, t, t_axis): - np.testing.assert_allclose(t0.reshape(t.shape).numpy(), t.numpy()) assert t.lazydata.axis == t_axis + np.testing.assert_allclose(t0.reshape(t.shape).numpy(), t.numpy()) t0 = Tensor.rand((4, 42, 15)).shard(devices_3, axis=1, splits=[14, 7, 21]) @@ -561,12 +628,16 @@ class TestMultiTensor(unittest.TestCase): # assert for cannot maintain axis with self.assertRaises(AssertionError): t0.reshape(4, 3, 2, 7, 15) + # it doesn't work like this anymore + # NOTE: this never failed in assign_multi, it failed tensor spec because MULTI was never pushed in the graph + @unittest.expectedFailure def test_mlb_assign_change_axis(self): t_none = Tensor.zeros((16, 16)).shard(devices_2).contiguous().realize() t_zero = Tensor.ones((16, 16)).shard(devices_2, axis=0) - with self.assertRaises(AssertionError): + with self.assertRaises(RuntimeError): # don't allow assigns that change axes t_none.assign(t_zero) + t_none.schedule() def test_init_rand_with_multiple_devices_fail(self): # init rand with multi device is not allowed @@ -606,14 +677,32 @@ class TestMultiTensor(unittest.TestCase): self.assertEqual(t.dtype, t2.dtype) self.assertEqual(t.lazydata.axis, t2.lazydata.axis) + def test_rand_like_from_alu(self): + a = Tensor.ones(4, 4).shard(devices_4, axis=0) + aa = a + a + self.assertEqual(aa.device, devices_4) + self.assertEqual(aa.lazydata.axis, 0) + raa = aa.rand_like() + self.assertEqual(raa.device, devices_4) + self.assertEqual(raa.lazydata.axis, 0) + + b = Tensor.empty(4, 4).shard(devices_4, axis=None) + ab = a + b + self.assertEqual(ab.device, devices_4) + self.assertEqual(ab.lazydata.axis, 0) + rab = ab.rand_like() + self.assertEqual(rab.device, devices_4) + self.assertEqual(rab.lazydata.axis, 0) + + @unittest.skip("no longer supports uneven shard") def test_rand_like_uneven_shard(self): - t = Tensor.empty((4, 42, 15)).shard(devices_3, axis=1, splits=(14, 7, 21)) + t = Tensor.empty((4, 42, 15)).shard(devices_3, axis=1) t2 = Tensor.rand_like(t) self.assertEqual(t.shape, t2.shape) self.assertEqual(t.device, t2.device) self.assertEqual(t.dtype, t2.dtype) self.assertEqual(t.lazydata.axis, t2.lazydata.axis) - assert all(tlb.shape == t2lb.shape for tlb, t2lb in zip(t.lazydata.lbs, t2.lazydata.lbs)) + assert all(tlb.shape == t2lb.shape for tlb, t2lb in zip(t.lazydata.src, t2.lazydata.src)) def test_rand_like_none_shard(self): t = Tensor.empty((16, 16)).shard(devices_2) @@ -656,9 +745,10 @@ class TestMultiTensor(unittest.TestCase): assert set(unique) == {0, 2}, unique assert 200 < counts[0] < 312, counts[0] + @unittest.skip("no longer supports uneven shard") def test_dropout_on_uneven_shard_axis(self): with Tensor.train(): - X = Tensor.ones(256).shard(devices_3, axis=0, splits=(100, 50, 106)) + X = Tensor.ones(256).shard(devices_3, axis=0) output = X.dropout(0.5).numpy() unique, counts = np.unique(output, return_counts=True) assert set(unique) == {0, 2}, unique @@ -690,12 +780,14 @@ class TestMultiTensor(unittest.TestCase): assert ast.src[2].src[0].op is Ops.LOAD assert ast.src[2].src[1].src[1].op is Ops.CONST and ast.src[2].src[1].src[1].arg == 3 + @unittest.skip("TODO: this requires forced_realize to be deleted.") def test_shard_memory(self): devices = (d0, d1, d2, d3) t = Tensor.zeros(16, 16).contiguous() t.shard_(devices, axis=0).realize() - assert all([lb is lb.base and lb.realized.base.size == 4 * 16 for lb in t.lazydata.lbs]) + assert all([lb is lb.base and lb.realized.base.size == 4 * 16 for lb in t.lazydata.src]) + @unittest.skip("this is unreliable on OSX") def test_clone(self): t = Tensor.rand(16, 16).shard(devices_2, axis=None) np.testing.assert_allclose(t.numpy(), t.clone().numpy()) @@ -703,13 +795,35 @@ class TestMultiTensor(unittest.TestCase): t = Tensor.rand(16, 16).shard(devices_2, axis=0) np.testing.assert_allclose(t.numpy(), t.clone().numpy()) -@unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL"), "no GPU CI") + @unittest.skip("this test looks wrong, times 0 is 0") + def test_multi_const_folding(self): + with Context(TRACK_MATCH_STATS=0): + a = Tensor.arange(3).realize() + zeros = Tensor.zeros(3).realize() + b = a.to(devices_2)*zeros.to(devices_2) + sched = b.schedule() + self.assertEqual(len(sched), 6) + # notably, only two copies (for the arange) - vs 4 copies if we didn't fold the const copy + self.assertEqual(len([x for x in sched if any(u.op is Ops.COPY for u in x.ast.toposort())]), 2) + run_schedule(sched) + self.assertListEqual(b.tolist(), [0, 0, 0]) + + @unittest.skip("not sure what this tests") + def test_dont_realize_intermediate_expand(self): + a = Tensor.empty(16, 1).shard_(devices_2, axis=0) + b = Tensor.empty(16, 16).to_(devices_2) + c = Tensor.empty(16, 16).shard_(devices_2, axis=1) + d = a+b + (d*c).realize() + assert not d.lazydata.is_realized + +@unittest.skipIf(not_support_multi_device(), "no multi") class TestHandleData(unittest.TestCase): def test_copied_to_device(self): device = (d0, d1, d2, d3) t = Tensor([1, 2, 3, 4]).shard(device).realize() not_covered = t.to(d5) - sched = create_schedule([not_covered.lazydata]) + sched = not_covered.schedule() assert len(sched) == 1 # setup again because create_schedule has side effect t = Tensor([1, 2, 3, 4]).shard(device).realize() @@ -719,14 +833,15 @@ class TestHandleData(unittest.TestCase): for d in device: t = Tensor([1, 2, 3, 4]).shard(device).realize() covered = t.to(d) - sched = create_schedule([covered.lazydata]) - assert len(sched) == 0 + sched = covered.schedule() + # TODO: this isn't optimized out anymore + #assert len(sched) == 0 # setup again because create_schedule has side effect t = Tensor([1, 2, 3, 4]).shard(device).realize() covered = t.to(d) assert covered.realize().tolist() == [1, 2, 3, 4] -@unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL"), "no GPU CI") +@unittest.skipIf(not_support_multi_device(), "no multi") class TestShrinkMultiTensorShardedAxis(unittest.TestCase): # shrink a multitensor on sharded axis def test_shrink_bad_args(self): @@ -736,25 +851,32 @@ class TestShrinkMultiTensorShardedAxis(unittest.TestCase): with self.assertRaises(AssertionError): # sharded axis shrink on non-device boundry is not allowed a = t.shrink(((0, 3), (0, 8))) + a.schedule() with self.assertRaises(AssertionError): # cannot shrink sharded and non-sharded axis at the same time a = t.shrink(((0, 2), (2, 4))) + a.schedule() a = t.shrink(((0, 2), (0, 8))) + a.schedule() assert a.shape == (2, 8) - assert a.lazydata.real == [True, False, False, False] + # real is no longer used, so these are on None and we can pad them however + """ with self.assertRaises(AssertionError): # cannot pad sharded and non-sharded axis at the same time p = a.pad(((0, 6), (0, 1))) + p.schedule() with self.assertRaises(AssertionError): # can only pad to whole axis p = a.pad(((1, 5), (0, 0))) + p.schedule() + """ p = a.pad(((0, 6), (0, 0))) + p.schedule() assert p.shape == (8, 8) - assert p.lazydata.real == [True, True, True, True] @given(strat.sampled_from([dtypes.float, dtypes.int, dtypes.int64, dtypes.int16])) def test_ops(self, dtype): @@ -766,7 +888,6 @@ class TestShrinkMultiTensorShardedAxis(unittest.TestCase): a = t.shrink(((0+2*i,2+2*i),None)) b = Tensor(t.numpy()[0+2*i:2+2*i]) assert a.shape == b.shape == (2, 8) - assert a.lazydata.real == [i==j for j in range(4)] np.testing.assert_allclose(a.numpy(), b.numpy()) # cast np.testing.assert_allclose(a.float().numpy(), b.float().numpy()) @@ -803,6 +924,7 @@ class TestShrinkMultiTensorShardedAxis(unittest.TestCase): np.testing.assert_allclose(a.reshape((2, 1, 8)).expand((2, 5, 8)).numpy(), b.reshape((2, 1, 8)).expand((2, 5, 8)).numpy(), rtol=1e-7, atol=1e-3) np.testing.assert_allclose(a.flip(-1).numpy(), b.flip(-1).numpy(), rtol=1e-7, atol=1e-3) + @unittest.skip("no longer supports uneven shard") def test_uneven(self): t = Tensor.arange(24).reshape(3, 8).contiguous().realize() t.shard_([f"{Device.DEFAULT}:{i}" for i in range(2)], axis=0) @@ -820,24 +942,27 @@ class TestShrinkMultiTensorShardedAxis(unittest.TestCase): np.testing.assert_equal((a+a).numpy(), na+na) np.testing.assert_equal((b+b).numpy(), nb+nb) + @unittest.skip("why didn't this work?") def test_add_two_partitions(self): t = Tensor.arange(64).reshape(8, 8).contiguous().realize() t.shard_([f"{Device.DEFAULT}:{i}" for i in range(4)], axis=0) a = t.shrink(((2, 4), None)) b = t.shrink(((6, 8), None)) - self.assertEqual(a.lazydata.real, [False, True, False, False]) - self.assertEqual(b.lazydata.real, [False, False, False, True]) na = t.numpy()[2:4] nb = t.numpy()[6:8] np.testing.assert_equal(a.numpy(), na) np.testing.assert_equal(b.numpy(), nb) + self.assertEqual(a.lazydata.real, (False, True, False, False)) + self.assertEqual(b.lazydata.real, (False, False, False, True)) with self.assertRaises(AssertionError): # cannot add directly c = a + b + c.schedule() c = a.pad(((2, 4), None)) + b.pad(((6, 0), None)) - self.assertEqual(c.lazydata.real, [True, True, True, True]) + c.realize() + self.assertEqual(c.lazydata.real, (True, True, True, True)) expected = np.concatenate([np.zeros_like(t.numpy()[0:2]), na, np.zeros_like(t.numpy()[4:6]), nb]) np.testing.assert_equal(c.numpy(), expected) @@ -857,7 +982,8 @@ class TestShrinkMultiTensorShardedAxis(unittest.TestCase): expected = np.arange(64).reshape((8,8)) + np.array([[0,0,1,1,2,2,3,3] for _ in range(8)]).T np.testing.assert_allclose(output.numpy(), expected) -@unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL"), "no GPU CI") +@unittest.skipIf(not_support_multi_device(), "no multi") +@unittest.skipIf(REAL_DEV == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") class TestBatchNorm(unittest.TestCase): def test_unsynced_backprop_conv_bn(self): with Tensor.train(): @@ -885,6 +1011,7 @@ class TestBatchNorm(unittest.TestCase): optim.step() out.numpy() + @unittest.skipIf(REAL_DEV == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_unsynced_backprop_standalone_bn(self): from extra.lr_scheduler import OneCycleLR GPUS = (d1, d2) @@ -898,8 +1025,9 @@ class TestBatchNorm(unittest.TestCase): def __call__(self, x:Tensor): bn_ts = [] - for bound, bn in zip(x.lazydata.bounds, self.bns): - xi = x.shrink((bound, None, None, None)) + each = x.shape[0]//len(self.bns) + for i, bn in enumerate(self.bns): + xi = x.shrink(((each*(i), each*(i+1)), None, None, None)) bni = bn(xi) bn_ts.append(bni) return bn_ts[0].cat(*bn_ts[1:]) @@ -987,9 +1115,9 @@ class TestBatchNorm(unittest.TestCase): p.to_(devices) synced_out = synced_bn(x) - synced_si = list(create_schedule(synced_out.lazydata.lbs)) + synced_si = list(synced_out.schedule()) unsynced_out = unsynced_bn(x) - unsynced_si = list(create_schedule(unsynced_out.lazydata.lbs)) + unsynced_si = list(unsynced_out.schedule()) # TODO: test synced / unsynced batchnorm cross device kernel and copies assert synced_si @@ -1010,10 +1138,48 @@ def helper_test_shard_op(shps, fxn, atol=1e-6, rtol=1e-3): except Exception as e: raise Exception(f"Failed shape {single_out.shape}: {e}") -@unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL"), "no GPU CI") +@unittest.skipIf(not_support_multi_device(), "no multi") class TestTensorOps(unittest.TestCase): def test_interpolate(self): helper_test_shard_op([(4,16,16),(4,24,24)], lambda x: Tensor.interpolate(x, (19,19))) + def test_bitcast(self): + helper_test_shard_op([(256,), (256,)], lambda x: x.bitcast(dtypes.int)) + +# TODO: make these tests pass with VIZ=1 +@unittest.skipIf(not_support_multi_device(), "no multi") +class TestMultiRamUsage(unittest.TestCase): + def setUp(self): + self.baseline = GlobalCounters.mem_used + self.N = 100 + def assertUsed(self, amt, strict=True): + used = GlobalCounters.mem_used - self.baseline + print(f"used {used} bytes") + if strict: self.assertEqual(used, amt) + else: self.assertLessEqual(used, amt) + + def test_zeros(self): + _ = Tensor.zeros(self.N, self.N).contiguous().realize() + self.assertUsed(self.N*self.N*4) + + def test_zeros_del(self): + _ = Tensor.zeros(self.N, self.N).contiguous().realize() + del _ + self.assertUsed(0) + + def test_zeros_copy(self): + _ = Tensor.zeros(self.N, self.N).contiguous().to(devices_2).realize() + # NOTE: the first one on the DEFAULT device should be freed + self.assertUsed(self.N*self.N*4*2) + + @unittest.skip("TODO: this is broken") + def test_zeros_shard(self): + _ = Tensor.zeros(self.N, self.N).contiguous().shard(devices_2, axis=0).realize() + self.assertUsed(self.N*self.N*4) # sharding should not increase total ram usage + + def test_zeros_contiguous_shard(self): + _ = Tensor.zeros(self.N, self.N).contiguous().shard(devices_2, axis=0).contiguous().realize() + self.assertUsed(self.N*self.N*4) # sharding should not increase total ram usage + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_nn.py b/tinygrad_repo/test/test_nn.py index 3e45d5c6f9..f99b2d2cdb 100755 --- a/tinygrad_repo/test/test_nn.py +++ b/tinygrad_repo/test/test_nn.py @@ -2,15 +2,14 @@ import unittest import numpy as np import torch -from tinygrad import Tensor, Device, TinyJit, dtypes -from tinygrad.ops import Ops -from tinygrad.helpers import CI, Context +from tinygrad import Tensor, Device, TinyJit +from tinygrad.uop.ops import Ops +from tinygrad.helpers import GlobalCounters, CI, Context, OSX from tinygrad.nn import Conv1d, ConvTranspose1d, Conv2d, ConvTranspose2d, Linear, Embedding from tinygrad.nn import BatchNorm, LayerNorm, LayerNorm2d, GroupNorm, InstanceNorm, RMSNorm, LSTMCell from tinygrad.nn.state import load_state_dict -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import run_schedule -from tinygrad.device import is_dtype_supported +from test.helpers import not_support_multi_device @unittest.skipIf(CI and Device.DEFAULT in {"CUDA", "NV"}, "slow") class TestNN(unittest.TestCase): @@ -268,7 +267,6 @@ class TestNN(unittest.TestCase): 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) - @unittest.skipIf(CI and 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 @@ -289,7 +287,6 @@ class TestNN(unittest.TestCase): 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 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 @@ -310,6 +307,7 @@ class TestNN(unittest.TestCase): 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 == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_groupnorm(self): BS, H, W, C, G = 20, 10, 10, 6, 3 @@ -329,13 +327,14 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.bias.grad.numpy(), torch_layer.bias.grad.detach().numpy(), atol=5e-4, rtol=5e-4) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_layernorm(self): N, C, H, W = 20, 5, 10, 10 @@ -355,13 +354,14 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.bias.grad.numpy(), torch_layer.bias.grad.detach().numpy(), atol=5e-4, rtol=5e-4) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_layernorm_2d(self): N, C, H, W = 20, 5, 10, 10 @@ -381,13 +381,14 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x.permute(0,2,3,1)).permute(0,3,1,2) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=5e-4, rtol=5e-4) np.testing.assert_allclose(layer.bias.grad.numpy(), torch_layer.bias.grad.detach().numpy(), atol=5e-4, rtol=5e-4) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_instancenorm_2d(self): N, C, H, W = 20, 10, 10, 10 @@ -407,13 +408,14 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=1e-3, rtol=1e-3) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=1e-3, rtol=1e-3) np.testing.assert_allclose(layer.bias.grad.numpy(), torch_layer.bias.grad.detach().numpy(), atol=1e-3, rtol=1e-3) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_instancenorm_3d(self): N, C, D, H, W = 20, 10, 10, 10, 10 @@ -433,27 +435,29 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=1e-3, rtol=1e-3) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=2e-3, rtol=1e-3) np.testing.assert_allclose(layer.bias.grad.numpy(), torch_layer.bias.grad.detach().numpy(), atol=1e-3, rtol=1e-3) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_rmsnorm(self): class TorchRMSNorm(torch.nn.Module): # https://github.com/meta-llama/llama/blob/be327c427cc5e89cc1d3ab3d3fec4484df771245/llama/model.py#L34C1-L77C36 - def __init__(self, dim: int, eps: float = 1e-6): + def __init__(self, dim: int, eps: float = 1e-6, elementwise_affine: bool = True): super().__init__() self.eps = eps - self.weight = torch.nn.Parameter(torch.ones(dim)) + self.elementwise_affine = elementwise_affine + self.weight = torch.nn.Parameter(torch.ones(dim)) if elementwise_affine else None def _norm(self, x): return x * torch.rsqrt(x.pow(2).mean(-1, keepdim=True) + self.eps) def forward(self, x): output = self._norm(x.float()).type_as(x) - return output * self.weight + return output if self.weight is None else output * self.weight B, T, embed_size = 4, 10, 20 torch_layer = TorchRMSNorm(embed_size) @@ -468,13 +472,28 @@ class TestNN(unittest.TestCase): torch_x = torch.tensor(x.numpy(), requires_grad=True) torch_z = torch_layer(torch_x) - torch_z.sum().backward(retain_graph=True) + torch_z.sum().backward() np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=1e-3, rtol=1e-3) np.testing.assert_allclose(layer.weight.grad.numpy(), torch_layer.weight.grad.detach().numpy(), atol=2e-3, rtol=1e-3) - @unittest.skipUnless(is_dtype_supported(dtypes.long), f"no long on {Device.DEFAULT}") + torch_layer = TorchRMSNorm(embed_size, elementwise_affine=False) + layer = RMSNorm(embed_size, elementwise_affine=False) + + for _ in range(10): + # forward + x = Tensor.randn(B, T, embed_size, requires_grad=True) + z = layer(x) + z.sum().backward() + + torch_x = torch.tensor(x.numpy(), requires_grad=True) + torch_z = torch_layer(torch_x) + torch_z.sum().backward() + + np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-6, rtol=5e-6) + np.testing.assert_allclose(x.grad.numpy(), torch_x.grad.detach().numpy(), atol=1e-3, rtol=1e-3) + def test_embedding(self): B, T, embed_size, vocab_size = 4, 10, 20, 28 @@ -486,14 +505,14 @@ class TestNN(unittest.TestCase): torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) # test - x = Tensor(np.random.randint(0, vocab_size, (B, T))) + x = Tensor(np.random.randint(0, vocab_size, (B, T), dtype=np.int32)) 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=1e-8, rtol=1e-8) # test with empty input length - x = Tensor(np.random.randint(0, vocab_size, (B, 0))) + x = Tensor(np.random.randint(0, vocab_size, (B, 0), dtype=np.int32)) z = layer(x) torch_x = torch.tensor(x.numpy()) torch_z = torch_layer(torch_x) @@ -505,29 +524,41 @@ class TestNN(unittest.TestCase): return layer(x).realize() for _ in range(3): - x = Tensor(np.random.randint(0, vocab_size, (B, T))) + x = Tensor(np.random.randint(0, vocab_size, (B, T), dtype=np.int32)) z = layer_jit(x) torch_x = torch.tensor(x.numpy()) torch_z = torch_layer(torch_x) np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=1e-8, rtol=1e-8) - def test_embedding_one_kernel(self): + def test_embedding_one_kernel(self, ops=41410, kcount=3): + GlobalCounters.reset() layer = Embedding(20, 30) layer.weight = Tensor.zeros_like(layer.weight).contiguous() a = Tensor([[1, 5, 9, 11], [12, 19, 8, 1]]) result = layer(a) - schedule = create_schedule([result.lazydata]) - self.assertEqual(3, len([item for item in schedule if item.ast.op is Ops.SINK]), "first run realizes arange, weight, and embedding") + schedule = result.schedule() + self.assertEqual(kcount, len([item for item in schedule if item.ast.op is Ops.SINK]), "first run realizes weight and embedding") run_schedule(schedule) b = Tensor([[1, 2, 3], [4, 5, 6], [7, 8, 9]]) result = layer(b) - schedule = create_schedule([result.lazydata]) + schedule = result.schedule() self.assertEqual(1, len([item for item in schedule if item.ast.op is Ops.SINK]), "second run realizes embedding only") run_schedule(schedule) + print(f"Embedding used {GlobalCounters.global_ops} ops") + self.assertLessEqual(GlobalCounters.global_ops, ops) + + # TODO: fused with opts uses more ops + def test_embedding_one_kernel_fused(self): + with Context(FUSE_ARANGE=1, NOOPT=0): + self.test_embedding_one_kernel(ops=612_000, kcount=2) + + def test_embedding_one_kernel_fused_noopt(self): + with Context(FUSE_ARANGE=1, NOOPT=1): + self.test_embedding_one_kernel(ops=0, kcount=2) def test_embedding_shape(self): vocab_size, embed_size = 10, 16 @@ -550,16 +581,16 @@ class TestNN(unittest.TestCase): np.testing.assert_allclose(layer.weight.numpy(), state_dict['weight'].numpy()) np.testing.assert_allclose(layer.bias.numpy(), state_dict['bias'].numpy()) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU CI") + @unittest.skipIf(not_support_multi_device(), "no multi") def test_load_state_dict_sharded_model(self): - devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2") + devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3") layer = Conv2d(3, 5, kernel_size=3) layer.weight.shard_(devices, 3) layer.bias.shard_(devices, None) state_dict = { - 'weight': Tensor.randn(5, 3, 3, 3), - 'bias': Tensor.randn(5), + 'weight': Tensor.randn(5, 3, 3, 3).realize(), + 'bias': Tensor.randn(5).realize(), } load_state_dict(layer, state_dict) @@ -571,9 +602,9 @@ class TestNN(unittest.TestCase): np.testing.assert_allclose(layer.weight.numpy(), state_dict['weight'].numpy()) np.testing.assert_allclose(layer.bias.numpy(), state_dict['bias'].numpy()) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU CI") + @unittest.skipIf(not_support_multi_device, "no multi") def test_load_state_dict_sharded_dict(self): - devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2") + devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3") layer = Conv2d(3, 5, kernel_size=3) state_dict = { @@ -588,9 +619,9 @@ class TestNN(unittest.TestCase): np.testing.assert_allclose(layer.weight.numpy(), state_dict['weight'].numpy()) np.testing.assert_allclose(layer.bias.numpy(), state_dict['bias'].numpy()) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU CI") + @unittest.skipIf(not_support_multi_device(), "no multi") def test_load_state_dict_sharded_model_dict_same_axis(self): - devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2") + devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3") layer = Conv2d(3, 5, kernel_size=3) layer.weight.shard_(devices, 3) @@ -609,9 +640,10 @@ class TestNN(unittest.TestCase): np.testing.assert_allclose(layer.weight.numpy(), state_dict['weight'].numpy()) np.testing.assert_allclose(layer.bias.numpy(), state_dict['bias'].numpy()) - @unittest.skipIf(CI and Device.DEFAULT in {"GPU", "CUDA", "METAL"}, "no GPU CI") + @unittest.skipIf(not_support_multi_device, "no multi") def test_load_state_dict_sharded_model_dict_different_axis(self): - devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2") + devices = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3") + devices5 = (f"{Device.DEFAULT}:1", f"{Device.DEFAULT}:2", f"{Device.DEFAULT}:3", f"{Device.DEFAULT}:4", f"{Device.DEFAULT}:5") layer = Conv2d(3, 5, kernel_size=3) layer.weight.shard_(devices, 3) @@ -620,14 +652,14 @@ class TestNN(unittest.TestCase): # different shard axis state_dict = { 'weight': Tensor.randn(5, 3, 3, 3).shard(devices, None), - 'bias': Tensor.randn(5).shard(devices, 0), + 'bias': Tensor.randn(5).shard(devices5, 0), } load_state_dict(layer, state_dict) # NOTE: model and state_dict shard differently, use the state_dict sharding # TODO: revisit this? self.assertEqual(layer.weight.device, devices) self.assertEqual(layer.weight.lazydata.axis, None) - self.assertEqual(layer.bias.device, devices) + self.assertEqual(layer.bias.device, devices5) self.assertEqual(layer.bias.lazydata.axis, 0) np.testing.assert_allclose(layer.weight.numpy(), state_dict['weight'].numpy()) np.testing.assert_allclose(layer.bias.numpy(), state_dict['bias'].numpy()) diff --git a/tinygrad_repo/test/test_ops.py b/tinygrad_repo/test/test_ops.py index 654b79c944..e0ddc66fc8 100644 --- a/tinygrad_repo/test/test_ops.py +++ b/tinygrad_repo/test/test_ops.py @@ -2,13 +2,17 @@ import time, math, unittest, functools import numpy as np from typing import List, Callable import torch -from tinygrad.helpers import getenv, IMAGE, DEBUG, CI, Context, TRANSCENDENTAL +import warnings +from tinygrad.helpers import getenv, IMAGE, DEBUG, CI, Context, TRANSCENDENTAL, DEVECTORIZE, OSX from tinygrad import Tensor, Device, dtypes from tinygrad.tensor import _to_np_dtype from tinygrad.device import is_dtype_supported +if getenv("TINY_BACKEND"): + import tinygrad.frontend.torch # noqa: F401 # pylint: disable=unused-import + torch.set_default_device("tiny") + if CI: - import warnings warnings.filterwarnings("ignore", message="Non-empty compiler output encountered") FORWARD_ONLY = getenv("FORWARD_ONLY", 0) @@ -46,35 +50,23 @@ def helper_test_op(shps, torch_fxn, tinygrad_fxn=None, atol=1e-6, rtol=1e-3, gra 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) + print(out.detach().cpu().numpy()) + compare("forward pass", ret.numpy(), out.detach().cpu().numpy(), atol=atol, rtol=rtol) torch_fbp, tinygrad_fbp = np.nan, np.nan - if not forward_only and not FORWARD_ONLY: + if not forward_only and not FORWARD_ONLY and ts and tst: st = time.monotonic() - (out+1).square().mean().backward() + torch_grads = torch.autograd.grad(torch_fxn(*ts).sum(), ts) torch_fbp = time.monotonic() - st st = time.monotonic() # NOTE: we now have to recompute the forward pass since we realized it - ret = tinygrad_fxn(*tst) - loss:Tensor = (ret+1).square().mean() - # test_ops uses new style gradient - tst_grads = loss.gradient(*tst) - if len(tst_grads): Tensor.realize(*tst_grads) - tinygrad_fbp = time.monotonic() - st - - for i, (t, tt_grad) in enumerate(zip(ts, tst_grads)): - compare(f"backward pass tensor {i}", tt_grad.numpy(), t.grad.detach().numpy(), atol=grad_atol, rtol=grad_rtol) - - """ - (ret+1).square().mean().backward() - for tt in tst: tt.grad.realize() + tiny_grads = tinygrad_fxn(*tst).sum().gradient(*tst) + Tensor.realize(*tiny_grads) 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) - """ + for i, (t, torch_grad) in enumerate(zip(tiny_grads, torch_grads)): + compare(f"backward pass tensor {i}", t.numpy(), torch_grad.detach().cpu().numpy(), atol=grad_atol, rtol=grad_rtol) if not CI: print("\ntesting %40r torch/tinygrad fp: %.2f / %.2f ms bp: %.2f / %.2f ms " % \ @@ -90,14 +82,14 @@ def prepare_test_op(low, high, shps, vals, forward_only=False): for i in range(len(ts)): # NOTE: torch default int64 for python ints input if ts[i].dtype == torch.int64: ts[i] = ts[i].type(torch.int32) - tst = [Tensor(x.detach().numpy(), requires_grad=(not forward_only and not FORWARD_ONLY)) for x in ts] + tst = [Tensor(x.detach().cpu().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, low=-1.5, high=1.5): + def helper_test_exception(self, shps, torch_fxn, tinygrad_fxn, expected, forward_only=False, exact=False, vals=None, low=-1.5, high=1.5): if getenv("MOCKGPU") and Device.DEFAULT == "NV": self.skipTest('helper_test_exception fails in CI CUDA') - ts, tst = prepare_test_op(low, high, shps, vals) + ts, tst = prepare_test_op(low, high, shps, vals, forward_only) with self.assertRaises(expected) as torch_cm: torch_fxn(*ts) with self.assertRaises(expected) as tinygrad_cm: @@ -352,30 +344,36 @@ class TestOps(unittest.TestCase): def test_cmp_le(self): self._test_cmp(lambda x,y: x<=y) def test_cmp_ne_backwards(self): + # new grad zeroes these out + """ t1 = torch.ones(4, requires_grad=True) t2 = torch.ones(4, requires_grad=True) self.assertRaises(RuntimeError, (t1 != t2).sum().backward) tt1 = Tensor.ones(4, requires_grad=True) tt2 = Tensor.ones(4, requires_grad=True) self.assertRaises(RuntimeError, (tt1 != tt2).sum().backward) + """ tt = Tensor.randn(4, requires_grad=True) (tt*(tt != 0)).sum().backward() t = torch.tensor(tt.numpy(), requires_grad=True) (t*(t != 0)).sum().backward() - np.testing.assert_allclose(t.grad.numpy(), tt.grad.numpy(), rtol=1e-5) + np.testing.assert_allclose(t.grad.cpu().numpy(), tt.grad.numpy(), rtol=1e-5) def test_cmp_lt_backwards(self): + # new grad zeroes these out + """ t1 = torch.ones(4, requires_grad=True) t2 = torch.ones(4, requires_grad=True) self.assertRaises(RuntimeError, (t1 < t2).sum().backward) tt1 = Tensor.ones(4, requires_grad=True) tt2 = Tensor.ones(4, requires_grad=True) self.assertRaises(RuntimeError, (tt1 < tt2).sum().backward) + """ tt = Tensor.randn(4, requires_grad=True) (tt*(tt < 0)).sum().backward() t = torch.tensor(tt.numpy(), requires_grad=True) (t*(t < 0)).sum().backward() - np.testing.assert_allclose(t.grad.numpy(), tt.grad.numpy(), rtol=1e-5) + np.testing.assert_allclose(t.grad.cpu().numpy(), tt.grad.numpy(), rtol=1e-5) # TODO: fix backward of these functions def test_trunc(self): @@ -406,6 +404,9 @@ class TestOps(unittest.TestCase): def test_isnan(self): helper_test_op(None, torch.isnan, Tensor.isnan, vals=[[float('-inf'), 0., float('inf'), float('nan'), 1.1]], forward_only=True) + def test_isfinite(self): + helper_test_op(None, torch.isfinite, Tensor.isfinite, vals=[[float('-inf'), 0., float('inf'), float('nan'), 1.1]], forward_only=True) + def test_lerp(self): helper_test_op([(45,35), (45,35), (45,35)], lambda x,y,z: x.lerp(y,z)) helper_test_op(None, lambda x,y,z: x.lerp(y,z), vals=[[1.,2.,3.], [4.,5.,6.], 0.5]) @@ -532,19 +533,45 @@ class TestOps(unittest.TestCase): helper_test_op([(45,65), (45,65)], lambda x,y: x/y, Tensor.div) helper_test_op([(45,65), (45,65)], lambda x,y: x/y) helper_test_op([(), ()], lambda x,y: x/y) + + @unittest.skipIf(getenv("AMD_LLVM", 0), "AMD with LLVM backend generate rcp in FP division causes trunc/floor errors") + def test_div_rounding_mode(self): + for denominator in [-10, -5, -3, -2, -1, 1, 2, 3, 5, 10]: + # int numerator + helper_test_op(None, lambda x,y: x.div(y, rounding_mode=None), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="trunc"), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="floor"), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + # float numerator + helper_test_op(None, lambda x,y: x.div(y, rounding_mode=None), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="trunc"), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="floor"), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + + for denominator in [-10.0, -5.0, -3.0, -2.0, -1.0, 1.0, 2.0, 3.0, 5.0, 10.0]: + # int numerator + helper_test_op(None, lambda x,y: x.div(y, rounding_mode=None), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="trunc"), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="floor"), forward_only=True, vals=[[5, 6, 7, 0, -5, -6, -7], [denominator]]) + # float numerator + helper_test_op(None, lambda x,y: x.div(y, rounding_mode=None), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="trunc"), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + helper_test_op(None, lambda x,y: x.div(y, rounding_mode="floor"), forward_only=True, vals=[[5.0, 6, 7, 0, -5, -6, -7], [denominator]]) + + self.helper_test_exception(None, lambda x,y: x.div(y, rounding_mode="typo"), lambda x,y: x.div(y, rounding_mode="typo"), forward_only=True, + vals=[[5], [0]], expected=RuntimeError) + def test_div_int(self): - helper_test_op(None, lambda x,y: x/y, Tensor.div, forward_only=True, vals=np.array([[5, 6, 7],[1, 2, 3]], dtype=np.int32)) - helper_test_op(None, lambda x,y: x//y, forward_only=True, vals=np.array([[5, 6, 7],[1, 2, 3]], dtype=np.int32)) - helper_test_op(None, lambda x: x/2, forward_only=True, vals=np.array([[3, 4, 5]], dtype=np.int32)) - helper_test_op(None, lambda x: x//2, forward_only=True, vals=np.array([[3, 4, 5]], dtype=np.int32)) + helper_test_op(None, lambda x,y: x/y, Tensor.div, forward_only=True, vals=[[5, 6, 7],[1, 2, 3]]) + helper_test_op(None, lambda x,y: x//y, forward_only=True, vals=[[5, 6, 7],[1, 2, 3]]) + helper_test_op(None, lambda x: x/2, forward_only=True, vals=[[3, 4, 5]]) + helper_test_op(None, lambda x: x//2, forward_only=True, vals=[[3, 4, 5]]) helper_test_op(None, functools.partial(torch.div, rounding_mode="trunc"), Tensor.idiv, forward_only=True, - vals=np.array([[5, -6, 7],[1, 2, 3]], dtype=np.int32)) + vals=[[-4, 7, 5, 4, -7, 8], [2, -3, 8, -2, 3, 5]]) if is_dtype_supported(dtypes.uint64): x = Tensor(2**64 - 1, dtype=dtypes.uint64).idiv(1) np.testing.assert_equal(x.numpy(), 2**64 - 1) # 1 // 0 is device dependent, but it should not raise Tensor([1]).idiv(1).realize() - if not (CI and (Device.DEFAULT=="LLVM" or getenv("PTX"))): # TODO: crashed in CI + if not (CI and getenv("PTX")): # TODO: crashed in PTX CI # ... because if might be in a where branch that the output is well defined t = Tensor([-1, 0, 1, 2]) np.testing.assert_equal((t > 0).where(1//t, t).numpy(), [-1, 0, 1, 0]) @@ -558,6 +585,21 @@ class TestOps(unittest.TestCase): helper_test_op([()], lambda x: x/2) helper_test_op([()], lambda x: 2/x) + def test_mod(self): + a = [-4, 7, 5, 4, -7, 8, -9] + b = [2, -3, 8, -2, 3, 5, -5] + for float_a in [True, False]: + for float_b in [True, False]: + va = [float(ai) for ai in a] if float_a else a + vb = [float(bi) for bi in b] if float_b else b + helper_test_op(None, lambda x,y: x%y, Tensor.mod, forward_only=True, vals=[va, vb]) + helper_test_op(None, lambda x,y: x%y, forward_only=True, vals=[va, vb]) + helper_test_op(None, lambda x: x%2, forward_only=True, vals=[va]) + helper_test_op(None, lambda x: x%3, forward_only=True, vals=[va]) + helper_test_op(None, lambda x: x%3.5, forward_only=True, vals=[va]) + helper_test_op(None, lambda x: 100%x, forward_only=True, vals=[va]) + helper_test_op(None, lambda x: 100.5%x, forward_only=True, vals=[va]) + def test_mul_naninf(self): helper_test_op([(45,65)], lambda x: x*math.inf) helper_test_op([(45,65)], lambda x: x*-math.inf) @@ -594,18 +636,54 @@ class TestOps(unittest.TestCase): helper_test_op([], lambda: b**1.1, lambda: a**1.1) def test_pow_const(self): + helper_test_op([(45,65)], lambda x: x**0.0) helper_test_op([(45,65)], lambda x: x**1.0) helper_test_op([(45,65)], lambda x: x**-1.0) + helper_test_op([(45,65)], lambda x: x**8.0) + helper_test_op([(45,65)], lambda x: x**5.5) + helper_test_op([(45,65)], lambda x: x**-5.5) + # helper_test_op([(45,65)], lambda x: x**-8.0) # TODO: fix this helper_test_op([(45,65)], lambda x: 1.0**x) + helper_test_op([(45,65)], lambda x: 5.5**x) + helper_test_op([(45,65)], lambda x: (-5.5)**x) + helper_test_op([(45,65)], lambda x: 8.0**x) helper_test_op([(45,65)], lambda x: x**2.0) helper_test_op([(45,65)], lambda x: 2.0**x) helper_test_op([()], lambda x: x**2.0) helper_test_op([()], lambda x: 2.0**x) - # TODO: fix backward - helper_test_op(None, lambda x: 0**x, vals=[[-2.,-1,0,1,2,3]], forward_only=True) - # TODO: fix backward, should be nan - helper_test_op(None, lambda x: (-2)**x, vals=[[-2.,-1,0,1,2,3]], forward_only=True) - + helper_test_op(None, lambda x: 0**x, vals=[[-2.,-1,0,1,2,3]]) + helper_test_op(None, lambda x: (-2)**x, vals=[[-2.,-1,0,1,2,3]]) + + def test_pow_const_direct(self): + # x ** c + def get_tiny_gradient(x, c): + t = Tensor([x], dtype=dtypes.float) + return (t ** c)[0].gradient(t)[0].item() + def get_torch_gradient(x, c): + t = torch.tensor([x], dtype=torch.float, requires_grad=True) + return torch.autograd.grad(t ** c, t)[0].item() + for x in [-math.inf, 0, 1, math.inf]: + for c in [-1, 0, 0.3, 1, 2]: + tiny_out = get_tiny_gradient(x, c) + torch_out = get_torch_gradient(x, c) + if math.isnan(tiny_out): + assert math.isnan(torch_out) + else: + self.assertAlmostEqual(tiny_out, torch_out, msg=f"{x}, {c}") + + def test_pow_zero_tensor(self): + helper_test_op(None, lambda x,y: x**y, vals=[[0.0], [0.0]]) + # TODO: fix WEBGPU + if Device.DEFAULT != "WEBGPU": + helper_test_op(None, lambda x,y: x**y, vals=[[0.0], [0.3]]) + helper_test_op(None, lambda x,y: x**y, vals=[[0.0], [-0.3]]) + def test_pow_zero_const(self): + helper_test_op(None, lambda x: x**0.3, vals=[[0.0]]) + helper_test_op(None, lambda x: x**0.0, vals=[[0.0]]) + helper_test_op(None, lambda x: x**-0.3, vals=[[0.0]]) + helper_test_op(None, lambda x: x**-1.0, vals=[[-1.0, 0.0, 1.0]]) + + @unittest.skip("not supported") def test_pow_int(self): def _test(base, exponent): helper_test_op(None, lambda x,y: x**y, vals=[base, exponent], forward_only=True) @@ -627,9 +705,11 @@ class TestOps(unittest.TestCase): def test_sqrt(self): helper_test_op([(45,65)], lambda x: x.sqrt()) + helper_test_op(None, lambda x: x.sqrt(), vals=[[0.0]]) helper_test_op([()], lambda x: x.sqrt()) def test_rsqrt(self): helper_test_op([(45,65)], lambda x: x.rsqrt()) + helper_test_op(None, lambda x: x.rsqrt(), vals=[[0.0]]) helper_test_op([()], lambda x: x.rsqrt()) def test_xor(self): @@ -640,7 +720,7 @@ class TestOps(unittest.TestCase): helper_test_op([], lambda: tor^0x1337, lambda: ten^0x1337, forward_only=True) helper_test_op([], lambda: 0x1337^tor, lambda: 0x1337^ten, forward_only=True) - self.helper_test_exception([(4), (4)], torch.bitwise_xor, Tensor.xor, expected=RuntimeError) + self.helper_test_exception([(4), (4)], torch.bitwise_xor, Tensor.bitwise_xor, expected=RuntimeError) def test_and(self): data = [[1,-8,1],[32,1,6]] @@ -655,6 +735,8 @@ class TestOps(unittest.TestCase): ten0, ten1 = Tensor(data[0], dtype=dtypes.bool), Tensor(data[1], dtype=dtypes.bool) helper_test_op([], lambda: tor0&tor1, lambda: ten0&ten1, forward_only=True) + helper_test_op(None, lambda x: (1 < x) & (x < 2), forward_only=True, vals=[[1.2, 1.2, 1.2, 3.2]]) + self.helper_test_exception([(4), (4)], torch.bitwise_and, Tensor.bitwise_and, expected=RuntimeError) def test_or(self): @@ -709,6 +791,12 @@ class TestOps(unittest.TestCase): helper_test_op([], lambda: tor.__rshift__(2), lambda: ten.__rshift__(2).cast(dtypes.int32), forward_only=True) helper_test_op([], lambda: tor.bitwise_right_shift(2), lambda: ten.rshift(2).cast(dtypes.int32), forward_only=True) + def test_idiv_shift_rewrite_negative(self): + a = Tensor(-5).idiv(2).item() + b = Tensor(-5).contiguous().idiv(2).item() + self.assertEqual(a, b) + self.assertEqual(Tensor(-1).contiguous().idiv(4).item(), 0) # NOTE this is trunc-div behaviour + def test_sin(self): helper_test_op([(45,65)], lambda x: x.sin()) helper_test_op([()], lambda x: x.sin()) @@ -727,7 +815,7 @@ class TestOps(unittest.TestCase): def test_tan(self): # NOTE: backward has much higher diff with input close to pi/2 and -pi/2 helper_test_op([(45,65)], lambda x: x.tan(), low=-1.5, high=1.5) - helper_test_op([(45,65)], lambda x: x.tan(), low=-5, high=5, forward_only=True) + helper_test_op([(45,65)], lambda x: x.tan(), low=-5, high=5) helper_test_op([()], lambda x: x.tan()) if not ((getenv("MOCKGPU") and Device.DEFAULT == "NV") or Device.DEFAULT == "WEBGPU"): helper_test_op(None, lambda x: x.sin(), vals=[[math.nan, math.inf, -math.inf, 0.0]]) @@ -755,9 +843,9 @@ class TestOps(unittest.TestCase): helper_test_op(None, lambda x: x.relu(), vals=[[-1.,0,1]]) def test_relu_maximum_exact(self): helper_test_op(None, lambda x: torch.maximum(x, torch.zeros_like(x, requires_grad=False)), lambda x: Tensor.maximum(x, 0), vals=[[-1.,0,1]]) - def test_leakyrelu(self): - helper_test_op([(45,65)], lambda x: torch.nn.functional.leaky_relu(x,0.01), Tensor.leakyrelu) - helper_test_op([()], lambda x: torch.nn.functional.leaky_relu(x,0.01), Tensor.leakyrelu) + def test_leaky_relu(self): + helper_test_op([(45,65)], lambda x: torch.nn.functional.leaky_relu(x,0.01), Tensor.leaky_relu) + helper_test_op([()], lambda x: torch.nn.functional.leaky_relu(x,0.01), Tensor.leaky_relu) def test_celu(self): for val in range(1, 5): helper_test_op([(45,65)], lambda x: torch.nn.functional.celu(x,val), lambda x: x.celu(val)) @@ -765,6 +853,12 @@ class TestOps(unittest.TestCase): def test_selu(self): helper_test_op([(45,65)], torch.nn.functional.selu, Tensor.selu) helper_test_op([()], torch.nn.functional.selu, Tensor.selu) + def test_silu(self): + helper_test_op([(45,65)], torch.nn.functional.silu, Tensor.silu) + helper_test_op([()], torch.nn.functional.silu, Tensor.silu) + def test_swish(self): + helper_test_op([(45,65)], torch.nn.functional.silu, Tensor.swish) + helper_test_op([()], torch.nn.functional.silu, Tensor.swish) def test_abs(self): helper_test_op([(45,65)], torch.abs, Tensor.abs) @@ -798,6 +892,16 @@ class TestOps(unittest.TestCase): def test_sign_exact(self): helper_test_op(None, torch.sign, Tensor.sign, vals=[[-1.,0,1]]) + def test_copysign(self): + helper_test_op([(45,65), (45,65)], torch.copysign, Tensor.copysign) + helper_test_op([(45,65), (45,1)], torch.copysign, Tensor.copysign) + helper_test_op([(45,1), (1,65)], torch.copysign, Tensor.copysign) + helper_test_op([(), ()], torch.copysign, Tensor.copysign) + def test_copysign_exact(self): + for i in [-1.,0.,1.]: + for j in [-1., 0., 1.]: + helper_test_op(None, torch.copysign, Tensor.copysign, vals=[[i], [j]]) + def test_softsign(self): helper_test_op([(45,65)], torch.nn.functional.softsign, Tensor.softsign) helper_test_op([()], torch.nn.functional.softsign, Tensor.softsign) @@ -814,7 +918,6 @@ class TestOps(unittest.TestCase): self.assertAlmostEqual(x.sigmoid()[0].gradient(x)[0].item(), 0.0) x = Tensor([-300.0]) self.assertAlmostEqual(x.sigmoid()[0].gradient(x)[0].item(), 0.0) - @unittest.skip("fix sigmoid stability") def test_sigmoid_alt_extreme(self): def sigmoid(x:Tensor): return x.exp() / (1 + x.exp()) x = Tensor([300.0]) @@ -888,6 +991,26 @@ class TestOps(unittest.TestCase): helper_test_op([(0,3)], lambda x: torch.cumsum(x, dim=0), lambda x: Tensor.cumsum(x, axis=0)) helper_test_op([(2,3,0)], lambda x: torch.cumsum(x, dim=2), lambda x: Tensor.cumsum(x, axis=2)) + def test_small_cumprod(self): + helper_test_op([(10)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + def test_simple_cumprod(self): + helper_test_op([(512)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + helper_test_op([(1022)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + def test_cumprod(self): + helper_test_op([()],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + self.helper_test_exception([()],lambda x: torch.cumprod(x, dim=1),lambda x: Tensor.cumprod(x, axis=1),expected=IndexError) + helper_test_op([(20,)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + self.helper_test_exception([(20,)],lambda x: torch.cumprod(x, dim=1),lambda x: Tensor.cumprod(x, axis=1),expected=IndexError) + self.helper_test_exception([(20,)],lambda x: torch.cumprod(x, dim=-2),lambda x: Tensor.cumprod(x, axis=-2),expected=IndexError) + helper_test_op([(20, 30)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + helper_test_op([(20, 30)],lambda x: torch.cumprod(x, dim=1),lambda x: Tensor.cumprod(x, axis=1)) + helper_test_op([(20, 30, 40)],lambda x: torch.cumprod(x, dim=2),lambda x: Tensor.cumprod(x, axis=2)) + helper_test_op([(20, 30, 40)],lambda x: torch.cumprod(x, dim=-1),lambda x: Tensor.cumprod(x, axis=-1)) + def test_cumprod_zero_axis(self): + helper_test_op([(2, 0, 4)],lambda x: torch.cumprod(x, dim=1),lambda x: Tensor.cumprod(x, axis=1)) + helper_test_op([(0, 3)],lambda x: torch.cumprod(x, dim=0),lambda x: Tensor.cumprod(x, axis=0)) + helper_test_op([(2, 3, 0)],lambda x: torch.cumprod(x, dim=2),lambda x: Tensor.cumprod(x, axis=2)) + def test_small_cummax(self): helper_test_op([(10)], lambda x: torch.cummax(x, dim=0).values, lambda x: Tensor.cummax(x, axis=0)) def test_simple_cummax(self): @@ -913,8 +1036,8 @@ class TestOps(unittest.TestCase): # check if it returns the first index for multiple occurences helper_test_op(None, lambda x: x.argmax().type(torch.int32), lambda x: x.argmax(), forward_only=True, vals=[[2, 2]]) helper_test_op(None, lambda x: x.argmax().type(torch.int32), lambda x: x.argmax(), forward_only=True, vals=[[1, 2, 2]]) - np.testing.assert_equal(Tensor([2,2]).argmax().numpy(), np.array(0)) - np.testing.assert_equal(Tensor([1,2,2]).argmax().numpy(), np.array(1)) + np.testing.assert_equal(Tensor([2,2]).argmax().numpy(), 0) + np.testing.assert_equal(Tensor([1,2,2]).argmax().numpy(), 1) helper_test_op([(10,20)], lambda x: x.argmax().type(torch.int32), lambda x: x.argmax(), forward_only=True) helper_test_op([(10,20)], lambda x: x.argmax(0, False).type(torch.int32), lambda x: x.argmax(0, False), forward_only=True) helper_test_op([(10,20)], lambda x: x.argmax(1, False).type(torch.int32), lambda x: x.argmax(1, False), forward_only=True) @@ -932,8 +1055,8 @@ class TestOps(unittest.TestCase): # check if it returns the first index for multiple occurences helper_test_op(None, lambda x: x.argmin().type(torch.int32), lambda x: x.argmin(), forward_only=True, vals=[[2, 2]]) helper_test_op(None, lambda x: x.argmin().type(torch.int32), lambda x: x.argmin(), forward_only=True, vals=[[3, 2, 2]]) - np.testing.assert_equal(Tensor([2,2]).argmin().numpy(), np.array(0)) - np.testing.assert_equal(Tensor([3,2,2]).argmin().numpy(), np.array(1)) + np.testing.assert_equal(Tensor([2,2]).argmin().numpy(), 0) + np.testing.assert_equal(Tensor([3,2,2]).argmin().numpy(), 1) helper_test_op([(10,20)], lambda x: x.argmin().type(torch.int32), lambda x: x.argmin(), forward_only=True) helper_test_op([(10,20)], lambda x: x.argmin(0, False).type(torch.int32), lambda x: x.argmin(0, False), forward_only=True) helper_test_op([(10,20)], lambda x: x.argmin(1, False).type(torch.int32), lambda x: x.argmin(1, False), forward_only=True) @@ -945,6 +1068,41 @@ class TestOps(unittest.TestCase): helper_test_op(None, lambda x: x.type(torch.int32).argmin().type(torch.int32), lambda x: x.argmin(), forward_only=True, vals=[[False, True]]) helper_test_op(None, lambda x: x.type(torch.int32).argmin().type(torch.int32), lambda x: x.argmin(), forward_only=True, vals=[[True, False]]) + def test_sort(self): + for dim in [-1, 0, 1]: + for descending in [True, False]: + helper_test_op([(8,45,65)], lambda x: x.sort(dim, descending).values, lambda x: x.sort(dim, descending)[0], forward_only=True) + helper_test_op([(8,45,65)], lambda x: x.sort(dim, descending).indices.type(torch.int32), lambda x: x.sort(dim, descending)[1], + forward_only=True) + # repeated values + helper_test_op(None, lambda x: x.sort(stable=True).values, lambda x: x.sort()[0], forward_only=True, vals=[[0, 1] * 9]) + helper_test_op(None, lambda x: x.sort(stable=True).indices.type(torch.int32), lambda x: x.sort()[1], forward_only=True, vals=[[0, 1] * 9]) + helper_test_op(None, lambda x: x.sort(stable=True, descending=True).values, + lambda x: x.sort(descending=True)[0], forward_only=True, vals=[[0, 1] * 9]) + helper_test_op(None, lambda x: x.sort(stable=True, descending=True).indices.type(torch.int32), + lambda x: x.sort(descending=True)[1], forward_only=True, vals=[[0, 1] * 9]) + + def test_topk(self): + helper_test_op([(10)], lambda x: x.topk(3).values, lambda x: x.topk(3)[0], forward_only=True) + helper_test_op([(10)], lambda x: x.topk(3).indices.type(torch.int32), lambda x: x.topk(3)[1], forward_only=True) + for dim in [0, 1, -1]: + for largest in [True, False]: + for sorted_ in [True]: # TODO support False + helper_test_op([(10,20,30)], + lambda x: x.topk(5, dim, largest, sorted_).values, + lambda x: x.topk(5, dim, largest, sorted_)[0], forward_only=True) + helper_test_op([(10,20,30)], + lambda x: x.topk(5, dim, largest, sorted_).indices.type(torch.int32), + lambda x: x.topk(5, dim, largest, sorted_)[1], forward_only=True) + # repeated values + value, indices = Tensor([1, 1, 0, 1, 0, 1, 0, 0, 1, 0, 0, 0, 1, 0]).topk(3) + np.testing.assert_equal(value.numpy(), [1, 1, 1]) + np.testing.assert_equal(indices.numpy(), [0, 1, 3]) + value, indices = Tensor([1, 1, 0, 1, 0, 1, 0, 0, 1, 0, 0, 0, 1, 0]).topk(3, largest=False) + np.testing.assert_equal(value.numpy(), [0, 0, 0]) + np.testing.assert_equal(indices.numpy(), [2, 4, 6]) + self.helper_test_exception([(4)], lambda x: x.topk(5), lambda x: x.topk(5), expected=(RuntimeError, ValueError)) + def test_einsum(self): # matrix transpose helper_test_op([(150,150)], lambda a: torch.einsum('ij->ji', a), lambda a: Tensor.einsum('ij->ji', a)) @@ -1097,8 +1255,7 @@ class TestOps(unittest.TestCase): np.arange(64,128,dtype=np.float32).reshape(8,8)]) def test_small_gemm_eye(self): helper_test_op(None, lambda x,y: x.matmul(y), lambda x,y: x@y, vals=[np.eye(8).astype(np.float32), np.eye(8).astype(np.float32)]) - @unittest.skipIf(CI and Device.DEFAULT in ["NV", "LLVM", "GPU", "CUDA"] or IMAGE \ - or Device.DEFAULT == "WEBGPU", "not supported on these in CI/IMAGE") + @unittest.skipIf(CI and Device.DEFAULT in ["NV", "LLVM", "GPU", "CUDA"] or IMAGE, "not supported on these in CI/IMAGE") def test_gemm_fp16(self): helper_test_op([(64,64), (64,64)], lambda x,y: x.half().matmul(y.half()), atol=5e-3, rtol=5e-3) def test_gemm(self): @@ -1150,11 +1307,11 @@ class TestOps(unittest.TestCase): self.helper_test_exception([()], lambda x: x.sum(1), lambda x: x.sum(1), expected=IndexError) self.helper_test_exception([()], lambda x: x.sum((1,)), lambda x: x.sum((1,)), expected=IndexError) - def test_sum_acc_dtype(self): - helper_test_op([(45,3)], lambda x: x.sum(), lambda x: x.sum(acc_dtype=dtypes.float32)) - if is_dtype_supported(dtypes.float64): helper_test_op([(45,3)], lambda x: x.sum(dtype=torch.float64), lambda x: x.sum(acc_dtype=dtypes.float64)) + def test_sum_dtype_arg(self): + helper_test_op([(45,3)], lambda x: x.sum(), lambda x: x.sum(dtype=dtypes.float32)) + if is_dtype_supported(dtypes.float64): helper_test_op([(45,3)], lambda x: x.sum(dtype=torch.float64), lambda x: x.sum(dtype=dtypes.float64)) - with self.assertRaises(AttributeError): Tensor([1.0, 2.0]).sum(acc_dtype="") + with self.assertRaises(AttributeError): Tensor([1.0, 2.0]).sum(dtype="") def test_sum_with_zeros_shape(self): helper_test_op([(4, 0)], lambda x: x.sum(axis=(0,))) @@ -1171,8 +1328,8 @@ class TestOps(unittest.TestCase): helper_test_op([()], lambda x: x.prod(0)) helper_test_op([()], lambda x: x.prod(-1)) - def test_prod_acc_dtype(self): - with self.assertRaises(AttributeError): Tensor([1.0, 2.0]).prod(acc_dtype="") + def test_prod_dtype_arg(self): + with self.assertRaises(AttributeError): Tensor([1.0, 2.0]).prod(dtype="") def test_min(self): helper_test_op([(3,3)], lambda x: x.min()) @@ -1221,6 +1378,25 @@ class TestOps(unittest.TestCase): def test_all_zero_axis(self): helper_test_op([(1,0,3,0,5)], lambda x: x.all(axis=(1,3)), forward_only=True) + def test_isclose(self): + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x), forward_only=True) + helper_test_op([(3, 4, 5, 6), (3, 4, 5, 6)], lambda x,y: x.isclose(y), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x, equal_nan=True), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-6), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-9), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-6, atol=0.0), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-9, atol=0.0), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-6, rtol=0.01), forward_only=True) + helper_test_op([(3, 4, 5, 6)], lambda x: x.isclose(x + 1e-9, rtol=0.01), forward_only=True) + helper_test_op(None, lambda x,y: x.isclose(y), vals=[[1e-7, 1e-8, 1e-9], [0.0, 0.0, 0.0]], forward_only=True) + + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and CI, "isinf check of 'nan' fails on CI software-based vulkan") + def test_isclose_edge_cases(self): + for a in [math.inf, -math.inf, math.nan, 0.0]: + for b in [math.inf, -math.inf, math.nan, 0.0]: + helper_test_op(None, lambda x,y: x.isclose(y), vals=[[a], [b]], forward_only=True) + helper_test_op(None, lambda x,y: x.isclose(y, equal_nan=True), vals=[[a], [b]], forward_only=True) + def test_mean(self): helper_test_op([(3,4,5,6)], lambda x: x.mean()) helper_test_op([()], lambda x: x.mean()) @@ -1243,17 +1419,22 @@ class TestOps(unittest.TestCase): helper_test_op([(15, 25, 35)], lambda x: x.var(2, correction=0)) helper_test_op([(15, 25, 35)], lambda x: x.var([1, 2], correction=0)) def test_var_zero_in_axis(self): - helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3))) - helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3), correction=0)) - helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3), correction=5)) - # TODO: fix backward when correction >= n + with warnings.catch_warnings(): + warnings.filterwarnings("ignore", message="var\\(\\): degrees of freedom is <= 0") + helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3))) + helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3), correction=0)) + helper_test_op([(1,0,3,0,5)], lambda x: x.var(axis=(1,3), correction=5)) def test_var_one_in_axis(self): - helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,3)), forward_only=True) + with warnings.catch_warnings(): + warnings.filterwarnings("ignore", message="var\\(\\): degrees of freedom is <= 0") + helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,3))) + # TODO: fix backward + helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,3), correction=5), forward_only=True) + helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,4), correction=5), forward_only=True) + helper_test_op([(1,)], lambda x: x.var(axis=(0,), correction=0)) helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,3), correction=0)) - helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,3), correction=5), forward_only=True) helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,4))) helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,4), correction=0)) - helper_test_op([(1,2,3,1,5)], lambda x: x.var(axis=(0,4), correction=5), forward_only=True) def test_var_keepdim(self): helper_test_op([(15, 25, 35)], lambda x: x.var(keepdim=True)) helper_test_op([(15, 25, 35)], lambda x: x.var(0, keepdim=True, correction=0)) @@ -1270,18 +1451,22 @@ class TestOps(unittest.TestCase): helper_test_op([(15, 25, 35)], lambda x: x.std(2, correction=0)) helper_test_op([(15, 25, 35)], lambda x: x.std([1, 2], correction=0)) def test_std_zero_in_axis(self): - helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3))) - helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3), correction=0)) - helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3), correction=5)) - # TODO: fix backward when correction >= n + with warnings.catch_warnings(): + warnings.filterwarnings("ignore", message="std\\(\\): degrees of freedom is <= 0") + helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3))) + helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3), correction=0)) + helper_test_op([(1,0,3,0,5)], lambda x: x.std(axis=(1,3), correction=5)) def test_std_one_in_axis(self): - helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,3)), forward_only=True) - # TODO: this one broke too with correction=0 in new gradient + with warnings.catch_warnings(): + warnings.filterwarnings("ignore", message="std\\(\\): degrees of freedom is <= 0") + helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,3))) + helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,3), correction=5)) + helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,4), correction=5)) + # TODO: fix backward + helper_test_op([(1,)], lambda x: x.std(axis=(0,), correction=0), forward_only=True) helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,3), correction=0), forward_only=True) - helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,3), correction=5), forward_only=True) helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,4))) helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,4), correction=0)) - helper_test_op([(1,2,3,1,5)], lambda x: x.std(axis=(0,4), correction=5)) def test_std_keepdim(self): helper_test_op([(15, 25, 35)], lambda x: x.std(keepdim=True)) helper_test_op([(15, 25, 35)], lambda x: x.std(0, keepdim=True, correction=0)) @@ -1305,9 +1490,9 @@ class TestOps(unittest.TestCase): helper_test_op([()], torch.nn.Softmax(dim=0), Tensor.softmax, atol=1e-7, grad_atol=1e-7) helper_test_op([()], torch.nn.Softmax(dim=-1), Tensor.softmax, atol=1e-7, grad_atol=1e-7) def test_softmax_other_axis(self): - helper_test_op([(10,10,10)], lambda x: x.softmax(0), atol=1e-7, grad_atol=1e-7) - helper_test_op([(10,10,10)], lambda x: x.softmax(1), atol=1e-7, grad_atol=1e-7) - helper_test_op([(10,10,10)], lambda x: x.softmax(2), atol=1e-7, grad_atol=1e-7) + helper_test_op([(10,10,10)], lambda x: x.softmax(0), atol=1e-7, grad_atol=2e-7) + helper_test_op([(10,10,10)], lambda x: x.softmax(1), atol=1e-7, grad_atol=2e-7) + helper_test_op([(10,10,10)], lambda x: x.softmax(2), atol=1e-7, grad_atol=2e-7) def test_softmax_argmax(self): helper_test_op([(45,65)], lambda x: x.softmax(0).argmax().type(torch.int32), lambda x: x.softmax(0).argmax(), forward_only=True, atol=1e-7, grad_atol=1e-7) @@ -1339,7 +1524,7 @@ class TestOps(unittest.TestCase): helper_test_op([()], lambda x: torch.logcumsumexp(x, dim=0), lambda x: x.logcumsumexp(), atol=1e-7, grad_atol=1e-7) helper_test_op([()], lambda x: torch.logcumsumexp(x, dim=-1), lambda x: x.logcumsumexp(-1), atol=1e-7, grad_atol=1e-7) - @unittest.expectedFailure # TODO: fix numerical instability + @unittest.skipIf(not DEVECTORIZE, "broken without DEVECTORIZE. TODO: fix this") def test_logcumsumexp_numerical(self): helper_test_op(None, lambda x: torch.logcumsumexp(x, dim=0), lambda x: x.logcumsumexp(), atol=1e-7, grad_atol=1e-7, vals=[[0.0, 100.0]]) @@ -1364,12 +1549,12 @@ class TestOps(unittest.TestCase): helper_test_op([()], lambda x: torch.nn.functional.hardtanh(x, -val, val), lambda x: x.hardtanh(-val, val), grad_atol=1e-6) def test_asinh(self): helper_test_op([(45,65)], lambda x: x.asinh(), grad_atol=1e-6) - # NOTE: this one has larger atol - helper_test_op([(45,65)], lambda x: x.asinh(), atol=1e-2, grad_atol=1e-6, low=-300, high=-297) + # TODO: this one has larger tol? + helper_test_op([(45,65)], lambda x: x.asinh(), atol=1e-2, rtol=2e-2, grad_rtol=2e-2, low=-300, high=-297) helper_test_op([(45,65)], lambda x: x.asinh(), grad_atol=1e-6, low=300, high=303) def test_acosh(self): helper_test_op([(45,65)], lambda x: x.acosh(), grad_atol=1e-6) - helper_test_op([(45,65)], lambda x: x.acosh(), grad_atol=1e-6, low=-300, high=-297) + helper_test_op([(45,65)], lambda x: x.acosh(), grad_atol=1e-3, grad_rtol=1e-2, low=-300, high=-297) helper_test_op([(45,65)], lambda x: x.acosh(), grad_atol=1e-6, low=300, high=303) def test_atanh(self): helper_test_op([(45,65)], lambda x: x.atanh(), grad_atol=1e-6) @@ -1650,6 +1835,10 @@ class TestOps(unittest.TestCase): x = Tensor.ones((4,3,6,6)) x.reshape([]) + def test_view(self): + helper_test_op([(4,3,6,6)], lambda x: x.view((12,6,6))) + helper_test_op([(4,3,6,6)], lambda x: x.view((-1,3,6,6))) + def test_flip(self): helper_test_op([(4,3,6,6)], lambda x: x.flip((0,))) helper_test_op([(4,3,6,6)], lambda x: x.flip((0,1))) @@ -1839,6 +2028,8 @@ class TestOps(unittest.TestCase): 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(), grad_rtol=1e-5) + self.helper_test_exception([(2,16,2,2), (32,16,3,3)], lambda x,w: torch.nn.functional.conv_transpose2d(x,w,padding=(1,1,1)), + lambda x,w: Tensor.conv_transpose2d(x,w,padding=(1,1,1)), expected=(RuntimeError, ValueError)) def test_dilated_conv_transpose2d(self): for dilation in [(1,2), (2,1), 2, 1]: @@ -1902,9 +2093,6 @@ class TestOps(unittest.TestCase): 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()) - 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()) def _test_conv2d(self, bs=1, cin=1, cout=6): for H in [1,2,3]: @@ -1927,6 +2115,8 @@ class TestOps(unittest.TestCase): # regression test for https://github.com/tinygrad/tinygrad/pull/7549/ self.helper_test_exception([(2,16,2,2), (32,16,3,3)], lambda x,w:torch.nn.functional.conv2d(x,w), lambda x,w: Tensor.conv2d(x,w), expected=(RuntimeError, AssertionError)) + self.helper_test_exception([(2,16,2,2), (32,16,3,3)], lambda x,w:torch.nn.functional.conv2d(x,w,padding=(1,1,1)), + lambda x,w: Tensor.conv2d(x,w,padding=(1,1,1)), expected=(RuntimeError, ValueError)) def test_large_input_conv2d(self): bs = 4 @@ -1937,7 +2127,7 @@ class TestOps(unittest.TestCase): 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-4, grad_rtol=1e-5) + lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_atol=1e-4, grad_rtol=1e-4) def test_simple_grouped_conv2d(self): bs = 1 @@ -1991,6 +2181,10 @@ class TestOps(unittest.TestCase): lambda x,w: torch.nn.functional.conv2d(x,w,stride=2).relu(), lambda x,w: Tensor.conv2d(x,w,stride=2).relu()) + @unittest.skipIf(Device.DEFAULT != "LLVM", "DEVECTORIZE=0 only for LLVM") + def test_strided_conv2d_simple_vec(self): + with Context(DEVECTORIZE=0): self.test_strided_conv2d_simple() + def test_strided_conv2d(self): bs = 4 cin = 3 @@ -2085,10 +2279,21 @@ class TestOps(unittest.TestCase): def test_max_pool2d_padding(self): for ksz in [(2,2), (3,3), 2, 3, (3,2)]: - with self.subTest(kernel_size=ksz): - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=ksz, padding=1), - lambda x: Tensor.max_pool2d(x, kernel_size=ksz, padding=1)) + for p in [1, (1,0), (0,1)]: + with self.subTest(kernel_size=ksz, padding=p): + helper_test_op([(32,2,110,28)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=ksz, padding=p), + lambda x: Tensor.max_pool2d(x, kernel_size=ksz, padding=p)) + self.helper_test_exception([(32,2,110,28)], lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(2,2), padding=(1,1,1)), + lambda x: Tensor.max_pool2d(x, kernel_size=(2,2), padding=(1,1,1)), expected=(RuntimeError, ValueError)) + + def test_max_pool2d_asymmetric_padding(self): + shape = (32,2,111,28) + for p in [(0,1,0,1), (2,1,2,1), (2,0,2,1)]: + with self.subTest(padding=p): + helper_test_op([shape], + lambda x: torch.nn.functional.max_pool2d(torch.nn.functional.pad(x, p, value=float("-inf")), kernel_size=(5,5)), + lambda x: Tensor.max_pool2d(x, kernel_size=(5,5), padding=p)) def test_max_pool2d_padding_int(self): ksz = (2,2) @@ -2143,6 +2348,56 @@ class TestOps(unittest.TestCase): lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(3,3), stride=3, padding=1, ceil_mode=True), lambda x: Tensor.max_pool2d(x, kernel_size=(3,3), stride=3, padding=1, ceil_mode=True)) + def test_max_pool2d_return_indices(self): + # batch and multi-channel + helper_test_op([(2,3,6,6)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(2,2), return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(2,2), return_indices=True)[1], forward_only=True) + # dilation + helper_test_op([(1,1,10,10)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(3,2), dilation=(2,3), return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(3,2), dilation=(2,3), return_indices=True)[1], forward_only=True) + # padding + helper_test_op([(1,1,5,5)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(3,3), padding=1, return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(3,3), padding=1, return_indices=True)[1], forward_only=True) + # ceil mode padding + helper_test_op([(1, 1, 7, 7)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(2, 2), stride=(2, 2), ceil_mode=True, return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(2, 2), stride=(2, 2), ceil_mode=True, return_indices=True)[1], + forward_only=True) + # global maxpool + helper_test_op([(1,1,12,13)], + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(12, 13), return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(12, 13), return_indices=True)[1], + forward_only=True) + # multiple identical values in same window and overlapping windows + helper_test_op(None, + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(3,3), stride=1, return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(3,3), stride=1, return_indices=True)[1], + vals=[[[[[1]*6]*6]]], forward_only=True) # Tensor.ones(1,1,6,6) + # overlapping max indices + helper_test_op(None, + lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(2,2), stride=1, return_indices=True)[1].type(torch.int32), + lambda x: Tensor.max_pool2d(x, kernel_size=(2,2), stride=1, return_indices=True)[1], + vals=[[[[[1,2]*3]*6]]], forward_only=True) # Tensor([1,2,1,2,1,2]).expand(1,1,6,6) + + def test_max_unpool2d(self): + args = {"kernel_size":(5,5), "stride":(6,5)} + helper_test_op([(8,3,50,50)], + lambda x: torch.nn.functional.max_unpool2d(*torch.nn.functional.max_pool2d(x, return_indices=True, **args), **args), + lambda x: Tensor.max_unpool2d(*Tensor.max_pool2d(x, return_indices=True, **args), **args), forward_only=True) + args = {"kernel_size":(3,3), "stride":(6,7), "padding":1} + helper_test_op([(8,3,30,30)], + lambda x: torch.nn.functional.max_unpool2d(*torch.nn.functional.max_pool2d(x, return_indices=True, **args), **args, output_size=(30,30)), + lambda x: Tensor.max_unpool2d(*Tensor.max_pool2d(x, return_indices=True, **args), **args, output_size=(30,30)), forward_only=True) + # batch_size and channel_size of output_size are ignored + helper_test_op([(1,3,7,6)], + lambda x: torch.nn.functional.max_unpool2d(*torch.nn.functional.max_pool2d(x, kernel_size=(2,2), return_indices=True), + kernel_size=(2,2), output_size=(99,99,7,6)), + lambda x: Tensor.max_unpool2d(*Tensor.max_pool2d(x, kernel_size=(2,2), return_indices=True), + kernel_size=(2,2), output_size=(99,99,7,6)), forward_only=True) + def test_avg_pool2d(self): shape = (32,2,111,28) for ksz in [(2,2), (3,3), (3,2), (5,5), (5,1)]: @@ -2159,10 +2414,23 @@ class TestOps(unittest.TestCase): def test_avg_pool2d_padding(self): shape = (32,2,111,28) for ksz in [(2,2), (3,3), 2, 3, (3,2)]: - with self.subTest(kernel_size=ksz): + for p in [1, (1,0), (0,1)]: + with self.subTest(kernel_size=ksz, padding=p): + helper_test_op([shape], + lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=ksz, padding=p), + lambda x: Tensor.avg_pool2d(x, kernel_size=ksz, padding=p), rtol=1e-5) + with self.assertRaises(ValueError): + Tensor.avg_pool2d(Tensor.randn((32,2,111,28)), kernel_size=(2,2), padding=(1,1,1)) + + def test_avg_pool2d_asymmetric_padding(self): + shape = (32,2,111,28) + for p in [(0,1,0,1), (2,1,2,1), (2,0,2,1)]: + with self.subTest(padding=p): helper_test_op([shape], - lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=ksz, padding=1), - lambda x: Tensor.avg_pool2d(x, kernel_size=ksz, padding=1), rtol=1e-5) + lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=(5,5), padding=1), + lambda x: Tensor.avg_pool2d(x, kernel_size=(5,5), padding=1), rtol=1e-5) + self.helper_test_exception([shape], lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=(2,2), padding=(1,1,1)), + lambda x: Tensor.avg_pool2d(x, kernel_size=(2,2), padding=(1,1,1)), expected=(RuntimeError, ValueError)) def test_avg_pool2d_padding_not_counted(self): shape = (32,2,111,28) @@ -2173,6 +2441,14 @@ class TestOps(unittest.TestCase): lambda x: Tensor.avg_pool2d(x, kernel_size=ksz, padding=1, count_include_pad=False), rtol=1e-5) def test_avg_pool2d_ceil_mode(self): + shape = (1,1,6,6) + for ksz in [(3,3), 3, (3,2), 4]: + with self.subTest(kernel_size=ksz): + helper_test_op([shape], + lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=ksz, padding=1, stride=3, ceil_mode=True), + lambda x: Tensor.avg_pool2d(x, kernel_size=ksz, padding=1, stride=3, ceil_mode=True), rtol=1e-5) + + def test_avg_pool2d_ceil_mode_padding_not_counted(self): shape = (1,1,6,6) for ksz in [(3,3), 3, (3,2), 4]: with self.subTest(kernel_size=ksz): @@ -2186,14 +2462,6 @@ class TestOps(unittest.TestCase): lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=(3,3), stride=3, padding=1, ceil_mode=True), lambda x: Tensor.avg_pool2d(x, kernel_size=(3,3), stride=3, padding=1, ceil_mode=True)) - def test_avg_pool2d_ceil_mode_include_pad(self): - shape = (1,1,6,6) - for ksz in [(3,3), 3, (3,2), 4]: - with self.subTest(kernel_size=ksz): - helper_test_op([shape], - lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=ksz, padding=1, stride=3, ceil_mode=True, count_include_pad=True), - lambda x: Tensor.avg_pool2d(x, kernel_size=ksz, padding=1, stride=3, ceil_mode=True, count_include_pad=True), rtol=1e-5) - def test_avg_pool2d_ceil_mode_include_pad_output_size_reduce_by_one(self): # sliding window ignored from end region helper_test_op([(1,1,5,5)], @@ -2205,8 +2473,6 @@ class TestOps(unittest.TestCase): 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) - # TODO: linearizer block error - @unittest.expectedFailure def test_avg_pool3d_failure(self): with Context(NOOPT=0): helper_test_op([(1,1,16,16,16)], @@ -2359,9 +2625,10 @@ class TestOps(unittest.TestCase): 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), requires_grad=False) for tor in [a,b,c,d,e]] + i, j, k, o, p = [Tensor(tor.detach().cpu().numpy().astype(np.int32), requires_grad=False) for tor in [a,b,c,d,e]] return a,b,c,d,e,i,j,k,o,p + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "WEBGPU can only run kernels with up to 10 buffers") 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 @@ -2413,6 +2680,7 @@ class TestOps(unittest.TestCase): helper_test_op([(2,3)], lambda x: x[torch.tensor([[0,1,-1],[-1,-2,0]]), torch.tensor([2,1,-1])], lambda x: x[Tensor([[0,1,-1],[-1,-2,0]]), Tensor([2,1,-1])]) + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "WEBGPU can only run kernels with up to 10 buffers") def test_slice_fancy_indexing_list_indices(self): a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() helper_test_op([(2,5,6,5,3,4)], lambda x: x[[[0]]], lambda x: x[[[0]]]) @@ -2432,6 +2700,7 @@ class TestOps(unittest.TestCase): helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,((2,),(1,),(0,)),c,(2,1,0)], lambda x: x[i,((2,),(1,),(0,)),k,(2,1,0)]) helper_test_op([(2,5,6,5,3,4)], lambda x: x[1,(2,1,0),None,c,(2,1,0),e], lambda x: x[1,(2,1,0),None,k,(2,1,0),p]) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") def test_slice_fancy_indexing_list_with_tensors(self): a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() helper_test_op([(2,5,6,5,3,4)], lambda x: x[[a]], lambda x: x[[i]]) @@ -2453,7 +2722,7 @@ class TestOps(unittest.TestCase): # 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) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) helper_test_op([(4,5,6)], lambda x: x.gather(dim=0, index=b), lambda x: x.gather(dim=0, index=a)) helper_test_op([(4,5,6)], lambda x: x.gather(dim=1, index=b), lambda x: x.gather(dim=1, index=a)) helper_test_op([(4,5,6)], lambda x: x.gather(dim=2, index=b), lambda x: x.gather(dim=2, index=a)) @@ -2469,9 +2738,17 @@ class TestOps(unittest.TestCase): lambda x: x.gather(dim=0, index=Tensor([2, 1, 0, 1, 2])), vals=[[1., 2., 3.]]) + @unittest.expectedFailure + @unittest.skipIf(torch._C._get_privateuse1_backend_name() == "tiny", 'results in a success instead of a failure') + def test_gather_failure(self): + # gather with inf values do not work, other values results in nan + helper_test_op(None, lambda x: x.gather(dim=0, index=torch.tensor([2, 1, 0, 1, 2], requires_grad=False)), + lambda x: x.gather(dim=0, index=Tensor([2, 1, 0, 1, 2])), + vals=[[-float("inf"), 2., 3.]]) + def test_scatter(self): 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) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) for dim in (0,1,2,-1,-2,-3): helper_test_op([(4,5,6), (4,5,6)], lambda x,src: x.scatter(dim=dim, index=b, src=src), lambda x,src: x.scatter(dim=dim, index=a, src=src), forward_only=True) @@ -2480,19 +2757,23 @@ class TestOps(unittest.TestCase): lambda x,src: x.scatter(dim=1, index=a, src=src), forward_only=True) helper_test_op([(10,3,10), (10,10,10)], lambda x,src: x.scatter(dim=1, index=b, src=src), lambda x,src: x.scatter(dim=1, index=a, src=src), forward_only=True) + self.helper_test_exception([(2,3,10), (10,10,10)], lambda x,src: x.scatter(dim=1, index=b, src=src), lambda x,src: x.scatter(dim=1, index=a, src=src), expected=(RuntimeError, AssertionError)) self.helper_test_exception([(10,3,10), (10,3,10)], lambda x,src: x.scatter(dim=1, index=b, src=src), lambda x,src: x.scatter(dim=1, index=a, src=src), expected=(RuntimeError, AssertionError)) self.helper_test_exception([(3,4,5), (3,4,5)], lambda x,src: x.scatter(dim=1, index=b, src=src, mode="typo"), - lambda x,src: x.scatter(dim=1, index=a, src=src, mode="typo"), expected=TypeError) + lambda x,src: x.scatter(dim=1, index=a, src=src, mode="typo"), expected=TypeError) + self.helper_test_exception([(3,4,5), (3,4,5)], lambda x,src: x.half().scatter(dim=1, index=b, src=src), + lambda x,src: x.half().scatter(dim=1, index=a, src=src), expected=RuntimeError) + helper_test_op([(4,5,6)], lambda x: x.scatter(dim=1, index=b, value=3), lambda x: x.scatter(dim=1, index=a, src=3), forward_only=True) helper_test_op([(4,5,6)], lambda x: x.scatter(dim=1, index=b, value=float("inf")), lambda x: x.scatter(dim=1, index=a, src=float("inf")), forward_only=True) # overlapping indices with 0s b = torch.tensor([0,0], requires_grad=False) - a = Tensor(b.detach().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) helper_test_op(None, lambda x,src: x.scatter(0, b, src), lambda x,src: x.scatter(0, a, src), forward_only=True, @@ -2500,13 +2781,7 @@ class TestOps(unittest.TestCase): def test_scatter_add(self): 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) - for dim in (0,1,2,-1,-2,-3): - helper_test_op([(4,5,6), (4,5,6)], lambda x,src: x.scatter(dim=dim, index=b, src=src, reduce="add"), - lambda x,src: x.scatter(dim=dim, index=a, src=src, reduce="add"), forward_only=True) - - 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) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) helper_test_op([(4,5,6)], lambda x: x.scatter(dim=1, index=b, value=float("inf"), reduce="add"), lambda x: x.scatter(dim=1, index=a, src=float("inf"), reduce="add"), forward_only=True) @@ -2514,15 +2789,11 @@ class TestOps(unittest.TestCase): if Device.DEFAULT != "WEBGPU": helper_test_op([(4,5,6)], lambda x: x.scatter(1, b, float("nan"), reduce="add"), - lambda x: x.scatter(1, a, float("nan"), reduce="add"), forward_only=True,) + lambda x: x.scatter(1, a, float("nan"), reduce="add"), forward_only=True) def test_scatter_mul(self): 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) - for dim in (0,1,2,-1,-2,-3): - helper_test_op([(4,5,6), (4,5,6)], lambda x,src: x.scatter(dim=dim, index=b, src=src, reduce="multiply"), - lambda x,src: x.scatter(dim=dim, index=a, src=src, reduce="multiply"), forward_only=True) - + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) helper_test_op([(4,5,6)], lambda x: x.scatter(dim=1, index=b, value=float("inf"), reduce="multiply"), lambda x: x.scatter(dim=1, index=a, src=float("inf"), reduce="multiply"), forward_only=True) @@ -2530,27 +2801,66 @@ class TestOps(unittest.TestCase): if Device.DEFAULT != "WEBGPU": helper_test_op([(4,5,6)], lambda x: x.scatter(1, b, float("nan"), reduce="multiply"), - lambda x: x.scatter(1, a, float("nan"), reduce="multiply"), forward_only=True,) + lambda x: x.scatter(1, a, float("nan"), reduce="multiply"), forward_only=True) + + def test_scatter_no_reduce_tensor_src(self): + with self.assertRaises(TypeError): + Tensor.ones(4).scatter(dim=1, index=Tensor([0]), src=Tensor.ones(4), reduce="add") + def test_scatter_reduce(self): + b = torch.randint(3, size=[3,4,5], dtype=torch.int64, requires_grad=False) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) + for reduce in ("sum", "prod", "mean", "amin", "amax"): + for dim in (0,1,2,-1,-2,-3): + helper_test_op([(4,5,6), (4,5,6)], + lambda x,src: x.scatter_reduce(dim=dim, index=b, src=src, reduce=reduce), + lambda x,src: x.scatter_reduce(dim=dim, index=a, src=src, reduce=reduce), forward_only=True) + helper_test_op([(4,5,6), (4,5,6)], + lambda x,src: x.scatter_reduce(dim=dim, index=b, src=src, reduce=reduce, include_self=False), + lambda x,src: x.scatter_reduce(dim=dim, index=a, src=src, reduce=reduce, include_self=False), forward_only=True) + + def test_scatter_reduce_prod_zeros(self): + b = torch.randint(3, size=[3,4,5], dtype=torch.int64, requires_grad=False) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) x = Tensor.zeros([4,5,6]).float() y = torch.zeros([4,5,6]).float() - helper_test_op([(4,5,6)], lambda src: y.scatter(dim=1, index=b, src=src, reduce="multiply"), - lambda src: x.scatter(dim=1, index=a, src=src, reduce="multiply"), forward_only=True) + helper_test_op([(4,5,6)], + lambda src: y.scatter_reduce(dim=1, index=b, src=src, reduce="prod"), + lambda src: x.scatter_reduce(dim=1, index=a, src=src, reduce="prod"), forward_only=True) - def test_scaled_product_attention(self): + def test_scatter_reduce_errors(self): + b = torch.randint(3, size=[3,4,5], dtype=torch.int64, requires_grad=False) + a = Tensor(b.detach().cpu().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) + # invalid reduce arg + self.helper_test_exception([(4,5,6), (4,5,6)], + lambda x,src: x.scatter_reduce(dim=0, index=b, src=src, reduce="INVALID"), + lambda x,src: x.scatter_reduce(dim=0, index=a, src=src, reduce="INVALID"), + RuntimeError) + # dtype mismatch + self.helper_test_exception([(4,5,6), (4,5,6)], + lambda x,src: x.half().scatter_reduce(dim=0, index=b, src=src, reduce="sum"), + lambda x,src: x.half().scatter_reduce(dim=0, index=a, src=src, reduce="sum"), + RuntimeError) + + def test_scaled_dot_product_attention(self): helper_test_op([(32,8,16,64), (32,8,16,64), (32,8,16,64)], torch.nn.functional.scaled_dot_product_attention, Tensor.scaled_dot_product_attention) 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)) - def test_scaled_product_attention_mismatch_ls(self): + def test_scaled_dot_product_attention_mismatch_ls(self): helper_test_op([(32,8,4,64), (32,8,16,64), (32,8,16,64)], torch.nn.functional.scaled_dot_product_attention, Tensor.scaled_dot_product_attention) - def test_scaled_product_attention_causal(self): + def test_scaled_dot_product_attention_causal(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,is_causal=True), lambda x,y,z: Tensor.scaled_dot_product_attention(x,y,z,is_causal=True)) + self.helper_test_exception([(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,is_causal=True,attn_mask=m), + lambda x,y,z,m: Tensor.scaled_dot_product_attention(x,y,z,is_causal=True,attn_mask=m), + expected=RuntimeError) + 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))) @@ -2642,6 +2952,10 @@ class TestOps(unittest.TestCase): helper_test_op([(32,10)], lambda x: x.masked_fill((x>0.1).detach(), -math.inf)) helper_test_op([(32,10)], lambda x: x.masked_fill((x<0.1).detach(), -math.inf)) + def test_masked_select(self): + helper_test_op([(32, 10)], lambda x: x.masked_select(x>0.5), lambda x: x.masked_select(x>0.5), forward_only=True) + helper_test_op([(32, 10)], lambda x: x.masked_select(torch.tensor(True)), lambda x: x.masked_select(Tensor(True)), forward_only=True) + @unittest.skipIf(Device.DEFAULT == "QCOM", "OpenCL fails to compile this (both on GPU(qcom)/QCOM backends)") def test_cast(self): helper_test_op([(3, 3)], lambda x: x.float()) @@ -2687,6 +3001,14 @@ class TestOpsUint8(unittest.TestCase): lambda x: x.type(torch.uint8).min(), lambda x: x.cast(dtypes.uint8).min(), forward_only=True, vals=[[0, 128, 255, 64, 32, 16]]) +@unittest.skipUnless(is_dtype_supported(dtypes.bfloat16), f"no bfloat16 on {Device.DEFAULT}") +class TestOpsBFloat16(unittest.TestCase): + def test_cast(self): + # TODO: helper_test_op breaks in unrelated part + # TODO: wrong output with GPU=1 / PYTHON=1 on mac + data = [60000.0, 70000.0, 80000.0] + np.testing.assert_allclose(Tensor(data).cast("bfloat16").numpy(), torch.tensor(data).type(torch.bfloat16).float().numpy()) + if __name__ == '__main__': np.random.seed(1337) unittest.main(verbosity=2) diff --git a/tinygrad_repo/test/test_opt_gemm.py b/tinygrad_repo/test/test_opt_gemm.py new file mode 100644 index 0000000000..862d977895 --- /dev/null +++ b/tinygrad_repo/test/test_opt_gemm.py @@ -0,0 +1,45 @@ +import numpy as np +import unittest +from tinygrad import Tensor +from tinygrad.helpers import get_single_element +from tinygrad.codegen.kernel import Kernel, Opt, OptOps +from tinygrad.engine.realize import CompiledRunner, ExecItem + +class TestOptGemm(unittest.TestCase): + @classmethod + def setUpClass(cls): + N = 64 + cls.a = Tensor.randn(N, N).contiguous().realize() + cls.b = Tensor.randn(N, N).contiguous().realize() + cls.res = cls.a.T.numpy() @ cls.b.T.numpy() + + def _test_gemm_unrolled_permute_l(self, opts=[]): + t = self.a.T @ self.b.T + # TODO: this should be a generic test helper + si = get_single_element(t.schedule()) + k = Kernel(si.ast) + k.apply_opts(opts) + run = CompiledRunner(k.to_program()) + ExecItem(run, si.bufs).run() + test = si.bufs[0].numpy().reshape(self.res.shape) + np.testing.assert_allclose(self.res, test, atol=1e-4) + + def test_gemm_unrolled_permute_l_44(self): + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=4)] + self._test_gemm_unrolled_permute_l(opts) + + def test_gemm_unrolled_permute_l_424(self): + # was failing with LLVM + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=2), Opt(op=OptOps.UPCAST, axis=0, arg=4)] + self._test_gemm_unrolled_permute_l(opts) + + def test_gemm_unrolled_permute_l_42(self): + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UPCAST, axis=1, arg=2)] + self._test_gemm_unrolled_permute_l(opts) + + def test_gemm_unrolled_permute_l_22(self): + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=2), Opt(op=OptOps.UPCAST, axis=1, arg=2)] + self._test_gemm_unrolled_permute_l(opts) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_optim.py b/tinygrad_repo/test/test_optim.py index 876954a6b6..283378e70a 100644 --- a/tinygrad_repo/test/test_optim.py +++ b/tinygrad_repo/test/test_optim.py @@ -127,7 +127,7 @@ class TestOptim(unittest.TestCase): old_state = Tensor.training t.sum().backward() Tensor.training = False - self.assertRaises(AssertionError, optimizer.step) + self.assertRaises(RuntimeError, optimizer.step) Tensor.training = True optimizer.step() Tensor.training = old_state diff --git a/tinygrad_repo/test/test_pickle.py b/tinygrad_repo/test/test_pickle.py index 0880959373..e9d88e1817 100644 --- a/tinygrad_repo/test/test_pickle.py +++ b/tinygrad_repo/test/test_pickle.py @@ -1,9 +1,8 @@ import unittest, pickle, types import numpy as np from tinygrad import Tensor, TinyJit, Variable, dtypes -from tinygrad.engine.schedule import create_schedule -from tinygrad.helpers import GlobalCounters -from tinygrad.ops import PatternMatcher, UPat, UOp +from tinygrad.helpers import GlobalCounters, ContextVar, Context +from tinygrad.uop.ops import PatternMatcher, UPat, UOp, Ops class TestPickle(unittest.TestCase): def test_pickle_code_object(self): @@ -21,8 +20,10 @@ class TestPickle(unittest.TestCase): self.assertEqual(pm2.rewrite(sink).key, tt.key) def test_pickle_main_pattern_matcher(self): - from tinygrad.codegen.uopgraph import sym - pickle.dumps(sym) + from tinygrad.codegen.devectorizer import sym + ssym = pickle.dumps(sym) + dsym = pickle.loads(ssym) + self.assertEqual(dsym.patterns[0][0].location, sym.patterns[0][0].location) def test_pickle_realized_tensor(self): print("** init") @@ -39,7 +40,7 @@ class TestPickle(unittest.TestCase): def test_pickle_realized_tensor_alt(self): print("** init") - t = Tensor.rand(10, 10).to("CLANG").realize() + t = Tensor.rand(10, 10).to("CPU").realize() st = pickle.dumps(t) t_values = t.numpy() del t # free buffers @@ -49,6 +50,35 @@ class TestPickle(unittest.TestCase): np.testing.assert_equal(t_values, t2.numpy()) self.assertEqual(GlobalCounters.kernel_count-init, 0) + def test_pickle_realized_tensor_alt2(self): + print("** init") + t = Tensor.rand(10, 10).to("CPU").realize() + tensor_uop = t.lazydata + assert tensor_uop.is_realized, f"expected {tensor_uop} to be realized" + t_values = t.numpy() + # pickle + st = pickle.dumps(t) + # free buffers + del t + del tensor_uop + print("** post pickle") + t2:Tensor = pickle.loads(st) + assert t2.lazydata.is_realized, f"expected {t2.lazydata} to be realized" + np.testing.assert_equal(t_values, t2.numpy()) + + # NOTE: currently Buffer exists on the uop, not tensor + def test_pickle_buffer_uop(self): + t = Tensor.arange(4).realize() + a = t.lazydata + assert a.op is Ops.BUFFER + self.assertIsNotNone(buffer:=a.realized) + s = pickle.dumps(a) + # free buffers + del a + del buffer + a2:UOp = pickle.loads(s) + self.assertListEqual(a2.realized.as_buffer().cast("I").tolist(), [0, 1, 2, 3]) + def test_pickle_unrealized_tensor(self): t = Tensor.ones(10, 10) st = pickle.dumps(t) @@ -66,7 +96,7 @@ class TestPickle(unittest.TestCase): np.testing.assert_equal(vt2.numpy(), 20) def test_pickle_buffer_view(self): - t = Tensor.arange(10, device="CLANG").contiguous().realize() + t = Tensor.arange(10, device="CPU").contiguous().realize() vt = t[3:5].contiguous().realize() assert hasattr(vt.lazydata.buffer, 'base') ref_value = vt.tolist() @@ -77,7 +107,7 @@ class TestPickle(unittest.TestCase): assert ref_value == vt2.tolist() def test_pickle_numpy(self): - t = Tensor(np.array([1,2,3,4.])) + t = Tensor(np.array([1,2,3,4.]), dtype=dtypes.float32) st = pickle.dumps(t) t2:Tensor = pickle.loads(st) np.testing.assert_equal(t.numpy(), t2.numpy()) @@ -96,10 +126,17 @@ class TestPickle(unittest.TestCase): out = add_fxn(x, y) np.testing.assert_equal(out.numpy(), 102) + def test_pickle_context_var(self): + v = ContextVar("test_var", 0) + with Context(test_var=1): + vs = pickle.dumps(v) + v2 = pickle.loads(vs) + self.assertEqual(v2.value, 1) + def test_pickle_schedule(self): a = Tensor([1,2]) out = a + 2 - sched = create_schedule([out.lazydata]) + sched = out.schedule() pk = pickle.dumps(sched) sched_pk = pickle.loads(pk) self.assertEqual(sched_pk[-1].ast, sched[-1].ast) @@ -112,9 +149,10 @@ class TestPickle(unittest.TestCase): class TestPickleJIT(unittest.TestCase): @classmethod def setUpClass(cls): + N = 10 @TinyJit def add(a, b): return a.sum()+b+1 - for _ in range(3): add(Tensor.rand(1000, 1000), Tensor.rand(1000, 1000)) + for _ in range(3): add(Tensor.rand(N, N), Tensor.rand(N, N)) cls.st = pickle.dumps(add) del add diff --git a/tinygrad_repo/test/test_profiler.py b/tinygrad_repo/test/test_profiler.py index b307c45ac4..989f79f423 100644 --- a/tinygrad_repo/test/test_profiler.py +++ b/tinygrad_repo/test/test_profiler.py @@ -3,7 +3,6 @@ from tinygrad import Device, Tensor, dtypes, TinyJit from tinygrad.helpers import CI, getenv, Context from tinygrad.device import Buffer, BufferSpec, Compiled, ProfileRangeEvent, ProfileDeviceEvent, ProfileGraphEvent from tinygrad.runtime.support.hcq import HCQCompiled -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import get_runner MOCKGPU = getenv("MOCKGPU") @@ -34,7 +33,7 @@ class TestProfiler(unittest.TestCase): TestProfiler.a = Tensor([0.,1.], device=Device.DEFAULT).realize() TestProfiler.b = self.a + 1 - si = create_schedule([self.b.lazydata])[-1] + si = self.b.schedule()[-1] TestProfiler.runner = get_runner(TestProfiler.d0.device, si.ast) TestProfiler.b.lazydata.buffer.allocate() @@ -59,7 +58,7 @@ class TestProfiler(unittest.TestCase): profile, _ = helper_profile_filter_device(profile, TestProfiler.d0.device) kernel_runs = [x for x in profile if isinstance(x, ProfileRangeEvent)] assert len(kernel_runs) == 1, "one kernel run is expected" - assert kernel_runs[0].is_copy, "kernel should not be copy" + assert kernel_runs[0].is_copy, "kernel should be copy" def test_profile_multiops(self): runner_name = TestProfiler.runner._prg.name @@ -99,6 +98,18 @@ class TestProfiler(unittest.TestCase): assert len(evs) == 1, "one kernel runs are expected" assert evs[0].is_copy, "kernel should be copy" + def test_profile_multidev_transfer(self): + d1 = Device[f"{Device.DEFAULT}:1"] + + buf1 = Tensor.randn(10, 10, device=f"{Device.DEFAULT}:0").realize() + with helper_collect_profile(TestProfiler.d0, d1) as profile: + buf1.to(f"{Device.DEFAULT}:1").realize() + + profile0, _ = helper_profile_filter_device(profile, TestProfiler.d0.device) + kernel_runs = [x for x in profile0 if isinstance(x, ProfileRangeEvent)] + assert len(kernel_runs) == 1, "one kernel run is expected" + assert kernel_runs[0].is_copy, "kernel should be copy" + @unittest.skipIf(Device.DEFAULT in "METAL" or (MOCKGPU and Device.DEFAULT == "AMD"), "AMD mockgpu does not support queue wait interrupts") def test_profile_graph(self): d1 = Device[f"{Device.DEFAULT}:1"] diff --git a/tinygrad_repo/test/test_quantize_onnx.py b/tinygrad_repo/test/test_quantize_onnx.py new file mode 100644 index 0000000000..9b0fd63f41 --- /dev/null +++ b/tinygrad_repo/test/test_quantize_onnx.py @@ -0,0 +1,368 @@ +# ruff: noqa: E501 +import numpy as np +import unittest +from dataclasses import replace +from tinygrad import Tensor, Context, Device, dtypes +from tinygrad.uop.ops import Ops, UOp # noqa: F401 # pylint: disable=unused-import +from tinygrad.codegen.kernel import Kernel, Opt, OptOps +from tinygrad.engine.realize import CompiledRunner, ExecItem, lower_schedule_item +from tinygrad.engine.search import bufs_from_lin +from tinygrad.shape.shapetracker import ShapeTracker, View # noqa: F401 # pylint: disable=unused-import + +N = 512 + +def create_gemm_model(model_path:str, batch_size=N, in_size=N, out_size=N, bias=False): + import onnx + from onnx import helper, numpy_helper, TensorProto + # Define input and output + input_tensor = helper.make_tensor_value_info("input", TensorProto.FLOAT, [batch_size, in_size]) + output_tensor = helper.make_tensor_value_info("output", TensorProto.FLOAT, [batch_size, out_size]) + + # Create random weights and bias + W_data = np.random.randn(in_size, out_size).astype(np.float32) + W_init = numpy_helper.from_array(W_data, name="W") + + if bias: + B_data = np.random.randn(out_size).astype(np.float32) + B_init = numpy_helper.from_array(B_data, name="B") + gemm_node = helper.make_node("Gemm", inputs=["input", "W", "B"], outputs=["output"], alpha=1.0, beta=1.0, transB=0) + graph_def = helper.make_graph([gemm_node], "SingleGemmGraph", [input_tensor], [output_tensor], initializer=[W_init, B_init]) + else: + gemm_node = helper.make_node("Gemm", inputs=["input", "W"], outputs=["output"], alpha=1.0, beta=1.0, transB=0) + graph_def = helper.make_graph([gemm_node], "SingleGemmGraph", [input_tensor], [output_tensor], initializer=[W_init]) + + # Create and save the model + model_def = helper.make_model(graph_def, producer_name="single_gemm_example") + onnx.save_model(model_def, model_path) + return model_path + +def sexec(out:Tensor, opts:list[Opt], replace_src=None, run_count=3): + si = out.schedule()[-1] + k = Kernel(si.ast, opts=Device[Device.DEFAULT].renderer) + #opts = [Opt(op=OptOps.UPCAST, axis=0, arg=128)] #, Opt(op=OptOps.UNROLL, axis=0, arg=4)] + k.apply_opts(opts) + prg = k.to_program() + if replace_src is not None: + old_name = prg.src.split("__attribute__((noinline)) void ")[1].split("(")[0] + prg = replace(prg, src=replace_src + "/* DSP boilerplate */" + prg.src.split("/* DSP boilerplate */")[1].replace(old_name, "fxn")) + ei = ExecItem(CompiledRunner(prg), [x.ensure_allocated() for x in si.bufs], si.metadata) + for _ in range(run_count): ei.run(wait=True) + +def get_quantized_model(sz): + from onnxruntime.quantization import quantize_static, QuantFormat, QuantType, CalibrationDataReader + class FakeDataReader(CalibrationDataReader): + def __init__(self): self.cnt = 0 + def get_next(self) -> dict: + self.cnt += 1 + if self.cnt == 100: return None + return {"input": np.random.uniform(size=(sz, sz)).astype(np.float32)} + out_file = "/tmp/test_out.onnx" + quantize_static(create_gemm_model("/tmp/test_in.onnx", sz, sz, sz), out_file, + FakeDataReader(), quant_format=QuantFormat.QDQ, per_channel=False, reduce_range=False, + activation_type=QuantType.QUInt8, weight_type=QuantType.QInt8, + extra_options={"ActivationSymmetric": False}) + return out_file + +@unittest.skipIf(Device.DEFAULT != "CPU", "only tests for CPU") +class TestQuantizeOnnxCPU(unittest.TestCase): + def test_quant_128(self, sz=128): + try: + import onnx + except ImportError: + raise unittest.SkipTest() + from tinygrad.frontend.onnx import OnnxRunner + out_file = get_quantized_model(sz) + onnx_model = onnx.load(out_file) + run_onnx = OnnxRunner(onnx_model) + inp = Tensor(np.random.uniform(size=(sz, sz)).astype(np.float32)) + with Context(DONT_REALIZE_EXPAND=1, QUANTIZE=1): + sched = run_onnx({"input":inp})["output"].schedule() + ei = lower_schedule_item(sched[-2]) + daccs = [u for u in ei.prg.p.uops if u.op is Ops.DEFINE_ACC] + assert all(u.dtype.scalar() is dtypes.int for u in daccs) + +@unittest.skipIf(Device.DEFAULT != "DSP", "only tests for DSP") +class TestQuantizeOnnx(unittest.TestCase): + def test_quant_128(self): self.test_quant(128) + def test_quant(self, sz=512): + from examples.benchmark_onnx import load_onnx_model + # divide is ~1500-2000 without reduce_range, 750-900 with it + out_file = get_quantized_model(sz) + run_onnx_jit, _ = load_onnx_model(out_file) + with Context(DONT_REALIZE_EXPAND=1): + run_onnx_jit(input=Tensor(np.random.uniform(size=(sz, sz)).astype(np.float32))) + + def test_prequant_conv2d_1x1(self): + X = Tensor(np.random.uniform(0, 255, size=(1, 32, 128, 128)).astype(np.uint8)) + W = Tensor(np.random.uniform(0, 255, size=(64, 32, 1, 1)).astype(np.uint8)) + out = X.conv2d(W, dtype=X.dtype) + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=128), Opt(op=OptOps.UNROLL, axis=0, arg=4)] + sexec(out, opts) + + def test_prequant_gemm(self): + N = 512 + X = Tensor(np.random.uniform(0, 255, size=(N,N)).astype(np.uint8)) + W = Tensor(np.random.uniform(0, 255, size=(N,N)).astype(np.uint8)) + out = X.matmul(W, dtype=X.dtype) + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=128), Opt(op=OptOps.UNROLL, axis=0, arg=4)] + sexec(out, opts) + + # TODO: this has to work + def test_prequant_gemm_intacc_early(self, xi=np.int8, wi=np.int8): + N = 512 + X = Tensor(np.random.uniform(0, 255, size=(N,N)).astype(xi)) + W = Tensor(np.random.uniform(0, 255, size=(N,N)).astype(wi)) + with Context(DONT_REALIZE_EXPAND=1): + # this divide is interesting and forces the accumulator to actually be an int + out = (X.cast("int").matmul(W.cast("int"))//1000).cast("int8") + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=128), Opt(op=OptOps.UNROLL, axis=0, arg=4)] + sexec(out, opts) + + def test_prequant_gemm_handcode(self): + src = """typedef int int128 __attribute__((aligned(512),vector_size(512))); + typedef int int32 __attribute__((aligned(128),vector_size(128))); + typedef int int64 __attribute__((aligned(256),vector_size(256))); + typedef unsigned char unsigned_char4 __attribute__((aligned(4),vector_size(4))); + typedef signed char signed_char128 __attribute__((aligned(128),vector_size(128))); + typedef unsigned char unsigned_char128 __attribute__((aligned(128),vector_size(128))); + typedef unsigned char unsigned_char256 __attribute__((aligned(256),vector_size(256))); + union V256 { + unsigned_char256 vec256; + struct { + unsigned_char128 lo128; + unsigned_char128 hi128; + }; + }; + __attribute__((noinline)) void fxn(unsigned char* restrict __attribute__((align_value(128))) data0, + unsigned char* restrict __attribute__((align_value(128))) data1, + signed char* restrict __attribute__((align_value(128))) data2) { + for (int ridx0 = 0; ridx0 < 512; ridx0++) { + int alu0 = (ridx0<<9); + for (int ridx1 = 0; ridx1 < 4; ridx1++) { + int alu1 = (ridx1<<7); + int32 acc0 = __builtin_HEXAGON_V6_vd0_128B(); + int32 acc1 = __builtin_HEXAGON_V6_vd0_128B(); + int32 acc2 = __builtin_HEXAGON_V6_vd0_128B(); + int32 acc3 = __builtin_HEXAGON_V6_vd0_128B(); + + for (int ridx2 = 0; ridx2 < 128; ridx2++) { + unsigned_char4 val0 = *((unsigned_char4*)((data1+(alu0+(ridx2<<2))))); + int alu2 = (alu1+(ridx2<<11)); + signed_char128 x0 = *((signed_char128*)((data2+alu2))); + signed_char128 x1 = *((signed_char128*)((data2+(alu2+512)))); + signed_char128 x2 = *((signed_char128*)((data2+(alu2+1024)))); + signed_char128 x3 = *((signed_char128*)((data2+(alu2+1536)))); + + union V256 ss01; + // ss01.lo128 = (x0[0], x1[0], x0[2], x1[2], x0[4], x1[4], ...) + // ss01.hi128 = (x0[1], x1[1], x0[3], x1[3], x0[5], x1[5], ...) + ss01.vec256 = __builtin_HEXAGON_V6_vshufoeb_128B(x1, x0); + + union V256 ss23; + // ss23.lo128 = (x2[0], x3[0], x2[2], x3[2], x2[4], x3[4], ...) + // ss23.hi128 = (x2[1], x3[1], x2[3], x3[3], x2[5], x3[5], ...) + ss23.vec256 = __builtin_HEXAGON_V6_vshufoeb_128B(x3, x2); + + union V256 sslo; + // sslo.lo128 = (x0[0], x1[0], x2[0], x3[0], x0[4], x1[4], ...) + // sslo.hi128 = (x0[2], x1[2], x2[2], x3[2], x0[6], x1[6], ...) + sslo.vec256 = __builtin_HEXAGON_V6_vdealvdd_128B(ss23.lo128, ss01.lo128, 2); + + union V256 sshi; + // sshi.lo128 = (x0[1], x1[1], x2[1], x3[1], x0[5], x1[5], ...) + // sshi.hi128 = (x0[3], x1[3], x2[3], x3[3], x0[7], x1[7], ...) + sshi.vec256 = __builtin_HEXAGON_V6_vdealvdd_128B(ss23.hi128, ss01.hi128, 2); + + //unsigned_char128 w0 = (unsigned_char128){val0[0],val0[1],val0[2],val0[3],val0[0],val0[1],val0[2],val0[3],... + unsigned_char128 w0 = __builtin_HEXAGON_V6_lvsplatw_128B(*((unsigned int*)&val0)); + + acc0 = __builtin_HEXAGON_V6_vrmpybusv_acc_128B(acc0, w0, sslo.lo128); + acc1 = __builtin_HEXAGON_V6_vrmpybusv_acc_128B(acc1, w0, sshi.lo128); + acc2 = __builtin_HEXAGON_V6_vrmpybusv_acc_128B(acc2, w0, sslo.hi128); + acc3 = __builtin_HEXAGON_V6_vrmpybusv_acc_128B(acc3, w0, sshi.hi128); + } + acc0 /= 1000; + acc1 /= 1000; + acc2 /= 1000; + acc3 /= 1000; + // ','.join([f"acc{j}[{i}]" for i in range(32) for j in range(4)]) + // acc0[0], acc0[1], acc0[2], ..... acc3[30], acc3[31] + unsigned_char128 packed = __builtin_HEXAGON_V6_vpackhub_sat_128B(__builtin_HEXAGON_V6_vpackwh_sat_128B(acc3, acc2), + __builtin_HEXAGON_V6_vpackwh_sat_128B(acc1, acc0)); + packed = __builtin_HEXAGON_V6_vshuffb_128B(packed); + packed = __builtin_HEXAGON_V6_vshuffb_128B(packed); + // acc0[0], acc1[0], acc2[0], ..... acc2[31], acc3[31] + *((unsigned_char128*)((data0+(alu0+alu1)))) = packed; + } + } + }""" + self.test_prequant_gemm_intacc(np.uint8, np.int8, src) + + def test_prequant_gemm_intacc_32(self): + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=0), Opt(op=OptOps.UPCAST, axis=0, arg=4), Opt(op=OptOps.UNROLL, axis=0, arg=0)] + self.test_prequant_gemm_intacc(np.uint8, np.int8, N=32, opts=opts) + def test_prequant_gemm_intacc_128(self): self.test_prequant_gemm_intacc(np.uint8, np.int8, N=128) + def test_prequant_gemm_intacc_256(self): self.test_prequant_gemm_intacc(np.uint8, np.int8, N=256) + def test_prequant_gemm_intacc(self, xi=np.uint8, wi=np.uint8, replace_src=None, N=512, clip=True, opts=None): + X = Tensor(m1:=(np.random.uniform(0, 255, size=(N,N)).astype(xi))).realize() + W = Tensor(m2:=(np.random.uniform(0, 255, size=(N,N)).astype(wi))).realize() + # ugh, it's so broken with those casts. need DONT_REALIZE_EXPAND=1 python3 test/test_quantize_onnx.py TestQuantizeOnnx.test_prequant + tg_dtype = dtypes.int8 if xi == np.int8 else dtypes.uint8 + with Context(DONT_REALIZE_EXPAND=1): + out = (X.int().matmul(W.int())//1000) + if clip: out = out.clip(dtypes.min(tg_dtype),dtypes.max(tg_dtype)) + out = out.cast(tg_dtype) + opts = [Opt(op=OptOps.UPCAST, axis=1, arg=128), Opt(op=OptOps.UNROLL, axis=0, arg=4)] if opts is None else opts + sexec(out, opts, replace_src, run_count=1) + tout = out.numpy() + mout = ((m1.astype(np.int32) @ m2.astype(np.int32)) / 1000) + if clip: mout = mout.clip(dtypes.min(tg_dtype),dtypes.max(tg_dtype)) + mout = mout.astype(xi) + print(tout) + print(mout) + np.testing.assert_equal(tout, mout) + + def test_prequant_gemm_intacc_wi(self): self.test_prequant_gemm_intacc(wi=np.int8) + def test_prequant_gemm_intacc_xiwi(self): self.test_prequant_gemm_intacc(xi=np.int8, wi=np.int8) + def test_prequant_gemm_intacc_xiwi_noclip(self): self.test_prequant_gemm_intacc(xi=np.int8, wi=np.int8, clip=False) + + def test_prequant_gemv(self): + N = 2048 + # ugh, it's so broken with those casts. need DONT_REALIZE_EXPAND=1 python3 test/test_quantize_onnx.py TestQuantizeOnnx.test_prequant + X = Tensor(np.random.uniform(0, 255, size=(1,N)).astype(np.uint8)).realize() + W = Tensor(np.random.uniform(0, 255, size=(N,N)).astype(np.uint8)).realize() + #out = X.cast(dtypes.int) @ W.cast(dtypes.int) + #out = X @ W + out = X.matmul(W, dtype=X.dtype) + opts = [Opt(op=OptOps.UPCAST, axis=0, arg=128), Opt(op=OptOps.UNROLL, axis=0, arg=4)] + sexec(out, opts) + +@unittest.skipIf(Device.DEFAULT != "DSP", "only tests for DSP") +class TestDSPCache(unittest.TestCase): + def test_cache_speed(self): + # string becuase this breaks Python language server for syntax highlight for some reason + ast = eval("""UOp(Ops.SINK, dtypes.void, arg=None, src=( + UOp(Ops.STORE, dtypes.void, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.uchar.ptr(25088), arg=0, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 28, 28, 32, 1), strides=(0, 896, 32, 1, 0), offset=0, mask=None, contiguous=True),)), src=()), + UOp(Ops.CAST, dtypes.uchar, arg=None, src=( + UOp(Ops.XOR, dtypes.int, arg=None, src=( + UOp(Ops.MAX, dtypes.int, arg=None, src=( + UOp(Ops.XOR, dtypes.int, arg=None, src=( + UOp(Ops.MAX, dtypes.int, arg=None, src=( + UOp(Ops.CAST, dtypes.int, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.ADD, dtypes.float, arg=None, src=( + UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (4,)), src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.CAST, dtypes.float, arg=None, src=( + UOp(Ops.CAST, dtypes.int, arg=None, src=( + UOp(Ops.LOAD, dtypes.uchar, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.uchar.ptr(150528), arg=1, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 28, 28, 32, 192), strides=(0, 5376, 192, 0, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=0.012368360534310341, src=( + x22:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 28, 28, 32, 192), strides=(0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.CAST, dtypes.float, arg=None, src=( + UOp(Ops.CAST, dtypes.int, arg=None, src=( + UOp(Ops.LOAD, dtypes.char, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.char.ptr(6144), arg=2, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32, 48, 4), strides=(4, 128, 1), offset=0, mask=None, contiguous=False), View(shape=(1, 28, 28, 32, 192), strides=(0, 0, 0, 192, 1), offset=0, mask=None, contiguous=False))), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=0.007441135589033365, src=( + x22,)),)),)),)), + UOp(Ops.MUL, dtypes.float, arg=None, src=( + UOp(Ops.CAST, dtypes.float, arg=None, src=( + UOp(Ops.LOAD, dtypes.int, arg=None, src=( + UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(32), arg=3, src=()), + UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 28, 28, 32, 1), strides=(0, 0, 0, 1, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)), + UOp(Ops.CONST, dtypes.float, arg=9.203465015161783e-05, src=( + x36:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 28, 28, 32, 1), strides=(0, 0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)),)),)), + UOp(Ops.CONST, dtypes.float, arg=33.812857328652136, src=( + x36,)),)), + UOp(Ops.CONST, dtypes.float, arg=0.4999999, src=( + x36,)),)), + UOp(Ops.CONST, dtypes.float, arg=136.0, src=( + x36,)),)),)), + UOp(Ops.CONST, dtypes.int, arg=0, src=( + x36,)),)), + x41:=UOp(Ops.CONST, dtypes.int, arg=-1, src=( + x36,)),)), + UOp(Ops.CONST, dtypes.int, arg=-256, src=( + x36,)),)), + x41,)),)),)),))""") + opts = [Opt(op=OptOps.UNROLL, axis=0, arg=8), Opt(op=OptOps.UPCAST, axis=1, arg=32), Opt(op=OptOps.UPCAST, axis=0, arg=4)] + with Context(DEVECTORIZE=0, QUANTIZE=1): + k = Kernel(ast, opts=Device[Device.DEFAULT].renderer) + k.apply_opts(opts) + prg = k.to_program() + #print(prg.src) + + new_src = """ +typedef int int32 __attribute__((aligned(128),vector_size(128))); +typedef signed char signed_char128 __attribute__((aligned(128),vector_size(128))); +typedef unsigned char unsigned_char8 __attribute__((aligned(8),vector_size(8))); +typedef unsigned char unsigned_char4 __attribute__((aligned(4),vector_size(4))); +typedef unsigned char unsigned_char128 __attribute__((aligned(128),vector_size(128))); +__attribute__((noinline)) void r_196_24_8_32_4(unsigned char* restrict __attribute__((align_value(128))) data0, unsigned char* restrict __attribute__((align_value(128))) data1, signed char* restrict __attribute__((align_value( +128))) data2, int* restrict __attribute__((align_value(128))) data3) { + int32 cast0 = (int32){0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}; + int32 val0 = *((int32*)((data3+0))); + for (int ridx0 = 0; ridx0 < 196; ridx0++) { + int32 acc0 = cast0; + int32 acc1 = cast0; + int32 acc2 = cast0; + int32 acc3 = cast0; + __builtin_HEXAGON_Y2_dcfetch(data1+ridx0*768); + __builtin_HEXAGON_Y2_dcfetch(data1+ridx0*768+192); + __builtin_HEXAGON_Y2_dcfetch(data1+ridx0*768+384); + __builtin_HEXAGON_Y2_dcfetch(data1+ridx0*768+576); + for (int ridx1 = 0; ridx1 < 24; ridx1++) { + signed_char128 val1 = *((signed_char128*)((data2+(ridx1<<8)))); + signed_char128 val2 = *((signed_char128*)((data2+((1+(ridx1<<1))<<7)))); + + int alu0 = ((ridx0*768)+(ridx1<<3)); + + unsigned_char8 val3 = *((unsigned_char8*)((data1+alu0))); + __builtin_HEXAGON_Y2_dcfetch(((data1+alu0)+16)); + unsigned_char8 val4 = *((unsigned_char8*)((data1+(alu0+192)))); + __builtin_HEXAGON_Y2_dcfetch(((data1+(alu0+192))+16)); + unsigned_char8 val5 = *((unsigned_char8*)((data1+(alu0+384)))); + __builtin_HEXAGON_Y2_dcfetch(((data1+(alu0+384))+16)); + unsigned_char8 val6 = *((unsigned_char8*)((data1+(alu0+576)))); + __builtin_HEXAGON_Y2_dcfetch(((data1+(alu0+576))+16)); + + unsigned_char4 alu5 = __builtin_shufflevector(val3, val3, 0, 1, 2, 3); + unsigned_char4 alu6 = __builtin_shufflevector(val4, val4, 0, 1, 2, 3); + unsigned_char4 alu7 = __builtin_shufflevector(val5, val5, 0, 1, 2, 3); + unsigned_char4 alu8 = __builtin_shufflevector(val6, val6, 0, 1, 2, 3); + acc0 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc0, val1, (*((unsigned int*)&alu5))); + acc1 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc1, val1, (*((unsigned int*)&alu6))); + acc2 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc2, val1, (*((unsigned int*)&alu7))); + acc3 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc3, val1, (*((unsigned int*)&alu8))); + + unsigned_char4 alu9 = __builtin_shufflevector(val3, val3, 4, 5, 6, 7); + unsigned_char4 alu10 = __builtin_shufflevector(val4, val4, 4, 5, 6, 7); + unsigned_char4 alu11 = __builtin_shufflevector(val5, val5, 4, 5, 6, 7); + unsigned_char4 alu12 = __builtin_shufflevector(val6, val6, 4, 5, 6, 7); + acc0 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc0, val2, (*((unsigned int*)&alu9))); + acc1 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc1, val2, (*((unsigned int*)&alu10))); + acc2 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc2, val2, (*((unsigned int*)&alu11))); + acc3 = __builtin_HEXAGON_V6_vrmpybus_acc_128B(acc3, val2, (*((unsigned int*)&alu12))); + } + unsigned_char128 alu18 = __builtin_HEXAGON_V6_vpackhub_sat_128B(__builtin_HEXAGON_V6_vpackwh_sat_128B((((((acc3+val0)*203)+32767)/65536)+136), (((((acc2+val0)*203)+32767)/65536)+136)), __builtin_HEXAGON_V6_vpackwh_sat_128B((((((acc1+val0)*203)+32767)/65536)+136), (((((acc0+val0)*203)+32767)/65536)+136))); + *((unsigned_char128*)((data0+(ridx0<<7)))) = alu18; + } +} +""" + prg = replace(prg, src=new_src+prg.src.split("/* DSP boilerplate */ ")[1]) + rt = CompiledRunner(prg) + #Device.default.compiler.disassemble(rt.lib) + ei = ExecItem(rt, bufs_from_lin(k)) + tm = ei.run(wait=True) + print(f"final time {tm*1e6:.2f} us") + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/test_randomness.py b/tinygrad_repo/test/test_randomness.py index 707e1e9cd4..05012ec30a 100644 --- a/tinygrad_repo/test/test_randomness.py +++ b/tinygrad_repo/test/test_randomness.py @@ -8,6 +8,7 @@ from tinygrad.helpers import getenv, CI from tinygrad.device import is_dtype_supported from tinygrad.engine.realize import lower_schedule, CompiledRunner from hypothesis import given, settings, strategies as strat +from test.helpers import not_support_multi_device settings.register_profile("my_profile", max_examples=200, deadline=None, derandomize=getenv("DERANDOMIZE_CI", False)) settings.load_profile("my_profile") @@ -65,7 +66,7 @@ class TestRandomness(unittest.TestCase): self.assertFalse(normal_test(Tensor.rand)) self.assertTrue(equal_distribution(Tensor.rand, torch.rand, lambda x: np.random.rand(*x))) - @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need float16 support") + @unittest.skipUnless(is_dtype_supported(dtypes.float16) and is_dtype_supported(dtypes.ulong), "need float16 and ulong support") def test_rand_float16(self): N = 128 x = Tensor.rand((2, N, N), dtype=dtypes.float16) @@ -76,7 +77,7 @@ class TestRandomness(unittest.TestCase): assert nx[nx == 0].size > 0 equal_distribution(lambda *x: Tensor.rand(*x, dtype=dtypes.float16), torch.rand, lambda x: np.random.rand(*x), shape=(2, N, N)) - @unittest.skipIf(CI and Device.DEFAULT == "NV", "gpuocelot doesn't support certain ops needed for threefry") + @unittest.skipIf(CI and Device.DEFAULT in {"NV", "CUDA"}, "gpuocelot doesn't support certain ops needed for threefry") def test_threefry_against_reference(self): Tensor.manual_seed(1337) @@ -97,8 +98,9 @@ class TestRandomness(unittest.TestCase): np.testing.assert_allclose(jr, r) + @unittest.skipIf(getenv("PTX"), "fails with PTX") def test_threefry_doesnt_use_long(self): - for ei in lower_schedule(Tensor.rand(20).schedule()): + for (_,ei) in lower_schedule(Tensor.rand(20).schedule()): if isinstance(ei.prg, CompiledRunner): for u in ei.prg.p.uops: self.assertNotIn(u.dtype, {dtypes.long, dtypes.ulong}, msg=f"long found in {ei.prg.p.name}") @@ -119,12 +121,26 @@ class TestRandomness(unittest.TestCase): 0.3108327388763428, 0.09639489650726318, 0.004686474800109863, 0.8435229063034058, 0.824237585067749, 0.5873836278915405, 0.4232727289199829, 0.2530076503753662, 0.40300023555755615, 0.03966474533081055, 0.27904558181762695, 0.9150195121765137, 0.48057758808135986, 0.23821306228637695, 0.7676635980606079], dtype=np.float32) + r = Tensor.rand(20).numpy() + np.testing.assert_allclose(r, jr, atol=1e-5, rtol=1e-5) + # next 20, np.arange(20, 40, dtype=np.uint32) + jr = np.array([0.7444133758544922, 0.7713677883148193, 0.8233780860900879, 0.43871235847473145, 0.517757773399353, + 0.6437174081802368, 0.967403769493103, 0.26167726516723633, 0.6825339794158936, 0.14966607093811035, + 0.28920769691467285, 0.017063498497009277, 0.2627382278442383, 0.9525482654571533, 0.9351049661636353, + 0.43904995918273926, 0.043945908546447754, 0.6616791486740112, 0.6667773723602295, 0.5228077173233032], dtype=np.float32) r = Tensor.rand(20).numpy() + np.testing.assert_allclose(r, jr, atol=1e-5, rtol=1e-5) - np.testing.assert_allclose(jr, r, atol=1e-5, rtol=1e-5) + # next 10, np.arange(40, 50, dtype=np.uint32) + jr = np.array([0.9614430665969849, 0.059279561042785645, 0.01909029483795166, 0.47882091999053955, 0.9677121639251709, + 0.36863112449645996, 0.3102607727050781, 0.06608951091766357, 0.35329878330230713, 0.26518797874450684], dtype=np.float32) + r = Tensor.rand(10).numpy() + # TODO: this failed because increment happened before _threefry_random_bits + with self.assertRaises(AssertionError): + np.testing.assert_allclose(r, jr, atol=1e-5, rtol=1e-5) - @unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL", "NV"), "no GPU CI") + @unittest.skipIf(not_support_multi_device(), "no multi") def test_threefry_tensors_cnt(self): Tensor.manual_seed(1337) @@ -143,7 +159,7 @@ class TestRandomness(unittest.TestCase): assert len(Tensor._device_rng_counters) == 0 assert len(Tensor._device_seeds) == 0 - @unittest.skipIf(CI and Device.DEFAULT in ("GPU", "CUDA", "METAL", "NV"), "no GPU CI") + @unittest.skipIf(not_support_multi_device(), "no multi") def test_threefry_same_kernels(self): Tensor.manual_seed(0) @@ -185,6 +201,13 @@ class TestRandomness(unittest.TestCase): assert rand.dtype == empty.dtype assert rand.device == empty.device + def test_randn_like(self): + empty = Tensor.empty((80, 44)) + rand = Tensor.randn_like(empty) + assert rand.shape == empty.shape + assert rand.dtype == empty.dtype + assert rand.device == empty.device + def test_rand_like_zero_shape(self): empty = Tensor.empty(0, 20) rand = Tensor.rand_like(empty) @@ -199,7 +222,6 @@ class TestRandomness(unittest.TestCase): assert rand.dtype == empty.dtype assert rand.device == empty.device - @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need float16 support") def test_rand_like_dtype(self): empty = Tensor.empty((80, 44), dtype=dtypes.float16) rand = Tensor.rand_like(empty) @@ -213,7 +235,21 @@ class TestRandomness(unittest.TestCase): assert rand.dtype == dtypes.float16 assert rand.device == empty.device + def test_randn_like_dtype(self): + empty = Tensor.empty((80, 44), dtype=dtypes.float16) + rand = Tensor.randn_like(empty) + assert rand.shape == empty.shape + assert rand.dtype == empty.dtype + assert rand.device == empty.device + + empty = Tensor.empty((80, 44)) + rand = Tensor.randn_like(empty, dtype=dtypes.float16) + assert rand.shape == empty.shape + assert rand.dtype == dtypes.float16 + assert rand.device == empty.device + def test_randn(self): + self.assertEqual(Tensor.randn(3,3,dtype=dtypes.half).dtype, dtypes.half) self.assertTrue(normal_test(Tensor.randn)) self.assertTrue(equal_distribution(Tensor.randn, torch.randn, lambda x: np.random.randn(*x))) @@ -238,7 +274,7 @@ class TestRandomness(unittest.TestCase): numpy_func=lambda x: np.random.randint(low=-2, high=5, size=x))) self.assertTrue(equal_distribution(partial(Tensor.randint, low=-2, high=5, dtype="int32"), numpy_func=lambda x: np.random.randint(low=-2, high=5, size=x))) - self.assertTrue(Tensor.randint(1, device="CLANG").device=="CLANG") + self.assertTrue(Tensor.randint(1, device="CPU").device=="CPU") # check types of args with self.assertRaises(TypeError): Tensor.randint((3, 4), low=0.1, high=3) with self.assertRaises(TypeError): Tensor.randint((3, 4), low=0, high=3.5) @@ -296,17 +332,15 @@ class TestRandomness(unittest.TestCase): @TinyJit def sample_one(): return Tensor(w).multinomial(1, replacement=False).realize() - # TODO: fix mockgpu issue - if not (CI and Device.DEFAULT == "AMD"): - tiny_samples = [sample_one().item() for _ in range(1000)] - torch_samples = [torch.tensor(w).multinomial(1, replacement=False).item() for _ in range(1000)] - self.assertTrue(equal_distribution(lambda *_: Tensor(tiny_samples), lambda _: torch.tensor(torch_samples))) + tiny_samples = [sample_one().item() for _ in range(1000)] + torch_samples = [torch.tensor(w).multinomial(1, replacement=False).item() for _ in range(1000)] + self.assertTrue(equal_distribution(lambda *_: Tensor(tiny_samples), lambda _: torch.tensor(torch_samples))) def test_multinomial_counterexample(self): - tiny_res = Tensor([0.3, 0.6, 0.1]).multinomial(2000, replacement=True) - torch_res = torch.tensor([0.3, 0.6, 0.1]).multinomial(2000, replacement=True) + tiny_res = Tensor([0.3, 0.6, 0.1]).multinomial(4000, replacement=True) + torch_res = torch.tensor([0.3, 0.6, 0.1]).multinomial(4000, replacement=True) self.assertTrue(equal_distribution(lambda *_: tiny_res, lambda _: torch_res)) - torch_res = torch.tensor([0.2, 0.7, 0.1]).multinomial(2000, replacement=True) + torch_res = torch.tensor([0.2, 0.7, 0.1]).multinomial(4000, replacement=True) self.assertFalse(equal_distribution(lambda *_: tiny_res, lambda _: torch_res)) def test_conv2d_init(self): diff --git a/tinygrad_repo/test/test_renderer_failures.py b/tinygrad_repo/test/test_renderer_failures.py index eb39d3771f..329975b94e 100644 --- a/tinygrad_repo/test/test_renderer_failures.py +++ b/tinygrad_repo/test/test_renderer_failures.py @@ -1,16 +1,18 @@ import unittest from typing import List, cast import numpy as np -from tinygrad.codegen.uopgraph import full_graph_rewrite -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.device import Buffer, Device -from tinygrad.dtype import dtypes +from tinygrad.device import Buffer, Device, is_dtype_supported +from tinygrad.dtype import dtypes, ConstType from tinygrad.engine.realize import CompiledRunner from tinygrad.helpers import dedup, flatten, prod from tinygrad.renderer.cstyle import CStyleLanguage -from tinygrad.ops import UOp, Ops +from tinygrad.renderer.ptx import PTXRenderer +from tinygrad.renderer.wgsl import WGSLRenderer +from tinygrad.runtime.ops_python import PythonRenderer +from tinygrad.uop.ops import UOp, Ops from tinygrad.renderer import ProgramSpec from tinygrad.tensor import Tensor, _to_np_dtype +from tinygrad.codegen import full_rewrite def _test_uop_result(inputs:List[Tensor], stores:List[UOp], local_size=None): for x in inputs: x.realize() @@ -21,37 +23,63 @@ def _test_uop_result(inputs:List[Tensor], stores:List[UOp], local_size=None): outbufs = [Buffer(Device.DEFAULT, sz:=(1 if local_size is None else prod(local_size)), (dtype:=u.src[1].dtype), \ initial_value=np.zeros(sz, dtype=_to_np_dtype(dtype)).data) for u in uops if u.op is Ops.STORE] inbufs = [cast(UOp,x.lazydata).base.buffer for x in inputs] - src = Device[Device.DEFAULT].renderer.render("test", uops) - ei = CompiledRunner(ProgramSpec("test", src, Device.DEFAULT, uops=uops, local_size=local_size)) + src = Device[Device.DEFAULT].renderer.render(uops) + ei = CompiledRunner(ProgramSpec("test", src, Device.DEFAULT, uops[-1], uops=uops, local_size=local_size)) ei.exec(outbufs+inbufs) return [np.frombuffer(x.as_buffer(), _to_np_dtype(x.dtype)) for x in outbufs] -@unittest.skipIf(not isinstance(Device[Device.DEFAULT].renderer, CStyleLanguage), "uops are for cstyle") -class TestCStyleFailures(unittest.TestCase): - def test_inline_const_alu(self): - a = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) - b = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 1) - idx = UOp.const(dtypes.int, 0) - ld = UOp(Ops.LOAD, dtypes.int, (b.index(idx),)) - alu = ld.alu(Ops.MAX, UOp.const(dtypes.int, dtypes.min(dtypes.int)+1)) - store = UOp.store(a.index(idx), alu) - sink = UOp(Ops.SINK, dtypes.void, (store,)) - uops = linearize_uop(full_graph_rewrite(sink, Device[Device.DEFAULT].renderer)) - # CLANG doesn't use the max function - ret = _test_uop_result([Tensor([1])], uops)[0] - self.assertEqual(ret[0], 1) +def _setup_and_test_alu(alu_op:Ops, input_val:ConstType, *alu_src_uops:UOp): + dtype = alu_src_uops[0].dtype + a = UOp(Ops.DEFINE_GLOBAL, dtype.ptr(), (), 0) + b = UOp(Ops.DEFINE_GLOBAL, dtype.ptr(), (), 1) + idx = UOp.const(dtypes.int, 0) + ld = UOp(Ops.LOAD, dtype, (b.index(idx),)) + alu = ld.alu(alu_op, *alu_src_uops) + store = UOp.store(a.index(idx), alu) + sink = UOp(Ops.SINK, dtypes.void, (store,)) + uops = full_rewrite(sink, Device[Device.DEFAULT].renderer) + return _test_uop_result([Tensor([input_val])], uops)[0] -@unittest.skipUnless(Device[Device.DEFAULT].renderer.has_local and Device.DEFAULT == "PTX", "need local") -class TestPTXFailures(unittest.TestCase): +class TestRendererFailures(unittest.TestCase): + @unittest.skipIf(not isinstance(Device[Device.DEFAULT].renderer, (PTXRenderer, PythonRenderer)), "test is for ptx or python renderer") def test_gated_store_with_alu(self): a = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) gate_alu = (lidx0:=UOp(Ops.SPECIAL, dtypes.int, (), ('lidx0', 4))).ne(0) gated_alu_store = UOp(Ops.STORE, dtypes.void, (a.index(lidx0, gate_alu), UOp.const(dtypes.int, 1))) sink = UOp(Ops.SINK, dtypes.void, (gated_alu_store,)) - uops = linearize_uop(full_graph_rewrite(sink, Device[Device.DEFAULT].renderer)) + uops = full_rewrite(sink, Device[Device.DEFAULT].renderer) ret = _test_uop_result([], uops, local_size=[4, 1, 1])[0] np.testing.assert_equal(ret, [0, 1, 1, 1]) + @unittest.skipIf(not isinstance(Device[Device.DEFAULT].renderer, (PTXRenderer, PythonRenderer)), "test is for ptx or python renderer") + def test_gated_store_with_alu_2d(self): + a = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) + gate_alu_0 = (lidx0:=UOp(Ops.SPECIAL, dtypes.int, (), ('lidx0', 4))).ne(0) + gate_alu_1 = (lidx1:=UOp(Ops.SPECIAL, dtypes.int, (), ('lidx1', 2))).ne(0) + gated_alu_store = UOp(Ops.STORE, dtypes.void, (a.index(lidx0+lidx1*4, gate_alu_0&gate_alu_1), UOp.const(dtypes.int, 1))) + sink = UOp(Ops.SINK, dtypes.void, (gated_alu_store,)) + uops = full_rewrite(sink, Device[Device.DEFAULT].renderer) + ret = _test_uop_result([], uops, local_size=[4, 2, 1])[0] + np.testing.assert_equal(ret, [0, 0, 0, 0, 0, 1, 1, 1]) + +@unittest.skipIf(not isinstance(Device[Device.DEFAULT].renderer, CStyleLanguage), "uops are for cstyle") +class TestCStyleFailures(unittest.TestCase): + def test_inline_const_alu(self): + # CPU doesn't use the max function + ret = _setup_and_test_alu(Ops.MAX, 1, UOp.const(dtypes.int, dtypes.min(dtypes.int)+1)) + self.assertEqual(ret[0], 1) + +@unittest.skipUnless(isinstance(Device[Device.DEFAULT].renderer, WGSLRenderer), "tests for wgsl renderer") +class TestWGSLFailures(unittest.TestCase): + def test_multiply_infinity(self): + # multiplying a positive constant by infinity should return infinity + # WGSL pipelines do not handle this reliably, some of which return zero, unless infinity always comes from a read on a dynamic buffer + ret = _setup_and_test_alu(Ops.MUL, 5.0, UOp.const(dtypes.float32, float("inf"))) + self.assertEqual(ret[0], float("inf")) + +@unittest.skipIf(not isinstance(Device[Device.DEFAULT].renderer, PTXRenderer), "tests for ptx renderer") +class TestPTXFailures(unittest.TestCase): + @unittest.skip("INDEX can only have a gate ALU parent, not an IF") def test_gated_store_with_if(self): a = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) gate_alu = (lidx0:=UOp(Ops.SPECIAL, dtypes.int, (), ('lidx0', 4))).ne(0) @@ -59,9 +87,17 @@ class TestPTXFailures(unittest.TestCase): if_uop = UOp(Ops.IF, dtypes.void, (gate_alu,)) gated_alu_store = UOp(Ops.STORE, dtypes.void, (a.index(lidx0, if_uop), val)) sink = UOp(Ops.SINK, dtypes.void, (gated_alu_store,)) - uops = linearize_uop(full_graph_rewrite(sink, Device[Device.DEFAULT].renderer)) + uops = full_rewrite(sink, Device[Device.DEFAULT].renderer) ret = _test_uop_result([], uops, local_size=[4, 1, 1])[0] np.testing.assert_equal(ret, [0, 1, 1, 1]) + @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + def test_gated_define_acc_with_half_dtype(self): + a = Tensor.randn(32, 32, dtype=dtypes.half).realize() + b = Tensor.randn(34, 32, dtype=dtypes.half).realize() + result = a.pad((1,1)).matmul(b, dtype=dtypes.half).numpy() + reference = a.pad((1,1)).matmul(b, dtype=dtypes.float).numpy() + np.testing.assert_allclose(result, reference, atol=1e-2, rtol=1e-2) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_rewrite_tracked_childen.py b/tinygrad_repo/test/test_rewrite_tracked_childen.py new file mode 100644 index 0000000000..a1dea7955d --- /dev/null +++ b/tinygrad_repo/test/test_rewrite_tracked_childen.py @@ -0,0 +1,63 @@ +import unittest +from tinygrad import Tensor +from tinygrad.uop.ops import PatternMatcher, Ops, UPat, graph_rewrite, RewriteContext, UOp +from tinygrad.engine.grouper import sym, merge_views + +class TestRewriteTrackedChildren(unittest.TestCase): + @unittest.skip("track_children no longer supported") + def test_children_in_context(self): + def print_children(ctx:RewriteContext, sink:UOp): + view_w_child = sink.src[0].src[0].src[0] + assert view_w_child.op is Ops.VIEW + assert set([x.arg for x in ctx.children[view_w_child]]) == set((2,3)) + ctx.update_children() + assert set([x.arg for x in ctx.children[view_w_child]]) == set((3,4)) + # this is the 3 + assert len(ctx.children[sink.src[0].src[1]]) == 1 + assert next(iter(ctx.children[sink.src[0].src[1]])).op is Ops.ADD + # this is the 4 + assert len(ctx.children[sink.src[0].src[0]]) == 1 + assert next(iter(ctx.children[sink.src[0].src[0]])).op is Ops.ADD + rewrite = PatternMatcher([ + (UPat(Ops.CONST, arg=2, name="x"), lambda x: x.replace(arg=4)), + (UPat(Ops.SINK, name="sink"), print_children) + ]) + a = Tensor(2) + b = Tensor(3) + c = a + b + sink = c.lazydata.sink() + sink = graph_rewrite(sink, rewrite, track_children=True) + + def test_simple_child(self): + rewrite = PatternMatcher([ + (UPat(Ops.CONST, arg=2, name="x"), lambda x: x.replace(arg=4)), + ]) + a = Tensor(2) + b = Tensor(3) + c = a + b + sink = c.lazydata + view_w_child = a.lazydata.src[0] + print([x().arg for x in view_w_child.children]) + print([x.arg for x in sink.get_children_map()[view_w_child]]) + self.assertSetEqual(set([x.arg for x in sink.get_children_map()[view_w_child]]), set((2,3))) + # children can either be added to or removed from the map with graph_rewrite + # added to is easy to detect, just hook the UOp constructor + # when are children removed? + # * if a rewrite rule returns a UOp, the matched node is removed from the graph + sink = graph_rewrite(sink, rewrite) + print([x().arg for x in view_w_child.children]) + print([x.arg for x in sink.get_children_map()[view_w_child]]) + self.assertSetEqual(set([x.arg for x in sink.get_children_map()[view_w_child]]), set((3,4))) + + @unittest.skip("track_children no longer supported") + def test_child_after_parent_update(self): + def print_children(ctx, r): + ctx.update_children() + print(ctx.children[r]) + extra = PatternMatcher([(UPat(Ops.REDUCE_AXIS, name="r"), print_children)]) + a = Tensor.empty(3, 3) + r = (a+0).sum() + graph_rewrite(r.lazydata, merge_views+sym+extra, track_children=True) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_sample.py b/tinygrad_repo/test/test_sample.py index 9af7557ca1..ae71327924 100644 --- a/tinygrad_repo/test/test_sample.py +++ b/tinygrad_repo/test/test_sample.py @@ -1,7 +1,9 @@ import unittest import numpy as np -from tinygrad import Tensor, Variable +from tinygrad import Tensor, Variable, Device +from tinygrad.helpers import OSX +@unittest.skipIf(Device.DEFAULT == "WEBGPU" and not OSX, "WEBGPU Vulkan can only run kernels with up to 10 buffers") class TestSample(unittest.TestCase): def test_sample(self): X = Tensor.rand(10000, 50).realize() diff --git a/tinygrad_repo/test/test_schedule.py b/tinygrad_repo/test/test_schedule.py index 22eb30e8d0..7d198e83ae 100644 --- a/tinygrad_repo/test/test_schedule.py +++ b/tinygrad_repo/test/test_schedule.py @@ -1,7 +1,6 @@ # 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 -# ruff: noqa: E501 import unittest import numpy as np @@ -10,36 +9,37 @@ from typing import List, Optional, Union, cast from tinygrad import nn, dtypes, Device, Tensor from tinygrad.device import is_dtype_supported -from tinygrad.dtype import DType +from tinygrad.dtype import DType, ImageDType from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.shape.view import View -from tinygrad.ops import PatternMatcher, UOp, Ops, UPat, graph_rewrite, track_rewrites, view_supported_devices -from tinygrad.helpers import CI, DEBUG, FUSE_ARANGE, GlobalCounters, flatten, getenv, SPLIT_REDUCEOP, unwrap, prod, Context -from tinygrad.codegen.kernel import Kernel, verify_ast -from tinygrad.engine.schedule import BUF_LIMIT, ScheduleContext, ScheduleItem, create_schedule, view_right, view_left, do_realize, remove_movement_ops -from tinygrad.engine.realize import CompiledRunner, get_runner, run_schedule -from extra.models.llama import precompute_freqs_cis - +from tinygrad.uop.ops import PatternMatcher, UOp, Ops, GroupOp, UPat, graph_rewrite, track_rewrites +from tinygrad.codegen.symbolic import symbolic_simple +from tinygrad.uop.spec import type_verify, shape_spec +from tinygrad.helpers import CI, DEBUG, FUSE_ARANGE, SPLIT_REDUCEOP, GlobalCounters, Context, getenv, all_same, temp +from tinygrad.engine.grouper import view_left, view_right, sym, get_becomes_map, Kernel, create_ast, merge_views, create_kernels +from tinygrad.engine.schedule import ScheduleItem, create_schedule_with_vars +from tinygrad.engine.realize import CompiledRunner, run_schedule, lower_schedule + +def verify_ast(sink:UOp): return type_verify(list(sink.toposort()), shape_spec) class KernelCountException(Exception): pass def check_schedule(t:Union[Tensor, List[Tensor], UOp], allowed:int, to_prerealize:Optional[List[Tensor]]=None, filter_sink=True): - if isinstance(t, Tensor): outs = t.lazydata.lbs - elif isinstance(t, List): outs = flatten([r.lazydata.lbs for r in t]) - else: outs = [t] if to_prerealize: - for pre in to_prerealize: pre.schedule() - sched = create_schedule(outs) - if filter_sink: sched = [s for s in sched if s.ast.op is Ops.SINK] - if len(sched) != allowed: + with Context(DEBUG=0, TRACK_MATCH_STATS=0): Tensor.realize(*to_prerealize) + if isinstance(t, Tensor): sched = t.schedule() + elif isinstance(t, List) and isinstance(t[0], Tensor): sched = Tensor.schedule(*t) + else: + assert isinstance(t, UOp), f"can't schedule {t}" + sink = UOp.sink(t) if t.op is not Ops.SINK else t + becomes_map = get_becomes_map(sink) + sched, _, __ = create_schedule_with_vars(sink.substitute(becomes_map)) + # test lowering all the ScheduleItems to ExecItems + kernel_cnt = len([si for si,ei in lower_schedule(sched.copy()) if isinstance(ei.prg, CompiledRunner) or not filter_sink]) + if kernel_cnt != allowed: print(f"SCHEDULE ISSUE, expecting {allowed} got {len(sched)}") if DEBUG >= 3: for i,s in enumerate(sched): print("kernel", i+1) print(s.ast) - raise KernelCountException(f"{len(sched)=} != {allowed}") - # test the (sink) ops linearize - for s in sched: - if s.ast.op is not Ops.SINK: continue - get_runner(s.bufs[0].device, s.ast) + raise KernelCountException(f"{kernel_cnt} != {allowed}") return sched def _realize_weights(m): @@ -54,7 +54,7 @@ def _test_conv2d(allowed:int, dtype:DType=dtypes.float, **kwargs): w = Tensor.uniform(16, CIN, 3, 3, requires_grad=True).realize() ret = Tensor.conv2d(img, w).relu().mean().backward() dtypes.default_float = old_default_float - with Context(**kwargs): s = create_schedule([ret.lazydata, img.grad.lazydata, w.grad.lazydata]) + with Context(**kwargs): s = Tensor.schedule(ret, img.grad, w.grad) run_schedule(s.copy()) cnt = len([si for si in s if si.ast.op is Ops.SINK]) assert cnt == allowed, f"expected {allowed} kernels, got {cnt}" @@ -67,7 +67,96 @@ def _test_conv2d(allowed:int, dtype:DType=dtypes.float, **kwargs): np.testing.assert_allclose(img.grad.numpy(), ref_img.grad.detach().numpy(), atol=1e-6 if dtype == dtypes.float else 1e-2) np.testing.assert_allclose(w.grad.numpy(), ref_w.grad.detach().numpy(), atol=1e-6 if dtype == dtypes.float else 1e-2) +@track_rewrites(named=True) +def schedule_graph_rewrite(big_sink:UOp): return graph_rewrite(big_sink, merge_views+sym, {}) + class TestSchedule(unittest.TestCase): + @unittest.skipIf(Device.DEFAULT == "CPU", "devices must mismatch") + def test_error_on_device_mismatch(self): + a = Tensor.empty(10) + b = Tensor.empty(10, device="CPU") + c = a+b + with self.assertRaises(RuntimeError): check_schedule(c, 1) + + @unittest.skipUnless(is_dtype_supported(dtypes.half) and getenv("CAST_AFTER_EXPAND"), "need half and CAST_AFTER_EXPAND=1") + @unittest.skip("CAST_AFTER_EXPAND is not supported") + def test_expand_buffer_before_cast(self): + a = Tensor.randn(4, 2, 1).realize().permute((1, 0, 2)) + b = a.cast(dtypes.half).expand((2, 4, 4))+2 + run_schedule(check_schedule(b, 1)) + np.testing.assert_allclose(b.numpy(), np.broadcast_to(a.numpy().astype(np.float16), (2, 4, 4))+2) + + def test_indexing_scalars_simple(self): + X = Tensor.randn(2, 2).realize() + xt = X[Tensor(1)][Tensor(0)] + with Context(FUSE_ARANGE=1): + run_schedule(check_schedule(xt, 2)) + np.testing.assert_equal(xt.numpy(), X.numpy()[1][0]) + + @unittest.expectedFailure # TODO: failing because of can_chase + def test_indexing_scalars_multiple_dims(self): + X = Tensor.randn(2, 3).realize() + xt = X[Tensor(0)][Tensor(1)] + with Context(FUSE_ARANGE=1): + run_schedule(check_schedule(xt, 2)) + np.testing.assert_equal(xt.numpy(), X.numpy()[0][1]) + + def test_push_pads_elementwise(self): + x = Tensor.full((4,4), 2.).contiguous().realize() + y = Tensor.full((4,4), 4.).contiguous().realize() + z = (x.reciprocal()*y).pad((None, (0,1),)).sum() + run_schedule(check_schedule(z, 2)) + self.assertEqual(z.item(), 32) + + def test_push_pads_contiguous(self): + x = Tensor.full((4,1), 2.).contiguous() + y = Tensor.full((4,4), 4.).contiguous() + z = (x.reciprocal().expand(4,4)*y).pad((None, (0,1),)).sum() + run_schedule(check_schedule(z, 2, [x,y])) + self.assertEqual(z.item(), 32) + + def test_rand(self): + x = Tensor.rand(32) + check_schedule(x, 3, [Tensor._device_rng_counters[x.device]]) + + def test_rand_recompute_arange(self): + x = Tensor.rand(32) + with Context(DONT_GROUP_REDUCES=1): + check_schedule(x, 2, [Tensor._device_rng_counters[x.device]]) + + @unittest.skip("TODO: do not divide by zero given x.idiv(VALID)") + def test_rand_handcoded(self): + Tensor.manual_seed(0) + x = Tensor.rand(32) + # pre-realize shared seed + Tensor._device_rng_counters[x.device].realize() + # run custom kernelized kernel + sched_sink = graph_rewrite(x.lazydata, create_kernels, ctx={u:None for u in x.lazydata.toposort() if u.op is Ops.COPY}, bottom_up=True) + y = Tensor(graph_rewrite(sched_sink, create_ast, bottom_up=True)) + run_schedule(check_schedule(y, 1)) + # compare against reference + run_schedule(check_schedule(x, 3)) + np.testing.assert_allclose(y.numpy(), x.numpy()) + + def test_empty_is_not_realized(self): + a = Tensor.empty(10) + child = a+2 + assert not a.lazydata.is_realized + child.realize() + assert a.lazydata.is_realized + + # NOTE: because empty does not have an ExecItem if realize is called on a childless empty, it never gets allocated. + def test_childless_empty_never_allocates(self): + a = Tensor.empty(10) + a.realize() + assert not a.lazydata.is_realized + + def test_simplify_padded_const(self): + a = Tensor.empty(1022).cummax(axis=0) + sched = check_schedule(a, 5) + ast = sched[0].ast + self.assertLessEqual(len([u for u in ast.toposort() if u.op is Ops.WHERE]), 6) + def test_basic_binop_fusion(self): a = Tensor.empty(10) b = Tensor.empty(10) @@ -111,7 +200,7 @@ class TestSchedule(unittest.TestCase): def test_constants_are_embedded(self): a = Tensor.empty(3,3) * 2 - check_schedule(a, 2, filter_sink=False) + check_schedule(a, 1, filter_sink=False) def tests_constants_are_folded(self): a = Tensor(2) @@ -146,6 +235,13 @@ class TestSchedule(unittest.TestCase): c = a.sum(axis=0, keepdim=True).permute(2,1,0) + b with self.assertRaises(KernelCountException): check_schedule(c, 1) + def test_allow_push_permutes(self): + a = Tensor.randn(10,10,10).realize() + b = Tensor.randn(10,10,1).realize() + c = a.sum(axis=0, keepdim=True).permute(2,1,0) + b + with Context(DONT_GROUP_REDUCES=1): run_schedule(check_schedule(c, 1)) + np.testing.assert_allclose(c.numpy(), np.sum(a.numpy(), axis=0, keepdims=True).transpose(2,1,0)+b.numpy()) + def test_binop_early_reshape_reduce_fusion(self): a = Tensor.empty(100) b = Tensor.empty(100) @@ -198,7 +294,7 @@ class TestSchedule(unittest.TestCase): r1 = (x - r0).sum(axis=0).div(2) out = r0 + r1 schedule = check_schedule(out, 2) - reduceops = [x for si in schedule for x in si.ast.toposort if x.op is Ops.REDUCE_AXIS] + reduceops = [x for si in schedule for x in si.ast.toposort() if x.op is Ops.REDUCE_AXIS] assert len(reduceops) == 2 def test_cache_reduce_multiple_children(self): @@ -209,9 +305,33 @@ class TestSchedule(unittest.TestCase): out0 = r0 + y out1 = r1 + y schedule = check_schedule([out0, out1], 4) - reduceops = [x for si in schedule for x in si.ast.toposort if x.op is Ops.REDUCE_AXIS] + reduceops = [x for si in schedule for x in si.ast.toposort() if x.op is Ops.REDUCE_AXIS] assert len(reduceops) == 2 + def test_div_collapse_buffer(self): + a = Tensor.full((4,), 4.0).contiguous().realize() + b = Tensor.full((4,), 2.0).contiguous().realize() + expr = (a*b)/b + check_schedule(expr, 0) + np.testing.assert_allclose(expr.numpy(), np.full((4,), 4.0)) + + def test_div_collapse_const(self): + a = Tensor.full((4,), 4.0).contiguous().realize() + expr = a/a + check_schedule(expr, 0) + np.testing.assert_allclose(expr.numpy(), np.full((4,), 1.0)) + + def test_div_collapse(self): + a = Tensor.full((4,), 1.0).contiguous().realize() + b = Tensor.full((4,), 2.0).contiguous().realize() + c = Tensor.full((4,), 3.0).contiguous().realize() + GlobalCounters.reset() + expr = (a/b)/c + expr.realize() + self.assertEqual(GlobalCounters.kernel_count, 1) + self.assertLessEqual(GlobalCounters.global_ops, 4*3) + np.testing.assert_allclose(expr.numpy(), (a.numpy()/b.numpy())/c.numpy()) + def test_dedup_assign(self): a = Tensor.ones(4).contiguous().realize() b = Tensor.full((4,), 2.).contiguous() @@ -229,27 +349,32 @@ class TestSchedule(unittest.TestCase): # a and b share the same underlying device memory self.assertIs(a.lazydata.realized, b.lazydata.realized) - # EMPTY and COPY are assigned to unique device Buffers - - def test_no_dedup_copy(self): + def test_copy_dedups(self): src = Tensor.ones(4).contiguous().realize() a = src.clone() b = src.clone() - sched = check_schedule([a, b], 2, filter_sink=False) + sched = check_schedule([a, b], 1, filter_sink=False) run_schedule(sched) - # a and b are assigned to different device Buffers - self.assertIsNot(a.lazydata.realized, b.lazydata.realized) + # a and b are assigned to the same device Buffer + self.assertIs(a.lazydata.realized, b.lazydata.realized) + + # EMPTY is assigned to a unique device Buffer def test_no_dedup_empty(self): a = Tensor.empty((4,)) b = Tensor.empty((4,)) - sched = check_schedule([a, b], 2, filter_sink=False) - run_schedule(sched) - self.assertIsNot(a.lazydata.realized, b.lazydata.realized) + # NOTE: empty does not have any schedule + check_schedule([a, b], 0, filter_sink=False) + self.assertIsNot(a.lazydata.buffer, b.lazydata.buffer) + + def test_dedup_outputs(self): + a = Tensor.full((4, 4), 1.).contiguous().realize() + b = Tensor.full((4, 4), 1.).contiguous().realize() + check_schedule([a+b, a+b], 1) def test_fold_double_unary(self): y = Tensor.empty(2) - out = y.sum(keepdim=True).sqrt().__neg__() + out = y.sum(keepdim=True).sqrt().neg() check_schedule(out, 1) #@unittest.skip("may want to reconsider this") @@ -284,9 +409,10 @@ class TestSchedule(unittest.TestCase): out = bn(c1(img)).relu() check_schedule(out, 4, [c1.weight, c1.bias]) + @unittest.skipUnless(is_dtype_supported(dtypes.ulong), "Needs ulong") def test_fold_conv_batchnorm_optim(self): # this is too high - for optim, cnt in [(nn.optim.Adam, 18), (nn.optim.SGD, 15)]: + for optim, cnt in [(nn.optim.Adam, 30), (nn.optim.SGD, 11)]: with self.subTest(optim=optim.__name__): with Tensor.train(): img = Tensor.ones(1,3,4,4) @@ -483,31 +609,27 @@ class TestSchedule(unittest.TestCase): check_schedule(x, 3) def test_resnet_block(self): - old_training = Tensor.training - Tensor.training = False - - in_planes, planes = 64, 64 - conv1 = nn.Conv2d(in_planes, planes, kernel_size=3, stride=1, padding=1, bias=False) - bn1 = nn.BatchNorm2d(planes) - conv2 = nn.Conv2d(planes, planes, kernel_size=3, padding=1, stride=1, bias=False) - bn2 = nn.BatchNorm2d(planes) - - x = Tensor.empty(1, 64, 32, 32) - out = bn1(conv1(x)).relu() - out = bn2(conv2(out)) - out = (out + x).relu() - check_schedule(out, 2, [conv1.weight, conv2.weight]) - Tensor.training = old_training + with Tensor.train(False): + in_planes, planes = 64, 64 + conv1 = nn.Conv2d(in_planes, planes, kernel_size=3, stride=1, padding=1, bias=False) + bn1 = nn.BatchNorm2d(planes) + conv2 = nn.Conv2d(planes, planes, kernel_size=3, padding=1, stride=1, bias=False) + bn2 = nn.BatchNorm2d(planes) + x = Tensor.empty(1, 64, 32, 32) + out = bn1(conv1(x)).relu() + out = bn2(conv2(out)) + out = (out + x).relu() + run_schedule(check_schedule(out, 2, [conv1.weight, conv2.weight])) def test_contiguous_while_contiguous(self): x = Tensor.empty(1, 64, 32, 32) out = x.contiguous() - check_schedule(out, 1, filter_sink=False) + check_schedule(out, 0, filter_sink=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_sink=False) + check_schedule(out, 1, filter_sink=False) def test_fold_with_contiguous(self): a = Tensor.randn(16, 16, 16).realize() @@ -515,21 +637,93 @@ class TestSchedule(unittest.TestCase): c = (a.sum(2).contiguous() + b).contiguous() check_schedule(c, 2) + def test_kernelize(self): + a = Tensor.empty(10) + b = Tensor.empty(10) + c = (a+b).kernelize() + d = c+2 + check_schedule(d, 2) + + def test_kernelize_view(self): + a = Tensor.empty(4,1) + b = a*2 + c = b.kernelize()+Tensor.empty(4,4) + check_schedule(c, 2) + + def test_multioutput_ast(self): + a = Tensor.zeros(1, dtype=dtypes.int).contiguous().realize().lazydata + b = Tensor.zeros(1, dtype=dtypes.int).contiguous().realize().lazydata + c = Tensor.arange(4).realize().lazydata + kernel = UOp(Ops.KERNEL, src=(a, b, c), arg=Kernel(UOp.sink(c.r(Ops.ADD, (0,))+1, c.r(Ops.ADD, (0,))*2))) + kernel = graph_rewrite(kernel, create_ast) + run_schedule(check_schedule(UOp.sink(a.assign(kernel), b.assign(kernel)), 1)) + self.assertEqual(a.buffer.numpy(), [7]) + self.assertEqual(b.buffer.numpy(), [12]) + + # unlike schedule, kernelize can be called multiple times on a Tensor + def test_double_kerenlize(self): + a = Tensor.empty(10) + b = Tensor.empty(10) + c = (a+b) + d = c.kernelize()+2 + e = c.kernelize()+d.kernelize() + check_schedule(e, 3) + + def test_kernelize_bw(self): + a = Tensor.full((3,), 2.0, requires_grad=True).contiguous() + b = Tensor.full((3,), 3.0, requires_grad=True).contiguous() + x = (a*b).kernelize() + y = Tensor.eye(3, requires_grad=True) + z = y.matmul(x).sum() + z.backward() + self.assertEqual(z.item(), 18.0) + self.assertEqual(z.grad.item(), 1.0) + + def test_kernelize_bw_view(self): + a = Tensor.full((3,1), 2.0, requires_grad=True).contiguous() + b = Tensor.full((3,1), 3.0, requires_grad=True).contiguous() + x = (a*b).kernelize() + y = Tensor.eye(6, requires_grad=True) + z = y.matmul(x.expand(3,2).reshape(6)).sum() + z.backward() + self.assertEqual(z.item(), 36.0) + self.assertEqual(z.grad.item(), 1.0) + + @unittest.skip("no longer supported") def test_double_from(self): x = Tensor([1,2,3,4]) out = x.to('python') check_schedule(out, 0, filter_sink=False) - def test_pow_const_tensor_simplified(self): - x = Tensor([1,2,3,4]) - # NOTE: this does not test ** Tensor(2) is simpler in ast than ** Tensor(2.5) - out = x ** Tensor(2) - check_schedule(out, 1) + def _alu_from_tensor(self, t:Tensor): + s = [s for s in t.schedule() if s.ast.op is Ops.SINK] + self.assertEqual(len(s), 1) + return [u.op for u in s[0].ast.toposort() if u.op in GroupOp.ALU] + + def test_2_pow_is_exp2(self): + t = 2.0 ** Tensor([1.0, 2.0, 3.0]) + self.assertEqual(self._alu_from_tensor(t), [Ops.EXP2]) + + def test_pow_05_is_sqrt(self): + t = Tensor([1.0, 2.0, 3.0]) ** 0.5 + self.assertEqual(self._alu_from_tensor(t), [Ops.SQRT]) + + def test_pow_neg_05_is_rsqrt(self): + t = Tensor([1.0, 2.0, 3.0]) ** -0.5 + self.assertEqual(self._alu_from_tensor(t), [Ops.RECIP, Ops.SQRT]) + + def test_pow_2_has_1_mul(self): + t = Tensor([1.0, 2.0, 3.0]) ** Tensor(2.0) + self.assertEqual(self._alu_from_tensor(t), [Ops.MUL]) + + def test_pow_8_has_3_muls(self): + t = Tensor([1.0, 2.0, 3.0]) ** 8 + self.assertEqual(self._alu_from_tensor(t), [Ops.MUL, Ops.MUL, Ops.MUL]) def test_pow_const_tensor_to_zero(self): x = Tensor([1,2,3,4]) - out = x ** Tensor(0) - # NOTE: this is ConstBuffer 0 + ConstBuffer 1 + out = x ** Tensor(0.0) + # NOTE: this is UOp.const(0) + UOp.const(1) check_schedule(out, 0) def test_zero_size(self): @@ -549,7 +743,6 @@ class TestSchedule(unittest.TestCase): out = x.sum(1).relu().elu() + y.sum(1).relu().elu() check_schedule(out, 2) - # multireduce spec @unittest.skipUnless(SPLIT_REDUCEOP, "Testing split reducop requires SPLIT_REDUCEOP") def test_preserve_multistage_reduce(self): big_enough = getenv("REDUCEOP_SPLIT_THRESHOLD", 32768) @@ -570,7 +763,7 @@ class TestSchedule(unittest.TestCase): out = x.relu().sum(1) + out2[0] check_schedule(out, 2) - # multireduce spec + @unittest.skip("these two Tensors are the same") def test_example_matmul(self): x = Tensor.eye(64, requires_grad=True) y = Tensor.eye(64, requires_grad=True) @@ -580,6 +773,24 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), np.ones((64,64))) + def test_example_matmul_contig(self): + x = Tensor.eye(64, requires_grad=True).contiguous().realize() + y = Tensor.eye(64, requires_grad=True).contiguous().realize() + z = y.matmul(x).sum() + z.backward() + out = x.grad.contiguous() + run_schedule(check_schedule(out, 2)) + np.testing.assert_allclose(out.numpy(), np.ones((64,64))) + + def test_example_matmul_same(self): + x = Tensor.eye(64, requires_grad=True) + z = x.matmul(x).sum() + z.backward() + out = x.grad.contiguous() + run_schedule(check_schedule(out, 2)) + # NOTE: the gradient flows twice + np.testing.assert_allclose(out.numpy(), 2*np.ones((64,64))) + def test_contiguous_add(self): x = Tensor.empty(32) y = Tensor.empty(32) @@ -599,9 +810,9 @@ class TestSchedule(unittest.TestCase): x = x.sum(1) x = x[:16] out = x + y - check_schedule(out, 2) # TODO: this should be 1 + # NOTE: this could be 1 kernel if we mask the store? + check_schedule(out, 2) - # multireduce spec def test_multireduce_shrink(self): Tensor.manual_seed(0) a = Tensor.randn(32, 32).realize() @@ -624,7 +835,7 @@ class TestSchedule(unittest.TestCase): out = x.contiguous() + y.contiguous() check_schedule(out, 2, filter_sink=False) - # multireduce spec + @unittest.expectedFailure def test_reduce_same_size(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -636,7 +847,7 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out1.numpy(), out1_np:=a.numpy().sum()+4, atol=1e-4, rtol=1e-6) np.testing.assert_allclose(out2.numpy(), out0_np*out1_np, atol=1e-4, rtol=1e-6) - # multireduce spec + @unittest.expectedFailure def test_reduce_multiple_paths(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -647,7 +858,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out0.numpy(), out0_np:=np.exp2(a.numpy().sum()), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out1.numpy(), a.numpy().sum()+out0_np, atol=1e-4, rtol=1e-6) - # multireduce spec def test_multireduce_reduce_multiple_paths(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -657,14 +867,13 @@ class TestSchedule(unittest.TestCase): out2 = b.sum().exp2() out3 = b.sum() + out2 # run_schedule(check_schedule([out0, out1, out2, out3], 1)) - run_schedule(check_schedule([out0, out1, out2, out3], 2)) + run_schedule(check_schedule([out0, out1, out2, out3], 6)) np.testing.assert_allclose(out0.numpy(), np_out0:=np.exp2(a.numpy().sum()), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out1.numpy(), np_out1:=a.numpy().sum()+np_out0, atol=1e-4, rtol=1e-4) np_b = (a.numpy() + np_out0 + np_out1) np.testing.assert_allclose(out2.numpy(), np_out2:=np.exp2(np_b.sum()), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out3.numpy(), np_b.sum()+np_out2, atol=1e-4, rtol=1e-4) - # multireduce spec def test_reduce_ext_reduce_child(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -677,7 +886,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out0.numpy(), a.numpy().sum()+b.numpy().sum()+2, atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out1.numpy(), a.numpy().sum()+b.numpy().sum()+4, atol=1e-4, rtol=1e-4) - # multireduce spec def test_reduce_multiple_paths_midreduce(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -693,7 +901,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out1.numpy(), out1_np:=(a.numpy() - out0_np).max(), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out2.numpy(), r_np + out1_np, atol=1e-4, rtol=1e-4) - # multireduce spec def test_reduce_multiple_paths_midreduce_fused(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -707,7 +914,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out1.numpy(), out1_np:=b.numpy().max() + out0_np*2, atol=1e-4, rtol=1e-6) np.testing.assert_allclose(out2.numpy(), a.numpy().sum() + out1_np, atol=1e-4, rtol=1e-6) - # multireduce spec def test_reduce_multiple_paths_midexpand(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4).realize() @@ -736,6 +942,7 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out0.numpy(), a.numpy().sum()+2, atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out1.numpy(), a.numpy().sum()+b.numpy(), atol=1e-4, rtol=1e-4) + @unittest.expectedFailure def test_reduce_shrink_child(self): a = Tensor.empty(100, 100) b = Tensor.empty(10,) @@ -757,7 +964,6 @@ class TestSchedule(unittest.TestCase): out1 = out0[0] + Tensor.empty(1, ) check_schedule([r, out0, out1], 3) - # multireduce spec def test_std_multireduce_fusion(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -765,7 +971,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), x.numpy().std(axis=-1, ddof=1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_argmin_multireduce_fusion(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -773,7 +978,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 3)) np.testing.assert_equal(out.numpy(), x.numpy().argmin(axis=-1)) - # multireduce spec def test_argmax_multireduce_fusion(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -793,7 +997,6 @@ class TestSchedule(unittest.TestCase): compare = torch.nn.functional.scaled_dot_product_attention(torch.tensor(q.numpy()),torch.tensor(k.numpy()),torch.tensor(v.numpy())) np.testing.assert_allclose(out.numpy(), compare.numpy(), atol=1e-6, rtol=1e-3) - # multireduce spec def test_ugly_reduceop_pairing(self): Tensor.manual_seed(0) a = Tensor.randn(4, 32).realize() @@ -805,7 +1008,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out.numpy(), \ (c.numpy()*a.numpy().sum(axis=-1,keepdims=True)).sum(-1) + (b.numpy()*a.numpy().sum(axis=-1,keepdims=True)).sum(-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_reduce_expand_reduce_fusion(self): Tensor.manual_seed(0) a = Tensor.randn(4, 32).realize() @@ -814,7 +1016,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), (a.numpy()+a.numpy().sum(axis=-1,keepdims=True)).sum(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_reduce_expand_reduce_expand_fusion(self): Tensor.manual_seed(0) a = Tensor.randn(4, 32).realize() @@ -824,7 +1025,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out.numpy(), \ a.numpy()+(a.numpy()+a.numpy().sum(axis=-1,keepdims=True)).sum(axis=-1,keepdims=True), atol=1e-4, rtol=1e-4) - # multireduce spec def test_branching_reduces_and_expands_fusion(self): Tensor.manual_seed(0) a = Tensor.randn(4, 32).realize() @@ -835,7 +1035,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out0.numpy(), a.numpy()+a.numpy().sum(axis=-1,keepdims=True), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out1.numpy(), (a.numpy()+a.numpy().sum(axis=-1,keepdims=True)).sum(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_simple_sequential(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -845,7 +1044,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), (y.numpy() + x.numpy().sum(axis=-1, keepdims=True)).sum(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_simple_parallel(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -855,7 +1053,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), y.numpy().sum(axis=-1) + x.numpy().sum(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_sequential(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -864,7 +1061,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), x.numpy().std(axis=-1, ddof=1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_parallel(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -874,7 +1070,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 4)) np.testing.assert_allclose(out.numpy(), x.numpy().std(axis=-1, ddof=1) + y.numpy().std(axis=-1, ddof=1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_diffops_sequential(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -883,7 +1078,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), (x.numpy() - x.numpy().max(axis=-1, keepdims=True)).sum(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_diffops_parallel(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -893,7 +1087,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), x.numpy().sum(axis=-1) + y.numpy().max(axis=-1), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multireduce_fusion_sequential_and_parallel(self): Tensor.manual_seed(0) x = Tensor.randn(4, 32).realize() @@ -907,7 +1100,6 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(out[0].numpy(), np.sqrt(np.square(x.numpy() - np_mu).sum(-1)/x.shape[-1]), atol=1e-4, rtol=1e-4) np.testing.assert_allclose(out[1].numpy(), np.sqrt(np.square(y.numpy() - np_mu).sum(-1)/y.shape[-1]), atol=1e-4, rtol=1e-4) - # multireduce spec def test_multimatmul_fusion(self): Tensor.manual_seed(0) a,b = Tensor.randn(4, 64).realize(), Tensor.rand(64,8).realize() @@ -925,6 +1117,24 @@ class TestSchedule(unittest.TestCase): expected = (x_exp:=np.exp(x.numpy()-x.numpy().max(-1, keepdims=True)))/x_exp.sum(-1, keepdims=True) np.testing.assert_allclose(out.numpy(), expected, atol=1e-4, rtol=1e-4) + @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + def test_softmax_upcast(self): + # input half, softmax in float + Tensor.manual_seed(0) + x = Tensor.randn(4, 12, 64, 64, dtype=dtypes.half).realize() + out = x.softmax(dtype=dtypes.float) + sched = out.schedule() + self.assertEqual(len(sched), 3) + self.assertEqual(sched[0].bufs[0].dtype, dtypes.half) + + # input float, softmax in float + Tensor.manual_seed(0) + x = Tensor.randn(4, 12, 64, 64, dtype=dtypes.float).realize() + out = x.softmax(dtype=dtypes.float) + sched = out.schedule() + self.assertEqual(len(sched), 3) + self.assertEqual(sched[0].bufs[0].dtype, dtypes.float) + def test_softmax_backward(self): Tensor.manual_seed(0) x = Tensor.randn(4, 12, 64, 64, requires_grad=True).realize() @@ -951,9 +1161,9 @@ class TestSchedule(unittest.TestCase): check_schedule(out, 5) def test_scaled_dot_product_attention_causal_fusion(self): - x, y, z, m = (Tensor.empty(32, 8, 16, 16) for _ in range(4)) - out = Tensor.scaled_dot_product_attention(x, y, z, attn_mask=m, is_causal=True) - check_schedule(out, 6) + x, y, z = (Tensor.empty(32, 8, 16, 16) for _ in range(3)) + out = Tensor.scaled_dot_product_attention(x, y, z, is_causal=True) + check_schedule(out, 5) def test_adam_step_fusion(self): with Tensor.train(): @@ -962,7 +1172,7 @@ class TestSchedule(unittest.TestCase): _realize_weights(layer) opt = nn.optim.Adam(nn.state.get_parameters(layer), lr=1e-4) layer(x).relu().sum().backward() - check_schedule(opt.schedule_step(), 10) + check_schedule(opt.schedule_step(), 16) def test_adam_conv_fuse(self): with Tensor.train(): @@ -972,7 +1182,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.Adam(nn.state.get_parameters(c1), lr=1e-4) opt.zero_grad() c1(img).relu().sum().backward() - check_schedule(opt.schedule_step(), 10) + check_schedule(opt.schedule_step(), 16) def test_adam_2convs_fuse(self): with Tensor.train(): @@ -983,7 +1193,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.Adam(nn.state.get_parameters([c1, c2]), lr=1e-4) opt.zero_grad() c2(c1(img).relu()).relu().sum().backward() - check_schedule(opt.schedule_step(), 13) + check_schedule(opt.schedule_step(), 20) def test_sgd_conv_fuse(self): with Tensor.train(): @@ -993,7 +1203,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.SGD(nn.state.get_parameters(c1)) opt.zero_grad() c1(img).relu().sum().backward() - check_schedule(opt.schedule_step(), 5) + check_schedule(opt.schedule_step(), 3) def test_sgd_2convs_fuse(self): with Tensor.train(): @@ -1004,8 +1214,9 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.SGD(nn.state.get_parameters([c1, c2])) opt.zero_grad() c2(c1(img).relu()).relu().sum().backward() - check_schedule(opt.schedule_step(), 8) + check_schedule(opt.schedule_step(), 7) + @unittest.skipUnless(is_dtype_supported(dtypes.ulong), "Needs ulong") def test_fold_2convs_sgd_nesterov_momentum_wd(self): with Tensor.train(): img = Tensor.empty(2,3,4,4) @@ -1015,7 +1226,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.SGD(nn.state.get_parameters([c1, c2]), nesterov=True, momentum=0.9, weight_decay=0.1) opt.zero_grad() c2(c1(img).relu()).relu().sum().backward() - check_schedule(opt.schedule_step(), 10) + check_schedule(opt.schedule_step(), 13) def test_sgd_4convs_fuse(self): with Tensor.train(): @@ -1028,7 +1239,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.SGD(nn.state.get_parameters([c1, c2, c3, c4])) opt.zero_grad() c4(c3(c2(c1(img).relu()).relu()).relu()).relu().sum().backward() - check_schedule(opt.schedule_step(), 18) + check_schedule(opt.schedule_step(), 17) def test_sgd_4convs_fuse_conv_bw(self): with Tensor.train(): @@ -1041,7 +1252,7 @@ class TestSchedule(unittest.TestCase): opt = nn.optim.SGD(nn.state.get_parameters([c1, c2, c3, c4])) opt.zero_grad() c4(c3(c2(c1(img).relu()).relu()).relu()).relu().sum().backward() - with Context(FUSE_CONV_BW=1): check_schedule(opt.schedule_step(), 15) + with Context(FUSE_CONV_BW=1): check_schedule(opt.schedule_step(), 14) @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") def test_prefer_half_buffer(self): @@ -1059,13 +1270,18 @@ class TestSchedule(unittest.TestCase): shared = x.sum().half().float() a = shared * 2 b = shared * 3 - sched = check_schedule([a, b], 1) - for si in sched[:-2]: assert all(out.dtype == dtypes.half for out in si.outputs) + sched = check_schedule([a, b], 3) + # store reduceop in half + self.assertEqual(sched[0].bufs[0].dtype, dtypes.half) + # fuse cast with the child kernel + self.assertEqual(sched[1].bufs[0].dtype, dtypes.float) + self.assertEqual(sched[2].bufs[0].dtype, dtypes.float) # reduce a = z.sum(axis=0).half().float().sum(axis=0) sched = check_schedule(a, 2) - for si in sched[:-1]: assert all(out.dtype == dtypes.half for out in si.outputs) + self.assertEqual(sched[0].bufs[0].dtype, dtypes.half) + self.assertEqual(sched[1].bufs[0].dtype, dtypes.float) # expand # expand will realize just after the .float(), so requires change to realize-before-expand @@ -1088,7 +1304,6 @@ class TestSchedule(unittest.TestCase): schedule = check_schedule([b, c], 3) self.assertIs(schedule[0].ast.src[0].src[2].op, Ops.ADD) - # multireduce spec def test_multireduce_simple_chase(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4, 4).realize() @@ -1112,7 +1327,6 @@ class TestSchedule(unittest.TestCase): schedule = check_schedule([d, e], 3) self.assertIs(schedule[0].ast.src[0].src[2].op, Ops.ADD) - # multireduce spec def test_multireduce_push_permute_chase(self): Tensor.manual_seed(0) a = Tensor.randn(4, 4, 4).realize() @@ -1135,7 +1349,6 @@ class TestSchedule(unittest.TestCase): schedule = check_schedule(d, 2) self.assertIs(schedule[0].ast.src[0].src[2].op, Ops.ADD) - # multireduce spec def test_multireduce_push_shrink_chase(self): Tensor.manual_seed(0) a = Tensor.randn(16, 16).realize() @@ -1156,7 +1369,6 @@ class TestSchedule(unittest.TestCase): schedule = check_schedule(b, 2) self.assertIs(schedule[0].ast.src[0].src[2].op, Ops.REDUCE_AXIS) - # multireduce spec def test_multireduce_midreduce_nochase(self): Tensor.manual_seed(0) a = Tensor.randn(16, 16).realize() @@ -1195,6 +1407,7 @@ class TestSchedule(unittest.TestCase): # changed by: multireduce spec # pattern in adam + @unittest.expectedFailure def test_partial_fuse3(self): Tensor.manual_seed(0) a = Tensor.randn(16, 16).realize() @@ -1211,6 +1424,7 @@ class TestSchedule(unittest.TestCase): np.testing.assert_allclose(f.numpy(), b.numpy().sum() - e_np, atol=1e-4, rtol=1e-4) # changed by: multireduce spec + @unittest.expectedFailure def test_partial_fuse4(self): Tensor.manual_seed(0) a = Tensor.randn(16, 16).realize() @@ -1234,7 +1448,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 1)) np.testing.assert_allclose(out.numpy(), np.pad(a.numpy()+b.numpy(), ((0, 1), (0, 1), (0, 1)), constant_values=1.0).sum(), atol=1e-5, rtol=1e-6) - # multireduce spec def test_multireduce_pad_reduce_safe(self): Tensor.manual_seed(0) a = Tensor.randn(3, 4, 5).realize() @@ -1252,7 +1465,6 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(out, 2)) np.testing.assert_allclose(out.numpy(), np.pad(np.log2(a.numpy()), ((0, 1), (0, 1), (0, 1)), constant_values=1.0).sum(), atol=1e-5, rtol=1e-6) - # multireduce spec def test_multireduce_pad_reduce_unsafe(self): Tensor.manual_seed(0) a = Tensor.randn(3, 4, 5).abs().realize() @@ -1292,6 +1504,15 @@ class TestSchedule(unittest.TestCase): run_schedule(check_schedule(d, 2)) np.testing.assert_equal(d.numpy(), np.pad(np.exp2(a.numpy())[:, None, :], ((0, 0), (1, 1), (0, 0)))*2) + def test_fuse_arange_pad_replicate_mode(self): + x = Tensor.empty(3,3,3,3, requires_grad=True) + y = x.pad((-1,2,2,-1), mode="replicate") + dx = y.sum().gradient(x)[0] + with Context(FUSE_ARANGE=1): + sched = check_schedule(dx, 3) + run_schedule(sched) + np.testing.assert_allclose(dx.numpy(), [[[[0.,3.,9.],[0,1.,3.],[0.,0.,0.]]]*3]*3) + # TODO like openpilot with imagef @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") def test_base_change_expand_expand(self): @@ -1328,14 +1549,13 @@ class TestSchedule(unittest.TestCase): p = np.tile(p, 2) np.testing.assert_allclose(tiny_ret, p) - @unittest.skipIf(Device.DEFAULT not in view_supported_devices, "subbuffer not supported") - def test_bitcast_subbufer(self): - x = cast(UOp, Tensor.empty(1, dtype=dtypes.float32).realize().lazydata) - a = x.alu(Ops.EXP2).cast(dtypes.int32, True, allow_buffer_view=True) - b = x.cast(dtypes.int32, True, allow_buffer_view=True) - b = a.alu(Ops.ADD, b) - check_schedule(b, 2) # this should fuse when it makes sense + def test_bitcast_fuses(self): + x = Tensor.empty(1, dtype=dtypes.float32) + a = x.exp2().bitcast(dtypes.int32) + b = x.bitcast(dtypes.int32) + check_schedule(a+b, 1) # this should fuse when it makes sense + @unittest.skip("disabling subbuffer manually isn't supported anymore") def test_bitcast_disable_subbufer(self): x = cast(UOp, Tensor.empty(1, dtype=dtypes.float32).realize().lazydata) a = x.alu(Ops.EXP2).cast(dtypes.int32, True, allow_buffer_view=False) @@ -1352,14 +1572,15 @@ class TestSchedule(unittest.TestCase): def test_conv2d(self): _test_conv2d(7) def test_conv2d_fused(self): _test_conv2d(6, FUSE_CONV_BW=1) - @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + @unittest.skipUnless(is_dtype_supported(dtypes.half) and is_dtype_supported(dtypes.ulong), "need half and ulong") def test_conv2d_half(self): _test_conv2d(7, dtype=dtypes.half) @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "Causes other tests to fail") @unittest.expectedFailure def test_conv2d_fused_half(self): _test_conv2d(5, dtype=dtypes.half) + @unittest.skip("splitting kernels exceeding device buffer count is not yet supported") def _test_buf_cnt(self, cnt:int, allowed:int): - if (m:=BUF_LIMIT.get(Device.DEFAULT)) is None or m != 32: self.skipTest(f"test needs a buf_max of 32 {Device.DEFAULT}") alu = functools.reduce(lambda x,y: x+y, [Tensor.ones((1, 1)).contiguous().realize() for _ in range(cnt-1)]) s = alu.schedule() assert len(s) == allowed @@ -1373,6 +1594,7 @@ class TestSchedule(unittest.TestCase): @unittest.expectedFailure def test_buf_cnt_over_limit_alt(self): self._test_buf_cnt(63, allowed=3) + @unittest.skipIf(getenv("VIZ"), "TODO: VIZ blocks gc") def test_schedule_mem_used(self): base = GlobalCounters.mem_used Tensor.ones(256).contiguous().realize() @@ -1388,11 +1610,11 @@ class TestSchedule(unittest.TestCase): def test_const_schedule(self): constv = Tensor.empty(2, 2).lazydata.const_like(10) - self.assertEqual(len(create_schedule([constv])), 0) + check_schedule(constv, 0) def test_const_schedule_contig(self): constv = Tensor.empty(2, 2).lazydata.const_like(10).contiguous() - self.assertEqual(len(create_schedule([constv])), 1) + check_schedule(constv, 1) @unittest.skipIf(Device.DEFAULT != "GPU", "image only supported on GPU") def test_image_matmul(self): @@ -1400,8 +1622,11 @@ class TestSchedule(unittest.TestCase): x = Tensor.randn((9, 9)).realize() y = Tensor.randn((9, 9)).realize() out = x@y - run_schedule(check_schedule(out, 4)) + run_schedule(check_schedule(out, 3)) np.testing.assert_allclose(out.numpy(), x.numpy()@y.numpy(), atol=1e-4, rtol=1e-4) + self.assertIsInstance(out.dtype, ImageDType) + self.assertIsNotNone(out.lazydata.base.realized) + self.assertIsInstance(out.lazydata.base.realized.dtype, ImageDType) def _test_fusion(self, shapes, f, cnt): with Context(DEBUG=0, TRACK_MATCH_STATS=0): args = [Tensor.randn(s).realize() for s in shapes] @@ -1427,15 +1652,51 @@ class TestSchedule(unittest.TestCase): def test_late_fusion_post_expand(self): self._test_fusion([(32, 32)], lambda a:a-a.sum(1), 2) + def test_cast_padded_view(self): + a = Tensor.arange(4).reshape(1, 4) + casted_view = a.pad(((0, 1), (0, 0))).cast(dtypes.float) + casted_view.realize() + self.assertEqual(casted_view.lazydata.base.realized.size, 4) + realized_view = casted_view.contiguous().realize() + self.assertEqual(realized_view.lazydata.base.realized.size, 8) + self.assertListEqual(realized_view.tolist(), [[0.0, 1.0, 2.0, 3.0], [0.0, 0.0, 0.0, 0.0]]) + + # NOTE: we only reorder CAST if it's an EXPAND + def test_cast_after_shrink(self): + a = Tensor.arange(4).reshape(1, 4) + casted_view = a.shrink(((0, 1), (0, 2))).cast(dtypes.float) + casted_view.realize() + self.assertEqual(casted_view.lazydata.base.realized.size, 2) + realized_view = casted_view.contiguous().realize() + self.assertEqual(realized_view.lazydata.base.realized.size, 2) + self.assertListEqual(realized_view.tolist(), [[0, 1]]) + + def test_cast_const_view(self): + a = Tensor.ones((4, 4), dtype=dtypes.float32) + casted_view = a.cast(dtypes.int32) + run_schedule(check_schedule(casted_view, 0)) + self.assertIsNone(casted_view.lazydata.base.realized) + realized_const_view = casted_view.contiguous() + run_schedule(check_schedule(realized_const_view, 1)) + self.assertListEqual(realized_const_view.tolist(), [[1, 1, 1, 1], [1, 1, 1, 1], [1, 1, 1, 1], [1, 1, 1, 1]]) + + def test_cast_padded_const(self): + a = Tensor(1, dtype=dtypes.int32).reshape(1, 1).pad(((1, 1), None)) + casted_view = a.cast(dtypes.float32) + run_schedule(check_schedule(casted_view, 0)) + realized_const_view = casted_view.contiguous() + run_schedule(check_schedule(realized_const_view, 1)) + self.assertListEqual(realized_const_view.tolist(), [[0], [1], [0]]) + class TestIndexing(unittest.TestCase): def check_schedule(self, xt:Union[Tensor,List[Tensor]], cnt:int): with Context(FUSE_ARANGE=getenv("FUSE_ARANGE", 1)): lst = [xt] if isinstance(xt, Tensor) else xt s = Tensor.schedule(*lst) - kernels = [si for si in s if si.ast.op is Ops.SINK] - for si in kernels: verify_ast(si.ast) - run_schedule(s.copy()) + lowered = [x[1] for x in lower_schedule(s.copy())] + kernels = [ei for ei in list(lowered) if isinstance(ei.prg, CompiledRunner)] if FUSE_ARANGE: self.assertEqual(len(kernels), cnt) + for ei in lowered: ei.run(do_update_stats=True) return s def test_simple_indexing(self): @@ -1445,11 +1706,10 @@ class TestIndexing(unittest.TestCase): self.check_schedule(xt, 2) np.testing.assert_equal(xt.numpy(), X.numpy()[idxs.numpy()]) - @unittest.skip("TODO: support pads in graph_rewrite") def test_simple_indexing_alt(self): X = Tensor.arange(16).reshape(4, 4) xt = X[[1, 2], [1, 2]] - self.check_schedule(xt, 3) + self.check_schedule(xt, 5) np.testing.assert_equal(xt.numpy(), (np.arange(16).reshape(4, 4))[[1, 2], [1, 2]]) def test_advanced_indexing(self): @@ -1458,18 +1718,16 @@ class TestIndexing(unittest.TestCase): self.check_schedule(xt, 2) np.testing.assert_equal(xt.numpy(), (np.arange(10)+1)[[0]]) - @unittest.expectedFailure def test_advanced_indexing_alt(self): X = Tensor.arange(6).reshape(3, 2)+1 xt = X[[Tensor([2]), Tensor([1])]] self.check_schedule(xt, 6) np.testing.assert_equal(xt.numpy(), 6) - @unittest.skip("TODO: support pads in graph_rewrite") def test_advanced_simple_indexing_combined(self): X = Tensor.arange(16).reshape(4, 4) xt = X[1:2, [1, 2]] - self.check_schedule(xt, 2) + self.check_schedule(xt, 4) def test_push_through_reshape(self): Tensor.manual_seed(0) @@ -1482,9 +1740,9 @@ class TestIndexing(unittest.TestCase): Tensor.manual_seed(0) a = Tensor.arange(4,) b = Tensor.randn(4, 4).realize() - out = a+b + out = (a+b).sum() self.check_schedule(out, 1) - np.testing.assert_allclose(out.numpy(), np.arange(4)+b.numpy()) + np.testing.assert_allclose(out.numpy(), (np.arange(4)+b.numpy()).sum(), atol=1e-5) def test_argmin(self): Tensor.manual_seed(0) @@ -1503,18 +1761,25 @@ class TestIndexing(unittest.TestCase): def test_arange_transposed(self): Tensor.manual_seed(0) x = Tensor.randint(4, 1).realize() - a = (Tensor.arange(4,)*x).T + a = ((Tensor.arange(4,)*x).T).sum() self.check_schedule(a, 1) - np.testing.assert_equal(a.numpy(), (np.arange(4)*x.numpy()).T) + np.testing.assert_equal(a.numpy(), (np.arange(4)*x.numpy()).T.sum()) + + def test_div_padded_arange(self): + x = Tensor.full((2,2), 16) + y = x.idiv(Tensor.linspace(2, 8, steps=4, dtype=dtypes.int).reshape(2,2)).pad(((1,1), (1,1))) + out = y.sum(axis=1) + with Context(FUSE_ARANGE=1): run_schedule(check_schedule(out, 2)) + self.assertListEqual(out.tolist(), [0, 12, 4, 0]) def test_arange_transposed_descendants(self): Tensor.manual_seed(0) x = Tensor.randint(4, 1).realize() a = (Tensor.arange(4,)*x).T b = Tensor.randint(4, 4).realize() - out = a+b + out = (a+b).sum() self.check_schedule(out, 1) - np.testing.assert_equal(out.numpy(), (np.arange(4)*x.numpy()).T+b.numpy()) + np.testing.assert_equal(out.numpy(), ((np.arange(4)*x.numpy()).T+b.numpy()).sum()) def test_arange_index(self): Tensor.manual_seed(0) @@ -1524,12 +1789,20 @@ class TestIndexing(unittest.TestCase): self.check_schedule(out, 1) np.testing.assert_allclose(out.numpy(), (x.numpy()+np.arange(10)[2]).sum(), atol=1e-5, rtol=1e-6) + def test_arange_index_shrink(self): + Tensor.manual_seed(0) + with Context(TRACK_MATCH_STATS=0): + x = Tensor.randn(11).realize() + a = Tensor.arange(22) + out = (x + a[:11]).sum() + self.check_schedule(out, 1) + def test_arange_index_contiguous(self): Tensor.manual_seed(0) x = Tensor.randn(5, 2).realize() a = Tensor.arange(10).contiguous() out = (x + a[2]).sum() - self.check_schedule(out, 2) + self.check_schedule(out, 3) np.testing.assert_allclose(out.numpy(), (x.numpy()+np.arange(10)[2]).sum(), atol=1e-5, rtol=1e-6) def test_arange_index_child(self): @@ -1545,7 +1818,7 @@ class TestIndexing(unittest.TestCase): x = Tensor.randn(5, 2).realize() a = (Tensor.arange(10)+1).contiguous() out = (x + a[2]).sum() - self.check_schedule(out, 2) + self.check_schedule(out, 3) np.testing.assert_allclose(out.numpy(), (x.numpy()+(np.arange(10)+1)[2]).sum(), atol=1e-5, rtol=1e-6) def test_arange_childless_base(self): @@ -1572,34 +1845,36 @@ class TestIndexing(unittest.TestCase): a[0] = 6 np.testing.assert_equal(a.numpy(), [6., 2., 3., 4.]) - @unittest.skipUnless(Device.DEFAULT in view_supported_devices, "need view") + @unittest.skip("BUFFER_VIEW no longer supported on non-disk devices") def test_arange_view_op(self): a = Tensor.arange(12).reshape(4, 3).shrink(((1, 2), (1, 3))).contiguous() sched = self.check_schedule(a, 1) self.assertIs(sched[1].ast.op, Ops.BUFFER_VIEW) np.testing.assert_equal(a.numpy(), [[4, 5]]) - @unittest.skipIf(Device.DEFAULT == "CLANG", "tests copy from ext device") + @unittest.skipIf(Device.DEFAULT == "CPU", "tests copy from ext device") def test_arange_shrink_copy(self): - a = Tensor.arange(12).reshape(4, 3).shrink(((1, 2), (1, 3))).to("CLANG") - sched = self.check_schedule(a, 1) + a = Tensor.arange(12).reshape(4, 3).shrink(((1, 2), (1, 3))).to("CPU") + sched = self.check_schedule(a, 2) # NOTE: there is a contiguous between REDUCE_AXIS and COPY self.assertIs(sched[-1].ast.op, Ops.COPY) np.testing.assert_equal(a.numpy(), [[4, 5]]) - @unittest.skipIf(Device.DEFAULT == "CLANG", "tests copy from ext device") + @unittest.skipIf(Device.DEFAULT == "CPU", "tests copy from ext device") def test_arange_expand_copy(self): - a = Tensor.arange(4).reshape(2, 2, 1).expand(2, 2, 2).contiguous().to("CLANG") - sched = self.check_schedule(a, 1) - self.assertIs(sched[1].ast.op, Ops.COPY) + a = Tensor.arange(4).reshape(2, 2, 1).expand(2, 2, 2).contiguous().to("CPU") + sched = self.check_schedule(a, 2) # NOTE: there is a contiguous between REDUCE_AXIS and COPY + self.assertIs(sched[2].ast.op, Ops.COPY) + self.assertIs(sched[1].ast.src[0].src[2].op, Ops.LOAD) self.assertIs(sched[0].ast.src[0].src[2].op, Ops.ADD) np.testing.assert_equal(a.numpy(), [[[0, 0], [1, 1]], [[2, 2], [3, 3]]]) - @unittest.skip("TODO: support pads in graph_rewrite") - #@unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") + @unittest.skipUnless(is_dtype_supported(dtypes.half), "need half") def test_precompute_freqs_cis(self): - args = {"dim":32 if CI else 128, "end":2048 if CI else 8192, "theta":10000, "dtype":dtypes.half} + from extra.models.llama import precompute_freqs_cis + args = {"dim":32 if CI else 128, "end":2048 if CI else 8192, "theta":10000} fused = precompute_freqs_cis(**args) - self.check_schedule(fused, 1) + with Context(FUSE_ARANGE=1): + run_schedule(check_schedule(fused, 3)) if getenv("CHECK", 1): ref = precompute_freqs_cis(**args) run_schedule(check_schedule(ref, 3)) @@ -1641,6 +1916,7 @@ class TestIndexing(unittest.TestCase): loss_ref = torch.nn.CrossEntropyLoss()(torch.tensor(yt.numpy()), torch.tensor(Y_train.numpy())[torch.tensor(samples.numpy())]) np.testing.assert_allclose(loss_fused, loss_ref.numpy(), atol=1e-6, rtol=1e-6) + @unittest.expectedFailure def test_arange_fuse_grouped_children(self): X = Tensor.randn(4, 4).realize() r = (X+Tensor.arange(16).reshape(4, 4)).sum() @@ -1651,14 +1927,13 @@ class TestIndexing(unittest.TestCase): np.testing.assert_allclose(out0.numpy(), r_ref+2, rtol=2e-7) np.testing.assert_allclose(out1.numpy(), r_ref+3, rtol=2e-7) - @unittest.expectedFailure - def test_fold_arange_view(self): + def test_dont_fold_arange_contiguous_view(self): X = Tensor.randn(4, 4).realize() r = (X+Tensor.arange(16).reshape(4, 4).contiguous()).sum(1, keepdim=True) - self.check_schedule([r], 1) - np.testing.assert_allclose(r.numpy(), (X.numpy()+np.arange(16).reshape(4, 4)).sum(1, keepdims=True)) + self.check_schedule([r], 2) + np.testing.assert_allclose(r.numpy(), (X.numpy()+np.arange(16).reshape(4, 4)).sum(1, keepdims=True), atol=1e-5, rtol=1e-6) - @unittest.expectedFailure + @unittest.skip("multi output isn't supported") def test_multiview_arange_children(self): X = Tensor.randn(2,3,4,4).numpy() with Context(FUSE_ARANGE=1): @@ -1670,269 +1945,134 @@ class TestIndexing(unittest.TestCase): def test_recursive_swizzle(self): a = Tensor([1,2,3,4]).realize() for _ in range(24): a = a + a - ast = a.schedule()[0].ast - swizzle = ast.src[0].src[2].reshape((4, 1)) - new_uop = swizzle_rewrite(swizzle) + new_uop = swizzle_rewrite(a.lazydata.reshape((4, 1))) self.assertEqual(new_uop.st, ShapeTracker.from_shape((4,)).reshape((4, 1))) self.assertEqual(swizzle_cnt(new_uop), 0) def test_no_rewrite_elementwise(self): - bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), i) for i in range(3)] - ld1 = UOp(Ops.LOAD, dtypes.int, (bufs[1], ShapeTracker.from_shape((32, 32)).to_uop())) - ld2 = UOp(Ops.LOAD, dtypes.int, (bufs[2], ShapeTracker.from_shape((32, 32)).to_uop())) - sink = UOp(Ops.SINK, dtypes.void, (UOp(Ops.STORE, dtypes.void, (bufs[0], ShapeTracker.from_shape((32, 32)).to_uop(), ld1+ld2)),)) - rsink = graph_rewrite(sink, view_right) - self.assertEqual(rsink.key, sink.key) + a = Tensor.empty(32, 32) + b = Tensor.empty(32, 32) + sink = (a+b).schedule()[0].ast + self.assertEqual(swizzle_cnt(sink), 0) def test_simple_store_reshape(self): - bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), i) for i in range(2)] - ld = UOp(Ops.LOAD, dtypes.int, (bufs[1], ShapeTracker.from_shape((32, 32)).to_uop())) - r = UOp(Ops.REDUCE_AXIS, dtypes.int, (ld,), (Ops.ADD, (0, 1))) - r = UOp(Ops.VIEW, dtypes.int, (r,), ShapeTracker.from_shape(())) - r = r + 2 - sink = UOp(Ops.SINK, dtypes.void, (UOp(Ops.STORE, dtypes.void, (bufs[0], ShapeTracker.from_shape(()).to_uop(), r)),)) - rsink = graph_rewrite(sink, view_right) - # this AST first needs to swizzle, but it doesn't have implicit movementops - with self.assertRaisesRegex(AssertionError, "swizzle"): verify_ast(sink) - verify_ast(rsink) + a = Tensor.empty(32, 32).sum(axis=1)+Tensor.empty(1,32) + ast = a.schedule()[0].ast + self.assertEqual(ast.shape, (32, 1)) + self.assertEqual(a.lazydata.shape, (1, 32)) def test_no_reshape_reduceop(self): - bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), i) for i in range(2)] - ld = UOp(Ops.LOAD, dtypes.int, (bufs[1], ShapeTracker.from_shape((32, 32)).to_uop())) - r = UOp(Ops.REDUCE_AXIS, dtypes.int, (ld,), (Ops.ADD, (0, 1))) - sink = UOp(Ops.SINK, dtypes.void, (UOp(Ops.STORE, dtypes.void, (bufs[0], ShapeTracker.from_shape((1, 1)).to_uop(), r)),)) - rsink = graph_rewrite(sink, view_right) - verify_ast(sink) - self.assertEqual(sink.key, rsink.key) + a = Tensor.empty(32, 32).sum(axis=(1,)).contiguous() + ast = a.schedule()[0].ast + self.assertEqual(ast.shape, (32, 1)) + self.assertEqual(a.lazydata.shape, (32,)) @track_rewrites(named=True) def swizzle_rewrite(u:UOp) -> UOp: return graph_rewrite(graph_rewrite(u, view_left), view_right) - -def swizzle_cnt(u:UOp) -> int: return len([x for x in u.toposort if x.op is Ops.VIEW and len(x.src) != 0]) +def swizzle_cnt(u:UOp) -> int: return len([x for x in u.toposort() if x.op is Ops.VIEW and len(x.src) != 0 and x.src[0].op is not Ops.BUFFER]) class TestSwizzle(unittest.TestCase): def test_swizzle_simple(self): - sink = UOp(Ops.SINK, dtypes.void, arg=None, src=( - UOp(Ops.STORE, dtypes.void, arg=None, src=( - UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), arg=0, src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 1), strides=(0, 0), offset=0, mask=None, contiguous=True),)), src=()), # noqa: E501 - UOp(Ops.REDUCE_AXIS, dtypes.int, arg=(Ops.ADD, (0, 1)), src=( - UOp(Ops.ADD, dtypes.int, arg=None, src=( - UOp(Ops.VIEW, dtypes.int, arg=ShapeTracker(views=(View(shape=(32, 32), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=( # noqa E501 - UOp(Ops.REDUCE_AXIS, dtypes.int, arg=(Ops.ADD, (0, 1)), src=( - UOp(Ops.LOAD, dtypes.int, arg=None, src=( - x8:=UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), arg=1, src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32, 32), strides=(32, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)), # noqa E501 - UOp(Ops.LOAD, dtypes.int, arg=None, src=( - x8, - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(32, 32), strides=(32, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)),)) # noqa E501 - sink = swizzle_rewrite(sink) - k = Kernel(sink) - p = k.to_program() - a = Tensor.randint(32, 32).realize() - b = Tensor.empty((), dtype=dtypes.int).realize() - CompiledRunner(p).exec([b.lazydata.buffer, a.lazydata.buffer]) - expected_out = (a.numpy() + a.numpy().sum()).sum() - np.testing.assert_equal(b.numpy(), expected_out) + Tensor.manual_seed(0) + with Context(DEBUG=0, TRACK_MATCH_STATS=0): + a = Tensor.randint(32, 32).realize() + r = (a+a).sum(1).sum(0) + # double reduce collapses to a single reduce + with Context(DONT_GROUP_REDUCES=1): + run_schedule(check_schedule(r, 1)) + self.assertEqual(r.numpy(), (a.numpy()+a.numpy()).sum(1).sum(0)) def test_single_swizzle(self): - # ast in tensor style - a = Tensor.randint(4,).realize() - expected_out = a.numpy().sum(0)+1 - # LazyBuffer to pre-rewrite AST - bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), i) for i in range(2)] - ld = UOp(Ops.LOAD, dtypes.int, (bufs[1], ShapeTracker.from_shape((4,)).to_uop())) - r = UOp(Ops.REDUCE_AXIS, dtypes.int, (ld,), (Ops.ADD, (0,))) - swizzle_r = UOp(Ops.VIEW, dtypes.int, (r,), unwrap(r.st).reshape(())) - alu = swizzle_r+1 - sink = UOp(Ops.SINK, dtypes.void, (UOp(Ops.STORE, dtypes.void, (bufs[0], ShapeTracker.from_shape(()).to_uop(), alu,),),)) - # graph rewrite - sink = swizzle_rewrite(sink) - # verify output - k = Kernel(sink) - p = k.to_program() - b = Tensor.empty((1,), dtype=dtypes.int).realize() - CompiledRunner(p).exec([b.lazydata.buffer, a.lazydata.buffer]) - np.testing.assert_equal(b.numpy(), expected_out) + Tensor.manual_seed(0) + with Context(DEBUG=0, TRACK_MATCH_STATS=0): + a = Tensor.randint(4, 1).realize() + b = Tensor.ones((1, 1), dtype=a.dtype).contiguous().realize() + # ADD(REDUCE(RESHAPE(LOAD)), LOAD) to ADD(REDUCE(RESHAPE(LOAD))), RESHAPE(LOAD) + r = a.sum(0)+b + run_schedule(check_schedule(r, 1)) + self.assertEqual(r.numpy(), a.numpy().sum(0)+1) def test_double_swizzle_possible(self): - # ast in tensor style - Tensor.manual_seed(0) - a = Tensor.randint(4,).realize() - b = Tensor.randint(4,).realize() - expected_out = a.numpy().sum(0)+b.numpy().sum(0)+2 - # LazyBuffer to pre-rewrite AST - bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), i) for i in range(3)] - ld1 = UOp(Ops.LOAD, dtypes.int, (bufs[1], ShapeTracker.from_shape((4,)).to_uop())) - r1 = UOp(Ops.REDUCE_AXIS, dtypes.int, (ld1,), (Ops.ADD, (0,))) - ld2 = UOp(Ops.LOAD, dtypes.int, (bufs[2], ShapeTracker.from_shape((4,)).to_uop())) - r2 = UOp(Ops.REDUCE_AXIS, dtypes.int, (ld2,), (Ops.ADD, (0,))) - alu = UOp(Ops.VIEW, r1.dtype, (r1,), ShapeTracker.from_shape(()))+UOp(Ops.VIEW, r2.dtype, (r2,), ShapeTracker.from_shape(())) - sink = UOp(Ops.SINK, dtypes.void, (UOp(Ops.STORE, dtypes.void, (bufs[0], ShapeTracker.from_shape(()).to_uop(), alu+2,),),)) # noqa: E501 - # graph rewrite - sink = swizzle_rewrite(sink) - # verify output - k = Kernel(sink) - p = k.to_program() - c = Tensor.empty((1,), dtype=dtypes.int).realize() - CompiledRunner(p).exec([c.lazydata.buffer, a.lazydata.buffer, b.lazydata.buffer]) - np.testing.assert_equal(c.numpy(), expected_out) - - def test_swizzle_rewrite_alt(self): - swizzle = UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(2, 3, 3, 65, 3, 65), strides=(103788, 34596, 3, 558, 1, 9), offset=0, mask=((0, 2), (0, 3), (0, 3), (0, 62), (0, 3), (0, 62)), contiguous=False), View(shape=(2, 3, 256, 256), strides=(114075, 38025, 195, 1), offset=0, mask=((0, 2), (0, 3), (0, 195), (0, 195)), contiguous=False), View(shape=(1, 2, 1, 3, 4, 64, 4, 64), strides=(0, 196608, 0, 65536, 16384, 256, 64, 1), offset=0, mask=None, contiguous=True))), src=( # noqa: E501 - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (3,)), src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=1, src=()), - UOp(Ops.VIEW, dtypes.void, arg=(ld_st:=ShapeTracker(views=(View(shape=(2, 1, 3, 16, 62, 62, 3, 3), strides=(0, 0, 9, 27, 0, 0, 3, 1), offset=0, mask=None, contiguous=False),))), src=()),)),)),)) # noqa: E501 - # there's an UNROLL pushing through the REDUCE_AXIS - self.assertGreater(prod(swizzle.st.shape), prod(swizzle.src[0].st.shape)) - ret = swizzle_rewrite(swizzle) - # UNROLL is rewritten - self.assertEqual(prod(ret.st.shape), prod(ret.src[0].st.shape)) - # and pushed to the LOAD - new_load_st = unwrap([x for x in ret.toposort if x.op is Ops.VIEW][0].st) - self.assertGreater(prod(new_load_st.shape), prod(ld_st.shape)) - self.assertEqual(new_load_st.views[0].strides, (0, 9, 3, 0, 1, 0, 27)) + Tensor.manual_seed(0) + with Context(DEBUG=0, TRACK_MATCH_STATS=0): + a = Tensor.randint(4,).realize() + b = Tensor.randint(4,).realize() + # parallel reduce! + add = a.sum(0)+b.sum(0) + with Context(DONT_GROUP_REDUCES=1): + run_schedule(check_schedule(add, 1)) + self.assertEqual(add.numpy(), a.numpy().sum(0)+b.numpy().sum(0)) + + @unittest.skip("TODO: how do we express the norm") + def test_softmax_one_kernel(self): + Tensor.manual_seed(0) + with Context(DEBUG=0, TRACK_MATCH_STATS=0): + a = Tensor.randn(32, 32).realize() + t = a.softmax() + with Context(DONT_GROUP_REDUCES=1, DONT_REALIZE_EXPAND=1): + check_schedule(t, 1) - def test_permute_rewrite(self): - sink = UOp(Ops.STORE, dtypes.void, arg=None, src=( - x1:=UOp(Ops.BUFFER, dtypes.float, arg=(1, ('METAL', 16384, dtypes.float)), src=()), - x2:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 32, 32, 16), strides=(0, 512, 16, 1), offset=0, mask=None, contiguous=True),)), src=()), - UOp(Ops.CONTIGUOUS, dtypes.float, arg=None, src=( - x1, - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 32, 32, 16), strides=(0, 32, 1, 1024), offset=0, mask=None, contiguous=False),)), src=( - UOp(Ops.ADD, dtypes.float, arg=None, src=( - UOp(Ops.ADD, dtypes.float, arg=None, src=( - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 16, 32, 32), strides=(0, 1, 512, 16), offset=0, mask=None, contiguous=False),)), src=( - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (7, 8)), src=( - UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 32, 32, 1, 1, 4, 4, 4, 4, 1, 1), strides=(0, 512, 16, 0, 0, 0, 0, 4, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=( - x11:=UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(2, ('METAL', 16384, dtypes.float)), src=()), - x2,)),)), - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 32, 32, 1, 1, 4, 4, 4, 4, 1, 1), strides=(0, 0, 0, 0, 0, 64, 1, 16, 4, 0, 0), offset=0, mask=None, contiguous=False),)), src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(8, ('METAL', 256, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(4, 1, 4, 1, 4, 4), strides=(64, 0, 16, 0, 4, 1), offset=0, mask=None, contiguous=True),)), src=()),)),)),)),)),)), - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 16, 32, 32), strides=(0, 1, 0, 0), offset=0, mask=None, contiguous=False),)), src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(10, ('METAL', 16, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(16,), strides=(1,), offset=0, mask=None, contiguous=True),)), src=()),)),)),)), - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(1, 16, 32, 32), strides=(0, 1, 512, 16), offset=0, mask=None, contiguous=False),)), src=( - x11,)),)),)),)),)) - ret = swizzle_rewrite(sink) - self.assertEqual(swizzle_cnt(ret), 0) + def test_argmax_one_kernel(self): + Tensor.manual_seed(0) + with Context(DEBUG=0, TRACK_MATCH_STATS=0): + a = Tensor.randn(10, 20).realize() + t = a.argmax(0) + with Context(DONT_GROUP_REDUCES=1, DONT_REALIZE_EXPAND=1): t.realize() - @unittest.expectedFailure - def test_fuse_conv2_relu_bw(self): - # fuse (relu bw, conv2d, conv2d bw, relu) - sink = UOp(Ops.SINK, dtypes.void, arg=None, src=( - UOp(Ops.STORE, dtypes.void, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(10, ('METAL', 128, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 16, 2, 2), strides=(64, 4, 2, 1), offset=0, mask=None, contiguous=True),)), src=()), - UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.CAST, dtypes.float, arg=None, src=( - UOp(Ops.CMPLT, dtypes.bool, arg=None, src=( - x6:=UOp(Ops.WHERE, dtypes.float, arg=None, src=( - UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 16, 2, 2), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - x9:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=()), - x9,)), - UOp(Ops.MAX, dtypes.float, arg=None, src=( - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(2, 16, 2, 2), strides=(64, 4, 2, 1), offset=0, mask=None, contiguous=True),)), src=( - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (5, 6, 7)), src=( - UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(9, ('METAL', 96, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 16, 2, 2, 3, 3, 3), strides=(48, 0, 0, 4, 1, 16, 4, 1), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.PRELOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(16, ('METAL', 432, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 1, 16, 2, 2, 3, 3, 3), strides=(0, 0, 27, 0, 0, 9, 3, 1), offset=0, mask=None, contiguous=False),)), src=()),)),)),)),)), - x6,)),)),)), - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(2, 16, 2, 2), strides=(64, 4, 2, 1), offset=0, mask=None, contiguous=True),)), src=( - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (4, 6)), src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(18, ('METAL', 128, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 16, 2, 3, 2, 3), strides=(64, 4, 2, 0, 1, 0), offset=0, mask=((0, 2), (0, 16), (0, 2), (0, 1), (0, 2), (0, 1)), contiguous=False), View(shape=(1, 2, 1, 16, 3, 2, 3, 2), strides=(0, 576, 0, 36, 12, 6, 2, 1), offset=0, mask=None, contiguous=True))), src=()),)),)),)),)),)),)) - ret = swizzle_rewrite(sink) - self.assertEqual(swizzle_cnt(ret), 0) + def test_swizzle_reduceop(self): + Tensor.manual_seed(0) + x = Tensor.randn(4,4).realize() + y = Tensor.randn(4,4,4).realize() + out = x.reshape(4,4,1).expand(4,4,4).sum(axis=(1,))+y + with Context(DONT_REALIZE_EXPAND=1, DONT_GROUP_REDUCES=1): + run_schedule(check_schedule(out, 1)) + np.testing.assert_allclose(out.numpy(), np.tile(x.numpy().reshape(4,4,1), (1,1,4)).sum(axis=1)+y.numpy()) - @unittest.expectedFailure + def test_permute_rewrite(self): + x = Tensor.randn(4, 4, 16).realize() + y = Tensor.randn(4, 1, 16).realize() + z = Tensor.randn(4, 4, 1).realize() + t = (x*y).sum(axis=(0, 2)).reshape(1, 4, 1).permute(0, 2, 1)+z + with Context(DONT_GROUP_REDUCES=1, DONT_REALIZE_EXPAND=1): run_schedule(check_schedule(t, 1)) + t_np = (x.numpy()*y.numpy()).sum(axis=(0, 2)).reshape(1, 4, 1).transpose(0, 2, 1)+z.numpy() + np.testing.assert_allclose(t.numpy(), t_np, atol=1e-6, rtol=1e-3) + + @unittest.skip("TODO: this swizzle isn't resolvable when there's a mask") def test_swizzle_failure_permute(self): - sink = UOp(Ops.SINK, dtypes.void, arg=None, src=( - UOp(Ops.STORE, dtypes.void, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(20, ('METAL', 65, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(1, 65), strides=(0, 1), offset=0, mask=None, contiguous=True),)), src=()), - UOp(Ops.ADD, dtypes.float, arg=None, src=( - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (0,)), src=( - UOp(Ops.ADD, dtypes.float, arg=None, src=( - x6:=UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.ADD, dtypes.float, arg=None, src=( - UOp(Ops.PRELOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(8, ('METAL', 2925, dtypes.float)), src=()), - x10:=UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(45, 65), strides=(65, 1), offset=0, mask=None, contiguous=True),)), src=()),)), - UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x12:=UOp(Ops.VALID, dtypes.bool, arg=None, src=( - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(45, 65), strides=(0, 0), offset=0, mask=None, contiguous=False),)), src=()),)), - UOp(Ops.CONST, dtypes.float, arg=1.0, src=()), - x15:=UOp(Ops.CONST, dtypes.float, arg=0.0, src=()),)),)), - UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x12, - UOp(Ops.CONST, dtypes.float, arg=0.0003418803389649838, src=()), - x15,)),)), - x6,)),)), - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (0,)), src=( - UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.WHERE, dtypes.float, arg=None, src=( - x12, - UOp(Ops.CONST, dtypes.float, arg=-1.0, src=()), - x15,)), - UOp(Ops.MUL, dtypes.float, arg=None, src=( - UOp(Ops.PRELOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(2, ('METAL', 2925, dtypes.float)), src=()), - x10,)), - UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(45, 65), strides=(1, 89), offset=44, mask=None, contiguous=False),)), src=( - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (2,)), src=( - UOp(Ops.LOAD, dtypes.float, arg=None, src=( - UOp(Ops.BUFFER, dtypes.float, arg=(4, ('METAL', 2925, dtypes.float)), src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(65, 45, 90), strides=(1, 0, 65), offset=0, mask=((0, 65), (0, 45), (0, 45)), contiguous=False), View(shape=(65, 4094), strides=(4050, 1), offset=0, mask=((0, 65), (0, 4050)), contiguous=False), View(shape=(1, 65, 46, 89), strides=(0, 4094, 89, 1), offset=0, mask=None, contiguous=True))), src=()),)),)),)),)),)),)),)),)),)) - ret = swizzle_rewrite(sink) - self.assertEqual(swizzle_cnt(ret), 0) - - def test_non_contiguous_view_simplify(self): - st = ShapeTracker(views=(View(shape=(2048, 2048), strides=(1, 2048), offset=0, mask=None, contiguous=False),)) - a = UOp(Ops.LOAD, dtypes.char, (UOp.new_buffer(Device.DEFAULT, 4194304, dtypes.char), st.to_uop())) - ret = swizzle_rewrite(a.view(st)) - self.assertEqual(ret.st_arg, st+st) - - def test_contiguous_view_simplify(self): - base = ShapeTracker.from_shape((32, 32)) - a = UOp(Ops.LOAD, dtypes.char, (UOp.new_buffer(Device.DEFAULT, base.size, dtypes.char), base.to_uop())) - swizzle = a.reshape((64, 16)) - swizzle = graph_rewrite(swizzle, remove_movement_ops) - self.assertEqual(swizzle_cnt(swizzle), 1) - ret = swizzle_rewrite(swizzle) - self.assertEqual(ret.st_arg, base.reshape((64, 16))) # late rewrite - reswizzle = a.reshape((64, 16)).reshape((32, 32)) - self.assertEqual(swizzle_cnt(reswizzle), 0) # instant rule - ret = swizzle_rewrite(reswizzle) - self.assertIs(ret, reswizzle) - - def test_late_fusion_post_permute_simpler(self): - base = ShapeTracker.from_shape((32, 16, 1)) - start = UOp(Ops.LOAD, dtypes.char, (UOp.new_buffer(Device.DEFAULT, base.size, dtypes.char), base.to_uop())) - r = start.expand((32, 16, 16)).r(Ops.ADD, (2,)) - add = r.reshape((16, 32, 1)) + UOp.const_with_shape(r.dtype, 0, (16, 32, 1)) - self.assertEqual(add.st, ShapeTracker.from_shape((16, 32, 1))) - to_store = add.permute((1, 0, 2)).contiguous() - to_store = graph_rewrite(to_store, remove_movement_ops) - self.assertEqual(to_store.st, ShapeTracker.from_shape((32, 16, 1))) - self.assertEqual(to_store.src[0].st, add.st.permute((1, 0, 2))) - self.assertIs(to_store.src[0].op, Ops.VIEW) - ret = graph_rewrite(to_store, view_left) - self.assertEqual(swizzle_cnt(ret), 1) + a = Tensor.empty(45,65).T.reshape(65,1,45).pad((None,None,(0,45))).expand(65,45,90) + b = Tensor.empty(45,65) + a_reduce = a.sum(axis=(2,), keepdim=True).sum(axis=(1,)) + b_reduce = b.sum(axis=(0,)) + t = a_reduce+b_reduce + with Context(DONT_GROUP_REDUCES=1, DONT_REALIZE_EXPAND=1): run_schedule(check_schedule(t, 1)) + + def test_parallel_reduce_possible(self): + Tensor.manual_seed(0) + x = Tensor.randn(4, 2, 2).realize() + y = Tensor.randn(4, 2, 2).realize() + t = x.sum(axis=1)+y.sum(axis=1) + with Context(DONT_GROUP_REDUCES=1): run_schedule(check_schedule(t, 1)) + np.testing.assert_allclose(t.numpy(), x.numpy().sum(axis=1)+y.numpy().sum(axis=1), atol=1e-6, rtol=1e-3) + + # kernels can only have 1 or n in each dim + @unittest.expectedFailure + def test_dont_parallelize_different_n(self): + Tensor.manual_seed(0) + x = Tensor.randn(4, 2, 2).realize() + y = Tensor.randn(4, 3, 2).realize() + t = x.sum(axis=1)+y.sum(axis=1) + with Context(DONT_GROUP_REDUCES=1): run_schedule(check_schedule(t, 1)) + np.testing.assert_allclose(t.numpy(), x.numpy().sum(axis=1)+y.numpy().sum(axis=1), atol=1e-6, rtol=1e-3) + + def test_unsafe_pad(self): + x = Tensor.full((2,2), 1.0).contiguous() + y = x*x.sum((1,)).reciprocal() + t = y.pad(((0,1),None)) + run_schedule(check_schedule(t, 3)) + np.testing.assert_equal(t.numpy(), [[0.5, 0.5], [0.5, 0.5], [0., 0.]]) def store_val(si:ScheduleItem): return si.ast.src[0].src[2] +zero_pm = UPat(Ops.CONST, arg=0) class TestView(unittest.TestCase): def test_all_masked_out(self): # start with non CONST Ops @@ -1940,8 +2080,7 @@ class TestView(unittest.TestCase): # all masked out, degrades to const 0 b = a.pad(((0, 10), None))[10:] sched = check_schedule(b.contiguous(), 1) - # TODO: this VALID can clean up, where do we need st? - self.assertIs(store_val(sched[-1]), UOp.const_with_shape(b.dtype, 0, b.lazydata.st.shape)) + assert zero_pm.match(store_val(sched[-1]), {}) run_schedule(sched) np.testing.assert_equal(b.numpy(), 0) @@ -1952,18 +2091,14 @@ class TestView(unittest.TestCase): assert b.shape == (10, 10) sched = check_schedule(b.contiguous(), 1) self.assertEqual(sched[-1].ast.full_shape, (10, 10)) - self.assertIs(store_val(sched[-1]), UOp.const_with_shape(b.dtype, 0, b.lazydata.st.shape)) + assert zero_pm.match(store_val(sched[-1]), {}) run_schedule(sched) np.testing.assert_equal(b.numpy(), 0) def test_zero_size_alt(self): - st = ShapeTracker.from_shape((135, 0, 9)) - a = UOp(Ops.VIEW, dtypes.float, (UOp.new_buffer(Device.DEFAULT, 121, dtypes.float), UOp(Ops.EMPTY, dtypes.float)), st) - b = a.pad(pad_arg:=((0, 0), (0, 0), (18, 0))) - self.assertEqual(b.st, st.pad(pad_arg)) - # TODO: why does this help? - b = graph_rewrite(b, remove_movement_ops) - self.assertIs(b.base.src[1], UOp.const(dtypes.float, 0)) + a = Tensor.empty(135, 0, 9) + b = a.pad(((0, 0), (0, 0), (18, 0))) + check_schedule(b, 0) def test_partial_mask(self): # partial masked out does not degrade into CONST @@ -1976,33 +2111,93 @@ class TestView(unittest.TestCase): run_schedule(sched) np.testing.assert_allclose(b.numpy(), np.pad(a.numpy(), ((0, 5), (0, 0)))[5:]) -@track_rewrites(named=True) -def big_graph_rewrite(big_graph:UOp, ctx) -> UOp: return graph_rewrite(big_graph, do_realize, ctx) -class TestBigGraph(unittest.TestCase): + # a*VIEW(x), where VIEW(x) = 0 + # x collapses along with its children + def test_parent_view_collapses(self): + a = Tensor([1, 2]) + b = Tensor.arange(3).contiguous() + bv = b.pad(((0, 2),))[-2:] + # this becomes a late a*0 + late_mul = a*bv + check_schedule(late_mul, 0) + # the arange doesn't realize + self.assertIsNone(b.lazydata.base.realized) + # mul doesn't realize + self.assertIsNone(late_mul.lazydata.base.realized) + self.assertEqual(late_mul.tolist(), [0, 0]) + + # SINK has two branches: + # a*VIEW(x), where VIEW(x) = 0 + # x+2 + # as long as one child realizes, x does not collapse + def test_parent_multiple_children_no_collapse(self): + a = Tensor([1, 2]) + b = Tensor.arange(3).contiguous() + bv = b.pad(((0, 2),))[-2:] + late_mul = a*bv + other_child = b+2 + s = check_schedule([late_mul, other_child], 2) + # the arange becomes a BUFFER + self.assertIs(b.lazydata.base.op, Ops.BUFFER) + # mul still collapses + self.assertIs(late_mul.lazydata.base.op, Ops.CONST) + run_schedule(s) + self.assertEqual(other_child.tolist(), [2, 3, 4]) + +def tensor_rewrite(t) -> UOp: return graph_rewrite(t.lazydata.base, merge_views+symbolic_simple) +class TestSimplifier(unittest.TestCase): def test_sink_childless_const(self): - x = UOp.const(dtypes.int, 0) - big_graph = big_graph_rewrite(x.sink(), ctx:=ScheduleContext()) - self.assertIs(big_graph, UOp(Ops.NOOP)) - self.assertEqual(len(ctx.realizes), 0) - - def test_sink_childless_const_alt(self): - x = UOp.const(dtypes.int, 0) - y = UOp(Ops.VIEW, dtypes.int, (UOp(Ops.BUFFER, dtypes.int, (), 0), UOp.const(dtypes.int, 0)), ShapeTracker.from_shape(())) - big_graph = big_graph_rewrite(UOp.sink(x, y), ctx:=ScheduleContext()) - self.assertIs(big_graph, UOp(Ops.NOOP)) - self.assertEqual(len(ctx.realizes), 0) + x = Tensor(0) + check_schedule(x, 0) def test_sink_childless_const_alt_expanded(self): - # this is a real STORE of CONST (post expand) - y = UOp(Ops.VIEW, dtypes.int, (UOp.new_buffer(Device.DEFAULT, 1, dtypes.int), UOp.const(dtypes.int, 0)), ShapeTracker.from_shape(())) - out = UOp(Ops.VIEW, dtypes.int, (UOp.new_buffer(Device.DEFAULT, 2, dtypes.int), y.reshape((1,)).expand((2,)).contiguous(),), ShapeTracker.from_shape((2,))) - big_graph = big_graph_rewrite(out.sink(), ctx:=ScheduleContext()) - self.assertIs(big_graph, out.sink()) - self.assertEqual(len(ctx.realizes), 1) + x = Tensor.zeros(4, 4).contiguous() + check_schedule(x, 1) + + def test_all_const_uops(self): + a = Tensor(4)*Tensor(2) + sink = tensor_rewrite(a) + assert UPat.cvar().match(sink, {}) + + def test_masked_const_elementwise(self): + a = Tensor.eye(10)@Tensor.eye(10) + sink = tensor_rewrite(a) + assert UPat(Ops.REDUCE_AXIS, src=(UPat.cvar().view()*UPat.cvar().view(),)).match(sink, {}) + + def test_elementwise_ops(self): + a = Tensor.empty(4, 4, dtype=dtypes.int) + sink = tensor_rewrite(a*0) + assert UPat(Ops.CONST, arg=0).match(sink, {}) + self.assertIs(tensor_rewrite(a*1).base, a.lazydata.base) + self.assertIs(tensor_rewrite(a+0).base, a.lazydata.base) + self.assertIs(tensor_rewrite(a//1).base, a.lazydata.base) + + def test_cast_folding(self): + a = Tensor(1.0).cast(dtypes.int) + sink = tensor_rewrite(a) + assert UPat.cvar(dtype=dtypes.int).match(sink, {}) + + def test_const_folding_mul(self): + a = Tensor([1]) + sink = tensor_rewrite(a*0) + assert UPat(Ops.CONST, arg=0).match(sink, {}), f"expected {sink} to collapse to a const 0" + assert sink.shape == a.shape + + def test_const_folding_ne(self): + a = Tensor([1]) + sink = tensor_rewrite(a != a) + assert UPat(Ops.CONST, arg=False).match(sink, {}), f"expected {sink} to collapse to a const False" + assert sink.shape == a.shape + + def test_const_folding_lt(self): + a = Tensor([1]) + sink = tensor_rewrite(a < a) + assert UPat(Ops.CONST, arg=False).match(sink, {}), f"expected {sink} to collapse to a const False" + assert sink.shape == a.shape tensor_const_pm = PatternMatcher([ - (UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat(Ops.CONST, src=()))), lambda: True), - (UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat(Ops.BIND, src=(UPat(Ops.DEFINE_VAR), UPat(Ops.CONST))))), lambda: True), + (UPat(Ops.CONST, src=(UPat(Ops.VIEW, src=(UPat(Ops.DEVICE),)),)), lambda: True), + (UPat(Ops.BIND, src=(UPat(Ops.DEFINE_VAR, src=(UPat(Ops.VIEW, src=(UPat(Ops.DEVICE),)))), UPat(Ops.CONST))), lambda: True), ]) class TestConst(unittest.TestCase): # ** part 1: basic functionality of a tensor directly created from CONST @@ -2018,19 +2213,6 @@ class TestConst(unittest.TestCase): print(a.lazydata) self.assertTrue(tensor_const_pm.rewrite(a.lazydata)) - def test_uop_methods(self): - a = Tensor(1) - self.assertTrue(a.lazydata.is_unrealized_const()) - self.assertTrue(a.lazydata.is_unrealized_unmasked_const()) - - a = Tensor.ones((4, 4)) - self.assertTrue(a.lazydata.is_unrealized_const()) - self.assertTrue(a.lazydata.is_unrealized_unmasked_const()) - - a = Tensor.ones((4, 4)).pad((1, 1),) - self.assertTrue(a.lazydata.is_unrealized_const()) - self.assertFalse(a.lazydata.is_unrealized_unmasked_const()) - def test_const_schedule(self): a = Tensor.ones((4, 4)) sched = a.schedule() @@ -2046,17 +2228,16 @@ class TestConst(unittest.TestCase): a = Tensor.ones((4,)).pad((1, 1)).contiguous() sched = a.schedule() print(sched[0].ast) - const_ast_pattern = UPat(Ops.SINK, src=(UPat.store(UPat(), UPat(), UPat(Ops.WHERE, src=(UPat(Ops.VALID), UPat.cvar("x"), UPat(Ops.CONST, arg=0)))),)) + const_ast_pattern = UPat(Ops.SINK, src=(UPat.store(UPat(), UPat(), UPat.where(UPat(Ops.VALID), UPat.cvar("x"), UPat(Ops.CONST, arg=0))),)) self.assertEqual(len(const_ast_pattern.match(sched[0].ast, {})), 1) run_schedule(sched) self.assertListEqual(a.tolist(), [0, 1, 1, 1, 1, 0]) - # TOOD: currently even unmasked constants are VALID until codegen def test_unmasked_const_ast(self): a = Tensor.ones((4,)).contiguous() sched = a.schedule() print(sched[0].ast) - const_ast_pattern = UPat(Ops.SINK, src=(UPat.store(UPat(), UPat(), UPat(Ops.WHERE, src=(UPat(Ops.VALID), UPat.cvar("x"), UPat(Ops.CONST, arg=0)))),)) + const_ast_pattern = UPat(Ops.SINK, src=(UPat.store(UPat(), UPat(), UPat(Ops.CONST)),)) self.assertEqual(len(const_ast_pattern.match(sched[0].ast, {})), 1) run_schedule(sched) self.assertListEqual(a.tolist(), [1, 1, 1, 1]) @@ -2077,7 +2258,7 @@ class TestConst(unittest.TestCase): sched = add.schedule() self.assertEqual(len(sched), 0) # b+0 and b share the same underlying device memory - self.assertIs(add.lazydata.realized, b.lazydata.realized) + self.assertIs(add.lazydata.buffer, b.lazydata.buffer) self.assertListEqual(add.tolist(), [2, 2, 2, 2]) def test_src_masked_const_folding(self): @@ -2090,12 +2271,12 @@ class TestConst(unittest.TestCase): self.assertEqual(len(sched), 1) run_schedule(sched) # add gets assigned to a new buffer - self.assertIsNot(add.lazydata.realized, b.lazydata.realized) + self.assertIsNot(add.lazydata.base.realized, b.lazydata.base.realized) self.assertListEqual(add.tolist(), [4, 2, 2, 2, 2, 4]) # ** part 3: Tensor variable bindings - @unittest.expectedFailure # TODO: should schedule assert if you try to realize a Variable? + #@unittest.expectedFailure # TODO: should schedule assert if you try to realize a Variable? def test_var_schedule(self): vv = UOp.variable("a", 0, 10).bind(1) a = Tensor(vv) @@ -2110,5 +2291,368 @@ class TestConst(unittest.TestCase): run_schedule(sched, var_vals) self.assertEqual(a.tolist(), 3) +@unittest.skipIf(Device.DEFAULT == "CPU", "tests copy from another device to cpu") +class TestCopyFolding(unittest.TestCase): + def test_const_copy_is_free(self): + b = Tensor(1).to("CPU") + check_schedule(b, 0, filter_sink=False) + assert b.item() == 1 + + def test_late_const_copy_folding(self): + a = Tensor.arange(3).realize() + zeros = Tensor.zeros(3).realize() + b = (a*zeros).to("CPU") + run_schedule(check_schedule(b, 0, filter_sink=False)) + self.assertListEqual(b.tolist(), [0, 0, 0]) + + def test_alu_after_copy(self): + a = Tensor.ones((4,)).to("CPU").lazydata + b = Tensor.empty(4, device="CPU").lazydata + add = a+b + add = schedule_graph_rewrite(add) + assert all_same([x.device for x in add.src]), f"ALU has different devices! {[x.device for x in add.src]}" + + @unittest.skip("this is just clone now") + def test_copy_to_same_device(self): + a = Tensor.empty(4).lazydata + b = a.copy_to_device(a.device) + check_schedule(b, 0, filter_sink=False) + b = schedule_graph_rewrite(b) + # NOTE: Tensor.empty(4) always creates a VIEW(BUFFER) with ShapeTracker((4,)), we simplify this to jsut a BUFFER + # in the scheduler because buffer already has shape (4,) + self.assertIs(b, a.base) + + @unittest.skip("this is just clone now") + def test_copy_to_same_device_alt(self): + a = Tensor.empty(4, 4).lazydata + b = a.copy_to_device(a.device) + check_schedule(b, 0, filter_sink=False) + b = schedule_graph_rewrite(b) + self.assertIs(b.base, a.base) + + def test_clone(self): + a = Tensor.empty(4).lazydata + check_schedule(a.clone(), 1, filter_sink=False) + + # NOTE: moving copy before view might change this + def test_shrink_copy(self): + a = Tensor.arange(4) + view = a.shrink(((0, 2),)) + b = view.clone() + # NOTE: this was sort of a bug making this 2 + run_schedule(check_schedule(b, 3, filter_sink=False)) + self.assertEqual(b.lazydata.base.buffer.size, 2) + self.assertEqual(b.lazydata.size, 2) + self.assertListEqual(b.tolist(), [0, 1]) + + def test_expanded_copy(self): + a = Tensor.arange(2) + view = a.reshape(2, 1).expand(2, 2) + b = view.clone() + run_schedule(check_schedule(b, 2, filter_sink=False)) + self.assertEqual(b.lazydata.base.buffer.size, 2) + self.assertEqual(b.lazydata.size, 4) + self.assertListEqual(b.tolist(), [[0, 0], [1, 1]]) + + def test_permuted_copy(self): + a = Tensor.arange(4) + b = a.reshape(2, 2).permute(1, 0) + b.realize() + self.assertListEqual(b.tolist(), [[0, 2], [1, 3]]) + + def test_permute_on_disk(self): + with open(temp('dt_arange_4_permute'), "wb") as f: f.write(Tensor.arange(4).realize().lazydata.base.buffer.as_buffer()) + a = Tensor.empty(4, dtype=dtypes.int32, device=f"disk:{temp('dt_arange_4_permute')}") + b = a.reshape(2, 2).permute(1, 0).to("CPU") + b.realize() + self.assertListEqual(b.tolist(), [[0, 2], [1, 3]]) + + def test_permute_after_shrink(self): + a = Tensor.arange(5) + b = a.shrink(((0, 4),)).reshape(2, 2).permute(1, 0).to("CPU") + b.realize() + self.assertListEqual(b.tolist(), [[0, 2], [1, 3]]) + + # NOTE: disk permute must come after COPY + # TODO: this is wrong because of the permute + @unittest.expectedFailure + def test_permute_after_shrink_on_disk(self): + with open(temp('dt_arange_5_permute'), "wb") as f: f.write(Tensor.arange(5).realize().lazydata.base.buffer.as_buffer()) + a = Tensor.empty(5, dtype=dtypes.int32, device=f"disk:{temp('dt_arange_5_permute')}") + b = a.shrink(((0, 4),)).reshape(2, 2).permute(1, 0).to("CPU") + b.realize() + self.assertListEqual(b.tolist(), [[0, 2], [1, 3]]) + +class TestTensorUOpSpec(unittest.TestCase): + def test_const_must_be_unmasked(self): + a = Tensor.ones((4, 4)).pad((2, 2)) + unsafe_push_views = PatternMatcher([ + (UPat.cvar("root").view(name="view"), lambda root,view: root.replace(src=tuple(x.view(view.st) for x in root.src))), + ]) + a.lazydata = graph_rewrite(a.lazydata.sink(), merge_views+merge_views+unsafe_push_views) + with self.assertRaisesRegex(RuntimeError, "UOp verification failed"): + a.schedule() + + def test_expanded_const_ok(self): + a = Tensor.ones((4, 4)) + t = graph_rewrite(a.lazydata.sink(), merge_views+merge_views) + create_schedule_with_vars(t) + + # NOTE: changing symbolic CONST VIEWs is not allowed + @unittest.expectedFailure + def test_symbolic_shape_ok(self): + a = Tensor.ones(4) + vi = UOp.variable("i", 1, 10).bind(4) + a.lazydata = graph_rewrite(a.reshape(vi).sum().lazydata, merge_views+merge_views) + a.schedule() + +class TestBufferUOp(unittest.TestCase): + # BUFFER has a ShapeTracker of shape=(n,) and stride=(1,) + def test_buffer_has_buffer(self): + buf = Tensor.empty(10) + self.assertIsNotNone(buf.lazydata.buffer) + self.assertEqual(buf.lazydata.st, ShapeTracker.from_shape((10,))) + # the device Buffer remains unallocated until it's we run the schedule + self.assertFalse(buf.lazydata.buffer.is_allocated()) + add = buf+1 + sched = add.schedule() + self.assertFalse(buf.lazydata.buffer.is_allocated()) + run_schedule(sched) + self.assertTrue(buf.lazydata.buffer.is_allocated()) + + def test_buffer_has_unique_buffer(self): + buf = Tensor.empty(10) + buf1 = buf.lazydata.buffer + buf2 = buf.lazydata.buffer + self.assertIs(buf1, buf2) + + # we also allow VIEW(BUFFER) to access the underlying device Buffer, as long as it's contiguous + def test_buffer_view_allowed(self): + add = Tensor.empty(1, 1)+Tensor.empty(1, 1) + add.realize() + self.assertIsNotNone(add.lazydata.buffer) + self.assertEqual(add.lazydata.shape, (1, 1)) + + def test_buffer_view_not_allowed(self): + permuted_view = Tensor.empty(1, 2, 3).permute(0, 2, 1) + merged = graph_rewrite(permuted_view.lazydata, merge_views) + with self.assertRaisesRegex(AssertionError, "VIEW only works here if it's contiguous"): + merged.buffer # cannot access Buffer of a non contiguous VIEW + + def test_buffer_only_after_realize(self): + a = Tensor([1])+Tensor([2]) + # accessing realized will return None + self.assertIsNone(a.lazydata.realized) + # accessing Buffer will assert + with self.assertRaisesRegex(AssertionError, "must be BUFFER"): + a.lazydata.buffer # there is no BUFFER on an unrealized ADD + # Buffer only exists once we realize it + a.realize() + self.assertIsNotNone(a.lazydata.buffer) + + def test_const_does_not_realize(self): + a = Tensor(1)+Tensor(2) + run_schedule(check_schedule(a, 0)) + self.assertIsNone(a.lazydata.base.realized) + + def test_var_does_not_realize(self): + a = Tensor(UOp.variable("a", 0, 10).bind(1)) + run_schedule(check_schedule(a, 0)) + self.assertIsNone(a.lazydata.base.realized) + + def test_view_does_not_realize(self): + a = Tensor.randn(1, 4).expand(4, 4) + a.realize() + self.assertEqual(a.lazydata.base.realized.size, 4) + a2 = a.contiguous().realize() + self.assertEqual(a2.lazydata.base.realized.size, 16) + +class TestContiguous(unittest.TestCase): + def test_contiguous_buffer(self): + a = Tensor.empty(4) + b = a.contiguous() + check_schedule(b, 0) + + def test_contiguous_buffer_view(self): + a = Tensor.empty(4) + b = a.reshape((2, 2)).contiguous() + check_schedule(b, 0) + + def test_non_contiguous_buffer_view(self): + a = Tensor.empty(4, 1) + b = a.expand((4, 4)).contiguous() + check_schedule(b, 1) + + def test_size_change_buffer_view(self): + a = Tensor.empty(4) + b = a.reshape((1, 1, 4)).shrink(((0, 1), (0, 1), (0, 3))).contiguous() + check_schedule(b, 1) + + def test_double_contiguous_realizes_once(self): + a = Tensor.empty(4, 1) + b = a.expand((4, 4)).contiguous().contiguous() + check_schedule(b, 1) + + def test_view_does_not_realize(self): + a = Tensor.empty(4) + b = a.expand((4, 4)) + check_schedule(b, 0) + self.assertEqual(b.lazydata.base.buffer.size, 4) + + def test_contiguous_view_realizes(self): + a = Tensor.empty(4) + b = a.expand((4, 4)).contiguous() + check_schedule(b, 1) + self.assertEqual(b.lazydata.base.buffer.size, 16) + +class TestUOpBecome(unittest.TestCase): + # the simplest case, if we create a new BUFFER for this tensor UOp + def test_new_buffer(self): + a = Tensor.empty(4, 4) + b = Tensor.empty(4, 4) + add = a+b + check_schedule(add, 1) + # NOTE: realized base is always a flat buffer + assert UPat(Ops.BUFFER).match(add.lazydata.base, {}) + # the Tensor UOp can optionally stack a VIEW on top of the BUFFER, in this case to preserve the (4, 4) shape of the tensor + assert add.lazydata is not add.lazydata.base + self.assertEqual(add.lazydata.size, 16) + self.assertEqual(add.lazydata.shape, (4, 4)) + + def test_new_buffer_view(self): + a = Tensor.empty(4, 4) + b = Tensor.empty(4, 4) + add = (a+b).reshape(8, 2) + check_schedule(add, 1) + assert UPat(Ops.BUFFER).match(add.lazydata.base, {}) + # the shape is preserverd in the becomes_map. + self.assertEqual(add.lazydata.shape, (8, 2)) + assert add.lazydata is not add.lazydata.base + + def test_new_flat_buffer(self): + a = Tensor.empty(4,) + b = Tensor.empty(4,) + add = a+b + check_schedule(add, 1) + # BUFFER already has a shape (4,), this tensor just becomes a contiguous BUFFER + assert UPat(Ops.BUFFER).match(add.lazydata, {}) + + # sometimes we prefer to perform an op before movement ops, in this case we should stack the mops on top of the new buffer + + # NOTE: this expand is not reordered because there's before it to fuse + def test_reorder_expand(self): + a = Tensor.empty(4, 1) + b = a.expand(4, 4).reciprocal() + check_schedule(b, 1) + self.assertEqual(b.lazydata.base.buffer.size, 16) + self.assertEqual(b.lazydata.st, ShapeTracker.from_shape((4, 4))) + + def test_reorder_expand_alt(self): + x = Tensor.empty(4, 1) + y = Tensor.empty(4, 1) + img = Tensor.empty(4, 4) + z = (img*x) / y + check_schedule(z, 1) + + def test_become_existing_buffer(self): + a = Tensor.empty(4, 4) + b = a*1 + assert UPat(Ops.MUL).match(b.lazydata, {}) # before scheduling it's a mul + check_schedule(b, 0) + assert UPat(Ops.VIEW, src=(UPat(Ops.BUFFER))).match(b.lazydata, {}) # scheduling merges all MovementOps into a single VIEW + self.assertIs(a.lazydata.base.buffer, b.lazydata.base.buffer) + + def test_become_buf_with_mops(self): + a = Tensor.empty(2, 4, 2) + noop = a.shrink(((1, 2), (0, 4), (0, 2))).reshape(4, 2)*1+0 + # before realizing, this tensor is base + assert noop.lazydata is noop.lazydata.base + noop.realize() + # it becomes a realized view after realize + assert noop.lazydata is not noop.lazydata.base + assert noop.lazydata.base.op is Ops.BUFFER + late_add = noop+2 + late_add.realize() + + def test_become_const_in_base(self): + a = Tensor.empty(4) + b = a*0 + assert UPat(Ops.MUL).match(b.lazydata, {}) # before scheduling it's a mul + check_schedule(b, 0) + assert UPat(Ops.CONST, arg=0).match(b.lazydata.base, {}) # scheduling replaces the tensor lazydata with a VIEW(BUFFER) + + def test_become_const_in_view(self): + # if we shrink the base down to a size 0, only the VIEW becomes CONST, base is unchanged. + add = Tensor.empty(2, 2)+Tensor.empty(2, 2) + b = add.shrink(((0, 1), (0, 0))) + check_schedule(b, 0) + assert UPat(Ops.CONST, arg=0).match(b.lazydata, {}) + self.assertEqual(b.shape, (1, 0)) + # the base is untouched. + assert UPat(Ops.ADD).match(add.lazydata, {}) + + def test_become_const_from_const(self): + const_add = Tensor(1)+Tensor(2) + assert UPat(Ops.ADD).match(const_add.lazydata, {}) + check_schedule(const_add, 0) + assert UPat(Ops.CONST, arg=3).match(const_add.lazydata.base, {}) + + # tensors can become another realized tensor source + def test_become_existing_buf_simple(self): + a = Tensor.empty(4, 4) + b = a+0 + check_schedule(b, 0) + assert b.lazydata.base.op is Ops.BUFFER + self.assertIs(a.lazydata, b.lazydata) + + # they can also chain other movement ops on top of the tensor source + def test_become_existing_buf_view(self): + a = Tensor.empty(4, 4) + b = a.permute((1, 0))+0 + check_schedule(b, 0) + self.assertEqual(b.lazydata.st, a.lazydata.permute((1, 0)).st) + + def test_become_existing_buf_view_alt(self): + a = Tensor.empty(4, 4) + b = a.permute((1, 0)).reshape((8, 2))+0 + check_schedule(b, 0) + self.assertEqual(b.lazydata.st, a.lazydata.permute((1, 0)).reshape((8, 2)).st) + + # they can also have other base parents that simplified, in that case we just backtrack to the chained mops + def test_become_existing_buf_complex(self): + a = Tensor.empty(4, 4) + b = (a.permute((1, 0))+0).reshape((8, 2))+0 + check_schedule(b, 0) + self.assertEqual(b.lazydata.st, a.lazydata.permute((1, 0)).reshape((8, 2)).st) + assert b.lazydata.base.op is Ops.BUFFER + + def test_become_multiple_choices(self): + a = Tensor.empty(16) + b = (a.reshape(1, 1, 4, 1, 4)+0).reshape(1, 1, 4, 4).shrink(((0, 1), (0, 1), (0, 3), (0, 3)))+0 + c = (a.reshape(1, 1, 4, 4)+0).shrink(((0, 1), (0, 1), (0, 3), (0, 3)))+0 + check_schedule([b, c], 0) + assert all_same([x.lazydata.base.realized for x in [a,b,c]]) + # these movement ops result in the same ShapeTracker + assert b.lazydata.st == c.lazydata.st + assert b.lazydata is c.lazydata + assert UPat(Ops.VIEW, src=(UPat(Ops.BUFFER),)).match(c.lazydata, {}) + + def test_setitem_becomes_subbuffer(self): + a = Tensor.full((4,), 2.).contiguous().realize() + b = a.shrink(((0, 2),)).assign(Tensor.full((2,), 1.0)) + b.realize() + assert a.lazydata.is_realized + assert a.lazydata.buffer._base is None + # b is a subbuffer of a + assert b.lazydata.op is Ops.BUFFER_VIEW + assert b.lazydata.src[0] is a.lazydata + + def test_setitem_offset(self): + a = Tensor.full((16,), 0.).contiguous().realize() + b = Tensor.full((16,), 1.).contiguous().realize() + a_view = a[4:].reshape(3, 4).shrink(((0,2),(0,2))).reshape((4,)) + b.shrink(((0,4),)).assign(a_view).realize() + self.assertListEqual(b.tolist(), [0.0, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]) + if __name__ == '__main__': unittest.main(verbosity=2) diff --git a/tinygrad_repo/test/test_search.py b/tinygrad_repo/test/test_search.py index 37747b2106..19923a6953 100644 --- a/tinygrad_repo/test/test_search.py +++ b/tinygrad_repo/test/test_search.py @@ -3,9 +3,8 @@ import unittest from test.helpers import ast_const from tinygrad.codegen.kernel import Opt, OptOps from tinygrad.codegen.kernel import Kernel -from tinygrad.ops import UOp, Ops -from tinygrad.engine.schedule import create_schedule -from tinygrad.engine.search import time_linearizer, bufs_from_lin, actions, beam_search +from tinygrad.uop.ops import UOp, Ops +from tinygrad.engine.search import bufs_from_lin, actions, beam_search from tinygrad.device import Device, Buffer from tinygrad.tensor import Tensor from tinygrad.dtype import dtypes @@ -13,18 +12,21 @@ from tinygrad.helpers import Context, GlobalCounters from tinygrad.engine.realize import capturing from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import View +from extra.optimization.helpers import time_linearizer class TestTimeLinearizer(unittest.TestCase): + @unittest.skipIf(Device.DEFAULT == "WEBGPU", "WebGPU timestamps are low precision, tm is 0") def test_reasonable_time(self): - si = [i for i in create_schedule([Tensor([1,2,3,4]).add(1).lazydata]) if i.ast.op is Ops.SINK][0] - out = Buffer(Device.DEFAULT, si.outputs[0].size, si.outputs[0].dtype).allocate() - memops = {x.src[0].arg:x.src[-1].arg.real_size() for x in si.ast.toposort if x.op is Ops.LOAD} - rawbufs = [out] + [Buffer(Device.DEFAULT, memops[i], x.dtype).allocate() for i,x in enumerate(si.inputs, start=len(si.outputs))] + a = Tensor([1,2,3,4]).realize() + si = (a+1).schedule()[0] + # create fresh empty buffers + rawbufs = [Buffer(b.device, b.size, b.dtype).allocate() for b in si.bufs] tm = time_linearizer(Kernel(si.ast), rawbufs, allow_test_size=False, cnt=10, disable_cache=True) assert tm > 0 and tm != float('inf') def test_bufs_from_lin(self): - si = [i for i in create_schedule([Tensor([1,2,3,4]).add(1).lazydata]) if i.ast.op is Ops.SINK][0] + a = Tensor([1,2,3,4]).realize() + si = (a+1).schedule()[0] rawbufs = bufs_from_lin(lin:=Kernel(si.ast)) assert len(rawbufs) == len(lin.membufs) == 2 assert all(r is not None for r in rawbufs) @@ -34,7 +36,7 @@ class TestTimeLinearizer(unittest.TestCase): def test_bufs_from_lin_alt(self): a = Tensor.randn(4, 4).realize() b = a+a[0] - si = [si for si in b.schedule() if si.ast.op is Ops.SINK][0] + si = b.schedule()[0] rawbufs = bufs_from_lin(k:=Kernel(si.ast)) assert len(rawbufs) == len(k.membufs) == 2 assert all(r is not None for r in rawbufs) @@ -91,15 +93,44 @@ class TestBEAM(unittest.TestCase): # ensure amt=0 are not duplicated if Opt(OptOps.UPCAST, 0, 0) in actions: - assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.UPCAST, axis=0, amt=4)]) == 0, "did not de-dup UPCAST" + assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.UPCAST, axis=0, arg=4)]) == 0, "did not de-dup UPCAST" if Opt(OptOps.LOCAL, 0, 0) in actions: - assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.LOCAL, axis=0, amt=4)]) == 0, "did not de-dup LOCAL" + assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.LOCAL, axis=0, arg=4)]) == 0, "did not de-dup LOCAL" if Opt(OptOps.UNROLL, 0, 0) in actions: - assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.UNROLL, axis=0, amt=3)]) == 0, "did not de-dup UNROLL" + assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.UNROLL, axis=0, arg=3)]) == 0, "did not de-dup UNROLL" if Opt(OptOps.GROUP, 0, 0) in actions: - assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.GROUP, axis=0, amt=3)]) == 0, "did not de-dup GROUP" + assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.GROUP, axis=0, arg=3)]) == 0, "did not de-dup GROUP" if Opt(OptOps.GROUPTOP, 0, 0) in actions: - assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.GROUPTOP, axis=0, amt=3)]) == 0, "did not de-dup GROUPTOP" + assert len([x for x in lins if x.applied_opts[0] == Opt(OptOps.GROUPTOP, axis=0, arg=3)]) == 0, "did not de-dup GROUPTOP" + + @unittest.skipUnless(Device[Device.DEFAULT].renderer.tensor_cores, "test requires tensor cores") + def test_search_over_shape(self): + from test.test_linearizer import helper_realized_ast + from tinygrad.engine.search import get_kernel_actions + + dtype_pairs = [(tc.dtype_in, tc.dtype_out) for tc in Device[Device.DEFAULT].renderer.tensor_cores] + multi_shape_dtype_pairs = [dts for dts in dtype_pairs if dtype_pairs.count(dts) > 1] + + if len(multi_shape_dtype_pairs) == 0: raise unittest.SkipTest("only one tc available per dtype pair to search over") + + for (dtype_in, dtype_out) in multi_shape_dtype_pairs: + a = Tensor.rand(16, 16, dtype=dtype_in) + b = Tensor.rand(16, 16, dtype=dtype_in) + realized_ast, _ = helper_realized_ast(a.matmul(b, dtype=dtype_out)) + + lins = get_kernel_actions(Kernel(realized_ast)).values() + assert len(set(lin.tensor_core.dims for lin in lins if lin.tensor_core is not None)) > 1 + + def test_get_kernel_actions_preserves_actions_state(self): + from test.test_linearizer import helper_realized_ast + from tinygrad.engine.search import get_kernel_actions + a = Tensor.rand(16, 16) + b = Tensor.rand(16, 16) + realized_ast, _ = helper_realized_ast(a @ b) + actions_before = actions.copy() + get_kernel_actions(Kernel(realized_ast)) + actions_after = actions.copy() + assert actions_after == actions_before, "actions state was not preserved" def test_filter_global_buffer(self): # taken from https://github.com/tinygrad/tinygrad/issues/4612 diff --git a/tinygrad_repo/test/test_setitem.py b/tinygrad_repo/test/test_setitem.py index 84ccb8bc1f..d3f066bad4 100644 --- a/tinygrad_repo/test/test_setitem.py +++ b/tinygrad_repo/test/test_setitem.py @@ -1,6 +1,6 @@ import unittest -from tinygrad import Device, Tensor, TinyJit, Variable, dtypes -from tinygrad.helpers import CI +from tinygrad import Tensor, TinyJit, Variable, dtypes +from tinygrad.helpers import Context import numpy as np class TestSetitem(unittest.TestCase): @@ -26,6 +26,16 @@ class TestSetitem(unittest.TestCase): n[slc] = val.numpy() if isinstance(val, Tensor) else val np.testing.assert_allclose(t.numpy(), n) + def test_padded_setitem(self): + t = Tensor.arange(10) + t[4:1:-2] = 11 + self.assertListEqual(t.tolist(), [0, 1, 11, 3, 11, 5, 6, 7, 8, 9]) + + def test_setitem_inplace_mul(self): + t = Tensor.arange(10).realize() + t[:3] *= 10 + self.assertListEqual(t.tolist(), [0, 10, 20, 3, 4, 5, 6, 7, 8, 9]) + def test_setitem_into_unrealized(self): t = Tensor.arange(4).reshape(2, 2) t[1] = 5 @@ -70,7 +80,8 @@ class TestSetitem(unittest.TestCase): t[1] ^= 5 np.testing.assert_allclose(t.numpy(), [[0, 1], [7, 6]]) - @unittest.expectedFailure + #@unittest.expectedFailure + # update: passing after delete_forced_realize def test_setitem_consecutive_inplace_operator(self): t = Tensor.arange(4).reshape(2, 2).contiguous() t[1] += 2 @@ -121,30 +132,26 @@ class TestSetitem(unittest.TestCase): np.testing.assert_allclose(t.numpy(), n) def test_jit_setitem_variable_offset(self): - @TinyJit - def f(t:Tensor, a:Tensor, v:Variable): - t.shrink(((v,v+1), None)).assign(a).realize() + with Context(IGNORE_OOB=1): + @TinyJit + def f(t:Tensor, a:Tensor, v:Variable): + t.shrink(((v,v+1), None)).assign(a).realize() - t = Tensor.zeros(6, 6).contiguous().realize() - n = np.zeros((6, 6)) + t = Tensor.zeros(6, 6).contiguous().realize() + n = np.zeros((6, 6)) - for i in range(6): - v = Variable("v", 0, 6).bind(i) - a = Tensor.full((1, 6), fill_value=i+1, dtype=dtypes.float).contiguous() - n[i, :] = i+1 - f(t, a, v) - np.testing.assert_allclose(t.numpy(), n) - np.testing.assert_allclose(t.numpy(), [[1,1,1,1,1,1],[2,2,2,2,2,2],[3,3,3,3,3,3],[4,4,4,4,4,4],[5,5,5,5,5,5],[6,6,6,6,6,6]]) + for i in range(6): + v = Variable("v", 0, 6).bind(i) + a = Tensor.full((1, 6), fill_value=i+1, dtype=dtypes.float).contiguous() + n[i, :] = i+1 + f(t, a, v) + np.testing.assert_allclose(t.numpy(), n) + np.testing.assert_allclose(t.numpy(), [[1,1,1,1,1,1],[2,2,2,2,2,2],[3,3,3,3,3,3],[4,4,4,4,4,4],[5,5,5,5,5,5],[6,6,6,6,6,6]]) def test_setitem_overlapping_inplace1(self): t = Tensor([[3.0], [2.0], [1.0]]).contiguous() t[1:] = t[:-1] - if (Device.DEFAULT == "LLVM") or (CI and Device.DEFAULT == "AMD"): - # TODO: FIXME - with self.assertRaises(AssertionError): - self.assertEqual(t.tolist(), [[3.0], [3.0], [2.0]]) - else: - self.assertEqual(t.tolist(), [[3.0], [3.0], [2.0]]) + self.assertEqual(t.tolist(), [[3.0], [3.0], [2.0]]) def test_setitem_overlapping_inplace2(self): t = Tensor([[3.0], [2.0], [1.0]]).contiguous() diff --git a/tinygrad_repo/test/test_softmax_fusion.py b/tinygrad_repo/test/test_softmax_fusion.py new file mode 100644 index 0000000000..fd0dedc068 --- /dev/null +++ b/tinygrad_repo/test/test_softmax_fusion.py @@ -0,0 +1,176 @@ +import unittest +import numpy as np +from tinygrad import Tensor, GlobalCounters, Context, Device +from tinygrad.dtype import DTypeLike, dtypes +from tinygrad.helpers import DEBUG, get_single_element +from tinygrad.engine.realize import lower_schedule_item +from tinygrad.device import is_dtype_supported + +def single_kernel_softmax(x_in:Tensor, axis=-1, dtype:DTypeLike|None=None) -> Tensor: + # only support axis =-1 + x = x_in.reshape(-1, x_in.shape[-1]) + nr_dim, r_dim = x.shape + + inp = x.reshape(nr_dim, 1, 1, r_dim).expand(nr_dim, r_dim, 1, r_dim) + imx = x.reshape(nr_dim, 1, r_dim, 1).expand(nr_dim, r_dim, r_dim, r_dim).max(axis=-2, keepdim=True) + m = inp - imx.detach() + if dtype is not None: m = m.cast(dtype) + e = m.exp() + ss = e.sum(axis=-1, keepdim=True) + + inp = x.reshape(nr_dim, r_dim, 1, 1) + imx = x.reshape(nr_dim, 1, r_dim, 1).expand(nr_dim, r_dim, r_dim, 1).max(axis=-2, keepdim=True) + m = inp - imx.detach() + if dtype is not None: m = m.cast(dtype) + e = m.exp() + + out = e.div(ss).reshape(x_in.shape) + return out + +def run_one_schedule_item(out): lower_schedule_item(get_single_element(out.schedule())).run() + +class TestFuse(unittest.TestCase): + def _test_fuse(self, fxn, *args, atol=1e-7, allow_multiple=False, **kwargs): + GlobalCounters.reset() + out_single = fxn(*args, **kwargs).fuse() + if not allow_multiple: run_one_schedule_item(out_single) + np_single = out_single.numpy() + GlobalCounters.reset() + np_multi = fxn(*args, **kwargs).numpy() + np.testing.assert_allclose(np_single, np_multi, atol=atol) + + def test_fuse_norm(self): + a = Tensor.rand(50,50).realize() + self._test_fuse(lambda a: a / a.mean(axis=1), a) + + def test_fuse_argmax(self): + a = Tensor.rand(50,50).realize() + self._test_fuse(lambda a: a.argmax(axis=-1), a) + + def test_fuse_softmax(self): + a = Tensor.rand(50,50).realize() + self._test_fuse(lambda a: a.softmax(axis=-1), a) + + def test_fuse_gemm_softmax(self): + a = Tensor.rand(50,50).realize() + b = Tensor.rand(50,50).realize() + self._test_fuse(lambda a,b: ((a@b).relu()+a).contiguous().softmax(axis=-1), a,b, allow_multiple=True) + + @unittest.skipUnless(is_dtype_supported(dtypes.float16, Device.DEFAULT), f"no float16 on {Device.DEFAULT}") + def test_fuse_softmax_dtype(self): + a = Tensor.rand(50,50).realize() + self._test_fuse(lambda a: a.softmax(axis=-1, dtype='half'), a, atol=3e-4) + + def test_fuse_arange_eye(self): + self._test_fuse(lambda: Tensor.arange(10).reshape(10,1).expand(10,10) == Tensor.arange(10).reshape(1,10).expand(10,10)) + + def test_double_gemm(self): + N = 32 + with Context(TRACK_MATCH_STATS=0, DEBUG=0): + a = (Tensor.rand(N,N)-0.5).realize() + b = (Tensor.rand(N,N)-0.5).realize() + c = (Tensor.rand(N,N)-0.5).realize() + self._test_fuse(lambda a,b,c: a@b@c, a, b, c, atol=1e-5) + + def test_embedding(self): + with Context(TRACK_MATCH_STATS=0, DEBUG=0): + vocab_sz = 123 + embed_sz = 16 + weight = (Tensor.rand(vocab_sz, embed_sz)-0.5).realize() + a = Tensor([1, 1, 2, 3]).realize() + def embedding(idx:Tensor): + arange = Tensor.arange(vocab_sz).unsqueeze(-1) + big_shp = idx.shape + (vocab_sz, embed_sz) + arange, vals = arange.expand(big_shp), weight.expand(big_shp) + idx = idx.reshape(idx.shape+(1, 1)).expand(big_shp) + return (arange == idx).mul(vals).sum(-2, dtype=vals.dtype) + self._test_fuse(embedding, a, atol=1e-5) + + @unittest.skip("still broken") + def test_flash_attention(self): + BS = 4 + HEADS = 2 + MATDIM = 16 + EMB = 8 + with Context(TRACK_MATCH_STATS=0, DEBUG=0): + q = Tensor.randn(BS, HEADS, MATDIM, EMB).realize() + k = Tensor.randn(BS, HEADS, MATDIM, EMB).realize() + v = Tensor.randn(BS, HEADS, MATDIM, EMB).realize() + # TODO: OPT is breaking things. NOOPT isn't linearizing + with Context(NOOPT=1): + self._test_fuse(Tensor.scaled_dot_product_attention, q, k, v) + +class TestSoftmaxFusion(unittest.TestCase): + @classmethod + def setUpClass(cls): + with Context(TRACK_MATCH_STATS=0): cls.test = Tensor.rand(32, 10).contiguous().realize() + + def setUp(self): + GlobalCounters.reset() + + def test_norm(self): + print("*** norm ***") + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + # NOTE: there's an implied expand on the mean here + sout = self.test / self.test.mean(-1, keepdim=True) + sout.realize() + + print("*** single kernel norm ***") + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + inp = self.test.reshape(32, 10, 1) + div = self.test.reshape(32, 1, 10).expand(32, 10, 10).mean(axis=-1, keepdim=True) + out = (inp / div).reshape(32, 10) + out.realize() + + np.testing.assert_allclose(sout.numpy(), out.numpy()) + + def test_softmax(self): + # this is the softmax from scaled_dot_product_attention + # it becomes 3 kernels + print("*** softmax ***") + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + sout = self.test.softmax(-1) + sout.realize() + + print("*** single kernel softmax ***") + # NOTE: DONT_GROUP_REDUCES is required here + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2), DONT_GROUP_REDUCES=1): + out = single_kernel_softmax(self.test) + out.realize() + + np.testing.assert_allclose(sout.numpy(), out.numpy()) + + def test_auto_softmax(self): + print("*** softmax ***") + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + sout = self.test.softmax(-1) + sout.realize() + + print("*** auto single kernel softmax ***") + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + out = self.test.contiguous().softmax(-1).fuse() + run_one_schedule_item(out) + + np.testing.assert_allclose(sout.numpy(), out.numpy()) + + def test_softmax_bw(self): + print("*** softmax bw ***") + self.test.requires_grad_() + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2)): + self.test.softmax(-1).sum().backward() + sg = self.test.grad.realize() + + self.test.grad = None + + print("*** single kernel softmax bw ***") + # NOTE: DONT_GROUP_REDUCES is required here + # TODO: fix RecursionError with DONT_GROUP_REDUCES + with self.assertRaises(RecursionError): + with Context(NOOPT=1, DEBUG=max(DEBUG.value, 2), DONT_GROUP_REDUCES=1): + single_kernel_softmax(self.test).sum().backward() + g = self.test.grad.realize() + + np.testing.assert_allclose(sg.numpy(), g.numpy(), atol=1e-7) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_speed_v_torch.py b/tinygrad_repo/test/test_speed_v_torch.py index 1cf1a3e044..b6c728ad1d 100644 --- a/tinygrad_repo/test/test_speed_v_torch.py +++ b/tinygrad_repo/test/test_speed_v_torch.py @@ -3,6 +3,7 @@ os.environ["NVIDIA_TF32_OVERRIDE"] = "0" os.environ["MKL_NUM_THREADS"] = "1" os.environ["NUMEXPR_NUM_THREADS"] = "1" os.environ["OMP_NUM_THREADS"] = "1" +os.environ["VECLIB_MAXIMUM_THREADS"] = "1" import unittest import torch torch.set_num_threads(1) @@ -47,14 +48,16 @@ def helper_test_speed(f1, *args): cache_defeat += 1 # manual pre sync - if isinstance(args[0], Tensor): Device[args[0].device].synchronize() + if isinstance(args[0], Tensor): + local_device = Device[args[0].device] + local_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() + if isinstance(ret, Tensor): local_device.synchronize() else: sync() et = (time.perf_counter() - st) * 1000 if i >= 1: ets.append(et) @@ -159,8 +162,8 @@ class TestSpeed(unittest.TestCase): 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)) + helper_test_generic_square('cat_0', 2048, lambda x,y: torch.cat((x,y),dim=0), lambda x,y: x.cat(y,dim=0)) + helper_test_generic_square('cat_1', 2048, lambda x,y: torch.cat((x,y),dim=1), lambda x,y: x.cat(y,dim=1)) def test_array_packing(self): N = 2048 @@ -190,6 +193,10 @@ class TestSpeed(unittest.TestCase): def f(a, b): return a.exp() helper_test_generic_square('exp', 2048, f, f, onearg=True) + def test_sqrt(self): + def f(a, b): return a.sqrt() + helper_test_generic_square('sqrt', 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) @@ -202,8 +209,12 @@ class TestSpeed(unittest.TestCase): 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 test_add_a(self): + def f(a, b): return a + b + helper_test_generic_square('add', 1, f, f) + + def test_add_big(self): + for N in [1024, 4096]: def f(a, b): return a + b helper_test_generic_square('add', N, f, f) diff --git a/tinygrad_repo/test/test_stunning.py b/tinygrad_repo/test/test_stunning.py new file mode 100644 index 0000000000..0429a4051d --- /dev/null +++ b/tinygrad_repo/test/test_stunning.py @@ -0,0 +1,59 @@ +import unittest +from tinygrad import nn, Tensor, Variable, Context, Device +from tinygrad.helpers import trange + +class Model: + def __init__(self): self.layer = nn.Linear(28*28, 10) + def __call__(self, x:Tensor) -> Tensor: return self.layer(x.flatten(1)) + +class TestStunning(unittest.TestCase): + def test_indexing_variable(self): + a = Tensor.arange(100*10).reshape(100, 10).contiguous() + + # index without variable + nv = a[12].tolist() + + # index with variable + vi = Variable('i', 0, a.shape[0]-1) + wv = a[vi.bind(12)].tolist() + + self.assertListEqual(nv, wv) + + def test_indexing_two_bind(self): + a = Tensor.arange(100*10).reshape(100, 10).contiguous() + + nv = a[12].cat(a[76]).tolist() + + vi = Variable('i', 0, a.shape[0]-1) + with self.assertRaisesRegex(AssertionError, "different values for the same key"): + wv = a[vi.bind(12)].cat(a[vi.bind(76)]).tolist() + self.assertListEqual(nv, wv) + + @unittest.skipIf(Device.DEFAULT in {"WEBGPU", "NV", "CUDA"}, "Too many buffers / too slow") + @unittest.skip("This is binding a Variable to two different values") + def test_simple_train(self, steps=6, bs=4, adam=True): + X_train, Y_train, _, _ = nn.datasets.mnist() + model = Model() + if adam: opt = nn.optim.Adam(nn.state.get_parameters(model)) + else: opt = nn.optim.SGD(nn.state.get_parameters(model), momentum=0.1) + samples = Tensor.randint(steps, bs, high=X_train.shape[0]) + Y_train = Y_train.one_hot(10) + X_samp, Y_samp = X_train[samples], Y_train[samples] + vi = Variable('i', 0, samples.shape[0]-1) + with Context(FUSE_ARANGE=1, SPLIT_REDUCEOP=0): + with Tensor.train(): + losses = [] + for i in range(samples.shape[0]): + vib = vi.bind(i) + opt.zero_grad() + pred = model(X_samp[vib].realize()) + loss = (pred - Y_samp[vib]).square().mean() + losses.append(loss.backward()) + opt.schedule_step() + #losses = Tensor.stack(*losses) + + # run + for i in (t:=trange(len(losses))): t.set_description(f"loss: {losses[i].item():6.2f}") + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/test_subbuffer.py b/tinygrad_repo/test/test_subbuffer.py index 8b6e2043f4..9c9a34d5e7 100644 --- a/tinygrad_repo/test/test_subbuffer.py +++ b/tinygrad_repo/test/test_subbuffer.py @@ -1,9 +1,10 @@ import unittest from tinygrad import Device, dtypes, Tensor from tinygrad.device import Buffer -from tinygrad.ops import view_supported_devices +from tinygrad.helpers import Context +from test.helpers import REAL_DEV -@unittest.skipIf(Device.DEFAULT not in view_supported_devices, "subbuffer not supported") +@unittest.skipUnless(hasattr(Device[Device.DEFAULT].allocator, "_offset"), "subbuffer not supported") class TestSubBuffer(unittest.TestCase): def setUp(self): self.buf = Buffer(Device.DEFAULT, 10, dtypes.uint8).ensure_allocated() @@ -35,17 +36,33 @@ class TestSubBuffer(unittest.TestCase): def test_subbuffer_used(self): t = Tensor.arange(0, 10, dtype=dtypes.uint8).realize() - # TODO: why does it needs contiguous - vt = t[2:4].contiguous().realize() + vt = t[2:4].realize() out = (vt + 100).tolist() assert out == [102, 103] - @unittest.skipIf(Device.DEFAULT not in {"CUDA", "NV", "AMD"}, "only NV, AMD, CUDA") + @unittest.skipIf(REAL_DEV not in {"CUDA", "NV", "AMD"}, "only NV, AMD, CUDA") def test_subbuffer_transfer(self): t = Tensor.arange(0, 10, dtype=dtypes.uint8).realize() vt = t[2:5].contiguous().realize() out = vt.to(f"{Device.DEFAULT}:1").realize().tolist() assert out == [2, 3, 4] + def test_subbuffer_deallocate(self): + with Context(LRU=0): + vbuf = self.buf.view(2, dtypes.uint8, offset=3).ensure_allocated() + self.buf.deallocate() + vbuf.deallocate() + + # Allocate a fake one on the same place + _ = Buffer(Device.DEFAULT, 10, dtypes.uint8).ensure_allocated() + + self.buf.ensure_allocated() + self.buf.copyin(memoryview(bytearray(range(10, 20)))) + + vbuf.ensure_allocated() + + tst = vbuf.as_buffer().tolist() + assert tst == [13, 14] + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_symbolic_jit.py b/tinygrad_repo/test/test_symbolic_jit.py index 05608180aa..1529e3bc21 100644 --- a/tinygrad_repo/test/test_symbolic_jit.py +++ b/tinygrad_repo/test/test_symbolic_jit.py @@ -2,9 +2,18 @@ import unittest from test.helpers import assert_jit_cache_len from tinygrad import Variable, Tensor, TinyJit +from tinygrad.helpers import Context import numpy as np class TestSymbolicJit(unittest.TestCase): + def setUp(self): + # A lot of these test are out of bounds, so we ignore the bounds check + self.context = Context(IGNORE_OOB=1) + self.context.__enter__() + + def tearDown(self): + self.context.__exit__(None, None, None) + def test_plus1(self): def f(a): return (a+1).realize() jf = TinyJit(f) @@ -175,6 +184,19 @@ class TestSymbolicJit(unittest.TestCase): np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) assert_jit_cache_len(jf, 1) + def test_slice(self): + # slice 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[3:5, vi:vi+2] + symbolic = jf(symbolic).numpy() + expected = f(a[3:5, i:i+2]).numpy() + np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) + assert_jit_cache_len(jf, 1) + def test_ones_sum(self): def f(a): return a.sum().realize() jf = TinyJit(f) @@ -290,4 +312,4 @@ class TestSymbolicJit(unittest.TestCase): np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) if __name__ == '__main__': - unittest.main() \ No newline at end of file + unittest.main() diff --git a/tinygrad_repo/test/test_symbolic_ops.py b/tinygrad_repo/test/test_symbolic_ops.py index a654654528..76bb3e87ef 100644 --- a/tinygrad_repo/test/test_symbolic_ops.py +++ b/tinygrad_repo/test/test_symbolic_ops.py @@ -1,10 +1,20 @@ import unittest -from tinygrad import Variable -from tinygrad.tensor import Tensor +from tinygrad import Tensor, Variable +from tinygrad.shape.shapetracker import View +from tinygrad.helpers import Context, GlobalCounters +from tinygrad.uop.ops import sym_infer from examples.gpt2 import Attention import numpy as np class TestSymbolicOps(unittest.TestCase): + def setUp(self): + # A lot of these test are out of bounds, so we ignore the bounds check + self.context = Context(IGNORE_OOB=1) + self.context.__enter__() + + def tearDown(self): + self.context.__exit__(None, None, None) + def test_plus1(self): def f(a): return (a+1).realize() for i in range(1, 5): @@ -34,17 +44,32 @@ class TestSymbolicOps(unittest.TestCase): 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 test_attention(self, dropout_p=0.0, imin=1, imax=5, use_symbolic=True): 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) + for i in range(imin, imax): + vi = Variable("i", 1, 10).bind(i) if use_symbolic else i q = Tensor.rand(2, 1, 4, 8) k = Tensor.rand(2, i, 4, 8) v = Tensor.rand(2, i, 4, 8) + Tensor.realize(q, k, v) + GlobalCounters.reset() 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_cmp_symbolic(self): + # symbolic isn't seeing if i == i, so it's not putting them on the same axis + self.test_attention(imin=4, imax=5, use_symbolic=False) + self.test_attention(imin=4, imax=5, use_symbolic=True) + + # until this works, symbolic single kernel softmax won't + @unittest.expectedFailure + def test_attention_simple_view(self): + i = Variable("i", 2, 10) + v1 = View.create((2,4,1,i,i), ((i*4),i,0,0,1)) + v2 = View.create((2,4,1,i,i,i), (((i*i)*4),(i*i),0,0,i,1)) + self.assertIsNotNone(v1+v2) + def test_attention_training(self): with Tensor.train(): self.test_attention(dropout_p=0.0) @@ -139,6 +164,15 @@ class TestSymbolicOps(unittest.TestCase): expected = a.shrink(((3,5),(i,i+2))).numpy() np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) + def test_slice(self): + for i in range(1, 5): + vi = Variable("i", 1, 10).bind(i) + a = Tensor.rand(7, 11) + symbolic = a[3:5, vi:vi+2] + symbolic = symbolic.numpy() + expected = a[3:5, i:i+2].numpy() + np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) + def test_ones_sum(self): for i in range(1, 5): vi = Variable("i", 1, 10).bind(i) @@ -187,5 +221,18 @@ class TestSymbolicOps(unittest.TestCase): symbolic = a.reshape(vi, vj).var(axis).reshape(expected.shape).numpy() np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) + @unittest.expectedFailure + def test_conv2d_ceildiv_edge_case(self): + v = Variable('v', 11, 50_000) + val = 39601 + x = Tensor.randn(1, 22, 39601).reshape(1, 22, v.bind(val)) + weight = Tensor.randn(256, 22, 12) + + result = x.conv2d(weight=weight, groups=1, stride=6, dilation=1, padding=(3, 3)) + var_val = {v: val} + shape = tuple(sym_infer(s, var_val) for s in result.shape) + self.assertEqual(shape, (1, 256, 6600)) # TODO: fails if ceildiv is incorrect + # TODO: test output is correct + if __name__ == '__main__': - unittest.main() \ No newline at end of file + unittest.main() diff --git a/tinygrad_repo/test/test_tensor.py b/tinygrad_repo/test/test_tensor.py index 3a5853e2c5..8f4403139a 100644 --- a/tinygrad_repo/test/test_tensor.py +++ b/tinygrad_repo/test/test_tensor.py @@ -3,11 +3,15 @@ import numpy as np import torch import unittest, copy, mmap, random, math, array from tinygrad import Tensor, Device, dtypes -from tinygrad.engine.schedule import create_schedule -from tinygrad.helpers import getenv, temp, _METADATA, mv_address +from tinygrad.tensor import _METADATA +from tinygrad.helpers import getenv, temp, mv_address from extra.gradcheck import numerical_jacobian, jacobian, gradcheck from hypothesis import given, settings, strategies as strat from tinygrad.device import is_dtype_supported +from tinygrad.uop.ops import Ops, UOp +from tinygrad.runtime.support.compiler_cuda import PTX +from tinygrad.codegen import full_rewrite +from tinygrad.dtype import DType settings.register_profile("my_profile", max_examples=200, deadline=None, derandomize=getenv("DERANDOMIZE_CI", False)) settings.load_profile("my_profile") @@ -58,17 +62,16 @@ class TestTinygrad(unittest.TestCase): np.testing.assert_allclose(x, y, atol=1e-5) # A simple test is to check that we can accumulate gradients (run backward twice or more times) - # This will only work if retain_graph works. - def test_retain_graph(self): + def test_accumulate_gradients(self): 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(retain_graph=True) + out.backward() xgrad,wgrad = x.grad, W.grad - out.backward(retain_graph=True) + out.backward() xgrad2,wgrad2 = x.grad, W.grad out.backward() # no need to retain again since we will not re-run backward xgrad3,wgrad3 = x.grad, W.grad @@ -148,6 +151,27 @@ class TestTinygrad(unittest.TestCase): for x,y in zip(test_tinygrad(), test_pytorch()): np.testing.assert_allclose(x, y, atol=1e-5, rtol=1e-6) + @unittest.expectedFailure + def test_const_backward_pass(self): + init = 3.5 + + def test_pytorch(): + w1 = torch.tensor(init, requires_grad=True) + w2 = torch.tensor(init, requires_grad=True) + out = w1.add(w2) + out.backward() + return w1.grad, w2.grad + + def test_tinygrad(): + w1 = Tensor(init, requires_grad=True) + w2 = Tensor(init, requires_grad=True) + out = w1.add(w2) + out.backward() + return w1.grad.numpy(), w2.grad.numpy() + + 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) @@ -211,6 +235,13 @@ class TestTinygrad(unittest.TestCase): b = random_fn(10,10).realize() np.testing.assert_allclose(a.numpy(), b.numpy()) + def test_randperm(self): + Tensor.manual_seed(0) + a = Tensor.randperm(10).realize() + np.testing.assert_equal(a.numpy(), [5, 2, 8, 1, 3, 7, 9, 6, 0, 4]) + b = Tensor.randperm(1000).realize() + np.testing.assert_equal(set(b.numpy()), set(range(1000))) + 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 @@ -243,7 +274,7 @@ class TestTinygrad(unittest.TestCase): assert a.shape == b.shape, f"shape mismatch {a.shape} != {b.shape}" def test_rand_like_device(self): - a = Tensor.ones(3, 3, device="CLANG") + a = Tensor.ones(3, 3, device="CPU") b = Tensor.rand_like(a) self.assertEqual(b.device, a.device) @@ -322,7 +353,7 @@ class TestTinygrad(unittest.TestCase): def test_tensor_from_blob(self): x = memoryview(bytearray(16)).cast('I') - t = Tensor.from_blob(mv_address(x), (4,), dtype=dtypes.int, device="CLANG") + t = Tensor.from_blob(mv_address(x), (4,), dtype=dtypes.int, device="CPU") z = (t+1) np.testing.assert_equal(z.numpy(), [1, 1, 1, 1]) @@ -410,7 +441,7 @@ class TestTinygrad(unittest.TestCase): def test_tensor_dtype_errors(self): with self.assertRaises(AttributeError): Tensor([3], dtype="typo") - with self.assertRaises(TypeError): Tensor([3], dtype=(dtypes.int,)) + with self.assertRaises(AttributeError): Tensor([3], dtype=(dtypes.int,)) def test_tensor_bytes(self): data = b"abc123" @@ -465,7 +496,7 @@ class TestTinygrad(unittest.TestCase): def test_repr_with_grad(self): a = Tensor([1], requires_grad=True) b = Tensor([1]) - c = (a + b).mean().backward() + c = (a + b).sum().backward() print(a) print(c) @@ -481,6 +512,12 @@ class TestTinygrad(unittest.TestCase): subprocess.run([f'NPY=1 {Device.DEFAULT}=1 python3 -c "from tinygrad import Device; assert Device.DEFAULT == \\"{Device.DEFAULT}\\""'], shell=True, check=True) + def test_no_attributeerror_after_apply_uop_exception(self): + try: + Tensor.arange(4).reshape(3,2) + except ValueError: + Tensor.zeros(2, 2).realize() + @unittest.skip("this test is just flaky, sync issue") class TestMoveTensor(unittest.TestCase): d0, d1 = f"{Device.DEFAULT}:0", f"{Device.DEFAULT}:1" @@ -647,10 +684,26 @@ class TestZeroShapeTensor(unittest.TestCase): def test_clone(self): a = Tensor.rand(16, 16).realize() - np.testing.assert_allclose(a.numpy(), a.clone().numpy()) + b = a.clone() + np.testing.assert_allclose(a.numpy(), b.numpy()) + self.assertIsNot(a.lazydata.base.buffer, b.lazydata.base.buffer) a = Tensor.rand(16, 16).mul(5.0).add(5.0) - np.testing.assert_allclose(a.numpy(), a.clone().numpy()) + b = a.clone() + np.testing.assert_allclose(a.numpy(), b.numpy()) + self.assertIsNot(a.lazydata.base.buffer, b.lazydata.base.buffer) + + def test_clone_with_shrink(self): + a = Tensor.rand(16, 16) + b = a.shrink(((2, 10), None)).clone() + b.realize() + self.assertIsNot(a.lazydata.base.buffer, b.lazydata.base.buffer) + + def test_clone_with_shrink_realized(self): + a = Tensor.rand(16, 16).realize() + b = a.shrink(((2, 10), None)).clone() + b.realize() + self.assertIsNot(a.lazydata.base.buffer, b.lazydata.base.buffer) def test_clone_with_grad(self): a = Tensor.rand(16, 16, requires_grad=True) @@ -669,7 +722,7 @@ class TestZeroShapeTensor(unittest.TestCase): class TestTensorCreationDevice(unittest.TestCase): # test auxiliary tensors are created on the same device def test_one_hot(self): - y = Tensor([1, 2, 3]).to("CLANG") + y = Tensor([1, 2, 3]).to("CPU") x = y.one_hot(10) x.realize() @@ -720,12 +773,29 @@ class TestInferenceMode(unittest.TestCase): class TestTensorMetadata(unittest.TestCase): def setUp(self) -> None: _METADATA.set(None) + + # NOOPs are not included in kernel metadata + def test_exclude_noop_metadata(self): + a = Tensor.rand(4, 4)*1 + self.assertEqual(a.lazydata.metadata.name, "__mul__") + k = a.schedule()[-1] + self.assertEqual([m.name for m in k.metadata], ["rand"]) + + # we exclude const from kernel metadata because tensor methods can share the same CONST UOp + @unittest.skip("TODO: flaky") + def test_exclude_const_metadata(self): + a = Tensor.arange(4) + b = Tensor.full((4,), -1, dtype=dtypes.int).contiguous() + sched = Tensor.schedule(a, b) + self.assertEqual([m.name for m in sched[0].metadata], ["arange"]) + self.assertEqual([m.name for m in sched[1].metadata], ["contiguous"]) + def test_matmul(self): x = Tensor.rand(3, requires_grad=True) W = Tensor.rand(3, 3, requires_grad=True) out = x.matmul(W) self.assertEqual(out.lazydata.metadata.name, "matmul") - si = create_schedule([out.lazydata])[-1] + si = out.schedule()[-1] self.assertEqual(len(si.metadata), 1) self.assertEqual(si.metadata[0].name, "matmul") @@ -733,7 +803,7 @@ class TestTensorMetadata(unittest.TestCase): x = Tensor.rand(3, requires_grad=True) out = x.relu() self.assertEqual(out.lazydata.metadata.name, "relu") - si = create_schedule([out.lazydata])[-1] + si = out.schedule()[-1] self.assertEqual(len(si.metadata), 1) self.assertEqual(si.metadata[0].name, "relu") @@ -744,13 +814,13 @@ class TestTensorMetadata(unittest.TestCase): self.assertEqual(out.lazydata.metadata.name, "__mul__") self.assertEqual(out.lazydata.src[0].metadata.name, "relu") self.assertEqual(out.lazydata.src[1].metadata.name, "sigmoid") - si = create_schedule([out.lazydata])[-1] + si = out.schedule()[-1] self.assertEqual(len(si.metadata), 3) self.assertEqual(set(m.name for m in si.metadata), {"relu", "sigmoid", "__mul__"}) def test_complex_backward(self): - x = Tensor.rand(3, requires_grad=True) - y = Tensor.rand(3, requires_grad=True) + x = Tensor.rand(3, requires_grad=True).realize() + y = Tensor.rand(3, requires_grad=True).realize() out = (x.relu() * y.sigmoid()).sum() self.assertEqual(out.lazydata.metadata.name, "sum") out.backward() @@ -758,12 +828,80 @@ class TestTensorMetadata(unittest.TestCase): self.assertTrue(x.grad.lazydata.metadata.backward) self.assertEqual(y.grad.lazydata.metadata.name, "sigmoid") self.assertTrue(y.grad.lazydata.metadata.backward) - si = create_schedule([out.lazydata, x.grad.lazydata, y.grad.lazydata])[-1] + si = Tensor.schedule(out, x.grad, y.grad)[-1] self.assertEqual(len(si.metadata), 3, f"failed with {si.metadata}") self.assertEqual(set(m.name for m in si.metadata), {"sigmoid", "sigmoid", "relu"}) bw = [m for m in si.metadata if m.backward] self.assertEqual(len(bw), 1) self.assertEqual(bw[0].name, "sigmoid") +class TestIdxUpcast(unittest.TestCase): + def _find_op(self, ast: UOp, op: Ops): + if ast.op is op: return ast + for src in ast.src: + if (ret:=self._find_op(src, op)) is not None: return ret + def _schedule_render(self, a: Tensor): + schedule, _ = a.schedule_with_vars() + for s in schedule: + if s.ast.op is Ops.SINK: + renderer = Device[s.bufs[0].device].renderer + uops = full_rewrite(s.ast, renderer) + renderer.render(uops) + return uops + + def _assert(self, dtype: DType, a: Tensor): + uops = self._schedule_render(a) + # Assert the dtype of the INDEX value, This will need be updated if UOp spec changes + store = next(uop for uop in uops if uop.op is Ops.STORE) + assert store.op is Ops.STORE + idx = self._find_op(store, Ops.INDEX) + if idx is not None: # PTX turns Ops.INDEX into pointer arithmetic earlier than cstyle, plus it's already cast to int64 + assert idx.op is Ops.INDEX + idx_val = idx.src[1] + assert idx_val.dtype is dtype + + # use expand to generate kernel that uses large idx + def do_op_then_assert(self, dtype: DType, dim1, dim2, dim3): + self._assert(dtype, Tensor.empty(dim1, dim2, 1).expand(-1, -1, dim3).contiguous()) + + @unittest.skipUnless(is_dtype_supported(dtypes.long), "int64 is supported") + def test_overflow(self): + # 2**11, 2**11, 2**11 -> 2**33 will overflow when indexed + self.do_op_then_assert(dtypes.long, 2048, 2048, 2048) + + @unittest.skipUnless(is_dtype_supported(dtypes.long), "int64 is supported") + def test_overflow_sym(self): + self.do_op_then_assert(dtypes.long, 2048, 2048, UOp.variable("dim3", 0, 2048).bind(32)) + + def test_regular(self): + self.do_op_then_assert(dtypes.int, 64, 64, 64) + + def test_regular_sym(self): + self.do_op_then_assert(dtypes.int, 2048, 2048, UOp.variable("dim3", 0, 64).bind(32)) + + @unittest.skipIf(PTX, "PTX always convert Ops.INDEX to int64") + def test_symfold(self): + # This would cause an overflow, but after sym fold it's within int32 + a = Tensor.arange(65535) + uops = self._schedule_render(a) + assert all(uop.dtype is not dtypes.long for uop in uops) + + @unittest.skipIf(is_dtype_supported(dtypes.long), "int64 is supported") + def test_int64_unsupported_overflow_sym(self): + with self.assertRaises(KeyError): + self.do_op_then_assert(dtypes.long, 2048, 2048, UOp.variable("dim3", 0, 2048).bind(32)) + + @unittest.skipIf(is_dtype_supported(dtypes.long), "int64 is supported") + def test_int64_unsupported_overflow(self): + with self.assertRaises(KeyError): + self.do_op_then_assert(dtypes.long, 2048, 2048, 2048) + + @unittest.skip("This is kept for reference, it requires large memory to run") + def test_overflow_kernel_run(self): + # This creates a total of 2**31+10 elements, requiring at least 2147 MB memory to run + # Modified example from issue 3271 + a = Tensor.empty(2**11, 2**11, 1, dtype=dtypes.int8).permute((2, 0, 1)).expand((2**9+10, -1, -1)).contiguous() + a.realize() + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_lazybuffer.py b/tinygrad_repo/test/test_tensor_uop.py similarity index 74% rename from tinygrad_repo/test/test_lazybuffer.py rename to tinygrad_repo/test/test_tensor_uop.py index 040c7ad926..d6fc085e06 100644 --- a/tinygrad_repo/test/test_lazybuffer.py +++ b/tinygrad_repo/test/test_tensor_uop.py @@ -3,10 +3,9 @@ import numpy as np import unittest from tinygrad import Tensor, Device, dtypes from tinygrad.engine.realize import run_schedule -from tinygrad.ops import Ops, UOp -from tinygrad.engine.schedule import create_schedule +from tinygrad.uop.ops import Ops, UOp, UPat -class TestLazyBuffer(unittest.TestCase): +class TestTensorUOp(unittest.TestCase): def test_fromcpu_shape_tracker(self): def helper(a: np.ndarray): print(a.shape, a.strides, a.flags.c_contiguous) @@ -62,53 +61,61 @@ class TestLazyBuffer(unittest.TestCase): def test_const_dtype(self): lb: UOp = Tensor([1], dtype=dtypes.int).lazydata - assert lb.const_like(1).const_arg == 1 - assert type(lb.const_like(1).const_arg) is int + assert lb.const_like(1).base.arg == 1 + assert type(lb.const_like(1).base.arg) is int lb: UOp = Tensor([1], dtype=dtypes.float).lazydata - assert lb.const_like(1).const_arg == 1.0 - assert type(lb.const_like(1).const_arg) is float + assert lb.const_like(1).base.arg == 1.0 + assert type(lb.const_like(1).base.arg) is float - def test_forced_realized_alu(self): + def test_contiguous_alu(self): a = Tensor.randn(2, 2).realize() b = Tensor.randn(2, 2).realize() add = (a+b).contiguous() out = add+2 - sched = create_schedule([out.lazydata]) + sched = out.schedule() self.assertEqual(len(sched), 2) run_schedule(sched) np.testing.assert_allclose(out.numpy(), a.numpy()+b.numpy()+2) - def test_forced_realized_metaop(self): + # NOTE: contiguous on a buffer collapses + def test_contiguous_empty(self): empty = Tensor.empty(1).contiguous() - sched = create_schedule([empty.lazydata]) - self.assertEqual(len(sched), 1) - self.assertIs(sched[0].ast.op, Ops.EMPTY) - run_schedule(sched) - + sched = empty.schedule() + self.assertEqual(len(sched), 0) + + def test_contiguous_folded_alu(self): + a = Tensor.empty(8, 8) + # NOTE: the buffer for mul_0 late folds to just a CONST + mul_0 = a*0 + out = mul_0.shrink(((4, 8), (0, 8))).contiguous() + out.realize() + self.assertEqual(out.tolist(), Tensor.zeros(4, 8).tolist()) + +reduce_kernel = UPat(Ops.SINK, src=(UPat(Ops.STORE, src=(UPat(), UPat(), UPat(Ops.REDUCE_AXIS))))) class TestReduceOp(unittest.TestCase): def test_no_split_reduce_kernel(self): a = Tensor.rand(4, 4).realize() a = a.sum() - sched = create_schedule([a.lazydata]) + sched = a.schedule() assert len(sched) == 1 - self.assertIs(sched[0].ast.src[0].src[2].op, Ops.REDUCE_AXIS) + assert reduce_kernel.match(sched[0].ast, {}) def test_split_reduce_kernel_dim0(self): a = Tensor.rand(256, 255).realize() a = a.sum() - sched = create_schedule([a.lazydata]) + sched = a.schedule() assert len(sched) == 2 for s in sched: - self.assertIs(s.ast.src[0].src[2].op, Ops.REDUCE_AXIS) + assert reduce_kernel.match(s.ast, {}) def test_split_reduce_kernel_dim1(self): a = Tensor.rand(255, 256).realize() a = a.sum() - sched = create_schedule([a.lazydata]) + sched = a.schedule() assert len(sched) == 2 for s in sched: - self.assertIs(s.ast.src[0].src[2].op, Ops.REDUCE_AXIS) + assert reduce_kernel.match(s.ast, {}) if __name__ == "__main__": unittest.main() diff --git a/tinygrad_repo/test/test_tensor_variable.py b/tinygrad_repo/test/test_tensor_variable.py index eb7ddeb386..a680cf9a6e 100644 --- a/tinygrad_repo/test/test_tensor_variable.py +++ b/tinygrad_repo/test/test_tensor_variable.py @@ -1,6 +1,7 @@ import unittest import numpy as np from tinygrad import Tensor, Variable +from tinygrad.helpers import Context class TestTensorVariable(unittest.TestCase): def test_add_tvar(self): @@ -22,38 +23,43 @@ class TestTensorVariable(unittest.TestCase): assert (Tensor(3) * (vv * 4)).item() == 24 def test_symbolic_mean(self): - vv = Variable("a", 1, 10).bind(2) - t = Tensor.ones(2, 2).contiguous().reshape(2, vv) - ret = t.mean().item() - assert ret == 1 + with Context(IGNORE_OOB=1): + vv = Variable("a", 1, 10).bind(2) + t = Tensor.ones(2, 2).contiguous().reshape(2, vv) + ret = t.mean().item() + assert ret == 1 def test_symbolic_mean_2d(self): - vv = Variable("a", 1, 10).bind(2) - vv2 = Variable("b", 1, 10).bind(2) - t = Tensor.ones(2, 2).contiguous().reshape(vv2, vv) - ret = t.mean().item() - assert ret == 1 + with Context(IGNORE_OOB=1): + vv = Variable("a", 1, 10).bind(2) + vv2 = Variable("b", 1, 10).bind(2) + t = Tensor.ones(2, 2).contiguous().reshape(vv2, vv) + ret = t.mean().item() + assert ret == 1 def test_symbolic_mean_2d_axis_1(self): - vv = Variable("a", 1, 10).bind(2) - vv2 = Variable("b", 1, 10).bind(2) - t = Tensor.ones(2, 2).contiguous().reshape(vv2, vv) - ret = t.mean(axis=1).reshape(2, 1).numpy() - assert np.all(ret == 1) + with Context(IGNORE_OOB=1): + vv = Variable("a", 1, 10).bind(2) + vv2 = Variable("b", 1, 10).bind(2) + t = Tensor.ones(2, 2).contiguous().reshape(vv2, vv) + ret = t.mean(axis=1).reshape(2, 1).numpy() + assert np.all(ret == 1) def test_symbolic_mean_2d_add(self): - add_term = Variable("c", 0, 10).bind(1) - vv = Variable("a", 1, 10).bind(1) - vv2 = Variable("b", 1, 10).bind(1) - t = Tensor.ones(2, 2).contiguous().reshape(vv2+add_term, vv+add_term) - ret = t.mean().item() - assert ret == 1 + with Context(IGNORE_OOB=1): + add_term = Variable("c", 0, 10).bind(1) + vv = Variable("a", 1, 10).bind(1) + vv2 = Variable("b", 1, 10).bind(1) + t = Tensor.ones(2, 2).contiguous().reshape(vv2+add_term, vv+add_term) + ret = t.mean().item() + assert ret == 1 def test_symbolic_var(self): - vv = Variable("a", 1, 10).bind(2) - t = Tensor.ones(2, 2).contiguous().reshape(2, vv) - ret = t.var().item() - assert ret == 0 + with Context(IGNORE_OOB=1): + vv = Variable("a", 1, 10).bind(2) + t = Tensor.ones(2, 2).contiguous().reshape(2, vv) + ret = t.var().item() + assert ret == 0 def test_symbolic_pad(self): vv = Variable("a", 1, 10).bind(2) diff --git a/tinygrad_repo/test/test_tiny.py b/tinygrad_repo/test/test_tiny.py index 9001e0078c..0d6798fbab 100644 --- a/tinygrad_repo/test/test_tiny.py +++ b/tinygrad_repo/test/test_tiny.py @@ -1,7 +1,7 @@ # basic self-contained tests of the external functionality of tinygrad import unittest, random from tinygrad import Tensor, Context, Variable, TinyJit, dtypes, Device, nn -from tinygrad.helpers import IMAGE +from tinygrad.helpers import IMAGE, CI class TestTiny(unittest.TestCase): @@ -11,6 +11,10 @@ class TestTiny(unittest.TestCase): out = Tensor([1.,2,3]) + Tensor([4.,5,6]) self.assertListEqual(out.tolist(), [5.0, 7.0, 9.0]) + def test_plus_int(self): + out = Tensor([1,2,3], dtype=dtypes.int) + Tensor([4,5,6], dtype=dtypes.int) + self.assertListEqual(out.tolist(), [5, 7, 9]) + def test_plus_big(self): out = Tensor.ones(16).contiguous() + Tensor.ones(16).contiguous() self.assertListEqual(out.tolist(), [2]*16) @@ -23,7 +27,7 @@ class TestTiny(unittest.TestCase): out = Tensor.ones(256).contiguous().sum() self.assertEqual(out.item(), 256) - def test_gemm(self, N=4, out_dtype=dtypes.float): + def test_gemm(self, N=64, out_dtype=dtypes.float): a = Tensor.ones(N,N).contiguous() b = Tensor.eye(N).contiguous() self.assertListEqual((out:=a@b).flatten().tolist(), [1.0]*(N*N)) @@ -63,25 +67,29 @@ class TestTiny(unittest.TestCase): # *** BEAM (for Kernel speed) *** def test_beam(self): - with Context(BEAM=1): self.test_plus() + with Context(BEAM=1, IGNORE_BEAM_CACHE=1): self.test_plus() # *** symbolic (to allow less recompilation) *** def test_symbolic(self): i = Variable('i', 1, 10) - for s in [2,5]: - ret = Tensor.ones(s).contiguous().reshape(i.bind(s)) + 1 - self.assertListEqual(ret.reshape(s).tolist(), [2.0]*s) + with Context(IGNORE_OOB=1): + for s in [2,5]: + ret = Tensor.ones(s).contiguous().reshape(i.bind(s)) + 1 + self.assertListEqual(ret.reshape(s).tolist(), [2.0]*s) def test_symbolic_reduce(self): i = Variable('i', 1, 10) - for s in [2,5]: - ret = Tensor.ones(s).contiguous().reshape(i.bind(s)).sum() - self.assertEqual(ret.item(), s) + with Context(IGNORE_OOB=1): + for s in [2,5]: + ret = Tensor.ones(s).contiguous().reshape(i.bind(s)).sum() + self.assertEqual(ret.item(), s) # *** a model *** - def test_mnist_model(self): + # TODO: this is failing because of how swizzling rewrites the ShapeTracker of the final STORE + @unittest.skipIf(IMAGE>0 or (CI and Device.DEFAULT == "DSP"), "failing because of make things that can't be images not images") + def test_mnist(self): layers = [ nn.Conv2d(1, 32, 5), Tensor.relu, nn.Conv2d(32, 32, 5), Tensor.relu, @@ -91,8 +99,8 @@ class TestTiny(unittest.TestCase): nn.BatchNorm(64), Tensor.max_pool2d, lambda x: x.flatten(1), nn.Linear(576, 10)] - # pre-realize random weights - for p in nn.state.get_parameters(layers): p.realize() + # replace random weights with ones + for p in nn.state.get_parameters(layers): p.replace(Tensor.ones_like(p).contiguous()).realize() # run model inference probs = Tensor.rand(1, 1, 28, 28).sequential(layers).tolist() @@ -102,11 +110,10 @@ class TestTiny(unittest.TestCase): @unittest.skipIf(Device.DEFAULT != "GPU", "image only supported on GPU") def test_image(self): - with Context(IMAGE=2): self.test_gemm(out_dtype=dtypes.imagef((4, 1, 4))) + with Context(IMAGE=2): self.test_gemm(N=4, out_dtype=dtypes.imagef((4, 1, 4))) def test_beam_image(self): - with Context(BEAM=1): self.test_image() + with Context(BEAM=1, IGNORE_BEAM_CACHE=1): self.test_image() if __name__ == '__main__': unittest.main() - diff --git a/tinygrad_repo/test/test_transcendental.py b/tinygrad_repo/test/test_transcendental.py index 3a4df6cb6d..932cfa2935 100644 --- a/tinygrad_repo/test/test_transcendental.py +++ b/tinygrad_repo/test/test_transcendental.py @@ -1,11 +1,12 @@ import unittest from tinygrad import Tensor, Device, dtypes from tinygrad.tensor import _to_np_dtype -from tinygrad.helpers import Context, getenv +from tinygrad.helpers import Context, getenv, CI, OSX from test.test_schedule import check_schedule from test.test_dtype_alu import ht, dtypes_float from tinygrad.device import is_dtype_supported import numpy as np +import math from hypothesis import given, settings, strategies as strat settings.register_profile("my_profile", max_examples=200, deadline=None, derandomize=getenv("DERANDOMIZE_CI", False)) @@ -13,7 +14,7 @@ settings.load_profile("my_profile") class TestTranscendentalMath(unittest.TestCase): @unittest.skipUnless(is_dtype_supported(dtypes.float64, Device.DEFAULT), f"no float64 on {Device.DEFAULT}") - @unittest.skipIf(getenv("MOCKGPU") and Device.DEFAULT == "NV", "crashed") + @unittest.skipIf(getenv("MOCKGPU") and Device.DEFAULT in {"NV", "CUDA"}, "crashed") @given(ht.float64, strat.sampled_from([(Tensor.exp, np.exp), (Tensor.log, np.log), (Tensor.sin, np.sin)])) def test_float64(self, x, op): if op[0] == Tensor.sin: @@ -24,17 +25,23 @@ class TestTranscendentalMath(unittest.TestCase): op[1](np.array([x], dtype=_to_np_dtype(dtypes.float64))), atol=3e-2, rtol=1e-5) # sin can have bigger atol for very big x - @unittest.skipIf(getenv("MOCKGPU") and Device.DEFAULT == "NV", "crashed") - @given(ht.float32, strat.sampled_from([(Tensor.exp, np.exp), (Tensor.log, np.log), (Tensor.sin, np.sin)])) + @unittest.skipIf(getenv("MOCKGPU") and Device.DEFAULT in {"NV", "CUDA"}, "crashed") + @given(ht.float32, strat.sampled_from([(Tensor.exp, np.exp),(Tensor.log, np.log)] + + ([(Tensor.sin, np.sin)] if is_dtype_supported(dtypes.ulong) else []))) def test_float32(self, x, op): + # wrong nan behavior on Vulkan + if (math.isnan(x) or (x < 0 and op[0] == Tensor.log)) and CI and Device.DEFAULT == "WEBGPU" and not OSX: return with Context(TRANSCENDENTAL=2), np.errstate(all='ignore'): np.testing.assert_allclose(op[0](Tensor([x], dtype=dtypes.float32)).numpy(), op[1](np.array([x], dtype=_to_np_dtype(dtypes.float32))), atol=2e-5, rtol=1e-5) @unittest.skipUnless(is_dtype_supported(dtypes.float16, Device.DEFAULT), f"no float16 on {Device.DEFAULT}") - @given(ht.float16, strat.sampled_from([(Tensor.exp, np.exp), (Tensor.log, np.log), (Tensor.sin, np.sin)])) + @given(ht.float16, strat.sampled_from([(Tensor.exp, np.exp),(Tensor.log, np.log)] + + ([(Tensor.sin, np.sin)] if is_dtype_supported(dtypes.ulong) else []))) def test_float16(self, x, op): + # wrong nan behavior on Vulkan + if (math.isnan(x) or (x < 0 and op[0] == Tensor.log)) and CI and Device.DEFAULT == "WEBGPU" and not OSX: return with Context(TRANSCENDENTAL=2), np.errstate(all='ignore'): np.testing.assert_allclose(op[0](Tensor([x], dtype=dtypes.float16)).numpy(), op[1](np.array([x], dtype=_to_np_dtype(dtypes.float16))), @@ -52,11 +59,12 @@ class TestTranscendentalMath(unittest.TestCase): class TestFromFuzzer(unittest.TestCase): @given(strat.sampled_from(dtypes_float)) + @unittest.skipUnless(is_dtype_supported(dtypes.ulong), "Needs ulong") def test_sin(self, dtype): if not is_dtype_supported(dtype): return if dtype == dtypes.float64: # crashes in CI CUDA - if getenv("MOCKGPU") and Device.DEFAULT == "NV": return + if getenv("MOCKGPU") and Device.DEFAULT in {"NV", "CUDA"}: return def _test_value(n: float, unit: float=1.0): next_float = np.nextafter(1.0, 2.0, dtype=_to_np_dtype(dtype)) ulp = next_float - 1.0 @@ -74,11 +82,12 @@ class TestFromFuzzer(unittest.TestCase): _test_value(np.pi * 2, unit=1.5) @given(strat.sampled_from(dtypes_float)) + @unittest.skipIf(Device.DEFAULT == "WEBGPU" and CI, "Nan location mismatch on Vulkan, Metal works") def test_log2(self, dtype): if not is_dtype_supported(dtype): return if dtype == dtypes.float64: # crashes in CI CUDA - if getenv("MOCKGPU") and Device.DEFAULT == "NV": return + if getenv("MOCKGPU") and Device.DEFAULT in {"NV", "CUDA"}: return def _test_value(n: float, unit: float=1.0): next_float = np.nextafter(1.0, 2.0, dtype=_to_np_dtype(dtype)) ulp = next_float - 1.0 @@ -93,6 +102,7 @@ class TestFromFuzzer(unittest.TestCase): _test_value(0.0000009) class TestTranscendentalSchedule(unittest.TestCase): + @unittest.skipUnless(is_dtype_supported(dtypes.ulong), "Needs ulong") def test_transcendental_sin_fusion(self): with Context(TRANSCENDENTAL=2): a = Tensor.empty(10) @@ -117,5 +127,37 @@ class TestTranscendentalSchedule(unittest.TestCase): c = c.exp2() check_schedule(c, 1) +class TestTranscendentalVectorized(unittest.TestCase): + def _vectorized_data(self, low, high, vec_size): + np_data = np.linspace(low, high, num=(128 // vec_size) * vec_size, dtype=np.float32).reshape(-1, vec_size) + data = Tensor(np_data, dtype=dtypes.float32.vec(vec_size)) + return data, np_data + + def _test_vectorized_op(self, fxn, np_fxn, data_range, vec_size, param_range=None): + data, np_data = self._vectorized_data(data_range[0], data_range[1], vec_size) + if param_range: + param, np_param = self._vectorized_data(param_range[0], param_range[1], vec_size) + out, np_out = fxn(data, param), np_fxn(np_data, np_param) + else: + out, np_out = fxn(data), np_fxn(np_data) + np.testing.assert_allclose(out.numpy(), np_out, rtol=1e-4) + + def test_exp2_vectorized(self): + for vec_size in [1,2,3,4,5,127,128]: self._test_vectorized_op(Tensor.exp2, np.exp2, (-100, 100), vec_size) + + def test_log2_vectorized(self): + for vec_size in [1,2,3,4,5,127,128]: self._test_vectorized_op(Tensor.log2, np.log2, (0.001, 200), vec_size) + + @unittest.skipIf(getenv("DSP"), "requires int division") + def test_sin_vectorized(self): + for vec_size in [1,2,3,4,5,127,128]: self._test_vectorized_op(Tensor.sin, np.sin, (-100, 100), vec_size) + + def test_pow_vectorized(self): + # np.pow returns nan for negative values raised to a non-integral power + for vec_size in [1,2,3,4,5,127,128]: self._test_vectorized_op(Tensor.pow, np.pow, (0.001, 200), vec_size, param_range=(-10, 10)) + + def test_sqrt_vectorized(self): + for vec_size in [1,2,3,4,5,127,128]: self._test_vectorized_op(Tensor.sqrt, np.sqrt, (0, 100), vec_size) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/test_uop_graph.py b/tinygrad_repo/test/test_uop_graph.py index 55c9d01f73..38418936b6 100644 --- a/tinygrad_repo/test/test_uop_graph.py +++ b/tinygrad_repo/test/test_uop_graph.py @@ -1,13 +1,11 @@ from typing import List -import unittest, time -from tinygrad import dtypes, Device -from tinygrad.helpers import DEBUG -from tinygrad.ops import Ops, UOp, KernelInfo, UPat, PatternMatcher -from tinygrad.renderer import Renderer -from tinygrad.codegen.lowerer import rewrite_shapetracker_with_index -from tinygrad.codegen.uopgraph import full_graph_rewrite, graph_rewrite, expander, sym -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.shape.shapetracker import ShapeTracker, View +import unittest, pytest +from tinygrad import dtypes, Variable +from tinygrad.helpers import DEBUG, Context +from tinygrad.uop.ops import Ops, UOp, UPat, PatternMatcher, track_rewrites, graph_rewrite +from tinygrad.codegen.symbolic import sym +from tinygrad.codegen import full_rewrite, full_rewrite_to_sink +from tinygrad.codegen.expander import expander simple_pm = PatternMatcher([ (UPat.cvar('x', dtypes.int), lambda x: UOp.const(dtypes.float, 1.0) + UOp.const(dtypes.float, 2.0)), @@ -16,51 +14,11 @@ simple_pm = PatternMatcher([ ((UPat.var('x') + UPat.cvar('c1')) + UPat.cvar('c2'), lambda x,c1,c2: x + (c1.arg+c2.arg)), ]) -def to_uops_list(u:List[UOp]) -> List[UOp]: return linearize_uop(full_graph_rewrite(UOp.sink(*u))) - -class TestGraphRewriteEfficiency(unittest.TestCase): - def test_create_many_uops(self): - c1 = UOp.const(dtypes.int, 1) - c2 = UOp.const(dtypes.int, 2) - st = time.perf_counter() - uops = [UOp(Ops.ADD, dtypes.int, (c1, c2)) for _ in range(10000)] - et = time.perf_counter() - st - print(f"created {len(uops)} uops in {et*1000:.2f} ms") - - def test_expand_rewrite(self): - sink = UOp(Ops.SINK, dtypes.void, arg=KernelInfo(local_dims=2, upcasted=4, dont_use_locals=False), src=( - UOp(Ops.STORE, dtypes.void, arg=None, src=( - UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), arg=0, src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=(View(shape=(2, 4, 64, 8, 16, 1, 1, 3, 3, 4, 1), - strides=(1179648, 9216, 1, 147456, 576, 0, 0, 64, 192, 36864, 0), - offset=0, mask=None, contiguous=False),)), src=()), - UOp(Ops.REDUCE_AXIS, dtypes.float, arg=(Ops.ADD, (5, 6, 10)), src=( - UOp(Ops.CAST, dtypes.float, arg=None, src=( - UOp(Ops.MUL, dtypes.half, arg=None, src=( - UOp(Ops.LOAD, dtypes.half, arg=None, src=( - UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=1, src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=( - View(shape=(1, 1024, 1, 64, 4, 17, 4, 17), strides=(0, 14400, 0, 225, 0, 15, 0, 1), offset=-16, - mask=((0, 1), (0, 1024), (0, 1), (0, 64), (0, 4), (1, 16), (0, 4), (1, 16)), contiguous=False), - View(shape=(2, 4, 64, 8, 16, 16, 15, 3, 3, 4, 15), strides=(0, 73984, 4734976, 0, 4624, 295936, 68, 18, 1224, 0, 1), offset=0, - mask=None, contiguous=False))), src=()),)), - UOp(Ops.LOAD, dtypes.half, arg=None, src=( - UOp(Ops.DEFINE_GLOBAL, dtypes.half.ptr(), arg=2, src=()), - UOp(Ops.VIEW, dtypes.void, arg=ShapeTracker(views=( - View(shape=(2, 4, 64, 8, 16, 16, 15, 3, 3, 4, 15), strides=(7200, 0, 230400, 900, 0, 14400, 15, 0, 0, 225, 1), offset=0, - mask=None, contiguous=False),)), src=()),)),)),)),)),)),)) - lower_sink = rewrite_shapetracker_with_index(sink, Device[Device.DEFAULT].renderer) - cnt = [0] - old_init = UOp.__init__ - def uop_hook(self, *args, **kwargs): - cnt[0] += 1 - old_init(self, *args, **kwargs) - UOp.__init__ = uop_hook - st = time.perf_counter() - new_sink = full_graph_rewrite(lower_sink) - et = time.perf_counter() - st - UOp.__init__ = old_init - print(f"rewrote in {et*1000:.2f} ms, from {len(lower_sink.toposort)} -> {len(new_sink.toposort)}, creating {cnt[0]} uops") +def to_uops_list(u:List[UOp]) -> List[UOp]: + # we strip the SINK here for legacy reasons + ret = full_rewrite(UOp.sink(*u)) + assert ret[-1].op is Ops.SINK + return ret[:-1] class TestGraphRewriteConst(unittest.TestCase): def test_gep_const(self): @@ -93,6 +51,57 @@ class TestGraphRewriteConst(unittest.TestCase): self.assertEqual(ret.dtype, dtypes.int.vec(3)) self.assertEqual(ret.arg, 2) +xfail_broken_const_wraparound = pytest.mark.xfail(reason="const folding does not properly implement modular arithmetic") +class TestModularWraparound(unittest.TestCase): + def _test(self, uop:UOp, expected:int): + results = to_uops_list([uop]) + self.assertEqual(len(results), 1) + self.assertEqual(results[0].op, Ops.CONST) + self.assertEqual(results[0].dtype, uop.dtype) + self.assertEqual(results[0].arg, expected) + + @xfail_broken_const_wraparound + def test_cast(self): + t = self._test + t(UOp.const(dtypes.uint, 0xABCD17D6).cast(dtypes.uint8), 0xD6) + t(UOp.const(dtypes.uint, 0xABCD17D6).cast(dtypes.uint8).cast(dtypes.uint), 0xD6) + + @xfail_broken_const_wraparound + def test_mul(self): + t = self._test + t(UOp.const(dtypes.uint, 0xABCD17D6) * 0xAABBCCDD, 1147018174) + t(UOp.const(dtypes.int, 0xABCD17D6) * 10, -1241321892) + + @xfail_broken_const_wraparound + def test_div(self): + t = self._test + t(UOp.const(dtypes.uint, 0xABCD17D6) * 0xAABBCCDD // 11, 104274379) + t(UOp.const(dtypes.int, 0xABCD17D6) * 10 // 11, -112847444) + + @xfail_broken_const_wraparound + def test_neg(self): + t = self._test + t(-UOp.const(dtypes.uint8, 1), 0xFF) + t(-UOp.const(dtypes.uint16, 1), 0xFFFF) + t(-UOp.const(dtypes.uint32, 1), 0xFFFFFFFF) + t(-UOp.const(dtypes.uint64, 1), 0xFFFFFFFFFFFFFFFF) + + @xfail_broken_const_wraparound + def test_neg_min_int(self): + t = self._test + t(-UOp.const(dtypes.int8, -2**7), -2**7) + t(-UOp.const(dtypes.int16, -2**15), -2**15) + t(-UOp.const(dtypes.int32, -2**31), -2**31) + t(-UOp.const(dtypes.int64, -2**63), -2**63) + + @xfail_broken_const_wraparound + def test_payne_hanek_reduction_bug(self): + t = self._test + a = (UOp.const(dtypes.uint, 43748177600).cast(dtypes.uint) | 36).cast(dtypes.ulong) + b = 2536655455 * a + 4294967296 * UOp.const(dtypes.ulong, 25366554550) + c = (b + 2261737165) // 4611686018427387904 + t(c, 0) + class TestGraphRewrite(unittest.TestCase): def test_dedup(self): v1 = UOp(Ops.DEFINE_VAR, dtypes.float) @@ -106,7 +115,7 @@ class TestGraphRewrite(unittest.TestCase): a1 = UOp(Ops.DEFINE_VAR, dtypes.int, (), ("a1", UOp.const(dtypes.int, 0), UOp.const(dtypes.int, 11))) a2 = UOp(Ops.DEFINE_VAR, dtypes.int, (), ("a2", UOp.const(dtypes.int, 0), UOp.const(dtypes.int, 11))) sink = a1.sink(a2) - define_vars = [x for x in graph_rewrite(sink, PatternMatcher([])).toposort if x.op is Ops.DEFINE_VAR] + define_vars = [x for x in graph_rewrite(sink, PatternMatcher([])).toposort() if x.op is Ops.DEFINE_VAR] self.assertEqual(len(define_vars), 1) def test_simple(self): @@ -187,7 +196,7 @@ class TestGraphRewrite(unittest.TestCase): print(sink.render()) self.assertEqual(sink.op, Ops.ADD) self.assertEqual(sink.src[1].op, Ops.CONST) - self.assertEqual(len([x for x in sink.toposort if x.op is Ops.CONST]), 1) + self.assertEqual(len([x for x in sink.toposort() if x.op is Ops.CONST]), 1) class TestUOpGraph(unittest.TestCase): def test_add_constant_fold(self): @@ -255,7 +264,7 @@ class TestUOpGraph(unittest.TestCase): uops = to_uops_list([out]) if DEBUG >= 4: from tinygrad import Device - print(Device[Device.DEFAULT].renderer.render("test", uops)) + print(Device[Device.DEFAULT].renderer.render(uops)) return uops[-1].src[-1] # possible @@ -383,6 +392,78 @@ class TestUOpGraph(unittest.TestCase): self.assertEqual(out.src[1].op, Ops.CONST) self.assertEqual(out.src[1].arg, 6) + def test_bitcast_to_same_dtype_fold(self): + for dt in dtypes.ints + dtypes.floats + (dtypes.bool,): + d0 = UOp(Ops.DEFINE_GLOBAL, dt.ptr(), arg=0) + v = UOp(Ops.LOAD, dt, (d0.index(UOp.const(dtypes.int, 0)),)) + uops = to_uops_list([v.bitcast(dt)]) + self.assertEqual(len([x for x in uops if x.op is Ops.BITCAST]), 0, f"dtype = {dt}") + + def test_in_out_of_bounds_access(self): + with Context(IGNORE_OOB=0): + glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(16), (), 0) + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(UOp.const(dtypes.int, 0)),)) + to_uops_list([ld0]) + ld1 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(UOp.const(dtypes.int, 15)),)) + to_uops_list([ld1]) + ld1 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(UOp.const(dtypes.int, 7)),)) + to_uops_list([ld1]) + + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(UOp.const(dtypes.int, 42)),)) + with self.assertRaises(RuntimeError): to_uops_list([ld0]) + + def test_in_out_of_bounds_access_symbolic(self): + with Context(IGNORE_OOB=0): + glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(16), (), 0) + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(Variable("i", 1, 10)),)) + to_uops_list([ld0]) + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(Variable("i", 0, 15)),)) + to_uops_list([ld0]) + + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(Variable("i", 0, 20)),)) + with self.assertRaises(RuntimeError): to_uops_list([ld0]) + + def test_out_of_bounds_off_by_one_access(self): + with Context(IGNORE_OOB=0): + glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(16), (), 0) + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(UOp.const(dtypes.int, 16)),)) + with self.assertRaises(RuntimeError): to_uops_list([ld0]) + + def test_in_out_bounds_access_with_mask(self): + with Context(IGNORE_OOB=0): + glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(16), (), 0) + gidx0 = UOp(Ops.SPECIAL, dtype=dtypes.int, arg=("gidx0", 42)) + ld0 = UOp(Ops.LOAD, dtypes.int, (glbl0.index(gidx0, (5=0)&(ld0<32)),)) + to_uops_list([ld1]) + + ld1 = UOp(Ops.LOAD, dtypes.int, (glbl1.index(ld0*2, (ld0>=0)&(ld0<64)),)) + with self.assertRaises(RuntimeError): to_uops_list([ld1]) + def test_fold_gated_load(self): glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) glbl1 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 1) @@ -397,7 +478,7 @@ class TestUOpGraph(unittest.TestCase): def test_fold_gated_load_local(self): glbl0 = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) - smem = UOp(Ops.DEFINE_LOCAL, dtypes.int.ptr(local=True), (), ("temp", 1)) + smem = UOp(Ops.DEFINE_LOCAL, dtypes.int.ptr(size=18, local=True), (), "temp") lidx = UOp(Ops.SPECIAL, dtypes.int, (), ("lidx0", 16)) st = UOp(Ops.STORE, dtypes.void, (smem.index(lidx), UOp.load(glbl0.index(lidx), dtype=dtypes.int))) barrier = UOp(Ops.BARRIER, dtypes.void, (st, )) @@ -430,11 +511,10 @@ class TestUOpGraph(unittest.TestCase): def test_switched_range_order(self): glbl = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0) - c0 = UOp.const(dtypes.int, 0) c2 = UOp.const(dtypes.int, 2) cf = UOp.const(dtypes.float, 0.0) - r1 = UOp(Ops.RANGE, dtypes.int, (c0, c2), 0) - r2 = UOp(Ops.RANGE, dtypes.int, (c0, c2), 1) + r1 = UOp(Ops.RANGE, dtypes.int, (c2,), 0) + r2 = UOp(Ops.RANGE, dtypes.int, (c2,), 1) alu = UOp(Ops.MUL, dtypes.int, (r2, r1)) store = UOp(Ops.STORE, dtypes.void, (glbl.index(alu), cf)) uops = to_uops_list([store]) @@ -443,8 +523,8 @@ class TestUOpGraph(unittest.TestCase): # ranges are closed in the right order self.assertEqual(endranges[-1].src[0], ranges[0]) +@track_rewrites() def expander_rewrite(sink): return graph_rewrite(sink, sym + expander) -def float4_rewrite(sink): return full_graph_rewrite(sink, Renderer()) class TestExpander(unittest.TestCase): def test_expand_add_broadcast(self): @@ -593,75 +673,10 @@ class TestExpander(unittest.TestCase): sink = expander_rewrite(sink) print(sink) -class TestLoadStoreFolder(unittest.TestCase): - def test_simple_load_fold(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - load = [UOp(Ops.LOAD, dtypes.float, (buf.index(UOp.const(dtypes.int, i)),)) for i in range(4)] - sink = UOp(Ops.VECTORIZE, dtypes.float.vec(len(load)), tuple(load)) - - sink = float4_rewrite(sink.sink()) - assert len([x for x in sink.toposort if x.op is Ops.LOAD]) == 1 - - def test_two_load_fold(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - load = [UOp(Ops.LOAD, dtypes.float, (buf.index(UOp.const(dtypes.int, i)),)) for i in range(8)] - sink = UOp(Ops.VECTORIZE, dtypes.float.vec(len(load)), tuple(load)) - sink = float4_rewrite(sink.sink()) - assert len([x for x in sink.toposort if x.op is Ops.LOAD]) == 2 - - def test_simple_load_fold_gated(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - gate = UOp(Ops.DEFINE_VAR, dtypes.bool) - load = [UOp(Ops.LOAD, dtypes.float, (buf.index(UOp.const(dtypes.int, i), gate),)) for i in range(4)] - sink = UOp(Ops.VECTORIZE, dtypes.float.vec(len(load)), tuple(load)) - sink = float4_rewrite(sink.sink()) - assert len([x for x in sink.toposort if x.op is Ops.LOAD]) == 1 - single_load = [x for x in sink.toposort if x.op is Ops.LOAD][0] - self.assertEqual(single_load.src[1].op, Ops.VECTORIZE) - - def test_simple_load_dont_fold_different_gated(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - gate = UOp.variable("g1", False, True, dtypes.bool) - gate2 = UOp.variable("g2", False, True, dtypes.bool) - load = [UOp(Ops.LOAD, dtypes.float, (buf.index(UOp.const(dtypes.int, i), gate if i == 0 else gate2), - UOp.const(dtypes.float, 0))) for i in range(4)] - sink = UOp(Ops.VECTORIZE, dtypes.float.vec(len(load)), tuple(load)) - sink = float4_rewrite(sink.sink()) - assert len([x for x in sink.toposort if x.op is Ops.LOAD]) == 3 - - def test_simple_store_fold(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - load = [UOp(Ops.STORE, dtypes.float, (buf.index(UOp.const(dtypes.int, i)), UOp.const(dtypes.float, 0))) for i in range(4)] - sink = UOp(Ops.SINK, dtypes.void, tuple(load)) - sink = float4_rewrite(sink) - assert len([x for x in sink.toposort if x.op is Ops.STORE]) == 1 - - def test_simple_store_fold_gate(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - gate = UOp.variable("g1", False, True, dtypes.bool) - load = [UOp(Ops.STORE, dtypes.float, (buf.index(UOp.const(dtypes.int, i)), UOp.const(dtypes.float, 0), gate)) for i in range(4)] - sink = UOp(Ops.SINK, dtypes.void, tuple(load)) - sink = float4_rewrite(sink) - assert len([x for x in sink.toposort if x.op is Ops.STORE]) == 1 - one_store = [x for x in sink.toposort if x.op is Ops.STORE][0] - assert len(one_store.src) == 3 - _if_node = one_store.src[2] - assert _if_node.op == Ops.IF and _if_node.src[0] == gate - - def test_simple_store_dont_fold(self): - buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr()) - gate = UOp.variable("g1", False, True, dtypes.bool) - gate2 = UOp.variable("g2", False, True, dtypes.bool) - load = [UOp(Ops.STORE, dtypes.float, (buf.index(UOp.const(dtypes.int, i), gate if i == 0 else gate2), - UOp.const(dtypes.float, i))) for i in range(4)] - sink = UOp(Ops.SINK, dtypes.void, tuple(load)) - sink = float4_rewrite(sink) - assert len([x for x in sink.toposort if x.op is Ops.STORE]) == 3 - class TestIFUOps(unittest.TestCase): def test_create_ifs(self): gbuf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0) - sbuf = UOp(Ops.DEFINE_LOCAL, dtypes.float.ptr(local=True), (), ("smem", 4)) + sbuf = UOp(Ops.DEFINE_LOCAL, dtypes.float.ptr(size=4, local=True), (), "smem") valid = UOp(Ops.SPECIAL, dtypes.int, (), ("gidx0", 10))<5 lidx = UOp(Ops.SPECIAL, dtypes.int, (), ("lidx0", 4)) gate = valid&(lidx.ne(2)) @@ -671,8 +686,8 @@ class TestIFUOps(unittest.TestCase): lbuf = UOp(Ops.LOAD, dtypes.float, (sbuf.index(UOp.const(dtypes.int, 0)), barrier)) store = UOp(Ops.STORE, dtypes.void, (gbuf.index(UOp.const(dtypes.int, 0), gate), lbuf)) sink = UOp(Ops.SINK, dtypes.void, (store,)) - sink = full_graph_rewrite(sink) - if_uops = [u for u in sink.toposort if u.op is Ops.IF] + sink = full_rewrite_to_sink(sink) + if_uops = [u for u in sink.toposort() if u.op is Ops.IF] self.assertEqual(len(if_uops), 1) self.assertEqual(if_uops[0].src[0], gate) for st in sink.src: @@ -680,7 +695,7 @@ class TestIFUOps(unittest.TestCase): def test_expand_ifs_one_gate(self): gbuf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0) - sbuf = UOp(Ops.DEFINE_LOCAL, dtypes.float.ptr(local=True), (), ("smem", 16)) + sbuf = UOp(Ops.DEFINE_LOCAL, dtypes.float.ptr(size=16, local=True), (), "smem") valid = UOp(Ops.SPECIAL, dtypes.int, (), ("gidx0", 4))<1 lidx = UOp(Ops.SPECIAL, dtypes.int, (), ("lidx0", 16)) gate = valid&(lidx.ne(2)) @@ -689,8 +704,8 @@ class TestIFUOps(unittest.TestCase): lbufs = [UOp(Ops.LOAD, dtypes.float, (sbuf.index(UOp.const(dtypes.int, i)), barrier)) for i in range(4)] stores = [UOp(Ops.STORE, dtypes.void, (gbuf.index(UOp.const(dtypes.int, i), gate), lbufs[i])) for i in range(4)] sink = UOp(Ops.SINK, dtypes.void, tuple(stores)) - sink = full_graph_rewrite(sink) - if_uops = [u for u in sink.toposort if u.op is Ops.IF] + sink = full_rewrite_to_sink(sink) + if_uops = [u for u in sink.toposort() if u.op is Ops.IF] self.assertEqual(len(if_uops), 1) self.assertEqual(if_uops[0].src[0], gate) for st in sink.src: @@ -705,8 +720,8 @@ class TestIFUOps(unittest.TestCase): gate = valid&(lidx.ne(2)) stores = [UOp(Ops.STORE, dtypes.void, (buf, UOp.const(dtypes.int, i), UOp.const(dtypes.float, i), gate)) for i in range(4)] sink = UOp(Ops.SINK, dtypes.void, tuple(stores)) - sink = full_graph_rewrite(sink) - if_uops = [u for u in sink.toposort if u.op is Ops.IF] + sink = full_rewrite_to_sink(sink) + if_uops = [u for u in sink.toposort() if u.op is Ops.IF] self.assertEqual(len(if_uops), 1) self.assertEqual(if_uops[0].src[0], gate) for st in sink.src: diff --git a/tinygrad_repo/test/test_uops.py b/tinygrad_repo/test/test_uops.py index c77f1985c9..ebee1f659c 100644 --- a/tinygrad_repo/test/test_uops.py +++ b/tinygrad_repo/test/test_uops.py @@ -1,29 +1,32 @@ -from typing import Optional, Tuple, Any, List +from typing import Optional, Any import unittest, math import numpy as np from tinygrad.shape.shapetracker import ShapeTracker +from tinygrad.shape.view import View # noqa F401 from tinygrad.tensor import Tensor, _to_np_dtype from tinygrad.helpers import CI, DEBUG, getenv, Context, Timing from tinygrad.dtype import dtypes, DType from tinygrad.device import Buffer, Device -from tinygrad.ops import Ops, UOp, UPat, KernelInfo, exec_alu, spec # noqa F401 +from tinygrad.uop.ops import Ops, UOp, UPat, KernelInfo, exec_alu # noqa F401 +from tinygrad.uop.spec import spec from tinygrad.renderer import ProgramSpec -from tinygrad.engine.schedule import create_schedule, to_si -from tinygrad.engine.realize import CompiledRunner, lower_schedule_item, get_kernel -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.codegen.uopgraph import full_graph_rewrite, sym +from tinygrad.engine.grouper import fix_kernel_ops +from tinygrad.engine.realize import CompiledRunner, get_kernel +from tinygrad.codegen import full_rewrite +from tinygrad.codegen.symbolic import sym from tinygrad.device import is_dtype_supported +from tinygrad.codegen.kernel import Kernel, Opt, OptOps -def to_uops_list(u:List[UOp], opts=None, skip_check=False) -> List[UOp]: return linearize_uop(full_graph_rewrite(UOp.sink(*u), opts), skip_check) +def to_uops_list(u:list[UOp], opts=None, skip_check=False) -> list[UOp]: return full_rewrite(UOp.sink(*u), opts) def _uops_to_prg(uops_list): - uops = linearize_uop(full_graph_rewrite(UOp.sink(*uops_list), opts=Device[Device.DEFAULT].renderer)) - src = Device[Device.DEFAULT].renderer.render("test", uops) + uops = full_rewrite(ast:=UOp.sink(*uops_list), opts=Device[Device.DEFAULT].renderer) + src = Device[Device.DEFAULT].renderer.render(uops) has_local = Device[Device.DEFAULT].renderer.has_local - return CompiledRunner(ProgramSpec("test", src, Device.DEFAULT, uops=uops, + return CompiledRunner(ProgramSpec("test", src, Device.DEFAULT, ast, uops=uops, global_size=[1,1,1] if has_local else None, local_size=[1,1,1] if has_local else None)) -def uop(uops:List[UOp], uop:Ops, dtype:Optional[DType], src:Tuple[UOp, ...], arg:Any=None) -> UOp: +def uop(uops:list[UOp], uop:Ops, dtype:Optional[DType], src:tuple[UOp, ...], arg:Any=None) -> UOp: uops.append(UOp(uop, dtype, tuple(src), arg)) return uops[-1] @@ -102,11 +105,11 @@ class TestUOps(unittest.TestCase): self._equal(f([a,b,c], op, dts), fxn(a,b,c)) class TestFloatUOps(TestUOps): - @unittest.skipIf(Device.DEFAULT == "CLANG", 'not supported as uop') + @unittest.skipIf(Device.DEFAULT == "CPU", 'not supported as uop') def test_exp2(self): self._test_uop_fxn(Ops.EXP2, lambda a: np.exp2(a)) - @unittest.skipIf(Device.DEFAULT == "CLANG", 'not supported as uop') + @unittest.skipIf(Device.DEFAULT == "CPU", 'not supported as uop') def test_log2(self): self._test_uop_fxn(Ops.LOG2, lambda a: math.log2(a) if a > 0 else float('-inf' if a==0 else 'nan')) - @unittest.skipIf(Device.DEFAULT == "CLANG", 'not supported as uop') + @unittest.skipIf(Device.DEFAULT == "CPU", 'not supported as uop') def test_sin(self): self._test_uop_fxn(Ops.SIN, lambda a: math.sin(a)) def test_recip(self): self._test_uop_fxn(Ops.RECIP, lambda a: 1/a if a != 0 else float('inf')) def test_sqrt(self): self._test_uop_fxn(Ops.SQRT, lambda a: math.sqrt(a) if a >= 0 else float('nan')) @@ -236,26 +239,19 @@ class TestExecALU(TestUOps): class TestConstantFolding(unittest.TestCase): def test_cast_const(self): t = Tensor(1, dtype=dtypes.float).cast(dtypes.int) - si = create_schedule([t.lazydata]) + si = t.schedule() assert len(si) == 0 - def test_bitcast_const(self): - t = Tensor(1, dtype=dtypes.float).bitcast(dtypes.int) - si = create_schedule([t.lazydata]) - assert len(si) == 1 - ji = lower_schedule_item(si[-1]) - assert any(uop.op is Ops.BITCAST for uop in ji.prg.p.uops), f"{[uop.op for uop in ji.prg.p.uops]} does not contain bitcast" - class TestGatedStoreRewrite(unittest.TestCase): def test_tiny_gate_store(self): gmem = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0) gidx0 = UOp(Ops.SPECIAL, dtypes.int, (), ('gidx0', 4)) - idx = UOp(Ops.INDEX, dtypes.float.ptr(), (gmem, gidx0 * UOp.const(dtypes.int, 2))) - val = UOp.const(dtypes.float, 42.0) gate = gidx0= 4: print(Device[Device.DEFAULT].renderer.render("test", uops)) + if DEBUG >= 4: print(Device[Device.DEFAULT].renderer.render(uops)) if_uop = next(u for u in uops if u.op is Ops.IF) endif = next(u for u in uops if u.op is Ops.ENDIF) assert endif.src[0] is if_uop @@ -268,13 +264,12 @@ class TestGatedStoreRewrite(unittest.TestCase): gmem1 = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 1) gidx0 = UOp(Ops.SPECIAL, dtypes.int, (), ('gidx0', 4)) idx = gidx0 * UOp.const(dtypes.int, 2) - idx0 = UOp(Ops.INDEX, dtypes.float.ptr(), (gmem0, idx)) + idx0 = UOp(Ops.INDEX, dtypes.float.ptr(), (gmem0, idx, gidx0= 4: print(Device[Device.DEFAULT].renderer.render("test", uops)) + if DEBUG >= 4: print(Device[Device.DEFAULT].renderer.render(uops)) if_uop = next(u for u in uops if u.op is Ops.IF) endif = next(u for u in uops if u.op is Ops.ENDIF) assert endif.src[0] is if_uop @@ -288,13 +283,13 @@ class TestGatedStoreRewrite(unittest.TestCase): gmem1 = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 1) gidx0 = UOp(Ops.SPECIAL, dtypes.int, (), ('gidx0', 4)) idx = gidx0*UOp.const(dtypes.int, 2) - idx0 = UOp(Ops.INDEX, dtypes.float.ptr(), (gmem0, idx)) - idx1 = UOp(Ops.INDEX, dtypes.float.ptr(), (gmem1, idx)) - val = UOp.const(dtypes.float, 42.0) gate = gidx0= 4: print(Device[Device.DEFAULT].renderer.render("test", uops)) + if DEBUG >= 4: print(Device[Device.DEFAULT].renderer.render(uops)) ifs = [u for u in uops if u.op is Ops.IF] endifs = [u for u in uops if u.op is Ops.ENDIF] self.assertEqual(len(ifs), 1) @@ -309,7 +304,7 @@ class TestLocalAccess(unittest.TestCase): @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_shared, "test requires shared memory") def test_local_basic(self): uops = [] - smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.float32.ptr(local=True), (), ('smem', 16)) + smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.float32.ptr(size=16, local=True), (), 'smem') st = uop(uops, Ops.STORE, dtypes.void, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 0)), uop(uops, Ops.CONST, dtypes.float32, (), 42.0))) barr = uop(uops, Ops.BARRIER, dtypes.void, (st,)) sres = uop(uops, Ops.LOAD, dtypes.float32, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 0)), barr)) @@ -319,16 +314,17 @@ class TestLocalAccess(unittest.TestCase): @unittest.skipUnless(Device.DEFAULT == "WEBGPU", "Test local access with packed data type") def test_local_packed(self): uops = [] - smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.uint8.ptr(local=True), (), ('smem', 16)) + smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.uint8.ptr(size=16, local=True), (), 'smem') st = uop(uops, Ops.STORE, dtypes.void, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 0)), uop(uops, Ops.CONST, dtypes.uint8, (), 42))) barr = uop(uops, Ops.BARRIER, dtypes.void, (st,)) sres = uop(uops, Ops.LOAD, dtypes.uint8, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 0)), barr)) self.assertEqual(_test_uops_result(dtypes.uint8, uops, sres), 42) @unittest.skipUnless(Device[Device.DEFAULT].renderer.has_shared, "test requires shared memory") + @unittest.skip("tinygrad doesn't support this behavior") def test_local_indirect(self): uops = [] - smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.int32.ptr(local=True), (), ('smem', 16)) + smem = uop(uops, Ops.DEFINE_LOCAL, dtypes.int32.ptr(size=16, local=True), (), 'smem') st1 = uop(uops, Ops.STORE, dtypes.void, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 1)), uop(uops, Ops.CONST, dtypes.int32, (), 2))) st2 = uop(uops, Ops.STORE, dtypes.void, (smem.index(uop(uops, Ops.CONST, dtypes.int32, (), 2)), uop(uops, Ops.CONST, dtypes.int32, (), 42))) barr = uop(uops, Ops.BARRIER, dtypes.void, (st1,st2)) @@ -346,23 +342,63 @@ class TestAssembly(unittest.TestCase): a1 = UOp(Ops.MUL, dtypes.int, (l1, c1)) a2 = UOp(Ops.MUL, dtypes.int, (l1, c2)) uops = to_uops_list([a1,a2], opts=Device[Device.DEFAULT].renderer) - Device[Device.DEFAULT].renderer.render("test", uops) + Device[Device.DEFAULT].renderer.render(uops) ops = [x.op for x in uops] self.assertIn(Ops.SHL, ops) self.assertIn(Ops.MUL, ops) - def test_bitshift_right(self): - g1 = UOp(Ops.DEFINE_GLOBAL, dtypes.int32.ptr(), (), 0) - c1 = UOp(Ops.CONST, dtypes.int, (), 2) - c2 = UOp(Ops.CONST, dtypes.int, (), 3) - l1 = UOp(Ops.LOAD, dtypes.int, (g1.index(c1),)) - a1 = UOp(Ops.IDIV, dtypes.int, (l1, c1)) - a2 = UOp(Ops.IDIV, dtypes.int, (l1, c2)) - uops = to_uops_list([a1,a2], opts=Device[Device.DEFAULT].renderer) - Device[Device.DEFAULT].renderer.render("test", uops) + def test_division_power_of_two(self): + g = UOp(Ops.DEFINE_GLOBAL, dtypes.uint32.ptr(), (), 0) + c = UOp(Ops.CONST, dtypes.uint, (), 2) + l = UOp(Ops.LOAD, dtypes.uint, (g.index(c),)) + a = UOp(Ops.IDIV, dtypes.uint, (l, c)) + uops = to_uops_list([a], opts=Device[Device.DEFAULT].renderer) + Device[Device.DEFAULT].renderer.render(uops) + ops = [x.op for x in uops] + self.assertIn(Ops.SHR, ops) + self.assertNotIn(Ops.IDIV, ops) + + def test_fast_idiv_and_mod(self): + g = UOp(Ops.DEFINE_GLOBAL, dtypes.uint32.ptr(), (), 0) + c = UOp(Ops.CONST, dtypes.uint, (), 3) + l = UOp(Ops.LOAD, dtypes.uint, (g.index(c),)) + a = UOp(Ops.IDIV, dtypes.uint, (l, c)) + uops = to_uops_list([a], opts=Device[Device.DEFAULT].renderer) + Device[Device.DEFAULT].renderer.render(uops) + ops = [x.op for x in uops] + self.assertIn(Ops.SHR, ops) + self.assertNotIn(Ops.IDIV, ops) + + b = UOp(Ops.MOD, dtypes.uint, (l, c)) + uops = to_uops_list([b], opts=Device[Device.DEFAULT].renderer) + Device[Device.DEFAULT].renderer.render(uops) ops = [x.op for x in uops] self.assertIn(Ops.SHR, ops) - self.assertIn(Ops.IDIV, ops) + self.assertNotIn(Ops.MOD, ops) + + @unittest.expectedFailure + def test_fast_idiv_overflow(self): + # This will be possible with a slightly different method for fast_idiv + g = UOp(Ops.DEFINE_GLOBAL, dtypes.uint32.ptr(), (), 0) + c = UOp(Ops.CONST, dtypes.uint, (), 7) + l = UOp(Ops.LOAD, dtypes.uint, (g.index(c),)) + a = UOp(Ops.IDIV, dtypes.uint, (l, c)) + uops = to_uops_list([a], opts=Device[Device.DEFAULT].renderer) + Device[Device.DEFAULT].renderer.render(uops) + ops = [x.op for x in uops] + self.assertIn(Ops.SHR, ops) + self.assertNotIn(Ops.IDIV, ops) + + def test_mulacc_unrolled(self): + # test that acc = acc + a0*b0 + a1*b1 + a2*b2 + a3*b3 + # is not acc = acc + (a0*b0 + a1*b1 + a2*b2 + a3*b3) + a = Tensor.empty(1024) + b = Tensor.empty(1024) + c = (a*b).sum() + k = Kernel(c.schedule()[-1].ast) + k.apply_opt(Opt(OptOps.UNROLL, 0, 4)) + uops = k.linearize().uops + self.assertEqual(len([x.op for x in uops if x.op is Ops.MULACC]), 4) class TestUOpMethod(unittest.TestCase): @unittest.skip("uops lt no longer ordered") @@ -376,12 +412,11 @@ class TestUOpMethod(unittest.TestCase): def test_uop_variables(self): a = UOp.variable("a", 1, 10) - uop_var = UOp.const(dtypes.int, a) - st_var = UOp(Ops.LOAD, dtypes.float, (UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0), - ShapeTracker.from_shape((2, a)).to_uop())) - ast_vars = (st_var+uop_var).variables() - self.assertEqual(len(ast_vars), 1) - self.assertEqual(ast_vars[0], a) + uop_var = Tensor(a.bind(1)) + st_var = Tensor.empty((2, 1)).reshape((2, a.bind(1))) + _, var_vals = (uop_var+st_var).schedule_with_vars() + self.assertEqual(len(var_vals), 1) + self.assertEqual(list(var_vals)[0], a) def test_const_factor(self): gidx0 = UOp(Ops.SPECIAL, dtypes.int, (), ('gidx0', 8)) @@ -405,14 +440,6 @@ class TestUOpMethod(unittest.TestCase): self.assertEqual(const._device, None) with self.assertRaises(AssertionError): const.device - def test_const_arg(self): - var = UOp.variable("a", 1, 10) - with self.assertRaises(AssertionError): UOp.const(dtypes.int, var).const_arg - const = UOp.const(dtypes.int, 1) - self.assertEqual(const.const_arg, 1) - tensor_const = UOp(Ops.VIEW, dtypes.int, (UOp.new_buffer(Device.DEFAULT, 1, dtypes.int), const), ShapeTracker.from_shape(())) - self.assertEqual(tensor_const.const_arg, 1) - class TestUOpStr(unittest.TestCase): def test_uop_str(self): a = UOp(Ops.CONST, dtypes.float, (), 2.0) + UOp(Ops.CONST, dtypes.float, (), 3.0) @@ -431,6 +458,14 @@ class TestUOpStr(unittest.TestCase): vec = UOp(Ops.VECTORIZE, dtypes.int.vec(4), tuple(UOp.const(dtypes.int, x) for x in range(4))) assert str(eval(str(vec))) == str(vec) + def test_device_arg(self): + device = UOp(Ops.DEVICE, arg="GPU") + assert str(eval(str(device))) == str(device) + + def test_reduceop_arg(self): + sum_uop = Tensor.empty(32, 32).sum().lazydata + assert str(eval(str(sum_uop))) == str(sum_uop) + @unittest.skip("uop no longer has order like this") class TestIndexingOrdering(unittest.TestCase): # NOTE: these tests skip type_verify since they add dtype to STORE @@ -467,18 +502,20 @@ class TestIndexingOrdering(unittest.TestCase): gidx0 = UOp(Ops.SPECIAL, dtypes.int, (), ('gidx0', 4)) st0 = UOp(Ops.STORE, dtypes.float.vec(4), (buf, gidx0+UOp.const(dtypes.int, 0), UOp.const(dtypes.float.vec(4), 42))) st1 = UOp(Ops.STORE, dtypes.float, (buf, UOp.const(dtypes.int, 4), UOp.const(dtypes.float, 10))) - uops = linearize_uop(UOp.sink(st1, st0), skip_check=True) + uops = full_rewrite(UOp.sink(st1, st0)) stores = [st for st in uops if st.op is Ops.STORE] assert stores[0].src[1] < stores[1].src[1], f"stored at idx {stores[1].src[1].arg} AFTER {stores[0].src[1].arg}" class TestUPatHelpers(unittest.TestCase): def test_location(self): - self.assertEqual(sym.patterns[-1][0].location[0].replace("\\", "/").split("/")[-1], "uopgraph.py") - self.assertEqual(to_si.patterns[0][0].location[0].replace("\\", "/").split("/")[-1], "schedule.py") - self.assertEqual(spec.patterns[0][0].location[0].replace("\\", "/").split("/")[-1], "ops.py") - with self.assertRaises(AssertionError): # TODO: location UPat files created in test/*? - test_upat = UPat(Ops.CONST, dtypes.bool) - self.assertEqual(test_upat.location[0].split("/")[-1], __file__.replace("\\", "/").split("/")[-1]) + self.assertEqual(sym.patterns[-1][0].location[0].replace("\\", "/").split("/")[-1], "symbolic.py") + self.assertEqual(fix_kernel_ops.patterns[0][0].location[0].replace("\\", "/").split("/")[-1], "grouper.py") + self.assertEqual(spec.patterns[0][0].location[0].replace("\\", "/").split("/")[-1], "spec.py") + test_upat = UPat(Ops.CONST, dtypes.bool) + self.assertEqual(test_upat.location[0].split("/")[-1], __file__.replace("\\", "/").split("/")[-1]) + test_upat_named = test_upat.named("test_name") + self.assertEqual(test_upat.location[0], test_upat_named.location[0]) + self.assertNotEqual(test_upat.location[1], test_upat_named.location[1]) class TestUopsObject(unittest.TestCase): # LOL, running this test breaks all instances of "4" @@ -494,5 +531,122 @@ class TestUopsObject(unittest.TestCase): with Timing("create 10k uops:"): ret = [UOp(Ops.CONST, dtypes.int, arg=10000000+i) for i in range(10000)] assert len(ret) == 10000 + +class TestShapeSpec(unittest.TestCase): + # ** CONST is CONST(VIEW(DEVICE)) -> RESHPAE -> EXPAND + + def test_expanded_const(self): + a = Tensor(1).lazydata + self.assertEqual(a.st, ShapeTracker.from_shape(())) + a = Tensor.ones((4, 4)).lazydata + self.assertEqual(a.st, ShapeTracker.from_shape(()).reshape((1,1)).expand((4,4))) + + def test_padded_const(self): + a = Tensor.ones((1, 1)).pad(((1, 1), (1, 1))) + ast = a.contiguous().schedule()[0].ast + valid_pattern = UPat(Ops.WHERE, src=(UPat(Ops.VALID), UPat.cvar(), UPat.cvar())) + valid_ternary = [x for x in ast.toposort() if valid_pattern.match(x, {})][0] + # the WHERE outputs a contiguous (3, 3) + self.assertEqual(valid_ternary.st, ShapeTracker.from_shape((3, 3))) + valid, x, y = valid_ternary.src + # very notably, only the first source is padded + self.assertIsNotNone(valid.st.views[-1].mask) + assert x.st.views[-1].mask is y.st.views[-1].mask is None + assert all(s.shape == (3, 3) for s in valid_ternary.src) + + # NOTE: CONST ShapeTracker comes from its source + def test_scalar_const(self): + a = Tensor(0).lazydata + self.assertEqual(a.st, ShapeTracker.from_shape(())) + + def test_scalar_var(self): + vv = UOp.variable("a", 1, 4).bind(2) + t = Tensor(vv).lazydata + self.assertEqual(t.st, ShapeTracker.from_shape(())) + + # ** ASSIGN is ASSIGN(VIEW(BUFFER), new_val) + + def test_assign_flat(self): + buffer = Tensor.arange(4).realize() + a = buffer.assign(Tensor.zeros((4,), dtype=dtypes.int)) + assign_pattern = UPat(Ops.ASSIGN, src=(UPat(Ops.BUFFER), UPat())) + assert assign_pattern.match(a.lazydata, {}) + a.realize() + self.assertEqual(buffer.tolist(), [0, 0, 0, 0]) + + def test_assign_permuted(self): + buffer = Tensor.arange(4).reshape(2, 1, 2).contiguous().realize() + a = buffer.permute((1, 2, 0)).assign(Tensor.arange(4).reshape(1, 2, 2).contiguous()) + a.realize() + self.assertEqual(buffer.tolist(), [[[0, 2]], [[1, 3]]]) + + def test_assign_reshaped(self): + buffer = Tensor.ones((4,)).contiguous().realize() + a = buffer.reshape((2, 2)).assign(Tensor.zeros((2, 2))) + assign_pattern = UPat(Ops.ASSIGN, src=(UPat(Ops.RESHAPE, src=(UPat(Ops.BUFFER))), UPat())) + assert assign_pattern.match(a.lazydata, {}) + a.realize() + self.assertEqual(buffer.tolist(), [0, 0, 0, 0]) + + # setitem is a partial assign + def test_setitem(self): + a = Tensor.ones((4,)).contiguous().realize() + assign = a.shrink(((1, 2),)).assign(Tensor.zeros((1,))) + # the ASSIGN UOp has size=1 + self.assertEqual(assign.lazydata.size, 1) + # the ASSIGN views the buffer with a shrunk st + self.assertEqual(assign.lazydata.src[0].st, ShapeTracker.from_shape((4,)).shrink(((1, 2),))) + # the underlying BUFFER has a size=4 + self.assertEqual(assign.lazydata.buf_uop.size, 4) + # NOTE: output shape is different from the BUFFER shape + self.assertNotEqual(assign.lazydata.shape, a.lazydata.shape) + assign.realize() + self.assertEqual(a.tolist(), [1, 0, 1, 1]) + + def test_buffer_st(self): + a = UOp.new_buffer(Device.DEFAULT, 10, dtypes.float) + self.assertEqual(a.st, ShapeTracker.from_shape((10,))) + + def test_ops_st(self): + # view / mop + a = Tensor.empty(4, 2, 1).permute((1, 2, 0)).lazydata + self.assertEqual(a.st, ShapeTracker.from_shape((4, 2, 1)).permute((1, 2, 0))) + # alu / reduce + alu = a*2 + self.assertEqual(alu.st, ShapeTracker.from_shape((2, 1, 4))) + r = Tensor.empty(4, 4).sum(axis=1) + self.assertEqual(r.lazydata.st, ShapeTracker.from_shape((4,))) + + def test_st_wmma_none(self): + A = UOp(Ops.DEFINE_VAR, dtypes.float.vec(16), arg=('a', UOp.const(dtypes.float, 0), UOp.const(dtypes.float, 1))) + B = UOp(Ops.DEFINE_VAR, dtypes.float.vec(16), arg=('b', UOp.const(dtypes.float, 0), UOp.const(dtypes.float, 2))) + C = UOp(Ops.DEFINE_VAR, dtypes.float.vec(16), arg=('c', UOp.const(dtypes.float, 0), UOp.const(dtypes.float, 3))) + wmma = UOp(Ops.WMMA, dtypes.float.vec(16), (A, B, C)) + assert wmma.st is None + +class TestUOpChildren(unittest.TestCase): + def test_children_exist(self): + a = UOp.variable("weird_name_234", 0, 10) + b = a*a + self.assertEqual(len(a.children), 1) + self.assertIs(list(a.children)[0](), b) + + def test_children_cleaned_up(self): + a = UOp.variable("weird_name_235", 0, 10) + b = a*a + self.assertEqual(len(a.children), 1) + del b + self.assertEqual(len(a.children), 0) + + def test_children_cleaned_up_two(self): + a = UOp.variable("weird_name_236", 0, 10) + b = a*a + c = a*2 + self.assertEqual(len(a.children), 2) + del b + self.assertEqual(len(a.children), 1) + del c + self.assertEqual(len(a.children), 0) + if __name__ == '__main__': unittest.main(verbosity=2) diff --git a/tinygrad_repo/test/test_uops_stats.py b/tinygrad_repo/test/test_uops_stats.py index 323c8bbbc5..fdaf21c4f7 100644 --- a/tinygrad_repo/test/test_uops_stats.py +++ b/tinygrad_repo/test/test_uops_stats.py @@ -1,13 +1,13 @@ import unittest from tinygrad import Tensor from tinygrad.helpers import getenv, GlobalCounters -from tinygrad.engine.schedule import create_schedule from tinygrad.engine.realize import lower_schedule_item, ProgramSpec from tinygrad.renderer import Estimates -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.ops import Ops, UOp +from tinygrad.codegen import full_rewrite +from tinygrad.uop.ops import Ops, UOp from tinygrad.dtype import dtypes from tinygrad.codegen.kernel import Kernel, Opt, OptOps, KernelOptError +from tinygrad.device import Device def flops_mem(uops, ignore_indexing=False): est = Estimates.from_uops(uops, ignore_indexing) @@ -16,7 +16,7 @@ def flops_mem(uops, ignore_indexing=False): # **************** new FlopCounter **************** def get_stats(x:Tensor): - si = create_schedule([x.lazydata])[-1] + si = x.schedule()[-1] ei = lower_schedule_item(si) return ei.prg.estimates.ops, ei.prg.estimates.mem @@ -32,6 +32,7 @@ class TestMemoryCount(unittest.TestCase): _, mem = get_stats(a+3) self.assertEqual(mem, 1024*1024*2) # 1 read + 1 write + @unittest.skip("depends on subbuffer working") def test_add_slice(self): a = Tensor.empty(1024, 1024, dtype=dtypes.uint8)[:512] _, mem = get_stats(a+3) @@ -65,6 +66,15 @@ class TestMemoryCount(unittest.TestCase): _, mem = get_stats(a.assign(a+a)) self.assertEqual(mem, 1024*1024*2) # 1 read + 1 write + @unittest.skipIf(Device.DEFAULT == "CPU", "test copy to CPU from other device") + def test_copyout(self): + a = Tensor.empty(32, dtype=dtypes.uint8).to("CPU") + _, mem = get_stats(a) + self.assertEqual(mem, 32*1) + a = Tensor.empty(32, dtype=dtypes.uint32).to("CPU") + _, mem = get_stats(a) + self.assertEqual(mem, 32*4) + # NOTE: this still isn't testing unroll using the acc @unittest.skipUnless(getenv("PYTHON"), "only run test on emulated tensor cores") class TestUOpsStatsMatmulHalf(unittest.TestCase): @@ -111,17 +121,19 @@ class TestUOpsStats(unittest.TestCase): # NOTE; ops also include indexing ops assert expected_ops <= ops and ops <= expected_ops * 2 - def test_simple_matmul(self): - a = Tensor.empty(1024,1024) - b = Tensor.empty(1024,1024) + def test_simple_matmul(self, M=1024, N=1024, K=1024): + a = Tensor.empty(M,N) + b = Tensor.empty(N,K) c = a@b ops, mem = get_stats(c) - expected_ops = c.numel() * 1024 * 2 + expected_ops = c.numel() * N * 2 required_mem = a.nbytes() + b.nbytes() + c.nbytes() assert expected_ops <= ops and ops <= expected_ops * 1.2 # NOTE: it's hard to assert on the memory here, all depends on caching assert required_mem <= mem + def test_simple_matmul_8192(self): self.test_simple_matmul(8192, 8192, 8192) + #MULACC should have the same stats as MUL + ADD def test_mulacc(self): globl = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), tuple()) @@ -132,7 +144,7 @@ class TestUOpsStats(unittest.TestCase): u3 = UOp(Ops.CONST, dtypes.int, tuple(), 3) u4 = UOp(Ops.MUL, dtypes.int, (u1,u2)) u5 = UOp(Ops.ADD, dtypes.int, (u4,u3)) - uops = linearize_uop(u5.sink()) + uops = full_rewrite(u5.sink()) globl = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), tuple()) o1 = UOp(Ops.CONST, dtypes.int, tuple(), 1) @@ -141,11 +153,11 @@ class TestUOpsStats(unittest.TestCase): u2 = UOp(Ops.LOAD, dtypes.int, (globl.index(o2),)) u3 = UOp(Ops.CONST, dtypes.int, tuple(), 3) u4 = UOp(Ops.MULACC, dtypes.int, (u1,u2,u3)) - uops_fma = linearize_uop(u4.sink()) + uops_fma = full_rewrite(u4.sink()) self.assertEqual(flops_mem(uops), flops_mem(uops_fma)) -N = 100 +N = 64 @unittest.skipIf(getenv("PTX"), "wrong in PTX") # maybe? class TestStatsOptimized(unittest.TestCase): @classmethod @@ -165,6 +177,14 @@ class TestStatsOptimized(unittest.TestCase): self.check_gemm(p) self.assertEqual(p.estimates.lds, 2*N*N*N*4 + 4*N*N) + def test_gemm_tc_unroll(self): + k = Kernel(self.ast_gemm) + if not k.apply_tensor_cores(): self.skipTest("no tensor cores") + k.apply_opt(Opt(OptOps.UNROLL, 0, 2)) + p = k.to_program() + print(p.src) + self.check_gemm(p) + # this is a good lesson about why UPCASTing is a good idea def test_gemm_one_upcasted(self): diff --git a/tinygrad_repo/test/test_viz.py b/tinygrad_repo/test/test_viz.py deleted file mode 100644 index d14fd7d97a..0000000000 --- a/tinygrad_repo/test/test_viz.py +++ /dev/null @@ -1,215 +0,0 @@ -from typing import Dict, List, Optional -import unittest, decimal, json -from tinygrad.dtype import dtypes -from tinygrad.ops import TRACK_MATCH_STATS, TrackedPatternMatcher as PatternMatcher, UOp, Ops, UPat, graph_rewrite, track_rewrites, symbolic -from tinygrad.ops import tracked_ctxs as contexts, tracked_keys as keys -from tinygrad.device import ProfileDeviceEvent, ProfileRangeEvent, ProfileGraphEvent, ProfileGraphEntry -from tinygrad.viz.serve import get_details, get_metadata, uop_to_json, to_perfetto - -@track_rewrites(named=True) -def rewrite(sink:UOp, pm:PatternMatcher, **kwargs): return graph_rewrite(sink, pm, **kwargs) - -def helper_test_viz(sink:UOp, pm:PatternMatcher, **kwargs) -> List[UOp]: - rewrite(sink, pm, **kwargs) - assert len(contexts) == 1 - assert len(contexts[0]) == 1 - k = get_metadata(keys, contexts)[0][0] - g = get_details(*k) - return g.graphs[1:] - -class TestViz(unittest.TestCase): - def setUp(self): - contexts.clear() - keys.clear() - self.tms = TRACK_MATCH_STATS.value - TRACK_MATCH_STATS.value = 2 - def tearDown(self): TRACK_MATCH_STATS.value = self.tms - - def test_viz_simple(self): - pm = PatternMatcher([ - (UPat.var("x")*1, lambda x:x), - ]) - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - uops = helper_test_viz(a*1, pm) - self.assertEqual(len(uops), 1) - self.assertEqual(uops[0], a) - - def test_rewrite_twice(self): - pm = PatternMatcher([ - (UPat.var("x")+UPat.var("x"), lambda x:x*2), - (UPat.var("x", dtypes.int)*2, lambda x:x.alu(Ops.SHL, UOp.const(dtypes.int, 1))), - ]) - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - uops = helper_test_viz(a+a, pm) - self.assertEqual(len(uops), 2) - self.assertEqual(uops[0], a*2) - self.assertEqual(uops[1], graph_rewrite(a+a, pm)) - - def test_rewrite_with_ctx(self): - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - b = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 1), UOp.const(dtypes.int, 0))) - def store_load(ctx:Dict[UOp, None], x:UOp) -> Optional[UOp]: - if x in ctx: return None - ctx[x] = None - return UOp.store(*x.src, x) - pm = PatternMatcher([ - (UPat(Ops.LOAD, name="x"), store_load), - ]) - uops = helper_test_viz(a+b, pm, ctx={}) - self.assertEqual(len(uops), 2) - self.assertEqual(uops[-1], graph_rewrite(a+b, pm, {})) - - def test_track_rewrites(self): - simple = PatternMatcher([(UPat.var("x")*1, lambda x:x)]) - @track_rewrites(named=True) - def do_rewrite(x:UOp): return graph_rewrite(x, simple) - ld = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), arg=1), UOp.const(dtypes.int, 0))) - do_rewrite(ld*1) - do_rewrite(ld*2) - ret = get_metadata(keys, contexts) - self.assertEqual(len(ret), 2) - key, _, m = ret[0][0] - self.assertEqual(key, "do_rewrite_1") - self.assertEqual(len(m.upats), 1) - key, _, m = ret[1][0] - self.assertEqual(key, "do_rewrite_2") - self.assertEqual(len(m.upats), 0) - - def test_track_rewrites_with_exception(self): - simple = PatternMatcher([(UPat.var("x")*1, lambda x:x)]) - @track_rewrites() - def do_rewrite(x:UOp): - x = graph_rewrite(x, simple) # NOTE: viz tracks this - raise Exception("test") - ld = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), arg=1), UOp.const(dtypes.int, 0))) - with self.assertRaises(Exception): do_rewrite(ld*1) - ret = get_metadata(keys, contexts) - self.assertEqual(len(ret), 1) - - def test_fold_const(self): - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - graph = uop_to_json(a) - assert not any(v[0].startswith("CONST") for v in graph.values()) - assert len([x for x in graph.values() if "CONST" in x[0]]) == 1 - - @unittest.skip("TODO: bring this back with better testing") - def test_bottom_up_rewrite(self): - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - n1 = a.sin() - uop = n1.sin() - pm = PatternMatcher([(UPat(tuple(Ops), name="x"), lambda ctx,x: ctx.get(x,None))]) - ret = helper_test_viz(uop, pm, ctx={a.sin():a.sqrt(), n1.sin():n1.sqrt()}, bottom_up=True) - self.assertEqual(len(ret), 2) - self.assertIs(ret[0], a.sin().sqrt()) # first rewrite - self.assertIs(ret[1], a.sqrt().sqrt()) # second one - - def test_top_down_rewrite(self): - a = UOp(Ops.LOAD, dtypes.int, (UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), (), 0), UOp.const(dtypes.int, 0))) - n1 = a.sin() - uop = n1.sin() - pm = PatternMatcher([(UPat(tuple(Ops), name="x"), lambda ctx,x: ctx.get(x,None))]) - # if it wasn't bottom_up, it's rewritten once - ret = helper_test_viz(uop, pm, ctx={a.sin():a.sqrt(), n1.sin():n1.sqrt()}, bottom_up=False) - self.assertEqual(len(ret), 1) - self.assertIs(ret[0], a.sqrt().sin()) # only rewrite - - # NOTE: calling graph_rewrite when the function isn't decorated with track_rewrites should not VIZ - def test_rewrite_without_context(self): - def untracked_graph_rewrite(sink): return graph_rewrite(sink, symbolic) - @track_rewrites(named=True) - def tracked_graph_rewrite(sink): return graph_rewrite(sink, symbolic) - # test - add = UOp.const(dtypes.int, 2) + UOp.const(dtypes.int, 1) - untracked_graph_rewrite(add) - self.assertEqual(len(contexts), 0) - tracked_graph_rewrite(add) - self.assertEqual(len(contexts), 1) - - def test_inner_rewrite_location(self): - # inner rewrite gets tracked in another context - def inner_rewrite(sink): return graph_rewrite(sink, symbolic) - @track_rewrites(named=True) - def tracked_graph_rewrite(sink): return inner_rewrite(sink) - # test - add = UOp.const(dtypes.int, 2) + UOp.const(dtypes.int, 1) - tracked_graph_rewrite(add) - self.assertEqual(len(contexts), 1) - # location of context is inner_rewrite - fp, lineno = contexts[0][0].loc - self.assertEqual(lineno, inner_rewrite.__code__.co_firstlineno) - self.assertEqual(fp, inner_rewrite.__code__.co_filename) - -class TextVizProfiler(unittest.TestCase): - def test_perfetto_node(self): - prof = [ProfileRangeEvent(device='NV', name='E_2', st=decimal.Decimal(1000), en=decimal.Decimal(1010), is_copy=False), - ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100))] - - j = json.loads(to_perfetto(prof)) - - # Device regs always first - self.assertEqual(j['traceEvents'][0]['name'], 'process_name') - self.assertEqual(j['traceEvents'][0]['ph'], 'M') - self.assertEqual(j['traceEvents'][0]['args']['name'], 'NV') - - self.assertEqual(j['traceEvents'][1]['name'], 'thread_name') - self.assertEqual(j['traceEvents'][1]['ph'], 'M') - self.assertEqual(j['traceEvents'][1]['pid'], j['traceEvents'][0]['pid']) - self.assertEqual(j['traceEvents'][1]['tid'], 0) - self.assertEqual(j['traceEvents'][1]['args']['name'], 'COMPUTE') - - self.assertEqual(j['traceEvents'][2]['name'], 'thread_name') - self.assertEqual(j['traceEvents'][2]['ph'], 'M') - self.assertEqual(j['traceEvents'][2]['pid'], j['traceEvents'][0]['pid']) - self.assertEqual(j['traceEvents'][2]['tid'], 1) - self.assertEqual(j['traceEvents'][2]['args']['name'], 'COPY') - - self.assertEqual(j['traceEvents'][3]['name'], 'E_2') - self.assertEqual(j['traceEvents'][3]['ts'], 0) - self.assertEqual(j['traceEvents'][3]['dur'], 10) - self.assertEqual(j['traceEvents'][3]['ph'], 'X') - self.assertEqual(j['traceEvents'][3]['pid'], j['traceEvents'][0]['pid']) - self.assertEqual(j['traceEvents'][3]['tid'], 0) - - def test_perfetto_copy_node(self): - prof = [ProfileRangeEvent(device='NV', name='COPYxx', st=decimal.Decimal(1000), en=decimal.Decimal(1010), is_copy=True), - ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100))] - - j = json.loads(to_perfetto(prof)) - - self.assertEqual(j['traceEvents'][3]['name'], 'COPYxx') - self.assertEqual(j['traceEvents'][3]['ts'], 900) # diff clock - self.assertEqual(j['traceEvents'][3]['dur'], 10) - self.assertEqual(j['traceEvents'][3]['ph'], 'X') - self.assertEqual(j['traceEvents'][3]['tid'], 1) - - def test_perfetto_graph(self): - prof = [ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100)), - ProfileDeviceEvent(device='NV:1', comp_tdiff=decimal.Decimal(-500), copy_tdiff=decimal.Decimal(-50)), - ProfileGraphEvent(ents=[ProfileGraphEntry(device='NV', name='E_25_4n2', st_id=0, en_id=1, is_copy=False), - ProfileGraphEntry(device='NV:1', name='NV -> NV:1', st_id=2, en_id=3, is_copy=True)], - deps=[[], [0]], - sigs=[decimal.Decimal(1000), decimal.Decimal(1002), decimal.Decimal(1004), decimal.Decimal(1008)])] - - j = json.loads(to_perfetto(prof)) - - # Device regs always first - self.assertEqual(j['traceEvents'][0]['args']['name'], 'NV') - self.assertEqual(j['traceEvents'][1]['args']['name'], 'COMPUTE') - self.assertEqual(j['traceEvents'][2]['args']['name'], 'COPY') - self.assertEqual(j['traceEvents'][3]['args']['name'], 'NV:1') - self.assertEqual(j['traceEvents'][4]['args']['name'], 'COMPUTE') - self.assertEqual(j['traceEvents'][5]['args']['name'], 'COPY') - - self.assertEqual(j['traceEvents'][6]['name'], 'E_25_4n2') - self.assertEqual(j['traceEvents'][6]['ts'], 0) - self.assertEqual(j['traceEvents'][6]['dur'], 2) - self.assertEqual(j['traceEvents'][6]['pid'], j['traceEvents'][0]['pid']) - - self.assertEqual(j['traceEvents'][7]['name'], 'NV -> NV:1') - self.assertEqual(j['traceEvents'][7]['ts'], 954) - self.assertEqual(j['traceEvents'][7]['dur'], 4) - self.assertEqual(j['traceEvents'][7]['pid'], j['traceEvents'][3]['pid']) - - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_winograd.py b/tinygrad_repo/test/test_winograd.py index 0acbee9de5..975fe88b69 100644 --- a/tinygrad_repo/test/test_winograd.py +++ b/tinygrad_repo/test/test_winograd.py @@ -1,9 +1,9 @@ import unittest from tinygrad import Tensor, GlobalCounters, dtypes -from tinygrad.ops import Ops +from tinygrad.uop.ops import Ops from tinygrad.helpers import Timing, CI, Profiling, WINO, DEBUG, getenv from tinygrad.codegen.kernel import Kernel -from tinygrad.engine.schedule import create_schedule +from tinygrad.codegen.heuristic import hand_coded_optimizations class TestWinograd(unittest.TestCase): def setUp(self): @@ -20,14 +20,14 @@ class TestWinograd(unittest.TestCase): out = Tensor.conv2d(x, w) with Timing("scheduling: "): - sched = create_schedule([out.lazydata]) + sched = out.schedule() for i,s in enumerate(sched): if s.ast.op is not Ops.SINK: continue - ops = s.ast.toposort + ops = s.ast.toposort() with Timing(f"linearize {i} with {len(ops):4d} ops: "): l = Kernel(s.ast) - l.hand_coded_optimizations() + l.apply_opts(hand_coded_optimizations(l)) l.linearize() assert len(l.sts) <= 256 # just the current value to prevent regression if DEBUG >= 2: print(f"{len(l.sts):4d} shapetrackers with max {max(len(x.views) for x in l.sts)} views") diff --git a/tinygrad_repo/test/test_zero_copy.py b/tinygrad_repo/test/test_zero_copy.py index 1b999314c3..6f2b2cda0b 100644 --- a/tinygrad_repo/test/test_zero_copy.py +++ b/tinygrad_repo/test/test_zero_copy.py @@ -13,7 +13,7 @@ def time_tensor_numpy(out:Tensor): N = 4096 class TestZeroCopy(unittest.TestCase): - @unittest.skipIf(Device.DEFAULT not in {"CLANG", "LLVM", "METAL"}, "device isn't zero copy") + @unittest.skipIf(Device.DEFAULT not in {"CPU", "LLVM", "METAL"}, "device isn't zero copy") def test_zero_copy_from_default_to_cpu(self): demo = Tensor.rand(1).realize() t1 = time_tensor_numpy(demo) diff --git a/tinygrad_repo/test/testextra/test_bench_log.py b/tinygrad_repo/test/testextra/test_bench_log.py new file mode 100644 index 0000000000..dd63f916ea --- /dev/null +++ b/tinygrad_repo/test/testextra/test_bench_log.py @@ -0,0 +1,108 @@ +import unittest, time +from unittest.case import skipIf + +from extra.bench_log import BenchEvent, InstantBenchEvent, WallTimeEvent, KernelTimeEvent, log_event_instant, _events, clear_events +from tinygrad.helpers import Context, CI +from tinygrad.tensor import Tensor +from tinygrad.device import Device + +class TestBenchLog(unittest.TestCase): + def setUp(self): + clear_events() + + def test_log_single_wall_time(self): + for event in BenchEvent: + with WallTimeEvent(event): + time.sleep(0.1) + + # check event list + for event in BenchEvent: + self.assertEqual(len(_events[event]["wall"]), 1) + self.assertGreater(_events[event]["wall"][0], 0) + + def test_log_double_wall_time(self): + for event in BenchEvent: + with WallTimeEvent(event): + time.sleep(0.1) + + for event in reversed(BenchEvent): + with WallTimeEvent(event): + time.sleep(0.2) + + # check event list + for event in BenchEvent: + self.assertEqual(len(_events[event]["wall"]), 2) + self.assertGreater(_events[event]["wall"][0], 0) + self.assertGreater(_events[event]["wall"][1], 0) + + @skipIf(CI and Device.DEFAULT == "CUDA", "ci cuda timing is not accurate") + def test_log_single_kernel_time(self): + wall_times = [] + + with Context(DEBUG=2): + for event in BenchEvent: + with KernelTimeEvent(event): + st = time.perf_counter() + Tensor.rand(32, 32).sum().realize().item() + wall_times.append(time.perf_counter() - st) + + # check event list + for event in BenchEvent: + self.assertEqual(len(_events[event]["kernel"]), 1) + self.assertLess(_events[event]["kernel"][0], wall_times[0]) + self.assertGreater(_events[event]["kernel"][0], 0) + + @skipIf(CI and Device.DEFAULT == "CUDA", "ci cuda timing is not accurate") + def test_interleaved_wall_kernel_time(self): + wall_times = [] + with Context(DEBUG=2): + for event in BenchEvent: + with KernelTimeEvent(event): + st = time.perf_counter() + Tensor.rand(32, 32).sum().realize().item() + wall_times.append(time.perf_counter() - st) + + with WallTimeEvent(event): + st = time.perf_counter() + Tensor.rand(32, 32).sum().realize().item() + wall_times.append(time.perf_counter() - st) + + # check event list + for event in BenchEvent: + self.assertEqual(len(_events[event]["wall"]), 1) + self.assertEqual(len(_events[event]["kernel"]), 1) + self.assertLess(_events[event]["kernel"][0], wall_times[0]) + self.assertGreater(_events[event]["kernel"][0], 0) + + @skipIf(CI and Device.DEFAULT == "CUDA", "ci cuda timing is not accurate") + def test_stacked_wall_kernel_time(self): + with Context(DEBUG=2): + for event in BenchEvent: + with KernelTimeEvent(event): + with WallTimeEvent(event): + Tensor.rand(32, 32).sum().realize().item() + + for event in BenchEvent: + with WallTimeEvent(event): + with KernelTimeEvent(event): + Tensor.rand(32, 32).sum().realize().item() + + for event in BenchEvent: + self.assertEqual(len(_events[event]["wall"]), 2) + self.assertEqual(len(_events[event]["kernel"]), 2) + self.assertLess(_events[event]["kernel"][0], _events[event]["wall"][0]) + self.assertGreater(_events[event]["kernel"][0], 0) + self.assertLess(_events[event]["kernel"][1], _events[event]["wall"][1]) + self.assertGreater(_events[event]["kernel"][1], 0) + + def test_log_instant_event(self): + for event in InstantBenchEvent: + log_event_instant(event, 1000) + + # check event list + for event in InstantBenchEvent: + self.assertEqual(len(_events[event]), 1) + self.assertEqual(_events[event][0], 1000) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/testextra/test_f16_decompress.py b/tinygrad_repo/test/testextra/test_f16_decompress.py index 9cfa936a49..6806877034 100644 --- a/tinygrad_repo/test/testextra/test_f16_decompress.py +++ b/tinygrad_repo/test/testextra/test_f16_decompress.py @@ -1,14 +1,15 @@ import unittest from extra.f16_decompress import u32_to_f16 from tinygrad.tensor import Tensor -from tinygrad.device import Device, is_dtype_supported +from tinygrad.device import is_dtype_supported from tinygrad import dtypes import numpy as np class TestF16Decompression(unittest.TestCase): + @unittest.skipUnless(is_dtype_supported(dtypes.float16), "need float16") def test_u32_to_f16(self): - a = Tensor.randn(50, dtype=dtypes.float16, device=None if is_dtype_supported(dtypes.float16) else "CLANG:0") - f16_as_u32 = a.bitcast(dtypes.uint32) if is_dtype_supported(dtypes.float16) else a.bitcast(dtypes.uint32).to(Device.DEFAULT) + a = Tensor.randn(50, dtype=dtypes.float16) + f16_as_u32 = a.bitcast(dtypes.uint32) f16 = u32_to_f16(f16_as_u32) ref = a.numpy() out = f16.numpy().astype(np.float16) diff --git a/tinygrad_repo/test/testextra/test_lr_scheduler.py b/tinygrad_repo/test/testextra/test_lr_scheduler.py index 2f12547024..ce7464ecf6 100644 --- a/tinygrad_repo/test/testextra/test_lr_scheduler.py +++ b/tinygrad_repo/test/testextra/test_lr_scheduler.py @@ -107,7 +107,7 @@ class TestLrScheduler(unittest.TestCase): self._test_multisteplr(1, {'milestones': [1], 'gamma': 0.133}, 1e-6, 1e-6, adam=False) if DEBUG>=2: print("third") - def test_onecyclelr(self): self._test_onecyclelr(1000, {'pct_start': 0.3, 'anneal_strategy': 'linear', + def test_onecyclelr(self): self._test_onecyclelr(100, {'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") diff --git a/tinygrad_repo/test/testextra/test_mockgpu.py b/tinygrad_repo/test/testextra/test_mockgpu.py index ec6b76a3d4..0f1d616480 100644 --- a/tinygrad_repo/test/testextra/test_mockgpu.py +++ b/tinygrad_repo/test/testextra/test_mockgpu.py @@ -5,7 +5,7 @@ import unittest, importlib class TestMockGPU(unittest.TestCase): # https://github.com/tinygrad/tinygrad/pull/7627 def test_import_typing_extensions(self): - import extra.mockgpu.mockgpu # noqa: F401 # pylint: disable=unused-import + import test.mockgpu.mockgpu # noqa: F401 # pylint: disable=unused-import import typing_extensions importlib.reload(typing_extensions) # pytest imports typing_extension before mockgpu diff --git a/tinygrad_repo/test/unit/test_allreduce.py b/tinygrad_repo/test/unit/test_allreduce.py new file mode 100644 index 0000000000..7eb54bd9d3 --- /dev/null +++ b/tinygrad_repo/test/unit/test_allreduce.py @@ -0,0 +1,30 @@ +import unittest +from tinygrad import Tensor +from tinygrad.helpers import Context +from tinygrad.uop.ops import Ops + +class TestRingAllReduce(unittest.TestCase): + @unittest.skip("still broken") + def test_schedule_ring(self): + with Context(RING=2): + N = 4 + ds = tuple(f"CPU:{i}" for i in range(N)) + t = Tensor.empty(N, N*100).shard(ds, axis=0).realize() + schedules = t.sum(0).schedule_with_vars()[0] + copies = [si for si in schedules if si.ast.op is Ops.COPY] + pairs = [(c.bufs[0].device, c.bufs[1].device) for c in copies] + # N*(N-1) scatter reduce, and N*(N-1) allgather + self.assertEqual(len(pairs), N*(N-1)*2) + # copy topology forms a ring + self.assertEqual(len(set(pairs)), N) + + def test_correct_ring(self): + with Context(RING=2): + N = 4 + ds = tuple(f"CPU:{i}" for i in range(N)) + t = Tensor.ones(N, N*100).contiguous().shard(ds, axis=0).realize() + out = t.sum(0) + self.assertListEqual(out.tolist(), [4]*N*100) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/unit/test_attention.py b/tinygrad_repo/test/unit/test_attention.py new file mode 100644 index 0000000000..9929dbc32d --- /dev/null +++ b/tinygrad_repo/test/unit/test_attention.py @@ -0,0 +1,20 @@ +import unittest +from tinygrad import Tensor, dtypes + +# TODO: test_scheduler, but just in uint +class TestAttention(unittest.TestCase): + def test_half_qkv_buffers(self): + BS, seqlen, dim = 10, 4, 100 + q = Tensor.ones(BS, seqlen, dim, dtype=dtypes.half).contiguous().realize() + k = Tensor.ones(BS, seqlen, dim, dtype=dtypes.half).contiguous().realize() + v = Tensor.ones(BS, seqlen, dim, dtype=dtypes.half).contiguous().realize() + attn = q.scaled_dot_product_attention(k, v) + sched = attn.schedule() + # attention has 5 kernels now + self.assertEqual(len(sched), 5) + softmax_inputs = sched[1:4] + for si in softmax_inputs: + assert all(b.dtype == dtypes.half for b in si.bufs), f"non half {si.bufs=}" + +if __name__ == '__main__': + unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/unit/test_block_reorder.py b/tinygrad_repo/test/unit/test_block_reorder.py new file mode 100644 index 0000000000..24488d23c8 --- /dev/null +++ b/tinygrad_repo/test/unit/test_block_reorder.py @@ -0,0 +1,76 @@ +import unittest, random +from tinygrad.dtype import dtypes +from tinygrad.uop.ops import print_uops, UOp, Ops +from tinygrad.codegen.linearize import block_reorder +from tinygrad.renderer.cstyle import OpenCLRenderer + +def is_toposorted(lst:list[UOp]): + seen = set() + for u in lst: + if any(p not in seen for p in u.src): return False + seen.add(u) + return True + +class TestBlockReorder(unittest.TestCase): + def _test_randomize(self, golden:list[UOp]): + # test random order is always same + for _ in range(50): + # shuffle and form a valid toposort + lst = golden[:] + random.shuffle(lst) + topolst = [] + for u in lst: + for p in u.toposort(): + if p not in topolst: topolst.append(p) + assert is_toposorted(topolst) + + for x,y in zip(golden, this_order:=block_reorder(topolst)): + if x is not y: + print_uops(golden) + print_uops(this_order) + self.assertIs(x, y) + + def _test_render(self, golden:list[UOp]): + return OpenCLRenderer().render(golden) + + def test_loads(self): + a = UOp(Ops.DEFINE_GLOBAL, dtype=dtypes.float.ptr(), arg=0) + b = UOp(Ops.DEFINE_GLOBAL, dtype=dtypes.float.ptr(), arg=1) + c = UOp(Ops.DEFINE_GLOBAL, dtype=dtypes.float.ptr(), arg=2) + v1 = UOp(Ops.SPECIAL, dtype=dtypes.int, arg=("gidx0", 4)) + v2 = UOp(Ops.SPECIAL, dtype=dtypes.int, arg=("gidx1", 4)) + v1 = v1*27 + v2 = v2*4 + loads = [ + a.index(v1).load(dtype=dtypes.float), + a.index(v1+1).load(dtype=dtypes.float), + a.index(v1+2).load(dtype=dtypes.float), + a.index(v1+3).load(dtype=dtypes.float), + b.index(v2).load(dtype=dtypes.float), + b.index(v2+1).load(dtype=dtypes.float), + b.index(v2+2).load(dtype=dtypes.float), + b.index(v2+3).load(dtype=dtypes.float)] + #random.shuffle(loads) + sink = c.store(sum(loads)).sink() + + # determine golden order + golden = block_reorder(sink.toposort()) + + # render for test + print(self._test_render(golden)) + #print_uops(golden) + + # assert the loads are in this order + self.assertListEqual([g.src[0].src[1].render() for g in golden if g.op is Ops.LOAD], + ['(gidx1*4)', '((gidx1*4)+1)', '((gidx1*4)+2)', '((gidx1*4)+3)', + '(gidx0*27)', '((gidx0*27)+1)', '((gidx0*27)+2)', '((gidx0*27)+3)']) + + # assert math is after loads + first_math = [i for i,g in enumerate(golden) if g.op is Ops.ADD and g.dtype == dtypes.float][0] + assert not any(x.op is Ops.LOAD for x in golden[first_math:]) + + # confirm the sort is stable + self._test_randomize(golden) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/unit/test_device.py b/tinygrad_repo/test/unit/test_device.py index e0ffe6c6ea..1f20cebd49 100644 --- a/tinygrad_repo/test/unit/test_device.py +++ b/tinygrad_repo/test/unit/test_device.py @@ -1,10 +1,8 @@ #!/usr/bin/env python import unittest -from unittest.mock import patch -import os from tinygrad import Tensor from tinygrad.device import Device, Compiler -from tinygrad.helpers import diskcache_get, diskcache_put, getenv +from tinygrad.helpers import diskcache_get, diskcache_put, getenv, Context class TestDevice(unittest.TestCase): def test_canonicalize(self): @@ -24,6 +22,12 @@ class TestDevice(unittest.TestCase): with self.assertRaises(ModuleNotFoundError): Device["TYPO"] + def test_lowercase_canonicalizes(self): + device = Device.DEFAULT + Device.DEFAULT = device.lower() + self.assertEqual(Device.canonicalize(None), device) + Device.DEFAULT = device + class MockCompiler(Compiler): def __init__(self, key): super().__init__(key) def compile(self, src) -> bytes: return src.encode() @@ -32,20 +36,20 @@ class TestCompiler(unittest.TestCase): def test_compile_cached(self): diskcache_put("key", "123", None) # clear cache getenv.cache_clear() - with patch.dict(os.environ, {"DISABLE_COMPILER_CACHE": "0"}, clear=True): + with Context(DISABLE_COMPILER_CACHE=0): self.assertEqual(MockCompiler("key").compile_cached("123"), str.encode("123")) self.assertEqual(diskcache_get("key", "123"), str.encode("123")) def test_compile_cached_disabled(self): diskcache_put("disabled_key", "123", None) # clear cache getenv.cache_clear() - with patch.dict(os.environ, {"DISABLE_COMPILER_CACHE": "1"}, clear=True): + with Context(DISABLE_COMPILER_CACHE=1): self.assertEqual(MockCompiler("disabled_key").compile_cached("123"), str.encode("123")) self.assertIsNone(diskcache_get("disabled_key", "123")) def test_device_compile(self): getenv.cache_clear() - with patch.dict(os.environ, {"DISABLE_COMPILER_CACHE": "1"}): + with Context(DISABLE_COMPILER_CACHE=1): a = Tensor([0.,1.], device=Device.DEFAULT).realize() (a + 1).realize() diff --git a/tinygrad_repo/test/unit/test_disk_tensor.py b/tinygrad_repo/test/unit/test_disk_tensor.py index 917a497e9d..1e11a85e24 100644 --- a/tinygrad_repo/test/unit/test_disk_tensor.py +++ b/tinygrad_repo/test/unit/test_disk_tensor.py @@ -3,14 +3,14 @@ import numpy as np from tinygrad import Tensor, Device, dtypes from tinygrad.dtype import DType from tinygrad.nn.state import safe_load, safe_save, get_state_dict, torch_load -from tinygrad.helpers import Timing, fetch, temp, CI +from tinygrad.helpers import Timing, fetch, temp, CI, OSX from tinygrad.device import is_dtype_supported def compare_weights_both(url): import torch fn = fetch(url) tg_weights = get_state_dict(torch_load(fn)) - torch_weights = get_state_dict(torch.load(fn, map_location=torch.device('cpu'), weights_only=True), tensor_type=torch.Tensor) + torch_weights = get_state_dict(torch.load(fn, map_location=torch.device('cpu'), weights_only=False), tensor_type=torch.Tensor) assert list(tg_weights.keys()) == list(torch_weights.keys()) for k in tg_weights: if tg_weights[k].dtype == dtypes.bfloat16: tg_weights[k] = torch_weights[k].float() # numpy doesn't support bfloat16 @@ -68,8 +68,8 @@ class TestRawDiskBuffer(unittest.TestCase): _test_bitcasted(t, dtypes.float32, 3.1415927) _test_bitcasted(t, dtypes.uint32, 0x40490FDB) # doesn't suport normal cast - with self.assertRaises(RuntimeError): - Tensor.empty((4,), dtype=dtypes.int16, device=f"disk:{tmp}").cast(dtypes.float16) + with self.assertRaises(NotImplementedError): + Tensor.empty((4,), dtype=dtypes.int16, device=f"disk:{tmp}").cast(dtypes.float16).realize() # Those two should be moved to test_dtype.py:test_shape_change_bitcast after bitcast works on non-disk with self.assertRaises(RuntimeError): @@ -164,6 +164,7 @@ class TestSafetensors(unittest.TestCase): def test_save_all_dtypes(self): for dtype in dtypes.fields().values(): if dtype in [dtypes.bfloat16]: continue # not supported in numpy + if dtype in [dtypes.double, *dtypes.fp8s] and Device.DEFAULT == "METAL": continue # not supported on METAL path = temp(f"ones.{dtype}.safetensors") ones = Tensor(np.random.rand(10,10), dtype=dtype) safe_save(get_state_dict(ones), path) @@ -210,7 +211,7 @@ class TestSafetensors(unittest.TestCase): 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="CLANG").to(f"disk:{temp(fn)}") + tinygrad_tensor = Tensor(data, device="CPU").to(f"disk:{temp(fn)}") numpy_arr = np.array(data) tinygrad_fxn(tinygrad_tensor) np_fxn(numpy_arr) @@ -250,7 +251,7 @@ class TestDiskTensor(unittest.TestCase): def test_write_ones(self): pathlib.Path(temp("dt_write_ones")).unlink(missing_ok=True) - out = Tensor.ones(10, 10, device="CLANG").contiguous() + out = Tensor.ones(10, 10, device="CPU").contiguous() outdisk = out.to(f"disk:{temp('dt_write_ones')}") print(outdisk) outdisk.realize() @@ -265,6 +266,14 @@ class TestDiskTensor(unittest.TestCase): reloaded = Tensor.empty(10, 10, device=f"disk:{temp('dt_write_ones')}") np.testing.assert_almost_equal(reloaded.numpy(), np.ones((10, 10))) + def test_simple_setitem(self): + pathlib.Path(temp(fn:="dt_simple_setitem")).unlink(missing_ok=True) + data = [[1],[2]] + src = Tensor(data) + dt = src.to(f"disk:{temp(fn)}") + dt[1] = [3] + self.assertEqual(dt.tolist(), [[1], [3]]) + def test_assign_slice(self): def assign(x,s,y): x[s] = y helper_test_disk_tensor("dt_assign_slice_1", [0,1,2,3], lambda x: assign(x, slice(0,2), [13, 12])) @@ -288,15 +297,16 @@ class TestDiskTensor(unittest.TestCase): def test_bitcast(self): with open(temp('dt_bitcast'), "wb") as f: f.write(bytes(range(10,20))) t = Tensor.empty(5, dtype=dtypes.int16, device=f"disk:{temp('dt_bitcast')}") - ret = t.to("CLANG").bitcast(dtypes.uint16) + 1 + ret = t.to("CPU").bitcast(dtypes.uint16) + 1 assert ret.tolist() == [2827, 3341, 3855, 4369, 4883] def test_bitcast_view(self): with open(temp('dt_bitcast_view'), "wb") as f: f.write(bytes(range(10, 24))) t = Tensor.empty(3, dtype=dtypes.uint, device=f"disk:{temp('dt_bitcast_view')}").shrink([(0, 2)]) - ret = t.bitcast(dtypes.uint16).to("CLANG") + 1 + ret = t.bitcast(dtypes.uint16).to("CPU") + 1 assert ret.tolist() == [2827, 3341, 3855, 4369] + @unittest.skipIf(OSX, "new LLVM has an issue on OSX") def test_bf16_disk_write_read(self): t = Tensor([10000, -1, -1000, -10000, 20], dtype=dtypes.float32) t.to(f"disk:{temp('dt_bf16_disk_write_read_f32')}").realize() @@ -341,6 +351,11 @@ class TestDiskTensor(unittest.TestCase): on_dev = t.to(Device.DEFAULT).realize() np.testing.assert_equal(on_dev.numpy(), t.numpy()) + @unittest.skipUnless(OSX, "seems to only be an issue on macOS with file size >2 GiB") + def test_copy_to_cpu_not_truncated(self): + with open((fn:=temp("dt_copy_to_cpu_not_truncated")), "wb") as f: f.write(b'\x01' * (size := int(2 * 1024**3)) + (test := b"test")) + x = Tensor.empty(size + len(test), dtype=dtypes.uint8, device=f"disk:{fn}").to("CPU").realize() + assert x[size:].data().tobytes() == test class TestPathTensor(unittest.TestCase): def setUp(self): @@ -361,10 +376,10 @@ class TestPathTensor(unittest.TestCase): np.testing.assert_array_equal(t.numpy(), np.frombuffer(self.test_data, dtype=np.uint8)) def test_path_tensor_with_device(self): - t = Tensor(self.test_file, device="CLANG") + t = Tensor(self.test_file, device="CPU") self.assertEqual(t.shape, (100,)) self.assertEqual(t.dtype, dtypes.uint8) - self.assertEqual(t.device, "CLANG") + self.assertEqual(t.device, "CPU") np.testing.assert_array_equal(t.numpy(), np.frombuffer(self.test_data, dtype=np.uint8)) def test_path_tensor_empty_file(self): @@ -389,8 +404,8 @@ class TestPathTensor(unittest.TestCase): def test_path_tensor_copy_to_device(self): t = Tensor(self.test_file) - t_cpu = t.to("CLANG") - self.assertEqual(t_cpu.device, "CLANG") + t_cpu = t.to("CPU") + self.assertEqual(t_cpu.device, "CPU") np.testing.assert_array_equal(t_cpu.numpy(), np.frombuffer(self.test_data, dtype=np.uint8)) if __name__ == "__main__": diff --git a/tinygrad_repo/test/unit/test_elf.py b/tinygrad_repo/test/unit/test_elf.py index ed8edce694..cdf02b7728 100644 --- a/tinygrad_repo/test/unit/test_elf.py +++ b/tinygrad_repo/test/unit/test_elf.py @@ -1,12 +1,13 @@ import unittest, subprocess, platform +from tinygrad.runtime.ops_cpu import ClangJITCompiler from tinygrad.runtime.support.elf import elf_loader class TestElfLoader(unittest.TestCase): def test_load_clang_jit_strtab(self): src = ''' - void relocation(int); // will be a jump to relocation (needed for .rela.text to exist) - void test(int x) { - relocation(x+1); + int something; // will be a load from a relocation (needed for .rela.text to exist) + int test(int x) { + return something + x; } ''' args = ('-x', 'c', '-c', '-target', f'{platform.machine()}-none-unknown-elf', '-march=native', '-fPIC', '-O2', '-ffreestanding', '-nostdlib') @@ -14,6 +15,15 @@ class TestElfLoader(unittest.TestCase): _, sections, _ = elf_loader(obj) section_names = [sh.name for sh in sections] assert '.text' in section_names and '.rela.text' in section_names, str(section_names) + def test_clang_jit_compiler_external_raise(self): + src = ''' + int evil_external_function(int); + int test(int x) { + return evil_external_function(x+2)*2; + } + ''' + with self.assertRaisesRegex(RuntimeError, 'evil_external_function'): + ClangJITCompiler().compile(src) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_gradient.py b/tinygrad_repo/test/unit/test_gradient.py index 21182874f2..3c3290864d 100644 --- a/tinygrad_repo/test/unit/test_gradient.py +++ b/tinygrad_repo/test/unit/test_gradient.py @@ -1,10 +1,9 @@ from typing import Callable import unittest, math -import jax -import jax.numpy as jnp +import torch from tinygrad import Tensor from tinygrad.dtype import dtypes -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp from tinygrad.gradient import compute_gradient class TestGradient(unittest.TestCase): @@ -13,20 +12,22 @@ class TestGradient(unittest.TestCase): self.assertAlmostEqual(x, y, places=5) def _test_one_input_function(self, f:Callable, jf:Callable|None=None): + if jf is None: jf = f x = UOp.variable('x', -math.inf, math.inf, dtype=dtypes.float) - gx = compute_gradient(f(x), UOp.const(dtypes.float, 1.0), [x])[x] - gf = jax.grad(f if jf is None else jf) + gx = compute_gradient(f(x), UOp.const(dtypes.float, 1.0), set([x]))[x] for val in [-5., -2.0, 0.0, 2.0, 5.]: - tg_out, jax_out = gx.substitute({x: x.const_like(val)}).ssimplify(), gf(val).item() - self._cmp_nan_okay(tg_out, jax_out) + tg_out = gx.substitute({x: x.const_like(val)}).ssimplify() + tx = torch.tensor([val], dtype=torch.float, requires_grad=True) + torch_out = torch.autograd.grad(jf(tx), tx)[0].item() + self._cmp_nan_okay(tg_out, torch_out) def _test_two_input_function(self, f:Callable, jf:Callable|None=None): + if jf is None: jf = f x = UOp.variable('x', -math.inf, math.inf, dtype=dtypes.float) y = UOp.variable('y', -math.inf, math.inf, dtype=dtypes.float) - grads = compute_gradient(f(x, y), UOp.const(dtypes.float, 1.0), [x, y]) + grads = compute_gradient(f(x, y), UOp.const(dtypes.float, 1.0), set([x, y])) gx, gy = grads[x], grads[y] - gf = jax.grad(f if jf is None else jf, argnums=(0, 1)) for valx in [-5., -2.0, 0.0, 2.0, 5.]: for valy in [-5., -2.0, 0.0, 2.0, 5.]: @@ -34,28 +35,32 @@ class TestGradient(unittest.TestCase): substitutions = {x: x.const_like(valx), y: y.const_like(valy)} tg_out_x = gx.substitute(substitutions).ssimplify() tg_out_y = gy.substitute(substitutions).ssimplify() - jax_out_x, jax_out_y = [x.item() for x in gf(valx, valy)] - self._cmp_nan_okay(tg_out_x, jax_out_x) - self._cmp_nan_okay(tg_out_y, jax_out_y) + tx = torch.tensor([valx], dtype=torch.float, requires_grad=True) + ty = torch.tensor([valy], dtype=torch.float, requires_grad=True) + torch_grad = torch.autograd.grad(jf(tx, ty), [tx, ty]) + torch_out_x, torch_out_y = [x.item() for x in torch_grad] + + self._cmp_nan_okay(tg_out_x, torch_out_x) + self._cmp_nan_okay(tg_out_y, torch_out_y) # unary ops unit def test_recip(self): self._test_one_input_function(lambda x: 1.0/x) - def test_sin(self): self._test_one_input_function(lambda x: x.sin(), lambda x: jnp.sin(x)) - def test_sqrt(self): self._test_one_input_function(lambda x: x.sqrt(), lambda x: jnp.sqrt(x)) - def test_log2(self): self._test_one_input_function(lambda x: x.log2(), lambda x: jnp.log2(x)) - def test_exp2(self): self._test_one_input_function(lambda x: x.exp2(), lambda x: jnp.exp2(x)) + def test_sin(self): self._test_one_input_function(lambda x: x.sin()) + def test_sqrt(self): self._test_one_input_function(lambda x: x.sqrt()) + def test_log2(self): self._test_one_input_function(lambda x: x.log2()) + def test_exp2(self): self._test_one_input_function(lambda x: x.exp2()) # binary ops unit def test_add(self): self._test_two_input_function(lambda x,y: x+y) def test_mul(self): self._test_two_input_function(lambda x,y: x*y) # chain rule - def test_chain(self): self._test_one_input_function(lambda x: x.sin().sqrt(), lambda x: jnp.sqrt(jnp.sin(x))) + def test_chain(self): self._test_one_input_function(lambda x: x.sin().sqrt()) def test_chain_binop(self): self._test_two_input_function(lambda x,y: (x*y)+x*y) - def test_big_add_sin(self): self._test_two_input_function(lambda x,y: x.sin()+3.0/y, lambda x,y: jnp.sin(x)+3.0/y) + def test_big_add_sin(self): self._test_two_input_function(lambda x,y: x.sin()+3.0/y) def test_big_chain(self): self._test_two_input_function(lambda x,y: (1.0/x*y)+x*y) - def test_where(self): self._test_two_input_function(lambda x,y: (x 0, @@ -154,14 +154,14 @@ class TestEdgeCasesAndSpecialOperations(unittest.TestCase): @unittest.skip("broken") def test_full_graph_rewrite_modulo_negative_dividend(self): x_var_uop = UOp.variable('x', -5, -1) - optimized_sink = full_graph_rewrite((x_var_uop % 3).sink()) + optimized_sink = full_rewrite_to_sink((x_var_uop % 3).sink()) for x_value in range(-5, 0): self.assertEqual(x_value % 3, evaluate_uop(optimized_sink.src[0], {'x': x_value})) @unittest.skip("broken") def test_full_graph_rewrite_division_negative_divisor(self): x_var_uop = UOp.variable('x', 1, 5) - optimized_sink = full_graph_rewrite((x_var_uop // -2).sink()) + optimized_sink = full_rewrite_to_sink((x_var_uop // -2).sink()) for x_value in range(1, 6): self.assertEqual(x_value // -2, evaluate_uop(optimized_sink.src[0], {'x': x_value})) @@ -203,7 +203,8 @@ class TestGEPAndVectorizeRewrite(unittest.TestCase): import inspect -from tinygrad.ops import graph_rewrite, _substitute, track_rewrites, symbolic_simple +from tinygrad.uop.ops import graph_rewrite, _substitute, track_rewrites +from tinygrad.codegen.symbolic import symbolic_simple class TestBottomUpRewrite(unittest.TestCase): def test_const_folding(self): @@ -274,5 +275,6 @@ class TestSubstitute(unittest.TestCase): ret = substitute(ret, {a.sin():a.sqrt(), n1.sin():n1.sqrt()}) self.assertIs(ret, a.sqrt().sqrt()) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_helpers.py b/tinygrad_repo/test/unit/test_helpers.py index 7f777d2bfd..3114e5202f 100644 --- a/tinygrad_repo/test/unit/test_helpers.py +++ b/tinygrad_repo/test/unit/test_helpers.py @@ -1,10 +1,9 @@ import gzip, unittest -from PIL import Image from tinygrad import Variable from tinygrad.helpers import Context, ContextVar -from tinygrad.helpers import merge_dicts, strip_parens, prod, round_up, fetch, fully_flatten, from_mv, to_mv, polyN +from tinygrad.helpers import merge_dicts, strip_parens, prod, round_up, fetch, fully_flatten, from_mv, to_mv, polyN, time_to_str, cdiv, cmod, getbits from tinygrad.tensor import get_shape -from tinygrad.codegen.lowerer import get_contraction +from tinygrad.codegen.lowerer import get_contraction, get_contraction_with_reduce import numpy as np VARIABLE = ContextVar("VARIABLE", 0) @@ -19,38 +18,32 @@ class TestContextVars(unittest.TestCase): _TMP = ContextVar("_TMP", 5) self.assertEqual(_TMP.value, 5) - @unittest.expectedFailure - def test_multiple_creation_ignored(self): + def test_cannot_recreate(self): _TMP2 = ContextVar("_TMP2", 1) - _TMP2 = ContextVar("_TMP2", 2) - self.assertEqual(_TMP2.value, 1) + with self.assertRaises(RuntimeError): + _TMP2 = ContextVar("_TMP2", 2) - @unittest.expectedFailure 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) + with self.assertRaises(RuntimeError): + _TMP3 = ContextVar("_TMP3", 2) - @unittest.expectedFailure - def test_value_accross_modules(self): + def test_value_across_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) + with self.assertRaises(RuntimeError): + _C = ContextVar("C", 0) - @unittest.expectedFailure 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) + with self.assertRaises(RuntimeError): + # Assignment in another module. + exec('from tinygrad.helpers import ContextVar;B = ContextVar("B", 0);B.value = 3;', {}) # pylint:disable=exec-used def test_context_assignment(self): with Context(VARIABLE=1): @@ -62,44 +55,17 @@ class TestContextVars(unittest.TestCase): with Context(SOMETHING_ELSE=1): pass - @unittest.expectedFailure - 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) - - @unittest.expectedFailure - 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): + MORE = ContextVar("MORE", 2) + with Context(VARIABLE=3, MORE=3): self.assertEqual(VARIABLE.value, 3) + self.assertEqual(MORE.value, 3) self.assertEqual(VARIABLE.value, 2) + self.assertEqual(MORE.value, 2) self.assertEqual(VARIABLE.value, 1) + self.assertEqual(MORE.value, 2) # TODO: should this raise? self.assertEqual(VARIABLE.value, 0) def test_decorator(self): @@ -159,11 +125,13 @@ class TestFetch(unittest.TestCase): assert (len(fetch('https://google.com', allow_caching=False).read_bytes())>0) def test_fetch_img(self): + from PIL import Image img = fetch("https://avatars.githubusercontent.com/u/132956020", allow_caching=False) with Image.open(img) as pimg: assert pimg.size == (77, 77), pimg.size def test_fetch_subdir(self): + from PIL import Image img = fetch("https://avatars.githubusercontent.com/u/132956020", allow_caching=False, subdir="images") with Image.open(img) as pimg: assert pimg.size == (77, 77), pimg.size @@ -215,6 +183,20 @@ class TestMemoryview(unittest.TestCase): assert base[0] == 2 class TestGetContraction(unittest.TestCase): + def test_contraction_with_reduce(self): + r = get_contraction((16, 1, 1, 1), (16, 1, 1)) + self.assertEqual(r, [[0], [], [1, 2, 3]]) + r = get_contraction_with_reduce((16, 1, 1, 1), (16, 1, 1), (1,)) + self.assertEqual(r, [[0], [1, 2], [3]]) + + r = get_contraction((16, 1, 1, 1, 1), (16, 1, 1, 1)) + self.assertEqual(r, [[0], [], [], [1, 2, 3, 4]]) + r = get_contraction_with_reduce((16, 1, 1, 1, 1), (16, 1, 1, 1), (1,)) + self.assertEqual(r, [[0], [1, 2], [3], [4]]) + + r = get_contraction_with_reduce((2, 512, 1, 1), (2, 1, 512), (1,)) + self.assertIsNone(r) + def test_contraction(self): r = get_contraction((1,2,3,4), (2,3,4)) self.assertEqual(r, [[0, 1], [2], [3]]) @@ -308,12 +290,63 @@ class TestPolyN(unittest.TestCase): def test_uop(self): from tinygrad.dtype import dtypes - from tinygrad.ops import UOp + from tinygrad.uop.ops import UOp from test.helpers import eval_uop np.testing.assert_allclose(eval_uop(polyN(UOp.const(dtypes.float, 1.0), [1.0, -2.0, 1.0])), 0.0) np.testing.assert_allclose(eval_uop(polyN(UOp.const(dtypes.float, 2.0), [1.0, -2.0, 1.0])), 1.0) np.testing.assert_allclose(eval_uop(polyN(UOp.const(dtypes.float, 3.0), [1.0, -2.0, 1.0])), 4.0) np.testing.assert_allclose(eval_uop(polyN(UOp.const(dtypes.float, 4.0), [1.0, -2.0, 1.0])), 9.0) +class TestTimeToStr(unittest.TestCase): + def test_seconds(self): self.assertEqual(" 10.01s ", time_to_str(10.01)) + def test_boundary_sec_ms(self): self.assertEqual("10000.00ms", time_to_str(10)) + def test_milliseconds(self): self.assertEqual(" 500.00ms", time_to_str(0.5)) + def test_boundary_ms_us(self): self.assertEqual("10000.00us", time_to_str(0.01)) + def test_microseconds(self): self.assertEqual(" 100.00us", time_to_str(0.0001)) + def test_zero(self): self.assertEqual(" 0.00us", time_to_str(0)) + def test_width_formatting(self): self.assertEqual(" 10.01s ", time_to_str(10.01, w=6)) + +class TestCStyleDivMod(unittest.TestCase): + def test_div_pos(self): + self.assertEqual(cdiv(-9, 5), -1) + self.assertEqual(cdiv(-4, 5), 0) + self.assertEqual(cdiv(0, 5), 0) + self.assertEqual(cdiv(4, 5), 0) + self.assertEqual(cdiv(9, 5), 1) + def test_div_neg(self): + self.assertEqual(cdiv(-9, -5), 1) + self.assertEqual(cdiv(-4, -5), 0) + self.assertEqual(cdiv(0, -5), 0) + self.assertEqual(cdiv(4, -5), 0) + self.assertEqual(cdiv(9, -5), -1) + def test_mod_pos(self): + self.assertEqual(cmod(-9, 5), -4) + self.assertEqual(cmod(-4, 5), -4) + self.assertEqual(cmod(0, 5), 0) + self.assertEqual(cmod(4, 5), 4) + self.assertEqual(cmod(9, 5), 4) + def test_mod_neg(self): + self.assertEqual(cmod(-9, -5), -4) + self.assertEqual(cmod(-4, -5), -4) + self.assertEqual(cmod(0, -5), 0) + self.assertEqual(cmod(4, -5), 4) + self.assertEqual(cmod(9, -5), 4) + +class TestGetBits(unittest.TestCase): + def test_low_bits(self): + self.assertEqual(getbits(0b11010110, 0, 3), 0b0110) + + def test_high_bits(self): + self.assertEqual(getbits(0b11010110, 4, 7), 0b1101) + + def test_middle_bits(self): + self.assertEqual(getbits(0b11010110, 3, 5), 0b010) + + def test_full_range(self): + self.assertEqual(getbits(0b11010110, 0, 7), 0b11010110) + + def test_single_bit(self): + self.assertEqual(getbits(0b100000000, 8, 8), 1) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_linearizer_rewrite.py b/tinygrad_repo/test/unit/test_linearizer_rewrite.py new file mode 100644 index 0000000000..358c43cec6 --- /dev/null +++ b/tinygrad_repo/test/unit/test_linearizer_rewrite.py @@ -0,0 +1,28 @@ +import unittest +from tinygrad import Tensor, Context, Device +from tinygrad.codegen.kernel import Kernel, Opt, OptOps + +class TestLinearizerRewrite(unittest.TestCase): + def test_reduction(self): + t = Tensor.ones((64,64), device="NULL").contiguous().realize() + out = (t*2).sum(axis=1) + with Context(SPLIT_REDUCEOP=0, DEVECTORIZE=0): + si = out.schedule()[-1] + k = Kernel(si.ast, Device["CPU"].renderer) + k.apply_opt(Opt(OptOps.UPCAST, 0, 4)) + k.apply_opt(Opt(OptOps.UNROLL, 0, 4)) + prg = k.to_program() + print(prg.src) + + def test_arange(self): + out = Tensor.arange(32, device="NULL") + with Context(SPLIT_REDUCEOP=0, DEVECTORIZE=0): + si = out.schedule()[-1] + k = Kernel(si.ast, Device["CPU"].renderer) + k.apply_opt(Opt(OptOps.UPCAST, 0, 4)) + k.apply_opt(Opt(OptOps.UNROLL, 0, 4)) + prg = k.to_program() + print(prg.src) + +if __name__ == '__main__': + unittest.main() diff --git a/tinygrad_repo/test/unit/test_microbenchmarks.py b/tinygrad_repo/test/unit/test_microbenchmarks.py new file mode 100644 index 0000000000..71b43c880c --- /dev/null +++ b/tinygrad_repo/test/unit/test_microbenchmarks.py @@ -0,0 +1,43 @@ +import unittest, time +from tinygrad.uop.ops import UOp +from tinygrad.dtype import dtypes + +# it's about 1 ms per 1k UOps on M3 +N = 10000 + +class TestMicrobenchmarks(unittest.TestCase): + def setUp(self): + self.st = time.perf_counter() + def tearDown(self): + et = (time.perf_counter() - self.st) + print(f"{self._testMethodName} {et*1e3:.2f} ms") + + def test_uop_instant_creation(self): + for i in range(N): UOp.const(dtypes.int, 100+i) + + def test_uop_list_creation(self): + [UOp.const(dtypes.int, 100+i) for i in range(N)] + + def test_uop_add_2n(self): + a = UOp.const(dtypes.int, 2) + for _ in range(N): a = a + a + + def test_uop_toposort(self): + a = UOp.const(dtypes.int, 0) + for i in range(N): a = a + UOp.const(dtypes.int, 100+i) + self.setUp() + self.assertEqual(len(a.toposort()), 2*N+1) + + def test_uop_toposort_2n(self): + a = UOp.const(dtypes.int, 0) + for i in range(N): a = a + a + self.setUp() + self.assertEqual(len(a.toposort()), N+1) + + def test_uop_simplify(self): + a = UOp.const(dtypes.int, 2) + for _ in range(N): (a+a).simplify() + +if __name__ == '__main__': + unittest.main() + diff --git a/tinygrad_repo/test/unit/test_pattern_matcher.py b/tinygrad_repo/test/unit/test_pattern_matcher.py index f4003011e6..d1dfffaadd 100644 --- a/tinygrad_repo/test/unit/test_pattern_matcher.py +++ b/tinygrad_repo/test/unit/test_pattern_matcher.py @@ -1,7 +1,7 @@ import unittest, itertools from tinygrad.dtype import dtypes -from tinygrad.ops import Ops, UOp, GroupOp # noqa: F401 -from tinygrad.ops import PatternMatcher, UPat +from tinygrad.uop.ops import Ops, UOp, GroupOp # noqa: F401 +from tinygrad.uop.ops import PatternMatcher, UPat class TestPatternMatcher(unittest.TestCase): def test_simple_match(self): @@ -23,6 +23,14 @@ class TestPatternMatcher(unittest.TestCase): c1 = v1+v2 self.assertEqual(matcher.rewrite(c1), c1) + def test_minimum_len(self): + matcher = PatternMatcher([ + (UPat(Ops.NOOP, src=(UPat(Ops.NOOP), UPat(Ops.NOOP)), allow_any_len=True), lambda: True), + ]) + self.assertTrue(matcher.rewrite(UOp(Ops.NOOP, src=(UOp(Ops.NOOP), UOp(Ops.NOOP), UOp(Ops.NOOP),)))) + self.assertTrue(matcher.rewrite(UOp(Ops.NOOP, src=(UOp(Ops.NOOP), UOp(Ops.NOOP))))) + self.assertIsNone(matcher.rewrite(UOp(Ops.NOOP, src=(UOp(Ops.NOOP),)))) + @unittest.skip("closures aren't supported on pattern matchers") def test_match_sz_0(self): match_cnt = 0 diff --git a/tinygrad_repo/test/unit/test_rewrite_map.py b/tinygrad_repo/test/unit/test_rewrite_map.py new file mode 100644 index 0000000000..0eed947727 --- /dev/null +++ b/tinygrad_repo/test/unit/test_rewrite_map.py @@ -0,0 +1,202 @@ +import unittest +from tinygrad import dtypes +from tinygrad.uop.ops import UOp, graph_rewrite_map, _substitute +from tinygrad.codegen.symbolic import symbolic + +class TestRewriteMap(unittest.TestCase): + def test_substitute(self): + a = UOp.variable('a', 0, 10) + b = UOp.variable('b', 0, 10) + c = UOp.variable('c', 0, 10) + e = UOp.variable('e', 0, 10) + ret = (a+b)*c + sub = {a+b: e} + sub_map = graph_rewrite_map(ret, _substitute, sub, bottom_up=True) + self.assertIs(sub_map[a+b], e) + self.assertIs(sub_map[(a+b)*c], e*c) + + def test_substitute_depth_2(self): + a = UOp.variable('a', 0, 10) + b = UOp.variable('b', 0, 10) + c = UOp.variable('c', 0, 10) + d = UOp.variable('d', 0, 10) + e = UOp.variable('e', 0, 10) + f = UOp.variable('f', 0, 10) + ret = (a+b)*c+d + sub = {a+b: e, (a+b)*c: f} + sub_map = graph_rewrite_map(ret, _substitute, sub, bottom_up=True) + self.assertIs(sub_map[a+b], e) + self.assertIs(sub_map[(a+b)*c], f) + + def test_multistage_substitute(self): + a = UOp.variable('a', 0, 10) + b = UOp.variable('b', 0, 10) + c = UOp.variable('c', 0, 10) + d = UOp.variable('d', 0, 10) + sub1 = {a+b:c} + start = (a+b)*c + # stage 1: (a+b)*c -> c*c + sub_map1 = graph_rewrite_map(start, _substitute, sub1, bottom_up=True) + self.assertIs(sub_map1[(a+b)*c], c*c) + # stage 2: c*c -> d + sub2 = {c*c:d} + sub_map2 = graph_rewrite_map(sub_map1[start], _substitute, sub2, input_map=sub_map1, bottom_up=True) + # (a+b)*c -> c*c -> d + self.assertIs(sub_map2[(a+b)*c], d) + + def test_add_zero(self): + # Build a small graph: add(0, add(const=0, const=5)) + zero_node = UOp.const(dtypes.int, 0) + five_node = UOp.const(dtypes.int, 5) + inner_add = zero_node + five_node + root_add = zero_node + inner_add + + # Perform top-down rewrite + node_map = graph_rewrite_map(root_add, symbolic) + + # We expect that add(0, add(0, 5)) -> add(0, 5) -> 5 + # Check the mapping + assert node_map[root_add] == five_node + assert node_map[inner_add] == five_node + # zero_node and five_node map to themselves + assert node_map[zero_node] == zero_node + assert node_map[five_node] == five_node + + def test_double_neg(self): + """ + Test rewriting neg(neg(5)) => 5 using symbolic. + """ + # In some versions of TinyGrad, you might do: (-(-five_node)) + five_node = UOp.const(dtypes.int, 5) + # If your code allows UOp(...), do that; else you might do something like: + # double_neg_five = -(-five_node) + # But let's be explicit: + neg_five = -five_node + double_neg_five = -neg_five + + node_map = graph_rewrite_map(double_neg_five, symbolic) + + # node_map should map double_neg_five -> five_node + self.assertEqual(node_map[double_neg_five], five_node) + # five_node maps to itself + self.assertEqual(node_map[five_node], five_node) + + def test_add_zero_and_double_neg(self): + """ + Combine both rewrites: add(0, neg(neg(5))) => add(0, 5) => 5 + """ + zero_node = UOp.const(dtypes.int, 0) + five_node = UOp.const(dtypes.int, 5) + neg_five = -five_node + double_neg_five = -neg_five + root_add = zero_node + double_neg_five + + node_map = graph_rewrite_map(root_add, symbolic) + + # node_map: root_add -> five_node, double_neg_five -> five_node + self.assertEqual(node_map[root_add], five_node) + self.assertEqual(node_map[double_neg_five], five_node) + # zero_node, five_node map to themselves + self.assertEqual(node_map[zero_node], zero_node) + self.assertEqual(node_map[five_node], five_node) + + def test_multi_var_rewrites(self): + x_var = UOp.variable('x', 0, 10) + y_var = UOp.variable('y', -5, 5) + zero_node = UOp.const(dtypes.int, 0) + + sum_with_zero = y_var + zero_node # (y + 0) + combined = x_var + sum_with_zero # x + (y + 0) + double_neg = -(-combined) # neg(neg(x + y)) + final_expr = zero_node + double_neg # 0 + (x + y) + + node_map = graph_rewrite_map(final_expr, symbolic) + + # The final root should be (x_var + y_var). + expected = x_var + y_var + + # Each sub-expression has its own "final" result. + # (y + 0) -> y_var + self.assertEqual(node_map[sum_with_zero], y_var) + # (x + (y+0)) -> (x + y) + self.assertEqual(node_map[combined], expected) + # neg(neg(x+y)) -> (x + y) + self.assertEqual(node_map[double_neg], expected) + # 0 + (x+y) -> (x + y) + self.assertEqual(node_map[final_expr], expected) + + # x_var, y_var, zero_node remain unchanged + self.assertEqual(node_map[x_var], x_var) + self.assertEqual(node_map[y_var], y_var) + self.assertEqual(node_map[zero_node], zero_node) + + def test_complex_multi_var_edges(self): + """ + Build a multi-variable expression with multiple intermediates: + + x_var = UOp.variable('x', 1, 10) + y_var = UOp.variable('y', -5, 5) + z_var = UOp.variable('z', 0, 5) + zero_node = UOp.const(dtypes.int, 0) + one_node = UOp.const(dtypes.int, 1) + + yz_sum = y_var + z_var + yz_sum_zero = yz_sum + zero_node -> rewrites to yz_sum + yz_neg = -yz_sum_zero -> -(y+z) + yz_dneg = -yz_neg -> y+z (double neg gone) + x_plus_yz = x_var + yz_dneg -> x + (y+z) + double_neg_x = -(-x_plus_yz) -> x + (y+z) + final_expr = double_neg_x * one_node -> x + (y+z) + + We expect the final result to be (x + (y+z)). + Each original node should map to the final node that replaces it, + which might be structurally equivalent but not the same reference. + """ + x_var = UOp.variable('x', 1, 10) + y_var = UOp.variable('y', -5, 5) + z_var = UOp.variable('z', 0, 5) + zero_node = UOp.const(dtypes.int, 0) + one_node = UOp.const(dtypes.int, 1) + + # Build sub-expressions + yz_sum = y_var + z_var # (y + z) + yz_sum_zero = yz_sum + zero_node # (y + z) + 0 + yz_neg = -yz_sum_zero # -(y+z) + yz_dneg = -yz_neg # -(-(y+z)) -> (y+z) + x_plus_yz = x_var + yz_dneg # x + (y+z) + double_neg_x = -(-x_plus_yz) # neg(neg(x+(y+z))) -> x+(y+z) + final_expr = double_neg_x * one_node # (x+(y+z)) * 1 -> x+(y+z) + + node_map = graph_rewrite_map(final_expr, symbolic) + + # (y + z) is unchanged + self.assertEqual(node_map[yz_sum], yz_sum) + + # (y+z) + 0 => (y+z) + self.assertEqual(node_map[yz_sum_zero], yz_sum) + + # -(y+z) remains -(y+z), but might be a new UOp with updated children + # Compare structurally to -(y_var + z_var). + self.assertEqual(node_map[yz_neg], -yz_sum) + + # -(-(y+z)) => (y+z) + self.assertEqual(node_map[yz_dneg], yz_sum) + + # x + (y+z) => might get recreated if yz_dneg was changed, so compare to x + yz_sum + self.assertEqual(node_map[x_plus_yz], x_var + yz_sum) + + # -(-(x+(y+z))) => x + (y+z) + self.assertEqual(node_map[double_neg_x], x_var + yz_sum) + + # (x+(y+z)) * 1 => x+(y+z) + self.assertEqual(node_map[final_expr], x_var + yz_sum) + + # Unchanged atomic nodes map to themselves + self.assertEqual(node_map[x_var], x_var) + self.assertEqual(node_map[y_var], y_var) + self.assertEqual(node_map[z_var], z_var) + self.assertEqual(node_map[zero_node], zero_node) + self.assertEqual(node_map[one_node], one_node) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/unit/test_shapetracker.py b/tinygrad_repo/test/unit/test_shapetracker.py index b2acc24563..223acceb04 100644 --- a/tinygrad_repo/test/unit/test_shapetracker.py +++ b/tinygrad_repo/test/unit/test_shapetracker.py @@ -5,8 +5,8 @@ from tinygrad.dtype import dtypes from tinygrad.helpers import prod from tinygrad.shape.shapetracker import ShapeTracker, View from tinygrad import Variable -from tinygrad.ops import UOp, Ops, graph_rewrite -from tinygrad.codegen.uopgraph import sym +from tinygrad.uop.ops import UOp, Ops, graph_rewrite +from tinygrad.codegen.devectorizer import sym from itertools import product def shapetracker_getitem(st:ShapeTracker, val:int): @@ -43,9 +43,9 @@ class CheckingShapeTracker: 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) + def flip(self, arg): + self.st = self.st.flip(arg) + self.t = np.flip(self.t, tuple(i for i in range(len(arg)) if arg[i])) return self def shrink(self, arg): @@ -58,11 +58,6 @@ class CheckingShapeTracker: 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] @@ -579,20 +574,18 @@ class TestShapeTrackerFuzzFailures(unittest.TestCase): 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.flip( (True, False, True) ) + self.st.reshape( (3, 9) ) self.st.shrink( ((1, 2), (1, 5)) ) - self.st.stride( (1, -1) ) + self.st.flip( (True, True) ) 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,) ) + self.st.flip( (True, False) ) def test_case_4(self): self.st.reshape( (3, 3, 3, 1) ) self.st.pad( ((0, 0), (0, 0), (0, 0), (1, 1)) ) @@ -687,21 +680,13 @@ class TestShapeTracker(unittest.TestCase): self.st.reshape((9,6,1)) self.st.expand((9,6,4)) - def test_pad_stride(self): + def test_pad_flip(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)) + self.st.flip((True, False)) - 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_pad_flip_int(self): + self.st.pad(((1,4), (1,3))) + self.st.flip((0, 1)) def test_reshape(self): new_shape = self.st.shape[::-1] @@ -722,13 +707,13 @@ class TestShapeTracker(unittest.TestCase): self.apply(lambda x: x.expand(tuple(new_shape))) def test_flip_0(self): - self.apply(lambda x: x.flip((0,))) + self.apply(lambda x: x.flip((True, False))) def test_flip_1(self): - self.apply(lambda x: x.flip((1,))) + self.apply(lambda x: x.flip((False, True))) def test_flip_01(self): - self.apply(lambda x: x.flip((0,1))) + self.apply(lambda x: x.flip((True, True))) def test_slice_0(self): self.apply(lambda x: x.shrink(((1, x.shape[0]), (0, x.shape[1])))) @@ -754,16 +739,13 @@ class TestShapeTracker(unittest.TestCase): 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_double_flip(self): + self.apply(lambda x: x.flip((True, False))) + self.apply(lambda x: x.flip((True, False))) - 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_flip(self): self.apply(lambda x: x.flip((True, False))) + def test_flip2(self): self.apply(lambda x: x.flip((False, True))) + def test_flip3(self): self.apply(lambda x: x.flip((True, True))) def test_reshape_then_permute(self): self.test_reshape() @@ -833,6 +815,18 @@ class TestShapeTrackerSize(unittest.TestCase): strides=(0, 128, 0, 4096, 1), offset=0, mask=None, contiguous=False))) self.assertEqual(st.real_size(), 8389632) + def test_pad_size_simple(self): + st = ShapeTracker.from_shape((10,)).pad(((2,4),)) + self.assertEqual(st.real_size(), 10) + + def test_pad_size_multiview(self): + st = ShapeTracker.from_shape((10,10)).pad(((2,4), (3,1))).reshape((16*14,)) + self.assertEqual(st.real_size(), 100) + + def test_flip_size(self): + st = ShapeTracker.from_shape((10,10)).pad(((2,4), (3,1))).flip((True, True)) + self.assertEqual(st.real_size(), 100) + class TestConsecutive(unittest.TestCase): @classmethod def setUpClass(self): diff --git a/tinygrad_repo/test/unit/test_shapetracker_math.py b/tinygrad_repo/test/unit/test_shapetracker_math.py index f033800051..efd017f509 100644 --- a/tinygrad_repo/test/unit/test_shapetracker_math.py +++ b/tinygrad_repo/test/unit/test_shapetracker_math.py @@ -1,5 +1,4 @@ import unittest -from typing import List from tinygrad.helpers import prod from tinygrad.shape.view import View from tinygrad.shape.shapetracker import ShapeTracker @@ -7,14 +6,14 @@ from tinygrad import Variable from test.unit.test_shapetracker import shapetracker_getitem class MultiShapeTracker: - def __init__(self, sts:List[ShapeTracker]): self.sts = sts + def __init__(self, sts:list[ShapeTracker]): self.sts = sts @property def shape(self): return self.sts[0].shape def reshape(self, arg): self.sts = [x.reshape(arg) for x in self.sts] def permute(self, arg): self.sts = [x.permute(arg) for x in self.sts] def expand(self, arg): self.sts = [x.expand(arg) for x in self.sts] def shrink(self, arg): self.sts = [x.shrink(arg) for x in self.sts] - def stride(self, arg): self.sts = [x.stride(arg) for x in self.sts] + def flip(self, arg): self.sts = [x.flip(arg) for x in self.sts] def pad(self, arg): self.sts = [x.pad(arg) for x in self.sts] def st_equal(st1:ShapeTracker, st2:ShapeTracker) -> bool: @@ -76,8 +75,8 @@ class TestShapeTrackerAdd(unittest.TestCase): backup = st.sts[0] st.sts.append(ShapeTracker.from_shape(backup.shape)) st.reshape( (45,) ) - st.stride( (4,) ) - st.reshape( (4, 3) ) + st.flip( (True,) ) + st.reshape( (15, 3) ) assert st_equal(backup + st.sts[1], st.sts[0]) def test_off_by_one(self): @@ -156,22 +155,17 @@ class TestShapeTrackerInvert(unittest.TestCase): def test_can_invert_flip(self): a = ShapeTracker.from_shape((20, 10)) - x = a.stride((-1,1)) + x = a.flip((True,False)) ap = x + x.invert(a.shape) assert st_equal(ap, a) def test_can_invert_flip_permute(self): a = ShapeTracker.from_shape((20, 10)) x = a.permute((1,0)) - x = x.stride((-1,1)) + x = x.flip((True,False)) ap = x + x.invert(a.shape) assert st_equal(ap, a) - def test_cant_invert_stride(self): - a = ShapeTracker.from_shape((10, 10)) - x = a.stride((2,2)) - assert x.invert(a.shape) is None - def test_invert_failure(self): a = ShapeTracker.from_shape((2, 5)) x = a.pad( ((2, 0), (0, 0)) ) diff --git a/tinygrad_repo/test/unit/test_simplify_valid_idx.py b/tinygrad_repo/test/unit/test_simplify_valid_idx.py index 5be9c34f0e..c5adc1572a 100644 --- a/tinygrad_repo/test/unit/test_simplify_valid_idx.py +++ b/tinygrad_repo/test/unit/test_simplify_valid_idx.py @@ -1,9 +1,9 @@ import unittest, itertools -from typing import Tuple -from tinygrad.codegen.uopgraph import full_graph_rewrite, is_increasing +from tinygrad.codegen import full_rewrite_to_sink from tinygrad.dtype import dtypes -from tinygrad.ops import UOp, Ops, simplify_valid +from tinygrad.uop.ops import UOp, Ops +from tinygrad.codegen.symbolic import simplify_valid def get_gated_load_uop(valid:UOp, idx:UOp): return UOp(Ops.LOAD, dtypes.float, ( @@ -11,7 +11,7 @@ def get_gated_load_uop(valid:UOp, idx:UOp): UOp.const(dtypes.float, 0.0) )) -def get_load_image_uop(image_shape:Tuple[int, ...], valid:UOp, idx:Tuple[UOp, UOp]): +def get_load_image_uop(image_shape:tuple[int, ...], valid:UOp, idx:tuple[UOp, UOp]): return UOp(Ops.LOAD, dtypes.float.vec(4), ( UOp(Ops.DEFINE_GLOBAL, dtypes.imagef(image_shape), arg=0).index(UOp(Ops.VECTORIZE, dtypes.int.vec(2), idx), valid), UOp(Ops.VECTORIZE, dtypes.float.vec(4), src=(UOp.const(dtypes.float, 0.0),) * 4) @@ -19,7 +19,7 @@ def get_load_image_uop(image_shape:Tuple[int, ...], valid:UOp, idx:Tuple[UOp, UO def Special(expr, nmax): return UOp(Ops.SPECIAL, dtypes.int, (), (expr, nmax)) def Variable(expr, nmin, nmax): return UOp.variable(expr, nmin, nmax) -def Range(n, nmax): return UOp(Ops.RANGE, dtypes.int, arg=n, src=(UOp.const(dtypes.int, 0), UOp.const(dtypes.int, nmax),)) +def Range(n, nmax): return UOp(Ops.RANGE, dtypes.int, arg=n, src=(UOp.const(dtypes.int, nmax),)) class TestHelpers(unittest.TestCase): def test_is_increasing(self): @@ -34,19 +34,19 @@ class TestHelpers(unittest.TestCase): f2 = (idx2*2)+ridx1+((idx1+((ridx2+7)//8)+31)//32)+(-2) f3 = (idx2*2)+ridx1+(-1) - self.assertFalse(is_increasing(f0)) - self.assertTrue(is_increasing(f1)) - self.assertTrue(is_increasing(f2)) - self.assertTrue(is_increasing(f3)) + self.assertFalse(f0.is_increasing()) + self.assertTrue(f1.is_increasing()) + self.assertTrue(f2.is_increasing()) + self.assertTrue(f3.is_increasing()) - rng = UOp(Ops.RANGE, dtypes.int, arg=(2, True), src=(UOp(Ops.CONST, dtypes.int, arg=0, src=()), UOp(Ops.CONST, dtypes.int, arg=5, src=()),)) - self.assertTrue(is_increasing(rng)) - self.assertTrue(is_increasing(rng+2)) + rng = UOp(Ops.RANGE, dtypes.int, arg=(2, True), src=(UOp(Ops.CONST, dtypes.int, arg=5, src=()),)) + self.assertTrue(rng.is_increasing()) + self.assertTrue((rng+2).is_increasing()) class TestValidIdxSimplification(unittest.TestCase): def check(self, load, sidx, svalid): - load = full_graph_rewrite(load.sink()).src[0] - idx, valid = load.src[0].src[1], load.src[2] + load = full_rewrite_to_sink(load.sink()).src[0] + idx, valid = load.src[0].src[1], load.src[0].src[2] self.assertEqual(idx.render(simplify=False), sidx) self.assertEqual(valid.render(simplify=False), svalid) @@ -124,16 +124,85 @@ class TestValidIdxSimplification(unittest.TestCase): "(((ridx0*2)+(ridx3*-1))+1)", "(ridx2<1)") + def test_load_in_valid(self): + # from FUSE_ARANGE=1 python test/test_ops.py TestOps.test_scatter_add + # can lead to OOB + ridx2 = Range(2, 4) + lidx0 = Special("lidx0", 3) + gidx0 = Special("gidx0", 2) + idx=(((lidx0+(gidx0*3))+(ridx2*5))+40) + valid = (lidx0+(gidx0*3)) < 5 + val7 = get_gated_load_uop(valid, idx) + valid2 = valid & val7.cast(dtypes.bool).logical_not() + self.assertIsNone(simplify_valid(valid2)) + + def test_valid_becomes_const1(self): + # from DSP mobilenetv2 + ridx0 = Range(0, 30) + ridx1 = Range(1, 7) + ridx2 = Range(2, 2) + alu11 = (ridx1+ridx2) + alu15 = ((alu11+1)//7) + idx = (alu15*-31)+(((((alu11+218)//224)+ridx0)%30)*1568) + valid = (ridx2<1)&(ridx1<6) + load = get_gated_load_uop(valid, idx) + self.check(load, + "(ridx0*1568)", + "((ridx2<1)&(ridx1<6))") + + def test_valid_becomes_const1_z3(self): + from z3 import Ints, Solver, And, If, Not, unsat + ridx0, ridx1, ridx2, alu11, alu15 = Ints('ridx0 ridx1 ridx2 alu11 alu15') + alu11 = (ridx1+ridx2) + alu15 = ((alu11+1)/7) + idx = (alu15*-31)+(((((alu11+218)/224)+ridx0)%30)*1568) + valid = (ridx2<1)&(ridx1<6) + load = If(valid, idx, 0) + + # correct simplification + s = Solver() + s.add(And(0<=ridx0, ridx0<30, 0<=ridx1, ridx1<7, 0<=ridx2, ridx2<2)) + simplifed_idx = (ridx0*1568) + simplifed_load = If(valid, simplifed_idx, 0) + s.add(Not(load == simplifed_load)) # Check if they are NOT equivalent + assert s.check() == unsat, f"The expressions are not equivalent. {s.model()=}" + + # new solver for a wrong simplified expression + s = Solver() + s.add(And(0<=ridx0, ridx0<30, 0<=ridx1, ridx1<7, 0<=ridx2, ridx2<2)) + wrong_simplifed_idx = (ridx0*1567)+ridx1 + wrong_simplifed_load = If(valid, wrong_simplifed_idx, 0) + s.add(Not(load == wrong_simplifed_load)) # Check if they are NOT equivalent + assert s.check() != unsat, "The expressions are equivalent??" + print("The expressions are not equivalent.") + print(s.model()) + + @unittest.expectedFailure # TODO: improve uop_given_valid + def test_valid_becomes_const2(self): + ridx0 = Range(0, 4) + ridx1 = Range(1, 4) + ridx2 = Range(2, 4) + ridx3 = Range(3, 4) + idx= ((ridx0+ridx1+ridx2+ridx3+28)//30) + valid = ((ridx0+ridx1)<1).ne(True) & ((ridx2+ridx3)<1).ne(True) + load = get_gated_load_uop(valid, idx) + self.check(load, + "1", + "((((ridx0+ridx1)<1)!=True)&(((ridx2+ridx3)<1)!=True))") + class TestImageSimplification(unittest.TestCase): def check(self, load, svalid, sidx0, sidx1): - load = full_graph_rewrite(load.sink()).src[0] + load = full_rewrite_to_sink(load.sink()).src[0] idx = load.src[0].src[1] self.assertEqual(idx.op, Ops.VECTORIZE) self.assertEqual(len(idx.src), 2) idx0, idx1 = idx.src[0], idx.src[1] self.assertEqual(idx0.render(simplify=False), sidx0) self.assertEqual(idx1.render(simplify=False), sidx1) - if svalid is not None: self.assertEqual(load.src[2].render(simplify=False), svalid) + if svalid is not None: + self.assertEqual(load.src[0].src[2].render(simplify=False), svalid) + else: + self.assertEqual(len(load.src[0].src), 2, "svalid is None but load still has a valid") def test_idx_gt_c(self): # (idx1 < c+1).ne(True) ? (..., idx1-1+c) : 0 can drop the valid @@ -153,7 +222,7 @@ class TestImageSimplification(unittest.TestCase): valid = (gidx0<1).ne(True) & (gidx1<1).ne(True) load = get_load_image_uop(shape, valid, (gidx0, gidx1-1)) - self.check(load, None, "gidx0", "(gidx1+-1)") + self.check(load, "((gidx0<1)!=True)", "gidx0", "(gidx1+-1)") def test_idx_lt_bound(self): # (idx1 < image_bound) ? (..., idx1) : 0 can drop the valid @@ -192,7 +261,7 @@ class TestImageSimplification(unittest.TestCase): # empty -> invalid load = get_load_image_uop(shape, (gidx0<8) & (gidx0<8).ne(True), idx) - load = full_graph_rewrite(load.sink()).src[0] + load = full_rewrite_to_sink(load.sink()).src[0] self.assertEqual(load.op, Ops.VECTORIZE) self.assertEqual(load.dtype.count, 4) @@ -324,5 +393,19 @@ class TestImageSimplification(unittest.TestCase): load = get_load_image_uop(shape, valid, idx) self.check(load, "(((idx0+(idx1*64))%192)<160)", "((idx0+((idx1//3)*16))+128)", "(((idx0+(idx1*64))%192)//16)") + def test_simplify6(self): + # from openpilot + # the valid implies the numerator of the div/mod is positive and can be simplified with floordiv rules + idx1 = Special("idx1", 16) + idx2 = Special("idx2", 64) + ridx3 = Range(3, 3) + ridx4 = Range(4, 3) + ridx5 = Range(5, 3) + alu0 = ((idx2*1536)+(ridx4*768)+ridx3+(idx1*24)+(ridx5*3)+-771)%768 + alu1 = ((idx2*1536)+(ridx4*768)+ridx3+(idx1*24)+(ridx5*3)+-771)//768 + valid = (((idx2+ridx4)<1)!=1)&(((idx1+ridx5)<1)!=1) + load = get_load_image_uop((128, 768, 4), valid, (alu0, alu1)) + self.check(load, None, "((((idx1*24)+ridx3)+(ridx5*3))+-3)", "(((idx2*2)+ridx4)+-1)") + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_tensor_uop_representation.py b/tinygrad_repo/test/unit/test_tensor_uop_representation.py index f4011fd2d2..9156d2b6fb 100644 --- a/tinygrad_repo/test/unit/test_tensor_uop_representation.py +++ b/tinygrad_repo/test/unit/test_tensor_uop_representation.py @@ -1,16 +1,55 @@ import unittest from tinygrad import Tensor -from tinygrad.ops import UPat, Ops +from tinygrad.uop.ops import UPat, Ops, UOp -realized_pattern = UPat(Ops.VIEW, src=(UPat(Ops.BUFFER),)) -const_pattern = UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat(Ops.CONST))) -def is_pattern(ten:Tensor, pat:UPat): assert pat.match(ten.lazydata, {}) +# NOTE: unlike before base for a realized tensor is always a BUFFER +realized_pattern = UPat(Ops.BUFFER) +# after realization, base tensor uops become RESHAPE(BUFFER) +buffer_view_pattern = UPat(Ops.RESHAPE, src=(UPat(Ops.BUFFER),)) +const_pattern = UPat(Ops.CONST, src=(UPat(Ops.VIEW, src=(UPat(Ops.DEVICE),),))) +def is_pattern_uop(u:UOp, pat:UPat): assert pat.match(u, {}), f"{u}\nis not\n{pat}" +def is_pattern(ten:Tensor, pat:UPat): is_pattern_uop(ten.lazydata, pat) + +class TestTensorMutates(unittest.TestCase): + def test_mutate_add(self): + a = Tensor([1,2,3]) + b = Tensor([4,5,6]) + ret = a+b + pa = a.lazydata + pb = b.lazydata + pr = ret.lazydata + ret.schedule() + self.assertIsNot(pa, a.lazydata) + self.assertIsNot(pb, b.lazydata) + self.assertIsNot(pr, ret.lazydata) + for t in [a,b,ret]: is_pattern_uop(t.lazydata.base, realized_pattern) + + def test_reshape_is_same_parent(self): + a = Tensor([1,2,3]) + b = Tensor([4,5,6]) + c = a+b + d = (a+b).reshape(3,1) + d.realize() + is_pattern_uop(d.lazydata.base, realized_pattern) + is_pattern_uop(c.lazydata.base, realized_pattern) + # NOTE: we keep movement ops on top of the buffer view + is_pattern_uop(c.lazydata, UPat(Ops.BUFFER)) + is_pattern_uop(d.lazydata, UPat(Ops.VIEW, src=(realized_pattern,))) + + def test_reshape_is_same_child(self): + a = Tensor([1,2,3]) + b = Tensor([4,5,6]) + c = a+b + d = (a+b).reshape(3,1) + c.realize() + is_pattern_uop(c.lazydata.base, realized_pattern) + is_pattern_uop(d.lazydata.base, realized_pattern) class TestTensorUopRepresentation(unittest.TestCase): def test_realized(self): a = Tensor([1.,2,3]).realize() print(a.lazydata) - is_pattern(a, realized_pattern) + is_pattern_uop(a.lazydata.base, realized_pattern) def test_add_realized(self): a = Tensor([1.,2,3]).realize() @@ -22,7 +61,8 @@ class TestTensorUopRepresentation(unittest.TestCase): def test_const_pattern(self): a = Tensor(1) print(a.lazydata) - is_pattern(a, const_pattern) + is_pattern(a, const_pattern) # const in tensor has a DEVICE and VIEW src + is_pattern(a, UPat.cvar("x")) # even cvar works! def test_consts_do_not_realize(self): a = Tensor(1) @@ -34,9 +74,9 @@ class TestTensorUopRepresentation(unittest.TestCase): def test_viewed_consts_do_not_realize(self): a = Tensor.ones(10, 10) print(a.lazydata) - pre_realize = a.lazydata a.realize() - assert a.lazydata is pre_realize + is_pattern(a, const_pattern) + self.assertEqual(a.lazydata.shape, (10, 10)) # currently, CONSTs have a "fake" BUFFER. this should be fixed # current: @@ -51,11 +91,10 @@ class TestTensorUopRepresentation(unittest.TestCase): # UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(), strides=(), offset=0, mask=None, contiguous=True),)), src=( # UOp(Ops.CONST, dtypes.float, arg=1.0, src=( # UOp(Ops.DEVICE, dtypes.void, arg="METAL", src=()),)),)),)) - @unittest.expectedFailure def test_consts_dont_have_buffers(self): a = Tensor.ones(10, 10) print(a.lazydata) - buffers_in_parents = [x.op for x in a.lazydata.toposort if x.op is Ops.BUFFER] + buffers_in_parents = [x.op for x in a.lazydata.toposort() if x.op is Ops.BUFFER] self.assertEqual(len(buffers_in_parents), 0) # currently, COPY has an extra BUFFER on the output @@ -69,13 +108,20 @@ class TestTensorUopRepresentation(unittest.TestCase): # UOp(Ops.COPY, dtypes.float, arg=('TEST', False), src=( # UOp(Ops.VIEW, dtypes.float, arg=ShapeTracker(views=(View(shape=(3,), strides=(1,), offset=0, mask=None, contiguous=True),)), src=( # UOp(Ops.BUFFER, dtypes.float, arg=(1, 'METAL', 3), src=()),)) - @unittest.expectedFailure + # update: now the arg is just a single bool, the first source is a device. def test_copyin(self): a = Tensor([1.,2,3]).realize() c = a.to("TEST") # NOTE: this isn't checked print(c.lazydata) - # NOTE: this is wrong, COPY has an extra buffer for some reason - is_pattern(c, UPat(Ops.COPY, src=(realized_pattern,))) + is_pattern(c, UPat(Ops.COPY, src=(realized_pattern, UPat(Ops.DEVICE)))) + + def test_empty_buf(self): + a = Tensor.empty(3, 3) + is_pattern(a, UPat(Ops.RESHAPE, src=(UPat(Ops.BUFFER),))) + vi = UOp.variable("i", 1, 3).bind(1) + a = Tensor.empty(3, vi) + is_pattern(a, UPat(Ops.RESHAPE, src=(UPat(Ops.BUFFER),))) + self.assertEqual(a.lazydata.base.buffer.size, 9) if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_tqdm.py b/tinygrad_repo/test/unit/test_tqdm.py index ee622d5f4c..9d7b3756bf 100644 --- a/tinygrad_repo/test/unit/test_tqdm.py +++ b/tinygrad_repo/test/unit/test_tqdm.py @@ -92,6 +92,41 @@ class TestProgressBar(unittest.TestCase): self._compare_bars(tinytqdm_output, tqdm_output) if n > 3: break + @patch('sys.stderr', new_callable=StringIO) + @patch('shutil.get_terminal_size') + def test_unit_scale_exact(self, mock_terminal_size, mock_stderr): + unit_scale = True + ncols = 80 + mock_terminal_size.return_value = namedtuple(field_names='columns', typename='terminal_size')(ncols) + mock_stderr.truncate(0) + + total = 10 + with patch('time.perf_counter', side_effect=[0]+list(range(100))): # one more 0 for the init call + # compare bars at each iteration (only when tinytqdm bar has been updated) + for n in tinytqdm(range(total), desc="Test", total=total, unit_scale=unit_scale, rate=1e9): + tinytqdm_output = mock_stderr.getvalue().split("\r")[-1].rstrip() + elapsed = n + tqdm_output = tqdm.format_meter(n=n, total=total, elapsed=elapsed, ncols=ncols, prefix="Test", unit_scale=unit_scale) + self._compare_bars(tinytqdm_output, tqdm_output) + if n > 5: break + + total = 10 + k=0.001000001 + # regression test for + # E AssertionError: ' 1.00/10.0 1000it/s]' != ' 1.00/10.0 1.00kit/s]' + # E - 1.00/10.0 1000it/s] + # E ? ^ + # E + 1.00/10.0 1.00kit/s] + # E ? + ^ + with patch('time.perf_counter', side_effect=[0, *[i*k for i in range(100)]]): # one more 0 for the init call + # compare bars at each iteration (only when tinytqdm bar has been updated) + for n in tinytqdm(range(total), desc="Test", total=total, unit_scale=unit_scale, rate=1e9): + tinytqdm_output = mock_stderr.getvalue().split("\r")[-1].rstrip() + elapsed = n*k + tqdm_output = tqdm.format_meter(n=n, total=total, elapsed=elapsed, ncols=ncols, prefix="Test", unit_scale=unit_scale) + self._compare_bars(tinytqdm_output, tqdm_output) + if n > 5: break + @patch('sys.stderr', new_callable=StringIO) @patch('shutil.get_terminal_size') def test_set_description(self, mock_terminal_size, mock_stderr): diff --git a/tinygrad_repo/test/unit/test_transcendental_helpers.py b/tinygrad_repo/test/unit/test_transcendental_helpers.py index 3a811a0fc0..16a97ad48b 100644 --- a/tinygrad_repo/test/unit/test_transcendental_helpers.py +++ b/tinygrad_repo/test/unit/test_transcendental_helpers.py @@ -1,21 +1,29 @@ import unittest, math import numpy as np from tinygrad import dtypes -from tinygrad.ops import UOp -from tinygrad.codegen.transcendental import payne_hanek_reduction, cody_waite_reduction, frexp, rintk, pow2if +from tinygrad.uop.ops import UOp, Ops +from tinygrad.codegen.transcendental import TRANSCENDENTAL_SUPPORTED_DTYPES, payne_hanek_reduction, cody_waite_reduction +from tinygrad.codegen.transcendental import frexp, rintk, xpow, xexp2, xlog2, trig_poly, pow2if from test.helpers import eval_uop class TestTranscendentalFunctions(unittest.TestCase): def test_payne_hanek_reduction(self): - r, q = (eval_uop(u) for u in payne_hanek_reduction(UOp.const(dtypes.float64, 12 * math.pi + 0.1))) + # TODO: Test constant input when constant folding is fixed (or maybe test both variants) + # Load input value from a buffer to prevent constant folding + input_buf = UOp(Ops.DEFINE_GLOBAL, dtypes.double.ptr(), arg=1, src=()) + loaded_value = UOp.load(input_buf.index(UOp.const(dtypes.int, 0)), dtype=dtypes.double) + def eval_payne_hanek_reduction(v:float) -> tuple[float, int]: + return tuple(eval_uop(u, [(dtypes.float64, [v])]) for u in payne_hanek_reduction(loaded_value)) + + r, q = eval_payne_hanek_reduction(12 * math.pi + 0.1) np.testing.assert_allclose(r, 0.1 - math.pi / 2) np.testing.assert_equal(q, 1) - r, q = (eval_uop(u) for u in payne_hanek_reduction(UOp.const(dtypes.float64, 12 * math.pi))) + r, q = eval_payne_hanek_reduction(12 * math.pi) np.testing.assert_allclose(r, 0.0, atol=1e-8) np.testing.assert_equal(q, 4) - r, q = (eval_uop(u) for u in payne_hanek_reduction(UOp.const(dtypes.float64, 12 * math.pi - 0.1))) + r, q = eval_payne_hanek_reduction(12 * math.pi - 0.1) np.testing.assert_allclose(r, -0.1) np.testing.assert_equal(q, 4) @@ -63,5 +71,39 @@ class TestTranscendentalFunctions(unittest.TestCase): np.testing.assert_allclose(eval_uop(pow2if(UOp.const(dtypes.int, -10), dtypes.float)), 2**-10) np.testing.assert_allclose(eval_uop(pow2if(UOp.const(dtypes.int, -63), dtypes.float)), 2**-63) +class TestTranscendentalVectorizedFunctions(unittest.TestCase): + # given a scalar and vectorized input, check that the fxn outputs have the same + # scalar_dtypes, args, ops, and vcount (only for vectorized input) + + def _check_uop_vcount(self, u:tuple|UOp, vcount:int): + # check all UOps in u are vectorized with vcount + if isinstance(u, UOp): + assert u.dtype.vcount == vcount, f'expected {vcount=} but got {u.dtype.vcount=} for UOp\n{u=}' + [self._check_uop_vcount(x, vcount) for x in (u if isinstance(u, tuple) else u.src)] + + def _check_uops_match(self, u1:tuple|UOp, u2:tuple|UOp): + # check all UOps in u1, u2 have the same scalar_dtype, args, ops + if isinstance(u1, UOp) and isinstance(u2, UOp): + assert u1.dtype.scalar() == u2.dtype.scalar(), f'expected {u1.dtype.scalar()=} but got {u2.dtype.scalar()=} for UOps\n{u1=}\n{u2}' + assert u1.arg == u2.arg or (math.isnan(u1.arg) and math.isnan(u2.arg)), f'expected {u1.arg=} but got {u2.arg=} for UOps\n{u1=}\n{u2}' + assert u1.op == u2.op, f'expected {u1.op=} but got {u2.op=} for UOps\n{u1=}\n{u2}' + [self._check_uops_match(x1, x2) for x1, x2 in zip((u1 if isinstance(u1, tuple) else u1.src), (u2 if isinstance(u2, tuple) else u2.src))] + + def _test_vectorized(self, fxn, scalar_dtypes=TRANSCENDENTAL_SUPPORTED_DTYPES, vals=[-2,1.3,194], vcounts=[1,4,19]): + for scalar_dtype in scalar_dtypes: + for val in vals: + for vcount in vcounts: + in_scalar, in_vec = UOp.const(scalar_dtype, val), UOp.const(scalar_dtype.vec(vcount), val) + out_scalar, out_vec = fxn(in_scalar), fxn(in_vec) + self._check_uops_match(out_scalar, out_vec) + self._check_uop_vcount(out_vec, vcount) + + def test_xpow(self): return self._test_vectorized(lambda x: xpow(x, x)) + def test_xexp2(self): return self._test_vectorized(xexp2) + def test_xlog2(self): return self._test_vectorized(xlog2) + def test_payne_hanek_reduction(self): return self._test_vectorized(payne_hanek_reduction) + def test_cody_waite_reduction(self): return self._test_vectorized(cody_waite_reduction) + def test_trig_poly(self): return self._test_vectorized(lambda x: trig_poly(x, [0.0], [1.0])) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_uop_resolve.py b/tinygrad_repo/test/unit/test_uop_resolve.py index a4bb4889d4..83db03317b 100644 --- a/tinygrad_repo/test/unit/test_uop_resolve.py +++ b/tinygrad_repo/test/unit/test_uop_resolve.py @@ -1,6 +1,6 @@ import unittest from tinygrad.dtype import dtypes -from tinygrad.ops import UOp, resolve +from tinygrad.uop.ops import UOp, resolve class TestUOpResolve(unittest.TestCase): def test_simple_int(self): diff --git a/tinygrad_repo/test/unit/test_uop_symbolic.py b/tinygrad_repo/test/unit/test_uop_symbolic.py index 0f182a5665..f8482f2468 100644 --- a/tinygrad_repo/test/unit/test_uop_symbolic.py +++ b/tinygrad_repo/test/unit/test_uop_symbolic.py @@ -1,18 +1,16 @@ #!/usr/bin/env python -import unittest, pickle -from typing import Tuple +import unittest, pickle, functools from tinygrad.dtype import dtypes, ConstType -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.codegen.uopgraph import full_graph_rewrite, sym -from tinygrad.ops import UOp, Ops, graph_rewrite, sym_infer +from tinygrad.codegen import full_rewrite +from tinygrad.codegen.devectorizer import sym +from tinygrad.uop.ops import UOp, Ops, graph_rewrite, sym_infer from tinygrad import Variable -import functools -def render(self) -> Tuple[str, ConstType, ConstType]: +def render(self) -> tuple[str, ConstType, ConstType]: # NOTE: we need STORE so the ALU op has children glbl = UOp(Ops.DEFINE_GLOBAL, dtypes.int.ptr(), arg=0) - uops = linearize_uop(full_graph_rewrite(UOp(Ops.STORE, dtypes.void, (glbl.index(UOp.const(dtypes.int, 0)), self)).sink())) + uops = full_rewrite(UOp(Ops.STORE, dtypes.void, (glbl.index(UOp.const(dtypes.int, 0)), self)).sink()) rewritten_uop = [uop for uop in uops if uop.op is Ops.STORE][0].src[-1] return rewritten_uop.render(simplify=False), rewritten_uop.vmin, rewritten_uop.vmax @@ -85,17 +83,22 @@ class TestSymbolic(unittest.TestCase): assert idx1*4 is not idx1+4 assert idx1*4 is not idx2*4 assert idx1+idx2 is idx1+idx2 - # assert idx1+idx2 is idx2+idx1 + assert idx1+idx2 is not idx2+idx1 assert idx1+idx2 is not idx2 - # assert idx1*idx2 is idx2*idx1 + assert idx1*idx2 is not idx2*idx1 def test_factorize(self): a = Variable("a", 0, 8) + b = Variable("b", 0, 8) self.helper_test_variable(a*2+a*3, 0, 8*5, "(a*5)") + self.helper_test_variable(b+a*2+a*3, 0, 8*6, "(b+(a*5))") def test_factorize_no_mul(self): a = Variable("a", 0, 8) + b = Variable("b", 0, 8) self.helper_test_variable(a+a*3, 0, 8*4, "(a*4)") + self.helper_test_variable((a+b)+a*3, 0, 8*5, "(b+(a*4))") + self.helper_test_variable((a*3+b)+b*3, 0, 8*7, "((a*3)+(b*4))") def test_neg(self): self.helper_test_variable(-Variable("a", 0, 8), -8, 0, "(a*-1)") @@ -106,9 +109,14 @@ class TestSymbolic(unittest.TestCase): def test_sub_1(self): self.helper_test_variable(Variable("a", 0, 8)-1, -1, 7, "(a+-1)") + def test_const_var(self): + self.helper_test_variable(Variable("fake", 1, 1), 1, 1, "1") + def test_add_self(self): a = Variable("a", 0, 8) + b = Variable("b", 0, 8) self.helper_test_variable(a+a, 0, 16, "(a*2)") + self.helper_test_variable((a+b)+b, 0, 24, "(a+(b*2))") def test_sub_self(self): a = Variable("a", 0, 8) @@ -121,9 +129,9 @@ class TestSymbolic(unittest.TestCase): def test_mul_1(self): self.helper_test_variable(Variable("a", 0, 8)*1, 0, 8, "a") - @unittest.expectedFailure def test_mul_neg_1(self): - self.helper_test_variable((Variable("a", 0, 2)*-1)//3, -1, 0, "((((a*-1)+3)//3)+-1)") + self.helper_test_variable((Variable("a", 0, 2)*-1)//3, 0, 0, "0") + self.helper_test_variable((Variable("a", 2, 7)*-1)//3, -2, 0, "((a//3)*-1)") def test_mul_2(self): self.helper_test_variable(Variable("a", 0, 8)*2, 0, 16, "(a*2)") @@ -134,6 +142,9 @@ class TestSymbolic(unittest.TestCase): def test_mod_1(self): self.helper_test_variable(Variable("a", 0, 8)%1, 0, 0, "0") + def test_max_folds(self): + self.helper_test_variable(Variable("a", 0, 20).maximum(10).maximum(11), 11, 20, "max(a, 11)") + def test_add_min_max(self): self.helper_test_variable(Variable("a", 0, 8) * 2 + 12, 12, 16+12, "((a*2)+12)") @@ -145,8 +156,8 @@ class TestSymbolic(unittest.TestCase): self.helper_test_variable(Variable("a", 0, 6) // 2, 0, 3, "(a//2)") def test_div_neg_min_max(self): - self.helper_test_variable(Variable("a", 1, 7) // -2, -3, 0, "(a//-2)") - self.helper_test_variable(Variable("a", 0, 6) // -2, -3, 0, "(a//-2)") + self.helper_test_variable(Variable("a", 1, 7) // -2, -3, 0, "((a//2)*-1)") + self.helper_test_variable(Variable("a", 0, 6) // -2, -3, 0, "((a//2)*-1)") def test_sum_div_remove(self): self.helper_test_variable(usum([Variable("a", 0, 7), Variable("b", 0, 3)]) // 20, 0, 0, "0") @@ -188,7 +199,8 @@ class TestSymbolic(unittest.TestCase): def test_mod_congruence_multiple_vars(self): self.helper_test_variable((9+9*Variable("x",0,3)+9*Variable("y",0,3))%10, 3, 9, "(((x*-1)+(y*-1))+9)") - self.helper_test_variable((7+9*Variable("x",0,2)+9*Variable("y",0,2)+Variable("z",0,2))%10, 3, 9, "(((z+(x*-1))+(y*-1))+7)") + self.helper_test_variable((7+9*Variable("x",0,2)+9*Variable("y",0,2)+Variable("z",0,2))%10, 3, 9, + ("(((z+(x*-1))+(y*-1))+7)", "(((y*-1)+(z+(x*-1)))+7)")) self.helper_test_variable((10+12*Variable("x",0,2)+Variable("y", 0, 4)%3)%13, 8, 12, "(((x*-1)+(y%3))+10)") def test_div_congruence(self): @@ -242,6 +254,12 @@ class TestSymbolic(unittest.TestCase): def test_div_const_div(self): a = Variable("a", 0, 124) self.helper_test_variable((a//2+1)//2, 0, 31, "((a+2)//4)") + self.helper_test_variable(((-a)//2-1)//2, -31, 0, "(((a+2)//4)*-1)") + self.helper_test_variable(((-a)//2+10)//2, -26, 5, "((((a//2)*-1)+10)//2)") + + def test_div_const_div_wrong_sign(self): + a = Variable("a", 0, 124) + self.helper_test_variable(((a-10)//2+10)//2, 2, 33, "((((a+-10)//2)+10)//2)") def test_distribute_mul(self): self.helper_test_variable(usum([Variable("a", 0, 3), Variable("b", 0, 5)])*3, 0, 24, "((a*3)+(b*3))") @@ -257,12 +275,11 @@ class TestSymbolic(unittest.TestCase): 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", -20, 20)%10, -9, 9, "(a%10)") + self.helper_test_variable(Variable("a", -20, 0)%10, -9, 0, "(((a*-1)%10)*-1)") + self.helper_test_variable(Variable("a", -20, 1)%10, -9, 9, "(a%10)") # TODO: tighter max 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)") + self.helper_test_variable(Variable("a", -1, 20)%10, -9, 9, "(a%10)") # TODO: tighter min def test_ge_remove(self): self.helper_test_variable(Variable("a", 0, 6) >= 25, 0, 0, "False") @@ -280,11 +297,11 @@ class TestSymbolic(unittest.TestCase): def test_lt_sum_factor_rhs_partial(self): self.helper_test_variable((Variable("a", 0, 6)*6 + Variable("b", 0, 6)*4 + Variable("c", 0, 6)*8) < 4, 0, 1, - "((((a*3)+(b*2))+(c*4))<2)") + ("((((a*3)+(b*2))+(c*4))<2)", "(((b*2)+((a*3)+(c*4)))<2)")) def test_lt_sum_factor_rhs_all(self): self.helper_test_variable((Variable("a", 0, 6)*6 + Variable("b", 0, 6)*4 + Variable("c", 0, 6)*8) < 2, 0, 1, - "((((a*3)+(b*2))+(c*4))<1)") + ("((((a*3)+(b*2))+(c*4))<1)", "(((b*2)+((a*3)+(c*4)))<1)")) def test_and_fold(self): self.helper_test_variable(uand([uconst(0), Variable("a", 0, 1)]), 0, 0, "0") @@ -293,8 +310,8 @@ class TestSymbolic(unittest.TestCase): self.helper_test_variable(uand([uconst(1), Variable("a", 0, 1)]), 0, 1, "a") def test_mod_factor_negative(self): - self.helper_test_variable(usum([uconst(-29), Variable("a", 0, 10), Variable("b", 0, 10)*28]) % 28, 0, 27, "((a+27)%28)") - self.helper_test_variable(usum([uconst(-29), Variable("a", 0, 100), Variable("b", 0, 10)*28]) % 28, 0, 27, "((a+27)%28)") + self.helper_test_variable(usum([uconst(-29), Variable("a", 0, 10), Variable("b", 0, 10)*28]) % 28, -27, 27, "(((a+(b*28))+-29)%28)") + self.helper_test_variable(usum([uconst(-29), Variable("a", 0, 100), Variable("b", 0, 10)*28]) % 28, -27, 27, "(((a+(b*28))+-29)%28)") def test_sum_combine_num(self): self.helper_test_variable(usum([uconst(29), Variable("a", 0, 10), uconst(-23)]), 6, 16, "(a+6)") @@ -313,8 +330,8 @@ class TestSymbolic(unittest.TestCase): def test_add_div(self): # careful about the lower bounds and upper bounds - self.helper_test_variable((Variable("a", 0, 5)-2)//4, -1, 0, "(((a+2)//4)+-1)") - self.helper_test_variable((Variable("a", 0, 5)-1)//4, -1, 1, "(((a+3)//4)+-1)") + self.helper_test_variable((Variable("a", 0, 5)-2)//4, 0, 0, "0") + self.helper_test_variable((Variable("a", 0, 5)-1)//4, 0, 1, "((a+-1)//4)") self.helper_test_variable((Variable("a", 0, 5))//4, 0, 1, "(a//4)") self.helper_test_variable((Variable("a", 0, 5)+1)//4, 0, 1, "((a+1)//4)") self.helper_test_variable((Variable("a", 0, 5)+2)//4, 0, 1, "((a+2)//4)") @@ -322,27 +339,48 @@ class TestSymbolic(unittest.TestCase): self.helper_test_variable((Variable("a", 0, 5)+4)//4, 1, 2, "((a//4)+1)") self.helper_test_variable((Variable("a", 0, 5)+5)//4, 1, 2, "(((a+1)//4)+1)") + def test_div_neg_rem(self): + self.helper_test_variable((-Variable("a", 0, 255)+256)//2, 0, 128, "((((a+1)//2)*-1)+128)") + 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_mul_neg(self): + self.helper_test_variable((Variable("a", 0, 10)*-8+16)//4, -16, 4, "((a*-2)+4)") + def test_mul_div_factor_div(self): self.helper_test_variable((Variable("a", 0, 10)*4)//8, 0, 5, "(a//2)") + def test_mul_div_factor_div_neg(self): + self.helper_test_variable((Variable("a", 0, 10)*-4+4)//8, -4, 0, "(((a*-1)+1)//2)") + + def test_mod_gcd_factor_neg(self): + self.helper_test_variable((Variable("a", 0, 10)*-4+4)%8, -4, 4, "((((a*-1)+1)%2)*4)") + + def test_mod_gcd_fold_neg(self): + self.helper_test_variable((Variable("a", 0, 10)*-8+20)%4, 0, 0, "0") + def test_sum_div_partial_remove(self): self.helper_test_variable(usum([Variable("idx0", 0, 127)*4, Variable("idx2", 0, 3)])//4, 0, 127, "idx0") - @unittest.expectedFailure + def test_cdiv_const_evaluation(self): + self.helper_test_variable((Variable("a", 0, 2)-12)//8, -1, -1, "-1") + self.helper_test_variable((-Variable("a", 0, 2))//7, 0, 0, "0") + + def test_cmod_const_evaluation(self): + self.helper_test_variable((Variable("a", 1, 1)*-3)%8, -3, -3, "-3") + self.helper_test_variable((-Variable("a", 10, 10))%7, -3, -3, "-3") + def test_div_numerator_negative(self): - self.helper_test_variable((Variable("idx", 0, 9)*-10)//11, -9, 0, "((((idx*-10)+99)//11)+-9)") + self.helper_test_variable((Variable("idx", 0, 9)*-10)//11, -8, 0, "(((idx*10)//11)*-1)") def test_div_into_mod(self): self.helper_test_variable((Variable("idx", 0, 16)*4)%8//4, 0, 1, "(idx%2)") - # TODO: simplify the expression def test_div_neg_cancel(self): - self.helper_test_variable((-Variable("idx", 0, 100)+199)//-4 + 50, 1, 26, "((((idx*-1)+199)//-4)+50)") - self.helper_test_variable((-Variable("idx", 0, 100)+200)//-4 + 50, 0, 25, "((((idx*-1)+200)//-4)+50)") - self.helper_test_variable((-Variable("idx", 0, 100)+201)//-4 + 50, 0, 25, "((((idx*-1)+201)//-4)+50)") + self.helper_test_variable((-Variable("idx", 0, 100)+199)//-4 + 50, 1, 26, "((idx//4)+1)") + self.helper_test_variable((-Variable("idx", 0, 100)+200)//-4 + 50, 0, 25, "((idx+3)//4)") + self.helper_test_variable((-Variable("idx", 0, 100)+201)//-4 + 50, 0, 25, "((idx+2)//4)") def test_sum_div_big_const(self): gidx0 = Variable("gidx0", 0, 24) @@ -360,6 +398,7 @@ class TestSymbolic(unittest.TestCase): alu0 = gidx2*640+gidx1*160+(gidx0//5)*2+lidx0*320+lidx1*10 self.helper_test_variable((alu0+lidx2*2+1)//20, 0, 8192, ("((((((gidx0//5)+lidx2)//5)+lidx1)//2)+(((gidx2*32)+(gidx1*8))+(lidx0*16)))", + "(((lidx1+((lidx2+(gidx0//5))//5))//2)+((gidx2*32)+((gidx1*8)+(lidx0*16))))", "((((gidx1*8)+(gidx2*32))+(lidx0*16))+((lidx1+((lidx2+(gidx0//5))//5))//2))")) def test_sum_div_complex2(self): @@ -381,7 +420,8 @@ class TestSymbolic(unittest.TestCase): gidx0 = Variable("gidx0", 0, 7) lidx2 = Variable("lidx2", 0, 12) lidx3 = Variable("lidx3", 0, 1) - self.helper_test_variable((gidx0+lidx2+lidx3)*4, 0, 80, "(((gidx0*4)+(lidx2*4))+(lidx3*4))") + self.helper_test_variable((gidx0+lidx2+lidx3)*4, 0, 80, + ("(((gidx0*4)+(lidx2*4))+(lidx3*4))","((lidx3*4)+((gidx0*4)+(lidx2*4)))")) @unittest.expectedFailure def test_variable_divmod(self): @@ -392,16 +432,25 @@ class TestSymbolic(unittest.TestCase): self.helper_test_variable((idx0*v+idx1)//v, 0, 2, "(idx0)") self.helper_test_variable((idx0*v+idx1)%v, 0, start_pos, "idx1") - # TODO: simplify the expression + def test_divmod_variable_denom_fold_to_const(self): + x = Variable("x", 20, 23) + y = Variable("y", 8, 10) + self.helper_test_variable(x//y, 2, 2, "2") + self.helper_test_variable(x%y, 0, 7, "(x+(y*-2))") + # ensure all 4 corners are checked + x = Variable("x", -10, 10) + y = Variable("y", -8, 9) + self.helper_test_variable(x//y, -2147483648, 2147483647, "(x//y)") + self.helper_test_variable(x%y, -2147483648, 2147483647, "(x%y)") + def test_div_neg_all_range(self): gidx = Variable("gidx", 0, 124) lidx = Variable("lidx", 0, 7) - self.helper_test_variable((-gidx*8-lidx+999)//-4 + 250, 1, 250, "(((((gidx*-8)+(lidx*-1))+999)//-4)+250)") - self.helper_test_variable((-gidx*8-lidx+1000)//-4 + 250, 0, 250, "(((((gidx*-8)+(lidx*-1))+1000)//-4)+250)") - self.helper_test_variable((-gidx*8-lidx+1001)//-4 + 250, 0, 250, "(((((gidx*-8)+(lidx*-1))+1001)//-4)+250)") - self.helper_test_variable((-gidx*8-lidx+1002)//-4 + 250, 0, 250, "(((((gidx*-8)+(lidx*-1))+1002)//-4)+250)") + self.helper_test_variable((-gidx*8-lidx+999)//-4 + 250, 1, 250, "(((gidx*2)+(lidx//4))+1)") + self.helper_test_variable((-gidx*8-lidx+1000)//-4 + 250, 0, 250, "((gidx*2)+((lidx+3)//4))") + self.helper_test_variable((-gidx*8-lidx+1001)//-4 + 250, 0, 250, "((gidx*2)+((lidx+2)//4))") + self.helper_test_variable((-gidx*8-lidx+1002)//-4 + 250, 0, 250, "((gidx*2)+((lidx+1)//4))") - # NOTE: tests are not correct in symbolic def test_div_neg_then_neg(self): # taken from arange opts lidx0 = Variable("lidx0", 0, 7) @@ -409,7 +458,7 @@ class TestSymbolic(unittest.TestCase): alu2 = -lidx0-lidx1 self.helper_test_variable((((alu2+14)//(-32))+4), 4, 4, "4") self.helper_test_variable(-(((alu2+14)//(-32))+4), -4, -4, "-4") - self.helper_test_variable((((alu2+134)//(-32))+4), 0, 1, "(((((lidx0*-1)+(lidx1*-1))+134)//-32)+4)") + self.helper_test_variable((((alu2+134)//(-32))+4), 0, 1, "(((lidx0+lidx1)+25)//32)") self.helper_test_variable((((alu2+142)//(-32))+4), 0, 0, "0") self.helper_test_variable((((alu2+150)//(-32))+4), 0, 0, "0") self.helper_test_variable((((alu2+158)//(-32))+4), 0, 0, "0") @@ -438,6 +487,11 @@ class TestSymbolic(unittest.TestCase): unrolled_div = (gidx+2561)//4+(gidx+2562)//4+(gidx+2560)//4+(gidx+2559)//4 self.helper_test_variable(unrolled_div, 2559, 5118, "(gidx+2559)") + def test_arange_unrolled4_mul(self): + gidx = Variable("gidx", 0, 2559) + unrolled_div = 2*((gidx+2561)//4)+2*((gidx+2562)//4)+2*((gidx+2560)//4)+2*((gidx+2559)//4) + self.helper_test_variable(unrolled_div, 5118, 10236, "((gidx*2)+5118)") + def test_arange_unrolled4_small(self): gidx = Variable("gidx", 0, 3) unrolled_div = (gidx)//4+(gidx+2)//4+(gidx+3)//4+(gidx+1)//4 @@ -456,6 +510,11 @@ class TestSymbolic(unittest.TestCase): unrolled_div = (gidx+2559)//2+(gidx+2560)//2+3 self.helper_test_variable(unrolled_div, 2562, 5121, "(gidx+2562)") + def test_arange_unrolled2_neg(self): + ridx = Variable("ridx", 0, 255) + unrolled_div = -((255-ridx)//2) - ((256-ridx)//2) + self.helper_test_variable(unrolled_div, -255, 0, "(ridx+-255)") + def test_gated_load(self): idx = Variable("idx", 0, 24) self.helper_test_variable(idx//4, 0, 6, "(idx//4)") @@ -465,7 +524,7 @@ class TestSymbolic(unittest.TestCase): def test_idiv_lt(self): idx = Variable("idx", 0, 24) self.helper_test_variable((idx//4<3), 0, 1, "(idx<12)") - self.helper_test_variable((idx//-4<-3), 0, 1, "((idx//-4)<-3)") + self.helper_test_variable((idx//-4<-3), 0, 1, "(((idx//4)*-1)<-3)") def test_simplex_lt(self): a = Variable("a", 0, 3) @@ -477,8 +536,8 @@ class TestSymbolic(unittest.TestCase): self.helper_test_variable((a*3+b*4<1).ne(True), 0, 1, "(((a+b)<1)!=True)") self.helper_test_variable((a*(-3)+b*4<1).ne(True), 0, 1, "((((a*-3)+(b*4))<1)!=True)") # negative coeff, should not be simplified self.helper_test_variable((a*3+d*4<1).ne(True), 0, 1, "((((a*3)+(d*4))<1)!=True)") # var can be negative, should not be simplified - self.helper_test_variable((a+b+c*2<1).ne(True), 0, 1, ("((((a+b)+c)<1)!=True)", "(((c+(a+b))<1)!=True)")) - self.helper_test_variable((a+b*2+c*4<1).ne(True), 0, 1, ("((((a+b)+c)<1)!=True)", "(((c+(a+b))<1)!=True)")) + self.helper_test_variable((a+b+c*2<1).ne(True), 0, 1, ("((((a+b)+c)<1)!=True)", "(((c+(a+b))<1)!=True)", '(((b+(a+c))<1)!=True)')) + self.helper_test_variable((a+b*2+c*4<1).ne(True), 0, 1, ("((((a+b)+c)<1)!=True)", "(((c+(a+b))<1)!=True)", '(((b+(a+c))<1)!=True)')) def test_where_removal(self): cond = Variable("a", 0, 3) < 2 @@ -511,6 +570,49 @@ class TestSymbolic(unittest.TestCase): # not combining # TODO: can combine if one is identity element const self.helper_test_variable(aa+ab, 0, 6, "((a if (x<2) else b)+(a if (x<2) else 0))") + def test_negation_in_where(self): + cond = Variable("x", 0, 3) < 2 + a = Variable("a", 0, 3) + b = Variable("b", 0, 3) + w = cond.logical_not().where(a, b) + self.helper_test_variable(w, 0, 3, "(b if (x<2) else a)") + + def test_neg_in_comp(self): + a = Variable("a", 0, 3) + b = Variable("b", 0, 3) + self.helper_test_variable(-a<-b, False, True, "(b 2 + a = Variable("a", 0, 3) + b = Variable("b", 0, 3) + expr = cond1.where(cond2.where(a, b), b) + self.helper_test_variable(expr, 0, 3, "(a if ((s<6)&(2 (a if (s<5) else b) + self.helper_test_variable(expr, 0, 3, "(a if (s<5) else b)") + def test_symbolic_div(self): # from symbolic arange a = Variable("a", 1, 10) @@ -583,6 +685,7 @@ class TestSymInfer(unittest.TestCase): c = Variable("c", 0, 10) var_vals = {a: 2, b: 3, c: 4} assert sym_infer(5, var_vals) == 5 + assert sym_infer(4.2, var_vals) == 4.2 assert sym_infer(a, var_vals) == 2 assert sym_infer(b, var_vals) == 3 assert sym_infer(a+b, var_vals) == 5 @@ -590,6 +693,12 @@ class TestSymInfer(unittest.TestCase): 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 + def test_sym_infer_cdiv_cmod(self): + a = Variable("a", -1000, 1) + b = Variable("b", -1000, 1) + var_vals = {a: 1, b: -1000} + assert sym_infer(a%b, var_vals) == 1 + assert sym_infer(a//b, var_vals) == 0 """ @unittest.skip("not supported on uops yet") @@ -705,6 +814,7 @@ class TestSymbolicRealWorld(unittest.TestCase): self.assertIn(idx.render(), ("((((((((((lidx5+1)//16)*802816)+(((lidx5+1)%16)*49))+(gidx0*3211264))+(gidx1*784))+(gidx2*8))+(lidx4*100352))+lidx3)+2207744)", '((lidx3+((((((((lidx5+1)//16)*802816)+(((lidx5+1)%16)*49))+(gidx0*3211264))+(gidx1*784))+(gidx2*8))+(lidx4*100352)))+2207744)', + '((lidx3+((lidx4*100352)+((gidx2*8)+((gidx1*784)+((gidx0*3211264)+((((lidx5+1)//16)*802816)+(((lidx5+1)%16)*49)))))))+2207744)', )) class TestBounds(unittest.TestCase): diff --git a/tinygrad_repo/test/unit/test_uop_vmin_vmax.py b/tinygrad_repo/test/unit/test_uop_vmin_vmax.py index f687df3749..cc1ca49dd3 100644 --- a/tinygrad_repo/test/unit/test_uop_vmin_vmax.py +++ b/tinygrad_repo/test/unit/test_uop_vmin_vmax.py @@ -1,5 +1,5 @@ import unittest, math -from tinygrad.ops import UOp, Ops +from tinygrad.uop.ops import UOp, Ops from tinygrad.dtype import dtypes class TestVminVmaxProperties(unittest.TestCase): @@ -25,6 +25,31 @@ class TestVminVmaxProperties(unittest.TestCase): self.assertEqual(uop.vmin, 15) self.assertEqual(uop.vmax, 25) + def test_vmin_vmax_subtraction_with_variable(self): + x = UOp.variable('x', 10, 20) + uop = x - 5 + self.assertEqual(uop.vmin, 5) + self.assertEqual(uop.vmax, 15) + uop = 5 - x + self.assertEqual(uop.vmin, -15) + self.assertEqual(uop.vmax, -5) + + def test_vmin_vmax_and_with_variable(self): + x = UOp.variable('x', 10, 20) + uop = x & 5 + self.assertEqual(uop.vmin, 0) + self.assertEqual(uop.vmax, 5) + + # this can be improved + uop = x & 15 + self.assertEqual(uop.vmin, 0) + self.assertEqual(uop.vmax, 15) + + # this can be improved + uop = x & 32 + self.assertEqual(uop.vmin, 0) + self.assertEqual(uop.vmax, 20) + def test_vmin_vmax_multiplication_with_variable(self): # vmin and vmax for multiplication with a variable x = UOp.variable('x', -3, 4) @@ -95,39 +120,87 @@ class TestVminVmaxDivMod(unittest.TestCase): def test_vmin_vmax_division_negative(self): # vmin and vmax for division of a variable by a negative constant + # always positive x = UOp.variable('x', 10, 20) uop = x // -2 self.assertEqual(uop.vmin, -10) self.assertEqual(uop.vmax, -5) + uop = x // -3 + self.assertEqual(uop.vmin, -6) + self.assertEqual(uop.vmax, -3) + + # always negative + x = UOp.variable('x', -20, -10) + uop = x // -2 + self.assertEqual(uop.vmin, 5) + self.assertEqual(uop.vmax, 10) + uop = x // -3 + self.assertEqual(uop.vmin, 3) + self.assertEqual(uop.vmax, 6) + + # cross 0 + x = UOp.variable('x', -10, 10) + uop = x // -2 + self.assertEqual(uop.vmin, -5) + self.assertEqual(uop.vmax, 5) + uop = x // -3 + self.assertEqual(uop.vmin, -3) + self.assertEqual(uop.vmax, 3) + + def test_vmin_vmax_div_symbolic(self): + x = UOp.variable('x', 1, 10) + y = UOp.variable('y', 3, 5) + self.assertEqual((x//y).vmin, 0) + self.assertEqual((x//y).vmax, 3) + self.assertEqual(((-x)//y).vmin, -3) + self.assertEqual(((-x)//y).vmax, 0) + self.assertEqual((x//(-y)).vmin, -3) + self.assertEqual((x//(-y)).vmax, 0) + self.assertEqual(((-x)//(-y)).vmin, 0) + self.assertEqual(((-x)//(-y)).vmax, 3) + + self.assertEqual((100//y).vmin, 20) + self.assertEqual((100//y).vmax, 33) + self.assertEqual(((-100)//y).vmin, -33) + self.assertEqual(((-100)//y).vmax, -20) + self.assertEqual((100//(-y)).vmin, -33) + self.assertEqual((100//(-y)).vmax, -20) + self.assertEqual(((-100)//(-y)).vmin, 20) + self.assertEqual(((-100)//(-y)).vmax, 33) def test_vmin_vmax_mod_positive(self): # vmin and vmax for modulo of a variable by a positive constant - x = UOp.variable('x', 10, 20) - uop = x % 3 + positive = UOp.variable('positive', 10, 20) + uop = positive % 3 self.assertEqual(uop.vmin, 0) self.assertEqual(uop.vmax, 2) - @unittest.skip("broken") + negative = UOp.variable('negative', -20, -10) + uop = negative % 3 + self.assertEqual(uop.vmin, -2) + self.assertEqual(uop.vmax, 0) + + mixed = UOp.variable('mixed', -20, 20) + uop = mixed % 3 + self.assertEqual(uop.vmin, -2) + self.assertEqual(uop.vmax, 2) + def test_vmin_vmax_mod_negative(self): # vmin and vmax for modulo of a variable by a negative constant - x = UOp.variable('x', 10, 20) - uop = x % -3 + positive = UOp.variable('positive', 10, 20) + uop = positive % -3 + self.assertEqual(uop.vmin, 0) + self.assertEqual(uop.vmax, 2) + + negative = UOp.variable('negative', -20, -10) + uop = negative % -3 self.assertEqual(uop.vmin, -2) self.assertEqual(uop.vmax, 0) - def test_vmin_vmax_division_with_mixed_range(self): - # vmin and vmax for division of a variable with a range crossing zero - x = UOp.variable('x', -10, 10) - uop = x // 3 - self.assertEqual(uop.vmin, -4) # -10//3 = -4 - self.assertEqual(uop.vmax, 3) # 10//3 = 3 - - def test_vmin_vmax_mod_with_mixed_range(self): - # vmin and vmax for modulo of a variable with a range crossing zero - x = UOp.variable('x', -10, 10) - uop = x % 4 - self.assertEqual(uop.vmin, 0) # modulo always positive or zero when divisor is positive - self.assertEqual(uop.vmax, 3) # max possible mod is 3 when dividing by 4 + mixed = UOp.variable('mixed', -20, 20) + uop = mixed % -3 + self.assertEqual(uop.vmin, -2) + self.assertEqual(uop.vmax, 2) class TestVminVmaxVConst(unittest.TestCase): def test_vmin_vmax_vconst_single_element(self): @@ -160,6 +233,12 @@ class TestVminVmaxVConst(unittest.TestCase): self.assertEqual(uop.vmin, -3.2) self.assertEqual(uop.vmax, 1.5) + def test_vmin_vmax_vconst_with_bools(self): + # vmin and vmax for a vector constant of bool values + uop = UOp.const(dtypes.bool.vec(3), (True, False, False)) + self.assertIs(uop.vmin, False) + self.assertIs(uop.vmax, True) + class TestConstFactor(unittest.TestCase): def test_const_factor_constant(self): # const_factor for a constant diff --git a/tinygrad_repo/test/unit/test_upat_compile.py b/tinygrad_repo/test/unit/test_upat_compile.py new file mode 100644 index 0000000000..1f68a8830b --- /dev/null +++ b/tinygrad_repo/test/unit/test_upat_compile.py @@ -0,0 +1,53 @@ +import unittest +from tinygrad.helpers import DEBUG +from tinygrad.dtype import dtypes +from tinygrad.uop.ops import UPat, track_rewrites, GroupOp, Ops +from tinygrad.uop.upat import _get_code, upat_compile +import dis + +@track_rewrites() +def do_compile(up): + print("\n***** COMPILE", up) + match_code = _get_code(up, False) + match = upat_compile(up, lambda **kwargs: None) + print(match_code[0]) + if DEBUG >= 2: dis.dis(match) + return match_code[0] + +class TestUPatCompile(unittest.TestCase): + def test_double(self): + up = UPat.var("x") * UPat.cvar("c0") + UPat.var("x") * UPat.cvar("c1") + do_compile(up) + + def test_single(self): + up = UPat.var("x") + UPat.var("y") + do_compile(up) + + def test_xpx(self): + up = UPat.var("x") + UPat.var("x") + do_compile(up) + + def test_xp0(self): + up = UPat.var("x") + 0 + do_compile(up) + + def test_bool(self): + up = UPat.var('x', dtype=dtypes.bool) * UPat.var('y', dtype=dtypes.bool) + do_compile(up) + + def test_single_c(self): + up = (UPat.var("x") + UPat.var("y")) * UPat.var("c") + do_compile(up) + + def test_const_folding(self): + up = UPat(GroupOp.ALU-{Ops.THREEFRY}, name="a", src=UPat((Ops.VCONST, Ops.CONST))) + do_compile(up) + + @unittest.skip("fix this") + def test_range_named(self): + # this should be one src, but this should also still work + up = UPat(Ops.CAST, dtypes.float, UPat.var("x", dtypes.bfloat16)) + do_compile(up) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test/unit/test_verify_ast.py b/tinygrad_repo/test/unit/test_verify_ast.py index d38967a7c8..eaa23ebcb9 100644 --- a/tinygrad_repo/test/unit/test_verify_ast.py +++ b/tinygrad_repo/test/unit/test_verify_ast.py @@ -4,8 +4,8 @@ import unittest from tinygrad import Tensor from tinygrad.codegen.kernel import Kernel from tinygrad.helpers import DEBUG -from tinygrad.ops import UOp, Ops, print_uops -from tinygrad.codegen.kernel import verify_ast +from tinygrad.uop.ops import UOp, Ops, print_uops +from tinygrad.uop.spec import type_verify, shape_spec from tinygrad.shape.shapetracker import ShapeTracker from tinygrad import dtypes from tinygrad.shape.view import View @@ -15,8 +15,8 @@ def helper_test_verify_ast(*stores:UOp) -> Kernel: sink = UOp(Ops.SINK, dtypes.void, stores) if DEBUG >= 3: for op in stores: print(op) - try: verify_ast(sink) - except AssertionError as e: raise InvalidASTException(e.args) + try: type_verify(list(sink.toposort()), shape_spec) + except RuntimeError as e: raise InvalidASTException(e.args) k = Kernel(sink) k.linearize() if DEBUG >= 6: print_uops(k.uops) @@ -64,23 +64,24 @@ class TestVerifyAST(unittest.TestCase): a = UOp(Ops.LOAD, dtypes.float, (bufs[1], ShapeTracker.from_shape((32, 1)).to_uop())) r = UOp(Ops.REDUCE_AXIS, dtypes.float, (a,), (Ops.ADD, (0,))) st = UOp.store(bufs[0], ShapeTracker.from_shape((32, 1)).to_uop(), r) - with self.assertRaisesRegex(InvalidASTException, "implicit expand"): helper_test_verify_ast(st) + with self.assertRaises(InvalidASTException): helper_test_verify_ast(st) def test_reduce_add_store(self): bufs = [UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), i) for i in range(2)] a = UOp(Ops.LOAD, dtypes.float, (bufs[1], ShapeTracker.from_shape((32, 1)).to_uop())) r = UOp(Ops.REDUCE_AXIS, dtypes.float, (a,), (Ops.ADD, (0,))) st = UOp.store(bufs[0], ShapeTracker.from_shape((32, 1)).to_uop(), r+a) - with self.assertRaisesRegex(InvalidASTException, "implicit expand"): helper_test_verify_ast(st) + with self.assertRaises(InvalidASTException): helper_test_verify_ast(st) def test_buffer_uops_st(self): a = Tensor.randn(4, 4)+2 - uop_sts = verify_ast(a.schedule()[-1].ast) - store_st = [st for u,st in uop_sts.items() if u.op is Ops.STORE][0] + helper_test_verify_ast(ast:=a.schedule()[-1].ast) + store_st = [u.st for u in ast.toposort() if u.op is Ops.STORE][0] self.assertEqual(store_st, ShapeTracker.from_shape((4, 4))) - const_st = [st for u,st in uop_sts.items() if u.op is Ops.VALID][0] + const_st = [u.st for u in ast.toposort() if u.op is Ops.CONST][0] self.assertEqual(const_st, ShapeTracker.from_shape((1, 1)).expand((4, 4))) + @unittest.skip("questionable if we want this") def test_assert_swizzle(self): buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0) a = UOp(Ops.LOAD, dtypes.float, (buf, ShapeTracker.from_shape((32, 1)).to_uop())) @@ -88,10 +89,10 @@ class TestVerifyAST(unittest.TestCase): st = UOp.store(buf, ShapeTracker.from_shape((32, 1)).to_uop(), r.view(r.st.expand((32, 1)))+a) with self.assertRaisesRegex(InvalidASTException, "swizzle"): helper_test_verify_ast(st) - def test_flat_const_always_valid(self): + def test_const_view_always_valid(self): buf = UOp(Ops.DEFINE_GLOBAL, dtypes.float.ptr(), (), 0) - a = UOp.const(dtypes.int, 0).cast(dtypes.float) - st = UOp.store(buf, ShapeTracker.from_shape(()).to_uop(), a) + a = UOp.const(dtypes.int, 0).replace(src=(UOp(Ops.VIEW, dtypes.void, (UOp(Ops.DEVICE, arg="CPU"),), ShapeTracker.from_shape(())),)) + st = UOp.store(buf, ShapeTracker.from_shape(()).to_uop(), a.cast(dtypes.float)) helper_test_verify_ast(st) if __name__ == '__main__': diff --git a/tinygrad_repo/test/unit/test_view.py b/tinygrad_repo/test/unit/test_view.py index 6770a84cfa..45f7b59437 100644 --- a/tinygrad_repo/test/unit/test_view.py +++ b/tinygrad_repo/test/unit/test_view.py @@ -39,6 +39,11 @@ class TestView(unittest.TestCase): v = View.create(shape=(2,3,4), mask=((0,2),(0,3),(0,4))) self.assertTrue(v.contiguous) + def test_reshape_all_invalid(self): + v = View.create((4,5), mask=((0,0), (0,0))).reshape((20,)) + self.assertIsNotNone(v) + self.assertEqual(v, View.create((20,), mask=((0,0),))) + class TestMergeDims(unittest.TestCase): def test_contiguous(self): shape = (2, 3, 4) @@ -170,5 +175,53 @@ class TestMergeViews(unittest.TestCase): self.assertIsNotNone(v) self.assertEqual(v, target) + def test_view_padded_area1(self): + # test_multinomial + v0 = View(shape=(2,), strides=(0,), offset=0, mask=((1, 2),), contiguous=False) + v1 = View(shape=(1,), strides=(0,), offset=0, mask=None, contiguous=True) + v = v0 + v1 + self.assertIsNotNone(v) + self.assertEqual(v, View(shape=(1,), strides=(0,), offset=0, mask=((0, 0),), contiguous=False)) + + def test_view_padded_area2(self): + # test_pad_reflect_mode + v0 = View(shape=(1, 1, 10, 7), strides=(0, 0, 5, 1), offset=-15, mask=((0, 1), (0, 1), (3, 8), (0, 5)), contiguous=False) + v1 = View(shape=(0, 0, 0, 0), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=True) + v = v0 + v1 + self.assertIsNotNone(v) + self.assertEqual(v, View(shape=(0, 0, 0, 0), strides=(0, 0, 0, 0), offset=0, mask=None, contiguous=True)) + + def test_view_padded_area3(self): + # test_roll + v0 = View(shape=(2, 4), strides=(0, 1), offset=4, mask=((0, 1), (0, 4)), contiguous=False) + v1 = View(shape=(1, 4), strides=(0, 1), offset=4, mask=None, contiguous=False) + v = v0 + v1 + self.assertIsNotNone(v) + self.assertEqual(v, View(shape=(1, 4), strides=(0, 0), offset=0, mask=((0, 0), (0, 0)), contiguous=False)) + + def test_view_padded_area4(self): + # test_std_mean + v0 = View(shape=(2,), strides=(0,), offset=0, mask=((0, 1),), contiguous=False) + v1 = View(shape=(1, 1, 1), strides=(0, 0, 0), offset=1, mask=None, contiguous=False) + v = v0 + v1 + self.assertIsNotNone(v) + self.assertEqual(v, View(shape=(1, 1, 1), strides=(0, 0, 0), offset=0, mask=((0, 0), (0, 0), (0, 0)), contiguous=False)) + + def test_empty_shape_view1(self): + # test_stack_slice + v0 = View(shape=(3, 5), strides=(0, 1), offset=0, mask=((0, 1), (0, 5)), contiguous=False) + v1 = View(shape=(), strides=(), offset=0, mask=None, contiguous=True) + v = v0 + v1 + self.assertIsNotNone(v) + self.assertEqual(v, View(shape=(), strides=(), offset=0, mask=None, contiguous=True)) + + def test_empty_shape_view2(self): + # test_std_mean + v0 = View(shape=(2,), strides=(0,), offset=0, mask=((1, 2),), contiguous=False) + v1 = View(shape=(), strides=(), offset=0, mask=None, contiguous=True) + v = v0 + v1 + # TODO: why is this different? + self.assertIsNone(v) + if __name__ == '__main__': unittest.main() diff --git a/tinygrad_repo/test/unit/test_viz.py b/tinygrad_repo/test/unit/test_viz.py new file mode 100644 index 0000000000..d7409c4cc0 --- /dev/null +++ b/tinygrad_repo/test/unit/test_viz.py @@ -0,0 +1,295 @@ +import unittest, decimal, json +from tinygrad.dtype import dtypes +from tinygrad.uop.ops import TRACK_MATCH_STATS, TrackedPatternMatcher, UOp, graph_rewrite, track_rewrites, UPat, Ops +from tinygrad.codegen.symbolic import symbolic +from tinygrad.uop.ops import tracked_ctxs as contexts, tracked_keys as keys, _name_cnt, _substitute +from tinygrad.device import ProfileDeviceEvent, ProfileRangeEvent, ProfileGraphEvent, ProfileGraphEntry +from tinygrad.viz.serve import get_metadata, get_details, uop_to_json, to_perfetto + +# NOTE: VIZ tests always use the tracked PatternMatcher instance +symbolic = TrackedPatternMatcher(symbolic.patterns) +substitute = TrackedPatternMatcher(_substitute.patterns) + +inner_rewrite = TrackedPatternMatcher([ + (UPat.cvar("x"), lambda x: None if x.dtype == dtypes.float32 else UOp.const(dtypes.float32, x.arg)), +]) + +l2 = TrackedPatternMatcher([(UPat(Ops.CUSTOM, arg=2, name="x"), lambda x: x.replace(arg=3))]) +l1 = TrackedPatternMatcher([(UPat(Ops.CUSTOM, arg=1, name="x"), lambda x: graph_rewrite(x.replace(arg=2), l2))]) +l0 = TrackedPatternMatcher([(UPat(Ops.CUSTOM, arg=0, name="x"), lambda x: graph_rewrite(x.replace(arg=1), l1))]) + +class TestViz(unittest.TestCase): + def setUp(self): + # clear the global context + contexts.clear() + keys.clear() + _name_cnt.clear() + self.tms = TRACK_MATCH_STATS.value + TRACK_MATCH_STATS.value = 2 + def tearDown(self): TRACK_MATCH_STATS.value = self.tms + + def test_viz_simple(self): + a = UOp.variable("a", 0, 10) + @track_rewrites(named=True) + def test(sink): return graph_rewrite(sink, symbolic) + test(a*1) + ret = get_metadata(keys, contexts) + self.assertEqual(len(ret), 1) + key, val = ret[0] + self.assertEqual(key, "test_1") + self.assertEqual(val[0]["match_count"], 1) + + def test_track_two_rewrites(self): + a = UOp.variable("a", 0, 10) + @track_rewrites(named=True) + def test(sink): return graph_rewrite(sink, symbolic) + test((a+a)*1) + ret = get_metadata(keys, contexts) + key, val = ret[0] + self.assertEqual(len(ret), 1) # one context + self.assertEqual(len(val), 1) # one graph_rewrite call in context + self.assertEqual(key, "test_1") + self.assertEqual(val[0]["match_count"], 2) # two upats applied + + def test_track_multiple_calls_one_ctx(self): + a = UOp.variable("a", 0, 10) + @track_rewrites(named=True) + def test(a, b): + a = graph_rewrite(a, symbolic) + b = graph_rewrite(b, symbolic) + test(a*1, a*5) + ret = get_metadata(keys, contexts) + key, val = ret[0] + self.assertEqual(len(ret), 1) # one context + self.assertEqual(len(val), 2) # two graph_rewrite calls in context + self.assertEqual(key, "test_1") + self.assertEqual(val[0]["match_count"], 1) # one rewrite for a*0 + self.assertEqual(val[1]["match_count"], 0) # no rewrites for a*5 + + def test_track_rewrites(self): + @track_rewrites(named=True) + def do_rewrite(x:UOp): return graph_rewrite(x, symbolic) + a = UOp.variable("a", 0, 10) + b = UOp.variable("b", 0, 4) + do_rewrite(a*1) + do_rewrite(a*b) + ret = get_metadata(keys, contexts) + self.assertEqual(len(ret), 2) + key, m = ret[0] + self.assertEqual(key, "do_rewrite_1") + self.assertEqual(m[0]["match_count"], 1) + key, m = ret[1] + self.assertEqual(key, "do_rewrite_2") + self.assertEqual(m[0]["match_count"], 0) + + def test_track_rewrites_with_exception(self): + @track_rewrites() + def do_rewrite(x:UOp): + x = graph_rewrite(x, symbolic) # NOTE: viz tracks this + raise Exception("test") + a = UOp.variable("a", 0, 10) + with self.assertRaises(Exception): do_rewrite(a*1) + ret = get_metadata(keys, contexts) + self.assertEqual(len(ret), 1) + + def test_track_rewrites_name_fxn(self): + @track_rewrites(name_fxn=lambda r: f"output_{r}") + def do_rewrite(x:UOp): + x = graph_rewrite(x, symbolic) + return x.render() + expr = UOp.variable("a",0,10)*UOp.variable("b",0,10) + do_rewrite(expr) + key = get_metadata(keys, contexts)[0][0] + self.assertEqual(key, "output_(a*b) n1") + + expr2 = UOp.variable("a",0,10)+UOp.variable("b",0,10) + do_rewrite(expr2) + key = get_metadata(keys, contexts)[1][0] + self.assertEqual(key, "output_(a+b) n2") + + @unittest.expectedFailure + def test_name_in_positional_arg(self): + @track_rewrites(named=True) + def test(sink): return graph_rewrite(sink, symbolic, None, False, "name") + test(UOp.variable("a", 0, 1)) + self.assertEqual(contexts[0].pop().name, "name") + + # NOTE: CONST UOps do not get nodes in the graph + def test_dont_create_const_nodes(self): + a = UOp.variable("a", 0, 10) + b = UOp.variable("b", 0, 4) + self.assertEqual(len(uop_to_json(a*1)), 2) + self.assertEqual(len(uop_to_json(a*b)), 3) + + def test_bottom_up_rewrite(self): + a = UOp.variable("a", 0, 10) + b = UOp.variable("b", 0, 10) + c = UOp.variable("c", 0, 10) + @track_rewrites(named=True) + def fxn(sink): return graph_rewrite(sink, substitute, ctx={a+b:c}, bottom_up=True) + fxn(a+b) + #UOp.substitute(a+b, {a+b:c}) + ret = get_metadata(keys, contexts) + self.assertEqual(len(ret), 1) + _, m = ret[0] + self.assertEqual(m[0]["match_count"], 1) + + # NOTE: calling graph_rewrite when the function isn't decorated with track_rewrites should not VIZ + def test_rewrite_without_context(self): + def untracked_graph_rewrite(sink): return graph_rewrite(sink, symbolic) + @track_rewrites(named=True) + def tracked_graph_rewrite(sink): return graph_rewrite(sink, symbolic) + # test + add = UOp.const(dtypes.int, 2) + UOp.const(dtypes.int, 1) + untracked_graph_rewrite(add) + self.assertEqual(len(contexts), 0) + tracked_graph_rewrite(add) + self.assertEqual(len(contexts), 1) + + def test_inner_rewrite_location(self): + # inner rewrite gets tracked in another context + def inner_rewrite(sink): return graph_rewrite(sink, symbolic) + @track_rewrites(named=True) + def tracked_graph_rewrite(sink): return inner_rewrite(sink) + # test + add = UOp.const(dtypes.int, 2) + UOp.const(dtypes.int, 1) + tracked_graph_rewrite(add) + self.assertEqual(len(contexts), 1) + # location of context is inner_rewrite + fp, lineno = contexts[0][0].loc + self.assertEqual(lineno, inner_rewrite.__code__.co_firstlineno) + self.assertEqual(fp, inner_rewrite.__code__.co_filename) + + def test_nested_rewrite(self): + def make_float(x:UOp, y:UOp): + if x.dtype == dtypes.float: return None + x2 = graph_rewrite(x, inner_rewrite, name="inner_x") + y2 = graph_rewrite(y, inner_rewrite, name="inner_y") + return None if (x2 is x and y2 is y) else x2+y2 + outer_rewrite = TrackedPatternMatcher([(UPat.cvar("x")+UPat.cvar("y"), make_float),]) + @track_rewrites(named=True) + def rewrite(u:UOp): return graph_rewrite(u, outer_rewrite, name="outer") + a = UOp.const(dtypes.int, 1)+UOp.const(dtypes.int, 2) + rewrite(a) + self.assertEqual(len(contexts), 1) + tracked = contexts[0] + self.assertEqual(len(tracked), 3) + self.assertEqual(tracked[0].depth, 0) + self.assertEqual(tracked[1].depth, 1) + self.assertEqual(tracked[2].depth, 1) + # NOTE: this is sorted by the time called, maybe it should be by depth + self.assertEqual([x.name for x in tracked], ["outer", "inner_x", "inner_y"]) + self.assertEqual([len(x.matches) for x in tracked], [1, 1, 1]) + + def test_depth_level(self): + @track_rewrites(named=True) + def fxn(u:UOp): return graph_rewrite(u, l0) + ret = fxn(UOp(Ops.CUSTOM, arg=0)) + assert ret is UOp(Ops.CUSTOM, arg=3) + self.assertEqual(len(contexts), 1) + tracked = contexts[0] + self.assertEqual(tracked[0].depth, 0) + self.assertEqual(tracked[1].depth, 1) + self.assertEqual(tracked[2].depth, 2) + + def test_shape_label(self): + a = UOp.new_buffer("CPU", 1, dtypes.uint8).expand((4,)) + b = UOp.new_buffer("CPU", 1, dtypes.uint8).expand((8,)) + n = a+b + ser = uop_to_json(n) + self.assertIn("(4,)", ser[id(a)]["label"]) + self.assertIn("(8,)", ser[id(b)]["label"]) + with self.assertRaises(AssertionError): n.st + _ = ser[id(n)]["label"] # VIZ should not crash + + def test_default_named(self): + test = UOp(Ops.NOOP) + @track_rewrites() + def test_fxn(): return graph_rewrite(test, l0) + assert test_fxn() is test + self.assertEqual(keys[0], "test_fxn_1") + + @unittest.skip("TODO: doesn't work") + def test_recursion_err(self): + inf = TrackedPatternMatcher([ + (UPat.const(dtypes.int, 0).named("a"), lambda a: a.const_like(1)), + (UPat.const(dtypes.int, 1).named("b"), lambda b: b.const_like(0)), + ]) + @track_rewrites(named=True) + def func(u): return graph_rewrite(u, inf) + with self.assertRaises(RecursionError): func(UOp.const(dtypes.int, 0)) + _ = list(get_details(keys[0], contexts[0][0])) + +class TextVizProfiler(unittest.TestCase): + def test_perfetto_node(self): + prof = [ProfileRangeEvent(device='NV', name='E_2', st=decimal.Decimal(1000), en=decimal.Decimal(1010), is_copy=False), + ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100))] + + j = json.loads(to_perfetto(prof)) + + # Device regs always first + self.assertEqual(j['traceEvents'][0]['name'], 'process_name') + self.assertEqual(j['traceEvents'][0]['ph'], 'M') + self.assertEqual(j['traceEvents'][0]['args']['name'], 'NV') + + self.assertEqual(j['traceEvents'][1]['name'], 'thread_name') + self.assertEqual(j['traceEvents'][1]['ph'], 'M') + self.assertEqual(j['traceEvents'][1]['pid'], j['traceEvents'][0]['pid']) + self.assertEqual(j['traceEvents'][1]['tid'], 0) + self.assertEqual(j['traceEvents'][1]['args']['name'], 'COMPUTE') + + self.assertEqual(j['traceEvents'][2]['name'], 'thread_name') + self.assertEqual(j['traceEvents'][2]['ph'], 'M') + self.assertEqual(j['traceEvents'][2]['pid'], j['traceEvents'][0]['pid']) + self.assertEqual(j['traceEvents'][2]['tid'], 1) + self.assertEqual(j['traceEvents'][2]['args']['name'], 'COPY') + + self.assertEqual(j['traceEvents'][3]['name'], 'E_2') + self.assertEqual(j['traceEvents'][3]['ts'], 0) + self.assertEqual(j['traceEvents'][3]['dur'], 10) + self.assertEqual(j['traceEvents'][3]['ph'], 'X') + self.assertEqual(j['traceEvents'][3]['pid'], j['traceEvents'][0]['pid']) + self.assertEqual(j['traceEvents'][3]['tid'], 0) + + def test_perfetto_copy_node(self): + prof = [ProfileRangeEvent(device='NV', name='COPYxx', st=decimal.Decimal(1000), en=decimal.Decimal(1010), is_copy=True), + ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100))] + + j = json.loads(to_perfetto(prof)) + + self.assertEqual(j['traceEvents'][3]['name'], 'COPYxx') + self.assertEqual(j['traceEvents'][3]['ts'], 900) # diff clock + self.assertEqual(j['traceEvents'][3]['dur'], 10) + self.assertEqual(j['traceEvents'][3]['ph'], 'X') + self.assertEqual(j['traceEvents'][3]['tid'], 1) + + def test_perfetto_graph(self): + prof = [ProfileDeviceEvent(device='NV', comp_tdiff=decimal.Decimal(-1000), copy_tdiff=decimal.Decimal(-100)), + ProfileDeviceEvent(device='NV:1', comp_tdiff=decimal.Decimal(-500), copy_tdiff=decimal.Decimal(-50)), + ProfileGraphEvent(ents=[ProfileGraphEntry(device='NV', name='E_25_4n2', st_id=0, en_id=1, is_copy=False), + ProfileGraphEntry(device='NV:1', name='NV -> NV:1', st_id=2, en_id=3, is_copy=True)], + deps=[[], [0]], + sigs=[decimal.Decimal(1000), decimal.Decimal(1002), decimal.Decimal(1004), decimal.Decimal(1008)])] + + j = json.loads(to_perfetto(prof)) + + # Device regs always first + self.assertEqual(j['traceEvents'][0]['args']['name'], 'NV') + self.assertEqual(j['traceEvents'][1]['args']['name'], 'COMPUTE') + self.assertEqual(j['traceEvents'][2]['args']['name'], 'COPY') + self.assertEqual(j['traceEvents'][3]['args']['name'], 'NV:1') + self.assertEqual(j['traceEvents'][4]['args']['name'], 'COMPUTE') + self.assertEqual(j['traceEvents'][5]['args']['name'], 'COPY') + + self.assertEqual(j['traceEvents'][6]['name'], 'E_25_4n2') + self.assertEqual(j['traceEvents'][6]['ts'], 0) + self.assertEqual(j['traceEvents'][6]['dur'], 2) + self.assertEqual(j['traceEvents'][6]['pid'], j['traceEvents'][0]['pid']) + + self.assertEqual(j['traceEvents'][7]['name'], 'NV -> NV:1') + self.assertEqual(j['traceEvents'][7]['ts'], 954) + self.assertEqual(j['traceEvents'][7]['dur'], 4) + self.assertEqual(j['traceEvents'][7]['pid'], j['traceEvents'][3]['pid']) + +if __name__ == "__main__": + unittest.main() diff --git a/tinygrad_repo/test_driven_development.sh b/tinygrad_repo/test_driven_development.sh index e6334e6aa9..e868497e91 100755 --- a/tinygrad_repo/test_driven_development.sh +++ b/tinygrad_repo/test_driven_development.sh @@ -1,8 +1,8 @@ #!/bin/bash python3 test/external/process_replay/reset.py -RUN_PROCESS_REPLAY=1 pytest -n auto test/test_tiny.py test/test_uop_graph.py test/test_ops.py test/test_linearizer.py +CAPTURE_PROCESS_REPLAY=1 pytest -n auto test/test_tiny.py test/test_uop_graph.py test/test_ops.py test/test_linearizer.py while true; do if python3 test/test_tiny.py; then PYTHONPATH="." python3 test/external/process_replay/process_replay.py fi -done \ No newline at end of file +done diff --git a/tinygrad_repo/tinygrad/__init__.py b/tinygrad_repo/tinygrad/__init__.py index 947d03c9ed..5bc12f9116 100644 --- a/tinygrad_repo/tinygrad/__init__.py +++ b/tinygrad_repo/tinygrad/__init__.py @@ -4,7 +4,7 @@ if int(os.getenv("TYPED", "0")): install_import_hook(__name__) from tinygrad.tensor import Tensor # noqa: F401 from tinygrad.engine.jit import TinyJit # noqa: F401 -from tinygrad.ops import UOp +from tinygrad.uop.ops import UOp Variable = UOp.variable from tinygrad.dtype import dtypes # noqa: F401 from tinygrad.helpers import GlobalCounters, fetch, Context, getenv # noqa: F401 diff --git a/tinygrad_repo/tinygrad/codegen/__init__.py b/tinygrad_repo/tinygrad/codegen/__init__.py index e69de29bb2..b89549c322 100644 --- a/tinygrad_repo/tinygrad/codegen/__init__.py +++ b/tinygrad_repo/tinygrad/codegen/__init__.py @@ -0,0 +1,78 @@ +from typing import Any, Callable +import functools +from dataclasses import dataclass +from tinygrad.helpers import QUANTIZE, DEVECTORIZE, TRANSCENDENTAL +from tinygrad.uop.ops import PatternMatcher, graph_rewrite, UOp +from tinygrad.renderer import Renderer + +# import all pattern matchers here +from tinygrad.codegen.lowerer import pm_quant, pm_lowerer, get_index +from tinygrad.codegen.symbolic import sym, symbolic_simple, gep_pushing +from tinygrad.codegen.expander import migrate_indexing, pm_store_ignore, pm_move_ignore, pm_delete_ignore, expander +from tinygrad.codegen.devectorizer import load_store_folding, load_store_indexing, devectorize, \ + pm_reduce, ReduceContext, correct_load_store, pm_render, get_late_rewrite_patterns +from tinygrad.codegen.linearize import block_create, pm_blockend_merge, block_merge, pm_finalize, BlockContext + +@dataclass +class RewriteStep: + pm: PatternMatcher + ctx: Callable[[UOp], Any]|None = None + name: str|None = None + bottom_up: bool = False + def __call__(self, sink:UOp): + return graph_rewrite(sink, self.pm, ctx=self.ctx(sink) if self.ctx is not None else None, name=self.name, bottom_up=self.bottom_up) + +def apply_rewrites(sink:UOp, rewrites:list[RewriteStep]): return functools.reduce(lambda x,f: f(x), rewrites, sink) + +def get_rewrites_for_renderer(opts:Renderer, linearizer:bool=True) -> list[RewriteStep]: + # cache with the values of the context vars + return _get_rewrites_for_renderer(opts, linearizer, QUANTIZE.value, DEVECTORIZE.value, TRANSCENDENTAL.value) + +@functools.cache +def _get_rewrites_for_renderer(opts:Renderer, linearizer:bool, _QUANTIZE, _DEVECTORIZE, _TRANSCENDENTAL) -> list[RewriteStep]: + # ** lowerer (rewrite_shapetracker_with_index) ** + ret: list[RewriteStep] = [] + if _QUANTIZE and opts.device in {"CPU", "DSP"}: ret.append(RewriteStep(pm_quant, name="quantize")) + ret.append(RewriteStep(pm_lowerer, lambda ast: get_index(ast, opts), name="lowerer")) + + # ** expander (expand_rewrite) ** + ret.append(RewriteStep(sym+migrate_indexing, name="initial symbolic")) + + # ignore (for masked stores) + ret.append(RewriteStep(pm_store_ignore, name="store_ignore")) + ret.append(RewriteStep(pm_move_ignore, name="move_ignore")) + + # expand + remove surviving ignores + ret.append(RewriteStep(pm_delete_ignore+sym+expander, name="expander")) + + # ** devectorizer (full_graph_rewrite) ** + # remove reduce + ret.append(RewriteStep(pm_reduce+gep_pushing, lambda _: ReduceContext(), name="remove_reduce")) + + # devectorize (TODO: does this need opts?) + if _DEVECTORIZE >= 2: pm_devectorize = sym+load_store_folding+load_store_indexing + elif _DEVECTORIZE: pm_devectorize = sym+devectorize+load_store_folding+correct_load_store+load_store_indexing + else: pm_devectorize = sym+load_store_folding+correct_load_store+load_store_indexing + ret.append(RewriteStep(pm_devectorize, lambda _: opts, name="devectorize")) + + supported_ops = tuple(opts.code_for_op.keys()) + extra_matcher = opts.extra_matcher if opts.extra_matcher is not None else PatternMatcher([]) + + # optional pre matcher + if opts.pre_matcher is not None: ret.append(RewriteStep(opts.pre_matcher, name="pre_matcher")) + + # final rules for the renderer (without sym) + pm_final_rewrite = symbolic_simple+get_late_rewrite_patterns(supported_ops, _TRANSCENDENTAL>=2)+pm_render+extra_matcher + ret.append(RewriteStep(pm_final_rewrite, lambda _: opts, name="final rewrite")) + + # ** linearizer ** + if linearizer: + ret.append(RewriteStep(block_create, ctx=BlockContext.from_sink, name="Linearizer: Create Blocks", bottom_up=True)) + ret.append(RewriteStep(pm_blockend_merge, name="Linearizer: Merge Blockends")) + ret.append(RewriteStep(block_merge, name="Linearizer: Merge Blocks")) + ret.append(RewriteStep(pm_finalize, name="Linearizer: Finalize")) + return ret + +def full_rewrite_to_sink(sink:UOp, opts:Renderer|None=None, linearizer:bool=False) -> UOp: + return apply_rewrites(sink, get_rewrites_for_renderer(opts if opts is not None else Renderer(), linearizer)) +def full_rewrite(sink:UOp, opts:Renderer|None=None) -> list[UOp]: return list(full_rewrite_to_sink(sink, opts, linearizer=True).arg.lst) diff --git a/tinygrad_repo/tinygrad/codegen/devectorizer.py b/tinygrad_repo/tinygrad/codegen/devectorizer.py new file mode 100644 index 0000000000..c3a4911ec3 --- /dev/null +++ b/tinygrad_repo/tinygrad/codegen/devectorizer.py @@ -0,0 +1,431 @@ +from typing import Any, Callable, cast +import functools, operator, itertools +from collections import defaultdict +from dataclasses import dataclass +from tinygrad.device import is_dtype_supported +from tinygrad.dtype import dtypes, ImageDType, PtrDType, promo_lattice, DType +from tinygrad.uop.ops import UOp, Ops, UPat, PatternMatcher, resolve, graph_rewrite, GroupOp, identity_element +from tinygrad.codegen.symbolic import split_uop, uop_given_valid, parse_valid, simplify_valid, sym, symbolic_flat +from tinygrad.helpers import getenv, flatten, AMX, prod, partition +from tinygrad.codegen.transcendental import xexp2, xlog2, xsin, xpow, TRANSCENDENTAL_SUPPORTED_DTYPES +from tinygrad.renderer import Renderer + +# ***** image load valid simplification ***** + +def simplify_valid_load(buf:UOp, start_idx:UOp, valid:UOp) -> UOp|None: + if (idx:=uop_given_valid(valid, start_idx)) is None: return buf.const_like(0) + if not isinstance(buf.dtype, ImageDType): return None if idx is start_idx else buf.index(idx, valid) + + # wait for it to be image indexed before running simplification + if start_idx.dtype.count != 2: return None + + # can drop valid if idx is out of bound when valid is False + drop_stmt = [] + for stmt in split_uop(valid, Ops.AND): + try: X, is_upper_bound, c = parse_valid(stmt) + except ValueError: return None + + # for X0 + X1 + ... >= 1, check if it's out of bound when Xi = 0 for all i + if not is_upper_bound and c == 1 and all(u.op in GroupOp.Irreducible and u.vmin == 0 for u in split_uop(X, Ops.ADD)): + testidx = functools.reduce(lambda nowidx,u: nowidx.substitute({u:u.const_like(0)}), split_uop(X, Ops.ADD), idx) + testidx = testidx.simplify() + if testidx.gep(0).vmax < 0 or testidx.gep(1).vmax < 0: + drop_stmt.append(stmt) + continue + + # if X <= c, check if it's out of bound when X = c+1 + # if X >= c, check if it's out of bound when X = c-1 + test_value = c + 1 if is_upper_bound else c - 1 + for i,b in zip(idx.src, (buf.dtype.shape[1], buf.dtype.shape[0])): + if i.is_increasing(): + rw = i.substitute({X:X.const_like(test_value)}).simplify() + if rw.vmin >= b or rw.vmax < 0: + drop_stmt.append(stmt) + break + + if not drop_stmt and idx is start_idx: return None + new_valid = functools.reduce(operator.and_, ss) if (ss:=[s for s in split_uop(valid, Ops.AND) if s not in drop_stmt]) else None + return buf.index(idx, new_valid) + +def delete_redundant_gates(buf:UOp, idx:UOp, val:UOp, store_gate:UOp, cast:UOp|None=None) -> UOp|None: + if store_gate not in [gate.src[0] for gate in val.toposort() if gate.op is Ops.IF]: return None + # remove the gate from the index + return UOp.store(buf.index(idx).cast(cast.dtype) if cast is not None else buf.index(idx), val) + +load_store_indexing = PatternMatcher([ + # simplify valid + (UPat(Ops.AND, name="valid"), simplify_valid), + # image load valid idx simplification + (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("start_idx"), UPat.var("valid"))), simplify_valid_load), + # index True is just Index + (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("start_idx"), UPat(Ops.CONST, arg=True))), lambda buf,start_idx: buf.index(start_idx)), + # delete_redundant_gates (after expand) + (UPat(Ops.STORE, src=(UPat.any(stidx:=UPat.var("buf").index(UPat.var("idx"), UPat.var("store_gate")), stidx.cast().named("cast")), + UPat.var("val"))), delete_redundant_gates), +]) + +# ***** load/store grouping ***** + +def expand_index(buf:UOp, vec:UOp, mask:UOp|None=None): + if getenv("UNSAFE_DISABLE_MASK", 0): mask = None + # generate the individual indexes + midx = graph_rewrite(UOp.sink(*[buf.index(vec.gep(i), mask.gep(i) if mask is not None else None) for i in range(vec.dtype.count)]), + symbolic_flat+load_store_indexing, name=f"index_buf_{buf.arg}") + # extract all the relevant offsets + offsets_rootsrc: defaultdict[Any, dict[int, list[int]]] = defaultdict(dict) + for i in range(vec.dtype.count): + idx: Any = midx.src[i].src[1] + if idx.op is Ops.ADD and idx.src[1].op is Ops.CONST: root_src, arg = idx.src[0], idx.src[1].arg + elif idx.op is Ops.ADD and idx.src[0].op is Ops.CONST: root_src, arg = idx.src[1], idx.src[0].arg + elif idx.op is Ops.CONST: root_src, arg = "CONST", idx.arg + else: root_src, arg = idx, 0 + if len(midx.src[i].src) == 3: root_src = (midx.src[i].src[2], root_src) + offsets_rootsrc[root_src].setdefault(arg, []).append(i) + + # the buf.dtype is always a pointer + ptrdtype = cast(PtrDType, buf.dtype) + + # then rewrite everything we can into groups + ret = [] + idxs: list[int|None] = [None]*vec.dtype.count + global_offset = 0 + for offsets in offsets_rootsrc.values(): + grouped_offsets = [[x for _,x in group] for _,group in itertools.groupby(enumerate(sorted(offsets.keys())), lambda x: x[1]-x[0])] + for grp in grouped_offsets: + # get the index offset for this element. using [0] is okay, because they are the same + lidx = midx.src[offsets[grp[0]][0]] + if len(grp) > 1: lidx = lidx.cast(ptrdtype.base.vec(len(grp)).ptr(size=ptrdtype.size, local=ptrdtype.local)) + # set the idxs of the output + for i,g in enumerate(grp): + for oo in offsets[g]: idxs[oo] = global_offset+i + # add this lidx to the CAT + ret.append(lidx) + global_offset += len(grp) + assert None not in idxs, f"some idxs are missing {idxs}" + # this base thing is for image, we want the CAT to be a normal pointer + post_cat = UOp(Ops.PTRCAT, ptrdtype.base.ptr(size=ptrdtype.size, local=ptrdtype.local).vec(vec.dtype.count), tuple(ret)) + return post_cat.gep(tuple(cast(list[int], idxs))) + +def cat_after_store(cat:UOp, data:UOp): + # TODO: this is written in many places + offset = 0 + ret = [] + for s in cat.src: + ret.append(s.store(data.gep(tuple(range(offset, offset+s.dtype.count))))) + offset += s.dtype.count + return UOp.sink(ret[0], *ret[1:]) + +def gep_on_store(gep:UOp, st:UOp): + # NOTE: we need to invert the gep here, but it may be an expanding gep + # fake argsort. TODO: handle duplicates + a = {} + for i,x in enumerate(gep.arg): a[x] = i + new_arg = tuple(x[1] for x in sorted(a.items())) + return UOp(Ops.STORE, src=(gep.src[0], st.gep(new_arg))) + +load_store_folding = PatternMatcher([ + (UPat(Ops.INDEX, src=(UPat(Ops.VECTORIZE, src=UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL), name="buf")), UPat.var("vec"))), expand_index), + (UPat(Ops.INDEX, src=(UPat(Ops.VECTORIZE, src=UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL), name="buf")), UPat.var("vec"), + UPat.var("mask"))), expand_index), + # GEP after LOAD + (UPat(Ops.LOAD, src=(UPat(Ops.GEP, name="gep"),), name="ld", allow_any_len=True), + lambda gep, ld: ld.replace(dtype=ld.dtype.scalar().vec(gep.dtype.count), src=(gep.src[0],)+ld.src[1:]).gep(gep.arg)), + # GEP on data of STORE + (UPat(Ops.STORE, src=(UPat(Ops.GEP, name="gep"), UPat.var("st"))), gep_on_store), + # put PTRCAT after LOAD + (UPat(Ops.LOAD, src=(UPat(Ops.PTRCAT, name="cat"),), name="ld", allow_any_len=True), + lambda cat,ld: UOp(Ops.CAT, ld.dtype, tuple(ld.replace(dtype=x.dtype.base, src=(x,)+ld.src[1:]) for x in cat.src))), + # put PTRCAT after STORE + (UPat(Ops.STORE, src=(UPat(Ops.PTRCAT, name="cat"), UPat(name="data"))), cat_after_store), +]) + +# ***** optional patterns ***** + +@functools.lru_cache(None) +def magicgu(vmax:int, d:int) -> tuple[int,int]: + # calculate m,s such that x//d == (x*m) >> s for all 0 <= x <= vmax, d>0; adapted from Hacker's Delight, Chapter 10 + nc = (vmax+1)//(d) * d - 1 + nbits = vmax.bit_length() + for s in range(0, 2*nbits + 1): + if 2**s > nc*(d - 1 - (2**s - 1) % d): + m = (2**s + d - 1 - (2**s - 1) % d)//d + return m, s + assert False + +def fast_idiv(ctx: Renderer|None, x: UOp, d: int) -> UOp|None: + # idiv is truncated division, but arithmatic shift is floored division, so can only do non-negative numbers! + if x.vmin<0: return None + sign = 1 if d > 0 else -1 + m,s = magicgu(vmax := min(x.vmax, dtypes.max(x.dtype)), abs(d)) + if m * vmax <= dtypes.max(x.dtype): return sign * ((x*m) >> s) + # promo_lattice needs to return an unsigned type + if ctx is not None and dtypes.is_int(next_dtype := promo_lattice[x.dtype][-1]) and is_dtype_supported(next_dtype, ctx.device): + if m * vmax <= dtypes.max(next_dtype): return sign * ((x.cast(next_dtype)*m) >> s).cast(x.dtype) + return None + +powers_of_two = {2**i:i for i in range(64)} +@functools.cache +def get_late_rewrite_patterns(ops, force_transcendental=False): + pat: list[tuple[UPat, Callable]] = [(UPat(op, dtype=TRANSCENDENTAL_SUPPORTED_DTYPES, src=(UPat.var("d"),)), f) for op,f in \ + ((Ops.EXP2, xexp2), (Ops.LOG2, xlog2), (Ops.SIN, xsin)) if op not in ops or force_transcendental] + # rewrite SQRT to xpow 0.5 + if Ops.SQRT not in ops: pat.append((UPat(Ops.SQRT, src=UPat.var("d")), lambda d: xpow(d, d.const_like(0.5)))) + # rewrite MOD to AND (which should always be supported, but not for generic in tests): x % (2**y) -> x & (2**y-1) + if Ops.AND in ops: pat += [(UPat.var("x", dtypes.ints)%UPat.cvar("c"), lambda x,c: x & (c.arg-1) if c.arg in powers_of_two else None)] + # rewrite MUL/IDIV to SHL+SHR: x*(2**y) -> shl(x,y) and x//(2**y) -> shr(x,y) + if Ops.SHL in ops: pat += [(UPat.var("x", dtypes.ints)*UPat.cvar("c"), lambda c,x: x << v if (v:=powers_of_two.get(c.arg, 0)) else None)] + if Ops.SHR in ops: + # no reason to check x>=0 for uints + pat += [(UPat.var("x", dtypes.uints)//UPat.cvar("c"), lambda x,c: x >> v if (v:=powers_of_two.get(c.arg, 0)) else None)] + pat += [(UPat.var("x", dtypes.sints)//UPat.cvar("c"), lambda x,c: x >> v if (v:=powers_of_two.get(c.arg, 0)) and resolve(x>=0,False) else None)] + if not getenv("DISABLE_FAST_IDIV"): + pat += [(UPat.var("x", dtypes.ints)//UPat.cvar("d"), lambda ctx, x, d: fast_idiv(ctx, x, d.arg))] + pat += [(UPat.var("x", dtypes.ints)%UPat.cvar("d"), lambda ctx, x, d: x - d*f if (f:=fast_idiv(ctx, x, d.arg)) is not None else None)] + if Ops.NEG in ops: + pat += [(UPat.var('x')*-1, lambda x: x.alu(Ops.NEG))] + if Ops.SUB in ops: pat += [(UPat.var('x')+UPat.var('y').alu(Ops.NEG), lambda x,y: x.alu(Ops.SUB, y))] + if Ops.MULACC in ops: pat += [(UPat.var('a')*UPat.var('b')+UPat.var('c'), lambda a,b,c: a.alu(Ops.MULACC, b, c))] + return PatternMatcher(pat) + +# *** correct load/store *** + +def split_load_store(ctx:Renderer|None, ls:UOp, idx:UOp): + # this splits loads and stores into multiple chunks + + # if there's only one element to load/store, no splitting needed + if (sz:=ls.src[0].dtype.count) == 1: return None + buf = idx.src[0] + + # determine fold lengths + lengths = [] + must_divide = True + if ctx is not None and ctx.device == "DSP": + lengths = [128,64,32,16,8,4] + must_divide = False + elif buf.dtype.base != dtypes.float and buf.dtype.base != dtypes.half and not isinstance(buf.dtype, ImageDType): + pass + elif isinstance(buf.dtype, ImageDType): + lengths = [4] + elif ctx is not None and ctx.supports_float4: + # TODO: a better way to get this than ctx + lengths = [8,4,2] if buf.dtype.base == dtypes.half and getenv("ALLOW_HALF8") else ([16,8,4,2] if AMX else [4,2]) + lengths.append(1) # worst case, it's not folded + + # filter fold lengths that don't divide + if must_divide: lengths = [x for x in lengths if idx.src[1].divides(x) is not None] + + # split based on the fold lengths + global_offset = 0 + ret = [] + ptrdtype = cast(PtrDType, buf.dtype) + while global_offset < sz: + # with 1 at the end of the lengths list, this will always hit + for fold_length in lengths: + if global_offset+fold_length > sz: continue + lidx = buf.index(idx.src[1] + global_offset, idx.src[2] if len(idx.src) > 2 else None) + if fold_length > 1: lidx = lidx.cast(ptrdtype.base.vec(fold_length).ptr(size=ptrdtype.size, local=ptrdtype.local)) + if ls.op is Ops.STORE: ret.append(ls.replace(src=(lidx,ls.src[1].gep(tuple(range(global_offset, global_offset+fold_length))))+ls.src[2:])) + else: ret.append(ls.replace(src=(lidx,)+ls.src[1:], dtype=ls.dtype.scalar().vec(fold_length))) + global_offset += fold_length + break + + # if it wasn't split, we return None. otherwise we CAT them + return UOp(Ops.CAT, ls.dtype, tuple(ret)) if len(ret) > 1 else None + +def image_fixup(ls:UOp): + # normal image load or store, with the CAST from expand_index + if ls.src[0].op is Ops.CAST and isinstance(image_dtype:=ls.src[0].src[0].dtype, ImageDType): + assert ls.src[0].dtype.count == 4, "image must be casted to 4" + idx = ls.src[0].src[0] + oidx = UOp(Ops.VECTORIZE, dtypes.int.vec(2), ((idx.src[1] // 4) % image_dtype.shape[1], (idx.src[1] // (4*image_dtype.shape[1])))) + idx = idx.replace(src=(idx.src[0], oidx)+idx.src[2:]) + return ls.replace(src=(idx,)+ls.src[1:]) + + # this is an unprocessed image without a cast, aka unfoldable image load. this doesn't work for stores + if isinstance(image_dtype:=ls.src[0].dtype, ImageDType) and ls.src[0].src[1].dtype != dtypes.int.vec(2): + assert ls.op is Ops.LOAD, "if an image store isn't upcasted to 4, we can't store it" + idx = ls.src[0] + id4 = idx.src[1] % 4 + oidx = UOp(Ops.VECTORIZE, dtypes.int.vec(2), ((idx.src[1] // 4) % image_dtype.shape[1], (idx.src[1] // (4*image_dtype.shape[1])))) + idx = idx.replace(src=(idx.src[0], oidx)+idx.src[2:]) + vec_load = ls.replace(dtype=ls.dtype.vec(4), src=(idx,)+ls.src[1:]) + return functools.reduce(lambda ret, i: id4.ne(i).where(ret, vec_load.gep(i)), range(4), ls.const_like(float('nan'))) + + return None + +correct_load_store = PatternMatcher([ + # split LOAD/STORE + (UPat((Ops.LOAD, Ops.STORE), src=(UPat(Ops.INDEX, name="idx").cast(),), name="ls", allow_any_len=True), split_load_store), + # image indexing, including unfoldable images + (UPat((Ops.LOAD, Ops.STORE), name="ls"), image_fixup), +]) + +# *** uop expander *** + +# TODO: there's a lot shared with gep_through_wmma here +def no_vectorized_wmma(wmma:UOp): + out_sz = prod(x[1] for x in wmma.arg[6][-1]) + if wmma.dtype.count == out_sz: return None + tsrcs = [] + for s,sz in zip(wmma.src, wmma.arg[6]): + ssz = prod(x[1] for x in sz) + tsrcs.append([s.gep(tuple(range(grp, grp+ssz))) for grp in range(0, s.dtype.count, ssz)]) + wmmas = [UOp(Ops.WMMA, wmma.dtype.scalar().vec(out_sz), tsrc, wmma.arg) for tsrc in zip(*tsrcs)] + wmma_ex = flatten([[e.gep(i) for i in range(out_sz)] for e in wmmas]) + return UOp(Ops.VECTORIZE, wmma.dtype, tuple(wmma_ex)) + +def no_vectorized_alu(alu:UOp): + if alu.dtype.vcount == 1: return None + alus = tuple(UOp(alu.op, alu.dtype.scalar(), tuple(s.gep(i) for s in alu.src), alu.arg) for i in range(alu.dtype.vcount)) + return UOp(Ops.VECTORIZE, alu.dtype, alus) + +def no_vectorized_acc(acc:UOp): + if acc.dtype.count == 1: return None + alus = tuple(UOp(acc.op, acc.dtype.scalar(), + tuple(s.gep(i) if j == 0 else s for j,s in enumerate(acc.src)), acc.arg+(i,)) for i in range(acc.dtype.count)) + return UOp(Ops.VECTORIZE, acc.dtype, alus) + +devectorize = PatternMatcher([ + # no ALU on vectorized dtypes + (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.ASSIGN), name="alu"), no_vectorized_alu), + (UPat(Ops.WMMA, name="wmma"), no_vectorized_wmma), + (UPat(Ops.DEFINE_ACC, name="acc"), no_vectorized_acc), +]) + +pm_render = PatternMatcher([ + # for rendering, we use explicit VECTORIZE + (UPat(Ops.CONST, name='c'), + lambda c: UOp(Ops.VECTORIZE, c.dtype, (UOp.const(c.dtype.scalar(), c.arg),)*c.dtype.vcount) if c.dtype.vcount > 1 else None), + (UPat(Ops.VCONST, name='c'), lambda c: UOp(Ops.VECTORIZE, c.dtype, tuple(UOp.const(c.dtype.scalar(), x) for x in c.arg))), + (UPat(Ops.GEP, name='gep'), lambda gep: UOp(Ops.VECTORIZE, gep.dtype, tuple(gep.src[0].gep(x) for x in gep.arg)) if len(gep.arg) > 1 else None), + (UPat(Ops.GEP, name='gep'), lambda gep: gep.src[0] if gep.src[0].dtype.vcount == 1 and gep.arg == (0,) else None), + (UPat(Ops.VECTORIZE, src=(UPat(name='x'),)), lambda x: x), + # give any loads that are masked an alt value + (UPat(Ops.LOAD, src=(UPat(Ops.INDEX, src=(UPat(), UPat(), UPat())).or_casted(),), allow_any_len=True, name="x"), + lambda x: x.replace(src=(x.src[0], x.const_like(0))+x.src[1:]) if len(x.src) == 1 or x.src[1].op is Ops.CUSTOM else None), + # gate any stores that aren't gated with ifs + (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat(src=(UPat(), UPat(), UPat(dtype=dtypes.bool)), name="idx").or_casted(), UPat()), name="store"), + lambda store,idx: UOp(Ops.STORE, src=store.src+(UOp(Ops.IF, src=(idx.src[2],)),))), +]) + +# *** Ops.REDUCE -> Ops.DEFINE_ACC+Ops.ASSIGN *** + +@dataclass +class ReduceContext: + acc_num: int = 0 + +def horizontal_reduce(inp:UOp, out_dtype:DType) -> list[UOp]: + # if this has a horizontal reduction component, do that first + if inp.dtype != out_dtype: + # NOTE: [0 1 2 3 4 5 6 7] -> [0+4, 1+5, 2+6, 3+7] + horizontal_amount = inp.dtype.count//out_dtype.count + return [inp.gep(tuple(range(i, inp.dtype.count, horizontal_amount))) for i in range(0, horizontal_amount)] + return [inp] + +def reduce_to_acc(ctx:ReduceContext, red:UOp): + inp, reduce_range = red.src[0], red.src[1:] + lst = horizontal_reduce(inp, red.dtype) + assert all(x.dtype == red.dtype for x in lst), f"horizontal reduction mismatch {lst[0].dtype} != {red.dtype}" + # if we have a range + if len(reduce_range) != 0: + acc = UOp(Ops.DEFINE_ACC, red.dtype, (red.const_like(identity_element(red.arg, red.dtype.scalar())),) + tuple(reduce_range), (ctx.acc_num,)) + lst = [acc] + lst # put acc as the first element + ctx.acc_num += 1 + ret = functools.reduce(lambda x,y: x.alu(red.arg, y), lst) + return acc.assign(ret) if len(reduce_range) != 0 else ret + +def no_vectorized_reduce(inp:UOp, red:UOp): + if inp.dtype != red.dtype: + red = red.replace(src=(functools.reduce(lambda x,y: x.alu(red.arg, y), horizontal_reduce(inp, red.dtype)),)+red.src[1:]) + if red.dtype.vcount == 1: return red + # no_vectorize_alu ignoring ranges + if red.dtype.vcount == 1: return None + alus = tuple(UOp(red.op, red.dtype.scalar(), (red.src[0].gep(i),)+red.src[1:], red.arg) for i in range(red.dtype.vcount)) + return UOp(Ops.VECTORIZE, red.dtype, alus) + +def reduce_rangeless(red:UOp): + # TODO: share code with reduce_unparented + if red.arg not in {Ops.ADD, Ops.MAX}: return None + if red.src[0].dtype != red.dtype: return None + if any(x.op in {Ops.RANGE} for x in red.src[0].toposort()): return None + ret = red.src[0] + if red.arg is Ops.ADD: + for r in red.src[1:]: + ret = ret * r.src[0].cast(ret.dtype.scalar()).broadcast(ret.dtype.count) + return ret + +def no_range(u:UOp) -> bool: return not any(x.op is Ops.RANGE for x in u.sparents) + +pm_reduce_collapse = PatternMatcher([ + # lift x+y out of reduce on lt + ((UPat.var("x")+UPat.var("y")) < UPat.var("c"), lambda x,y,c: (x < (c-y)) if no_range(y) and no_range(c) else None), + # lift x*y out of reduce + ((UPat.var("x")*UPat.var("y")) < UPat.var("c"), + lambda x,y,c: (x < ((c+y-1) // y)) if no_range(y) and no_range(c) and y.vmin > 0 else None), + # lift x+y out of reduce on ne + ((UPat.var("x")+UPat.var("y")) != UPat.var("c"), lambda x,y,c: (x != (c-y)) if no_range(y) and no_range(c) else None), + # fold the range + ((UPat(Ops.RANGE, name="r") < UPat.var("cut")).where(0, UPat.cvar("val")).reduce(arg=Ops.ADD, allow_any_len=True), + lambda r,cut,val: (r.src[0]-cut).maximum(0).minimum(r.src[0]).cast(val.dtype) * val), + ((UPat(Ops.RANGE, name="r") < UPat.var("cut")).where(UPat.cvar("val"), 0).reduce(arg=Ops.ADD, allow_any_len=True), + lambda r,cut,val: cut.maximum(0).minimum(r.src[0]).cast(val.dtype) * val), + # REDUCE on ADD + ((UPat.var("x")+UPat.var("y")).reduce(arg=Ops.ADD, allow_any_len=True, name="r"), + lambda x,y,r: x.reduce(*r.src[1:], arg=Ops.ADD) + y.reduce(*r.src[1:],arg=Ops.ADD)), + # MUL casted bool + ((UPat.var("x") * UPat.var("gate", dtype=dtypes.bool).cast().or_broadcasted(name="b")), + lambda x,gate,b=None: gate.broadcast(x.dtype.count).where(x, 0) if b is not None else gate.where(x, 0)), + # WHERE on LOAD (works on max too) + (UPat.var("gate").where(UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("idx"))).load(), 0).reduce(arg=Ops.ADD, allow_any_len=True), + lambda buf,idx,gate: buf.index(idx, gate).load()), + (UPat.var("gate").where(0, UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("idx"))).load()).reduce(arg=Ops.ADD, allow_any_len=True), + lambda buf,idx,gate: buf.index(idx, gate.logical_not()).load()), + # INDEX on RANGE / gated RANGE + (UPat.var("buf").index(UPat.var("expr"), UPat.var("idx").eq(UPat(Ops.RANGE, name="r").or_casted())), + lambda buf,r,idx,expr: buf.index(expr.substitute({r:idx.cast(r.dtype)}), (idx.cast(r.dtype) >= 0) & (idx.cast(r.dtype) < r.src[0]))), + # AND on WHERE + ((UPat.any(UPat(Ops.DEFINE_VAR, name="x"), UPat(Ops.DEFINE_VAR).gep(name="x")) & UPat.var("y")) \ + .where(UPat.cvar("c"), 0).reduce(arg=Ops.ADD, allow_any_len=True, name="r"), + lambda x,y,c,r: y.where(c, 0).reduce(*r.src[1:], arg=Ops.ADD)*x.cast(c.dtype)), + # remove REDUCEs that no longer have a RANGE in the src + (UPat(Ops.REDUCE, name="red"), reduce_rangeless), + # devectorize REDUCE + (UPat(Ops.VECTORIZE, name="inp").reduce(name="red", allow_any_len=True), no_vectorized_reduce), + # index/load/where. TODO: this is more aggressive than needed + (UPat((Ops.INDEX, Ops.LOAD, Ops.WHERE), name="alu"), no_vectorized_alu), +])+sym + +def reduce_collapse(red:UOp): + included, not_included = partition(red.parents, lambda x: any(y in x.sparents for y in red.src[1:])) + if any(x.op in {Ops.STORE, Ops.REDUCE} for x in included): return None + replaces: dict[UOp, UOp] = {} + for u in included: + for s in u.src: + if s in not_included and s not in replaces and s.op not in {Ops.CONST, Ops.VCONST, Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL, Ops.DEFINE_VAR}: + replaces[s] = UOp(Ops.DEFINE_VAR, dtype=s.dtype, arg=(f'in{len(replaces)}', s.vmin, s.vmax)) + collapse_fxn = red.substitute(replaces) + sink = graph_rewrite(collapse_fxn, pm_reduce_collapse, name="reduce_collapse") + # TODO: why is REDUCE needed here and just RANGE isn't enough? + if any(x.op in {Ops.REDUCE, Ops.RANGE} for x in sink.toposort()): return None + return sink.substitute({v:k for k,v in replaces.items()}) + +def reduce_unparented(red:UOp): + if red.arg not in {Ops.ADD, Ops.MAX}: return None + reduce_parented, reduce_unparented = partition(red.src[1:], lambda x: x in red.src[0].sparents) + if len(reduce_unparented) == 0: return None + ret = red.replace(src=(red.src[0],)+tuple(reduce_parented)) if len(reduce_parented) or red.dtype != red.src[0].dtype else red.src[0] + if red.arg is Ops.ADD: + for r in reduce_unparented: ret = ret * r.src[0].cast(ret.dtype.scalar()).broadcast(ret.dtype.count) + return ret + +pm_reduce = PatternMatcher([ + # remove any ranges from a REDUCE that aren't referenced in the reduce source + (UPat(Ops.REDUCE, name="red"), reduce_unparented), + # remove REDUCE without loads (generic arange opt / indexing). TODO: support multi range + (UPat(Ops.REDUCE, src=(UPat(), UPat()), name="red"), reduce_collapse), + # REDUCE -> DEFINE_ACC+ASSIGN + (UPat(Ops.REDUCE, name="red"), reduce_to_acc), + # tensor core built in accumulate + (UPat(Ops.WMMA, name="wmma") + UPat.var("add"), + lambda add, wmma: UOp(wmma.op, wmma.dtype, (wmma.src[0], wmma.src[1], wmma.src[2]+add), wmma.arg)), +])+sym diff --git a/tinygrad_repo/tinygrad/codegen/expander.py b/tinygrad_repo/tinygrad/codegen/expander.py new file mode 100644 index 0000000000..be59b4cdc8 --- /dev/null +++ b/tinygrad_repo/tinygrad/codegen/expander.py @@ -0,0 +1,138 @@ +# this converts a lowerer program into a vectorized program + +import functools, itertools, operator +from tinygrad.helpers import AMX, dedup, flatten, all_same, prod +from tinygrad.uop.ops import UOp, Ops, UPat, PatternMatcher, GroupOp + +def _expand_arg_to_idx(args:tuple[tuple[int, int], ...], rpk:dict[int, int]) -> int: + idx, mul = 0, 1 + for axis,m in args[::-1]: + idx += rpk[axis] * mul + mul *= m + return idx + +def _choices_from_args(args:tuple[tuple[int, int], ...]) -> list[dict[int, int]]: + return [dict(x) for x in itertools.product(*[zip(itertools.repeat(axis), range(m)) for axis,m in args])] + +@functools.cache +def _swizzle_args(cargs:tuple[tuple[int, int], ...], eargs:tuple[tuple[int, int], ...], exclude_args:tuple[int, ...]) -> list[int]: + return [_expand_arg_to_idx(eargs, {**rpk, **{x:0 for x in exclude_args}} if exclude_args else rpk) for rpk in _choices_from_args(cargs)] + +def do_expand(root:UOp): + expands = [x for x in root.src if x.op is Ops.UNROLL] + if len(expands) == 0: return None + # NOTE: we 0 out the reduce axis for WMMA. in theory they should all be the same, but is this always correct? + exclude_args = tuple(dedup(root.arg[-1] + tuple(y[0] for y in flatten(root.arg[-2])))) if root.op is Ops.WMMA else () + if all_same(expands_args:=[x.arg for x in expands]) and len(exclude_args) == 0: + # if there's only one expand arg, it's okay to use it (optimization) + expand_args = expands[0].arg + else: + # otherwise, we sort them and GEP + expand_args = tuple(x for x in sorted(dedup(flatten(expands_args))) if x[0] not in exclude_args) + expand_sz = prod([x[1] for x in expand_args]) + new_srcs = [] + for i,src in enumerate(root.src): + if src.op is Ops.UNROLL: + if root.op is Ops.IF and i == 0: + # IF means OR on first arg to IF + new_srcs.append(functools.reduce(operator.__or__, [src.src[0].gep(i) for i in range(expand_sz)])) + elif expand_args == src.arg: + # just remove the expand + new_srcs.append(src.src[0]) + else: + lst = _swizzle_args(expand_args, src.arg, exclude_args) + # if the base dtype is > 1, put those at the end + if src.dtype.count > 1: lst = flatten([[i*src.dtype.count+j for j in range(src.dtype.count)] for i in lst]) + new_srcs.append(src.src[0].gep(tuple(lst))) + else: + # non-UNROLL input + if root.op is Ops.IF: + # for the first arg of IF, just pass them through ignoring UNROLLS + new_srcs.append(src) + elif root.op is Ops.REDUCE and src.op is Ops.RANGE: + # for any range args of REDUCE, pass them through + new_srcs.append(src) + elif src.dtype.count > 1: + # put any input dtype > 1 grouped together + new_srcs.append(UOp(Ops.CAT, src.dtype.scalar().vec(expand_sz*src.dtype.count), (src,)*expand_sz)) + else: + # repeat the arg + new_srcs.append(src.broadcast(expand_sz)) + + new_arg = root.arg + if root.op is Ops.GEP: + assert root.dtype.count == 1 + # is this right? + new_arg = tuple(range(root.arg[0], new_srcs[0].dtype.count, new_srcs[0].dtype.count // expand_sz)) + nsrc = UOp(root.op, root.dtype.scalar().vec(root.dtype.count*expand_sz), tuple(new_srcs), new_arg) + return UOp(Ops.UNROLL, root.dtype, (nsrc,), expand_args) + +def do_contract(con:UOp): + ex = con.src[0] + # CONTRACT without UNROLL repeats the element VECTORIZED + if ex.op is not Ops.UNROLL: return UOp(Ops.VECTORIZE, con.dtype, con.src*con.dtype.count) + # CONTRACT may remove several axes from UNROLL + assert con.dtype.count == prod([x[1] for x in con.arg]), "dtype is wrong" + idxs = [] + for rpk in _choices_from_args(new_ex_args:=tuple(x for x in ex.arg if x not in con.arg)): + idxs += [_expand_arg_to_idx(ex.arg, {**rpk, **lrpk}) for lrpk in _choices_from_args(con.arg)] + return UOp(Ops.UNROLL, con.dtype, (ex.src[0].gep(tuple(idxs)),), new_ex_args) + +expander = PatternMatcher([ + # double expand + (UPat(Ops.UNROLL, name="outer", src=(UPat(Ops.UNROLL, name="inner"),)), + lambda outer, inner: UOp(Ops.UNROLL, outer.dtype, (inner.src[0],), inner.arg+outer.arg)), + # do expansion + (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.GEP, Ops.WMMA, Ops.LOAD, Ops.STORE, Ops.INDEX, Ops.ASSIGN, + Ops.VECTORIZE, Ops.IF, Ops.REDUCE), name="root", custom_early_reject=set([Ops.UNROLL])), do_expand), + (UPat(Ops.CONTRACT, name="con"), do_contract), + # vectorize DEFINE_ACC + (UPat(Ops.VECTORIZE, src=UPat(Ops.DEFINE_ACC, name="acc"), name="v"), + lambda acc,v: acc.replace(dtype=v.dtype, src=(acc.src[0].broadcast(v.dtype.count),)+acc.src[1:])), + # BARRIERs aren't actually expanded + (UPat(Ops.BARRIER, src=(UPat(Ops.UNROLL, name="ex"),)), + lambda ex: UOp(Ops.UNROLL, src=(UOp(Ops.BARRIER, src=ex.src),)*len(ex.src), arg=ex.arg)), + # empty UNROLL is NOOP + (UPat(Ops.UNROLL, src=(UPat.var('x'),), arg=()), lambda x: x), + # UNROLL GEP (needed for WMMA, generalize this) -> vectorized ALU + (UPat(Ops.UNROLL, name="ex", src=tuple(UPat.var('x').gep(i)+UPat.var('y').gep(i) for i in range(256 if AMX else 8))), + lambda ex,x,y: UOp(Ops.UNROLL, ex.dtype, tuple((x+y).gep(i) for i in range(256 if AMX else 8)), ex.arg)), +]) + +def create_gate(root:UOp) -> UOp|None: + @functools.cache + def _gate_srcs(u:UOp, gate:UOp) -> UOp: + if u.op is Ops.BARRIER: return u + if u.op is Ops.LOAD and u.src[-1].op is Ops.BARRIER: + return UOp(u.op, u.dtype, u.src[:-1]+(UOp(Ops.IF, src=(gate, u.src[-1])),), arg=u.arg) + return u if (replace_source:=tuple(_gate_srcs(x, gate) for x in u.src)) == u.src else UOp(u.op, u.dtype, replace_source, u.arg) + idx = root.src[0] + if idx.op is Ops.CAST: idx = idx.src[0] + return None if idx.op is not Ops.INDEX or len(idx.src) == 2 or (ret:=_gate_srcs(root, idx.src[2])) is root else ret + +migrate_indexing = PatternMatcher([ + # create gate MUST BE BEFORE expander + (UPat(Ops.STORE, name="root"), create_gate), +]) + +# **** IGNORE support **** + +pm_store_ignore = PatternMatcher([ + (UPat().index(UPat(), UPat(name="mask")).store(UPat()).named("store"), + lambda store,mask: store.replace(src=(store.src[0], UOp(Ops.IGNORE, src=(store.src[1], mask)))) if store.src[1].op is not Ops.IGNORE else None), +]) + +pm_move_ignore = PatternMatcher([ + # IGNORE on SELF is nothing + (UPat(Ops.IGNORE, src=(UPat(name="x"), UPat(name="x"))), lambda x: x.const_like(True)), + # IGNORE on a CONST is nothing + (UPat(Ops.IGNORE, src=(UPat((Ops.CONST, Ops.VCONST), name="c"), UPat())), lambda c: c), + # move the IGNOREs + (UPat(Ops.IGNORE, src=(UPat((*GroupOp.ALU, Ops.CAST, Ops.VECTORIZE), name="alu"), UPat.var("mask")), name="ig"), + lambda ig,alu,mask: alu.replace(src=tuple(UOp(Ops.IGNORE, x.dtype, (x, mask)) for x in alu.src))), +]) + +pm_delete_ignore = PatternMatcher([ + # IGNORE on SELF is nothing + (UPat(Ops.IGNORE, src=(UPat(name="x"), UPat())), lambda x: x), +]) diff --git a/tinygrad_repo/tinygrad/codegen/heuristic.py b/tinygrad_repo/tinygrad/codegen/heuristic.py new file mode 100644 index 0000000000..1f77339003 --- /dev/null +++ b/tinygrad_repo/tinygrad/codegen/heuristic.py @@ -0,0 +1,133 @@ +import itertools +from tinygrad.codegen.kernel import Kernel, Opt, OptOps, KernelOptError +from tinygrad.helpers import getenv, DEBUG, all_int, prod +from tinygrad.dtype import ImageDType +from tinygrad.uop.ops import Ops, resolve + +def hand_coded_optimizations(k:Kernel) -> list[Opt]: + # make a copy so it does not mutate the input + k = k.copy() + + # should use matvec - TODO: adjust/tune based on the wide vs tall/large vs small mat + MV_BLOCKSIZE, MV_THREADS_PER_ROW, MV_ROWS_PER_THREAD = getenv("MV_BLOCKSIZE", 4), getenv("MV_THREADS_PER_ROW", 8), getenv("MV_ROWS_PER_THREAD", 4) + if k.opts.has_local and getenv("MV",1) != 0 and (MV_BLOCKSIZE > 1 or MV_THREADS_PER_ROW > 1 or MV_ROWS_PER_THREAD > 1) and \ + k.reduceop is not None and k.reduceop.arg[0] is Ops.ADD and len(k.full_shape) >= 2 and k.opts.has_shared and \ + (mulop:=k.reduceop.src[0]).op is Ops.MUL and mulop.src[0].op is Ops.LOAD and mulop.src[1].op is Ops.LOAD: + st0, st1 = k.sts[k.bufs.index(mulop.src[0])], k.sts[k.bufs.index(mulop.src[1])] + strides0, strides1 = st0.real_strides(), st1.real_strides() + def has_expanded_axis(shape, strides): return any(resolve(s > 1) and not resolve(st != 0) for s,st in zip(shape,strides)) + if strides0[k.first_reduce] == 1 and not (has_expanded_axis(st0.shape, strides0) and has_expanded_axis(st1.shape, strides1)): + for global_idx in range(k.global_dims): + if k.full_shape[k.first_reduce]%MV_THREADS_PER_ROW == 0 and k.full_shape[global_idx]%(MV_BLOCKSIZE*MV_ROWS_PER_THREAD) == 0: + if DEBUG >= 3: + print(f"MATVEC: {k.full_shape=} {k.first_reduce=} {strides0=} {MV_BLOCKSIZE=} {MV_THREADS_PER_ROW=} {MV_ROWS_PER_THREAD=}") + if MV_THREADS_PER_ROW > 1: k.apply_opt(Opt(OptOps.GROUP, 0, MV_THREADS_PER_ROW)) + if MV_BLOCKSIZE > 1: k.apply_opt(Opt(OptOps.LOCAL, global_idx, MV_BLOCKSIZE)) + if MV_ROWS_PER_THREAD > 1: k.apply_opt(Opt(OptOps.UPCAST, global_idx, MV_ROWS_PER_THREAD)) + return k.applied_opts + + if k.opts.has_local and k.opts.has_shared and all_int(k.sts[0].shape[:k.first_reduce]): + # are we grouping? (requires local shape support) + if not [x for x in k.sts[0].unit_stride_axes() if x >= k.first_upcast and k.sts[0].shape[x]%4 == 0] and \ + k.first_reduce <= 2 and k.first_reduce < k.shape_len and prod(k.sts[0].shape[:k.first_reduce]) <= 2048: + # TODO: use 1024 if it's allowed in a smarter way + for sz in ([256, 16] if prod(k.sts[0].shape[:k.first_reduce]) <= 32 else [16]): + if all(st.shape[k.first_reduce] % sz == 0 or st.shape[k.first_reduce] == 1 for st in k.sts): + try: # may fail due to excessive smem usage + k.apply_opt(Opt(OptOps.GROUPTOP, 0, sz)) + break + except KernelOptError: pass + + # upcast float4 images + for buf_index,buf in enumerate(k.bufs): + unit_stride_axes_mul_4 = [i for i in k.sts[buf_index].unit_stride_axes(ignore_valid=True) if k.sts[buf_index].shape[i]%4 == 0] + if buf.src[0].dtype.__class__ is ImageDType: + #assert len(unit_stride_axes_mul_4) >= 1, f"needs a unit stride axis in {k.bufs[buf_index]}" + if len(unit_stride_axes_mul_4) and all(x < k.first_upcast for x in unit_stride_axes_mul_4): + if unit_stride_axes_mul_4[0] < k.first_reduce: + k.apply_opt(Opt(OptOps.UPCAST, unit_stride_axes_mul_4[0], 4)) + else: + k.apply_opt(Opt(OptOps.UNROLL, unit_stride_axes_mul_4[0]-k.first_reduce, 4)) + + # no more opt if we are grouping + if k.group_for_reduces: return k.applied_opts + + # **** below this line need to be optional and benchmarked **** + + # TODO: doing extra upcasts with images doesn't work for some reason (maybe has to do with to_image_idx) + # to trigger the above bug, remove prod(k.full_shape[k.first_upcast:]) from the below + # expression and run test/test_ops.py with IMAGE=2 + # if there are small dims with lots of valid masks, upcast them (they might be from Tensor.stack) + # this can be made much smarter + to_upcast: list[int] = [] + # upcast leading axes first (hack-ish for winograd; we actually want to upcast masked axes with low stride first) + for axis in range(k.first_reduce): + # we might want to be able to split axes that are masked, or refuse to merge them in simplify_merge_adjacent + # for now skip upcasting here if there is a symbolic axis + if isinstance(k.full_shape[axis], int) and k.full_shape[axis] <= 7 and any(st.axis_is_masked(axis) for st in k.sts) and \ + prod(k.full_shape[k.first_upcast:]) * prod(k.full_shape[j] for j in to_upcast) * k.full_shape[axis] <= 7 * 7: + if DEBUG >= 4: print(f"upcasting masked axis : {axis}") + to_upcast.append(axis) + for axis in to_upcast[::-1]: k.apply_opt(Opt(OptOps.UPCAST, axis, 0)) + + # potentially do more upcasts of non reduce axes based on a heuristic + is_dsp = k.opts is not None and k.opts.device == "DSP" + upcasted_axis: set[int] = set() + while resolve(prod(k.sts[0].shape[:k.first_reduce]) >= 1024): + xb_choices = [] + # consider all the non reduce axes, and a 3 or 4 reduce. (128 on the DSP) + for axis, upcast_amount in itertools.product(range(k.first_reduce), ([128] if not len(upcasted_axis) else []) if is_dsp else [3,4]): + # if we haven't upcasted it, it's not symbolic, it mods, and buffer has stride 0 on axis while having no stride 0 in the upcasted axis already + if axis not in upcasted_axis and isinstance(k.full_shape[axis], int) and k.full_shape[axis]%upcast_amount == 0 and \ + any(st.views[-1].strides[axis] == 0 and not any(x[1] == 0 for x in k.upcasted_axis(buf_index)) for buf_index, st in enumerate(k.sts)): + xb_choices.append((sum(st.views[-1].strides[axis]>0 for st in k.sts), + sum(st.views[-1].strides[axis] for st in k.sts), axis, upcast_amount)) + if xb_choices: + xb_choices = sorted(xb_choices) + if DEBUG >= 4: print(f"float4 merging axis : {xb_choices}") + k.apply_opt(Opt(OptOps.UPCAST, xb_choices[0][2], xb_choices[0][3])) + upcasted_axis.add(xb_choices[0][2]) + else: break + + # if last dim is small(ish) and it's a reduce dim, upcast the reduce (loop unrolling). no simplify needed since it's just an upcast. + if k.first_reduce < k.first_upcast and (prod(k.full_shape[k.first_upcast:]) <= 4 or \ + not any(x!=y for x,y in zip(k.sts[0].shape[k.first_upcast:], k.full_shape[k.first_upcast:]))) and \ + (k.upcasted == 0 or prod(k.full_shape[-k.upcasted:]) < 64): + if isinstance(s:=k.full_unupcasted_shape[-1], int) and s <= 32: # NOTE: cannot loop unroll symbolic axis + k.apply_opt(Opt(OptOps.UNROLL, len(k.full_unupcasted_shape)-1-k.first_reduce, 0)) + # if it's small, upcast a second reduce dimension too + if k.first_reduce < k.first_upcast and s <= 3 and isinstance(s2:=k.full_unupcasted_shape[-1], int) and s2 <= 3: + k.apply_opt(Opt(OptOps.UNROLL, len(k.full_unupcasted_shape)-1-k.first_reduce, 0)) + else: + for splits in [4]: + if k.full_unupcasted_shape[-1]%splits == 0: + k.apply_opt(Opt(OptOps.UNROLL, len(k.full_unupcasted_shape)-1-k.first_reduce, splits)) + break + + # if nothing at all is upcasted and it's easy to, do an upcast + for splits in [4]: + if k.upcasted == 0 and k.full_unupcasted_shape and k.full_unupcasted_shape[-1] % splits == 0: + k.apply_opt(Opt(OptOps.UPCAST, len(k.full_unupcasted_shape)-1, splits)) + + # **** local groups **** + + if k.opts.has_local: + if getenv("NOLOCALS") and k.local_dims == 0 and not k.group_for_reduces: + k.apply_opt(Opt(OptOps.NOLOCALS)) + else: + # prioritize making expand axes local + local_axis_ranking = [(any(k.sts[buf_index].views[-1].strides[axis] == 0 for buf_index in range(len(k.sts))), axis) \ + for axis in range(len(k.full_shape[:k.first_reduce]))] + to_local: list[tuple[int, int]] = [] + for _, axis in sorted(local_axis_ranking, key=lambda x: (-x[0], -x[1])): + local_size = prod(sz for _, sz in to_local) + local_sz: int|None = next((x for x in ([32] * (axis == 0) + [16,8,4,3,2]) if k.full_shape[axis] % x == 0 and local_size * x <= 128), None) + if local_sz is not None: to_local.append((axis, local_sz)) + deleted_shape = 0 + for axis, local_sz in sorted(to_local[:3]): + axis = axis - deleted_shape + will_delete_shape = local_sz == k.full_shape[axis] + k.apply_opt(Opt(OptOps.LOCAL, axis, local_sz)) + if will_delete_shape: deleted_shape += 1 + + return k.applied_opts \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/codegen/kernel.py b/tinygrad_repo/tinygrad/codegen/kernel.py index 7b9426d99c..9da24668db 100644 --- a/tinygrad_repo/tinygrad/codegen/kernel.py +++ b/tinygrad_repo/tinygrad/codegen/kernel.py @@ -1,51 +1,34 @@ from __future__ import annotations -import itertools, functools +import itertools, functools, math from dataclasses import dataclass from collections import defaultdict -from typing import Optional, cast, Final, DefaultDict, Callable, Sequence -from enum import Enum, auto +from typing import Optional, cast, Final, Callable, Sequence -from tinygrad.ops import GroupOp, KernelInfo, UOp, Ops, can_pad, print_uops, type_verify, resolve, Variable, sint, \ - graph_rewrite, track_rewrites, view_left +from tinygrad.uop.ops import GroupOp, KernelInfo, UOp, Ops, can_pad, resolve, Variable, sint, graph_rewrite, track_rewrites, print_uops +from tinygrad.uop.ops import PatternMatcher, smax +from tinygrad.uop.spec import type_verify, shape_spec from tinygrad.device import Device -from tinygrad.renderer import Renderer, TensorCore, ProgramSpec +from tinygrad.renderer import Renderer, TensorCore, ProgramSpec, Opt, OptOps from tinygrad.dtype import ImageDType -from tinygrad.helpers import all_same, colored, ansilen, dedup, getenv, prod, round_up, all_int, to_function_name, diskcache_put -from tinygrad.helpers import DEBUG, TC_OPT, USE_TC, AMX +from tinygrad.helpers import all_same, colored, ansilen, dedup, getenv, prod, round_up, all_int, to_function_name, diskcache_put, unwrap, ContextVar +from tinygrad.helpers import DEBUG, TC_SELECT, TC_OPT, AMX, CAPTURE_PROCESS_REPLAY from tinygrad.shape.shapetracker import ShapeTracker from tinygrad.shape.view import strides_for_shape -from tinygrad.codegen.linearize import linearize_uop -from tinygrad.codegen.uopgraph import full_graph_rewrite -from tinygrad.codegen.lowerer import rewrite_shapetracker_with_index, get_contraction - -class OptOps(Enum): - TC = auto(); UPCAST = auto(); UNROLL = auto(); LOCAL = auto() # noqa: E702 - GROUP = auto(); GROUPTOP = auto(); NOLOCALS = auto(); PADTO = auto(); SWAP = auto() # noqa: E702 - def __lt__(self, x:OptOps): return self.value < x.value +from tinygrad.codegen.lowerer import get_contraction +from tinygrad.engine.grouper import view_left +from tinygrad.codegen import full_rewrite class KernelOptError(Exception): pass def check(cond:bool, msg:str=""): if not cond: raise KernelOptError(msg) -@dataclass(frozen=True, order=True) -class Opt: - op: OptOps - axis: Optional[int] = None - amt: Optional[int] = None - def __repr__(self): return f"Opt(op={self.op}, axis={self.axis}, amt={self.amt})" - def real_axis(self, k:Kernel): - if self.axis is None: return -1 - if self.op is OptOps.UNROLL: return k.first_reduce+self.axis - if self.op in {OptOps.GROUP, OptOps.GROUPTOP}: return k.first_reduce+k.group_for_reduces+self.axis - return self.axis - @dataclass class TensorCoreOptions: axes: tuple[int, ...] # the location of the original N and M axes if still in the shape axes_exist: tuple[bool, ...] # true if the original N and M axes are still in the shape axis_pads: tuple[tuple[int, int], ...] - def fix_axes(self, removed_axis:int): # adjust the TC axes if necesssary when a dimension is removed + def fix_axes(self, removed_axis:int): # adjust the TC axes if necessary when a dimension is removed axes, axes_exist = list(self.axes), list(self.axes_exist) for tc_dim in [i for i in range(2) if axes_exist[i]]: if removed_axis < axes[tc_dim]: axes[tc_dim] -= 1 @@ -54,25 +37,18 @@ class TensorCoreOptions: class Kernel: def __init__(self, ast:UOp, opts:Optional[Renderer]=None): - if ast.op is Ops.SINK: self.ast = ast + assert ast.op is Ops.SINK, ast.op + self.ast = ast self.opts = opts if opts is not None else Device[Device.DEFAULT].renderer - try: uop_sts_map = verify_ast(self.ast) - except AssertionError as e: - print("INVALID AST") - print(self.ast) - raise e + # verify AST matches the spec + if __debug__: type_verify(list(self.ast.toposort()), shape_spec) - self.reduceops = [x for x in self.ast.toposort if x.op is Ops.REDUCE_AXIS] + self.reduceops = [x for x in self.ast.toposort() if x.op is Ops.REDUCE_AXIS] self.vars: list[Variable] = self.ast.variables() # NOTE: this requires a specific order with the [::-1], this is likely a bug - self.bufs: list[UOp] = [x for x in self.ast.toposort if x.op in GroupOp.Buffer][::-1] - - # get earlybufs, before any reduceops - earlybufs: list[UOp] = [x for reduceop in self.reduceops for x in reduceop.src[0].toposort if x.op in GroupOp.Buffer] - self.full_buf_index: int = self.bufs.index(earlybufs[0]) if earlybufs else 0 - # NOTE: full_shape can be wrong if there's a tree of reduces + self.bufs: list[UOp] = [x for x in self.ast.toposort() if x.op in GroupOp.Buffer][::-1] # create new shapetrackers inside this kernel, we will permute them self.sts: list[ShapeTracker] = [x.st_arg for x in self.bufs] @@ -80,8 +56,11 @@ class Kernel: # add the shapetrackers for each reduce # we use this to track which axes are reduced in each reduce for x in self.reduceops: - self.sts.append(uop_sts_map[x]) - self.sts.append(uop_sts_map[x.src[0]]) + self.sts.append(unwrap(x.st)) + self.sts.append(unwrap(x.src[0].st)) + + # add a shapetracker to the end to track the full shape, with 0 strides so it can merge + self.sts.append(ShapeTracker.from_shape(tuple([smax(*s) for s in zip(*[x.shape for x in self.sts])]), (0,)*self.shape_len)) # move all reduce axes to the end reduce = list(enumerate(zip(self.full_shape, self.output_shape))) @@ -109,8 +88,8 @@ class Kernel: ret.opts, ret.ast = self.opts, self.ast # things downstream of the AST - ret.reduceops, ret.vars, ret.bufs, ret.full_buf_index = self.reduceops, self.vars, self.bufs, self.full_buf_index - ret.sts = self.sts[:len(ret.bufs)+len(ret.reduceops)*2] # NOTE: must redo the local buffers with TC in beam + ret.reduceops, ret.vars, ret.bufs = self.reduceops, self.vars, self.bufs + ret.sts = self.sts[:] # parameters for optimizations ret.applied_opts, ret.group_for_reduces, ret.upcasted, ret.local_dims, ret.dont_use_locals = \ @@ -122,9 +101,6 @@ class Kernel: @property def membufs(self) -> list[UOp]: return dedup([x.src[0] for x in self.bufs if x.op in {Ops.LOAD, Ops.STORE}]) - # TODO: these need more tests or it might silently be no-op - def float4_axis(self, i:int): return [x-self.first_upcast for x in self.sts[i].unit_stride_axes() if x >= self.first_upcast and self.sts[i].shape[x]%4 == 0] # noqa: E501 - def upcasted_axis(self, i:int) -> list[tuple[int, Optional[sint], bool]]: upcasted_shape, upcasted_stride = self.sts[i].shape[self.first_upcast:], self.sts[i].real_strides()[self.first_upcast:] assert all_int(upcasted_shape), f"cannot upcast a symbolic amount {upcasted_shape=}" @@ -145,7 +121,7 @@ class Kernel: def output_shape(self) -> tuple[sint, ...]: return self.sts[0].shape @property - def full_shape(self) -> tuple[sint, ...]: return self.sts[self.full_buf_index].shape + def full_shape(self) -> tuple[sint, ...]: return self.sts[-1].shape @property def full_unupcasted_shape(self) -> tuple[sint, ...]: return self.full_shape[:self.first_upcast] @@ -291,33 +267,31 @@ class Kernel: if DEBUG >= 3: print("TENSOR CORES", axis_buf0, axis_buf1, tc) return TensorCoreOptions(axes=(s0, s1, s2), axes_exist=(True, True), axis_pads=axis_pads) - def _apply_tc_opt(self, use_tensor_cores:int, axis:int, opt_level:int) -> bool: + def _apply_tc_opt(self, use_tensor_cores:int, axis:int, tc_select:int, opt_level:int) -> bool: if use_tensor_cores and self.reduceop is not None and self.reduceop.arg[0] is Ops.ADD: - for tc in self.opts.tensor_cores: + tensor_cores = self.opts.tensor_cores if tc_select == -1 else [self.opts.tensor_cores[tc_select]] + for tc in tensor_cores: tensor_core_opts = [self._create_tc_opts(reduceop, tc, axis, opt_level) for reduceop in self.reduceops] # can only fuse reduces with the same tc options assert all_same(tensor_core_opts) if tensor_core_opts[0] is None: continue - # tensor core -- unroll the reduce dim, upcast input and local the correct thread pattern self.tensor_core_opts = tc_opts = tensor_core_opts[0] # attempt to pad the tensor axes that require it try: for axis, dim in tc_opts.axis_pads: self.apply_opt(Opt(OptOps.PADTO, axis, dim), append_opt=False) # PADTO might fail except KernelOptError: continue - for tc_dim, amt in tc.reduce_axes: self.apply_opt(Opt(OptOps.UNROLL,tc_opts.axes[2]-self.first_reduce,amt), append_opt=False) - for opt in tc.opts_seq: - if opt == "UP": - for tc_dim, amt in tc.early_upcast_axes: self.apply_opt(Opt(OptOps.UPCAST,tc_opts.axes[tc_dim],amt), append_opt=False) - elif opt == "LC": - for tc_dim, amt in tc.threads: self.apply_opt(Opt(OptOps.LOCAL,tc_opts.axes[tc_dim],amt), append_opt=False) + # tensor core -- unroll the reduce dim (K), upcast and local the inner and outer dims (N, M) + for dim, amt in tc.get_reduce_axes(): self.apply_opt(Opt(OptOps.UNROLL, tc_opts.axes[2]-self.first_reduce, amt), append_opt=False) + for opt in tc.opts: self.apply_opt(Opt({"u":OptOps.UPCAST, "l":OptOps.LOCAL}[opt[0]], tc_opts.axes[int(opt[1])], 2), append_opt=False) self.tensor_core = tc self.use_tensor_cores = use_tensor_cores # TC=2 will do the shape ops without the WMMA return True return False - def apply_tensor_cores(self, use_tensor_cores=1, extra_opts:Optional[list[Opt]]=None, axis:int=0, tc_opt:Optional[int]=None) -> bool: - """ Attempts to apply a tensor core optimization to the kernel. If one exists and applies properly, return true, otherwise return false. + def apply_tensor_cores(self, use_tensor_cores=1, extra_opts:Optional[list[Opt]]=None, axis:int=0, tc_select:Optional[int]=None, + tc_opt:Optional[int]=None) -> bool: + """ Attempts to apply a tensor core optimization to the kernel. If one exists and applies properly, return true, otherwise return false. Tensor cores are optimized instructions that matrix multiply-accumulate across a wave of threads: D(M, N) = A(M, K) * B(K, N) + C(M, N). Keyword arguments: @@ -325,22 +299,26 @@ class Kernel: 0: will disable any tensor core matching 1: enable tensor cores 2: apply tensor core shape but don't use UOp.WMMA + 3: emulate tensor cores with local memory extra_opts -- additional Opt's to apply after the tensor core instead of the hand-coded additional Opt's (default None) + tc_select -- specifies which tensor core(s) to use for optimization (default -1) + -1: iterates through all available tensor cores in order and uses the first one that matches the requirements (dims and dtypes) + [0-N]: uses only the n'th tensor core available; useful for search tc_opt -- controls which kinds of kernels may be eligible for tensor cores application (default 2 during BEAM, 0 otherwise) - 0: applies to only kernels with a single reduce axis and direct UOps.LOAD into Ops.MUL - 1: allows kernels with multiple reduce axes and also multiplication of UOps.CAST'd buffers + 0: applies to only kernels with a single reduce axis and direct Ops.LOAD into Ops.MUL + 1: allows kernels with multiple reduce axes and also multiplication of Ops.CAST'd buffers 2: allows kernels with M, N, K axes that are not multiples of the tensor core dimensions by applying padding those axes as needed """ + if tc_select is None: tc_select = TC_SELECT.value if tc_opt is None: tc_opt = TC_OPT.value - if not self.opts.tensor_cores and use_tensor_cores != 2: return False + if not self.opts.tensor_cores: return False try: # check TC first and apply hand-coded opts if successful - self.apply_opt(Opt(OptOps.TC, axis, tc_opt)) + self.apply_opt(Opt(OptOps.TC, axis, (tc_select, tc_opt, use_tensor_cores))) if (tc_opts:=self.tensor_core_opts) is not None: - if extra_opts is not None: - for opt in extra_opts: self.apply_opt(opt) + if extra_opts is not None: self.apply_opts(extra_opts) else: - if (self.opts.device == "CLANG" and AMX): return True # skip hand-coded TC opts if AMX, upcasting will make kernel slower + if AMX: return True # skip hand-coded TC opts if AMX, upcasting will make kernel slower # hand-coded TC opts for tc_dim in [tc_dim for tc_dim in [1,0] if tc_opts.axes_exist[tc_dim]]: # attempt to upcast M and N szs = [sz for sz in [5,4,3,2] if self.full_shape[tc_opts.axes[tc_dim]] % sz == 0] @@ -352,25 +330,36 @@ class Kernel: except KernelOptError: return False + def real_axis(self, opt:Opt): + if opt.axis is None: return -1 + if opt.op is OptOps.UNROLL: return self.first_reduce+opt.axis + if opt.op in {OptOps.GROUP, OptOps.GROUPTOP}: return self.first_reduce+self.group_for_reduces+opt.axis + return opt.axis + def apply_opt(self, opt:Opt, append_opt:bool=True): if self.dont_use_locals: check(opt.op not in {OptOps.LOCAL, OptOps.GROUP, OptOps.GROUPTOP}, "not using locals") if opt.op is OptOps.TC: check(len(self.applied_opts) == 0, "tensor core opts must be first") # TODO: things like PADTO might be fine - check(opt.axis is not None and opt.amt is not None, "tensor core opts must have an axis and amt") - check((use_tensor_cores:=USE_TC.value) == 2 or len(self.opts.tensor_cores) > 0, "must have tensor cores or TC=2") - check(self._apply_tc_opt(use_tensor_cores, cast(int, opt.axis), cast(int, opt.amt)), "no tensor core available") + check(len(self.opts.tensor_cores) > 0, "must have tensor cores") + check(opt.axis is not None, "tensor core opts must have an axis") + check(opt.arg is not None and isinstance(opt.arg, tuple) and len(opt.arg) == 3, "tensor core opts must have valid arg") + check(-1 <= (tc_select:=cast(tuple, opt.arg)[0]) < len(self.opts.tensor_cores), "tensor core opts must have valid tc_select") + check(0 <= (tc_opt:=cast(tuple, opt.arg)[1]) <= 2, "tensor core opts must have valid tc_opt") + check(0 < (use_tensor_cores:=cast(tuple, opt.arg)[2]) <= 3, "use_tensor_cores value is not valid") + check(self._apply_tc_opt(use_tensor_cores, cast(int, opt.axis), tc_select, tc_opt), "no tensor core available") self.applied_opts.append(opt) return - axis = opt.real_axis(self) + axis = self.real_axis(opt) check(axis < len(self.full_shape), "invalid axis") - if opt.op is OptOps.SWAP: amt = cast(int, opt.amt) # amt is an axis in the SWAPs - elif opt.amt is not None: - amt = opt.amt if opt.amt != 0 else self.full_shape[axis] - check(isinstance(amt, int) and amt != 1, "shift/padto of amt 1 or Node is meaningless") - if opt.op is not OptOps.PADTO: check(self.full_shape[axis] % amt == 0, "no longer valid shift") + if opt.op is OptOps.SWAP: amt = cast(int, opt.arg) # arg is an axis in the SWAPs + elif opt.arg is not None: + check(isinstance(opt.arg, int), "arg should be int") + amt = arg if (arg:=cast(int, opt.arg)) != 0 else self.full_shape[axis] + check(isinstance(amt, int) and amt != 1, f"shift/padto of {amt=}, 1 or symbolic amount is meaningless") + if opt.op is not OptOps.PADTO: check(self.full_shape[axis] % amt == 0, f"no longer valid shift {self.full_shape[axis]=}, {amt=}") else: amt = -1 if self.reduceop is not None and (opt.op in {OptOps.GROUP, OptOps.GROUPTOP} or \ @@ -382,6 +371,8 @@ class Kernel: check(smem_sz <= self.opts.shared_max, f"exceeds maximum shared memory size: needs {smem_sz}, max {self.opts.shared_max}") if opt.op is OptOps.LOCAL: # cyan + # NOTE: LLVM/CPU can use locals too, but they are treated the same as globals (still helpful for L1 cache) + # it's disabled for now since it makes BEAM slow for little gain check(self.opts.has_local, "target does not support local") check(axis < self.global_dims, "local is for globals") self.shift_to(axis, amt, insert_before=self.first_reduce) @@ -405,8 +396,8 @@ class Kernel: self.upcast() elif opt.op is OptOps.UPCAST: # yellow check(axis < self.first_reduce, "upcast is for non-reduce") - check(not (self.tensor_core and self.global_dims <= axis < self.global_dims+len(self.tensor_core.threads)), "can't upcast TC locals") - check(amt <= 16, "don't upcast more than 16") + check(not (self.tensor_core and self.global_dims <= axis < self.global_dims+len(self.tensor_core.get_local_axes())), "can't upcast TC locals") + check((self.opts is not None and self.opts.device == "DSP") or amt <= 16, "don't upcast more than 16") self.shift_to(axis, amt, insert_before=None) self.upcast() elif opt.op is OptOps.NOLOCALS: @@ -422,7 +413,7 @@ class Kernel: check(not self.vars, "does not work with symbolic shape") check(axis < self.first_upcast, "cannot pad upcasted") # ok to pad SUM if all parent ALU ops have f(0) = 0 - if (r:=self.reduceop) is not None and self.first_reduce <= axis: check(r.arg[0] is Ops.ADD and can_pad(r, {}, set()), f"cannot pad {r}") + if (r:=self.reduceop) is not None and self.first_reduce <= axis: check(r.arg[0] is Ops.ADD and can_pad(r, {}), f"cannot pad {r}") padded = False for i,st in enumerate(self.sts): if (s:=st.shape[axis]) == 1: continue # reduced @@ -437,140 +428,17 @@ class Kernel: if self.simplify_ones() and self.tensor_core_opts: self.tensor_core_opts.fix_axes(axis) # fix up axes in TC opts if required after simplify_ones() - def required_optimizations(self) -> Kernel: - if isinstance(self.membufs[0].dtype, ImageDType): - unit_stride_axes_mul_4 = [i for i in self.sts[0].unit_stride_axes(ignore_valid=True) if self.sts[0].shape[i]%4 == 0] - assert unit_stride_axes_mul_4, f"needs a unit stride axis in {self.bufs[0]}" - if all(x < self.first_upcast for x in unit_stride_axes_mul_4): self.apply_opt(Opt(OptOps.UPCAST, unit_stride_axes_mul_4[0], 4)) - return self - - def hand_coded_optimizations(self) -> Kernel: - self.required_optimizations() - - # should use matvec - TODO: adjust/tune based on the wide vs tall/large vs small mat - MV_BLOCKSIZE, MV_THREADS_PER_ROW, MV_ROWS_PER_THREAD = getenv("MV_BLOCKSIZE", 4), getenv("MV_THREADS_PER_ROW", 8), getenv("MV_ROWS_PER_THREAD", 4) - if self.opts.has_local and getenv("MV",1) != 0 and (MV_BLOCKSIZE > 1 or MV_THREADS_PER_ROW > 1 or MV_ROWS_PER_THREAD > 1) and \ - self.reduceop is not None and self.reduceop.arg[0] is Ops.ADD and len(self.full_shape) >= 2 and self.opts.has_shared and \ - (mulop:=self.reduceop.src[0]).op is Ops.MUL and mulop.src[0].op is Ops.LOAD and mulop.src[1].op is Ops.LOAD: - st0, st1 = self.sts[self.bufs.index(mulop.src[0])], self.sts[self.bufs.index(mulop.src[1])] - strides0, strides1 = st0.real_strides(), st1.real_strides() - def has_expanded_axis(shape, strides): return any(resolve(s > 1) and not resolve(st != 0) for s,st in zip(shape,strides)) - if strides0[self.first_reduce] == 1 and not (has_expanded_axis(st0.shape, strides0) and has_expanded_axis(st1.shape, strides1)): - for global_idx in range(self.global_dims): - if self.full_shape[self.first_reduce]%MV_THREADS_PER_ROW == 0 and self.full_shape[global_idx]%(MV_BLOCKSIZE*MV_ROWS_PER_THREAD) == 0: - if DEBUG >= 3: - print(f"MATVEC: {self.full_shape=} {self.first_reduce=} {strides0=} {MV_BLOCKSIZE=} {MV_THREADS_PER_ROW=} {MV_ROWS_PER_THREAD=}") - if MV_THREADS_PER_ROW > 1: self.apply_opt(Opt(OptOps.GROUP, 0, MV_THREADS_PER_ROW)) - if MV_BLOCKSIZE > 1: self.apply_opt(Opt(OptOps.LOCAL, global_idx, MV_BLOCKSIZE)) - if MV_ROWS_PER_THREAD > 1: self.apply_opt(Opt(OptOps.UPCAST, global_idx, MV_ROWS_PER_THREAD)) - return self - - if self.opts.has_local and self.opts.has_shared and all_int(self.sts[0].shape[:self.first_reduce]): - # are we grouping? (requires local shape support) - if not self.float4_axis(0) and self.first_reduce <= 2 and self.first_reduce + 1 <= self.shape_len and prod(self.sts[0].shape[:self.first_reduce]) <= 2048: # noqa: E501 - # TODO: use 1024 if it's allowed in a smarter way - for sz in ([256, 16] if prod(self.sts[0].shape[:self.first_reduce]) <= 32 else [16]): - if all(st.shape[self.first_reduce] % sz == 0 or st.shape[self.first_reduce] == 1 for st in self.sts): - try: # may fail due to excessive smem usage - self.apply_opt(Opt(OptOps.GROUPTOP, 0, sz)) - break - except KernelOptError: pass - - # upcast float4 images - for buf_index,buf in enumerate(self.bufs): - unit_stride_axes_mul_4 = [i for i in self.sts[buf_index].unit_stride_axes(ignore_valid=True) if self.sts[buf_index].shape[i]%4 == 0] - if buf.src[0].dtype.__class__ is ImageDType: - #assert len(unit_stride_axes_mul_4) >= 1, f"needs a unit stride axis in {self.bufs[buf_index]}" - if len(unit_stride_axes_mul_4) and all(x < self.first_upcast for x in unit_stride_axes_mul_4): - if unit_stride_axes_mul_4[0] < self.first_reduce: - self.apply_opt(Opt(OptOps.UPCAST, unit_stride_axes_mul_4[0], 4)) - else: - self.apply_opt(Opt(OptOps.UNROLL, unit_stride_axes_mul_4[0]-self.first_reduce, 4)) - - # no more opt if we are grouping - if self.group_for_reduces: return self - - # **** below this line need to be optional and benchmarked **** - - # TODO: doing extra upcasts with images doesn't work for some reason (maybe has to do with to_image_idx) - # to trigger the above bug, remove prod(self.full_shape[self.first_upcast:]) from the below - # expression and run test/test_ops.py with IMAGE=2 - # if there are small dims with lots of valid masks, upcast them (they might be from Tensor.stack) - # this can be made much smarter - to_upcast: list[int] = [] - # upcast leading axes first (hack-ish for winograd; we actually want to upcast masked axes with low stride first) - for axis in range(self.first_reduce): - # we might want to be able to split axes that are masked, or refuse to merge them in simplify_merge_adjacent - # for now skip upcasting here if there is a symbolic axis - if isinstance(self.full_shape[axis], int) and self.full_shape[axis] <= 7 and any(st.axis_is_masked(axis) for st in self.sts) and \ - prod(self.full_shape[self.first_upcast:]) * prod(self.full_shape[j] for j in to_upcast) * self.full_shape[axis] <= 7 * 7: - if DEBUG >= 4: print(f"upcasting masked axis : {axis}") - to_upcast.append(axis) - for axis in to_upcast[::-1]: self.apply_opt(Opt(OptOps.UPCAST, axis, 0)) - - # potentially do more upcasts of non reduce axes based on a heuristic - upcasted_axis = set() - while resolve(prod(self.sts[0].shape[:self.first_reduce]) >= 1024): - xb_choices = [] - for axis, upcast_amount in itertools.product(range(self.first_reduce), [3,4]): # consider all the non reduce axes, and a 3 or 4 reduce - # if we haven't upcasted it, it's not symbolic, it mods, and buffer has stride 0 on axis while having no stride 0 in the upcasted axis already - if axis not in upcasted_axis and isinstance(self.full_shape[axis], int) and self.full_shape[axis]%upcast_amount == 0 and any(st.views[-1].strides[axis] == 0 and not any(x[1] == 0 for x in self.upcasted_axis(buf_index)) for buf_index, st in enumerate(self.sts)): # noqa: E501 - xb_choices.append((sum(st.views[-1].strides[axis]>0 for st in self.sts), sum(st.views[-1].strides[axis] for st in self.sts), axis, upcast_amount)) # noqa: E501 - if xb_choices: - xb_choices = sorted(xb_choices) - if DEBUG >= 4: print(f"float4 merging axis : {xb_choices}") - self.apply_opt(Opt(OptOps.UPCAST, xb_choices[0][2], xb_choices[0][3])) - upcasted_axis.add(xb_choices[0][2]) - else: break - - # if last dim is small(ish) and it's a reduce dim, upcast the reduce (loop unrolling). no simplify needed since it's just an upcast. - if self.first_reduce < self.first_upcast and (prod(self.full_shape[self.first_upcast:]) <= 4 or not any(r for _,_,r in self.upcasted_axis(self.full_buf_index))) and (self.upcasted == 0 or prod(self.full_shape[-self.upcasted:]) < 64): # noqa: E501 - if isinstance(s:=self.full_unupcasted_shape[-1], int) and s <= 32: # NOTE: cannot loop unroll symbolic axis - self.apply_opt(Opt(OptOps.UNROLL, len(self.full_unupcasted_shape)-1-self.first_reduce, 0)) - # if it's small, upcast a second reduce dimension too - if self.first_reduce < self.first_upcast and s <= 3 and isinstance(s2:=self.full_unupcasted_shape[-1], int) and s2 <= 3: - self.apply_opt(Opt(OptOps.UNROLL, len(self.full_unupcasted_shape)-1-self.first_reduce, 0)) - else: - for splits in [4]: - if self.full_unupcasted_shape[-1]%splits == 0: - self.apply_opt(Opt(OptOps.UNROLL, len(self.full_unupcasted_shape)-1-self.first_reduce, splits)) - break - - # if nothing at all is upcasted and it's easy to, do an upcast - # TODO: this is breaking the tests - for splits in [4]: - if self.upcasted == 0 and self.full_unupcasted_shape and self.full_unupcasted_shape[-1] % splits == 0: - self.apply_opt(Opt(OptOps.UPCAST, len(self.full_unupcasted_shape)-1, splits)) - - # **** local groups **** - - if self.opts.has_local: - if getenv("NOLOCALS") and self.local_dims == 0 and not self.group_for_reduces: - self.apply_opt(Opt(OptOps.NOLOCALS)) - else: - # prioritize making expand axes local - local_axis_ranking = [(any(self.sts[buf_index].views[-1].strides[axis] == 0 for buf_index in range(len(self.sts))), axis) for axis in range(len(self.full_shape[:self.first_reduce]))] # noqa: E501 - to_local: list[tuple[int, int]] = [] - for _, axis in sorted(local_axis_ranking, key=lambda x: (-x[0], -x[1])): - local_size = prod(sz for _, sz in to_local) - local_sz: Optional[int] = next((x for x in ([32] * (axis == 0) + [16, 8, 4, 3, 2]) if self.full_shape[axis] % x == 0 and local_size * x <= 128), None) # noqa: E501 - if local_sz is not None: to_local.append((axis, local_sz)) - deleted_shape = 0 - for axis, local_sz in sorted(to_local[:3]): - axis = axis - deleted_shape - will_delete_shape = local_sz == self.full_shape[axis] - self.apply_opt(Opt(OptOps.LOCAL, axis, local_sz)) - if will_delete_shape: deleted_shape += 1 - + def apply_opts(self, opts:Sequence[Opt]) -> Kernel: + for opt in opts: self.apply_opt(opt) return self # **** kernel outputs **** - kernel_cnt: Final[DefaultDict[str, int]] = defaultdict(int) + kernel_cnt: Final[defaultdict[str, int]] = defaultdict(int) @functools.cached_property def name(self) -> str: # kernel name (before late upcast) - kernel_type = "r" if self.reduceop is not None else ("C" if all(x.op is Ops.SINK or x.op in GroupOp.Buffer for x in self.ast.toposort) else "E") + kernel_type = "r" if self.reduceop is not None else ("C" if all(x.op is Ops.SINK or x.op in GroupOp.Buffer for x in self.ast.toposort()) else "E") suffix = colored('_', 'BLACK').join([colored(x.render() if isinstance(x, UOp) else str(x), c) for x,c in zip(self.full_shape, self.colors())]) name = kernel_type + (f"{len(self.ast.src)}" if len(self.ast.src) > 1 else "") + "_" + suffix @@ -579,14 +447,19 @@ class Kernel: num = f"n{Kernel.kernel_cnt[function_name]-1}" if Kernel.kernel_cnt[function_name] > 1 else "" return name + colored(num, 'BLACK') - def get_optimized_ast(self) -> UOp: - @functools.lru_cache(None) + def get_optimized_ast(self, name_override:Optional[str]=None) -> UOp: + @functools.cache def fixup_ast(op:UOp) -> UOp: - ret = op.replace(src=tuple(fixup_ast(x) for x in op.src)) + ret = op.replace(src=tuple(fixup_ast(x) for x in op.src)) # noqa: F821 if op.op in GroupOp.Buffer and op in self.bufs: st_uop = self.sts[self.bufs.index(op)].to_uop() - return ret.replace(src=(st_uop,)) if op.op is Ops.VALID else ret.replace(src=(ret.src[0], st_uop, *ret.src[2:])) - if op.op is Ops.SINK: return ret.replace(arg = KernelInfo(self.local_dims, self.upcasted, self.dont_use_locals)) + # NOTE: if CONST got masked after applying opts, we create a new VALID + if op.op is Ops.CONST and any(v.mask is not None for v in unwrap(st_uop.st).views): return op.valid(unwrap(st_uop.st)) + # otherwise we just replace the VIEW source + return ret.replace(src=(st_uop,)) if len(op.src) == 1 else ret.replace(src=(ret.src[0], st_uop, *ret.src[2:])) + if op.op is Ops.SINK: + return ret.replace(arg = KernelInfo(to_function_name(self.name) if name_override is None else name_override, + self.local_dims, self.upcasted, self.dont_use_locals)) if op.op is Ops.REDUCE_AXIS: reduce_idx = len(self.bufs) + self.reduceops.index(op) * 2 @@ -596,48 +469,45 @@ class Kernel: grouped_axes = reduced_axes(self.first_reduce, self.first_reduce + self.group_for_reduces) if (tc := self.tensor_core) and (self.use_tensor_cores == 1 or self.use_tensor_cores == 3): - def fix_st(st: ShapeTracker, wd_pattern, tcd_pattern): - st = ShapeTracker.from_shape(st.shape) # st needs to be contiguous - wd, warp_dims = self.global_dims, tuple(sz for _, sz in tc.threads) - tcd, tcd_dims = self.first_upcast, tuple(sz for _, sz in tc.reduce_axes + tc.early_upcast_axes) - - assert st.shape[wd:wd+len(warp_dims)] == warp_dims, f"warp dims wrong: {st.shape[wd:wd+len(warp_dims)]=} != {warp_dims=}" - assert st.shape[tcd:tcd+len(tcd_dims)] == tcd_dims, f"tcd dims wrong: {st.shape[tcd:tcd+len(tcd_dims)]=} != {tcd_dims=}" - assert tc.expanded_shape is not None - - new_shape = st.shape[:tcd] + tc.expanded_shape + st.shape[tcd+len(tcd_dims):] # expand the tcd - permaxis = list(range(wd)) + [y + (wd if x == 0 else tcd) for x,y in wd_pattern] + list(range(wd+len(warp_dims),tcd)) + \ - [y + (wd if x == 0 else tcd) for x,y in tcd_pattern] + list(range(tcd+len(tc.expanded_shape),len(new_shape))) - return st.reshape(new_shape).permute(tuple(permaxis)).reshape(st.shape).simplify() + wd, tcd = self.global_dims, self.first_upcast + def get_upcast_axes(buf): # upcast along non-zero dimensions of (tc_reduce + tc_upcast) + upcast_axes = int(math.log2(tc.elements_per_thread[buf])) + return tuple((tcd + len(tc.get_reduce_axes()) + len(tc.get_upcast_axes()) - (i+1), 2) for i in range(upcast_axes)) + def get_tc_swizzle_st(shape, local_perm, upcast_perm): + offset = (tcd - (wd + len(local_perm))) + permaxis = list(range(wd)) \ + + [wd + x + (offset if x >= len(local_perm) else 0) for x in local_perm] + list(range(wd + len(local_perm), tcd)) \ + + [wd + x + (offset if x >= len(local_perm) else 0) for x in upcast_perm] + list(range(tcd + len(upcast_perm), len(shape))) + return ShapeTracker.from_shape(shape).permute(tuple(permaxis)) srcs = list((ret.src[0] if ret.src[0].op is not Ops.CAST else ret.src[0].src[0]).src) - for i, tc_pattern in enumerate([tc.st1_pattern, tc.st2_pattern]): - if tc_pattern: srcs[i] = srcs[i].view(fix_st(srcs[i].st_arg if srcs[i].op is Ops.LOAD else srcs[i].src[0].st_arg, *tc_pattern)) + for i, (src, swizzle) in enumerate(zip(srcs, tc.swizzle)): + src_st = (src if src.op is Ops.LOAD else src.src[0]).st_arg + if swizzle: srcs[i] = src.view(get_tc_swizzle_st(src_st.shape, *swizzle)) if self.use_tensor_cores == 3: # for TC=3, emulate the warp addressing with locals - local_shape = tuple(1 if i >= self.first_reduce and i < self.first_upcast else s for i, s in enumerate(self.full_shape)) + local_shape = tuple(1 if st == 0 or i < wd or (i >= self.first_reduce and i < tcd) else src_st.shape[i] \ + for i,st in enumerate(src_st.real_strides())) st = store_st = ShapeTracker.from_shape(local_shape) - local_buffer = UOp(Ops.DEFINE_LOCAL, tc.dtype_in.ptr(size=st.real_size(), local=True), (), (f"temp{i + 1}", st.real_size())) - if tc_pattern: store_st = fix_st(store_st, *tc_pattern) + local_buffer = UOp(Ops.DEFINE_LOCAL, tc.dtype_in.ptr(size=st.real_size(), local=True), (), f"temp{i}") + if swizzle: store_st = get_tc_swizzle_st(store_st.shape, *swizzle) local_store = UOp.store(local_buffer, store_st.to_uop(), srcs[i]) srcs[i] = UOp(Ops.LOAD, tc.dtype_in, (local_buffer, st.to_uop(), local_store)) - tc_reduce_axes = tuple(self.first_upcast + ax for ax, _ in tc.reduce_axes) + tc_reduce_axes = tuple(tcd + ax for ax, _ in tc.get_reduce_axes()) if self.use_tensor_cores == 1: # real WMMA, use CONTRACT/UNROLL to get the vectorization right - upcast_axes = tuple(tuple((self.first_upcast + ax, sz) for ax, sz in up) for up in tc.upcast_axes) - wmma_arg = (str(tc), tc.dims, tc.dtype_in, tc.dtype_out, self.opts.device, prod(sz for _, sz in tc.threads), upcast_axes, tc_reduce_axes) - wmma_sz = [prod(x[1] for x in l) for l in upcast_axes] - wmma = UOp(Ops.WMMA, dtype=tc.dtype_out.vec(wmma_sz[2]), src=( - UOp(Ops.CONTRACT, dtype=srcs[0].dtype.vec(wmma_sz[0]), src=(srcs[0],), arg=upcast_axes[0]), - UOp(Ops.CONTRACT, dtype=srcs[1].dtype.vec(wmma_sz[1]), src=(srcs[1],), arg=upcast_axes[1]), - UOp.const(tc.dtype_out.vec(wmma_sz[2]), 0.0)), arg=wmma_arg) - tc_uop = UOp(Ops.UNROLL, tc.dtype_out, (wmma,), arg=upcast_axes[2]) + tc_upcast_axes = (get_upcast_axes(0), get_upcast_axes(1), get_upcast_axes(2)) + wmma_arg = (str(tc), tc.dims, tc.dtype_in, tc.dtype_out, self.opts.device, tc.threads, tc_upcast_axes, tc_reduce_axes) + wmma = UOp(Ops.WMMA, dtype=tc.dtype_out.vec(tc.elements_per_thread[2]), src=( + UOp(Ops.CONTRACT, dtype=srcs[0].dtype.vec(tc.elements_per_thread[0]), src=(srcs[0],), arg=tc_upcast_axes[0]), + UOp(Ops.CONTRACT, dtype=srcs[1].dtype.vec(tc.elements_per_thread[1]), src=(srcs[1],), arg=tc_upcast_axes[1]), + UOp.const(tc.dtype_out.vec(tc.elements_per_thread[2]), 0.0)), arg=wmma_arg) + tc_uop = UOp(Ops.UNROLL, tc.dtype_out, (wmma,), arg=tc_upcast_axes[2]) else: # for TC=3 MUL/SUM instead of WMMA tc_uop = UOp(Ops.REDUCE_AXIS, tc.dtype_out, ((srcs[0] * srcs[1]).cast(tc.dtype_out),), (Ops.ADD, tc_reduce_axes)) - new_reduce_axes = tuple(i for i in axes if i not in tc_reduce_axes) - return ret.replace(src=(tc_uop,), arg=(Ops.ADD, new_reduce_axes)) if new_reduce_axes else tc_uop + return ret.replace(src=(tc_uop,), arg=(Ops.ADD, new_axes)) if (new_axes := tuple(i for i in axes if i not in tc_reduce_axes)) else tc_uop ret = ret.replace(arg = (op.arg[0], axes)) if self.group_for_reduces and grouped_axes: @@ -647,7 +517,7 @@ class Kernel: (1,) * (self.shape_len - self.upcasted - self.group_for_reduces - self.first_reduce) + tuple([x[0] for x in self.upcasted_axis(0)]) st_uop = ShapeTracker.from_shape(local_shape).to_uop() local_size = st_uop.arg.real_size() - local_buffer = UOp(Ops.DEFINE_LOCAL, op.dtype.ptr(local_size, local=True), (), (f"temp{self.reduceops.index(op)+1}", local_size)) + local_buffer = UOp(Ops.DEFINE_LOCAL, op.dtype.ptr(local_size, local=True), (), f"temp{self.reduceops.index(op)}") local_load = UOp(Ops.LOAD, op.dtype, (local_buffer, st_uop, UOp.store(local_buffer, st_uop, ret))) grouped_reduce = UOp(Ops.REDUCE_AXIS, op.dtype, (local_load,), arg=(op.arg[0], grouped_axes)) if op is self.reduceops[-1]: return grouped_reduce @@ -655,73 +525,60 @@ class Kernel: return UOp(Ops.LOAD, op.dtype, (local_buffer, st_uop, UOp.store(local_buffer, st_uop, grouped_reduce))) return ret - - return graph_rewrite(fixup_ast(self.ast), view_left) + fixed_ast = fixup_ast(self.ast) + del fixup_ast + return graph_rewrite(fixed_ast, view_left, name="fixup optimized AST") # **** this is the lowerer **** @track_rewrites() - def linearize(self) -> Kernel: - modified_ast = self.get_optimized_ast() + def linearize(self, name_override:Optional[str]=None, ast_transform:Optional[Callable]=None) -> Kernel: + # display the AST + if getenv("VIZ"): graph_rewrite(self.ast, PatternMatcher([]), name="View Base AST") + + modified_ast = self.get_optimized_ast(name_override) + if ast_transform is not None: modified_ast = ast_transform(self, modified_ast) if DEBUG >= 3: print(self.name) - if getenv("RAWAST"): print(self.ast) - print(modified_ast) + if DEBUG >= 5: print(self.ast) + for i,(buf,st) in enumerate([(buf,st) for buf,st in zip(self.bufs, self.sts) if buf.op not in {Ops.CONST, Ops.VALID}]): + print(f"{i:2d}: {str(st.shape):25s} {str(buf.src[0].dtype).replace('dtypes.',''):20s} {str(st.real_strides()):30s}", + str(st) if DEBUG >= 4 else "") print(self.applied_opts) - verify_ast(modified_ast) - - self.uops:list[UOp] = linearize_uop(full_graph_rewrite(rewrite_shapetracker_with_index(modified_ast, self.opts), self.opts)) - if DEBUG >= 5: print_uops(self.uops) + if DEBUG >= 5: print(modified_ast) + # verify AST matches the spec after applying opts + if __debug__: type_verify(list(modified_ast.toposort())) + # TODO: sadly modified_ast doesn't pass the shape spec because of how group_for_reduces constructs UOps, there's probably a way to fix this + #if __debug__: type_verify(list(modified_ast.toposort()), shape_spec) + + try: + self.uops:list[UOp] = full_rewrite(modified_ast, self.opts) + except RuntimeError: + print("***** LINEARIZE FAILURE *****") + print(f"ast = {self.ast}") + print(f"opts = {self.applied_opts}") + raise + if DEBUG >= 6: print_uops(self.uops) return self - def to_program(self, name_override:Optional[str]=None) -> ProgramSpec: - self.linearize() - src = self.opts.render(name:=to_function_name(ansiname:=(name_override if name_override is not None else self.name)), self.uops) + def to_program(self, name_override:Optional[str]=None, ast_transform:Optional[Callable]=None) -> ProgramSpec: + self.linearize(name_override, ast_transform) + assert self.uops[-1].op is Ops.SINK, "last uop must be sink" + src = self.opts.render(self.uops) - if getenv("RUN_PROCESS_REPLAY"): - from test.external.process_replay.helpers import get_process_replay_ctx - diskcache_put("kernel_process_replay", str(id(self)), (self.ast, self.opts, self.applied_opts, name, *get_process_replay_ctx(), src)) + if CAPTURE_PROCESS_REPLAY: + import sys + frm = sys._getframe(1) + while (f_back:=frm.f_back) is not None and "unittest" not in f_back.f_code.co_filename: frm = f_back + loc = f"{frm.f_code.co_filename.split('/')[-1]}:{frm.f_lineno} {frm.f_code.co_name}" + diskcache_put("kernel_process_replay", str(id(self)), (self.ast, self.opts, self.applied_opts, self.uops[-1].arg.name, loc, ContextVar._cache, + src)) # group non-local bufs by the op type (LOAD or STORE) and the buffer arg. take the max access of that buffer in bytes # TODO: these max and min don't work on symbolic, and results are very wrong. - mem_bytes = sum(max(x.src[0].dtype.itemsize * x.st_arg.real_size() for x in group) - for _, group in itertools.groupby([x for x in self.ast.toposort if x.op in GroupOp.Buffer and x.src[0].op is Ops.DEFINE_GLOBAL], + mem_bytes = sum(max(x.src[0].dtype.nbytes() for x in group) + for _, group in itertools.groupby([x for x in self.ast.toposort() if x.op in GroupOp.Buffer and x.src[0].op is Ops.DEFINE_GLOBAL], key=lambda x: (x.op, x.src[0].arg))) - return ProgramSpec(ansiname, src, self.opts.device, self.uops, mem_estimate=mem_bytes, - global_size=[1,1,1] if self.opts.has_local else None, local_size=[1,1,1] if self.opts.has_local else None) - -# the living definition of intermediate UOps - -def _assert_valid_uop(uop:UOp, st:ShapeTracker, sts:dict[UOp, ShapeTracker]) -> None: - if not uop.has_st or uop in sts: return - # restore globals from the two stage reduce - if uop.op is Ops.LOAD and uop.src[0].op is Ops.DEFINE_LOCAL: - _assert_valid_uop(local_reduce:=uop.src[2].src[2], uop.st_arg, sts) - sts[uop] = sts[local_reduce] - return - for x in uop.src: _assert_valid_uop(x, st, sts) - # only reduceuop is allowed to change shape, limited to turning n to 1 - if uop.op in {Ops.REDUCE_AXIS, Ops.WMMA}: st = ShapeTracker.from_shape(sts[uop.src[0]].reduce(uop.axis_arg)) - # movementops are pushed to VIEW - elif uop.op is Ops.VIEW: - assert len(uop.src) == 0, f"can't swizzle in kernel yet {uop}" - st = uop.arg - # everything else inherits shape - else: - if len(src_sts:=[sts[x] for x in uop.src if x in sts]) == 0: return None - st = src_sts[0] - if not all_same(shapes:=[x.shape for x in src_sts]): - if all_same(sizes:=[prod(x) for x in shapes]): raise AssertionError(f"found implicit reshape {shapes}") - raise AssertionError(f"found implicit expand {sizes} {shapes}") - sts[uop] = st - -def verify_ast(ast:UOp) -> dict[UOp, ShapeTracker]: - assert ast.op is Ops.SINK and all(x.op is Ops.STORE for x in ast.src), "must be SINK" - assert all_same([x.st_arg.size for x in ast.src]), "outputs must be exactly the same size" - sts: dict[UOp, ShapeTracker] = {} - for out in ast.src: _assert_valid_uop(out, out.st_arg, sts) - shape_dims = [sorted(dedup(dims)) for dims in zip(*[x.shape for x in sts.values()])] - assert all(len(x) == 1 or (len(x) == 2 and x[0] == 1) for x in shape_dims), f"shapes must have either 1 or n in each dimension, {shape_dims}" - type_verify(list(sts)) - return sts + return ProgramSpec(self.name if not name_override else name_override, src, self.opts.device, self.ast, self.uops, self.applied_opts, mem_bytes, + global_size=[1,1,1] if self.opts.has_local else None, local_size=[1,1,1] if self.opts.has_local else None) diff --git a/tinygrad_repo/tinygrad/codegen/linearize.py b/tinygrad_repo/tinygrad/codegen/linearize.py index 6b6e9fab9d..bd9231e157 100644 --- a/tinygrad_repo/tinygrad/codegen/linearize.py +++ b/tinygrad_repo/tinygrad/codegen/linearize.py @@ -1,224 +1,245 @@ from __future__ import annotations -import collections, heapq -from dataclasses import dataclass -from tinygrad.ops import type_verify, UOp, Ops, PatternMatcher, UPat, graph_rewrite, GroupOp -from tinygrad.dtype import dtypes, PtrDType -from tinygrad.helpers import dedup, flatten, partition - -DONT_PLACE_IN_BLOCK = {Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL, Ops.DEFINE_VAR, Ops.SPECIAL, Ops.CONST, *GroupOp.Block} - -def disp(y:UOp) -> str: - if y.op is Ops.BLOCKSTART: return "w"+disp(y.src[0]) - if y.op is Ops.IF: return f'IF{id(y)}' - if y.op is Ops.RANGE: return str(y.arg) - return "" - -@dataclass(frozen=True) -class BasicBlock: - ctx: tuple[UOp, ...] - lst: tuple[UOp, ...] - end: UOp|None = None - def __lt__(self, o:BasicBlock): return tuple(x.tuplize for x in self.ctx+self.lst) < tuple(x.tuplize for x in o.ctx+o.lst) - def __repr__(self): - return f"{(str(disp(self.end))+' ') if self.end is not None else ''}"+\ - f"{[disp(y) for y in self.ctx]} {len(self.lst)}" + "\n" + '\n'.join([str(x.op) for x in self.lst]) - -def append_to_block(ctx:tuple[dict[UOp, tuple[UOp, ...]], dict[UOp, list[UOp]]], x:UOp): - block_ctxs, children = ctx - in_this_block = set(x.arg.lst) - - # collections to build - new_srcs: list[UOp] = [] - to_append: list[UOp] = [] - old_blocks: dict[tuple[UOp, ...], UOp] = {} - new_blocks: dict[tuple[UOp, ...], list[UOp]] = {} - - for u in x.src: - if u.op is Ops.BLOCK: - # merge sibling blocks. NOTE: blocks must only have one output source - assert u.arg.ctx not in old_blocks, "sibiling should never have been created" - old_blocks[u.arg.ctx] = u - elif u.op not in DONT_PLACE_IN_BLOCK and set(children[u]).issubset(in_this_block): - # if it can go in blocks and all its children are in the block, we add it to the block - if (block_ctx:=block_ctxs[u]) == x.arg.ctx: - # if it's the same context, we place the UOp in this block and append the parents to its srcs - new_srcs.extend(u.src) - to_append.append(u) - else: - # if it's a different context, we create a new block with this UOp - new_blocks.setdefault(block_ctx, []).append(u) - else: - # otherwise, we keep it in the srcs - new_srcs.append(u) - if len(to_append) == 0 and len(new_blocks) == 0: return None - - for rng,lst in new_blocks.items(): - srcs = flatten(y.src for y in lst) - if (old_block:=old_blocks.pop(rng, None)) is not None: - # NOTE: order shouldn't matter here - srcs.extend(old_block.src) - lst.extend(old_block.arg.lst) - new_block = UOp(Ops.BLOCK, dtypes.void, tuple(dedup(srcs)), BasicBlock(rng, tuple(lst))) - lrng = list(rng) - for r in rng[::-1]: - if r not in x.arg.ctx and r.op is not Ops.BLOCKSTART: - lrng.remove(r) - new_block = UOp(Ops.BLOCKEND, src=(new_block,), - arg=BasicBlock(tuple(lrng), (UOp(Ops.ENDIF if r.op is Ops.IF else Ops.ENDRANGE, src=(r,)),), r)) - new_srcs.append(new_block) - return UOp(Ops.BLOCK, dtypes.void, tuple(dedup(list(old_blocks.values())+new_srcs)), BasicBlock(x.arg.ctx, tuple(to_append)+x.arg.lst)) - -make_basic_blocks = PatternMatcher([ - (UPat(Ops.SINK, name="x"), lambda x: UOp(Ops.BLOCK, src=x.src, arg=BasicBlock((), (x,)))), - (UPat(Ops.BLOCK, name="x"), append_to_block), -]) - -def block_merge(ctx, x:UOp): - # ctx is children here - if x.op is Ops.BLOCKEND: - # if it's a BLOCKEND, see if we are done with placement. if all the children of the range are in here - in_this_block = set(x.arg.lst) - if len([y for y in ctx[x.arg.end] if y not in in_this_block]) == 0: - # find the parent block that has the BLOCKSTART in the ctx - parent_blocks = [y for y in x.src if y.op is Ops.BLOCK and UOp(Ops.BLOCKSTART, src=(x.arg.end,)) in y.arg.ctx] - assert len(parent_blocks) <= 1, "should never have two parent blocks" - if len(parent_blocks) == 1: - parent_block = parent_blocks[0] - # range needs DEFINE_ACC to be before the range (never in DEFINE_ACC for if) - early_ops, late_ops = partition(x.arg.lst, lambda y: y.op is Ops.DEFINE_ACC and x.arg.end in y.src) - return UOp(Ops.BLOCK, dtypes.void, tuple(y for y in x.src if y is not parent_block)+parent_block.src, - BasicBlock(tuple(y for y in x.arg.ctx if y is not x.arg.end), tuple(early_ops)+parent_block.arg.lst+tuple(late_ops))) - - new_srcs: list[UOp] = [] - to_append: list[UOp] = [] - new_ctx = x.arg.ctx - placed = set() - for u in x.src: - if u.op is Ops.BLOCK and (tuple(u.arg.ctx) == tuple(x.arg.ctx) or (x.arg.end is not None and x.arg.end in u.arg.ctx)): - # NOTE: this can't appear in srcs twice or it would be a BLOCKFORK - new_ctx += tuple(y for y in u.arg.ctx if y not in x.arg.ctx) - new_srcs.extend(u.src) - to_append.extend(u.arg.lst) - elif u.op is Ops.BLOCKFORK and x.src.count(u) == u.arg: # block fork appears # of times in srcs - if u not in placed: - new_srcs.extend(u.src) - placed.add(u) - else: - # keep it in srcs - new_srcs.append(u) - if len(to_append) == 0 and len(placed) == 0: return None - return UOp(x.op, dtypes.void, tuple(new_srcs), BasicBlock(tuple(sorted(new_ctx, key=lambda x: x.tuplize)), tuple(to_append)+x.arg.lst, x.arg.end)) - -pm_block_merge = PatternMatcher([(UPat((Ops.BLOCKEND, Ops.BLOCK), name="x"), block_merge),]) +import heapq +from collections import defaultdict +from dataclasses import dataclass, replace +from tinygrad.uop.ops import UOp, Ops, PatternMatcher, UPat, GroupOp +from tinygrad.helpers import dedup, partition, all_same, flatten +from tinygrad.uop.spec import type_verify # NOTE: any toposort should be valid here, unlike last time this isn't required, it's just for speed -def block_reorder(in_block:UOp): - in_this_block = set(in_block.arg.lst) - local_children: collections.defaultdict[UOp, list[UOp]] = collections.defaultdict(list) - in_degree: collections.defaultdict[UOp, int] = collections.defaultdict(int) +def block_reorder(lst:list[UOp]) -> list[UOp]: + in_this_block = set(lst) + local_children: defaultdict[UOp, list[UOp]] = defaultdict(list) + in_degree:dict[UOp, int] = {} priorities:dict[UOp, int] = {} # get local children and assign priorities - for u in reversed(in_block.arg.lst): + # NOTE: this requires the lst be locally toposorted + for u in reversed(lst): + in_degree[u] = 0 for s in u.src: if s in in_this_block: local_children[s].append(u) in_degree[u] += 1 - # put loads in the beginning of the block and prevent priority inversion - priorities[u] = min([-1000 if u.op is Ops.LOAD else 0] + [priorities[x] for x in local_children[u]]) - - # placement queue - queue:list[tuple[int, tuple, UOp]] = [] - def push(u:UOp): heapq.heappush(queue, (priorities[u], u.tuplize, u)) + # put loads in the beginning of the block and prevent priority inversion. hack for BARRIER grouping too + priority = [0] + [priorities[x] for x in local_children[u]] + if u.op is Ops.LOAD: priority.append(-1000) + if u.op is Ops.BARRIER: priority.append(-1500) + priorities[u] = min(priority) - # place the first ones that don't have deps - for u in in_block.arg.lst: - if u not in in_degree: push(u) + # number the uops in "ideal" order + nkey = {u:i for i,u in enumerate(sorted(lst, key=lambda x: (priorities[x],)+x.tuplize))} + # then force then to be toposorted in as close to the ideal order as possible + heapq.heapify(heap:=[(nkey[u],u) for u in lst if in_degree[u] == 0]) newlst = [] - while queue: - _,_,x = heapq.heappop(queue) - newlst.append(x) - for u in local_children[x]: - in_degree[u] -= 1 - if in_degree[u] == 0: push(u) - - assert len(newlst) == len(in_block.arg.lst), f"len mismatch {len(newlst)} != {len(in_block.arg.lst)}" - return in_block.replace(arg=BasicBlock(in_block.arg.ctx, tuple(newlst))) - -def linearize_uop(sink:UOp, skip_check:bool=not __debug__) -> list[UOp]: - assert sink.op is Ops.SINK, f"sink isn't sink, it's {sink.op}" - - # get children and all block contexts - temp_block_ctxs: dict[UOp, list[UOp]] = {} - children: dict[UOp, list[UOp]] = {} - for u in sink.toposort: - this_block_ctx: list[UOp] = [] - for s in u.src: - # save children - children.setdefault(s, []).append(u) - # compute block ctx - if s.op in {Ops.RANGE, Ops.IF}: this_block_ctx.append(s) - # don't flow (fully) through assign and store - elif s.op is Ops.STORE: + while heap: + newlst.append(u:=heapq.heappop(heap)[1]) + for v in local_children[u]: + in_degree[v] -= 1 + if in_degree[v] == 0: heapq.heappush(heap, (nkey[v],v)) + + assert len(newlst) == len(lst), f"len mismatch {len(newlst)} != {len(lst)}" + return newlst + +# ***** basic block ***** + +def disp(y:UOp) -> str: + if y.op is Ops.IF: return f'IF{id(y)}' + if y.op is Ops.RANGE: return str(y.arg) + return "" + +@dataclass(frozen=True, eq=False) +class BasicBlock2: + lst: tuple[UOp, ...] + ctx: tuple[UOp, ...] = () + end: UOp|None = None + cnt: int = 0 + child_ctx: tuple[UOp, ...]|None = None + def __lt__(self, _:BasicBlock2): raise RuntimeError("no comparing basic blocks") + def __repr__(self): + return f"{(str(disp(self.end))+' ') if self.end is not None else ''}"+f'f{self.cnt} '+\ + f"{[disp(y) for y in self.ctx]} {[disp(y) for y in self.child_ctx] if self.child_ctx is not None else '-'} "+\ + f"{len(self.lst)}" + "\n" + '\n'.join([str(x.op) for x in self.lst]) + def last_ctx(self): return self.child_ctx if self.child_ctx is not None else self.ctx + +def _sort_ctx(inp): return tuple(sorted(dedup(inp), key=lambda x: x.tuplize)) + +# ***** block context ***** + +@dataclass +class BlockContext: + child_count: dict[UOp, int] + block_ctxs: dict[UOp, tuple[UOp, ...]] + child_ctxs: dict[UOp, tuple[UOp, ...]] + def last_ctx(self, u): return ret if (ret:=self.child_ctxs.get(u)) is not None else self.block_ctxs[u] + @staticmethod + def from_sink(sink:UOp) -> BlockContext: + # get children and all block contexts + ctx = BlockContext({}, {}, {}) + for u in sink.toposort(): + this_block_ctx: list[UOp] = [] + ctx.child_count[u] = 0 + + # get children and accumulate the last_ctx + for s in u.src: + # NOTE: if a parent appears multiple times in the src, it counts multiple times as a child + ctx.child_count[s] += 1 + this_block_ctx += ctx.last_ctx(s) + + # save the block ctx + ctx.block_ctxs[u] = _sort_ctx(this_block_ctx) + + # RANGE/IF add to the next ctx + # STORE/ASSIGN subtract from the next ctx + if u.op in {Ops.RANGE, Ops.IF}: ctx.child_ctxs[u] = _sort_ctx(ctx.block_ctxs[u] + (u,)) + elif u.op is Ops.STORE: # ugh, deal with non-reduce locals. probably wrong - if isinstance(s.src[0].dtype, PtrDType) and s.src[0].dtype.local: - idx_context, store_context = temp_block_ctxs[s.src[0]], temp_block_ctxs[s] - this_block_ctx += [x for x in store_context if x not in idx_context and x.op is Ops.RANGE] - elif s.op is Ops.ASSIGN: - # flow though assign, but remove the ranges used in the assign - assert s.src[0].op is Ops.DEFINE_ACC - this_block_ctx += [x for x in temp_block_ctxs[s.src[1]] if x not in s.src[0].src[1:]] + if any(x.op is Ops.DEFINE_LOCAL for x in u.src[0].toposort()): + idx_context, store_context = ctx.last_ctx(u.src[0]), ctx.last_ctx(u.src[1]) + ctx.child_ctxs[u] = tuple([y for y in store_context if y not in idx_context and y.op is Ops.RANGE]) + else: ctx.child_ctxs[u] = () + elif u.op is Ops.ASSIGN: + assert u.src[0].op is Ops.DEFINE_ACC + ctx.child_ctxs[u] = tuple([y for y in ctx.last_ctx(u.src[1]) if y not in u.src[0].src[1:]]) + return ctx + +# ***** make blocks ***** + +DONT_PLACE_IN_BLOCK = {Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL, Ops.DEFINE_VAR, Ops.SPECIAL, Ops.CONST} + +def add_blockends(base_block:UOp, new_ctx:tuple[UOp, ...], current_ctx:tuple[UOp, ...], cnt:int=1) -> UOp: + ends_to_add = [z for z in new_ctx if z not in current_ctx] + while len(ends_to_add): + r:UOp = ends_to_add.pop(-1) + new_ctx = tuple([z for z in new_ctx if z is not r]) + end_uop = UOp(Ops.ENDIF if r.op is Ops.IF else Ops.ENDRANGE, src=(r,)) + base_block = UOp(Ops.BLOCKEND, src=(base_block,)*cnt, arg=BasicBlock2((end_uop,), tuple(new_ctx), end=r, cnt=cnt)) + return base_block + +def make_block_bottom_up(ctx:BlockContext, x:UOp): + if x.op is Ops.BLOCKSTART: + current_ctx, child_ctx = x.arg + lst = list(x.src) + child_count = 1 + else: + current_ctx, child_count, child_ctx = ctx.block_ctxs[x], ctx.child_count[x], ctx.child_ctxs.get(x, None) + lst = [x] + + # count of times we've seen this block, or a seed for a new block if we can't merge it + unmergable: defaultdict[UOp, int] = defaultdict(int) + blockseeds = defaultdict(list) + + # add the srcs of this to the frontier + # NOTE: things may be in here multiple times, that's okay + frontier_nodes = list(flatten(y.src[::-1] for y in lst)) + while len(frontier_nodes): + u = frontier_nodes.pop(0) + if u.op not in DONT_PLACE_IN_BLOCK and ctx.child_count[u] == unmergable[u]+1: + # count is correct + if (newctx:=ctx.block_ctxs[u]) == current_ctx: + # block has same context, merge it, and put the srcs on the frontier + lst.append(u) + frontier_nodes.extend(u.src[::-1]) else: - # flow though everything else - this_block_ctx += temp_block_ctxs[s] - temp_block_ctxs[u] = sorted(dedup(this_block_ctx), key=lambda x: x.tuplize) + # block has different context, add it to blockseeds + blockseeds[(newctx, ctx.child_ctxs.get(u, None))].append(u) + del unmergable[u] + else: + # count is incorrect (or it's DONT_PLACE_IN_BLOCK), add it to unmergable + unmergable[u] += 1 - # make final block_ctxs, add BLOCKSTART to block_ctxs for IF and RANGE - block_ctxs: dict[UOp, tuple[UOp, ...]] = {} - for u in sink.toposort: - block_ctxs[u] = ((UOp(Ops.BLOCKSTART, src=(u,)),) + tuple(temp_block_ctxs[u])) if u.op in {Ops.IF, Ops.RANGE} else tuple(temp_block_ctxs[u]) + # add unmergables to sources + srcs = [] + for u,cnt in unmergable.items(): srcs += [add_blockends(u, ctx.block_ctxs[u], current_ctx, cnt=cnt)]*cnt - # TODO: there's probably a clever way to remove this while loop - while 1: - sink = graph_rewrite(sink, make_basic_blocks, ctx=(block_ctxs, children)) + # add blockseeds, with blockends as needed + for (new_ctx, new_child_ctx), v in blockseeds.items(): + base_block = UOp(Ops.BLOCKSTART, src=tuple(v), arg=(new_ctx, new_child_ctx)) + srcs.append(add_blockends(base_block, new_ctx, current_ctx)) - # add BLOCKFORK (slow!) - block_parent_count = collections.Counter(flatten([x.src for x in sink.toposort if x.op is Ops.BLOCK])) - non_block_parents = set(flatten([x.src for x in sink.toposort if x.op is not Ops.BLOCK])) - forks = {u:UOp(Ops.BLOCKFORK, src=(UOp(Ops.BLOCK, src=u.src, arg=BasicBlock(block_ctxs[u], (u,))),), arg=child_count) - for u,child_count in block_parent_count.items() if u.op not in DONT_PLACE_IN_BLOCK and child_count > 1 and u not in non_block_parents} + lst = block_reorder(lst[::-1]) + bb = BasicBlock2(tuple(lst), ctx=current_ctx, cnt=child_count, child_ctx=child_ctx) + return UOp(Ops.BLOCK, src=tuple(srcs), arg=bb) - if not len(forks): break - sink = sink.substitute(forks) +block_create = PatternMatcher([ + (UPat(GroupOp.All-DONT_PLACE_IN_BLOCK.union({Ops.BLOCK, Ops.BLOCKEND}), name="x"), make_block_bottom_up), +]) + +# ***** blockend merging **** - # combine matching BLOCKENDS +def merge_blockends(sink:UOp) -> UOp|None: + # only run on the final BLOCK with the SINK in it + if sink.arg.lst[-1].op is not Ops.SINK: return None + # combine matching BLOCKENDS, the keys of this dictionary are the RANGE UOps, values are the BLOCKENDs blockends_to_arg: dict[UOp, list[UOp]] = {} - for be in sink.toposort: + for be in sink.toposort(): if be.op is Ops.BLOCKEND: blockends_to_arg.setdefault(be.arg.end, []).append(be) new_forks = {} for k,v in blockends_to_arg.items(): # NOTE: if any BLOCKEND is the parent of any other with the same arg, this algo fails if len(v) > 1: - out = UOp(Ops.BLOCKFORK, src=(UOp(Ops.BLOCKEND, src=tuple(flatten(x.src for x in v)), - arg=BasicBlock(tuple(dedup(flatten([y.arg.ctx for y in v]))), v[0].arg.lst, k)),), arg=len(v)) + bb = BasicBlock2(v[0].arg.lst, _sort_ctx(flatten([y.arg.ctx for y in v])), k, cnt=sum(y.arg.cnt for y in v)) + out = UOp(Ops.BLOCKEND, src=tuple(flatten([x.src for x in v])), arg=bb) + # NOTE: bb.ctx != u.arg.ctx can cause problems here for u in v: new_forks[u] = out - sink = sink.substitute(new_forks) + if len(new_forks) == 0: return None + return sink.substitute(new_forks) + +pm_blockend_merge = PatternMatcher([(UPat(Ops.BLOCK, name="sink"), merge_blockends)]) + +# ***** block merging **** + +def merge_block(x:UOp): + unmergable_blocks, mergable_blocks = [], [] + mergable_dict: defaultdict[UOp, int] = defaultdict(int) + for y in x.src: + if y.op is Ops.BLOCK and x.op is Ops.BLOCK and x.arg.ctx == y.arg.ctx: mergable_dict[y] += 1 + elif y.op is Ops.BLOCK and x.op is Ops.BLOCKEND and x.arg.end in y.arg.ctx: mergable_dict[y] += 1 + else: unmergable_blocks.append(y) + for k,v in mergable_dict.items(): + if v == k.arg.cnt: mergable_blocks.append(k) + else: unmergable_blocks.extend([k]*v) + if len(mergable_blocks) == 0: return None + del mergable_dict + + # create the block + arg = replace(x.arg, lst=tuple(flatten([y.arg.lst for y in mergable_blocks]))+x.arg.lst) + return UOp(x.op, src=tuple(flatten([y.src for y in mergable_blocks])+unmergable_blocks), arg=arg) + +def remove_blockend(x:UOp): + # if there's any remaining blocks that need to go in this BLOCKEND, we don't remove it + if any(x.arg.end in y.arg.ctx for y in x.src if y.op in {Ops.BLOCK, Ops.BLOCKEND}): return None + + parent_blocks = [y for y in x.src if y.op is Ops.BLOCK and y.arg.child_ctx is not None and x.arg.end in y.arg.child_ctx] + assert all_same(parent_blocks), f"should never have two parent blocks (has {len(parent_blocks)})" + if len(parent_blocks) > 0: + parent_block = parent_blocks[0] + assert len(parent_blocks) == parent_block.arg.cnt + # range needs DEFINE_ACC to be before the range (never in DEFINE_ACC for if) + early_ops, late_ops = partition(x.arg.lst, lambda y: y.op is Ops.DEFINE_ACC and x.arg.end in y.src) + # NOTE: we have to add a barrier at the start if barrier is used in the range + if x.op is Ops.BLOCKEND and any(y.op is Ops.BARRIER for y in late_ops) and late_ops[-1].op is Ops.ENDRANGE: + late_ops = [UOp(Ops.BARRIER)] + late_ops + arg = BasicBlock2(tuple(early_ops)+parent_block.arg.lst+tuple(late_ops), tuple([y for y in x.arg.ctx if y is not x.arg.end]), cnt=x.arg.cnt) + return UOp(Ops.BLOCK, src=tuple(y for y in x.src if y is not parent_block)+parent_block.src, arg=arg) + +block_merge = PatternMatcher([ + (UPat((Ops.BLOCK, Ops.BLOCKEND), name="x"), merge_block), + (UPat(Ops.BLOCKEND, name="x"), remove_blockend), +]) + +# ****** finalize ****** - # reorder ops in block for speed - sink = sink.substitute({u:newu for u in sink.toposort if u.op is Ops.BLOCK and (newu:=block_reorder(u)) is not u}) +def finalize(sink:UOp) -> UOp: + if sink.op is not Ops.BLOCK or not all(x.op in DONT_PLACE_IN_BLOCK for x in sink.src): + raise RuntimeError("linearize failure") - # final rewrite to merge all blocks into one - sink = graph_rewrite(sink, pm_block_merge, ctx=children) + # place the early things + lst = sorted(dedup(sink.src), key=lambda x: x.tuplize) + list(sink.arg.lst) - # there should just be one block left, with a few parents with 0 srcs - assert sink.op is Ops.BLOCK - _uops = sorted(dedup(sink.src), key=lambda x: x.tuplize) - assert all(len(x.src) == 0 and x.op not in {Ops.BLOCK, Ops.BLOCKSTART, Ops.BLOCKEND, Ops.BLOCKFORK} for x in _uops) - _uops += sink.arg.lst + if __debug__: type_verify(lst) - # sanity checks (NOTE: these can cause things to be skipped in BEAM) - if not skip_check: type_verify(_uops) + return UOp(Ops.BLOCKFINAL, arg=BasicBlock2(tuple(lst))) - # strip the SINK - return _uops[:-1] +pm_finalize = PatternMatcher([(UPat(Ops.BLOCK, name="sink"), finalize)]) diff --git a/tinygrad_repo/tinygrad/codegen/lowerer.py b/tinygrad_repo/tinygrad/codegen/lowerer.py index 429769fd1d..5790fc120f 100644 --- a/tinygrad_repo/tinygrad/codegen/lowerer.py +++ b/tinygrad_repo/tinygrad/codegen/lowerer.py @@ -1,11 +1,12 @@ # the job of the lowerer is to do indexing -import functools, itertools, operator +import itertools, operator, math from dataclasses import dataclass from typing import cast -from tinygrad.dtype import dtypes, PtrDType -from tinygrad.ops import KernelInfo, UOp, Ops, graph_rewrite, PatternMatcher, UPat, sint, identity_element, sint_to_uop +from tinygrad.dtype import dtypes, PtrDType, least_upper_dtype +from tinygrad.uop.ops import KernelInfo, UOp, Ops, PatternMatcher, UPat, sint, sint_to_uop from tinygrad.renderer import Renderer -from tinygrad.helpers import all_int, prod, partition, flatten +from tinygrad.helpers import all_int, prod, partition, flatten, unwrap +from tinygrad.codegen.symbolic import symbolic # returns the axes to create new_shape if new_shape can be created by combining axis from old_shape def get_contraction(old_shape:tuple[sint, ...], new_shape:tuple[sint, ...]) -> list[list[int]]|None: @@ -14,24 +15,56 @@ def get_contraction(old_shape:tuple[sint, ...], new_shape:tuple[sint, ...]) -> l except ValueError: return None return [list(range(st,ed)) for st,ed in zip([0]+split[:-1], split[:-1]+[len(old_shape)])] -# ***** indexing ***** +def get_contraction_with_reduce(old_shape:tuple[sint, ...], new_shape:tuple[sint, ...], reduce_axis:tuple[int, ...]) -> list[list[int]]|None: + if (contraction:=get_contraction(old_shape, new_shape)) is None: return None + # contraction returns the 1s as right justified as possible + # normally this contraction is good, but sometimes the reduce dim is empty. borrow from the next one, leaving one + # this ensures there's always ones available in the reduce dimension. this is also a valid contraction + for i in range(len(contraction)): + if i in reduce_axis and len(contraction[i]) == 0: + take_from = i+1 + while take_from < len(contraction) and len(contraction[take_from]) == 0: + assert new_shape[take_from] == 1 + take_from += 1 + if take_from == len(contraction) or new_shape[take_from] != 1: return None # nothing to take + for j in range(take_from, i, -1): + assert len(contraction[j]) > 0 + contraction[j-1] = contraction[j][:-1] + contraction[j] = contraction[j][-1:] + return contraction -def _limit_dims(dims:tuple[sint, ...], max_sizes:tuple[int, ...]): +# ***** indexing ***** +def _group_dims(dims:tuple[sint, ...], max_sizes:tuple[int, ...]): # TODO: symbolic shape if not all_int(dims): return dims while len(dims) > len(max_sizes) or any(d > m for d,m in zip(dims, max_sizes)): for i,m in enumerate(max_sizes): - if dims[i] * dims[i+1] <= m: + if i < (len(dims)-1) and dims[i] * dims[i+1] <= m: dims = dims[:i] + (dims[i]*dims[i+1],) + dims[i+2:] break - else: raise RuntimeError(f"cannot limit dim {dims=}, {max_sizes=}") + else: return None return dims +def _split_dims(dims, max_sizes): + if all(d <= m for d,m in zip(dims, max_sizes)): return dims + _dims = list(dims) + [1]*(3-len(dims)) + for i in range(len(_dims)): + while _dims[i] > max_sizes[i]: + div = next((d for d in range(2, math.ceil(math.sqrt(_dims[i])) + 1) if (_dims[i] % d) == 0), 1) + if div == 1: raise RuntimeError(f"cannot limit dim {dims=}, {max_sizes=}") + _dims[i], _dims[(i+1)%len(_dims)] = _dims[i]//div, _dims[(i+1)%len(_dims)]*div + return tuple(_dims[:2] if _dims[2] == 1 else _dims[0] if _dims[1:3] == [1,1] else _dims) + def get_grouped_dims(prefix, dims:tuple[sint, ...], max_sizes:tuple[int, ...]|None, reverse=False) -> list[UOp]: if reverse: dims = dims[::-1] - limited = _limit_dims(dims, max_sizes) if max_sizes is not None else dims + # try to group first: (a, b, c, d) -> (ab, c, d) + limited = (grouped if (grouped := _group_dims(dims, max_sizes)) else dims) if max_sizes is not None else dims + # check if grouping failed + if max_sizes is not None and len(limited) > len(max_sizes): raise RuntimeError(f"cannot limit dim {dims=}, {max_sizes=}") + # try to split up dims: (a,) -> (b, c) + if limited == dims: limited = _split_dims(dims, max_sizes) if max_sizes is not None else dims ret = raw_idxs = [UOp(Ops.SPECIAL, dtypes.int, (), (f"{prefix}{i}", s)) for i,s in enumerate(limited)] - if limited != dims: + if len(limited) < len(dims): ret = [] if (contraction:=get_contraction(dims, limited)) is None: raise AssertionError(f"get_contraction should not be None {dims=} {limited=}") for idx, contraction_group in zip(raw_idxs, contraction): @@ -39,6 +72,11 @@ def get_grouped_dims(prefix, dims:tuple[sint, ...], max_sizes:tuple[int, ...]|No ret.append(idx % dims[c]) idx //= dims[c] ret.append(idx) + elif len(limited) > len(dims): + a, b = len(limited), len(dims) + if a == 2 and b == 1: ret = [raw_idxs[0] * limited[1] + raw_idxs[1]] + if a == 3 and b == 1: ret = [raw_idxs[0] * (limited[1] * limited[2]) + raw_idxs[1] * limited[2] + raw_idxs[2]] + if a == 3 and b == 2: ret = [raw_idxs[0] * limited[1] + raw_idxs[1], raw_idxs[2]] return ret[::-1] if reverse else ret @dataclass @@ -53,8 +91,8 @@ def get_index(ast:UOp, opts:Renderer) -> IndexContext: full_shape = ast.full_shape first_upcasted = len(full_shape)-ki.upcasted # if there's no reduce, this is first_upcasted. assumes reduces are at the end - first_reduce = min([first_upcasted]+flatten(x.axis_arg for x in ast.toposort if x.op is Ops.REDUCE_AXIS)) - local_loads = [x for x in ast.toposort if x.op is Ops.LOAD and x.src[0].op is Ops.DEFINE_LOCAL] + first_reduce = min([first_upcasted]+flatten(x.axis_arg for x in ast.toposort() if x.op is Ops.REDUCE_AXIS)) + local_loads = [x for x in ast.toposort() if x.op is Ops.LOAD and x.src[0].op is Ops.DEFINE_LOCAL] # NOTE: sum up the reduced axes looking across all local loads, yields the number of grouped reduces group_for_reduces = sum([any(l.st_arg.shape[i]!=ast.src[0].st_arg.shape[i] for l in local_loads) for i in range(first_reduce,first_upcasted)]) global_dims = first_reduce-ki.local_dims @@ -69,10 +107,10 @@ def get_index(ast:UOp, opts:Renderer) -> IndexContext: get_grouped_dims("lidx", full_shape[global_dims:first_reduce+group_for_reduces], opts.local_max) else: # all loops are RANGES - idxs = [UOp(Ops.RANGE, dtypes.int, (sint_to_uop(0), sint_to_uop(g)), i) for i,g in enumerate(full_shape[:first_reduce])] + idxs = [UOp(Ops.RANGE, dtypes.int, (sint_to_uop(g),), i) for i,g in enumerate(full_shape[:first_reduce])] # reduce loops - idxs += [UOp(Ops.RANGE, dtypes.int, (sint_to_uop(0), sint_to_uop(g)), i) + idxs += [UOp(Ops.RANGE, dtypes.int, (sint_to_uop(g),), i) for i,g in enumerate(full_shape[first_reduce+group_for_reduces:first_upcasted], start=first_reduce+group_for_reduces)] # upcast loops @@ -83,7 +121,7 @@ def get_index(ast:UOp, opts:Renderer) -> IndexContext: # late indexes (group for reduce) ridxs = idxs[:] for a in range(first_reduce, first_reduce+group_for_reduces): - ridxs[a] = UOp(Ops.RANGE, dtypes.int, (sint_to_uop(0), sint_to_uop(full_shape[a])), 1000+a) + ridxs[a] = UOp(Ops.RANGE, dtypes.int, (sint_to_uop(full_shape[a]),), 1000+a) return IndexContext(idxs, ridxs) @@ -97,12 +135,8 @@ def lower_reduce_axis(ctx: IndexContext, x: UOp): ret = x.src[0] if len(contract_axis:=flatten(x.arg for x in reduce_expand)): ret = UOp(Ops.CONTRACT, x.dtype.vec(prod(x[1] for x in contract_axis)), (ret,), tuple(contract_axis)) - ret = functools.reduce(lambda x,y: x.alu(alu_op, y), [ret.gep(i) for i in range(ret.dtype.count)]) - if not len(reduce_range): return ret - # create ACC and assign - acc = UOp(Ops.DEFINE_ACC, x.dtype, (x.const_like(identity_element(alu_op, x.dtype.scalar())),) + tuple(reduce_range), (ctx.acc_num,)) - ctx.acc_num += 1 - return acc.assign(acc.alu(alu_op, ret)) + # REDUCE supports both "horizonal" reduction and range reduction. the horizonal elements are taken in the nearest group + return UOp(Ops.REDUCE, x.dtype, (ret,)+tuple(reduce_range), alu_op) def lower_load_store(ctx: IndexContext, x: UOp): idx, valid = x.st_arg.to_indexed_uops(ctx.ridxs if x.op is Ops.LOAD and x.src[0].op is Ops.DEFINE_LOCAL else ctx.idxs) @@ -111,8 +145,8 @@ def lower_load_store(ctx: IndexContext, x: UOp): barrier = (UOp(Ops.BARRIER, dtypes.void, (x.src[2],)),) if x.src[0].op is Ops.DEFINE_LOCAL else () return UOp(Ops.LOAD, x.dtype, (buf.index(idx, valid),) + barrier) # NOTE: only store the local reduceop in the threads that are actually doing the reduce - if cast(PtrDType, x.src[0].dtype).local and x.src[2].op is Ops.ASSIGN: - reduce_input = x.src[2].src[1].src[1] if x.src[2].src[1].src[1] is not x.src[2].src[0] else x.src[2].src[1].src[0] + if cast(PtrDType, x.src[0].dtype).local and x.src[2].op is Ops.REDUCE: + reduce_input = x.src[2].src[0] store_back = reduce_input.op is Ops.LOAD and cast(PtrDType, reduce_input.src[0].dtype).local else: store_back = False # NOTE: If we're storing the reduced value back into each thread, need to zero-out the reduced axes @@ -122,12 +156,79 @@ def lower_load_store(ctx: IndexContext, x: UOp): if oidx is not ridx: valid = valid * oidx.eq(0) return UOp(Ops.STORE, dtypes.void, (buf.index(idx, valid), x.src[2])) +def lower_const(x:UOp): + assert all(v.mask is None for v in unwrap(x.st).views), f"VIEW in CONST/DEFINE_VAR source must be unmasked, got {x.st}" + return x.replace(src=()) + pm_lowerer = PatternMatcher([ (UPat(Ops.REDUCE_AXIS, name="x"), lower_reduce_axis), + (UPat((Ops.CONST, Ops.DEFINE_VAR), src=(UPat(Ops.VIEW),), name="x"), lower_const), (UPat(Ops.VALID, src=(UPat(Ops.VIEW),), name="x"), lambda ctx,x: x.st_arg.to_indexed_uops(ctx.idxs)[1]), # rewrite LOAD/STORE VIEW to LOAD/STORE with indexed (UPat((Ops.LOAD, Ops.STORE), src=(UPat(), UPat(Ops.VIEW)), allow_any_len=True, name="x"), lower_load_store), (UPat(Ops.INDEX, src=(UPat.var("b"), UPat.var("idx"), UPat.const(dtypes.bool, True))), lambda b, idx: b.index(idx)), + (UPat(Ops.IGNORE, name="x"), lambda x: x.src[0]), ]) -def rewrite_shapetracker_with_index(ast:UOp, opts:Renderer) -> UOp: return graph_rewrite(ast, pm_lowerer, ctx=get_index(ast, opts)) +# **** this is the "quantization preprocessor", it makes ONNX quantized models, and probably also others, actually use ints **** + +FP = (1 << 15) +pm_quant = symbolic+PatternMatcher([ + # cast after add/mul + (UPat.var("x").cast(dtypes.float32) + UPat.var("y").cast(dtypes.float32), + lambda x,y: (x.cast(least_upper_dtype(x.dtype, y.dtype))+y.cast(least_upper_dtype(x.dtype, y.dtype))).cast(dtypes.float32)), + (UPat.var("x").cast(dtypes.float32) * UPat.var("y").cast(dtypes.float32), + lambda x,y: (x.cast(least_upper_dtype(x.dtype, y.dtype))*y.cast(least_upper_dtype(x.dtype, y.dtype))).cast(dtypes.float32)), + + # masked MUL after masked ADD + ((UPat.var("x") + UPat.var("v").where(UPat.var('cadd'), UPat(Ops.CONST, arg=0))) * UPat.var("v").where(UPat.var('cmul'), UPat(Ops.CONST, arg=0)), + lambda x,v,cadd,cmul: x*v.where(cmul, 0)+v.where(cadd*cmul, 0)), + + # MUL after reduce + (UPat(Ops.REDUCE_AXIS, src=(UPat.var("x") * UPat.cvar("c"),), name="r"), lambda x,c,r: r.replace(src=(x,))*c), + # CAST after reduce (doesn't work if it's a size change) + (UPat(Ops.REDUCE_AXIS, src=(UPat(Ops.CAST, src=(UPat.var("x"),)),), name="r"), + lambda x,r: r.replace(dtype=x.dtype, src=(x,)).cast(r.dtype) if dtypes.is_float(r.dtype) else None), + + # x*c1 + y*c2 -> (x+y)*c1 (if c1 and c2 are close floats) + (UPat.var("x")*UPat.cvar("c1", dtype=dtypes.floats) + UPat.var("y")*UPat.cvar("c2", dtype=dtypes.floats), + lambda x,y,c1,c2: (x+y)*c1 if abs(c1.arg-c2.arg) < 1e-9 else None), + # mul 0 * c1 is 0 + (UPat(Ops.VALID, src=(UPat(Ops.VIEW, name="v"),)).where(UPat.cvar("c1"), UPat(Ops.CONST, arg=0)) * + UPat(Ops.LOAD, src=(UPat(), UPat(Ops.VIEW, name="v"))).cast(dtypes.int).cast(dtypes.float).named("ld"), lambda ld,v,c1: ld*c1), + # mul (with plus) 0 * c1 is 0 + (UPat(Ops.VALID, src=(UPat(Ops.VIEW, name="v"),)).where(UPat.cvar("c1"), UPat(Ops.CONST, arg=0)) * + (UPat(Ops.LOAD, src=(UPat(), UPat(Ops.VIEW, name="v"))).cast(dtypes.int) + \ + UPat(Ops.VALID, src=(UPat(Ops.VIEW, name="v"),)).where(UPat.cvar(), UPat(Ops.CONST, arg=0))).cast(dtypes.float).named("ld"), + lambda ld,v,c1: ld*c1), + + # const push through add + ((UPat.var("x")*UPat.cvar("c1") + UPat.var("y")*UPat.cvar("c2")) * UPat.cvar("c3"), lambda x,y,c1,c2,c3: (x*c1*c3) + (y*c2*c3)), + + # fixed point mult, replace (x.float()*c1+c2).int() with an int expression + ((UPat.var("x").cast(dtypes.float)*UPat.var("c1")+UPat.var("cc")).cast(dtypes.int), + lambda x,c1,cc: ((x*(c1*FP).cast(x.dtype) + (cc*FP).cast(x.dtype)) // FP).cast(dtypes.int)), + # fixed point mult, replace (x.float()*c1 + y.float()*c2)*cc.int() with an int expression + ((UPat.var("x").cast(dtypes.float)*UPat.var("c1")+UPat.var("y").cast(dtypes.float)*UPat.var("c2")+UPat.var("cc")).cast(dtypes.int), + lambda x,c1,y,c2,cc: ((x*(c1*FP).cast(x.dtype) + y.cast(x.dtype)*(c2*FP).cast(x.dtype) + (cc*FP).cast(x.dtype)) // FP).cast(dtypes.int)), + + # where move + (UPat.var("valid").where(UPat.var("yes"), UPat(Ops.CONST, arg=0))*UPat.var("mul"), lambda valid, yes, mul: + (yes*mul*valid.where(UOp.const(mul.dtype, 1), UOp.const(mul.dtype, 0))) if yes.op is not Ops.CONST or yes.arg != 1 else None), + ((UPat.var("x")*UPat.cvar("c"))*(UPat.var().where(UPat(Ops.CONST, arg=1), UPat(Ops.CONST, arg=0)).named("v")), lambda x,c,v: (x*v)*c), + (UPat.var("x").cast().named('c') * UPat.var('valid').where(UPat(Ops.CONST, arg=1), UPat(Ops.CONST, arg=0)), lambda x,c,valid: + (x*valid.where(UOp.const(x.dtype, 1), UOp.const(x.dtype, 0))).cast(c.dtype)), + ((UPat.var('x') * UPat.var('v1').where(UPat(Ops.CONST, arg=1), UPat(Ops.CONST, arg=0)) * + UPat.var('v2').where(UPat(Ops.CONST, arg=1), UPat(Ops.CONST, arg=0))).named("mul"), lambda x, mul, v1, v2: + x * (v1&v2).where(UOp.const(mul.dtype, 1), UOp.const(mul.dtype, 0))), + + # where on two adds + (UPat.var("x") + UPat.var("v").where(UPat.var("a0"), UPat.var("a1")) + UPat.var("v").where(UPat.var("b0"), UPat.var("b1")), + lambda x,v,a0,a1,b0,b1: x + v.where(a0+b0, a1+b1)), + + # split REDUCE into multiple reduces (who remembers FOIL?) + (UPat(Ops.REDUCE_AXIS, src=((UPat(Ops.CAST, name="v1")+UPat.var("c1")) * UPat(Ops.CAST, name="v2"),), name="r"), + lambda v1,v2,c1,r: r.replace(src=(v1*v2,)) + r.replace(src=(c1*v2,))), + (UPat(Ops.REDUCE_AXIS, src=((UPat(Ops.CAST, name="v1")+UPat.var("c1")) * (UPat(Ops.CAST, name="v2",)+UPat.var("c2")),), name="r"), + lambda v1,v2,c1,c2,r: r.replace(src=(v1*v2,)) + r.replace(src=(c2*v1,)) + r.replace(src=(c1*v2,)) + r.replace(src=(c1*c2,))), +]) diff --git a/tinygrad_repo/tinygrad/codegen/symbolic.py b/tinygrad_repo/tinygrad/codegen/symbolic.py new file mode 100644 index 0000000000..d240aa3668 --- /dev/null +++ b/tinygrad_repo/tinygrad/codegen/symbolic.py @@ -0,0 +1,469 @@ +# all of symbolic lives here now +from typing import Any, Literal, cast +import math, operator, struct, functools +from collections import defaultdict +from tinygrad.uop.ops import Ops, PatternMatcher, UPat, UOp, GroupOp, exec_alu +from tinygrad.dtype import ConstType, dtypes, PtrDType +from tinygrad.helpers import partition, all_same, prod, flatten, get_single_element, cdiv, cmod +from tinygrad.codegen.transcendental import xpow + +# ******** phase 1 of symbolic used to live in ops, it's the most generic folding rules ******** + +def simplify_pow(x:UOp, c:UOp) -> UOp|None: + if c.arg < 0: return x.reciprocal().pow(-c) + if c.arg == 0: return x.const_like(1) + if int(c.arg-0.5)+0.5 == c.arg: return x.pow(c.const_like(c.arg-0.5)) * x.sqrt() + if int(c.arg) == c.arg: return (y := x.pow(c.const_like(c.arg//2))) * y * (x if c.arg%2 == 1 else 1) + return None + +def fold_bitcast(root:UOp, c:UOp) -> UOp|None: + if (from_fmt:=c.dtype.scalar().fmt) is None or (to_fmt:=root.dtype.scalar().fmt) is None: return None + def convert(v:Any): return struct.unpack(to_fmt, struct.pack(from_fmt, v))[0] + return root.const_like(convert(c.arg) if root.dtype.count == 1 else tuple(map(convert, c.arg))) + +symbolic_simple = PatternMatcher([ + # ** self folding ** + (UPat.var("x") + 0, lambda x: x), # x+0 -> x + (UPat.var("x") * 1, lambda x: x), # x*1 -> x + (UPat.var("x") // UPat.var("x"), lambda x: x.const_like(1)), # x//x -> 1 + (UPat.var("x") // 1, lambda x: x), # x//1 -> x + (UPat.var("x") // -1, lambda x: -x), # x//-1 -> -x + (UPat.var("x") / UPat.var("x"), lambda x: x.const_like(1)), # x/x -> 1 + ((UPat.var("x") * UPat.var("x2")) / UPat.var("x2"), lambda x,x2: x), # (x*x2)/x2 -> x + ((UPat.var() % UPat.var("y")).named("base") % UPat.var("y"), lambda base,y: base), # (x%y)%y = -> x%y (rewritten with base for speed) + (UPat.var("x")%UPat.cvar("c")+(UPat.var("x")//UPat.cvar("c"))*UPat.cvar("c"), lambda x,c: x), # (x%c)+(x//c)*c = x + ((UPat.var("x")//UPat.cvar("c1"))*UPat.cvar("c3")+UPat.var("x")%UPat.cvar("c1")*UPat.cvar("c2"), + lambda x,c1,c2,c3: x*c2 if c1.arg*c2.arg==c3.arg else None), # (x%c1)*c2+(x//c1)*c3 = x*c2 if c1*c2==c3 + (UPat.var("x", dtype=dtypes.bool) & UPat.cvar("c", vec=False), lambda x,c: x if c.arg else c), + (UPat.var("x", dtype=dtypes.bool) | UPat.cvar("c", vec=False), lambda x,c: c if c.arg else x), + (UPat(GroupOp.Idempotent, src=(UPat.var("x"), UPat.var("x"))), lambda x: x), + (UPat.var("x", dtype=dtypes.bool).logical_not().logical_not(), lambda x: x), + (UPat.var("x", dtype=dtypes.bool).where(UPat.const(dtypes.bool, True), UPat.const(dtypes.bool, False)), lambda x: x), + # ** zero folding ** + (UPat.var("x") < UPat.var("x"), lambda x: x.const_like(False).cast(dtypes.bool.vec(x.dtype.count))), # x < x -> False + (UPat.var("x") % UPat.var("x"), lambda x: x.const_like(0)), # x%x -> 0 + (UPat.var("x", dtype=dtypes.ints) != UPat.var("x", dtype=dtypes.ints), + lambda x: x.const_like(False).cast(dtypes.bool.vec(x.dtype.count))), # x != x -> False (only ints) + # x*0 -> 0 or 0*x -> 0 + # if x is nan or inf it should render the nan value. + # NOTE: this can be wrong for loaded NaN + (UPat.var("x") * 0, lambda x: x.const_like(float("nan") if isinstance(x.arg, float) and (math.isnan(x.arg) or math.isinf(x.arg)) else 0)), + # ** constant folding ** + # TODO: add const folding for Ops.THREEFRY + (UPat(GroupOp.Unary, src=(UPat((Ops.VCONST, Ops.CONST)),), name="a"), lambda a: a.const_like(exec_alu(a.op, a.dtype, [a.src[0].arg], False))), + (UPat(GroupOp.Binary-{Ops.THREEFRY}, src=(UPat((Ops.VCONST, Ops.CONST)),)*2, name="a"), + lambda a: a.const_like(exec_alu(a.op, a.dtype, [a.src[0].arg, a.src[1].arg], False))), + (UPat(GroupOp.Ternary, src=(UPat((Ops.VCONST, Ops.CONST)),)*3, name="a"), + lambda a: a.const_like(exec_alu(a.op, a.dtype, [a.src[0].arg, a.src[1].arg, a.src[2].arg], False))), + # bool MUL is AND, ADD/MAX is OR. prevents other rules to rewrite bool ADD/MUL incorrectly + (UPat.var('x', dtype=dtypes.bool) * UPat.var('y', dtype=dtypes.bool), lambda x,y: x&y), + (UPat.var('x', dtype=dtypes.bool) + UPat.var('y', dtype=dtypes.bool), lambda x,y: x|y), + (UPat.var('x', dtype=dtypes.bool).maximum(UPat.var('y', dtype=dtypes.bool)), lambda x,y: x|y), + # *** cast/bitcast *** + (UPat(Ops.CAST, name="root", src=(UPat.cvar("c"),)), lambda root, c: root.const_like(c.arg)), + (UPat((Ops.CAST, Ops.BITCAST), name="root"), lambda root: root.src[0] if root.dtype == root.src[0].dtype else None), + (UPat(Ops.BITCAST, name="root", src=(UPat.cvar("c"),)), fold_bitcast), + # ** pow ** + (UPat.var("x").alu(Ops.POW, UPat.cvar("c", vec=False)), simplify_pow), + # positive const ** x + (UPat.cvar("c", vec=False).alu(Ops.POW, UPat.var("x")), lambda c,x: c if c.arg == 1 else (x*math.log2(c.arg)).exp2() if c.arg > 0 else None), +]) + +# ******** phase 2 builds on phase 1, it includes the old "symbolic", rules that match deeper ******** + +def split_uop(x:UOp, sep:Ops): + if x.op is sep: + for s in x.src: yield from split_uop(s, sep) + else: yield x + +def fold_unrolled_divs(divs:UOp, denominator: int, fac=1) -> UOp|None: + # div pattern in unrolled arange + # example: (x//4+(x+1)//4+(x+2)//4+(x+3)//4 -> x + seen_const, ans = [], None + for u in split_uop(divs, Ops.ADD): + if fac!=1: + if u.op is not Ops.MUL or u.src[1].op is not Ops.CONST or u.src[1].arg != fac: return None + u = u.src[0] + if not (u.op is Ops.IDIV and u.src[1].op is Ops.CONST): return None + if denominator != u.src[1].arg: return None + if (s0:=u.src[0]).vmin < 0: return None + # assumed CONST is the last of an ADD + if s0.op is Ops.ADD and s0.src[1].op is Ops.CONST and s0.src[1].op is Ops.CONST: + seen_const.append(s0.src[1].arg) + s0 = s0.src[0] + else: seen_const.append(0) + if ans is None: ans = s0 + if ans is not s0: return None + if ans is None: return None + # the first (denominator-len(seen_const)) terms may have been folded to 0 already + for i in range(denominator-len(seen_const)): + if ans is not None and 0 <= ans.vmin and ans.vmax + i < denominator: seen_const.append(i) + if sorted(seen_const)==list(range(denominator)): + return fac*ans + return None + +def lt_folding(x:UOp, c:int) -> UOp|None: + p, np = partition(split_uop(x, Ops.ADD), lambda u: u.const_factor() == 1) + if np and (d:=math.gcd(*[u.const_factor() for u in np], c)) > 1 and 0 <= sum(u.vmin for u in p) and sum(u.vmax for u in p) < d: + return cast(UOp, functools.reduce(operator.add, np).divides(d))<(c//d) + return None + +def canonicalize_simplex(X:UOp) -> UOp|None: + # (X := a0*x0 + a1*x1 + ...) > 0 is equivalent to x0 + x1 + ... > 0 if xi >= 0 and ai > 0 for ints. + # returns x0 + x1 + ... in such case, or None if not + changed, ret = False, [] + for u in split_uop(X, Ops.ADD): + # assumed the const is the last src of MUL + if u.op is Ops.MUL and u.src[1].op is Ops.CONST and u.src[1].arg > 0: + changed = True + u = u.src[0] + if not (u.op in GroupOp.Irreducible and u.vmin >= 0): return None + ret.append(u) + return functools.reduce(operator.add, ret) if changed else None + +def div_and_mod_folding(x: UOp, y: UOp, which: Literal[Ops.MOD, Ops.IDIV], split_rem: bool=False) -> UOp|None: + # simplify x // y or x % y, None means no change + # simple cancel div/mod case + x_min, x_max, y_min, y_max = x.vmin, x.vmax, y.vmin, y.vmax + assert isinstance(x_min, int) and isinstance(x_max, int) and isinstance(y_min, int) and isinstance(y_max, int) + + if y_min*y_max > 0 and (q:=cdiv(x_min,y_min)) == cdiv(x_min,y_max) == cdiv(x_max,y_min) == cdiv(x_max,y_max): + return x - q*y if which is Ops.MOD else x.const_like(q) + + if (y.op is not Ops.CONST) or ((c := y.arg) <= 0) or (x.dtype.count > 1): return None + + svars, factors, quotients, remainders, gcd, div, const, something_changed = [], [], [], [], c, 1, 0, False + for u in split_uop(x, Ops.ADD): + if u.op is Ops.MOD and which is Ops.MOD and u.src[1].op is Ops.CONST and u.src[1].arg%c == 0: + u = u.src[0] + something_changed = True + v: UOp = u.divides(f:=u.const_factor()) + q, r = divmod(f, c) + if r==0 or ((which is Ops.MOD or split_rem or u.op is Ops.CONST) and r!=f): something_changed = True + if u.op is Ops.CONST: const += f + else: # div is the smallest common divisor of all terms + if f > 1 and c % f == 0 and (div == 1 or div > f): div = f + gcd = math.gcd(r, gcd) + factors.append(f); svars.append(v); quotients.append(q); remainders.append(r) # noqa: E702 + + # we can fold if the expression has only one non-constant term and this term can only take on two values + if len(svars)==1 and (v:=svars[0]).vmax-v.vmin == 1: + y1 = cmod(factors[0]*v.vmin+const, c) if which is Ops.MOD else cdiv(factors[0]*v.vmin+const, c) + y2 = cmod(factors[0]*v.vmax+const, c) if which is Ops.MOD else cdiv(factors[0]*v.vmax+const, c) + return (y2-y1)*(v-v.vmin) + y1 + + # a//c = (a-a%c)/c, if we can fold a%c, we can fold a//c + # within a mod we can freely subtract multiples of c, we use this to see if a is congruent to an expression whose vmin/vmax are between 0 and c + rems = [min(r, r-c, key=abs) for r in remainders] + if (rem:=sum(r*v for r,v in zip(rems,svars))+const%c).vmin//c==rem.vmax//c and all(f > 0 for f in factors): + if which is Ops.MOD: return rem - rem.vmin//c*c + return sum((f-r)//c * v for f,r,v in zip(factors,rems,svars)) + (const-const%c+rem.vmin//c*c)//c + + if (g:=math.gcd(gcd, const))!=1: + ret = UOp(which, x.dtype, src=(sum(f//g * v for f,v in zip(factors, svars)) + const//g, x.const_like(c//g))) + return ret*g if which is Ops.MOD else ret + + if gcd != 1: something_changed = True + if not something_changed: + if which is Ops.IDIV and (1 < div < c) and (newx:=div_and_mod_folding(x, x.const_like(div), Ops.IDIV)) is not None: return newx//(c//div) + return None + quo, rem = x.const_like(const//c), x.const_like((const%c)//gcd) + for q,r,f,v in zip(quotients, remainders, factors, svars): + if which is Ops.IDIV and (not split_rem) and r!=0: + rem += f//gcd * v + else: + rem += r//gcd * v + quo += q * v + + # if numerator before/after is negative, and it has remainder, don't simplify because C divmod is different from python divmod. + if (x_min < 0 or rem.vmin < 0) and remainders: return None + if which is Ops.MOD: return gcd*(rem % (c//gcd)) + const%gcd + return rem//(c//gcd)+quo + +def gep_through_wmma(gep:UOp, wmma:UOp): + out_sz = prod(x[1] for x in wmma.arg[6][-1]) + wmma_idxs = gep.arg[::out_sz] + for i in range(out_sz): + if tuple(x-i for x in gep.arg[i::out_sz]) != wmma_idxs: return None + tsrcs = [] + for s,sz in zip(wmma.src, wmma.arg[6]): + src_args = [] + ssz = prod(x[1] for x in sz) + for w in wmma_idxs: src_args += list(range((w//out_sz)*ssz, (w//out_sz)*ssz + ssz)) + tsrcs.append(s.gep(tuple(src_args))) + return UOp(Ops.WMMA, gep.dtype, tuple(tsrcs), wmma.arg) + +gep_pushing = PatternMatcher([ + # GEP/VECTORIZE, GEP/GEP, GEP/CONST, GEP/VCONST + (UPat(Ops.GEP, src=(UPat(Ops.GEP, name='g2'),), name='g1'), + lambda g1, g2: g2.src[0].gep(tuple(g2.arg[g1.arg[i]] for i in range(len(g1.arg))))), + (UPat(Ops.GEP, src=(UPat(Ops.VECTORIZE, name="vec"),), name="gep"), + lambda gep, vec: UOp(Ops.VECTORIZE, gep.dtype, tuple(vec.src[i] for i in gep.arg)) if len(gep.arg) > 1 else vec.src[gep.arg[0]]), + (UPat(Ops.GEP, src=(UPat.cvar("c", vec=False),), name="gep"), lambda gep, c: gep.const_like(c.arg)), + (UPat(Ops.GEP, src=(UPat(Ops.VCONST, name="c"),), name="gep"), lambda gep, c: gep.const_like(tuple(c.arg[x] for x in gep.arg))), + # GEP on void is skipped + (UPat(Ops.GEP, src=(UPat(dtype=dtypes.void, name="x"),)), lambda x: x), + # GEP in order is removed + (UPat(Ops.GEP, name="g"), lambda g: g.src[0] if not isinstance(g.dtype, PtrDType) and g.arg == tuple(range(g.src[0].dtype.count)) else None), + # push all GEPs through ALUs (fix arange stuff) + (UPat(Ops.GEP, src=(UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST), name='alu'),), name='gep'), + lambda gep,alu: UOp(alu.op, alu.dtype.scalar().vec(gep.dtype.count), tuple(x.gep(gep.arg) for x in alu.src), alu.arg) \ + if not isinstance(gep.dtype, PtrDType) else None), + # CAT can't be rendered. it's a VECTORIZE on vectors, we expand to a single VECTORIZEs with GEPs (TODO: move this later) + (UPat(Ops.CAT, name="x"), lambda x: UOp(Ops.VECTORIZE, x.dtype, tuple(y.gep(i) for y in x.src for i in range(y.dtype.count))) \ + if not isinstance(x.dtype, PtrDType) else None), + # VECTORIZE on same GEP + (UPat(Ops.VECTORIZE, name="v", src=UPat(Ops.GEP, src=(UPat.var("x"),))), lambda v,x: x.gep(tuple(get_single_element(i.arg) for i in v.src))), + # push some GEPs through WMMAs + (UPat(Ops.GEP, src=(UPat(Ops.WMMA, name="wmma"),), name="gep"), gep_through_wmma), +]) + +commutative = PatternMatcher([ + # ** COMMUTATIVE flipping (only for ints) ** + # NOTE: this can break merging vector math by only flipping some of them + (UPat(GroupOp.Commutative, dtype=dtypes.int, name='x'), lambda x: x.replace(src=x.src[::-1]) if x.src[1].tuplize < x.src[0].tuplize else None), +]) + +symbolic = symbolic_simple+commutative+PatternMatcher([ + # ** boolean algebra ** + (UPat.var("x") | (UPat.var("x") & UPat.var()), lambda x: x), # x|(x&y) -> x + # ** combine terms ** + (UPat.var("x") * UPat.cvar("c0") + UPat.var("x") * UPat.cvar("c1"), lambda x,c0,c1: x*(c0+c1)), # (x*c0)+(x*c1) -> x*(c0+c1) + ((UPat.var("y") + UPat.var("x") * UPat.cvar("c0")) + UPat.var("x") * UPat.cvar("c1"), lambda x,y,c0,c1: y+x*(c0+c1)), + (UPat.var("x") + UPat.var("x") * UPat.cvar("c"), lambda x,c: x*(c+1)), # (x+x*c)-> x*(c+1) + ((UPat.var("y") + UPat.var("x")) + UPat.var("x") * UPat.cvar("c"), lambda x,y,c: y+x*(c+1)), + (UPat.var("x") + UPat.var("x"), lambda x: x*2), # (x+x)-> x*2 + ((UPat.var("y") + UPat.var("x")) + UPat.var("x"), lambda y,x: y+x*2), + ((UPat.var("x") / UPat.var("x2")) / UPat.var("x3"), lambda x,x2,x3: x/(x2*x3) if x2 is not x3 else None), # (x/x2)/x3 -> x/(x2*x3) + (-1 * (UPat.var("x") + UPat.cvar("c")), lambda x,c: (-x)+(-c)), # -(x+c) -> -x + -c + # a conditional with the same results either way is a noop, also fold const conditionals + (UPat.var().where(UPat.var("val"), UPat.var("val")), lambda val: val), + (UPat.cvar("gate", vec=False).where(UPat.var("c0"), UPat.var("c1")), lambda gate, c0, c1: c0 if gate.arg else c1), + (UPat.var("cond", dtype=dtypes.bool).logical_not().where(UPat.var("t"), UPat.var("f")), lambda cond, t, f: cond.where(f,t)), + # alu of two where with same conds can combine, only do if true branch or false branch is const + (UPat(GroupOp.Binary, name="alu", src=(UPat.var("c").where(UPat.var("t"), UPat.var("f")), UPat.var("c").where(UPat.var("tt"), UPat.var("ff")))), \ + lambda alu,c,t,tt,f,ff: c.where(t.alu(alu.op, tt), f.alu(alu.op, ff)) if t.op == tt.op == Ops.CONST or f.op == ff.op == Ops.CONST else None), + # ALU/variable min==max -> CONST (slow!) + (UPat(GroupOp.ALU|{Ops.DEFINE_VAR, Ops.SPECIAL, Ops.RANGE}, name="x"), lambda x: x.const_like(x.vmin) if x.vmin == x.vmax else None), + # max folding + (UPat.maximum(UPat.var("x"), UPat.var("y")), lambda x,y: x if x.vmin >= y.vmax else y if x.vmax <= y.vmin else None), + # TODO: why does this rule break beautiful_mnist? + #((UPat.var("x")+UPat.var("z")).maximum(UPat.var("y")+UPat.var("z")), lambda x,y,z: x.maximum(y) + z), + #((UPat.var("x")*UPat.cvar("c1")).maximum(UPat.var("x")*UPat.cvar("c2")), max_var_const), + # ** two stage ALU folding ** + *((UPat.var("x").alu(op, UPat.cvar("c1")).alu(op, UPat.cvar("c2")).named("f"), + lambda f,x,c1,c2: x.alu(f.op,c1.alu(f.op,c2))) for op in GroupOp.Associative), + ((UPat.cvar("c0") + UPat.var("x")) < UPat.cvar("c1"), lambda x,c0,c1: x<(c1-c0)), # c0 + x < c1 -> x < c1 - c0 + ((UPat.var("x") // UPat.cvar("c1")) // UPat.cvar("c2"), lambda x,c1,c2: x//(c1*c2)), # (x//c1)//c2 -> x//(c1*c2) + # ** lt ** + # c0*x 0 and c1.arg > 0 else None), + # c0*x 0 else None), + # ** move add/mul consts to end (NOTE: this is still happening before constant folding) ** + ((UPat.var("x") + UPat.cvar("c1")) + UPat.var("y"), lambda x,c1,y: (x+y)+c1), + ((UPat.var("x") * UPat.cvar("c1")) * UPat.var("y"), lambda x,c1,y: (x*y)*c1), + # *** rules from symbolic *** + # unrolled arange div folding + ((UPat() + UPat()//UPat.cvar("d", vec=False)).named("divs"), lambda divs,d: fold_unrolled_divs(divs, d.arg)), + ((UPat() + (UPat()//UPat.cvar("d", vec=False))*UPat.cvar("c")).named("divs"), lambda divs,d,c: fold_unrolled_divs(divs, d.arg, c.arg)), + # generic lt folding + (UPat.var("x", dtypes.sints) 0 + # not x < 1 -> X > 0 + ((UPat.var("x", dtypes.ints)<1).ne(True), lambda x: (newx<1).ne(True) if (newx:=canonicalize_simplex(x)) is not None else None), + # ** div ** + # div folding + ((UPat.var("x")//UPat.cvar("c") + UPat.cvar("a"))//UPat.cvar("d"), lambda x,c,a,d: (x+a*c)//(c*d) + if x.vmin>=0 or x.vmax<=0 else None), # (x//c+a)//d -> (x+a*c)//(c*d) + (UPat.var("x", dtypes.sints) // UPat.var("y"), lambda x,y: div_and_mod_folding(x,y,Ops.IDIV)), + (UPat.var("x") // UPat.var("d"), lambda x,d: -(x//(-d)) if d.vmax <=0 else None), + (UPat.var("x") // UPat.var("d"), lambda x,d: -((-x)//d) if x.vmax <=0 else None), + ((UPat.var("x", dtypes.sints)+UPat.cvar("c", vec=False)).named("n")//UPat.cvar("d", vec=False), + lambda x,c,n,d: (-(-(c.arg%d.arg + x - (d.arg-1))//d) + c.arg//d.arg) if x.vmax<=0 and n.vmin>=0 and d.arg>0 else None), + # ** mod ** + # mod folding + (UPat.var("x") % UPat.var("y"), lambda x,y: div_and_mod_folding(x,y,Ops.MOD)), + (UPat.var("x") % UPat.var("d"), lambda x,d: -(x%(-d)) if d.vmax <=0 else None), + (UPat.var("x") % UPat.var("d"), lambda x,d: -((-x)%d) if x.vmax <=0 else None), +])+gep_pushing + +symbolic_flat = symbolic+PatternMatcher([ + # ** combine terms (opinionated) ** + (-1 * (UPat.var("x") + UPat.var("y")), lambda x,y: (-x)+(-y)), # -(x+y) -> -x + -y + # (x+y)*c -> x*c+y*c. only for int, float has inf*0=nan issue + ((UPat.var("x", dtypes.ints) + UPat.var("y")) * UPat.cvar("c"), lambda x,y,c: x*c+y*c), +]) + +# ******** we take a small aside to "simplify_valid" to rewrite valids ******** + +def parse_valid(valid:UOp) -> tuple[UOp, bool, int]: + # if it's X <= c, returns X, True, c + # if it's X >= c, returns X, False, c + + # (X < c).ne(True) -> X >= c + if valid.op is Ops.CMPNE and valid.src[1].op is Ops.CONST and valid.src[1].arg == 1 and \ + (s0:=valid.src[0]).op is Ops.CMPLT and s0.src[1].op is Ops.CONST: return s0.src[0], False, s0.src[1].arg + # X < c -> X <= c-1 + if valid.op is Ops.CMPLT and valid.src[1].op is Ops.CONST and dtypes.is_int(valid.src[0].dtype): return valid.src[0], True, valid.src[1].arg-1 + raise ValueError(f"not able to parse {valid=}") + +def uop_given_valid(valid:UOp, uop:UOp) -> UOp|None: + # return None if valid is always False, otherwise the simplified uop (might be the same as input) + + # first, parse valid into {expr: (lower_bound, upper_bound)} + bounds:defaultdict[UOp, list[ConstType|None]] = defaultdict(lambda: [None, None]) + for stmt in split_uop(valid, Ops.AND): + try: expr, is_upper, c = parse_valid(stmt) + except ValueError: return uop # give up if we cannot parse the valid + bounds[expr][int(is_upper)] = c + + # don't simplify any other gates, can lead to OOB, we substitute them back later + uop = uop.substitute((load_subs:={u: UOp(Ops.NOOP, arg=u) for u in uop.toposort() if u.op is Ops.INDEX})) + + # simplify uop given that valid is True + for expr,v in bounds.items(): + v0, v1 = (expr.vmin if v[0] is None else v[0], expr.vmax if v[1] is None else v[1]) + # some expr has lower bound > upper bound -> valid is an empty set and we return None + if v0 > v1: return None + # whole node became a const + if v0 == v1: + uop = uop.substitute({expr:expr.const_like(v0)}).simplify() + continue + # every candidate is a set of contrained UOp based on valid, and if every item in a set simplifies the uop into a same output, we rewrite uop + candidates = [] + if expr.op is Ops.ADD and v0 == 1 and all(u.op in GroupOp.Irreducible for u in split_uop(expr, Ops.ADD)): + # if the constraint is a simplex: X0 + X1 + ... > 0, we can check if all Xi > 0 simplify into the same output + candidates.append([(Xi, UOp.variable("fake", 1, Xi.vmax, Xi.dtype)) for Xi in split_uop(expr, Ops.ADD)]) + # try checking the whole clause + if expr in uop.toposort(): candidates.append([(expr, UOp.variable("fake", v0, v1, expr.dtype))]) + + for candidate in candidates: + # if every branch in candidate gives the same simplified uop, we can rewrite the uop + newuops = [uop.substitute({X:newX}).simplify().substitute({newX:X}).simplify() for X,newX in candidate] + if uop.op is Ops.VECTORIZE and len(uop.src) == 2: + if all_same([uops.src[0] for uops in newuops]): uop = uop.replace(src=(newuops[0].src[0], uop.src[1])) + if all_same([uops.src[1] for uops in newuops]): uop = uop.replace(src=(uop.src[0], newuops[0].src[1])) + elif all_same(newuops): uop = newuops[0] + + # put the loads back in + uop = uop.substitute({v:k for k,v in load_subs.items()}) + return uop + +def _valid_priority(v: UOp, valids:list[UOp]): + # we want valid that's in other valids' parents to be first, so it's more likely the other valids get simplified + try: return sum(-1 if parse_valid(v)[0] in other.toposort() else 0 for other in valids) + except ValueError: return 0 + +def simplify_valid(valid:UOp) -> UOp|None: + ret:list[UOp] = [] + something_changed = False + valids = list(split_uop(valid, Ops.AND)) + for stmt in sorted(valids, key=lambda v: _valid_priority(v, valids)): + ret.append(newstmt if ret and (newstmt:=uop_given_valid(functools.reduce(operator.and_, ret), stmt)) is not None else stmt) + if ret[-1] is not stmt: something_changed = True + return functools.reduce(operator.and_, ret) if something_changed else None + +# ***** threefry ***** + +def threefry2x32(x: UOp, key: UOp): + # split x and key from uint64 to two uint32 + x0, x1 = (x & 0xffffffff).cast(dtypes.uint32), ((x // 2**32) & 0xffffffff).cast(dtypes.uint32) + key0, key1 = (key & 0xffffffff).cast(dtypes.uint32), ((key // 2**32) & 0xffffffff).cast(dtypes.uint32) + + rotations = [[13, 15, 26, 6], [17, 29, 16, 24]] + ks = [key1, key0 ^ key1 ^ 0x1BD11BDA, key0] + xr = [x0 + ks[-1], x1 + ks[0]] + for i in range(5): + for r in rotations[i % 2]: xr[0], xr[1] = (x0 := xr[0] + xr[1]), x0 ^ ((xr[1] * 2**r) + (xr[1] // 2**(32 - r))) + xr = [(xr[0] + ks[i % 3]), (xr[1] + ks[(i + 1) % 3] + i + 1)] + + return xr[1].cast(dtypes.uint64) * 2**32 | xr[0].cast(dtypes.uint64) + +# ******** phase 3 is the complete symbolic, and deals with very complex things like loop rewriting and threefry transform ******** + +def reduce_mul_chain(r:UOp): + if r.arg not in {Ops.ADD, Ops.MAX}: return None + if r.dtype != r.src[0].dtype: return None + inside, outside = [], [] + for m in split_uop(r.src[0], Ops.MUL): + m_parents = m.toposort() + if all(r not in m_parents for r in r.src[1:]) and (r.arg != Ops.MAX or m.vmin >= 0): outside.append(m) + else: inside.append(m) + if len(outside) == 0: return None + return r.replace(src=(prod(inside) if len(inside) else r.src[0].const_like(1),)+r.src[1:])*prod(outside) + +# this is symbolic 2.0 +sym = symbolic_flat+PatternMatcher([ + # self ASSIGN is just self + (UPat(Ops.ASSIGN, src=(UPat.var('x'), UPat.var('x'))), lambda x: x), + # VECTORIZE/CONST, VECTORIZE/GEP + (UPat(Ops.VECTORIZE, src=UPat(Ops.CONST), name="vec"), lambda vec: UOp.const(vec.dtype, tuple(x.arg for x in vec.src))), + (UPat(Ops.VECTORIZE, src=UPat(Ops.GEP, src=(UPat.var("x"),)), name="vec"), lambda vec,x: x.gep(tuple(y.arg[0] for y in vec.src))), + # reorder ALU/VECTORIZE + (UPat(GroupOp.ALU, src=(UPat(Ops.VECTORIZE, src=UPat(name='x')), UPat(Ops.VECTORIZE, src=UPat(name='y'))), name='alu'), + lambda x,y,alu: UOp(Ops.VECTORIZE, alu.dtype, (UOp(alu.op, alu.dtype.scalar(), (x,y)),)*alu.dtype.count)), + # VECTORIZE of a single element is just that element + (UPat(Ops.VECTORIZE, src=(UPat(name='x'),)), lambda x: x), + # VECTORIZE void is SINK + (UPat(Ops.VECTORIZE, dtype=dtypes.void, src=UPat(Ops.BARRIER, name='b')), lambda b: b), + (UPat(Ops.VECTORIZE, dtype=dtypes.void, name='x'), lambda x: UOp(Ops.SINK, dtypes.void, x.src)), + # tensor core with a 0 input is acc + (UPat(Ops.WMMA, src=(UPat.const(None, 0.0), UPat.var(), UPat.var("acc"))), lambda acc: acc), + (UPat(Ops.WMMA, src=(UPat.var(), UPat.const(None, 0.0), UPat.var("acc"))), lambda acc: acc), + # threefry + remove longs + (UPat(Ops.THREEFRY, dtype=dtypes.uint64, src=(UPat.var("x"), UPat.var("key"))), threefry2x32), + (UPat.var('x', dtypes.uint32).cast(dtypes.uint64).cast(dtypes.uint32), lambda x: x), # cast there and back is noop (TODO: genericize) + ((UPat.var('x', dtypes.uint64)&0xFFFFFFFF).cast(dtypes.uint32), lambda x: x.cast(dtypes.uint32)), # cast does truncation + (((UPat.var(None, dtypes.uint64)*(1<<32)) | UPat.var('y', dtypes.uint32).cast(dtypes.uint64)).cast(dtypes.uint32), lambda y: y), + (((UPat.var('x', dtypes.uint64)*(1<<32)) | UPat.var(None, dtypes.uint32).cast(dtypes.uint64))//(1<<32), lambda x: x), + # hacks for threefry long removal when padded (TODO: genericize) + (UPat.var('x', dtypes.uint32).cast(dtypes.uint64) * UPat.var('y').where(UPat.const(dtypes.uint64, 1<<32), UPat.const(dtypes.uint64, 0)), + lambda x,y: y.where(x, UOp.const(dtypes.uint32, 0)).cast(dtypes.uint64) * (1<<32)), + ((UPat.var('x', dtypes.uint64)&(UPat.var('y').where(UPat.const(dtypes.uint64, 0xFFFFFFFF), UPat.const(dtypes.uint64, 0)))).cast(dtypes.uint32), + lambda x,y: y.where(x.cast(dtypes.uint32), UOp.const(dtypes.uint32, 0))), + # ** self folding ** + (UPat(Ops.DEFINE_ACC, src=(UPat.var("x"),)), lambda x: x), # a DEFINE_ACC without ranges is a CONST + (UPat(Ops.ASSIGN, src=(UPat.cvar(),UPat.var("x"))), lambda x: x), # an ASSIGN to a const is a NOOP + # x!=0 -> (bool)x + (UPat.var("x")!=0, lambda x: x.cast(dtypes.bool.vec(x.dtype.count))), + # ** where ** + # push cast to branches + (UPat.var("s").where(UPat.var("a"), UPat.var("b")).cast().named("cast"), lambda s,a,b,cast: s.where(a.cast(cast.dtype), b.cast(cast.dtype))), + # a.where(b.where(c, d), d) -> (a & b).where(c, d) + (UPat.var("a").where(UPat.var("b").where(UPat.var("c"), UPat.var("d")), UPat.var("d")), lambda a,b,c,d: (a&b).where(c,d)), + # ** pow ** + ((UPat(Ops.POW, name="p"), lambda p: xpow(*p.src))), + # ** load/store folding ** + (UPat.store(UPat(Ops.INDEX, name="index"), UPat.load(UPat(Ops.INDEX, name="index"))), lambda index: UOp(Ops.NOOP)), + (UPat.store(UPat(Ops.INDEX, name="index"), UPat.var("gate").where(UPat.var("alt"), UPat.load(UPat(Ops.INDEX, name="index")))), + lambda index, gate, alt: UOp.store(index.src[0].index(index.src[1], gate), alt)), + # fold gated LOAD/STORE + (UPat().index(UPat(), UPat.const(dtypes.bool, True)).named("idx"), lambda idx: idx.replace(src=idx.src[0:2])), # remove True + (UPat().index(UPat(), UPat.const(dtypes.bool, False)).named("idx"), lambda idx: idx.const_like(0)), # False -> NULL pointer + (UPat(Ops.LOAD, src=(UPat.const(None, 0),), allow_any_len=True, name="x"), lambda x: x.const_like(0)), # NULL pointer load loads 0 + (UPat(Ops.STORE, src=(UPat.const(None, 0),), allow_any_len=True), lambda: UOp(Ops.NOOP)), # NULL pointer store does nothing + # remove NOOPs from SINK + (UPat(Ops.SINK, name="root"), + lambda root: UOp(Ops.SINK, root.dtype, a, root.arg) if len(a:=tuple(x for x in root.src if x.op is not Ops.NOOP)) != len(root.src) else None), + # remove VECTORIZE from SINK/BARRIER + (UPat(Ops.BARRIER, src=(UPat((Ops.VECTORIZE, Ops.SINK), name='sink'),)), lambda sink: UOp(Ops.BARRIER, dtypes.void, sink.src)), + (UPat(Ops.SINK, name="root"), + lambda root: UOp(Ops.SINK, root.dtype, tuple(flatten(x.src if x.op in {Ops.SINK, Ops.UNROLL} else (x,) for x in root.src)), root.arg) + if any(x.op in {Ops.SINK, Ops.UNROLL} for x in root.src) else None), + ((UPat.var("x") * UPat.var("x")).reciprocal(), lambda x: x.reciprocal()*x.reciprocal()), # 1/(x^c) -> (1/x)^c + ((UPat.var("x") * UPat.var("x") * UPat.var("x")).reciprocal(), lambda x: x.reciprocal()*x.reciprocal()*x.reciprocal()), + (UPat.var("x") * ((1+UPat.var("x")).reciprocal().named("d")), lambda x,d: 1-d), # x*/(1+x) -> 1-1/(1+x) + (UPat.var("x") * ((1+UPat.var("x")).reciprocal().named("d")*UPat.var("y")), lambda x,y,d: y*(1-d)), + (UPat.var("x") * ((1+UPat.var("x")).reciprocal().named("d")+UPat.var("y")), lambda x,y,d: (1-d)+x*y), + # move const multiply after REDUCE (NOTE: the mul chain can do this, but only if it's a same dtype reduce) + ((UPat.var("x")*UPat.cvar("c", vec=False)).reduce(arg=Ops.ADD, name="r", allow_any_len=True), lambda x,c,r: r.replace(src=(x,)+r.src[1:])*c.arg), + # reduce mul chain, move muls after the reduce + (UPat(Ops.MUL).reduce(name="r", allow_any_len=True), reduce_mul_chain), +]) diff --git a/tinygrad_repo/tinygrad/codegen/transcendental.py b/tinygrad_repo/tinygrad/codegen/transcendental.py index 753aed3787..3fff6e09bf 100644 --- a/tinygrad_repo/tinygrad/codegen/transcendental.py +++ b/tinygrad_repo/tinygrad/codegen/transcendental.py @@ -1,7 +1,7 @@ import math from tinygrad.dtype import dtypes, DType from tinygrad.helpers import polyN -from tinygrad.ops import UOp +from tinygrad.uop.ops import UOp TRANSCENDENTAL_SUPPORTED_DTYPES = (dtypes.float16, dtypes.float32, dtypes.float64) @@ -10,9 +10,9 @@ def _lazy_map_numbers(x:UOp, inf:UOp, _inf:UOp, nan:UOp, ratio:UOp): return x.ne(math.inf).where(x.ne(x).where(nan, x.ne(-math.inf).where(ratio, _inf)), inf) # *** helper functions for bit manipulation *** -def mantissa_bits(d:DType) -> int: return dtypes.finfo(d)[1] -def exponent_bias(d:DType) -> int: return {dtypes.float64: 1023, dtypes.float32: 127, dtypes.float16: 15}[d] -def exponent_mask(d:DType) -> int: return {dtypes.float64: 2047, dtypes.float32: 255, dtypes.float16: 31}[d] +def mantissa_bits(d:DType) -> int: return dtypes.finfo(d.scalar())[1] +def exponent_bias(d:DType) -> int: return {dtypes.float64: 1023, dtypes.float32: 127, dtypes.float16: 15}[d.scalar()] +def exponent_mask(d:DType) -> int: return {dtypes.float64: 2047, dtypes.float32: 255, dtypes.float16: 31}[d.scalar()] # **** utils **** def shr(x:UOp, y:int) -> UOp: return x // (2**y) @@ -20,41 +20,41 @@ def shl(x:UOp, y:int) -> UOp: return x * (2**y) def rintk(d:UOp) -> UOp: """round d:float to int away from 0""" - out_dtype = {dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16}[d.dtype] + out_dtype = {dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16}[d.dtype.scalar()].vec(d.dtype.vcount) return (d + (d<0.0).where(d.const_like(-0.5), d.const_like(0.5))).cast(out_dtype) def pow2if(q:UOp, float_dtype:DType): """cast(2^q, float_dtype) where q is any integer in the range of [-126, 127]""" - out_dtype = {dtypes.int64: dtypes.float64, dtypes.int32: dtypes.float32, dtypes.int16: float_dtype}[q.dtype] + out_dtype = {dtypes.int64: dtypes.float64, dtypes.int32: dtypes.float32, dtypes.int16: float_dtype.scalar()}[q.dtype.scalar()].vec(q.dtype.vcount) return shl(q + exponent_bias(out_dtype), mantissa_bits(out_dtype)).bitcast(out_dtype) def ilogb2k(d:UOp) -> UOp: """calculate the integer part of log2(d), where d is normalized fp value in the range of [0, +inf).""" - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES - dint = d.bitcast({dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16}[d.dtype]) + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES + dint = d.bitcast({dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16}[d.dtype.scalar()].vec(d.dtype.vcount)) # -1 <= ilog2bk(d) <= 128 return (shr(dint, mantissa_bits(d.dtype)) & exponent_mask(d.dtype)) - exponent_bias(d.dtype) def ldexp3k(d:UOp, e:UOp) -> UOp: """d*2^e. e is a number obtained by casting an integer in the range [-127, 127] to a float. d is any float number.""" - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES and e.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES - cast_map = {dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16} - m1 = d.bitcast(cast_map[d.dtype]) - m2 = shl(e.cast(cast_map[d.dtype]), mantissa_bits(d.dtype)) + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES and e.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES + dtype = {dtypes.float64: dtypes.int64, dtypes.float32: dtypes.int32, dtypes.float16: dtypes.int16}[d.dtype.scalar()].vec(d.dtype.count) + m1 = d.bitcast(dtype) + m2 = shl(e.cast(dtype), mantissa_bits(d.dtype)) return (m1 + m2).bitcast(d.dtype).cast(d.dtype) def ldexp2k(d:UOp, e:UOp) -> UOp: """d*2^e. much faster than ldexp3k but risky. d > 0 and d is not denormal.""" - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES and e.dtype in (dtypes.int16, dtypes.int32, dtypes.int64) + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES and e.dtype.scalar() in (dtypes.int16, dtypes.int32, dtypes.int64) return (d * pow2if(shr(e, 1), d.dtype)) * pow2if(e - shr(e, 1), d.dtype) def frexp(v:UOp) -> tuple[UOp, UOp]: """frexp(v) -> (mantissa, exponent) assuming v != 0""" - assert v.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES + assert v.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES # m1 = masks for mantissa, m2 = masks to normalize the mantissa. - m1 = {dtypes.float64: 0x000FFFFFFFFFFFFF, dtypes.float32: 0x807FFFFF, dtypes.float16: 0x83FF}[v.dtype] - m2 = {dtypes.float64: 0x3FE0000000000000, dtypes.float32: 0x3F000000, dtypes.float16: 0x3800}[v.dtype] - bits = v.bitcast({dtypes.float64: dtypes.uint64, dtypes.float32: dtypes.uint32, dtypes.float16: dtypes.uint16}[v.dtype]) + m1 = {dtypes.float64: 0x000FFFFFFFFFFFFF, dtypes.float32: 0x807FFFFF, dtypes.float16: 0x83FF}[v.dtype.scalar()] + m2 = {dtypes.float64: 0x3FE0000000000000, dtypes.float32: 0x3F000000, dtypes.float16: 0x3800}[v.dtype.scalar()] + bits = v.bitcast({dtypes.float64: dtypes.uint64, dtypes.float32: dtypes.uint32, dtypes.float16: dtypes.uint16}[v.dtype.scalar()].vec(v.dtype.count)) exponent = shr(bits, mantissa_bits(v.dtype)) & exponent_mask(v.dtype) # Set the exponent bits appropriately to normalize the mantissa into the range of [0.5, 1.0). mantissa = ((bits & m1) | m2).bitcast(v.dtype) @@ -70,18 +70,18 @@ def payne_hanek_reduction(d:UOp) -> tuple[UOp, UOp]: - `r`[d.dtype] is the reminder value corresponding to `round_to_nearest(x % pi/2)`. - `q`[int32] is an integer, and q % 4 is corresponding to the quadrant of the original angle `d`. """ - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES # https://stackoverflow.com/questions/30463616/payne-hanek-algorithm-implementation-in-c/30465751#30465751 # 190 bits of 2/pi for Payne-Hanek style argument reduction two_over_pi_f = [0x00000000, 0x28be60db, 0x9391054a, 0x7f09d5f4, 0x7d4d3770, 0x36d8a566, 0x4f10e410] - intermediate_dtype = dtypes.float32 if d.dtype == dtypes.float16 else d.dtype + intermediate_dtype = dtypes.float32.vec(d.dtype.count) if d.dtype.base.scalar() == dtypes.float16 else d.dtype f, e = frexp(d) - ia = (f.cast(intermediate_dtype) * 4.294967296e9).cast(dtypes.uint64) + ia = (f.cast(intermediate_dtype) * 4.294967296e9).cast_vec(dtypes.uint64) # extract 96 relevant bits of 2/pi based on magnitude of argument - i = shr(e.cast(dtypes.uint64), 5) - e = e.cast(dtypes.int32) & 31 + i = shr(e.cast_vec(dtypes.uint64), 5) + e = e.cast_vec(dtypes.int32) & 31 offset = 32 - e def _take(an:UOp, offset:int, count:int=0) -> UOp: @@ -89,22 +89,22 @@ def payne_hanek_reduction(d:UOp) -> tuple[UOp, UOp]: if count+offset < len(two_over_pi_f) - 1: an = i.ne(count).where(_take(an, offset, count=count+1), an.const_like(two_over_pi_f[count+offset])) return an - def _shl_lazy(x, y): return (x.cast(dtypes.uint64) * pow2if(y, d.dtype).cast(dtypes.uint64)).cast(dtypes.uint32) - def _shr_lazy(x, y): return (x.cast(dtypes.uint64) // pow2if(y, d.dtype).cast(dtypes.uint64)).cast(dtypes.uint32) + def _shl_lazy(x, y): return (x.cast_vec(dtypes.uint64) * pow2if(y, d.dtype).cast_vec(dtypes.uint64)).cast_vec(dtypes.uint32) + def _shr_lazy(x, y): return (x.cast_vec(dtypes.uint64) // pow2if(y, d.dtype).cast_vec(dtypes.uint64)).cast_vec(dtypes.uint32) - a = [_take(UOp.const(dtypes.uint32, 0), i) for i in range(4)] + a = [_take(UOp.const(dtypes.uint32.vec(d.dtype.count), 0), i) for i in range(4)] # (two_over_pi_f[Int(i) + n] << e) | (two_over_pi_f[Int(i) + n+1] >> (nbits - e)) # Note: e >= 1 for all numbers d >= 1.0. assume e != 0 hi = _shl_lazy(a[0], e) | _shr_lazy(a[1], offset) mi = _shl_lazy(a[1], e) | _shr_lazy(a[2], offset) lo = _shl_lazy(a[2], e) | _shr_lazy(a[3], offset) - def _hp_mul(x:UOp, y:UOp) -> UOp: return x.cast(dtypes.uint64) * y.cast(dtypes.uint64) + def _hp_mul(x:UOp, y:UOp) -> UOp: return x.cast_vec(dtypes.uint64) * y.cast_vec(dtypes.uint64) # compute x * 2/pi p = shl(_hp_mul(ia, hi), 32) + _hp_mul(ia, mi) + shr(_hp_mul(ia, lo), 32) # round quotient to nearest - q = shr(p, 62).cast(dtypes.int32) + q = shr(p, 62).cast_vec(dtypes.int32) p = p & 0x3fffffffffffffff r = (p.cast(intermediate_dtype) * (3.4061215800865545e-19)).cast(d.dtype) @@ -119,7 +119,7 @@ def cody_waite_reduction(d:UOp) -> tuple[UOp, UOp]: """ def _reduce_d(x:UOp, q:UOp): # https://github.com/shibatch/sleef/blob/4e08851f59fc2b545f9c393c6a23dfd311a26308/src/libm/sleefdp.c#L789-L823 - if x.dtype == dtypes.float64: + if x.dtype.scalar() == dtypes.float64: # https://github.com/shibatch/sleef/blob/f6d8a841fbfddd26ce712834d4da220cd76048fb/src/common/misc.h#L77 PI_A, PI_B, PI_C, PI_D = 3.1415926218032836914, 3.1786509424591713469e-08, 1.2246467864107188502e-16, 1.2736634327021899816e-24 d = qdh * -PI_A + x @@ -129,9 +129,9 @@ def cody_waite_reduction(d:UOp) -> tuple[UOp, UOp]: d = qdh * -PI_C + d d = q * -PI_C + d d = (qdh + q) * -PI_D + d - elif x.dtype == dtypes.float16: + elif x.dtype.scalar() == dtypes.float16: # [FIXME] when reducing `d`, FP16 needs FP32 precision to achieve 1.0 ULP precision. - d = _reduce_d(x.cast(dtypes.float32), q.cast(dtypes.float32)).cast(dtypes.float16) + d = _reduce_d(x.cast_vec(dtypes.float32), q.cast_vec(dtypes.float32)).cast_vec(dtypes.float16) else: # https://github.com/shibatch/sleef/blob/4e08851f59fc2b545f9c393c6a23dfd311a26308/src/libm/sleefsp.c#L464-L503 d = q * -3.1414794921875 + x @@ -141,12 +141,12 @@ def cody_waite_reduction(d:UOp) -> tuple[UOp, UOp]: return d m_1_pi = 0.318309886183790671537767526745028724 - qdh = (d * (m_1_pi / 2.0**24)).cast(dtypes.int64).cast(d.dtype) * (2.0**24) - quadrant = rintk(d * m_1_pi -qdh) if d.dtype == dtypes.float64 else rintk(d * m_1_pi) - return _reduce_d(d, quadrant.cast(d.dtype)), quadrant.cast(dtypes.int32) + qdh = (d * (m_1_pi / 2.0**24)).cast_vec(dtypes.int64).cast(d.dtype) * (2.0**24) + quadrant = rintk(d * m_1_pi -qdh) if d.dtype.base.scalar() == dtypes.float64 else rintk(d * m_1_pi) + return _reduce_d(d, quadrant.cast(d.dtype)), quadrant.cast_vec(dtypes.int32) # *** approximate sine on small angle. *** -def trig_poly(d:UOp, coeff32, coeff64): return d * (polyN(d*d, coeff64) if d.dtype == dtypes.float64 else polyN(d*d, coeff32)) +def trig_poly(d:UOp, coeff32, coeff64): return d * (polyN(d*d, coeff64) if d.dtype.scalar() == dtypes.float64 else polyN(d*d, coeff32)) # approximate sine on [-pi/2, pi/2] def sin_poly(d:UOp) -> UOp: return trig_poly(d, [2.6083159809786593541503e-06, -0.0001981069071916863322258, 0.00833307858556509017944336, -0.166666597127914428710938, 1.0], @@ -172,7 +172,7 @@ def xsin(d:UOp, fast:bool=False, switch_over:float=30.0) -> UOp: - fast=True assumes x <= switch_over. - switch_over is the threshold for switching to payne_hanek_reduction. """ - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES # mask +-inf/nan as zero x = _lazy_map_numbers(d, d.const_like(0.0), d.const_like(0.0), d.const_like(0.0), d) # x_sign = sign(x) @@ -194,20 +194,20 @@ def xexp2(d:UOp) -> UOp: Implements a 1.0 ULP approximation for Ops.EXP2 - Paper: https://arxiv.org/pdf/2001.09258 """ - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES # mask +=inf/nan as zero. x = _lazy_map_numbers(d, d.const_like(0.0), d.const_like(0.0), d.const_like(0.0), d) q = rintk(x) # s = d - round(d) s = x - q.cast(x.dtype) # a polynomial approximation with 13 non-zero terms in the range of [−(log 2)/2,(log 2)/2]. - if d.dtype == dtypes.float64: + if d.dtype.scalar() == dtypes.float64: u = polyN(s, [0.4434359082926529454e-9, 0.7073164598085707425e-8, 0.1017819260921760451e-6, 0.1321543872511327615e-5, 0.1525273353517584730e-4, 0.1540353045101147808e-3, 0.1333355814670499073e-2, 0.9618129107597600536e-2, 0.5550410866482046596e-1, 0.2402265069591012214e+0, 0.6931471805599452862e+0, 0.1000000000000000000e+1]) else: u = polyN(s, [0.1535920892e-3, 0.1339262701e-2, 0.9618384764e-2, 0.5550347269e-1, 0.2402264476e+0, 0.6931471825e+0, 1.0]) u = ldexp2k(u, q) # u*2^q - upper, lower = {dtypes.float64: (1024, -2000), dtypes.float32: (128, -150), dtypes.float16: (23, -22)}[d.dtype] + upper, lower = {dtypes.float64: (1024, -2000), dtypes.float32: (128, -150), dtypes.float16: (23, -22)}[d.dtype.scalar()] # Replace x >= upper with +inf u = (d >= upper).where(d.const_like(math.inf), u) # Replace x < lower with zero. @@ -220,10 +220,10 @@ def xlog2(d:UOp) -> UOp: Implements a 1.0 ULP approximation for Ops.LOG2 Paper: https://arxiv.org/pdf/2001.09258 5.5 """ - assert d.dtype in TRANSCENDENTAL_SUPPORTED_DTYPES + assert d.dtype.scalar() in TRANSCENDENTAL_SUPPORTED_DTYPES # TODO: float16 denormal need float32 to achieve precision - if d.dtype == dtypes.float16: return xlog2(d.cast(dtypes.float32)).cast(dtypes.float16) - FLT_MIN = d.const_like(1e-6 if d.dtype == dtypes.float16 else 1e-4) + if d.dtype.scalar() == dtypes.float16: return xlog2(d.cast_vec(dtypes.float32)).cast_vec(dtypes.float16) + FLT_MIN = d.const_like(1e-6 if d.dtype.scalar() == dtypes.float16 else 1e-4) is_denormal = d UOp: x = (m - 1.0) / (m + 1.0) x2 = x * x - if d.dtype == dtypes.float64: + if d.dtype.scalar() == dtypes.float64: t = polyN(x2, [0.2211941750456081490e+0, 0.2200768693152277689e+0, 0.2623708057488514656e+0, 0.3205977477944495502e+0, 0.4121985945485324709e+0, 0.5770780162997058982e+0, 0.96179669392608091449]) s_hi, s_lo = e+x*2.885390081777926774, e.const_like(0) @@ -248,9 +248,19 @@ def xlog2(d:UOp) -> UOp: r = (d<-0.0).where(r.const_like(math.nan), r) # log2(0) = -Inf, but we will compare using the value of y because 1e-200==0 is true. # log2_zero = the value of unmasked xlog2(0.0). - log2_zero = {dtypes.float64: -1087, dtypes.float32: -191, dtypes.float16: -79}[d.dtype] + log2_zero = {dtypes.float64: -1087, dtypes.float32: -191, dtypes.float16: -79}[d.dtype.scalar()] r = r.ne(log2_zero).where(r, r.const_like(-math.inf)) # log2(NaN) = NaN r = d.ne(d).where(r.const_like(math.nan), r) # log2(-0.0) = -Inf. In certain devices like PTX, x == -0.0 won't be true. so making reciprocal. return d.reciprocal().ne(-math.inf).where(r, r.const_like(-math.inf)) + +def xpow(base:UOp, exponent:UOp) -> UOp: + # start with b ** e = exp2(e * log2(b)) + ret = (base < 0).where(-base, base).log2().mul(exponent).exp2() + # negative base adjustment: nan for non-integer exponent and -1 for odd exponent + non_int = exponent != exponent.cast_vec(dtypes.int32).cast(exponent.dtype) + adj = non_int.where(ret.const_like(math.nan), + (exponent < 0).where(-exponent, exponent).cast_vec(dtypes.int32).mod(2).cast_vec(dtypes.bool).where(ret.const_like(-1), ret.const_like(1))) + # fix 0 ** 0 = 1 + return (base.eq(0) & exponent.eq(0)).where(ret.const_like(1), ret * (base < 0).where(adj, ret.const_like(1))) diff --git a/tinygrad_repo/tinygrad/codegen/uopgraph.py b/tinygrad_repo/tinygrad/codegen/uopgraph.py deleted file mode 100644 index a536db0f04..0000000000 --- a/tinygrad_repo/tinygrad/codegen/uopgraph.py +++ /dev/null @@ -1,513 +0,0 @@ -from __future__ import annotations -from typing import Optional, TYPE_CHECKING, Any, DefaultDict, Callable -import functools, itertools, operator -from collections import defaultdict -from tinygrad.dtype import dtypes, ImageDType, PtrDType -from tinygrad.ops import UOp, Ops, UPat, PatternMatcher, symbolic_flat, symbolic_simple -from tinygrad.ops import graph_rewrite, split_uop, uop_given_valid, parse_valid, is_increasing, simplify_valid, GroupOp -from tinygrad.helpers import DEBUG, getenv, flatten, dedup, TRANSCENDENTAL, AMX, prod, partition, all_same -from tinygrad.codegen.transcendental import xexp2, xlog2, xsin, TRANSCENDENTAL_SUPPORTED_DTYPES - -if TYPE_CHECKING: from tinygrad.renderer import Renderer - -# ***** float4/image store handling ***** - -def fold_expanded(ex, buf): - if buf.dtype.base != dtypes.float and buf.dtype.base != dtypes.half and not isinstance(buf.dtype, ImageDType): return None - new_srcs = dedup(list(ex.src)) - old_new_srcs = new_srcs[:] - is_load, is_image = new_srcs[0].op is Ops.LOAD, isinstance(buf.dtype, ImageDType) - - # first, extract all the relevant offsets - offsets_rootsrc: DefaultDict[Any, dict] = defaultdict(dict) - for i,s in enumerate(new_srcs): - idx = s.src[0].src[1] - if s.dtype.count != 1 or (is_image and idx.dtype.count == 2): continue - if idx.op is Ops.ADD and idx.src[1].op is Ops.CONST: root_src, arg = idx.src[0], idx.src[1].arg - elif idx.op is Ops.CONST: root_src, arg = "CONST", idx.arg - else: root_src, arg = idx, 0 - # add gates for gated - if len(s.src[0].src) == 3: root_src = (s.src[0].src[2], root_src) - assert arg not in offsets_rootsrc[root_src], f"{offsets_rootsrc[root_src][arg]} != {i} with {len(s.src)} sources" - offsets_rootsrc[root_src][arg] = i - - # then rewrite everything we can - lengths = [4] if is_image else ([8,4,2] if buf.dtype.base == dtypes.half and getenv("ALLOW_HALF8") else ([16,8,4,2] if AMX else [4,2])) - used: set[tuple[UOp, UOp]] = set() - for rootsrc, offsets in offsets_rootsrc.items(): - for o in offsets: - for fold_length in lengths: - if all((rootsrc,o+i) not in used and o+i in offsets for i in range(fold_length)): - load_1 = new_srcs[offsets[o]] - new_src = list(load_1.src) - oidx = new_src[0].src[1] - if oidx.divides(fold_length) is None: continue - if is_image: - # for images, we rewrite the index. it must evenly divide 4 from the above check - new_src[0] = buf.index( - UOp(Ops.VECTORIZE, dtypes.int.vec(2), ((oidx // 4) % buf.dtype.shape[1], (oidx // (4*buf.dtype.shape[1])))), - rootsrc[0] if isinstance(rootsrc, tuple) else None) - else: - # for non image, we upcast the index pointer - new_src[0] = new_src[0].cast(new_src[0].dtype.base.vec(fold_length).ptr(size=new_src[0].dtype.size//fold_length, - local=new_src[0].dtype.local)) - # generate the folded new_srcs - if is_load: - new_load = UOp(Ops.LOAD, load_1.dtype.vec(fold_length), tuple(new_src)) - for i in range(fold_length): new_srcs[offsets[o+i]] = new_load.gep(i) - else: # vectorize the store - new_src[1] = UOp(Ops.VECTORIZE, new_src[1].dtype.vec(fold_length), tuple(new_srcs[offsets[o+i]].src[1] for i in range(fold_length))) - for i in range(fold_length): new_srcs[offsets[o+i]] = UOp(Ops.STORE, dtypes.void, tuple(new_src)) if i == 0 else None - used.update((rootsrc,o+i) for i in range(fold_length)) - - # dedup expand for LOAD - if is_load and len(old_new_srcs) != len(ex.src): new_srcs = [new_srcs[old_new_srcs.index(s)] for s in ex.src] - # remove Nones for STORE - return UOp(ex.op, ex.dtype, tuple(x for x in new_srcs if x is not None), ex.arg) if len(used) else None - -def fix_unfoldable_image_load(load:UOp, buf:UOp): - if not isinstance(buf.dtype, ImageDType) or (oidx:=load.src[0].src[1]).dtype.count == 2: return None - id4 = oidx % 4 - new_src = list(load.src) - # TODO: copied logic from above - new_src[0] = load.src[0].src[0].index( - UOp(Ops.VECTORIZE, dtypes.int.vec(2), ((oidx // 4) % buf.dtype.shape[1], (oidx // (4*buf.dtype.shape[1])))), - load.src[0].src[2] if len(load.src[0].src) == 3 else None) - vec_load = UOp(Ops.LOAD, load.dtype.vec(4), tuple(new_src)) - return functools.reduce(lambda ret, i: id4.ne(i).where(ret, vec_load.gep(i)), range(4), load.const_like(float('nan'))) - -buf_idx_pat = UPat(Ops.INDEX, src=(UPat.var("buf"),), allow_any_len=True) -float4_folding = PatternMatcher([ - (UPat(Ops.VECTORIZE, src=UPat(Ops.LOAD, src=(buf_idx_pat,), allow_any_len=True), name="ex"), fold_expanded), - (UPat((Ops.BARRIER, Ops.SINK), src=UPat(Ops.STORE, src=(buf_idx_pat,), allow_any_len=True), name="ex"), fold_expanded), -]) - -# ***** image load valid simplification ***** - -def simplify_valid_load(buf:UOp, start_idx:UOp, valid:UOp) -> UOp|None: - if (idx:=uop_given_valid(valid, start_idx)) is None: return buf.const_like(0) - if not isinstance(buf.dtype, ImageDType): return None if idx is start_idx else buf.index(idx, valid) - - # wait for it to be image indexed before running simplification - if start_idx.dtype.count != 2: return None - - # can drop valid if idx is out of bound when valid is False - drop_stmt = [] - for stmt in split_uop(valid, Ops.AND): - X, is_upper_bound, c = parse_valid(stmt) - - # for X0 + X1 + ... >= 1, check if it's out of bound when Xi = 0 for all i - if not is_upper_bound and c == 1 and all(u.op in GroupOp.Irreducible and u.vmin == 0 for u in split_uop(X, Ops.ADD)): - testidx = functools.reduce(lambda nowidx,u: nowidx.substitute({u:u.const_like(0)}), split_uop(X, Ops.ADD), idx) - testidx = testidx.simplify() - if testidx.gep(0).vmax < 0 or testidx.gep(1).vmax < 0: - drop_stmt.append(stmt) - continue - - # if X <= c, check if it's out of bound when X = c+1 - # if X >= c, check if it's out of bound when X = c-1 - test_value = c + 1 if is_upper_bound else c - 1 - for i,b in zip(idx.src, (buf.dtype.shape[1], buf.dtype.shape[0])): - if is_increasing(i): - rw = i.substitute({X:X.const_like(test_value)}).simplify() - if rw.vmin >= b or rw.vmax < 0: - drop_stmt.append(stmt) - break - - if not drop_stmt and idx is start_idx: return None - new_valid = functools.reduce(operator.and_, ss) if (ss:=[s for s in split_uop(valid, Ops.AND) if s not in drop_stmt]) else None - return buf.index(idx, new_valid) - -# ***** optional patterns ***** - -powers_of_two = {2**i:i for i in range(64)} -@functools.lru_cache(None) -def get_late_rewrite_patterns(ops, force_transcendental=False): - pat: list[tuple[UPat, Callable]] = [(UPat(op, dtype=TRANSCENDENTAL_SUPPORTED_DTYPES, src=(UPat.var("d"),)), f) for op,f in \ - ((Ops.EXP2, xexp2), (Ops.LOG2, xlog2), (Ops.SIN, xsin)) if op not in ops or force_transcendental] - # rewrite MOD to AND (which should always be supported, but not for generic in tests): x % (2**y) -> x & (2**y-1) - if Ops.AND in ops: - pat += [(UPat.var("x", dtypes.ints)%UPat.cvar("c"), lambda x,c: x & (c.arg-1) if c.arg in powers_of_two else None)] - # rewrite MUL/IDIV to SHL+SHR: x*(2**y) -> shl(x,y) and x//(2**y) -> shr(x,y) - if Ops.SHL in ops and Ops.SHR in ops: - pat += [ - (UPat.var("x", dtypes.ints)*UPat.cvar("c"), lambda c,x: x << powers_of_two[c.arg] if c.arg in powers_of_two else None), - (UPat.var("x", dtypes.ints)//UPat.cvar("c"), lambda x,c: x >> powers_of_two[c.arg] if c.arg in powers_of_two else None) - ] - if Ops.NEG in ops: - pat += [(UPat.var('x')*-1, lambda x: x.alu(Ops.NEG))] - if Ops.SUB in ops: pat += [(UPat.var('x')+UPat.var('y').alu(Ops.NEG), lambda x,y: x.alu(Ops.SUB, y))] - if Ops.MULACC in ops: - pat += [(UPat.var('a')*UPat.var('b')+UPat.var('c'), lambda a,b,c: a.alu(Ops.MULACC, b, c))] - return PatternMatcher(pat) - -# ***** threefry ***** - -def threefry2x32(x: UOp, key: UOp): - # split x into two uint32, since x in a uint64 - x0, x1 = (x & 0xffffffff).cast(dtypes.uint32), ((x // 2**32) & 0xffffffff).cast(dtypes.uint32) - - rotations = [[13, 15, 26, 6], [17, 29, 16, 24]] - key0, key1 = (key & 0xffffffff).cast(dtypes.uint32), ((key // 2**32) & 0xffffffff).cast(dtypes.uint32) - ks = [key1, key0 ^ key1 ^ 0x1BD11BDA, key0] - xr = [x0 + ks[-1], x1 + ks[0]] - for i in range(5): - for r in rotations[i % 2]: xr[0], xr[1] = (x0 := xr[0] + xr[1]), x0 ^ ((xr[1] * 2**r) + (xr[1] // 2**(32 - r))) - xr = [(xr[0] + ks[i % 3]), (xr[1] + ks[(i + 1) % 3] + i + 1)] - - return xr[1].cast(dtypes.uint64) * 2**32 | xr[0].cast(dtypes.uint64) - -# ***** other math rewrite **** - -def sigmoid_like(x:UOp, y:UOp): return (t:=(1/(x+1))) * (1-t) * y - -# ***** main rewriter ***** - -def loop_collapse(compval, multconst, rng:UOp, acc:UOp, idx2=None,idx3=None,extra=None,vec=None,ne=None, - add=UOp.const(dtypes.int, 0), mul:UOp=UOp.const(dtypes.int, 1)): - if getenv("DISABLE_LOOP_COLLAPSE") or rng not in acc.src: return None # must be the right REDUCE - loop_start, loop_end = rng.src - if loop_start.arg != 0: - # TODO: support and test this with other mul and loop_starts - if DEBUG >= 1: print(f"WARNING, NOT FOLDING: mul:{mul.arg} loop_start:{loop_start.arg}") - return None - if idx2 is not None: add = add + idx2 - if idx3 is not None: add = add + idx3 - if vec is not None: - # add, mul, loop_start, loop_end - def dvec(x:UOp): - if x.op is Ops.CONST: return UOp.const(x.dtype.vec(vec.dtype.count), x.arg) - return UOp(Ops.VECTORIZE, x.dtype.vec(vec.dtype.count), src=(x,)*vec.dtype.count) - add, mul, loop_start, loop_end = dvec(add), dvec(mul), dvec(loop_start), dvec(loop_end) - if mul.vmin > 0 and ne is not None: - comprange = UOp.minimum(loop_end, UOp.maximum((add-compval)//mul + (loop_end-loop_start), loop_start)) - elif mul.vmax < 0 and ne is None: - comprange = UOp.minimum(loop_end, UOp.maximum((add-compval-mul)//mul + (loop_end-loop_start), loop_start)) - else: - return None - new_reduce_op = comprange.cast(multconst.dtype) * multconst - # TODO: what does it mean to have the same numbered DEFINE_ACC with different ranges? - new_acc = acc.replace(src=acc.src[0:1]+tuple(x for x in acc.src[1:] if x is not rng)) - ret = new_acc.assign(new_acc+new_reduce_op) - if extra is not None: ret = ret + acc.assign(acc+extra) - return ret - -def index_collapse(idx:UOp,rng:UOp,buf:UOp,ld:UOp,acc:UOp,add=UOp.const(dtypes.int, 0),mul=UOp.const(dtypes.int, 1)): - if rng not in acc.src: return None - new_load = UOp.load(buf.index(add+mul*idx, (idx >= rng.src[0]) & (idx < rng.src[1])), dtype=ld.dtype) - new_acc = acc.replace(src=acc.src[0:1]+tuple(x for x in acc.src[1:] if x is not rng)) - return new_acc.assign(new_acc+new_load) - -# TODO: there's a lot shared with no_vectorized_wmma here -def gep_through_wmma(gep:UOp, wmma:UOp): - out_sz = prod(x[1] for x in wmma.arg[6][-1]) - wmma_idxs = gep.arg[::out_sz] - for i in range(out_sz): - if tuple(x-i for x in gep.arg[i::out_sz]) != wmma_idxs: return None - tsrcs = [] - for s,sz in zip(wmma.src, wmma.arg[6]): - src_args = [] - ssz = prod(x[1] for x in sz) - for w in wmma_idxs: src_args += list(range((w//out_sz)*ssz, (w//out_sz)*ssz + ssz)) - tsrcs.append(s.gep(tuple(src_args))) - return UOp(Ops.WMMA, gep.dtype, tuple(tsrcs), wmma.arg) - -def no_vectorized_wmma(wmma:UOp): - out_sz = prod(x[1] for x in wmma.arg[6][-1]) - if wmma.dtype.count == out_sz: return None - tsrcs = [] - for s,sz in zip(wmma.src, wmma.arg[6]): - ssz = prod(x[1] for x in sz) - tsrcs.append([s.gep(tuple(range(grp, grp+ssz))) for grp in range(0, s.dtype.count, ssz)]) - wmmas = [UOp(Ops.WMMA, wmma.dtype.scalar().vec(out_sz), tsrc, wmma.arg) for tsrc in zip(*tsrcs)] - wmma_ex = flatten([[e.gep(i) for i in range(out_sz)] for e in wmmas]) - return UOp(Ops.VECTORIZE, wmma.dtype, tuple(wmma_ex)) - -def reduce_collapse(acc:UOp, ret:UOp, alu:UOp): - reduce_parented, reduce_unparented = partition(acc.src[1:], lambda x: x in ret.toposort) - if len(reduce_unparented) == 0: return None - new_acc = acc.replace(src=acc.src[0:1]+tuple(reduce_parented)) - ret = new_acc.assign(new_acc.alu(alu.op, ret)) - if alu.op is Ops.ADD: - for r in reduce_unparented: ret = ret * (r.src[1]-r.src[0]).cast(ret.dtype.scalar()).broadcast(ret.dtype.count) - return ret - -acc_pat, rng_pat = UPat(Ops.DEFINE_ACC, name="acc"), UPat(Ops.RANGE, name="rng") -rng_aug = UPat.any(rng_pat, UPat.var("add")+rng_pat, UPat.var("mul")*rng_pat, UPat.var("add")+UPat.var("mul")*rng_pat) - -index_load = UPat.var("buf").index(rng_aug).load(name="ld") - -arange_augrng = UPat.any(rng_aug, rng_aug+UPat.var("idx2"), rng_aug+UPat.var("idx2")+UPat.var("idx3"), UPat(Ops.VECTORIZE, name="vec", src=rng_aug)) -arange_m = ((arange_augrng 1 else vec.src[gep.arg[0]]), - (UPat(Ops.GEP, src=(UPat.cvar("c", vec=False),), name="gep"), lambda gep, c: gep.const_like(c.arg)), - (UPat(Ops.GEP, src=(UPat(Ops.VCONST, name="c"),), name="gep"), lambda gep, c: gep.const_like(tuple(c.arg[x] for x in gep.arg))), - # push all GEPs through ALUs (fix arange stuff) - (UPat(Ops.GEP, src=(UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST), name='alu'),), name='gep'), - lambda gep,alu: UOp(alu.op, alu.dtype.scalar().vec(gep.dtype.count), tuple(x.gep(gep.arg) for x in alu.src), alu.arg)), - # push some GEPs through WMMAs - (UPat(Ops.GEP, src=(UPat(Ops.WMMA, name="wmma"),), name="gep"), gep_through_wmma), - # tensor core with a 0 input is acc - (UPat(Ops.WMMA, src=(UPat.const(None, 0.0), UPat.var(), UPat.var("acc"))), lambda acc: acc), - (UPat(Ops.WMMA, src=(UPat.var(), UPat.const(None, 0.0), UPat.var("acc"))), lambda acc: acc), - # tensor core cleanups - (UPat.var("add") + UPat(Ops.WMMA, name="wmma"), - lambda add, wmma: UOp(wmma.op, wmma.dtype, (wmma.src[0], wmma.src[1], wmma.src[2]+add), wmma.arg)), - # threefry + remove longs - (UPat(Ops.THREEFRY, dtype=dtypes.uint64, src=(UPat.var("x"), UPat.var("key"))), threefry2x32), - (UPat.var('x', dtypes.uint32).cast(dtypes.uint64).cast(dtypes.uint32), lambda x: x), # cast there and back is noop (TODO: genericize) - ((UPat.var('x', dtypes.uint64)&0xFFFFFFFF).cast(dtypes.uint32), lambda x: x.cast(dtypes.uint32)), # cast does truncation - (((UPat.var(None, dtypes.uint64)*(1<<32)) | UPat.var('y', dtypes.uint32).cast(dtypes.uint64)).cast(dtypes.uint32), lambda y: y), - (((UPat.var('x', dtypes.uint64)*(1<<32)) | UPat.var(None, dtypes.uint32).cast(dtypes.uint64))//(1<<32), lambda x: x), - # hacks for threefry long removal when padded (TODO: genericize) - (UPat.var('x', dtypes.uint32).cast(dtypes.uint64) * UPat.var('y').where(UPat.const(dtypes.uint64, 1<<32), UPat.const(dtypes.uint64, 0)), - lambda x,y: y.where(x, UOp.const(dtypes.uint32, 0)).cast(dtypes.uint64) * (1<<32)), - ((UPat.var('x', dtypes.uint64)&(UPat.var('y').where(UPat.const(dtypes.uint64, 0xFFFFFFFF), UPat.const(dtypes.uint64, 0)))).cast(dtypes.uint32), - lambda x,y: y.where(x.cast(dtypes.uint32), UOp.const(dtypes.uint32, 0))), - # arange loop folding - (acc_pat.assign(UPat.any(arange_m, arange_m+UPat.var("extra"))+acc_pat), loop_collapse), - # indexing, with cast or where - (acc_pat.assign(UPat.var("idx").eq(UPat(Ops.RANGE, name="rng")).cast()*index_load+acc_pat), index_collapse), - (acc_pat.assign(UPat.var("idx").eq(UPat(Ops.RANGE, name="rng")).where(index_load, UPat.const(None, 0.0))+acc_pat), index_collapse), - # parentless reduce # TODO: add MUL - (acc_pat.assign(UPat((Ops.ADD, Ops.MAX), src=[acc_pat, UPat.var("ret")], name="alu")), reduce_collapse), - # ** self folding ** - (UPat(Ops.DEFINE_ACC, src=(UPat.var("x"),)), lambda x: x), # a DEFINE_ACC without ranges is a CONST - (UPat(Ops.ASSIGN, src=(UPat.cvar(),UPat.var("x"))), lambda x: x), # an ASSIGN to a const is a NOOP - # x!=0 -> (bool)x - (UPat.var("x")!=0, lambda x: x.cast(dtypes.bool.vec(x.dtype.count))), - # ** load/store folding ** - (UPat.store(UPat(Ops.INDEX, name="index"), UPat.load(UPat(Ops.INDEX, name="index"))), lambda index: UOp(Ops.NOOP)), - (UPat.store(UPat(Ops.INDEX, name="index"), UPat.var("gate").where(UPat.var("alt"), UPat.load(UPat(Ops.INDEX, name="index")))), - lambda index, gate, alt: UOp.store(index.src[0].index(index.src[1], gate), alt)), - # fold gated LOAD/STORE - (UPat().index(UPat(), UPat.const(dtypes.bool, True)).named("idx"), lambda idx: idx.replace(src=idx.src[0:2])), # remove True - (UPat().index(UPat(), UPat.const(dtypes.bool, False)).named("idx"), lambda idx: idx.const_like(0)), # False -> NULL pointer - (UPat(Ops.LOAD, src=(UPat.const(None, 0),), allow_any_len=True, name="x"), lambda x: x.const_like(0)), # NULL pointer load loads 0 - (UPat(Ops.STORE, src=(UPat.const(None, 0),), allow_any_len=True), lambda: UOp(Ops.NOOP)), # NULL pointer store does nothing - # remove NOOPs from SINK - (UPat(Ops.SINK, name="root"), - lambda root: UOp(Ops.SINK, root.dtype, a, root.arg) if len(a:=tuple(x for x in root.src if x.op is not Ops.NOOP)) != len(root.src) else None), - # remove VECTORIZE from SINK/BARRIER - (UPat(Ops.BARRIER, src=(UPat((Ops.VECTORIZE, Ops.SINK), name='sink'),)), lambda sink: UOp(Ops.BARRIER, dtypes.void, sink.src)), - (UPat(Ops.SINK, name="root"), - lambda root: UOp(Ops.SINK, root.dtype, tuple(flatten(x.src if x.op in {Ops.SINK, Ops.UNROLL} else (x,) for x in root.src)), root.arg) - if any(x.op in {Ops.SINK, Ops.UNROLL} for x in root.src) else None), - # stable sigmoid - (UPat.var("x")*(((UPat.var("x")+1)*(UPat.var("x")+1)).reciprocal()), lambda x: sigmoid_like(x, x.const_like(1))), - (UPat.var("x")*(((UPat.var("x")+1)*(UPat.var("x")+1)).reciprocal()*UPat.var("y")), sigmoid_like), - (UPat.var("x")*(((UPat.var("x")+1)*(UPat.var("x")+1)*(UPat.var("x")+1)).reciprocal()), lambda x: sigmoid_like(x, (x+1).reciprocal())), -]) - -# *** uop expander *** - -def _expand_arg_to_idx(args:tuple[tuple[int, int], ...], rpk:dict[int, int]) -> int: - idx, mul = 0, 1 - for axis,m in args[::-1]: - idx += rpk[axis] * mul - mul *= m - return idx - -def _choices_from_args(args:tuple[tuple[int, int], ...]) -> list[dict[int, int]]: - return [dict(x) for x in itertools.product(*[zip(itertools.repeat(axis), range(m)) for axis,m in args])] - -@functools.lru_cache(None) -def _swizzle_args(cargs:tuple[tuple[int, int], ...], eargs:tuple[tuple[int, int], ...], exclude_args:tuple[int, ...]) -> list[int]: - return [_expand_arg_to_idx(eargs, {**rpk, **{x:0 for x in exclude_args}} if exclude_args else rpk) for rpk in _choices_from_args(cargs)] - -def do_expand(root:UOp): - expands = [x for x in root.src if x.op is Ops.UNROLL] - if len(expands) == 0: return None - # NOTE: we 0 out the reduce axis for WMMA. in theory they should all be the same, but is this always correct? - exclude_args = tuple(dedup(root.arg[-1] + tuple(y[0] for y in flatten(root.arg[-2])))) if root.op is Ops.WMMA else () - if all_same(expands_args:=[x.arg for x in expands]) and len(exclude_args) == 0: - # if there's only one expand arg, it's okay to use it (optimization) - expand_args = expands[0].arg - else: - # otherwise, we sort them and GEP - expand_args = tuple(x for x in sorted(dedup(flatten(expands_args))) if x[0] not in exclude_args) - expand_sz = prod([x[1] for x in expand_args]) - new_srcs = [] - for i,src in enumerate(root.src): - if src.op is Ops.UNROLL: - if root.op is Ops.IF and i == 0: - # IF means OR on first arg to IF - new_srcs.append(functools.reduce(operator.__or__, [src.src[0].gep(i) for i in range(expand_sz)])) - elif expand_args == src.arg: - # just remove the expand - new_srcs.append(src.src[0]) - else: - lst = _swizzle_args(expand_args, src.arg, exclude_args) - # if the base dtype is > 1, put those at the end - if src.dtype.count > 1: lst = flatten([[i*src.dtype.count+j for j in range(src.dtype.count)] for i in lst]) - new_srcs.append(src.src[0].gep(tuple(lst))) - else: - # non-UNROLL input - if root.op is Ops.IF: - # for the first arg of IF, just pass them through ignoring UNROLLS - new_srcs.append(src) - elif src.dtype.count > 1: - # put any input dtype > 1 grouped together - new_srcs.append(UOp(Ops.VECTORIZE, - src.dtype.scalar().vec(expand_sz*src.dtype.count), tuple(src.gep(i) for i in range(src.dtype.count))*expand_sz)) - else: - # repeat the arg - new_srcs.append(src.broadcast(expand_sz)) - - new_arg = root.arg - if root.op is Ops.GEP: - assert root.dtype.count == 1 - # is this right? - new_arg = tuple(range(root.arg[0], new_srcs[0].dtype.count, new_srcs[0].dtype.count // expand_sz)) - nsrc = UOp(root.op, root.dtype.scalar().vec(root.dtype.count*expand_sz), tuple(new_srcs), new_arg) - return UOp(Ops.UNROLL, root.dtype, (nsrc,), expand_args) - -def do_contract(con:UOp): - ex = con.src[0] - # CONTRACT without UNROLL repeats the element VECTORIZED - if ex.op is not Ops.UNROLL: return UOp(Ops.VECTORIZE, con.dtype, con.src*con.dtype.count) - # CONTRACT may remove several axes from UNROLL - assert con.dtype.count == prod([x[1] for x in con.arg]), "dtype is wrong" - idxs = [] - for rpk in _choices_from_args(new_ex_args:=tuple(x for x in ex.arg if x not in con.arg)): - idxs += [_expand_arg_to_idx(ex.arg, {**rpk, **lrpk}) for lrpk in _choices_from_args(con.arg)] - return UOp(Ops.UNROLL, con.dtype, (ex.src[0].gep(tuple(idxs)),), new_ex_args) - -def no_vectorized_alu(alu): - if alu.dtype.vcount == 1: return None - alus = tuple(UOp(alu.op, alu.dtype.scalar(), tuple(s.gep(i) for s in alu.src), alu.arg) for i in range(alu.dtype.vcount)) - return UOp(Ops.VECTORIZE, alu.dtype, alus) - -def create_gate(root:UOp) -> UOp|None: - @functools.lru_cache(None) - def _gate_srcs(u:UOp, gate:UOp) -> UOp: - if u.op is Ops.BARRIER: return u - if u.op is Ops.LOAD and u.src[-1].op is Ops.BARRIER: - return UOp(u.op, u.dtype, u.src[:-1]+(UOp(Ops.IF, dtypes.void, (gate, u.src[-1])),), u.arg) - return u if (replace_source:=tuple(_gate_srcs(x, gate) for x in u.src)) == u.src else UOp(u.op, u.dtype, replace_source, u.arg) - idx = root.src[0] - if idx.op is Ops.CAST: idx = idx.src[0] - return None if idx.op is not Ops.INDEX or len(idx.src) == 2 or (ret:=_gate_srcs(root, idx.src[2])) is root else ret - -expander = PatternMatcher([ - # double expand - (UPat(Ops.UNROLL, name="outer", src=(UPat(Ops.UNROLL, name="inner"),)), - lambda outer, inner: UOp(Ops.UNROLL, outer.dtype, (inner.src[0],), inner.arg+outer.arg)), - # do expansion - (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.GEP, Ops.WMMA, Ops.LOAD, Ops.STORE, Ops.INDEX, Ops.ASSIGN, - Ops.VECTORIZE, Ops.IF), name="root", custom_early_reject=set([Ops.UNROLL])), do_expand), - (UPat(Ops.CONTRACT, name="con"), do_contract), - # vectorize DEFINE_ACC - (UPat(Ops.VECTORIZE, src=UPat(Ops.DEFINE_ACC, name="acc"), name="v"), lambda acc,v: acc.replace(dtype=v.dtype)), - # BARRIERs aren't actually expanded - (UPat(Ops.BARRIER, src=(UPat(Ops.UNROLL, name="ex"),)), - lambda ex: UOp(Ops.UNROLL, dtypes.void, (UOp(Ops.BARRIER, dtypes.void, ex.src),)*len(ex.src), ex.arg)), - # empty UNROLL is NOOP - (UPat(Ops.UNROLL, src=(UPat.var('x'),), arg=()), lambda x: x), - # UNROLL GEP (needed for WMMA, generalize this) -> vectorized ALU - (UPat(Ops.UNROLL, name="ex", src=tuple(UPat.var('x').gep(i)+UPat.var('y').gep(i) for i in range(256 if AMX else 8))), - lambda ex,x,y: UOp(Ops.UNROLL, ex.dtype, tuple((x+y).gep(i) for i in range(256 if AMX else 8)), ex.arg)), -]) - -def no_vectorized_load_store(ls:UOp): - idx = ls.src[0] - assert isinstance(idx.dtype, PtrDType) - if idx.dtype.v == 1: return None - tv = [UOp(ls.op, ls.dtype.scalar(), tuple(j.gep(i) for j in ls.src)) for i in range(idx.dtype.v)] - return UOp(Ops.VECTORIZE, ls.dtype, tuple(tv)) - -def no_vectorized_acc(acc:UOp): - if acc.dtype.count == 1: return None - alus = tuple(UOp(acc.op, acc.dtype.scalar(), - tuple(s.gep(i) if j == 0 else s for j,s in enumerate(acc.src)), acc.arg+(i,)) for i in range(acc.dtype.count)) - return UOp(Ops.VECTORIZE, acc.dtype, alus) - -devectorize = PatternMatcher([ - # no ALU on vectorized dtypes - (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.ASSIGN, Ops.INDEX), name="alu"), no_vectorized_alu), - (UPat(Ops.WMMA, name="wmma"), no_vectorized_wmma), - (UPat(Ops.DEFINE_ACC, name="acc"), no_vectorized_acc), - (UPat((Ops.LOAD, Ops.STORE), name="ls"), no_vectorized_load_store), -]) - -def delete_redundant_gates(buf:UOp, idx:UOp, val:UOp, store_gate:UOp, cast:UOp|None=None) -> UOp|None: - if store_gate not in [gate.src[0] for gate in val.toposort if gate.op is Ops.IF]: return None - # remove the gate from the index - return UOp.store(buf.index(idx).cast(cast.dtype) if cast is not None else buf.index(idx), val) - -load_store_indexing = PatternMatcher([ - # late fixup of unfoldable image loads - (UPat(Ops.LOAD, src=(UPat.var("buf"), UPat()), allow_any_len=True, name="load"), fix_unfoldable_image_load), - # simplify valid - (UPat(Ops.AND, name="valid"), simplify_valid), - # image load valid idx simplification - (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("start_idx"), UPat.var("valid"))), simplify_valid_load), - # delete_redundant_gates (after expand) - (UPat(Ops.STORE, src=(UPat.any(stidx:=UPat.var("buf").index(UPat.var("idx"), UPat.var("store_gate")), stidx.cast().named("cast")), - UPat.var("val"))), delete_redundant_gates), -]) - -migrate_indexing = PatternMatcher([ - # create gate MUST BE BEFORE expander - (UPat(Ops.STORE, name="root"), create_gate), -]) - -def move_mask(x:UOp, buf:UOp, idx:UOp, mask:UOp, cast:UOp|None=None) -> UOp: - # this moves the mask from the indexing to the load/store op for rendering - nidx = buf.index(idx).cast(cast.dtype) if cast is not None else buf.index(idx) - return UOp.load(nidx, x.const_like(0), mask, *x.src[1:], dtype=x.dtype) if x.op is Ops.LOAD else UOp.store(nidx, x.src[1], mask, *x.src[2:]) - -pm_render = PatternMatcher([ - # for rendering, we use explicit VECTORIZE - (UPat(Ops.CONST, name='c'), - lambda c: UOp(Ops.VECTORIZE, c.dtype, (UOp.const(c.dtype.scalar(), c.arg),)*c.dtype.vcount) if c.dtype.vcount > 1 else None), - (UPat(Ops.VCONST, name='c'), lambda c: UOp(Ops.VECTORIZE, c.dtype, tuple(UOp.const(c.dtype.scalar(), x) for x in c.arg))), - (UPat(Ops.GEP, name='gep'), lambda gep: UOp(Ops.VECTORIZE, gep.dtype, tuple(gep.src[0].gep(x) for x in gep.arg)) if len(gep.arg) > 1 else None), - (UPat(Ops.VECTORIZE, src=(UPat(name='x'),)), lambda x: x), - # move masks of loads/stores - (UPat((Ops.LOAD, Ops.STORE), src=(UPat.any(masked_index:=UPat(Ops.INDEX, src=(UPat(name="buf"), UPat(name="idx"), UPat(name="mask"))), - masked_index.cast(None).named("cast")),), allow_any_len=True, name="x"), move_mask), - # gate any stores that aren't gated with ifs - (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat(), UPat(), UPat(dtype=dtypes.bool)), name="store"), - lambda store: UOp(Ops.STORE, src=store.src[:2]+(UOp(Ops.IF, src=(store.src[2],)),))), -]) - -# *** uop graph *** - -def full_graph_rewrite(sink:UOp, opts:Optional[Renderer]=None) -> UOp: - assert sink.op is Ops.SINK, f"sink isn't sink, it's {sink.op}" - supported_ops = tuple(opts.code_for_op.keys()) if opts is not None else () - extra_matcher = opts.extra_matcher if opts is not None and opts.extra_matcher is not None else PatternMatcher([]) - - # initial symbolic + migrate indexing (remove this) - sink = graph_rewrite(sink, sym+migrate_indexing) - - # expand - sink = graph_rewrite(sink, sym+expander) - - # devectorize + load_store_indexing - sink = graph_rewrite(sink, sym+(devectorize+float4_folding if opts is not None and opts.supports_float4 else devectorize)+load_store_indexing) - - # final rules for the renderer (without sym) - sink = graph_rewrite(sink, symbolic_simple+get_late_rewrite_patterns(supported_ops, TRANSCENDENTAL>=2)+pm_render+extra_matcher) - return sink diff --git a/tinygrad_repo/tinygrad/device.py b/tinygrad_repo/tinygrad/device.py index 023095f1d6..7a3b183dc5 100644 --- a/tinygrad_repo/tinygrad/device.py +++ b/tinygrad_repo/tinygrad/device.py @@ -1,30 +1,31 @@ from __future__ import annotations from dataclasses import dataclass, replace from collections import defaultdict -from typing import Optional, Any, Iterator, Generator -import multiprocessing, importlib, inspect, functools, pathlib, os, ctypes, contextlib, sys, re, atexit, pickle, decimal, time -from tinygrad.helpers import CI, OSX, getenv, diskcache_get, diskcache_put, DEBUG, GlobalCounters, flat_mv, from_mv, PROFILE, temp -from tinygrad.dtype import DType, ImageDType, PtrDType, dtypes +from typing import Optional, Any, Generic, TypeVar, Iterator, Generator +import multiprocessing, importlib, inspect, functools, pathlib, os, ctypes, ctypes.util, platform, contextlib, sys, re, atexit, pickle, decimal, time +from tinygrad.helpers import CI, OSX, LRU, getenv, diskcache_get, diskcache_put, DEBUG, GlobalCounters, flat_mv, from_mv, PROFILE, temp, mv_address, \ + cpu_time_execution, colored, Context, round_up, DISABLE_COMPILER_CACHE +from tinygrad.dtype import DType, ImageDType, PtrDType, dtypes, _to_np_dtype from tinygrad.renderer import Renderer -from tinygrad.ops import UOp, buffers # **************** Device **************** +ALL_DEVICES = ["METAL", "AMD", "NV", "CUDA", "QCOM", "GPU", "CPU", "LLVM", "DSP", "WEBGPU"] class _Device: def __init__(self) -> None: self._devices = [x.stem[len("ops_"):].upper() for x in (pathlib.Path(__file__).parent/"runtime").iterdir() if x.stem.startswith("ops_")] self._opened_devices:set[str] = set() - @functools.lru_cache(maxsize=None) # this class is a singleton, pylint: disable=method-cache-max-size-none + @functools.cache # this class is a singleton, pylint: disable=method-cache-max-size-none def _canonicalize(self, device:str) -> str: return re.sub(r":0$", "", (d:=device.split(":", 1)[0].upper()) + device[len(d):]) # NOTE: you can't cache canonicalize in case Device.DEFAULT changes - def canonicalize(self, device:Optional[str]) -> str: return self._canonicalize(device) if device is not None else Device.DEFAULT + def canonicalize(self, device:Optional[str]) -> str: return self._canonicalize(device if device is not None else Device.DEFAULT) def __getitem__(self, ix:str) -> Compiled: return self.__get_canonicalized_item(self.canonicalize(ix)) - @functools.lru_cache(maxsize=None) # this class is a singleton, pylint: disable=method-cache-max-size-none + @functools.cache # this class is a singleton, pylint: disable=method-cache-max-size-none def __get_canonicalized_item(self, ix:str) -> Compiled: cpn = multiprocessing.current_process().name assert (cpn == "MainProcess") or ix.split(":")[0] in ["DISK", "NPY", "PYTHON"], f"can only open device {ix} from parent, not {cpn}" x = ix.split(":")[0].upper() - ret = [cls for cname, cls in inspect.getmembers(importlib.import_module(f'{__name__.split(".")[0]}.runtime.ops_{x.lower()}')) \ + ret = [cls for cname, cls in inspect.getmembers(importlib.import_module(f'tinygrad.runtime.ops_{x.lower()}')) \ if (cname.lower() == x.lower() + "device")][0](ix) if DEBUG >= 1: print(f"opened device {ix} from pid:{os.getpid()}") self._opened_devices.add(ix) @@ -32,17 +33,20 @@ class _Device: @property def default(self) -> Compiled: return self[self.DEFAULT] def get_available_devices(self) -> Iterator[str]: - for device in ["METAL", "AMD", "NV", "CUDA", "QCOM", "GPU", "CLANG", "LLVM"]: + for device in ALL_DEVICES: with contextlib.suppress(Exception): yield self[device].device @functools.cached_property def DEFAULT(self) -> str: - if (from_env:=next((d for d in self._devices if d not in ["DISK", "NPY"] and getenv(d) == 1), None)): return from_env + from_env = [d for d in self._devices if d not in ["DISK", "NPY"] and getenv(d) == 1] + assert len(from_env) < 2, f"multiple devices set in env: {from_env}" + if len(from_env) == 1: return from_env[0] try: device = next(self.get_available_devices()) os.environ[device] = "1" # we set this in environment for spawned children return device except StopIteration as exc: raise RuntimeError("no usable devices") from exc Device = _Device() +atexit.register(lambda: [Device[dn].finalize() for dn in Device._opened_devices]) # **************** Profile **************** @@ -55,6 +59,9 @@ class ProfileDeviceEvent(ProfileEvent): @dataclass(frozen=True) class ProfileRangeEvent(ProfileEvent): device:str; name:str; st:decimal.Decimal; en:decimal.Decimal; is_copy:bool # noqa: E702 +@dataclass(frozen=True) +class ProfileProgramEvent(ProfileEvent): device:str; name:str; lib:bytes|None; base:int|None # noqa: E702 + @dataclass(frozen=True) class ProfileGraphEntry: device:str; name:str; st_id:int; en_id:int; is_copy:bool # noqa: E702 @@ -84,12 +91,22 @@ class BufferSpec: nolru: bool = False external_ptr: Optional[int] = None +class MultiBuffer: + def __init__(self, device:tuple[str, ...], size:int, dtype:DType): + self.bufs = [Buffer(d, size, dtype) for d in device] + self.size, self.dtype = size, dtype + def ref(self, cnt): + for b in self.bufs: b.ref(cnt) + return self + def is_allocated(self): return all(x.is_allocated() for x in self.bufs) + def __repr__(self): return f"" + class Buffer: def __init__(self, device:str, size:int, dtype:DType, opaque:Any=None, options:Optional[BufferSpec]=None, initial_value:Optional[bytes]=None, - lb_refcount=0, uop_ref:UOp|None=None, base:Optional[Buffer]=None, offset:int=0, preallocate=False): + lb_refcount=0, base:Optional[Buffer]=None, offset:int=0, preallocate=False): if isinstance(dtype, ImageDType): options = BufferSpec(image=dtype) # TODO: image hack shouldn't be here. where should it be? else: assert isinstance(dtype, DType) and not isinstance(dtype, PtrDType) - self.device, self.size, self.dtype, self.options, self.offset = device, size, dtype, options, offset + self.device, self.size, self.dtype, self.options, self.offset, self.allocated_views = device, size, dtype, options, offset, 0 if base is None: assert offset == 0, "base buffers can't have offset" self._base = None @@ -103,54 +120,67 @@ class Buffer: assert device == base.device, "base must have the same device" self._base = base if preallocate: self.allocate() - if uop_ref is not None: buffers[uop_ref] = self @property def base(self) -> Buffer: return self._base if self._base is not None else self @property def lb_refcount(self): return self.base._lb_refcount - def ref(self, cnt): self.base._lb_refcount += cnt + def ref(self, cnt): + self.base._lb_refcount += cnt + return self def is_allocated(self) -> bool: return hasattr(self, '_buf') def ensure_allocated(self) -> Buffer: return self.allocate() if not self.is_allocated() else self def allocate(self, opaque=None, external_ptr=None) -> Buffer: assert not self.is_allocated(), "can't allocate already allocated buffer" - self.allocator = Device[self.device].allocator + if DEBUG >= 7: print(f"buffer: allocate {self.nbytes} bytes on {self.device}") + self.allocator:Allocator = Device[self.device].allocator if external_ptr is not None: self.options = replace(self.options, external_ptr=external_ptr) if self.options else BufferSpec(external_ptr=external_ptr) if self._base is not None: self._base.ensure_allocated() + self._base.allocated_views += 1 assert hasattr(self.allocator, "_offset"), "offset function required for view" self._buf: Any = self.allocator._offset(self.base._buf, self.nbytes, self.offset) else: self._buf = opaque if opaque is not None else self.allocator.alloc(self.nbytes, self.options) if not self.device.startswith("DISK"): GlobalCounters.mem_used += self.nbytes return self + def deallocate(self): + assert self.is_allocated(), "buffer must be allocated to deallocate" + if DEBUG >= 7: print(f"buffer: deallocate {self.nbytes} bytes on {self.device}") + if self._base is None and (self.options is None or self.options.external_ptr is None): + if not self.device.startswith("DISK"): GlobalCounters.mem_used -= self.nbytes + self.allocator.free(self._buf, self.nbytes, self.options) + elif self._base is not None: self._base.allocated_views -= 1 + del self._buf def __reduce__(self): buf = None - if len(uop_refs:=[u for u,v in buffers.items() if self is v]) > 1: raise RuntimeError(f"double ref to buffer? {len(uop_refs)}") - uop_ref = None if len(uop_refs) == 0 else uop_refs[0] if self._base is not None: - return self.__class__, (self.device, self.size, self.dtype, None, None, None, 0, uop_ref, self.base, self.offset, self.is_allocated()) - if self.device == "NPY": return self.__class__, (self.device, self.size, self.dtype, self._buf, self.options, None, self.lb_refcount, uop_ref) + return self.__class__, (self.device, self.size, self.dtype, None, None, None, 0, self.base, self.offset, self.is_allocated()) + if self.device == "NPY": return self.__class__, (self.device, self.size, self.dtype, self._buf, self.options, None, self.lb_refcount) if self.is_allocated(): buf = bytearray(self.nbytes) self.copyout(memoryview(buf)) - return self.__class__, (self.device, self.size, self.dtype, None, self.options, buf, self.lb_refcount, uop_ref) + return self.__class__, (self.device, self.size, self.dtype, None, self.options, buf, self.lb_refcount) @property def nbytes(self): return self.size*self.dtype.itemsize - def __del__(self): - if not self.is_allocated(): return - if self._base is None and (self.options is None or self.options.external_ptr is None): - if not self.device.startswith("DISK"): GlobalCounters.mem_used -= self.nbytes - self.allocator.free(self._buf, self.nbytes, self.options) + def __del__(self): (not self.is_allocated()) or self.deallocate() def __repr__(self): return f"" + (f" offset:{self.offset}" if self._base is not None else "") + (f" {self.options=}" if self.options is not None else "") + ">" def as_buffer(self, allow_zero_copy=False, force_zero_copy=False) -> memoryview: # zero copy with as_buffer (disabled by default due to use after free) if (force_zero_copy or allow_zero_copy) and hasattr(self.allocator, '_as_buffer') and (self.options is None or self.options.image is None): return self.allocator._as_buffer(self._buf) assert not force_zero_copy, "force zero copy was passed, but copy is required" return self.copyout(memoryview(bytearray(self.nbytes))) + def as_typed_buffer(self, shape=None, allow_zero_copy=False, force_zero_copy=False) -> memoryview: + assert self.dtype.base.fmt is not None, f"no fmt dtype for {self.dtype.base}" + assert self.dtype.base.fmt != "e" or sys.version_info >= (3, 12) + return self.as_buffer(allow_zero_copy, force_zero_copy).cast(self.dtype.base.fmt, shape if shape is not None else (self.size,)) + def numpy(self) -> 'np.ndarray': # type: ignore [name-defined] # noqa: F821 + import numpy as np + assert _to_np_dtype(self.dtype.base) is not None, f"no np dtype for {self.dtype.base}" + return np.frombuffer(self.as_buffer(), dtype=_to_np_dtype(self.dtype.base)) def copyin(self, mv:memoryview): mv = flat_mv(mv) assert len(mv) == self.nbytes, f"size mismatch, {len(mv)=} != {self.dtype=} {self.size=}" @@ -168,11 +198,14 @@ class Buffer: if self._base is not None: return Buffer(self.device, size, dtype, base=self._base, offset=self.offset+offset) return Buffer(self.device, size, dtype, base=self, offset=offset) +DeviceType = TypeVar('DeviceType', bound='Compiled') + # TODO: size, dest, src are the same type. can we enforce this? -class Allocator: - # overriden in LRUAllocator +class Allocator(Generic[DeviceType]): + def __init__(self, dev:DeviceType): self.dev: DeviceType = dev + # overridden in LRUAllocator def alloc(self, size:int, options:Optional[BufferSpec]=None): - assert size > 0, f"alloc size must be positve, getting {size}" + assert size > 0, f"alloc size must be positive, getting {size}" return self._alloc(size, options if options is not None else BufferSpec()) def free(self, opaque, size:int, options:Optional[BufferSpec]=None): self._free(opaque, options if options is not None else BufferSpec()) @@ -185,12 +218,14 @@ class Allocator: # def _offset(self, buf, size:int, offset:int): # def _transfer(self, dest, src, sz:int, src_dev, dest_dev): -class LRUAllocator(Allocator): +class LRUAllocator(Allocator, Generic[DeviceType]): """ The LRU Allocator is responsible for caching buffers. It ensures that buffers are not freed until it is absolutely necessary, optimizing performance. """ - def __init__(self): self.cache: dict[tuple[int, Optional[BufferSpec]], Any] = defaultdict(list) + def __init__(self, dev:DeviceType): + self.cache: dict[tuple[int, Optional[BufferSpec]], Any] = defaultdict(list) + super().__init__(dev) def alloc(self, size:int, options:Optional[BufferSpec]=None): if len(c := self.cache[(size, options)]): return c.pop() try: return super().alloc(size, options) @@ -202,25 +237,83 @@ class LRUAllocator(Allocator): for opaque in opaques: super().free(opaque, sz, options) opaques.clear() def free(self, opaque:Any, size:int, options:Optional[BufferSpec]=None): - if getenv("LRU", 1) and (options is None or not options.nolru): self.cache[(size, options)].append(opaque) + if LRU and (options is None or not options.nolru): self.cache[(size, options)].append(opaque) else: super().free(opaque, size, options) -class _MallocAllocator(LRUAllocator): +class _MallocAllocator(LRUAllocator['Compiled']): def _alloc(self, size:int, options:BufferSpec): - return (ctypes.c_uint8 * size).from_address(options.external_ptr) if options.external_ptr else (ctypes.c_uint8 * size)() + # must be aligned to 0x20 for 256-bit ymm registers + # TODO: investigate if this is the cause of nondeterminism in speed + alignment = 0x1000 if size >= 0x1000 else 0x20 + return (ctypes.c_uint8 * size).from_address(options.external_ptr) if options.external_ptr else self._alloc_aligned(size, alignment) + def _alloc_aligned(self, size:int, alignment:int): + buffer = (ctypes.c_uint8 * (size + alignment))() + offset = round_up(ctypes.addressof(buffer), alignment) - ctypes.addressof(buffer) + return (ctypes.c_uint8 * size).from_buffer(buffer, offset) def _as_buffer(self, src) -> memoryview: return flat_mv(memoryview(src)) def _copyin(self, dest, src:memoryview): ctypes.memmove(dest, from_mv(src), len(src)) def _copyout(self, dest:memoryview, src): ctypes.memmove(from_mv(dest), src, len(dest)) def _offset(self, buf, size:int, offset:int): return from_mv(self._as_buffer(buf)[offset:offset+size]) -MallocAllocator = _MallocAllocator() +MallocAllocator = _MallocAllocator(None) # type: ignore + +# NOTE: MAP_JIT is added to mmap module in python 3.13 +MAP_JIT = 0x0800 + +# CPUProgram is a jit/shellcode program that can be just mmapped and jumped to +class CPUProgram: + rt_lib = ctypes.CDLL(ctypes.util.find_library('System' if OSX else 'kernel32') if OSX or sys.platform == "win32" else 'libgcc_s.so.1') + atomic_lib = ctypes.CDLL(ctypes.util.find_library('atomic')) if sys.platform == "linux" else None + + def __init__(self, name:str, lib:bytes): + if sys.platform == "win32": + PAGE_EXECUTE_READWRITE = 0x40 + MEM_COMMIT = 0x1000 + MEM_RESERVE = 0x2000 + ctypes.windll.kernel32.VirtualAlloc.restype = ctypes.c_void_p + self.mem = ctypes.windll.kernel32.VirtualAlloc(ctypes.c_void_p(0), ctypes.c_size_t(len(lib)), MEM_COMMIT | MEM_RESERVE, PAGE_EXECUTE_READWRITE) + ctypes.memmove(self.mem, lib, len(lib)) + ctypes.windll.kernel32.GetCurrentProcess.restype = ctypes.c_void_p + proc = ctypes.windll.kernel32.GetCurrentProcess() + ctypes.windll.kernel32.FlushInstructionCache(ctypes.c_void_p(proc), ctypes.c_void_p(self.mem), ctypes.c_size_t(len(lib))) + self.fxn = ctypes.CFUNCTYPE(None)(self.mem) + else: + from mmap import mmap, PROT_READ, PROT_WRITE, PROT_EXEC, MAP_ANON, MAP_PRIVATE + # On apple silicon with SPRR enabled (it always is in macos) RWX pages are unrepresentable: https://blog.svenpeter.dev/posts/m1_sprr_gxf/ + # MAP_JIT allows us to easily flip pages from RW- to R-X and vice versa. It is a noop on intel cpus. (man pthread_jit_write_protect_np) + self.mem = mmap(-1, len(lib), MAP_ANON | MAP_PRIVATE | (MAP_JIT if OSX else 0), PROT_READ | PROT_WRITE | PROT_EXEC) + + if OSX: CPUProgram.rt_lib.pthread_jit_write_protect_np(False) + self.mem.write(lib) + if OSX: CPUProgram.rt_lib.pthread_jit_write_protect_np(True) + + # __clear_cache isn't a normal libc function, but a compiler support routine found in libgcc_s for gcc and compiler-rt for clang. + # libgcc_s comes as shared library but compiler-rt is only a bunch of static library archives which we can't directly load, but fortunately + # it somehow found its way into libSystem on macos (likely because it used __builtin_clear_cache) and libgcc_s is ~always present on linux + # Using ["name"] instead of .name because otherwise name is getting mangled: https://docs.python.org/3.12/reference/expressions.html#index-5 + CPUProgram.rt_lib["__clear_cache"](ctypes.c_void_p(mv_address(self.mem)), ctypes.c_void_p(mv_address(self.mem) + len(lib))) + + self.fxn = ctypes.CFUNCTYPE(None)(mv_address(self.mem)) + + def __call__(self, *bufs, vals=(), wait=False): + args = list(bufs) + list(vals) + # NOTE: replace this by --target={host's triple}-elf in clang args once we only support macos sequoia and later. + # Apple relaxes abi requirement for stack arguments to always be at least 8 byte aligned on arm64 + # https://developer.apple.com/documentation/xcode/writing-arm64-code-for-apple-platforms + # This hack is required because clang/llvm bug doesn't allow us to just use {host's triple}+'-elf' (relocation failures) + # The bug was fixed in https://github.com/llvm/llvm-project/commit/454cc36630296262cdb6360b60f90a64a97f7f1a but was only backported to xcode 16+ + if platform.machine() == "arm64" and OSX: args = args[:8] + [ctypes.c_int64(a) if isinstance(a, int) else a for a in args[8:]] + return cpu_time_execution(lambda: self.fxn(*args), enable=wait) + + def __del__(self): + if sys.platform == 'win32': ctypes.windll.kernel32.VirtualFree(ctypes.c_void_p(self.mem), ctypes.c_size_t(0), 0x8000) #0x8000 - MEM_RELEASE # **************** for Compiled Devices **************** class CompileError(Exception): pass class Compiler: - def __init__(self, cachekey:Optional[str]=None): self.cachekey = None if getenv("DISABLE_COMPILER_CACHE") else cachekey + def __init__(self, cachekey:Optional[str]=None): self.cachekey = None if DISABLE_COMPILER_CACHE else cachekey def compile(self, src:str) -> bytes: return src.encode() # NOTE: empty compiler is the default def compile_cached(self, src:str) -> bytes: if self.cachekey is None or (lib := diskcache_get(self.cachekey, src)) is None: @@ -248,15 +341,25 @@ class Compiled: Called at the end of profiling to allow the device to finalize any profiling. """ # override this in your device implementation + def finalize(self): + """ + Called at the end of process lifetime to allow the device to finalize. + """ + # override this in your device implementation # TODO: move this to each Device def is_dtype_supported(dtype:DType, device:Optional[str]=None) -> bool: if device is None: device = Device.DEFAULT if dtype == dtypes.bfloat16: - # NOTE: this requires bf16 buffer support - return device in {"AMD"} or (device in {"CUDA", "NV"} and not CI and not getenv("PTX")) + if device == "METAL": return not CI + if device in {"CUDA", "NV"}: return not CI and not getenv("PTX") + if device in {"CPU", "LLVM"}: return not CI and platform.machine() in {"arm", "arm64", "aarch64", "x86_64", "amd64"} + return device == "AMD" + if dtype in dtypes.fp8s: + # not supported yet - in progress + return False if device == "WEBGPU": return dtype in [dtypes.bool, dtypes.char, dtypes.uchar, dtypes.short, - dtypes.ushort, dtypes.float, dtypes.int32, dtypes.uint32] + dtypes.ushort, dtypes.float, dtypes.int32, dtypes.uint32, dtypes.half] # for CI GPU and OSX, cl_khr_fp16 isn't supported # for CI LLVM, it segfaults because it can't link to the casting function # CI CUDA architecture is sm_35 but we need at least sm_70 to run fp16 ALUs @@ -271,12 +374,28 @@ def is_dtype_supported(dtype:DType, device:Optional[str]=None) -> bool: if PROFILE: @atexit.register - def finlize_profile(): + def finalize_profile(): devs = [Device[d] for d in Device._opened_devices] for dev in devs: dev.synchronize() for dev in devs: dev._at_profile_finalize() - with open(temp("profile.pkl"), "wb") as f: pickle.dump(Compiled.profile_events, f) + with open(fn:=temp("profile.pkl", append_user=True), "wb") as f: pickle.dump(Compiled.profile_events, f) + + if not getenv("SQTT", 0): + from tinygrad.uop.ops import launch_viz + launch_viz("PROFILE", fn) - from tinygrad.ops import launch_viz - launch_viz("PROFILE", temp("profile.pkl")) +if __name__ == "__main__": + for device in ALL_DEVICES: + try: + _ = Device[device].device + try: + from tinygrad import Tensor + with Context(CACHELEVEL=0): test = (Tensor([1,2,3], device=device) * 2).tolist() + if test != [2,4,6]: raise ValueError(f"got {test} instead of [2, 4, 6]") + result = colored("PASS", "green") + except Exception as e: + result = f"{colored('FAIL', 'yellow')} {e}" + except Exception as e: + result = f"{colored('FAIL', 'red')} {e}" + print(f"{'*' if device == Device.DEFAULT else ' '} {device:10s}: {result}") diff --git a/tinygrad_repo/tinygrad/dtype.py b/tinygrad_repo/tinygrad/dtype.py index e6fe4a574a..90c3c1e744 100644 --- a/tinygrad_repo/tinygrad/dtype.py +++ b/tinygrad_repo/tinygrad/dtype.py @@ -1,5 +1,5 @@ from __future__ import annotations -from typing import Final, Optional, ClassVar, Tuple, Union, Callable, Literal +from typing import Final, Optional, ClassVar, Union, Callable, Literal import math, struct, ctypes, functools from dataclasses import dataclass, fields from tinygrad.helpers import getenv, prod @@ -10,7 +10,7 @@ FmtStr = Literal['?', 'b', 'B', 'h', 'H', 'i', 'I', 'q', 'Q', 'e', 'f', 'd'] # all DTypes should only be created once class DTypeMetaClass(type): - dcache: dict[Tuple, DType] = {} + dcache: dict[tuple, DType] = {} def __call__(cls, *args, **kwargs): if (ret:=DTypeMetaClass.dcache.get(args, None)) is not None: return ret DTypeMetaClass.dcache[args] = ret = super().__call__(*args) @@ -33,7 +33,7 @@ class DType(metaclass=DTypeMetaClass): def base(self): return self @property def vcount(self): return self.count - @functools.lru_cache(None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def vec(self, sz:int) -> DType: assert self.count == 1, f"can't vectorize {self} with size {sz}" if sz == 1 or self == dtypes.void: return self # void doesn't vectorize, and sz=1 is scalar @@ -41,6 +41,7 @@ class DType(metaclass=DTypeMetaClass): def ptr(self, size=-1, local=False) -> PtrDType: return PtrDType(self.priority, self.itemsize, self.name, self.fmt, self.count, None, self, local, 1, size) def scalar(self) -> DType: return self._scalar if self._scalar is not None else self + def nbytes(self): raise RuntimeError("only ptr types have nbytes") @dataclass(frozen=True, eq=False) class PtrDType(DType): @@ -50,12 +51,17 @@ class PtrDType(DType): size: int = -1 # -1 is unlimited size @property def base(self): return self._base - @functools.lru_cache(None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def vec(self, sz:int) -> DType: assert self.v == 1, f"can't vectorize ptr {self} with size {sz}" if sz == 1: return self # sz=1 is a scalar - return type(self)(self.priority, self.itemsize, self.name, self.fmt, self.count, self, self._base, self.local, sz) + if isinstance(self, ImageDType): + return ImageDType(self.priority, self.itemsize, self.name, self.fmt, self.count, self, self._base, self.local, sz, self.size, self.shape) + return type(self)(self.priority, self.itemsize, self.name, self.fmt, self.count, self, self._base, self.local, sz, self.size) def ptr(self, size=-1, local=False): raise RuntimeError("can't make a pointer from a pointer") + def nbytes(self) -> int: + if self.size == -1: return 0 # TODO: this should be an exception + return self.size*self.itemsize @property def vcount(self): return self.v def __repr__(self): @@ -71,15 +77,17 @@ class ImageDType(PtrDType): class dtypes: @staticmethod - @functools.lru_cache(None) + @functools.cache def is_float(x: DType) -> bool: return x.scalar() in dtypes.floats or isinstance(x, ImageDType) - @staticmethod # static methds on top, or bool in the type info will refer to dtypes.bool - @functools.lru_cache(None) + @staticmethod # static methods on top, or bool in the type info will refer to dtypes.bool + @functools.cache def is_int(x: DType) -> bool: return x.scalar() in dtypes.ints @staticmethod - @functools.lru_cache(None) + @functools.cache def is_unsigned(x: DType) -> bool: return x.scalar() in dtypes.uints @staticmethod + def is_bool(x: DType) -> bool: return x.scalar() == dtypes.bool + @staticmethod def from_py(x) -> DType: if x.__class__ is float: return dtypes.default_float if x.__class__ is int: return dtypes.default_int @@ -95,12 +103,12 @@ class dtypes: # TODO: should truncate here return int(val) if dtypes.is_int(dtype) else float(val) if dtypes.is_float(dtype) else bool(val) @staticmethod - @functools.lru_cache(None) + @functools.cache def min(dtype:DType): if dtypes.is_int(dtype): return 0 if dtypes.is_unsigned(dtype) else -2**(dtype.itemsize*8-1) return -float("inf") if dtypes.is_float(dtype) else False @staticmethod - @functools.lru_cache(None) + @functools.cache def max(dtype:DType): if dtypes.is_int(dtype): return 2**(dtype.itemsize*8)-1+dtypes.min(dtype) return float("inf") if dtypes.is_float(dtype) else True @@ -108,7 +116,8 @@ class dtypes: def finfo(dtype:DType) -> tuple[int, int]: """(exponent, mantissa)""" if not dtypes.is_float(dtype): raise ValueError(f"{dtype} is not a floating point type") - return {dtypes.float16: (5, 10), dtypes.bfloat16: (8, 7), dtypes.float32: (8, 23), dtypes.float64: (11, 52)}[dtype] + return {dtypes.float16: (5, 10), dtypes.bfloat16: (8, 7), dtypes.float32: (8, 23), dtypes.float64: (11, 52), + dtypes.fp8e5m2: (5, 2), dtypes.fp8e4m3: (4, 3)}[dtype] @staticmethod def fields() -> dict[str, DType]: return DTYPES_DICT void: Final[DType] = DType.new(-1, 0, "void", None) @@ -121,11 +130,13 @@ class dtypes: uint32: Final[DType] = DType.new(6, 4, "unsigned int", 'I') int64: Final[DType] = DType.new(7, 8, "long", 'q') uint64: Final[DType] = DType.new(8, 8, "unsigned long", 'Q') - float16: Final[DType] = DType.new(9, 2, "half", 'e') + fp8e4m3: Final[DType] = DType.new(9, 1, "float8_e4m3", None) + fp8e5m2: Final[DType] = DType.new(10, 1, "float8_e5m2", None) + float16: Final[DType] = DType.new(11, 2, "half", 'e') # bfloat16 has higher priority than float16, so least_upper_dtype(dtypes.int64, dtypes.uint64) = dtypes.float16 - bfloat16: Final[DType] = DType.new(10, 2, "__bf16", None) - float32: Final[DType] = DType.new(11, 4, "float", 'f') - float64: Final[DType] = DType.new(12, 8, "double", 'd') + bfloat16: Final[DType] = DType.new(12, 2, "__bf16", None) + float32: Final[DType] = DType.new(13, 4, "float", 'f') + float64: Final[DType] = DType.new(14, 8, "double", 'd') # dtype aliases half = float16; float = float32; double = float64 # noqa: E702 @@ -141,32 +152,35 @@ class dtypes: default_float: ClassVar[DType] = float32 default_int: ClassVar[DType] = int32 - floats = (float16, bfloat16, float32, float64) + fp8s = (fp8e4m3, fp8e5m2) + floats = fp8s + (float16, bfloat16, float32, float64) uints = (uint8, uint16, uint32, uint64) sints = (int8, int16, int32, int64) ints = uints + sints + all = floats + ints + (bool,) if (env_default_float := getenv("DEFAULT_FLOAT", "")): dtypes.default_float = getattr(dtypes, env_default_float.lower()) assert dtypes.is_float(dtypes.default_float), f"{env_default_float} is not a float dtype" DTypeLike = Union[str, DType] -def to_dtype(dtype:DTypeLike) -> DType: return dtype if isinstance(dtype, DType) else getattr(dtypes, dtype) +def to_dtype(dtype:DTypeLike) -> DType: return dtype if isinstance(dtype, DType) else getattr(dtypes, dtype.lower()) # https://jax.readthedocs.io/en/latest/jep/9407-type-promotion.html # we don't support weak type and complex type promo_lattice = { dtypes.bool: [dtypes.int8, dtypes.uint8], dtypes.int8: [dtypes.int16], dtypes.int16: [dtypes.int32], dtypes.int32: [dtypes.int64], dtypes.int64: [dtypes.float16, dtypes.bfloat16], dtypes.uint8: [dtypes.int16, dtypes.uint16], dtypes.uint16: [dtypes.int32, dtypes.uint32], dtypes.uint32: [dtypes.int64, dtypes.uint64], dtypes.uint64: [dtypes.float16, dtypes.bfloat16], + dtypes.fp8e5m2: [dtypes.float16, dtypes.bfloat16], dtypes.fp8e4m3: [dtypes.float16, dtypes.bfloat16], dtypes.float16: [dtypes.float32], dtypes.bfloat16: [dtypes.float32], dtypes.float32: [dtypes.float64], } -@functools.lru_cache(None) +@functools.cache def _get_recursive_parents(dtype:DType) -> set[DType]: return set.union(*[_get_recursive_parents(d) for d in promo_lattice[dtype]], {dtype}) if dtype != dtypes.float64 else {dtypes.float64} -@functools.lru_cache(None) +@functools.cache def least_upper_dtype(*ds:DType) -> DType: return min(set.intersection(*[_get_recursive_parents(d) for d in ds])) if not (images:=[d for d in ds if isinstance(d, ImageDType)]) else images[0] -def least_upper_float(dt:DType) -> DType: return dt if dtypes.is_float(dt) else least_upper_dtype(dt, dtypes.float32) +def least_upper_float(dt:DType) -> DType: return dt if dtypes.is_float(dt) else least_upper_dtype(dt, dtypes.default_float) DTYPES_DICT = {k: v for k, v in dtypes.__dict__.items() if isinstance(v, DType) and not k.startswith(("default", "void"))} INVERSE_DTYPES_DICT = {**{v.name:k for k,v in DTYPES_DICT.items()}, "void": "void"} @@ -175,16 +189,105 @@ def sum_acc_dtype(dt:DType): # default acc dtype for sum if dtypes.is_unsigned(dt): return least_upper_dtype(dt, dtypes.uint) if dtypes.is_int(dt) or dt == dtypes.bool: return least_upper_dtype(dt, dtypes.int) - return least_upper_dtype(dt, dtypes.float) + return least_upper_dtype(dt, to_dtype(getenv("SUM_DTYPE", "float32"))) def truncate_fp16(x): try: return struct.unpack("@e", struct.pack("@e", float(x)))[0] except OverflowError: return math.copysign(math.inf, x) +def truncate_bf16(x): + max_bf16 = struct.unpack('f', struct.pack('I', 0x7f7f0000))[0] + if abs(x) > max_bf16: return math.copysign(math.inf, x) + f32_int = struct.unpack('I', struct.pack('f', x))[0] + bf = struct.unpack('f', struct.pack('I', f32_int & 0xFFFF0000))[0] + return bf + +# fp8-float conversions based on https://gitlab.com/nvidia/headers/cuda-individual/cudart/-/blob/main/cuda_fp8.hpp +def float_to_fp8(x: float, dtype: DType) -> int: + assert dtype in dtypes.fp8s, "Only for fp8s" + config = { + dtypes.fp8e4m3: {"EXP_BIAS": 7, "SIGNIFICAND_BITS": 4, "MANTISSA_MASK": 0x7, "MINDENORM_O2": 0x3F50000000000000, + "OVERFLOW_THRESHOLD": 0x407D000000000000, "MAXNORM": 0x7E, "MINNORM": 0x3F90000000000000, "INF_VALUE": 0x7F}, + dtypes.fp8e5m2: {"EXP_BIAS": 15, "SIGNIFICAND_BITS": 3, "MANTISSA_MASK": 0x3, "MINDENORM_O2": 0x3EE0000000000000, + "OVERFLOW_THRESHOLD": 0x40EE000000000000 - 1, "MAXNORM": 0x7B, "MINNORM": 0x3F10000000000000, "INF_VALUE": 0x7E} + }[dtype] + xbits, = struct.unpack('Q', struct.pack('d', x)) + FP8_DP_HALF_ULP = 1 << (53 - config["SIGNIFICAND_BITS"] - 1) + sign = ((xbits >> 63) & 1) << 7 + exp = (((xbits >> 52) & 0x7FF) - 1023 + config["EXP_BIAS"]) + mantissa = (xbits >> (53 - config["SIGNIFICAND_BITS"])) & config["MANTISSA_MASK"] + absx = xbits & 0x7FFFFFFFFFFFFFFF + + if absx <= config["MINDENORM_O2"]: res = 0 + elif absx > 0x7FF0000000000000: res = 0x7F if dtype == dtypes.fp8e4m3 else 0x7E | mantissa + elif absx > config["OVERFLOW_THRESHOLD"]: res = config["MAXNORM"] + elif absx >= config["MINNORM"]: + res = ((exp << (config["SIGNIFICAND_BITS"] - 1)) | mantissa) + round_bits = xbits & ((FP8_DP_HALF_ULP << 1) - 1) + if (round_bits > FP8_DP_HALF_ULP) or (round_bits == FP8_DP_HALF_ULP and (mantissa & 1)): res = res + 1 + else: + shift = 1 - exp + mantissa |= 1 << (config["SIGNIFICAND_BITS"] - 1) + res = (mantissa >> shift) + round_bits = (xbits | (1 << (53 - 1))) & ((FP8_DP_HALF_ULP << (shift + 1)) - 1) + if (round_bits > (FP8_DP_HALF_ULP << shift)) or (round_bits == (FP8_DP_HALF_ULP << shift) and (res & 1)): + res = res + 1 + + res |= sign + return int(res) + +def fp8_to_float(x: int, dtype: DType) -> float: + assert dtype in dtypes.fp8s, "Only for fp8s" + ur = x << 8 + + if dtype == dtypes.fp8e5m2 and (ur & 0x7FFF) > 0x7C00: ur = 0x7FFF + elif dtype == dtypes.fp8e4m3: + sign = ur & 0x8000 + exponent = ((ur & 0x7800) >> 1) + 0x2000 + mantissa = (ur & 0x0700) >> 1 + absx = x & 0x7F + if absx == 0x7F: ur = 0x7FFF + elif exponent == 0x2000: + if mantissa != 0: + mantissa <<= 1 + while (mantissa & 0x0400) == 0: + mantissa <<= 1 + exponent -= 0x0400 + mantissa &= 0x03FF + else: + exponent = 0 + ur = (sign | exponent) | mantissa + else: + ur = (sign | exponent) | mantissa + + half_bytes = struct.pack(' Optional[type]: + import numpy as np + return np.dtype(dtype.fmt).type if dtype.fmt is not None else None +def _from_np_dtype(npdtype:'np.dtype') -> DType: # type: ignore [name-defined] # noqa: F821 + import numpy as np + return dtypes.fields()[np.dtype(npdtype).name] + +@functools.cache +def _to_torch_dtype(dtype:DType) -> Optional['torch.dtype']: # type: ignore [name-defined] # noqa: F821 + import numpy as np, torch + # NOTE: torch doesn't expose this mapping with a stable API + try: return torch.from_numpy(np.array([], dtype=_to_np_dtype(dtype))).dtype + except TypeError: return None +@functools.cache +def _from_torch_dtype(torchdtype:'torch.dtype') -> DType: # type: ignore [name-defined] # noqa: F821 + return {v:k for k in dtypes.all if (v:=_to_torch_dtype(k)) is not None}[torchdtype] \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/engine/grouper.py b/tinygrad_repo/tinygrad/engine/grouper.py new file mode 100644 index 0000000000..3fdb862e6f --- /dev/null +++ b/tinygrad_repo/tinygrad/engine/grouper.py @@ -0,0 +1,543 @@ +from collections import defaultdict, deque +from dataclasses import dataclass +from tinygrad.uop.ops import UOp, Ops, GroupOp, PatternMatcher, UPat, graph_rewrite, graph_rewrite_map, identity_element, resolve +from tinygrad.uop.ops import can_pad, sint, track_rewrites, _substitute +from tinygrad.codegen.lowerer import get_contraction_with_reduce, get_contraction +from tinygrad.codegen.symbolic import symbolic_simple +from tinygrad.helpers import Metadata, all_int, all_same, colored, prod, dedup, unwrap, getenv, pluralize, ContextVar, Context, diskcache_put, flatten +from tinygrad.helpers import FUSE_CONV_BW, FUSE_ARANGE, DEBUG, DONT_REALIZE_EXPAND, DONT_GROUP_REDUCES, SPLIT_REDUCEOP, CAPTURE_PROCESS_REPLAY +from tinygrad.dtype import ImageDType +from tinygrad.engine.multi import multi_pm, replace_allreduce +from tinygrad.shape.shapetracker import ShapeTracker +from tinygrad.shape.view import View, strides_for_shape +from tinygrad.uop.spec import type_verify, sched_spec + +# creation can recurse a lot +import sys +sys.setrecursionlimit(10000) + +# **** UOp merge views + +merge_views = PatternMatcher([ + # merge adjacent views + (UPat(Ops.VIEW, src=(UPat(Ops.VIEW, name="v1"),), name="v2"), lambda v1,v2: v1.replace(arg=v1.arg+v2.arg)), + # merge view on load/store/valid + (UPat(Ops.VIEW, src=(UPat((Ops.LOAD, Ops.STORE, Ops.VALID), name="x"),), name="view"), + lambda x,view: x.replace(src=tuple((s.st+view.st).to_uop() if s.op is Ops.VIEW else s for s in x.src))), + # merge view on const if it's not masked + (UPat((Ops.CONST, Ops.DEFINE_VAR), name="x").view(name="view"), + lambda x,view: x.replace(src=(x.src[0].replace(arg=x.st+view.st),)) if all(v.mask is None for v in (x.st+view.st).views) else None), + # replace view with base if it's contiguous and the shapes match + (UPat(GroupOp.All-{Ops.DEVICE}, name="x").view(name="view"), lambda x,view: x if view.st.contiguous and x.shape == view.shape else None), + # replace masked view with zero if it can collapse + (UPat(Ops.VIEW, src=(UPat(),), name="view"), + lambda view: view.const_like(0) if (mask:=view.st.views[-1].mask) is not None and any((x[1]-x[0]) == 0 for x in mask) else None), + # movement ops apply a new view on the base + (UPat(GroupOp.Movement, src=(UPat.var("x"),), name="mop"), lambda mop,x: x.view(mop.st)), +]) + +# **** schedule simplifier + +def simplify_stride0_reduce(reduce:UOp, x:UOp): + # must be unmasked (NOTE: can be relaxed if not masked on stride 0 axis) + if any(v.mask is not None for v in unwrap(x.st).views): return None + # must have all stride 0 in the relevant axis (NOTE: can do partial) + if not all(unwrap(x.st).views[-1].strides[axis] == 0 for axis in reduce.arg[1]) or not all_int(x.shape): return None + prshape = prod(x.shape[i] for i in reduce.arg[1]) + ret = x.shrink(tuple((0,s) if i not in reduce.arg[1] else (0,1) for i,s in enumerate(x.shape))) + match reduce.arg[0]: + case Ops.ADD: return ret*prshape + case Ops.MUL: return ret.pow(prshape) + case Ops.MAX: return ret # NOTE: Ops.MAX is passthrough + +def split_reduceop(reduce:UOp, x:UOp): + if not SPLIT_REDUCEOP or not all_int(x.shape) or (prod(x.shape)//prod(reduce.shape))= 3: print(f"split {divisor}: {x.shape} -> {splitted.shape} -> {reduce.shape}") + # reduce original axes, then split + return splitted.r(*reduce.arg).r(reduce.arg[0], (len(reduce.shape),)).reshape(reduce.shape) + +ALWAYS_CONTIGUOUS = {Ops.CONTIGUOUS, Ops.ASSIGN, Ops.COPY, Ops.BUFFER, Ops.BUFFER_VIEW, Ops.CONST, Ops.BIND, Ops.DEVICE} + +sym = symbolic_simple+PatternMatcher([ + # UOp with size 0 is zero + (UPat(GroupOp.All-{Ops.SINK}, name="root"), lambda root: root.const_like(0) if root.base.st is not None and root.size == 0 \ + and not (root.base.op is Ops.CONST and root.base.arg == 0) else None), + # DETACH and CONTIGUOUS_BACKWARD are NOOPs here + (UPat((Ops.DETACH, Ops.CONTIGUOUS_BACKWARD), name="x"), lambda x: x.src[0]), + # MULTI in SINK just flattens srcs + (UPat(Ops.SINK, name="x"), + lambda x: UOp.sink(*new_src) if (new_src:=tuple(flatten([s.src if s.op is Ops.MULTI else [s] for s in x.src]))) != x.src else None), + # reduce of size 0 is the identity element + (UPat(Ops.REDUCE_AXIS, name="reduce", src=(UPat.var("x"),)), + lambda reduce,x: reduce.const_like(identity_element(reduce.arg[0], reduce.dtype)) if x.size == 0 and reduce.size != 0 else None), + # reduce on stride 0 is collapsed + (UPat(Ops.REDUCE_AXIS, name="reduce", src=(UPat.var("x"),)), simplify_stride0_reduce), + # split_reduceop + (UPat(Ops.REDUCE_AXIS, name="reduce", src=(UPat.var("x"),)), split_reduceop), + # COPY(CONST) creates a new CONST on the destination device + (UPat(Ops.COPY, name="root", src=(UPat.cvar("x"), UPat(Ops.DEVICE))), lambda root,x: root.const_like(x.arg)), + # store a shrink before COPY, otherwise view after the COPY + (UPat(Ops.COPY, src=(UPat(Ops.VIEW, name="v"), UPat(Ops.DEVICE)), name="copy"), lambda copy,v: + v.contiguous().copy_to_device(copy.device, arg=copy.arg) if prod(v.shape) < prod(v.base.shape) else \ + v.base.copy_to_device(copy.device, arg=copy.arg).view(v.st)), + # remove cast to image when it's already a contiguous image + (UPat(Ops.CAST, name="cast", src=(UPat(Ops.VIEW, name="vm", src=(UPat(Ops.CONTIGUOUS, name="base"),)),)), + lambda cast,base,vm: base.view(vm.st) if isinstance(cast.dtype, ImageDType) and isinstance(base.dtype, ImageDType) else None), + # make things that can't be images not images + (UPat(GroupOp.All-{Ops.BUFFER, Ops.VIEW, Ops.CONST, Ops.DEVICE}, name="u"), lambda u: u.replace(dtype=dt.base) if isinstance(dt:=u.dtype,ImageDType) + and (prod(u.shape) != prod(dt.shape) or not any(u.shape[x]%4 == 0 for x in u.st.unit_stride_axes())) else None), + # remove contiguous if we can just view the buffer + (UPat(Ops.CONTIGUOUS, name="root", src=(UPat(Ops.VIEW, name="view", src=(UPat(Ops.BUFFER, name="buf"),)),)), + lambda root,view,buf: view if view.st.contiguous and view.size == buf.size else None), + # contiguous/buffer/copy/assign is already contiguous + (UPat(Ops.CONTIGUOUS, name="root", src=(UPat((Ops.CONTIGUOUS, Ops.BUFFER, Ops.COPY, Ops.ASSIGN)),)), lambda root: root.src[0]), + # substitute BITCAST/CONTIGUOUS with BUFFER_VIEW on DISK + (UPat((Ops.BITCAST, Ops.CONTIGUOUS), src=(UPat.var("x"),), name="t"), lambda x,t: UOp(Ops.BUFFER_VIEW, t.dtype, (x.base,), + (t.size, x.st.views[0].offset)).reshape(t.shape) if isinstance(x.device, str) and x.device.startswith("DISK") else None), + # double ASSIGN to same target is one ASSIGN + (UPat(Ops.ASSIGN, src=(UPat.var("t"), UPat(Ops.ASSIGN, src=(UPat.var("t"), UPat.var("x"))))), lambda x,t: t.assign(x.contiguous())), + # ASSIGN to unrealized replaces the UOp + (UPat(Ops.ASSIGN, src=(UPat.var("t"), UPat.var("x"))), lambda x,t: x.contiguous() if t.base.op not in {Ops.BUFFER, Ops.BUFFER_VIEW} else None), + # put CAST to smaller dtype before EXPAND + (UPat(Ops.CAST, name="cast", src=(UPat(Ops.VIEW, name="vm"),)), lambda cast,vm: vm.base.cast(cast.dtype).view(vm.st) + if cast.dtype.itemsize <= vm.dtype.itemsize and resolve(prod(vm.shape) > vm.st.real_size()) else None), + # put UnaryOps before EXPANDs, if it can fuse with the input + (UPat(GroupOp.Unary, src=(UPat(Ops.VIEW, src=(UPat(GroupOp.All-ALWAYS_CONTIGUOUS, name="inp"),), name="v"),), name="alu"), + lambda inp,v,alu: inp.alu(alu.op).view(v.st) if resolve(prod(alu.shape) > v.st.real_size()) else None), +]) + +# support for using a contiguous permuted view instead of the parent view if one exists + +def found_contiguous(ctx:dict[UOp, UOp], contig:UOp, src:UOp): + if (sti:=unwrap(src.st).invert(src.base.shape)) is not None: ctx[src.base] = contig.view(sti) + +replace_contiguous = PatternMatcher([ + (UPat(Ops.CONTIGUOUS, src=(UPat(Ops.VIEW, name="src"),), name="contig"), found_contiguous), + (UPat(GroupOp.ALU, name="alu"), lambda ctx,alu: alu.replace(src=new_src) if (new_src:=tuple(ctx.get(s, s) for s in alu.src)) != alu.src else None), +]) + +# **** Grouper decides which of the UOps realize + +def realize(ctx:dict[UOp, None], tr:UOp) -> None: ctx[tr] = None + +def realize_before_view(ctx:dict[UOp, None], view:UOp, tr:UOp) -> None: + st = unwrap(view.st) + # always realize unsafe pad ops before masked view + if any(v.mask is not None for v in st.views) and not can_pad(tr, ctx): return realize(ctx, tr) + # fold simple pads + if len(st.views) == 1 and (m:=st.views[-1].mask) is not None and all_int(tr.shape) and resolve(prod(tr.shape) >= prod([y-x for x,y in m])): return + # realize before expand + if resolve(prod(tr.shape) < prod(st.shape)) and not DONT_REALIZE_EXPAND: return realize(ctx, tr) + +do_realize = PatternMatcher([ + # always realize SINK parents + (UPat(Ops.SINK, name="s"), lambda ctx,s: ctx.update((x.base, None) for x in s.src if x.base.op not in ALWAYS_CONTIGUOUS)), + # always realize ASSIGN/CONTIGUOUS/GroupOp.Meta + (UPat({Ops.ASSIGN, Ops.CONTIGUOUS, *GroupOp.Meta}, name="tr"), realize), + # realize before expand or unsafe pad ops + (UPat(Ops.VIEW, src=(UPat(GroupOp.All-ALWAYS_CONTIGUOUS, name="tr"),), name="view"), realize_before_view), + # realize before COPY + (UPat(Ops.COPY, src=(UPat(GroupOp.All-ALWAYS_CONTIGUOUS, name="tr"),), allow_any_len=True), realize), +]) + +def recursive_group(tr:UOp, st:ShapeTracker, r:UOp, children:defaultdict[UOp, dict[UOp, None]], realizes:dict[UOp, None], + reduce_for_op:dict[UOp, UOp], group:dict[UOp, None], cache:dict[tuple[UOp, ShapeTracker], None]) -> None: + if (tr, st) in cache: return + cache.setdefault((tr, st)) + rsize = unwrap(r.st).size + if tr in realizes and tr is not r: + # can only fuse contiguous + # max one reduceop per kernel + if not st.contiguous or st.size != rsize or tr in reduce_for_op: group.setdefault(r) + return group.setdefault(tr) + for tr_next in children[tr]: + # max one reduceop per kernel + if tr_next.op is Ops.REDUCE_AXIS: return group.setdefault(r) + # can only fuse contiguous + if len(st_childs:=dedup(unwrap(x.st) for x in tr_next.src if x.base == tr)) > 1: return group.setdefault(r) + recursive_group(tr_next, st+st_childs[0], r, children, realizes, reduce_for_op, group, cache) + +def group_realizes(sink:UOp) -> dict[UOp, None]: + # start by adding uops that always realize + realizes: dict[UOp, None] = {} + sink = graph_rewrite(sink, do_realize, ctx=realizes, name="do_realize") + if DONT_GROUP_REDUCES: return realizes + + # construct children graph (only for bases) + children: defaultdict[UOp, dict[UOp, None]] = defaultdict(dict) + assigns: dict[UOp, None] = {} + for u in (toposort:=sink.toposort()): + if u.op in {Ops.VIEW, Ops.SINK}: continue + if u.op is Ops.ASSIGN: assigns[u.buf_uop] = None + for s in u.src: children[s.base][u] = None + + # find all reduces, and pair them to a elementwise op. if they can't be cleanly paired, force realize the reduce (or a contig child) + reduce_for_op: dict[UOp, UOp] = {} + double_reduces: list[UOp] = [] + for r in toposort: + if r.op is not Ops.REDUCE_AXIS: continue + if len(r.arg) == 3 and r.arg[2] is True: continue + if FUSE_CONV_BW and r.src[0].base.op is Ops.REDUCE_AXIS and r.src[0] is not r.src[0].base: double_reduces.append(r) + if r in realizes: continue + group: dict[UOp, None] = {} + recursive_group(r, unwrap(r.st), r, children, realizes, reduce_for_op, group, cache={}) + # max one reduceop per kernel + can_chase = all(tr not in reduce_for_op for tr in group) + # TODO: forced_realize exists because the scheduler is incapable of checking for self-contained DAGs + forced_realize = r in group + # can only have one output + if not forced_realize and len(group) > 1: forced_realize = True + # can only fuse assign if no other assign_target is used in the kernel + if not forced_realize and (assign_targets:={x.buf_uop for x in group if x.op is Ops.ASSIGN}): + parents = deque((r, *group)) + while parents and not forced_realize: + p = parents.pop().base + if p.op is Ops.BUFFER and p in assigns and p not in assign_targets: forced_realize, can_chase = True, False + if p in realizes: continue + parents.extend(p.src) + if forced_realize or not group: + tr = r + if can_chase: + # can chase this down to contiguous children + st = unwrap(tr.st) + while len(children[tr]) == 1: + tr_next = next(iter(children[tr])) + st_childs = dedup(unwrap(s.st) for s in tr_next.src if s.base is tr) + if len(st_childs) > 1: break + if st.size != st_childs[0].size: break + st = st + st_childs[0] + if not st.contiguous or tr_next.op is Ops.REDUCE_AXIS: break + tr = tr_next + # don't cast to higher size before store (tr cannot be realized if forced_realize) + if tr.op is Ops.CAST and tr.dtype.itemsize > tr.src[0].dtype.itemsize: + tr = tr.src[0].base + group = {tr: None} + realizes[tr] = None + reduce_for_op.update((tr, r) for tr in group) + # fuse double reduces with no other child + for reduceop in double_reduces: + top_reduce = reduceop.src[0].base + if len(children[top_reduce]) == 1: del realizes[top_reduce] + return realizes + +# **** create kernels + +@dataclass(frozen=True) +class Kernel: + ast: UOp + metadata: tuple[Metadata, ...] = () + def __repr__(self): + ast_rep = f"SINK{tuple(s.op for s in self.ast.src)}" if self.ast.op is Ops.SINK else repr(self.ast.op) + return f"" + +def create_kernel(x:UOp, b:UOp|None=None): + if b is None: b = UOp.new_buffer(x.device, x.size, x.dtype) + kernel = UOp(Ops.KERNEL, src=(b,)+x.src, arg=Kernel(x.sink(), (m,) if (m:=x.metadata) else ())) + buffer = b.base if b.size == b.base.size else UOp(Ops.BUFFER_VIEW, b.dtype, (b.base,), (b.size, b.arg.views[0].offset)) + return buffer.assign(kernel).reshape(x.shape) + +DONT_PLACE_IN_KERNEL = {Ops.KERNEL, Ops.ASSIGN, Ops.BUFFER} +def append_to_kernel(ctx:dict[UOp, None], x:UOp): + new_srcs: list[UOp] = [] + metadata = dict.fromkeys(x.arg.metadata) + for s in x.src: + if s.op in DONT_PLACE_IN_KERNEL or s in ctx: new_srcs.append(s) + else: + new_srcs.extend(s.src) + if s.base.op not in {Ops.CONST, Ops.DEVICE} and (m:=s.metadata): metadata[m] = None + if (new_src:=tuple(dedup(new_srcs))) != x.src: return x.replace(src=new_src, arg=Kernel(x.arg.ast, tuple(metadata))) + +create_kernels = merge_views+PatternMatcher([ + # always give assign/contiguous a kernel + (UPat.assign(UPat.var("b"), UPat(GroupOp.All-{Ops.KERNEL}), name="x"), create_kernel), + (UPat(Ops.CONTIGUOUS, name="x"), create_kernel), + # create a buffer for COPY on the new device + (UPat(Ops.COPY, src=(UPat(), UPat(Ops.DEVICE)), name="x"), create_kernel), + # otherwise check the context if we're realizing this UOp + (UPat(GroupOp.All-DONT_PLACE_IN_KERNEL, name="x"), lambda ctx,x: create_kernel(x) if x in ctx else None), + # walk back the local graph until we reach a realized source + (UPat(Ops.KERNEL, name="x"), append_to_kernel), + # remove extra views and constants from SINK + (UPat(Ops.SINK, name="x"), + lambda x: x.replace(src=new_src) if (new_src:=tuple(dedup(s.base for s in x.src if s.base.op not in {Ops.CONST, Ops.BIND}))) != x.src else None), +]) + +# **** swizzler + +def reduce_push_add_ones(src:UOp, r:UOp, view:UOp): + # contiguous, expand, and the same with ones removed + if unwrap(view.st).contiguous and len(r.shape) < len(view.shape) and \ + tuple(x for x in r.shape if resolve(x != 1)) == tuple(x for x in view.shape if resolve(x != 1)): + new_shape: list[sint] = [] + new_reduce_axis = [] + if (contraction:=get_contraction_with_reduce(view.shape, r.shape, r.arg[1])) is None: return None + for i,pairs in enumerate(contraction): + new_shape_chunk = [view.shape[p] for p in pairs] + if i in r.arg[1]: + # if this is a reduce axis, we need a 1 in the view here to put it + assert len(new_shape_chunk) > 0 + new_shape += [1]*(len(pairs)-1) + [src.shape[i]] + new_reduce_axis.append(len(new_shape)-1) + else: + # otherwise, pass through the new_shape_chunk + new_shape += new_shape_chunk + ret = r.replace(src=(src.reshape(tuple(new_shape)),), arg=(r.arg[0], tuple(new_reduce_axis))+r.arg[2:]) + assert ret.shape == view.shape, f"shape mismatch on reduce_push_add_ones, {ret.shape} != {view.shape}" + return ret + return None + +view_left = merge_views+PatternMatcher([ + # view before elementwise ops + (UPat(Ops.VIEW, src=(UPat({*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.BIND}, name="e"),), name="view"), + lambda e,view: e.replace(src=tuple(s.view(s.st+view.st) if s.op is Ops.VIEW else s.view(view.st) for s in e.src))), + # if there's ones added after reduce, put this before the reduce + (UPat(Ops.VIEW, src=(UPat(Ops.REDUCE_AXIS, src=(UPat.var("src"),), name="r"),), name="view"), reduce_push_add_ones), +]) + +def apply_swizzle(u:UOp) -> UOp: return graph_rewrite(u, view_left, name="Sub View Left") + +def swizzle_reduceop(r:UOp, src:UOp, view:UOp, fuse=False): + if (st:=unwrap(view.st)).contiguous and st.size == r.size: return None + input_st = ShapeTracker.from_shape(src.shape) + tmp = input_st.permute(tuple(i for i in range(len(input_st.shape)) if i not in r.axis_arg)+r.axis_arg) + prshape = prod(rshape:=tmp.shape[-len(r.axis_arg):]) + strides = strides_for_shape(rshape) + nv = [View.create(v.shape+rshape, tuple(x*prshape for x in v.strides)+strides, + v.offset*prshape, v.mask+tuple((0,s) for s in rshape) if v.mask is not None else None) for v in st.views] + # create a new reduceop for the swizzled input + new_input_st = tmp + ShapeTracker(tuple(nv)) + new_axis = tuple(range(len(st.shape), len(st.shape) + len(r.axis_arg))) + swizzled_src = apply_swizzle(src.view(src.arg+new_input_st if src.op is Ops.VIEW else new_input_st)) + if fuse: red = UOp(Ops.REDUCE_AXIS, r.dtype, (swizzled_src.fuse(),), (r.arg[0], new_axis, True)) + else: red = UOp(Ops.REDUCE_AXIS, r.dtype, (swizzled_src,), (r.arg[0], new_axis)) + return red.view(ShapeTracker.from_shape(st.shape)) + +def reduceop_view_right(src:UOp, v:UOp, r:UOp): + assert unwrap(v.st).contiguous and v.size == src.size, f"can't compute new axis for {src.shape} -> {r.shape}" + if (contraction:=get_contraction(v.shape, src.shape)) is None: return None + new_axis: list[int] = [] + for i,pairs in enumerate(contraction): + if any(x in r.axis_arg for x in pairs): new_axis.append(i) + return src.r(r.arg[0], tuple(new_axis)).reshape(r.shape) + +def elementwise_view_right(root:UOp): + if not (swizzles:=[x for x in root.src if x.op is Ops.VIEW and x.base.op not in ALWAYS_CONTIGUOUS]): return None + assert all_same([x.base.size for x in swizzles]), f"swizzle inputs must have the same size {swizzles}" + # place view after applying the elementwise op + new_st = ShapeTracker.from_shape(swizzles[0].base.shape) + new_src = [x.base if x.base.shape==new_st.shape else apply_swizzle(x.view(x.arg+new_st) if x.op is Ops.VIEW else x.view(new_st)) for x in root.src] + # reshape to match downstream shapes + return root.replace(src=tuple(new_src)).reshape(root.shape) + +# push VIEW to children +view_right = merge_views+PatternMatcher([ + # push a non contiguous ShapeTracker through reduceop + (UPat(Ops.VIEW, src=(UPat(Ops.REDUCE_AXIS, src=(UPat.var("src"),), name="r"),), name="view"), swizzle_reduceop), + # apply view after reduceops + (UPat(Ops.REDUCE_AXIS, src=(UPat(Ops.VIEW, src=(UPat(GroupOp.All-ALWAYS_CONTIGUOUS, name="src"),), name="v"),), name="r"), reduceop_view_right), + # apply view after elementwise ops + (UPat(GroupOp.All-{Ops.SINK}, name="root"), elementwise_view_right), + # merge axes for double reduce (invert of SPLIT_REDUCEOP=1) + (UPat(Ops.REDUCE_AXIS, src=(UPat(Ops.REDUCE_AXIS, name="r1"),), name="r2"), + lambda r1,r2: r1.replace(arg=(r1.arg[0], r2.arg[1]+r1.arg[1])) if r1.arg[0] is r2.arg[0] else None), +]) + +# **** fix kernel AST + +add_buffer_ops = PatternMatcher([ + # LOAD + (UPat(Ops.BUFFER, name="x"), lambda ctx,x: UOp.load(UOp(Ops.DEFINE_GLOBAL, x.dtype.ptr(x.size), (), ctx.index(x)), x.st.to_uop())), + # STORE (except for meta ops) + (UPat(Ops.SINK, src=(UPat(GroupOp.Meta, name="x"),)), lambda x:x), + (UPat(Ops.SINK, src=UPat(GroupOp.All-{Ops.STORE}), name="sink"), lambda ctx,sink: + UOp.sink(*[UOp.store(UOp(Ops.DEFINE_GLOBAL, (s:=x.base).dtype.ptr(ctx[i].size), (), i), s.st.to_uop(), s) for i,x in enumerate(sink.src)])), + # passthrough ASSIGN + (UPat(Ops.ASSIGN, name="x"), lambda x: x.src[1]), + # VALID + (UPat(Ops.VIEW, src=(UPat((Ops.CONST, Ops.DEFINE_VAR), name="x"),), name="view"), lambda x,view: x.valid(view.arg)), +]) + +def check_load_st(glbl:UOp, view:UOp): + if glbl.arg != 0 or (st:=unwrap(view.st)).contiguous: return + # if it has a single view and it becomes contiguous when you shrink expanded axes, it's fine + if len(st.views) == 1 and st.shrink(tuple((0,1) if st == 0 else (0,s) for s,st in zip(st.shape, st.views[0].strides))).contiguous: return + # if it has a single view and it's equal when you shrink a contig, it's fine + if len(st.views) == 1 and (mask:=st.views[0].mask) is not None and ShapeTracker.from_shape(st.shape).shrink(mask) == st.shrink(mask): return + # otherwise, it's not fine + raise RuntimeError("self operand of augmented assign must be contiguous.\nhelp: consider using .contiguous():\n" + +colored(" - a += a.T\n", "red")+colored(" + a += a.T.contiguous()", "green")) + +fix_kernel_ops = PatternMatcher([ + # remove CONTIGUOUS/DEVICE from kernel AST + (UPat(Ops.CONTIGUOUS, src=(UPat.var("x"),)), lambda x: x), + (UPat(Ops.VIEW, src=(UPat(Ops.DEVICE),), name="view"), lambda view: view.replace(src=())), + # no ImageDType after load + (UPat(GroupOp.All-{Ops.DEFINE_GLOBAL}, name="x"), lambda x: x.replace(dtype=x.dtype.base) if isinstance(x.dtype, ImageDType) else None), + # if this kernel also assigns to the loaded buffer, ensure we can index it correctly + (UPat(Ops.LOAD, src=(UPat.var("glbl"), UPat.var("view"))), check_load_st), +]) + +def fix_kernel_ast(k:UOp) -> UOp|None: + if k.arg.ast.op in GroupOp.Meta or all(s.op is Ops.STORE for s in k.arg.ast.src): return None + # replace assign sources with a view of the target buffer + parents_rep: dict[UOp, UOp] = {} + for s in k.src: + if s.op is Ops.ASSIGN: + for out in s.src[1].arg.ast.src: parents_rep[out] = s.buf_uop.view(unwrap(out.st)) + parents_rep[s] = s.buf_uop + ast = k.arg.ast.substitute(parents_rep, name="replace realized") + # push views to edges + ast = graph_rewrite(graph_rewrite(ast, view_left, name="Main View Left"), view_right, name="Main View Right") + # replace buffer with define_global + add load/store last + ast = graph_rewrite(ast, merge_views+add_buffer_ops+fix_kernel_ops, bufs:=tuple(s.buf_uop for s in k.src), bottom_up=True, name="replace buffer") + if ast.op is Ops.SINK and not all_same([x.device for x in bufs]): + raise RuntimeError(f"all buffers must be on the same device: {tuple(b.buffer for b in bufs)}") + return k.replace(arg=Kernel(ast, k.arg.metadata)) + +create_ast = PatternMatcher([(UPat(Ops.KERNEL, name="k"), fix_kernel_ast),]) + +pm_fuse = PatternMatcher([ + # FUSE on CONTIGUOUS removes FUSE + (UPat(Ops.CONTIGUOUS, name="c").fuse(), lambda c: c), + + # FUSE triggers swizzle on reduceop + (UPat(Ops.VIEW, src=(UPat(Ops.REDUCE_AXIS, src=(UPat.var("src"),), name="r").or_casted(),), name="view").fuse(), + lambda r,src,view: ret.cast(view.dtype) if (ret:=swizzle_reduceop(r, src, view, fuse=True)) is not None else None), + + # FUSE on reduce (without view) adds fuse marker to grouper + (UPat(Ops.REDUCE_AXIS, name="r").fuse(), + lambda r: r.replace(src=(r.src[0].fuse(),), arg=r.arg+(True,)) if len(r.arg) == 2 else None), + + # remove FUSE and insert CONTIGUOUS if it's an unsafe pad + (UPat(Ops.VIEW, src=(UPat(GroupOp.UnsafePad, name="alu"),), name="view").fuse(), + lambda alu, view: alu.contiguous().view(view.st) if any(v.mask is not None for v in view.st.views) else None), + + # FUSE elementwise. + (UPat(Ops.VIEW, src=(UPat({*GroupOp.ALU, Ops.CAST}, name="alu"),), name="view").fuse(), + lambda alu, view: alu.replace(src=tuple(x.view(x.arg+view.arg if x.op is Ops.VIEW else view.arg).fuse() for x in alu.src))), + + # push FUSE through to srcs + (UPat(Ops.FUSE, name="x"), lambda x: x.src[0].replace(src=tuple(y.fuse() for y in x.src[0].src))), +]) + +def do_fusion(x:UOp): + found_contiguous = {} + def gate_contiguous(x): + if is_contiguous:=(x.op is Ops.CONTIGUOUS): found_contiguous[x] = x.replace(src=(UOp(Ops.VIEW, arg=x.st),)) + return not is_contiguous + x.toposort(gate=gate_contiguous) + del gate_contiguous + return graph_rewrite(x.substitute(found_contiguous), pm_fuse, name="local fusion").substitute({v:k for k,v in found_contiguous.items()}) + +def fuse_arange(root:UOp): + # skip if root is arange + if not FUSE_ARANGE or root.src[0].base.op is Ops.CONST: return None + # gather all local aranges (including any fused ones) + local_arange: list[UOp] = [] + def gate_reduce(u): + if u.op is Ops.REDUCE_AXIS and u.src[0].base.op is Ops.CONST: local_arange.append(u) + return u.op not in {*ALWAYS_CONTIGUOUS, Ops.REDUCE_AXIS} or u is root + toposort = root.toposort(gate=gate_reduce) + if not local_arange: return None + # fuse the nearest expand child of arange + local_children: dict[UOp, list[UOp]] = {} + for u in toposort: + for s in u.src: local_children.setdefault(s, []).append(u) + fuse_rep: dict[UOp, UOp] = {} + # skip if root depends on aranges with different ndims. This can be improved + if any(len(set(dims)) > 1 for dims in zip(*[r.src[0].shape for r in local_arange])): return + for r in local_arange: + # skip if already fused + if len(r.arg) > 2: continue + q = list(local_children[r]) + while q: + u = q.pop() + if not (curr_children:=local_children.get(u, [])): continue + for child in curr_children: + other_paths = {s for s in child.toposort() if s.op in {Ops.REDUCE_AXIS, Ops.BUFFER} and s not in {root, r}} + fuse_rep[child] = child.replace(src=tuple(s.fuse() if s is u else s for s in child.src)) + if other_paths: break + else: q.extend(curr_children) + return root.substitute(fuse_rep, name="fuse_arange") if fuse_rep else None + + +do_fuse = PatternMatcher([ + (UPat(Ops.FUSE, name="x"), do_fusion), + (UPat(Ops.REDUCE_AXIS, name="root"), fuse_arange), +]) + +PROCESS_REPLAY_CAPTURE:dict[int,bytes] = {} +if CAPTURE_PROCESS_REPLAY: + import atexit + @atexit.register + def save_process_replay(): + for k,v in PROCESS_REPLAY_CAPTURE.items(): diskcache_put("schedule_process_replay", k, v, prepickled=True) + +def get_name(becomes_map:dict[UOp, UOp]) -> str: + assigned_kernels = {u.base.buf_uop:u.base.src[1] for u in becomes_map.values() if u.base.op is Ops.ASSIGN}.values() + return f"Schedule {pluralize('Kernel', len(set(assigned_kernels)))}" + +@track_rewrites(name_fxn=get_name) +def get_becomes_map(big_sink:UOp) -> dict[UOp, UOp]: + # multi + merge_views + simplify + tensor_map = graph_rewrite_map(big_sink, multi_pm+replace_allreduce+do_fuse+merge_views+sym+replace_contiguous, ctx={}, name="merge_views") + + # display the cleaned up tensor graph + if getenv("VIZ"): graph_rewrite(tensor_map[big_sink], PatternMatcher([]), name="View Tensor Graph") + + # group into kernels + realize_map = group_realizes(tensor_map[big_sink]) + tensor_map = graph_rewrite_map(tensor_map[big_sink], create_kernels, ctx=realize_map, bottom_up=True, input_map=tensor_map, name="create_kernels") + + # if a kernel depends on a buffer, and that buffer is later assigned to, make the assign depend on the kernel's assign + kernel_assign: dict[UOp, UOp] = {} + assign_rep: dict[UOp, UOp] = {} + for u in tensor_map[big_sink].toposort(): + if u.op is not Ops.ASSIGN: continue + kernel_assign[u.buf_uop] = u + for s in u.src[1].src: + if s.op is not Ops.BUFFER or s is u.buf_uop or (a:=kernel_assign.get(s)) is None: continue + if any(x.op is Ops.ASSIGN and x.buf_uop is s for x in u.toposort()): + raise RuntimeError(f"cycle detected in graph, kernel for {u.buf_uop} must either depend on ASSIGN or BUFFER") + assign_rep[a] = kernel_assign[s] = a.replace(src=a.src+(u,)) + if assign_rep: + tensor_map = graph_rewrite_map(tensor_map[big_sink], _substitute, ctx=assign_rep, bottom_up=True, input_map=tensor_map, name="fix_assign") + + # finally, create the AST for kernels + tensor_map = graph_rewrite_map(tensor_map[big_sink], create_ast, bottom_up=True, input_map=tensor_map, name="create_ast") + + # display the final graph + sched_sink = tensor_map[big_sink] + if getenv("VIZ"): graph_rewrite(sched_sink, PatternMatcher([]), name="View Kernel Graph") + if getenv("VIZ"): graph_rewrite(sched_sink, PatternMatcher([]), name="View Memory Graph") + + # verify Kernels match the spec + type_verify(list(toposort:=sched_sink.toposort()), sched_spec) + + # capture process replay + if CAPTURE_PROCESS_REPLAY: + with Context(PICKLE_BUFFERS=0): + import pickle + PROCESS_REPLAY_CAPTURE[id(big_sink)] = pickle.dumps((big_sink, ContextVar._cache, [u.arg.ast for u in toposort if u.op is Ops.KERNEL])) + + # map tensors to buffer/assign/const + becomes_map: dict[UOp, UOp] = {} + for k,v in tensor_map.items(): + if k is v: continue + op = v.base.op + if op in {Ops.BUFFER, Ops.ASSIGN}: becomes_map[k] = v + if op is Ops.CONST and all_int(v.shape): becomes_map[k] = v + if op is Ops.MULTI and all(x.base in becomes_map for x in v.base.src): becomes_map[k] = v + + return becomes_map diff --git a/tinygrad_repo/tinygrad/engine/jit.py b/tinygrad_repo/tinygrad/engine/jit.py index a2776b937b..23f24250f7 100644 --- a/tinygrad_repo/tinygrad/engine/jit.py +++ b/tinygrad_repo/tinygrad/engine/jit.py @@ -2,11 +2,11 @@ from typing import TypeVar, Generic, Callable, Union, cast, Optional, Any import functools, collections from tinygrad.tensor import Tensor from tinygrad.helpers import flatten, merge_dicts, DEBUG, Context, BEAM, getenv, colored, JIT, dedup, partition, unwrap -from tinygrad.device import Buffer, Compiled, Device +from tinygrad.device import Buffer, Compiled, Device, MultiBuffer from tinygrad.dtype import DType -from tinygrad.ops import UOp, Variable, sym_infer +from tinygrad.uop.ops import UOp, Variable, sym_infer, Ops from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.engine.realize import ExecItem, capturing, EmptyOp, ViewOp, BufferCopy, BufferXfer, CompiledRunner, Runner, Estimates +from tinygrad.engine.realize import ExecItem, capturing, ViewOp, BufferCopy, BufferXfer, CompiledRunner, Runner, Estimates from tinygrad.engine.memory import _internal_memory_planner from tinygrad.nn.state import get_parameters from dataclasses import dataclass @@ -14,6 +14,8 @@ from weakref import WeakKeyDictionary class GraphException(Exception): pass +def graph_class(dev): return dev.graph.func if isinstance(dev.graph, functools.partial) else dev.graph + def apply_graph_to_jit(jit_cache: list[ExecItem], input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], max_batch_size=0) -> list[ExecItem]: # Split JIT cache into batches for faster graph execution. # This allows the accelerator to run some batches while subsequent graphs are still being updated. @@ -24,7 +26,8 @@ def apply_graph_to_jit(jit_cache: list[ExecItem], input_rawbuffers: list[Buffer] def flush_batch(): nonlocal current_batch, current_device, max_batch_size try: - if len(current_batch) <= 1 or current_device is None: raise GraphException("only one kernel doesn't graph") + if current_device is None: raise GraphException("no device for graph") + if len(current_batch) <= 1 and not getenv("GRAPH_ONE_KERNEL"): raise GraphException("only one kernel doesn't graph") graph_runner = current_device.graph(current_batch, input_rawbuffers, var_vals) # clear jit inputs to allow their memory to be freed/reused for (j,i) in graph_runner.input_replace.keys(): graph_runner.jit_cache[j].bufs[i] = None @@ -38,23 +41,24 @@ def apply_graph_to_jit(jit_cache: list[ExecItem], input_rawbuffers: list[Buffer] current_device = None for ji in jit_cache: - if ji.prg.__class__ in {EmptyOp, ViewOp}: continue - ji_graph_dev: Optional[Compiled] = None # device on which the ji will be graphed. Not graphed if None. - if isinstance(ji.prg, CompiledRunner): ji_graph_dev = ji.prg.dev - elif isinstance(ji.prg, BufferXfer) and ji.bufs[0] and ji.bufs[0].device.split(":", 1)[0] in {"CUDA", "NV", "AMD"}: - ji_graph_dev = Device[ji.bufs[0].device] - - graph_class = (ji_graph_dev.graph.func if isinstance(ji_graph_dev.graph, functools.partial) else ji_graph_dev.graph) if ji_graph_dev else None - can_be_graphed = ji_graph_dev and ji_graph_dev.graph - can_share_graph = (ji_graph_dev == current_device or (isinstance(graph_class, type) and issubclass(graph_class, MultiGraphRunner)) and - type(ji_graph_dev) is type(current_device)) - can_extend_graph_batch = can_be_graphed and (max_batch_size == 0 or len(current_batch) < max_batch_size) and can_share_graph + match ji.prg: + case CompiledRunner(): + ji_graph_dev = ji.prg.dev + # All GraphRunners can graph CompiledRunners + can_be_graphed = ji_graph_dev.graph is not None + case BufferXfer(): + ji_graph_dev = Device[unwrap(ji.bufs[0]).device] + # All *Multi*GraphRunner support graphing BufferXfers + can_be_graphed = ji_graph_dev.graph is not None and issubclass(graph_class(ji_graph_dev), MultiGraphRunner) + case ViewOp(): continue # ViewOps are just ignored + case _: can_be_graphed = False # Everything else is not graphed and flushes existing graph if it's being constructed + + is_multigraph = can_be_graphed and issubclass(graph_class(ji_graph_dev), MultiGraphRunner) + can_share_graph = can_be_graphed and (type(ji_graph_dev) is type(current_device) if is_multigraph else ji_graph_dev == current_device) + can_extend_graph_batch = can_share_graph and (max_batch_size == 0 or len(current_batch) < max_batch_size) if not can_extend_graph_batch and len(current_batch) > 0: flush_batch() - - if can_be_graphed: current_batch.append(ji) - else: graphed_jit_cache.append(ji) - - current_device = ji_graph_dev + (current_batch if can_be_graphed else graphed_jit_cache).append(ji) + current_device = ji_graph_dev if can_be_graphed else None if len(current_batch) > 0: flush_batch() return graphed_jit_cache @@ -71,7 +75,7 @@ class GraphRunner(Runner): def __init__(self, jit_cache: list[ExecItem], input_rawbuffers: list[Buffer], var_vals: dict[Variable, int]): self.jit_cache = jit_cache # NOTE: this is not used, but you have to keep these objects alive for the Graph self.input_replace:dict[tuple[int, int], int] = get_input_replace(jit_cache, input_rawbuffers) - self.var_vals_replace:dict[int, list[int]] = {} + self.var_vals_replace:dict[int, list[tuple[int, int]]] = {} self.launch_dims_replace:dict[int, tuple[Optional[int], Optional[int]]] = {} self.launch_dims_base:dict[int, tuple[tuple[int, ...], tuple[int, ...]]] = {} @@ -86,7 +90,7 @@ class GraphRunner(Runner): for j,ji in enumerate(jit_cache): estimates += ji.prg.estimates if isinstance(ji.prg, CompiledRunner): - if ji.prg.p.vars: self.var_vals_replace[j] = [self.vars.index(v) for v in ji.prg.p.vars] + if ji.prg.p.vars: self.var_vals_replace[j] = [(i, self.vars.index(v)) for i, v in enumerate(ji.prg.p.vars) if v not in ji.fixedvars] global_dim_idx, local_dim_idx = find_symbolic_dim(ji.prg.p.global_size), find_symbolic_dim(ji.prg.p.local_size) if global_dim_idx is not None or local_dim_idx is not None: @@ -103,7 +107,7 @@ class GraphRunner(Runner): def updated_vars(self, var_vals: dict[Variable, int]): vals = [var_vals[v] for v in self.vars] for j, vidxs in self.var_vals_replace.items(): - for i, v in enumerate(vidxs): yield j, i, vals[v] + for i, v in vidxs: yield j, i, vals[v] def updated_launch_dims(self, var_vals: dict[Variable, int]): dims = [tuple(sym_infer(s, var_vals) for s in dim) for dim in self.symbolic_dims] @@ -119,7 +123,9 @@ class GraphRunner(Runner): if id(rawbuf.base._buf) in self.w_dependency_map: wait_nodes.append(self.w_dependency_map[id(rawbuf.base._buf)]) if i in write: if id(rawbuf.base._buf) in self.r_dependency_map: wait_nodes.extend(self.r_dependency_map.pop(id(rawbuf.base._buf))) - self.w_dependency_map[id(rawbuf.base._buf)] = new_dependency + + for i,rawbuf in enumerate(rawbufs): + if i in write: self.w_dependency_map[id(rawbuf.base._buf)] = new_dependency else: self.r_dependency_map[id(rawbuf.base._buf)].append(new_dependency) return list({id(x):x for x in wait_nodes}.values()) @@ -127,6 +133,15 @@ class GraphRunner(Runner): # a marker for your graph supporting multiple devices of the same type class MultiGraphRunner(GraphRunner): pass +def get_out_buffers_for_ei(ei:ExecItem) -> list[Buffer]: + if isinstance(ei.prg, CompiledRunner): return [cast(Buffer, ei.bufs[out]) for out in ei.prg.p.outs if out not in ei.prg.p.ins] + if isinstance(ei.prg, (BufferCopy, BufferXfer)): return [cast(Buffer, ei.bufs[0])] + return [] + +def update_depends(depends:set[Buffer|None], jit_cache:list[ExecItem]): + for ei in jit_cache: + if any(b in depends for b in ei.bufs): depends.update(get_out_buffers_for_ei(ei)) + ReturnType = TypeVar('ReturnType') @dataclass class CapturedJit(Generic[ReturnType]): @@ -138,18 +153,36 @@ class CapturedJit(Generic[ReturnType]): expected_st_vars_dtype_device: list[tuple[ShapeTracker, tuple[Variable, ...], DType, str]] def __reduce__(self): + # TODO: free_intermediates here? replan_buffers_memory_layout here? return self.__class__, (self.ret, self.jit_cache, self.input_replace, self.extra_view_inputs, self.expected_names, self.expected_st_vars_dtype_device) def __post_init__(self): self._jit_cache: list[ExecItem] = self.jit_cache self._input_replace: dict[tuple[int, int], int] = self.input_replace - self._graphed = False + self._first_run = True self._clear_inputs() def _clear_inputs(self): for (j,i) in self._input_replace.keys(): self._jit_cache[j].bufs[i] = None + def free_intermediates(self): + depends: set[Buffer|None] = set([None]) + update_depends(depends, self.jit_cache) + for b in depends: + if b is not None: + if b.is_allocated(): b.deallocate() + if b._base is not None and b._base.allocated_views == 0 and b._base.is_allocated(): b._base.deallocate() + self.__post_init__() # reset the graph state + + def replan_buffers_memory_layout(self): + blacklist = [t.lazydata.buffer for t in get_parameters(self.ret)] + asgn = _internal_memory_planner([[b for item in self.jit_cache for b in item.bufs if b is not None and b not in blacklist]], ignore_checks=True) + self.jit_cache = [ExecItem(item.prg, [asgn.get(b,b) if b is not None else None for b in item.bufs]) for item in self.jit_cache] + for old, new in asgn.items(): + if old.is_allocated(): new.ensure_allocated().copyin(old.as_buffer()) + self.__post_init__() + # jit exec def __call__(self, input_buffers:list[Buffer], var_vals:dict[Variable, int]) -> ReturnType: # assign inputs @@ -158,10 +191,16 @@ class CapturedJit(Generic[ReturnType]): for (j,i),input_idx in self._input_replace.items(): self._jit_cache[j].bufs[i] = input_buffers[input_idx] # Condense the items into a graph executor. - if JIT < 2 and not self._graphed: - self._jit_cache = apply_graph_to_jit(self.jit_cache, input_buffers, var_vals, max_batch_size=getenv("JIT_BATCH_SIZE", 32)) - self._input_replace = get_input_replace(self._jit_cache, input_buffers) - self._graphed = True + if self._first_run: + # allocate intermediates if freed + for ji in self.jit_cache: + for b in ji.bufs: + if b is not None: b.ensure_allocated() + # create graph if needed + if JIT < 2: + self._jit_cache = apply_graph_to_jit(self.jit_cache, input_buffers, var_vals, max_batch_size=getenv("JIT_BATCH_SIZE", 32)) + self._input_replace = get_input_replace(self._jit_cache, input_buffers) + self._first_run = False if DEBUG >= 1 and len(self._jit_cache) >= 10: print(f"jit execs {len(self._jit_cache)} kernels") for ei in self._jit_cache: ei.run(var_vals, jit=True) @@ -171,9 +210,11 @@ class CapturedJit(Generic[ReturnType]): def _prepare_jit_inputs(args, kwargs): input_tensors: list[tuple[int|str, Tensor]] = [(name,t) for name,t in list(enumerate(args))+sorted(kwargs.items()) if t.__class__ is Tensor] names, tensors = [name for name,_ in input_tensors], [t for _,t in input_tensors] - if tensors: Tensor.realize(*tensors) - lbs: list[UOp] = flatten([t.lazydata.lbs for t in tensors]) - input_buffers: list[Buffer] = [lb.base.realized for lb in lbs if lb.base.realized is not None] + if len(unrealized_tensors := [x for x in tensors if not x.lazydata.is_realized]): Tensor.realize(*unrealized_tensors) + # TODO: this multi unpack stuff is not well tested. + lbs: list[UOp] = flatten([t.lazydata.src if t.lazydata.op is Ops.MULTI else [t.lazydata] for t in tensors]) + input_buffers: list[Buffer] = flatten([rb.bufs if isinstance(rb:=lb.base.realized, MultiBuffer) else [rb] + for lb in lbs if lb.base.realized is not None]) assert len(set(input_buffers)) == len(input_buffers), "duplicate inputs to JIT" st_varval_dtype_device = [(*unwrap(lb.st).unbind(), lb.dtype, lb.device) for lb in lbs] var_vals = merge_dicts([x[1] for x in st_varval_dtype_device] + [dict(v.unbind() for v in (args + tuple(kwargs.values())) if isinstance(v, UOp))]) @@ -181,12 +222,13 @@ def _prepare_jit_inputs(args, kwargs): return input_buffers, var_vals, names, st_vars_dtype_device class TinyJit(Generic[ReturnType]): - def __init__(self, fxn:Optional[Callable[..., ReturnType]], captured:Optional[CapturedJit]=None, prune=False): + def __init__(self, fxn:Optional[Callable[..., ReturnType]], captured:Optional[CapturedJit]=None, prune=False, optimize=False): assert fxn or captured, "need either a function or a CapturedJit" self.fxn = fxn self.captured: Optional[CapturedJit] = captured self.cnt: int = 2 if self.fxn is None else 0 self.prune = prune + self.optimize = optimize def add_buffer(self, b:Buffer) -> Buffer: if found:=self._buffer_replace.get(b, None): return found @@ -198,7 +240,7 @@ class TinyJit(Generic[ReturnType]): return ret def add(self, ei:ExecItem): - self._jit_cache.append(ExecItem(ei.prg, [self.add_buffer(buf) for buf in ei.bufs if buf is not None])) + self._jit_cache.append(ExecItem(ei.prg, [self.add_buffer(buf) for buf in ei.bufs if buf is not None], ei.metadata, ei.fixedvars)) def reset(self): assert self.fxn is not None, "can't reset without function" @@ -256,14 +298,8 @@ class TinyJit(Generic[ReturnType]): # prune independent kernels (optional) if self.prune: depends = set(input_buffers) - for ei in jit_cache: - if any(b in depends for b in ei.bufs): - if isinstance(ei.prg, CompiledRunner): - depends.update(cast(Buffer, ei.bufs[out]) for out in ei.prg.p.outs) - if isinstance(ei.prg, (BufferCopy, BufferXfer)): - depends.add(cast(Buffer, ei.bufs[0])) - pruned, onetime = partition(jit_cache, - lambda ei: not isinstance(ei.prg, CompiledRunner) or any(ei.bufs[out] in depends for out in ei.prg.p.outs)) + update_depends(depends, jit_cache) + pruned, onetime = partition(jit_cache, lambda ei: any(b in depends for b in get_out_buffers_for_ei(ei))) if DEBUG >= 1: print(f"pruned from {len(jit_cache)} -> {len(pruned)} kernels") # run the onetime kernels here for ei in onetime: @@ -275,13 +311,15 @@ class TinyJit(Generic[ReturnType]): # Exclude buffers involved in transfer ops to preserve parallelism. noopt_buffers = {b for ji in jit_cache if isinstance(ji.prg, BufferXfer) for b in ji.bufs} assigned = _internal_memory_planner([cast(list[Buffer], item.bufs) for item in jit_cache], noopt_buffers, debug_prefix="JIT ") - jit_cache = [ExecItem(item.prg, [assigned.get(b,b).ensure_allocated() for b in item.bufs if b is not None]) for item in jit_cache] + jit_cache = [ExecItem(item.prg, [assigned.get(b,b).ensure_allocated() for b in item.bufs if b is not None], + item.metadata, item.fixedvars) for item in jit_cache] input_replace = get_input_replace(jit_cache, input_buffers) if DEBUG >= 1 and len(set(input_replace.values())) != len(input_buffers): print("WARNING: some input tensors not found") # set this for next run self.captured = CapturedJit(ret, jit_cache, input_replace, extra_view_inputs, names, st_vars_dtype_device) + if self.optimize: self.captured.replan_buffers_memory_layout() elif self.cnt >= 2: # jit exec assert self.captured is not None diff --git a/tinygrad_repo/tinygrad/engine/memory.py b/tinygrad_repo/tinygrad/engine/memory.py index 99439c54b9..e925972d1d 100644 --- a/tinygrad_repo/tinygrad/engine/memory.py +++ b/tinygrad_repo/tinygrad/engine/memory.py @@ -1,50 +1,69 @@ +from typing import cast from collections import defaultdict from tinygrad.engine.schedule import ScheduleItem from tinygrad.device import Device, Buffer -from tinygrad.helpers import NO_MEMORY_PLANNER, dedup, DEBUG -from tinygrad.ops import Ops +from tinygrad.helpers import NO_MEMORY_PLANNER, dedup, DEBUG, round_up +from tinygrad.uop.ops import Ops +from tinygrad.dtype import dtypes, ImageDType +from tinygrad.runtime.support.allocator import TLSFAllocator # **************** memory planning **************** -def _internal_memory_planner(buffers:list[list[Buffer]|tuple[Buffer, ...]], noopt_buffers=None, debug_prefix="") -> dict[Buffer, Buffer]: +def _internal_memory_planner(buffers:list[list[Buffer]], noopt_buffers=None, ignore_checks=False, debug_prefix="") -> dict[Buffer, Buffer]: if NO_MEMORY_PLANNER: return {} - first_appearance, last_appearance = {}, {} + first_appearance, last_appearance, buf_to_opt = {}, {}, set() for i,u in enumerate(buffers): for buf in u: - if buf.is_allocated() or buf.lb_refcount > 0 or (noopt_buffers is not None and buf.base in noopt_buffers): continue + should_skip = buf.is_allocated() or buf.base.is_allocated() or buf.lb_refcount > 0 or (noopt_buffers is not None and buf.base in noopt_buffers) + if not ignore_checks and should_skip: continue if buf.base not in first_appearance: first_appearance[buf.base] = i last_appearance[buf.base] = i + buf_to_opt.add(buf) - # Sort buffers by size in descending order, prioritizing largest buffers for allocation first. - # Track free segments, each containing (start, stop, and buffer that could be reused on this segment). - free_segs: dict[tuple, list[tuple[int, int, Buffer]]] = defaultdict(list) # dict[buffer key, tuple[start, end, buffer to reuse on the seg]] - def find_replace_buffer(buf, st, en): - key = (buf.device, buf.dtype, buf.options) + ((buf.nbytes,) if not hasattr(Device[buf.device].allocator, "offset") else tuple()) + # Sort buffer operations in timeline order. Two events: buffer is allocated or buffer is freed. + buffer_requests = sorted([((first_appearance[buf], True), buf) for buf in first_appearance.keys()] + \ + [((last_appearance[buf] + 1, False), buf) for buf in first_appearance.keys()], key=lambda x: x[0]) - default_buf = (0, len(buffers) - 1, buf) # will return the buffer itself if the replace one is not found. - seg_st, seg_en, seg_buf = next((free_segs[key].pop(i) for i,(sst,sen,_) in enumerate(free_segs[key]) if sst <= st and en <= sen), default_buf) + # Try to suballocate from a shared buffer managed by global_planner using TLSFAllocator. + # Also track buffer replacements for buffers that do not support suballocation. + buffer_replace:dict[Buffer, tuple[Buffer|None, int|None]] = {} + reuse_buffers:dict[tuple, list[Buffer]] = defaultdict(list) + global_planner:dict[str, tuple[int, TLSFAllocator]] = defaultdict(lambda: (0, TLSFAllocator(1 << 44, block_size=0x1000, lv2_cnt=32))) + for (_, is_open_ev), buf in buffer_requests: + # Check if suballocation is possible for the given buffer and device. + if hasattr(Device[buf.device].allocator, "_offset") and not isinstance(buf.dtype, ImageDType): + if is_open_ev: buffer_replace[buf] = (None, global_planner[buf.device][1].alloc(round_up(buf.nbytes, 0x1000))) + else: global_planner[buf.device][1].free(cast(int, buffer_replace[buf][1])) + global_planner[buf.device] = (max(global_planner[buf.device][0], buffer_replace[buf][1] + buf.nbytes), global_planner[buf.device][1]) + else: + key = (buf.device, buf.dtype, buf.options, buf.nbytes) + if is_open_ev: buffer_replace[buf] = (reuse_buffers[key].pop(), None) if key in reuse_buffers and len(reuse_buffers[key]) > 0 else (buf, None) + else: reuse_buffers[key].append(cast(Buffer, buffer_replace[buf][0])) - free_segs[key] += [(seg_st, st - 1, seg_buf)] if st - 1 >= seg_st else [] - free_segs[key] += [(en + 1, seg_en, seg_buf)] if seg_en >= en + 1 else [] + # Allocate global buffers based on the memory planner. + global_buffers = {dev: Buffer(dev, round_up(sz, 0x1000), dtypes.int8) for dev, (sz, _) in global_planner.items()} + buffer_resolve:dict[Buffer, tuple[Buffer, int|None]] = {buf: (base or global_buffers[buf.device], off) for buf,(base,off) in buffer_replace.items()} - return seg_buf if seg_buf.nbytes == buf.nbytes else Buffer(buf.device, buf.size, buf.dtype, base=seg_buf) + # Assign buffers. First, assign full buffers (not sub-buffers). + assigned:dict[Buffer, Buffer] = {} + for buf, (base, off) in buffer_resolve.items(): + if buf != base: + assigned[buf] = base if off is None else Buffer(buf.device, buf.size, buf.dtype, base=base, offset=off) - buffer_requests = sorted([(first_appearance[buf], last_appearance[buf], buf) for buf in first_appearance.keys()], key=lambda x: -x[2].nbytes) - assigned = {buf:find_replace_buffer(buf, st, en) for st, en, buf in buffer_requests} + # Now assign sub-buffers. + for buf in buf_to_opt: + if buf._base is not None: + assigned[buf] = Buffer(buf.device, buf.size, buf.dtype, base=(pbuf:=assigned.get(buf.base, buf.base)).base, offset=pbuf.offset+buf.offset) - for i,u in enumerate(buffers): - for buf in u: - if buf.is_allocated() or buf.lb_refcount > 0 or (noopt_buffers is not None and buf.base in noopt_buffers): continue - if buf._base is not None: assigned[buf] = Buffer(buf.device, buf.size, buf.dtype, base=assigned.get(buf.base, buf.base).base, offset=buf.offset) - else: assigned[buf] = assigned.get(buf, buf) + if DEBUG >= 1: + ak, av = dedup(x for x in assigned.keys() if x._base is None),dedup(x for x in assigned.values() if x._base is None)+list(global_buffers.values()) + omem, nmem = sum([x.nbytes for x in ak])/1e6, sum([x.nbytes for x in av])/1e6 + if omem != nmem: print(f"{debug_prefix}memory reduced from {omem:.2f} MB -> {nmem:.2f} MB,", f"{len(ak)} -> {len(av)} bufs") - if DEBUG >= 1 and len(ak:=dedup(x for x in assigned.keys() if x._base is None)) != len(av:=dedup(x for x in assigned.values() if x._base is None)): - print(debug_prefix+f"memory reduced from {sum([x.nbytes for x in ak])/1e6:.2f} MB -> {sum([x.nbytes for x in av])/1e6:.2f} MB,", - f"{len(ak)} -> {len(av)} bufs") return assigned def memory_planner(schedule:list[ScheduleItem]) -> list[ScheduleItem]: # Exclude buffers involved in load ops (e.g transfers) to preserve parallelism in graphs. - assigned = _internal_memory_planner([si.bufs for si in schedule], + assigned = _internal_memory_planner([list(si.bufs) for si in schedule], noopt_buffers={b for si in schedule if si.ast.op is not Ops.SINK for b in si.bufs}) - return [ScheduleItem(si.ast, tuple(assigned.get(x, x) for x in si.bufs), si.metadata, si.assign_preloads) for si in schedule] + return [ScheduleItem(si.ast, tuple(assigned.get(x, x) for x in si.bufs), si.metadata, si.fixedvars) for si in schedule] diff --git a/tinygrad_repo/tinygrad/engine/multi.py b/tinygrad_repo/tinygrad/engine/multi.py new file mode 100644 index 0000000000..fb3f2e3e4d --- /dev/null +++ b/tinygrad_repo/tinygrad/engine/multi.py @@ -0,0 +1,145 @@ +import functools, itertools, operator +from tinygrad.helpers import all_same, all_int, prod, DEBUG, RING, getenv +from tinygrad.uop.ops import Ops, UOp, sint, PatternMatcher, UPat, GroupOp + +# *** allreduce implementation *** + +def handle_allreduce(buf:UOp, red:UOp) -> UOp|None: + if not isinstance(buf.device, tuple): return None + assert all_int(buf.shape), f"does not support symbolic shape {buf.shape}" + n_lbs, shape, numel = len(buf.device), buf.shape, prod(buf.shape) + # ring allreduce doesn't provide a benefit with only 2 nodes or where number of elements is less than 256k (empirically) + # fallback to naive allreduce to save on kernel dispatch, chunking and reassembling chunks. + use_ring = (RING >= 2 or (n_lbs > 2 and numel > getenv("RING_ALLREDUCE_THRESHOLD", 256_000) and RING >= 1)) + if DEBUG >= 2: print(f"{'RING ALLREDUCE' if use_ring else 'NAIVE ALLREDUCE'} {n_lbs}x{numel} | {buf.dtype}") + + # contiguous before we copy it + buf = buf.contiguous() + + # copy to all devices. if you shrink later, that'll be handled + if not use_ring: return functools.reduce(lambda x,y: x.alu(red.arg, y), + [UOp(Ops.COPY, buf.dtype, (buf, red.src[1]), arg=i) for i in range(len(buf.device))]) + + # new ring reduce + factor = next((f for f in [32, 16, 8, 4, 2] if numel % f == 0), 1) + base, left = (numel // factor) // n_lbs, (numel // factor) % n_lbs + chunk_sizes = [(base + 1) * factor] * left + [base * factor] * (n_lbs - left) + chunks = list(itertools.pairwise(itertools.accumulate(chunk_sizes, initial=0))) + + # extract chunks and scatter-reduce + reduced_chunks = [] + for i,(s,e) in enumerate(chunks): + chunk = buf.reshape((numel,)).shrink(((s,e),)) + reduced_chunk = chunk + for step in range(n_lbs-1): + src, dest = (i+step)%n_lbs, (i+step+1)%n_lbs + # copy the chunk from the src device to the dest (operating device), and select the chunk on the dest device + reduced_chunk = reduced_chunk.copy_to_device(buf.device[dest], src).alu(red.arg, chunk.copy_to_device(buf.device[dest], dest)) + reduced_chunks.append(reduced_chunk) + + # allgather + reassemble + pads = [((s,numel-e),) for s,e in chunks] + return functools.reduce(operator.add, [c.copy_to_device(buf.device).pad(pad) for pad,c in zip(pads, reduced_chunks)]).reshape(shape) + +replace_allreduce = PatternMatcher([(UPat(Ops.ALLREDUCE, src=(UPat.var("buf"), UPat()), name="red"), handle_allreduce),]) + +# ***** multi functions ***** + +def alu_multi(root:UOp): + msrcs = root.src + assert all_same([x.device for x in msrcs]), f"all buffers must have the same device {[x.device for x in msrcs]}" + axis = root.axis + assert axis is not None + + srcs = [] + for mlb in msrcs: + if mlb.axis == axis: + # same axis, just copy through + assert mlb.op is Ops.MULTI + srcs.append(mlb.src[0]) + elif mlb.axis is None: + # no axis, shard it + assert mlb.op is not Ops.MULTI + srcs.append(mlb._shard(axis)) + else: + # axis mismatch, unshard it, send it to all devices, and shard it correctly + assert mlb.op is Ops.MULTI + srcs.append(mlb.src[0]._unshard(mlb.axis).allreduce(Ops.ADD, mlb.device)._shard(axis)) + return srcs[0].alu(root.op, *srcs[1:]).multi(axis) + +def reduce_multi(root:UOp, multi:UOp): + op, axis = root.arg + if multi.axis is not None and multi.axis in axis: + # all-reduce on sharded axes + return multi.src[0].r(op, axis).allreduce(op, multi.device) + # reduce on non sharded axes, piecewise is fine. if axis is None this is also correct + return multi.src[0].r(op, axis).multi(axis=multi.axis) + +def _shape_to_single_shard(axis, shape:tuple[sint, ...], lb:UOp) -> tuple[sint, ...]: + return tuple(lb.shape[axis] if a == axis else s for a,s in enumerate(shape)) + +def reshape_multi(root:UOp, multi:UOp): + arg = root.arg + if (new_axis:=root.axis) is None: return multi.src[0].reshape(arg).multi(new_axis) + assert prod(multi.shape) == prod(arg), "reshape must maintain prod(shape)" + assert prod(multi.src[0].shape[multi.axis:])%prod(arg[new_axis+1:]) == 0, f"reshape cannot move items between shards {multi.shape} -> {root.arg=}" + new_shape_axis = prod(multi.src[0].shape[multi.axis:]) // prod(arg[new_axis+1:]) + return multi.src[0].reshape(tuple(s if a!=new_axis else new_shape_axis for a,s in enumerate(arg))).multi(new_axis) + +def expand_multi(root:UOp, multi:UOp): + # NOTE: this assert isn't needed, sharded axis can have dim 1 + assert multi.axis is None or root.arg[multi.axis] == multi.shape[multi.axis], f"expand not supported on sharded axis {root.arg=}" + return multi.src[0].expand(_shape_to_single_shard(multi.axis, root.arg, multi.src[0])).multi(multi.axis) + +def pad_multi(root:UOp, multi:UOp): + assert multi.axis is None or root.arg[multi.axis] == (0,0), f"padding not supported for {root.arg=}" + return multi.src[0].pad(root.arg).multi(multi.axis) + +def permute_multi(root:UOp, multi:UOp): + # all permutes supported! + return multi.src[0].permute(root.arg).multi(root.axis) + +def shrink_multi(root:UOp, multi:UOp): + assert multi.axis is None or root.arg[multi.axis] == (0, multi.shape[multi.axis]) or root.arg[multi.axis] in multi.bounds, \ + f"shrinking not supported for {root.arg=}" + if multi.axis is not None and root.arg[multi.axis] in multi.bounds and root.arg[multi.axis] != (0, multi.shape[multi.axis]): + assert all(root.arg[i] == (0, s) or i == multi.axis for i,s in enumerate(multi.shape)), \ + "cannot shrink sharded and non-sharded axis at the same time" + # NOTE: shrink on the shard axis is only allowed when result is a single partition, denoted by the new real + # we just copy it to all the devices, no real. this will be optimized out later + return multi.src[0].copy_to_device(multi.device, arg=multi.bounds.index(root.arg[multi.axis])) + return multi.src[0].shrink(tuple((0, multi.src[0].shape[multi.axis]) if a == multi.axis else s for a,s in enumerate(root.arg))).multi(multi.axis) + +def flip_multi(root:UOp, multi:UOp): + assert multi.axis is None or not root.arg[multi.axis], "flipping not supported on sharded axis" + return multi.src[0].flip(root.arg).multi(multi.axis) + +# from multiple devices -> one +def copy_multi(multi:UOp, device:UOp): + assert multi.axis is not None, "all multi ops have axis" + return multi.src[0]._unshard(multi.axis).allreduce(Ops.ADD, device) + +def assign_multi(dest:UOp, src:UOp): + if dest.axis != src.axis: raise RuntimeError(f"axis must match in assign {dest.axis} != {src.axis}") + return dest.src[0].assign(src.src[0]).multi(src.axis) + +def passthrough_multi(root:UOp, multi:UOp): + return root.replace(src=(multi.src[0],)).multi(multi.axis) + +# NOTE: this is the same pattern as Ops.UNROLL +multi_pm = PatternMatcher([ + (UPat(GroupOp.ALU, name="root", custom_early_reject=set([Ops.MULTI])), alu_multi), + (UPat(Ops.REDUCE_AXIS, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), reduce_multi), + (UPat(Ops.RESHAPE, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), reshape_multi), + (UPat(Ops.EXPAND, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), expand_multi), + (UPat(Ops.PAD, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), pad_multi), + (UPat(Ops.PERMUTE, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), permute_multi), + (UPat(Ops.SHRINK, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), shrink_multi), + (UPat(Ops.FLIP, src=(UPat(Ops.MULTI, name="multi"), ), name="root"), flip_multi), + (UPat(Ops.ASSIGN, src=(UPat(Ops.MULTI, name="dest"), UPat(Ops.MULTI, name="src"))), assign_multi), + (UPat(Ops.COPY, src=(UPat(Ops.MULTI, name="multi"), UPat(Ops.DEVICE, name="device"))), copy_multi), + (UPat(Ops.ALLREDUCE, src=(UPat(Ops.MULTI, name="multi"), UPat(Ops.DEVICE, name="device")), name="red"), + lambda multi,device,red: multi.src[0].allreduce(red.arg, device).multi(axis=multi.axis)), + (UPat((Ops.CAST, Ops.BITCAST, Ops.CONTIGUOUS, Ops.DETACH, Ops.CONTIGUOUS_BACKWARD, Ops.FUSE), + src=(UPat(Ops.MULTI, name="multi"), ), name="root"), passthrough_multi), +]) diff --git a/tinygrad_repo/tinygrad/engine/realize.py b/tinygrad_repo/tinygrad/engine/realize.py index 1dd7e62349..fc4352d11e 100644 --- a/tinygrad_repo/tinygrad/engine/realize.py +++ b/tinygrad_repo/tinygrad/engine/realize.py @@ -1,28 +1,28 @@ -from typing import List, Optional, cast, Generator +from typing import Optional, cast, Generator import time, pprint -from dataclasses import dataclass, replace -from tinygrad.helpers import colored, getenv, DEBUG, GlobalCounters, ansilen, BEAM, NOOPT, all_int, CAPTURING, Metadata, TRACEMETA -from tinygrad.ops import Ops, UOp, Variable, sym_infer +from dataclasses import dataclass, replace, field +from tinygrad.helpers import all_same, colored, getenv, DEBUG, GlobalCounters, ansilen, BEAM, NOOPT, all_int, CAPTURING, Metadata, TRACEMETA +from tinygrad.helpers import DEVECTORIZE, time_to_str, VALIDATE_WITH_CPU +from tinygrad.uop.ops import Ops, PatternMatcher, UOp, UPat, Variable, sym_infer from tinygrad.device import Device, Buffer from tinygrad.renderer import Renderer, ProgramSpec, Estimates from tinygrad.codegen.kernel import Kernel +from tinygrad.codegen.heuristic import hand_coded_optimizations from tinygrad.engine.schedule import ScheduleItem # **************** Program Creation **************** logkerns, logkerns_level = open(getenv("LOGKERNS", ""), "a") if getenv("LOGKERNS", "") else None, getenv("LOGKERNS_LEVEL", 1) def get_kernel(renderer:Renderer, ast:UOp) -> Kernel: - if DEBUG >= 5: print(ast) - k = Kernel(ast, opts=renderer).required_optimizations() + k = Kernel(ast, opts=renderer) if not NOOPT: - if not k.apply_tensor_cores(getenv("TC", 1)): k.hand_coded_optimizations() + if not k.apply_tensor_cores(getenv("TC", 1)): k.apply_opts(hand_coded_optimizations(k)) if BEAM >= 1: from tinygrad.engine.search import beam_search, bufs_from_lin - kb = Kernel(ast, opts=renderer).required_optimizations() + kb = Kernel(ast, opts=renderer) rawbufs = bufs_from_lin(kb, allocate=False) k = beam_search(kb, rawbufs, BEAM.value, bool(getenv("BEAM_ESTIMATE", 1))) if logkerns is not None: logkerns.writelines([f"{(k.ast, k.applied_opts)}\n"]) - if DEBUG >= 5: print((k.ast, k.applied_opts)) # print here to show final applied_opts for all kernels instead of just in beam_search return k # **************** Runners **************** @@ -38,12 +38,12 @@ class Runner: raise NotImplementedError("override this") class CompiledRunner(Runner): - def __init__(self, p:ProgramSpec, precompiled:Optional[bytes]=None): + def __init__(self, p:ProgramSpec, precompiled:Optional[bytes]=None, prg=None): if DEBUG >= 4: print(p.src) self.p:ProgramSpec = p self.lib:bytes = precompiled if precompiled is not None else Device[p.device].compiler.compile_cached(p.src) - if DEBUG >= 6: Device[p.device].compiler.disassemble(self.lib) - self._prg = Device[p.device].runtime(p.function_name, self.lib) + if DEBUG >= 7: Device[p.device].compiler.disassemble(self.lib) + self._prg = Device[p.device].runtime(p.function_name, self.lib) if prg is None else prg super().__init__(p.name, p.device, p.estimates) def __reduce__(self): return self.__class__, (self.p, self.lib) @@ -65,10 +65,6 @@ class CompiledRunner(Runner): assert len(local_size) == 3, "local size must have len 3" return self._prg(*[x._buf for x in rawbufs], **lra, vals=tuple(var_vals[k] for k in self.p.vars), wait=wait) -class EmptyOp(Runner): - def __init__(self, buf:Buffer): super().__init__(colored(f"empty {buf.size:10d} {buf.dtype}", "yellow"), buf.device) - def __call__(self, rawbufs:list[Buffer], var_vals:dict[Variable, int], wait=False): pass - class ViewOp(Runner): def __init__(self, buf:Buffer): super().__init__(colored(f"view {buf.nbytes:8d} @ {buf.offset:<10d}", "yellow"), buf.device) def __call__(self, rawbufs:list[Buffer], var_vals:dict[Variable, int], wait=False): @@ -103,11 +99,13 @@ class BufferXfer(BufferCopy): # **************** method cache **************** -method_cache: dict[tuple[str, bytes, int, int, bool], CompiledRunner] = {} +method_cache: dict[tuple[str, bytes, tuple[int, ...], bool], CompiledRunner] = {} def get_runner(device:str, ast:UOp) -> CompiledRunner: - ckey = (device, ast.key, BEAM.value, NOOPT.value, False) + # TODO: this should be all context relevant to rendering + context = (BEAM.value, NOOPT.value, DEVECTORIZE.value) + ckey = (device, ast.key, context, False) if cret:=method_cache.get(ckey): return cret - bkey = (device.split(":")[0], ast.key, BEAM.value, NOOPT.value, True) + bkey = (device.split(":")[0], ast.key, context, True) if bret:=method_cache.get(bkey): method_cache[ckey] = ret = CompiledRunner(replace(bret.p, device=device), bret.lib) else: @@ -122,8 +120,9 @@ class ExecItem: prg: Runner bufs: list[Optional[Buffer]] metadata: Optional[tuple[Metadata, ...]] = None + fixedvars: dict[Variable, int] = field(default_factory=dict) def run(self, _var_vals:Optional[dict[Variable, int]]=None, wait=False, jit=False, do_update_stats=True) -> Optional[float]: - var_vals = {} if _var_vals is None else _var_vals + var_vals = self.fixedvars if _var_vals is None else (_var_vals|self.fixedvars) bufs = [cast(Buffer, x) for x in self.bufs] if jit else [cast(Buffer, x).ensure_allocated() for x in self.bufs] et = self.prg(bufs, var_vals, wait=wait or DEBUG >= 2) if do_update_stats: @@ -134,32 +133,28 @@ class ExecItem: if DEBUG >= 2: lds_est = sym_infer(self.prg.estimates.lds, var_vals) mem_est = min(mem_est, lds_est) # there can't be more memory accessed than loads/stores. remove this when symbolic is fixed - ptm = (colored(f"{et*1e3:9.2f}ms", "yellow") if et > 0.01 else f"{et*1e6:9.2f}us") if et is not None else "" + ptm = colored(time_to_str(et, w=9), "yellow" if et > 0.01 else None) if et is not None else "" print(f"{colored(f'*** {self.prg.device[:7]:7s} {GlobalCounters.kernel_count:4d}', 'magenta' if jit else ('green' if self.prg.first_run else None))} {self.prg.display_name+' '*(41-ansilen(self.prg.display_name))} arg {len(bufs):2d} mem {GlobalCounters.mem_used/1e9:5.2f} GB " + # noqa: E501 (str() if et is None else f"tm {ptm}/{GlobalCounters.time_sum_s*1e3:9.2f}ms ({op_est/((et or 1e-20)*1e9):9.2f} GFLOPS {mem_est/((et or 1e-20)*1e9):6.1f}|{lds_est/((et or 1e-20)*1e9):<7.1f} GB/s)" + # noqa: E501 f" {[repr(m) if TRACEMETA >= 2 else str(m) for m in self.metadata] if self.metadata else ''}")) self.prg.first_run = False return et +# NOTE: ctx is the buffers +si_lowerer = PatternMatcher([ + (UPat(Ops.SINK, name="sink"), lambda ctx,sink: (runner:=get_runner(ctx[0].device, sink), [ctx[x] for x in runner.p.globals])), + (UPat(Ops.BUFFER_VIEW), lambda ctx: (ViewOp(ctx[0]), list(ctx))), + (UPat(Ops.COPY, name="copy"), lambda ctx,copy: ((BufferXfer(ctx[0].nbytes, ctx[0].device, ctx[1].device) \ + if hasattr(Device[ctx[0].device].allocator, '_transfer') and all_same([x.device.split(":")[0] for x in ctx]) \ + else BufferCopy(ctx[0].nbytes, ctx[0].device, ctx[1].device)), list(ctx))), +]) def lower_schedule_item(si:ScheduleItem) -> ExecItem: - assert len(set(x.device for x in si.bufs)) == 1 or si.ast.op is Ops.COPY - if si.ast.op is Ops.SINK: - runner = get_runner(si.outputs[0].device, si.ast) - return ExecItem(runner, [si.bufs[x] for x in runner.p.globals], si.metadata) - out = si.outputs[0] - if si.ast.op is Ops.COPY: - kernel_type = BufferCopy - if hasattr(Device[out.device].allocator, '_transfer') and out.device.split(":")[0] == si.inputs[0].device.split(":")[0]: - kernel_type = BufferXfer - return ExecItem(kernel_type(out.nbytes, out.device, si.inputs[0].device), list(si.bufs)) - if si.ast.op is Ops.EMPTY: return ExecItem(EmptyOp(out), list(si.bufs)) - if si.ast.op is Ops.BUFFER_VIEW: return ExecItem(ViewOp(out), list(si.bufs)) - raise RuntimeError(f"don't know how to lower {si.ast}") - -def lower_schedule(schedule:list[ScheduleItem]) -> Generator[ExecItem, None, None]: + return ExecItem(*cast(tuple[Runner,list], si_lowerer.rewrite(si.ast, si.bufs)), si.metadata, si.fixedvars) + +def lower_schedule(schedule:list[ScheduleItem]) -> Generator[tuple[ScheduleItem, ExecItem], None, None]: while len(schedule): si = schedule.pop(0) - try: yield lower_schedule_item(si) + try: yield (si, lower_schedule_item(si)) except Exception as e: if DEBUG >= 2: print(f"error lowering {si.ast.op}") @@ -169,9 +164,24 @@ def lower_schedule(schedule:list[ScheduleItem]) -> Generator[ExecItem, None, Non # **************** main run function **************** -capturing: List = [] # put classes with an add method in here +capturing: list = [] # put classes with an add method in here def run_schedule(schedule:list[ScheduleItem], var_vals:Optional[dict[Variable, int]]=None, do_update_stats=True): - for ei in lower_schedule(schedule): + for si, ei in lower_schedule(schedule): if len(capturing) and CAPTURING: capturing[0].add(ei) - ei.run(var_vals, do_update_stats=do_update_stats) + if VALIDATE_WITH_CPU and si.ast.op is Ops.SINK: + # copy in allocated buffers from the GPU + nb: tuple[Buffer, ...] = tuple(Buffer("CPU", b.size, b.dtype) for b in si.bufs) + for cpu_b, gpu_b in zip(nb, si.bufs): + if gpu_b.is_allocated(): cpu_b.ensure_allocated().copyin(gpu_b.as_buffer()) + + # run on GPU + ei.run(var_vals, do_update_stats=do_update_stats) + + # validate the output buffers match (NOTE: this is assuming the output is buffer 0) + lower_schedule_item(ScheduleItem(si.ast, nb, si.metadata, si.fixedvars)).run(var_vals, do_update_stats=do_update_stats) + import numpy as np + np.testing.assert_allclose(si.bufs[0].numpy(), nb[0].numpy(), rtol=1e-3, atol=1e-3) + else: + ei.run(var_vals, do_update_stats=do_update_stats) + diff --git a/tinygrad_repo/tinygrad/engine/schedule.py b/tinygrad_repo/tinygrad/engine/schedule.py index 7951d7129e..829d56266a 100644 --- a/tinygrad_repo/tinygrad/engine/schedule.py +++ b/tinygrad_repo/tinygrad/engine/schedule.py @@ -1,19 +1,9 @@ -import sys, atexit, functools, pickle -from collections import defaultdict, deque +from typing import cast from dataclasses import dataclass, field -from tinygrad.ops import GroupOp, UOp, Ops, PatternMatcher, UPat, Variable, can_pad, graph_rewrite, resolve, track_rewrites, view_left, merge_views -from tinygrad.ops import identity_element, buffers, exec_alu -from tinygrad.helpers import Context, Metadata, all_int, all_same, colored, diskcache_put, merge_dicts, prod, dedup, getenv, unwrap -from tinygrad.helpers import FUSE_CONV_BW, FUSE_ARANGE, DEBUG, ContextVar -from tinygrad.dtype import ConstType, ImageDType, dtypes -from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.shape.view import View, strides_for_shape -from tinygrad.device import Buffer - -# creation can recurse a lot -sys.setrecursionlimit(10000) - -BUF_LIMIT = {"METAL":32} +from collections import deque, defaultdict +from tinygrad.uop.ops import UOp, Variable, Ops, UPat, PatternMatcher, graph_rewrite, buffers +from tinygrad.device import Buffer, MultiBuffer +from tinygrad.helpers import Metadata, unwrap, merge_dicts # **** ScheduleItem return type @@ -21,530 +11,87 @@ BUF_LIMIT = {"METAL":32} class ScheduleItem: ast: UOp bufs: tuple[Buffer, ...] - metadata: tuple[Metadata, ...] - assign_preloads: tuple[UOp, ...] - @property - def outputs(self) -> tuple[Buffer, ...]: - """Read/write or write only buffers in the schedule.""" - return tuple(b for i,b in enumerate(self.bufs) if i in self.output_idxs) - @property - def inputs(self) -> tuple[Buffer, ...]: - """Read only buffers in the schedule.""" - return tuple(b for i,b in enumerate(self.bufs) if i not in self.output_idxs) - @functools.cached_property - def output_idxs(self) -> tuple[int, ...]: return tuple(x.src[0].arg for x in self.ast.src) if self.ast.op is Ops.SINK else (0,) - -# **** Schedule context and big graph - -@dataclass(frozen=True) -class ScheduleContext: - tensor_uops: dict[UOp, list[UOp]] = field(default_factory=dict) # this maps BUFFER uops of this schedule to the tensor uop - var_vals: dict[Variable, int] = field(default_factory=dict) # this maps a BIND's DEFINE_VAR to its value - assigns: set[UOp] = field(default_factory=set) # this holds all the BUFFER uops we ASSIGN to in this schedule - realizes: dict[UOp, UOp] = field(default_factory=dict) # this holds all the BUFFER uops we mutate in this schedule - allbufs: dict[UOp, UOp] = field(default_factory=dict) # this maps BUFFER uops the actual op - ops_metadata: dict[UOp, Metadata] = field(default_factory=dict) # this maps fused ops to Metadata - contiguous: dict[UOp, UOp] = field(default_factory=dict) # this maps roots to places they are made contiguous - children: defaultdict[UOp, dict[UOp, None]] = field(default_factory=lambda: defaultdict(dict)) - -def to_uop(buf:UOp, ctx:ScheduleContext, cache:dict[UOp, UOp]) -> UOp: - if (r:=cache.get(buf)) is not None: return r - # shapeless op is passthrough - # realized is passthrough - if buf.st is None or buf.base.is_realized: return buf - # view is passthrough - if buf is not buf.base: - cache[buf] = ret = to_uop(buf.base, ctx, cache).view(buf.st) - return ret - # make things that can't be images not images - dtype = buf.dtype - if isinstance(dtype, ImageDType) and (prod(buf.shape) != prod(dtype.shape) or not any(buf.shape[x]%4 == 0 for x in buf.st.unit_stride_axes())): - if DEBUG >= 2: print(f"forcing image {dtype} with shape {buf.shape} to {dtype.base}") - dtype = buf.dtype.base - # meta ops and assign already have a target buffer, otherwise we create a new one - buf_uop = buf.buf_uop if buf.op in {Ops.ASSIGN, Ops.VIEW} else UOp.new_buffer(buf.device, buf.size, dtype) - if buf.op is Ops.VIEW: op = buf.src[1].replace(src=tuple(to_uop(x, ctx, cache) for x in buf.src[1].src)) - else: op = buf.replace(dtype=dtype.base, src=tuple(to_uop(x, ctx, cache) for x in buf.src)) - # track the underlying tensor uop for this op - ctx.tensor_uops[buf_uop] = [buf] - # (early) bufferize - cache[buf] = ret = UOp(Ops.VIEW, dtype.base, (buf_uop, op.alu(Ops.CONTIGUOUS) if buf.forced_realize else op), buf.st) - return ret - -# **** AST graph rewrite - -# ** movement ops - -def apply_swizzle(u:UOp) -> UOp: - with Context(TRACK_MATCH_STATS=0): return graph_rewrite(u, view_left) - -def swizzle_r(r:UOp, src:UOp, st:ShapeTracker) -> UOp: - input_st = ShapeTracker.from_shape(unwrap(src.st).shape) - tmp = input_st.permute(tuple(i for i in range(len(input_st.shape)) if i not in r.axis_arg)+r.axis_arg) - prshape = prod(rshape:=tmp.shape[-len(r.axis_arg):]) - strides = strides_for_shape(rshape) - nv = [View.create(v.shape+rshape, tuple(x*prshape for x in v.strides)+strides, - v.offset*prshape, v.mask+tuple((0,s) for s in rshape) if v.mask is not None else None) for v in st.views] - # update input_st and axis - new_input_st = tmp + ShapeTracker(tuple(nv)) - new_axis = tuple(range(len(st.shape), len(st.shape) + len(r.axis_arg))) - return apply_swizzle(src.view(new_input_st)).r(r.arg[0], new_axis).view(ShapeTracker.from_shape(st.shape)) - -def reduceop_view_right(r:UOp, v:UOp, src:UOp) -> UOp: - if not (swizzle_st:=unwrap(v.st)).contiguous or v.size != src.size: raise AssertionError(f"can't push {v} down through {src}") - output_shape = swizzle_st.reduce(r.axis_arg) - return src.r(r.arg[0], tuple(i for i,(s,u) in enumerate(zip(src.shape, output_shape)) if s != u)).view(ShapeTracker.from_shape(output_shape)) - -def elementwise_view_right(root:UOp) -> UOp|None: - if len(swizzles:=[x for x in root.src if x.base is not x]) == 0: return None - assert all(x.base.st is not None for x in swizzles), f"found shapeless VIEW src in {root}" - assert all_same([x.base.size for x in swizzles]), f"swizzle inputs must have the same size {swizzles}" - # push the swizzle from src to root - output_swizzle = swizzles[0] - new_input_st = ShapeTracker.from_shape(output_swizzle.base.shape) - ret = root.replace(src=tuple(x if not x.has_st else x.src[0] if x in swizzles else apply_swizzle(x.view(new_input_st)) for x in root.src)) - # update the ASSIGN offset to match the new shape - if ret.op is Ops.ASSIGN and ret.arg is not None: ret = ret.replace(arg=ret.arg+new_input_st,) - return ret if ret.op is Ops.STORE else ret.view(ShapeTracker.from_shape(output_swizzle.shape)) - -def merge_double_reduce(root:UOp, first_reduce:UOp) -> UOp: - assert root.arg[0] == first_reduce.arg[0], "can't merge reduceops with different alu" - assert not any(x.op is Ops.REDUCE_AXIS for x in first_reduce.src[0].toposort), "can't merge more than two reduceops at a time" - return first_reduce.src[0].r(first_reduce.arg[0], root.axis_arg+first_reduce.axis_arg) - -# push VIEW to stores -view_right = merge_views+PatternMatcher([ - # ASSIGN with offset swizzles STORE - (UPat(Ops.STORE, src=(UPat.var("b"), UPat.var("st"), UPat(Ops.ASSIGN, name="a"))), - lambda a,b,st: None if a.arg is None else apply_swizzle(UOp.store(b, st, a.replace(arg=None)).view(a.arg))), - # REDUCE(src.view(contiguous=False)) -> REDUCE(src.view(contiguous=True)).view() - (UPat(Ops.REDUCE_AXIS, src=(UPat.var("src"),), name="r").view(name="v"), lambda v,r,src: None if v.st.contiguous else swizzle_r(r, src, v.st)), - # REDUCE(src.view()) -> REDUCE(src).view() - (UPat(Ops.REDUCE_AXIS, src=(UPat.var("src").view(name="v"),), name="r"), reduceop_view_right), - # ALU(src.view()) -> ALU(src).view() - (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.ASSIGN, Ops.CONTIGUOUS, Ops.STORE), name="root"), elementwise_view_right), - # double reduce op collapses to a single reduce op - (UPat(Ops.REDUCE_AXIS, src=(UPat(Ops.REDUCE_AXIS, name="first_reduce"),), name="root"), merge_double_reduce), -]) - -# ** ScheduleItem context builder - -@dataclass(frozen=True) -class ScheduleItemContext: - tensor_uops: dict[UOp, list[UOp]] - ops_metadata: dict[UOp, Metadata] - assigns: set[UOp] - var_vals: dict[Variable, int] - sinked: dict[UOp, UOp] - sts: set[ShapeTracker] = field(default_factory=set) - bufs: list[UOp] = field(default_factory=list) - metadata: set[Metadata] = field(default_factory=set) - assign_adj: dict[UOp, list[UOp]] = field(default_factory=dict) - -def _append_st_vars(ctx:ScheduleItemContext, x:UOp) -> UOp|None: - if (st:=unwrap(x.st)) in ctx.sts: return None - st, var_vals = st.simplify().unbind() - ctx.var_vals.update(var_vals) - ctx.sts.add(st) - return st.to_uop() if st != x.st else None - -def _append_buf(ctx:ScheduleItemContext, x:UOp) -> UOp: - assert x.arg[0] != -1, "fake -1 BUFFERS should not make it here" - ctx.bufs.append(x) - return UOp(Ops.DEFINE_GLOBAL, x.dtype.ptr(size=x.arg[1]), (), len(ctx.bufs)-1) -append_bufs = PatternMatcher([(UPat(Ops.BUFFER, name="x"), _append_buf)]) - -def _append_preload(ctx:ScheduleItemContext, x:UOp, b:UOp) -> UOp: - (adj_loads:=ctx.assign_adj.setdefault(b, [])).append(x) - if not all_same([x.op for x in adj_loads]): raise RuntimeError(f"Detected cycle when fusing {adj_loads}. Can only fuse PRELOAD or LOAD of {b}") - return x.replace(op=Ops.LOAD) -check_preload = PatternMatcher([(UPat(Ops.PRELOAD, src=(UPat.var("b"), UPat()), name="x"), _append_preload),]) - -to_si = PatternMatcher([ - (UPat(Ops.VIEW, name="x"), _append_st_vars), - (UPat(Ops.SINK, src=(UPat.store(UPat.var("b"), UPat(), UPat(GroupOp.Meta, name="x")),)), lambda b,x: x.replace(src=(b, *x.src))), - # don't need contiguous or assign anymore - (UPat(Ops.CONTIGUOUS, src=(UPat.var("x"),)), lambda x: x), - (UPat(Ops.ASSIGN, src=(UPat(), UPat.var("x"),)), lambda x: x), -]) - -add_metadata = PatternMatcher([(UPat(tuple(Ops), name="x"), lambda ctx,x: None if (m:=ctx.ops_metadata.get(x)) is None else ctx.metadata.add(m)),]) -add_assign_adjacents = PatternMatcher([(UPat.load(UPat.var("b"), UPat(), name="x"), lambda ctx,b,x: ctx.assign_adj.setdefault(b, []).append(x) - if b in ctx.assigns else None)]) - -# late folding for multi output kernels -multioutput = PatternMatcher([(UPat.load(UPat.var("b"), UPat()), lambda ctx,b: ctx.sinked.get(b)),]) - -def schedule_uop(pre:UOp, ctx:ScheduleContext) -> ScheduleItem: - # create the ast context - si_ctx = ScheduleItemContext(ctx.tensor_uops, ctx.ops_metadata, ctx.assigns, ctx.var_vals, {x.buf_uop:x.src[2] for x in pre.src}) - create_ctx = add_metadata if len(si_ctx.assigns) == 0 else add_metadata+add_assign_adjacents - sink = graph_rewrite(pre, create_ctx if len(si_ctx.sinked) == 1 else multioutput+create_ctx, si_ctx) - # do movement ops - sink = graph_rewrite(graph_rewrite(sink, view_left), view_right) - # convert to AST - sink = graph_rewrite(graph_rewrite(sink, to_si+check_preload if len(si_ctx.assigns) != 0 else to_si, si_ctx), append_bufs, si_ctx) - # assert buffer count limit - if (limit:=BUF_LIMIT.get(device:=si_ctx.bufs[0].device)) is not None and len(si_ctx.bufs) >= limit: - if DEBUG >= 3: print(sink) - raise RuntimeError(f"Kernel for {si_ctx.metadata} exceeded the {limit} buffer count limit for {device} with {len(si_ctx.bufs)} buffers.") - # we also allow masked views. if it has a single view and it's equal when you shrink a contig, it's fine - for ubuf,ops in si_ctx.assign_adj.items(): - if si_ctx.sinked.get(ubuf) is not None and not all((s:=x.st_arg).contiguous or (len(s.views) == 1 and (m:=s.views[0].mask) is not None \ - and ShapeTracker.from_shape(s.shape).shrink(m) == s.shrink(m)) for x in ops): - raise RuntimeError("self operand of augmented assign must be contiguous.\nhelp: consider using .contiguous():\n" - +colored(" - a += a.T\n", "red")+colored(" + a += a.T.contiguous()", "green")) - # can only schedule once - for buf_uop in si_ctx.sinked: - for luop in si_ctx.tensor_uops[buf_uop]: luop.become(buf_uop.view(unwrap(luop.st))) - # capture process replay - if getenv("RUN_PROCESS_REPLAY"): - PROCESS_REPLAY_CAPTURE[str(pre.key)] = pickle.dumps((pre, si_ctx.assigns, {k:v.value for k,v in ContextVar._cache.items()}, sink)) - return ScheduleItem(sink, tuple(u.buffer for u in si_ctx.bufs if u.size != 0), tuple(si_ctx.metadata), - tuple(ubuf for ubuf,ops in si_ctx.assign_adj.items() if any(x.op is Ops.PRELOAD for x in ops))) - -PROCESS_REPLAY_CAPTURE: dict[str, bytes] = {} -if getenv("RUN_PROCESS_REPLAY"): - @atexit.register - def save_process_replay() -> None: - for k,v in PROCESS_REPLAY_CAPTURE.items(): diskcache_put("schedule_process_replay", k, v, prepickled=True) - -# **** Schedule grouping - -def is_scheduled(u:UOp) -> bool: return u.op is Ops.VIEW and len(u.src) == 2 -def uval(u:UOp) -> UOp: - assert is_scheduled(u), f"must be a scheduled op {u}" - return r.src[0] if (r:=u.src[1]).op is Ops.CONTIGUOUS and not (r.src[0].base.op is Ops.VIEW and len(r.src[0].base.src) == 2) else r - -def recursive_group(tr:UOp, st:ShapeTracker, r:UOp, children:defaultdict[UOp, dict[UOp, None]], allbufs:dict[UOp, UOp], realizes:dict[UOp, UOp], - reduce_for_op:dict[UOp, UOp], group:dict[UOp, None], cache:dict[tuple[UOp, ShapeTracker], None]) -> None: - """recursively search the uop for groupable children, realize the UOp if a child can't group""" - if (tr, st) in cache: return - cache.setdefault((tr, st)) - rsize = unwrap(allbufs[r].st).size - if tr in realizes and tr is not r: - # can only fuse contiguous - # max one reduceop per kernel - if not st.contiguous or st.size != rsize or tr in reduce_for_op: group.setdefault(r) - return group.setdefault(tr) - for tr_next in children[tr]: - # max one reduceop per kernel - if (tr_next_uop:=uval(allbufs[tr_next]).base).op is Ops.REDUCE_AXIS: return group.setdefault(r) - # can only fuse contiguous - if len(st_childs:=dedup(unwrap(x.st) for x in tr_next_uop.src if is_scheduled(x.base) and x.base.buf_uop == tr)) > 1: return group.setdefault(r) - recursive_group(tr_next, st+st_childs[0], r, children, allbufs, realizes, reduce_for_op, group, cache) - -def get_isolated_children(r:UOp, reduce_for_op:dict[UOp, UOp], children:defaultdict[UOp, dict[UOp, None]], allbufs:dict[UOp, UOp], - realizes:dict[UOp, UOp], group:dict[UOp, None]) -> dict[UOp, None]: - rc_parents, cache = deque(group), set() - while rc_parents: - if (p:=uval(allbufs[rc_parents.pop()])) in cache: continue - cache.add(p) - # max one reduceop per kernel - if p.op is Ops.REDUCE_AXIS: return {} - rc_parents.extend(x.base.buf_uop for x in p.src if is_scheduled(x.base) and x.base.buf_uop is not r) - # search descendants of the reduceop that can cleanly group - descendants: dict[UOp, None] = {} - for tr in group: recursive_group(tr, unwrap(allbufs[tr].st), tr, children, allbufs, realizes, reduce_for_op, descendants, cache={}) - return merge_dicts([group, {} if any(tr in group for tr in descendants) else descendants]) - -def group_realizes(ctx:ScheduleContext) -> list[list[UOp]]: - """search the big graph for all the reduceops that need to realize, sometimes group/fuse the reduceop""" - # find all reduces, and pair them to a elementwise op. if they can't be cleanly paired, force realize the reduce (or a contig child) - reduce_for_op: dict[UOp, UOp] = {} - reduce_of_const: list[UOp] = [] - double_reduces: list[UOp] = [] - for r, r_uop in ctx.allbufs.items(): - if (r_uop:=uval(r_uop)).op is not Ops.REDUCE_AXIS: continue - if FUSE_CONV_BW and uval((x:=r_uop.src[0]).base).op is r_uop.op and x.base is not x: double_reduces.append(r) - if r in ctx.realizes: continue - group: dict[UOp, None] = {} - recursive_group(r, unwrap(r_uop.st), r, ctx.children, ctx.allbufs, ctx.realizes, reduce_for_op, group, cache={}) - # max one reduceop per kernel - can_chase = all(tr not in reduce_for_op for tr in group) - # TODO: forced_realize exists because the scheduler is incapable of checking for self-contained DAGs - forced_realize = r in group - if not forced_realize and len(group) > 1: - group = get_isolated_children(r, reduce_for_op, ctx.children, ctx.allbufs, ctx.realizes, group) - # can only fuse assign if no other assign_target is used in the kernel - if not forced_realize and any(x in ctx.assigns for x in group): - parents = deque((r, *group)) - while parents and not forced_realize: - if (p_uop:=ctx.allbufs.get(p:=parents.pop())) is None: continue - if (p_uop:=uval(p_uop)).op is Ops.ASSIGN and p not in group: forced_realize, can_chase = True, False - if p in ctx.realizes: continue - parents.extend([x.base.src[0] for x in p_uop.src if x.base.op is Ops.VIEW and len(x.base.src) != 0]) - if forced_realize or not group: - tr = r - if can_chase: - # can chase this down to contiguous children - st = unwrap(r_uop.st) - while len(ctx.children[tr]) == 1: - tr_next_uop = uval(ctx.allbufs[(tr_next:=next(iter(ctx.children[tr])))]) - st_childs = dedup([unwrap(x.st) for x in tr_next_uop.src if is_scheduled(x.base) and x.base.buf_uop is tr]) - if len(st_childs) > 1: break - if st.size != st_childs[0].size: break - st = st + st_childs[0] - if not st.contiguous or tr_next_uop.op is Ops.REDUCE_AXIS: break - tr = tr_next - # don't cast to higher size before store (tr cannot be realized if forced_realize) - if (tr_uop:=uval(ctx.allbufs[tr])).op is Ops.CAST and tr_uop.dtype.base.itemsize > tr_uop.src[0].dtype.base.itemsize: - tr = tr_uop.src[0].base.buf_uop - group = {tr: None} - ctx.realizes[tr] = tr - reduce_for_op.update((tr, r) for tr in group) - if FUSE_ARANGE and r_uop.arg[0] is Ops.ADD and uval(r_uop.src[0].base).op is Ops.CONST: reduce_of_const.append(r) - # fuse double reduces with no other child - for reduceop in double_reduces: - top_reduce = uval(ctx.allbufs[reduceop]).src[0].base.buf_uop - if len(ctx.children[top_reduce]) == 1: del ctx.realizes[top_reduce] - # maybe fuse arange with its children - for rbuf in reduce_of_const: - group = {tr:None for tr,rop in reduce_for_op.items() if rop is rbuf} - if any(luop.forced_realize for tr in group for luop in ctx.tensor_uops[tr]): continue - kernel_children = {c for tr in group for c in ctx.children[tr] if uval(ctx.allbufs[c]).op not in {Ops.COPY, Ops.BUFFER_VIEW}} - if len(kernel_children) == 0: continue - for tr in group: del ctx.realizes[tr] - # group BUFFER uops into kernels - output_groups: defaultdict[UOp, list[UOp]] = defaultdict(list) - for ubuf in ctx.realizes: output_groups[reduce_for_op.get(ubuf, ubuf)].append(ubuf) - return list(output_groups.values()) - -# **** Schedule creation and BFS toposort - -# ** ops in the big graph can either be pre-realized or scheduled (fused/realized) - -class UPatScheduled(UPat): - def __init__(self, *args, **kwargs): super().__init__(Ops.VIEW, name="base", src=(UPat(Ops.BUFFER, name="b"), - UPat(*args, **{"name":"to_store",**kwargs}))) - -# ** this is schedule level const folding - -def _as_const(u:UOp, val:ConstType) -> UOp: - assert is_scheduled(u), f"must be scheduled to fold {u}" - st = (base:=ShapeTracker.from_shape(())).reshape((1,)*len(u.shape)).expand(u.shape) - return UOp(Ops.VIEW, u.dtype, (u.buf_uop, UOp.const(u.dtype, val)), base).view(st) - -def simplify_reduceop(reduce:UOp, x:UOp) -> UOp|None: - # remove reduce on unmasked const - if all_int(x.shape) and x.is_unrealized_unmasked_const(): - prshape = prod(unwrap(x.st).shape[i] for i in reduce.arg[1]) - ret = x.const_arg - match reduce.arg[0]: - case Ops.ADD: ret *= prshape - case Ops.MUL: ret **= prshape - case Ops.MAX: pass # NOTE: Ops.MAX is passthrough - case _: return None - return UOp.const(reduce.dtype, ret) - return None - -def simplify_alu(alu:UOp): - if not all(x.is_unrealized_unmasked_const() for x in alu.src): return None - # this needs to have a VIEW next (it has to, right?) - return UOp.const(alu.dtype, exec_alu(alu.op, alu.dtype, [s.const_arg for s in alu.src])) - -def simplify_binop(binop:UOp, x:UOp, y:UOp): - if all_int(x.shape) and x.is_unrealized_unmasked_const(): other, const = y, x - elif all_int(y.shape) and y.is_unrealized_unmasked_const(): - if binop.op is Ops.IDIV and y.const_arg == 1: return x - other, const = x, y - else: return None - if binop.op is Ops.ADD and const.const_arg == 0: return other - if binop.op is Ops.MUL and const.const_arg == 1: return other - if binop.op is Ops.MUL and const.const_arg == 0: return UOp.const(binop.dtype, 0) - -def found_contiguous(ctx:ScheduleContext, contig:UOp, base:UOp, b:UOp): - if contig.src[0].op is Ops.VIEW and len(contig.src[0].src): - old_base = contig.src[0].src[0] - if old_base.op is Ops.VIEW and (sti:=unwrap(contig.src[0].st).invert(old_base.shape)) is not None: ctx.contiguous[old_base] = base.view(sti) -def replace_contiguous(ctx:ScheduleContext, alu:UOp): - new_src = list(alu.src) - for i,s in enumerate(alu.src): - if (replace_src:=ctx.contiguous.get(s, None)) is not None: new_src[i] = replace_src - if tuple(new_src) != alu.src: return alu.replace(src=tuple(new_src)) - -ops_folding = PatternMatcher([ - # op with size 0 is zero - (UPatScheduled(), lambda b,to_store,base: _as_const(base, 0) if base.size == 0 else None), - # DETACH is a NOOP here - (UPat(Ops.DETACH, name="detach"), lambda detach: detach.src[0]), - # elementwise const folding - (UPat(GroupOp.ALU, name="alu"), simplify_alu), - (UPat({Ops.ADD, Ops.MUL, Ops.IDIV}, name="binop", src=(UPat.var("x"), UPat.var("y"))), simplify_binop), - (UPat(Ops.CAST, src=(UPat.var("x"),), name="cast"), - lambda x,cast: UOp.const(cast.dtype, x.const_arg) if all_int(x.shape) and x.is_unrealized_unmasked_const() else None), - # reduce of size 0 is the identity element - (UPat(Ops.REDUCE_AXIS, name="reduce", src=(UPat.var("x"),)), - lambda reduce,x:UOp.const(reduce.dtype, identity_element(reduce.arg[0], reduce.dtype)) if x.size == 0 and reduce.size != 0 else None), - # reduce of const is collapsed (TODO: make this a generic rule for stride0) - (UPat(Ops.REDUCE_AXIS, name="reduce", src=(UPat.var("x"),)), simplify_reduceop), - # CONST doesn't need COPY - (UPat(Ops.COPY, src=(UPat.var("x"),)), lambda x:x if x.is_unrealized_const() else None), - # no double COPY - (UPat(Ops.COPY, src=(UPat(Ops.VIEW, src=(UPat(), UPat(Ops.COPY, name="base")),))), lambda base: base), - # no COPY to same device, except clone (arg is True) - (UPatScheduled(Ops.COPY, src=UPat(Ops.VIEW, name="copyin"), name="copy"), - lambda base,b,copyin,copy: copyin if base.device == copy.device and copy.arg[1] is not True else None), - # support for using a contiguous permuted view instead of the parent view if one exists - (UPatScheduled(Ops.CONTIGUOUS, name="contig"), found_contiguous), - (UPat(GroupOp.ALU, name="alu"), replace_contiguous), -]) - -# ** buffer merging - -def merge(ctx:ScheduleContext, v1:UOp, b1:UOp, v2:UOp, b2:UOp) -> UOp: - assert v1.st is not None and v2.st is not None and v1.st == v2.st, f"implicit movementop {v1.st} {v2.st}" - # if b2 is realized also realize b1 - if b2 in ctx.realizes: - ctx.realizes[b1] = b1 - del ctx.realizes[b2] - # ops referring to b2 now ref to b1 - ctx.tensor_uops[b1] += ctx.tensor_uops[b2] - del ctx.tensor_uops[b2] - # merge - return v1 - -def merge_realized(ctx:ScheduleContext, v1:UOp, b1:UOp, v2:UOp, b2:UOp): - # early become - for luop in ctx.tensor_uops.get(b1, [])+ctx.tensor_uops.get(b2, []): luop.become(b1.view(unwrap(luop.st))) - return v1 - -merge_bufs = PatternMatcher([ - # merge base - (UPat(Ops.VIEW, name="v2", src=(UPat(Ops.BUFFER, name="b2"), UPat(Ops.VIEW, name="v1", src=(UPat(Ops.BUFFER, name="b1"), UPat())))), merge), - (UPat(Ops.VIEW, name="v2", src=(UPat(Ops.BUFFER, name="b2"), UPat(Ops.VIEW, name="v1", src=(UPat(Ops.BUFFER, name="b1"),)))), merge_realized), - # collapse view - (UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat())).view(name="mv"))), lambda mv:mv), - (UPat(Ops.VIEW, src=(UPat(Ops.BUFFER), UPat(Ops.VIEW, src=(UPat(Ops.BUFFER),)).view(name="mv"))), lambda mv:mv), -]) - -# ** this decides which ops get realized - -def realize(ctx:ScheduleContext, b:UOp, to_store:UOp, **kwargs) -> None: - if to_store.op not in {Ops.CONST, Ops.BIND}: ctx.realizes.update([(b, to_store)]) - -def realize_view(ctx:ScheduleContext, view:UOp, src:UOp, b:UOp, **kwargs) -> None: - if src.st is None: return None - st = unwrap(view.st) - # fold simple pads - if len(st.views) == 1 and (m:=st.views[-1].mask) is not None and all_int(src.shape) and resolve(prod(src.shape) >= prod([y-x for x,y in m])): - return None if can_pad(src, ctx.realizes, set()) else realize(ctx, b, src) - # early realize before expand - if resolve(prod(src.shape) < prod(st.shape)): return realize(ctx, b, src) - # otherwise safety check pads - return None if (all(v.mask is None for v in st.views) or can_pad(src, ctx.realizes, set())) else realize(ctx, b, src) - -def fold_img_cast(ctx:ScheduleContext, xb:UOp, view:UOp, b:UOp, to_cast:UOp, **kwargs) -> UOp|None: - if not isinstance(xb.dtype, ImageDType) or b not in ctx.realizes or xb not in ctx.realizes or uval(to_cast).op in GroupOp.Meta: return None - del ctx.realizes[b] - return to_cast.view(unwrap(view.st)) - -def init_big_graph(sink:UOp) -> UOp|None: - new_src = tuple(x.base for x in sink.src if is_scheduled(x.base) and x.base.src[1].op is not Ops.CONST) - return None if new_src == sink.src else UOp(Ops.NOOP) if len(new_src) == 0 else UOp.sink(*new_src) - -do_realize = PatternMatcher([ - # always realize sinked ops - (UPat(Ops.SINK, name="sink"), init_big_graph), - # always realize meta ops - (UPatScheduled({Ops.ASSIGN, Ops.CONTIGUOUS, *GroupOp.Meta}), realize), - # realize before expand or unsafe pad ops - (UPatScheduled(name="src").view(name="view"), realize_view), - # don't realize image to image casts - (UPatScheduled(Ops.CAST, src=(UPat(Ops.VIEW, src=(UPat.var("xb"), UPat()), name="to_cast"),), dtype=dtypes.float).view(name="view"), fold_img_cast), - # realize before COPY or BUFFER_VIEW - (UPat((Ops.COPY, Ops.BUFFER_VIEW), src=(UPat.any(UPatScheduled(), UPatScheduled().view()),)), realize), - # ASSIGN only needs the buffer - (UPat(Ops.ASSIGN, src=(UPat(Ops.VIEW, name="dest"), UPat.var("src")), name="x"), lambda dest,src,x: x.replace(src=(dest.base.buf_uop, src))), -]) - -# ** this breaks down realized ops into STOREs and rewrites the ops to LOADs - -def generate_valid(ctx:ScheduleContext, b:UOp, to_store:UOp, base:UOp) -> UOp: - if to_store.op is Ops.BIND: ctx.var_vals.update([to_store.unbind()]) - return UOp.const_with_shape(base.dtype, to_store if to_store.op is Ops.BIND else to_store.arg, unwrap(base.st).shape) - -def append_realize(ctx:ScheduleContext, b:UOp, to_store:UOp, base:UOp) -> UOp: - ctx.realizes[b] = UOp.store(b, ShapeTracker.from_shape(base.shape).to_uop(), append_op(ctx, b, to_store)) - return UOp(Ops.LOAD, base.dtype, (b, unwrap(base.st).to_uop())) - -def append_op(ctx:ScheduleContext, b:UOp, to_store:UOp) -> UOp: - # TODO: metadata post merge - if (m:=ctx.tensor_uops[b][0].metadata) is not None: ctx.ops_metadata[to_store] = m - return to_store - -break_sched = PatternMatcher([ - # consts are always fused and generated - (UPatScheduled({Ops.CONST, Ops.BIND}), generate_valid), - # view of realized buffer just loads - (UPat(Ops.BUFFER, name="b").view(name="v"), lambda ctx,b,v: UOp(Ops.PRELOAD if b in ctx.assigns else Ops.LOAD, b.dtype.base, (b, v.st.to_uop()))), - # all other views either fold or realize with a store - (UPatScheduled(), lambda ctx,b,to_store,base: append_realize(ctx, b, to_store, base) if b in ctx.realizes else append_op(ctx, b, to_store)), + metadata: tuple[Metadata, ...] = () + fixedvars: dict[Variable, int] = field(default_factory=dict) + +# **** unbind Variables + +def unbind_view(ctx:list[dict[Variable, int]], x:UOp): + st = unwrap(x.st).simplify() + if any(x.op is Ops.BIND for x in st.vars()): + st, var_vals = st.unbind() + ctx.append(var_vals) + return x.replace(arg=st) if st != x.st else None + +def unbind_bind(ctx:list[dict[Variable, int]], x:UOp): + var, val = x.unbind() + ctx.append({var.replace(src=()):val}) + return var + +pm_unbind = PatternMatcher([ + (UPat(Ops.VIEW, name="x"), unbind_view), + (UPat(Ops.BIND, name="x"), unbind_bind), ]) -# **** Schedule context builder - -def append_uop(ctx:ScheduleContext, view:UOp, buf_uop:UOp) -> None: - ctx.allbufs[buf_uop] = view - if (op:=uval(view)).op is Ops.ASSIGN: ctx.assigns.add(buf_uop) - for x in op.src: - if is_scheduled(x.base): ctx.children.setdefault(x.base.buf_uop, {})[buf_uop] = None - # BUFFER_VIEW overrides the underlying buffer - if op.op is Ops.BUFFER_VIEW: - buffers[buf_uop] = (x:=op.src[0]).base.buffer.view(view.size, view.dtype, unwrap(x.st).views[0].offset*x.dtype.itemsize) - buf_uop.buffer.ref(1) -create_ctx = PatternMatcher([(UPat(Ops.VIEW, name="view", src=(UPat(Ops.BUFFER, name="buf_uop"), UPat())), append_uop)]) - -remove_movement_ops = PatternMatcher([(UPat(GroupOp.Movement, name="x"), lambda x: x.base.view(unwrap(x.st))),]) - -@track_rewrites(named=True) -def create_schedule_with_vars(outs:list[UOp]) -> tuple[list[ScheduleItem], dict[Variable, int]]: - if len(outs:=dedup(x.base for x in outs if x.base.realized is None and x.base.op is not Ops.CONST)) == 0: return [], {} - # create the big graph - ctx = ScheduleContext() - cache: dict[UOp, UOp] = {} - # to_uop is removing (many) of the movement ops - for u in (big_graph:=UOp.sink(*(to_uop(x, ctx, cache) for x in outs))).src: ctx.realizes[u.buf_uop] = u - big_graph = graph_rewrite(big_graph, remove_movement_ops+ops_folding+do_realize, ctx) - big_graph = graph_rewrite(big_graph, merge_bufs, ctx) - # create the scheduler context - graph_rewrite(big_graph, create_ctx, ctx) - # group realizes into kernels - store_groups = group_realizes(ctx) - graph_rewrite(big_graph, break_sched, ctx) - # preschedule realize groups - prescheduled: list[ScheduleItem] = [] - for store_uops in store_groups: - if len(stores:=[ctx.realizes[u] for u in store_uops if ctx.realizes[u].op is Ops.STORE]) != 0: - prescheduled.append(schedule_uop(UOp.sink(*stores), ctx)) - # do BFS - schedule_targets = {out:si for si in prescheduled for out in si.outputs} - graph: defaultdict[ScheduleItem, list[ScheduleItem]] = defaultdict(list) - in_degree: defaultdict[ScheduleItem, int] = defaultdict(int) - for si in prescheduled: - # realize outputs before a parent is assigned to - parents_assigns = dedup(xsi for x in si.assign_preloads if (xsi:=schedule_targets.get(x.buffer)) and xsi is not si) - for assign in parents_assigns: - graph[si].append(assign) - in_degree[assign] += 1 - # realize outputs after all parents are realized - scheduled_parents = dedup(xsi for x in si.inputs if (xsi:=schedule_targets.get(x)) is not None and xsi not in parents_assigns) - for x in scheduled_parents: - graph[x].append(si) - in_degree[si] += 1 - queue = deque(si for si in prescheduled if in_degree[si] == 0) +# **** schedule linearizer + +def create_schedule_with_vars(sched_sink:UOp) -> tuple[list[ScheduleItem], dict[Variable, int], dict[UOp, UOp]]: + # construct the KERNEL children graph based on assigns + children: defaultdict[UOp, list[UOp]] = defaultdict(list) + in_degree: dict[UOp, int] = {} + for u in (toposort:=sched_sink.toposort()): + if u.op is not Ops.ASSIGN: continue + k = u.src[1] + in_degree.setdefault(k, 0) + for s in k.src: + if s.op is not Ops.ASSIGN: continue + children[s.src[1]].append(k) + in_degree[k] += 1 + + # linearize KERNEL UOps into ScheduleItems in BFS order + queue = deque(k for k,v in in_degree.items() if v == 0) schedule: list[ScheduleItem] = [] + var_vals: dict[Variable, int] = {} while queue: - schedule.append(si:=queue.popleft()) - for x in graph[si]: + k = queue.popleft() + # unbind var_vals from the kernel + local_var_vals: list[dict[Variable, int]] = [] + ast = graph_rewrite(k.arg.ast, pm_unbind, ctx=local_var_vals, name="unbind vars") + var_vals = merge_dicts([var_vals, *local_var_vals]) + # create subbuffers if needed + if ast.op is Ops.BUFFER_VIEW: + base = k.src[1].buf_uop.buffer + assert isinstance(base, Buffer), "base can't be MultiBuffer" + buffers[k.src[0]] = base.view(k.size, ast.dtype, ast.arg[1]*base.dtype.itemsize) + ubufs = tuple(s.buf_uop.buffer for s in k.src) + if any(isinstance(x, MultiBuffer) for x in ubufs): + if ast.op is Ops.COPY: + if isinstance(ubufs[1], MultiBuffer) and ast.arg is None: # src is multiple buffers, none selected + if isinstance(ubufs[0], MultiBuffer): + # COPY ALL -> ALL + for b1,b2 in zip(ubufs[0].bufs, ubufs[1].bufs): schedule.append(ScheduleItem(ast, (b1, b2), k.arg.metadata)) + else: + # COPY ANY -> ONE. Currently we just select the first + schedule.append(ScheduleItem(ast, (ubufs[0], ubufs[1].bufs[0]), k.arg.metadata)) + else: + src_buf = ubufs[1].bufs[ast.arg] if isinstance(ubufs[1], MultiBuffer) else ubufs[1] + if isinstance(ubufs[0], MultiBuffer): + # COPY ONE -> ALL (BROADCAST) + for b in ubufs[0].bufs: schedule.append(ScheduleItem(ast, (b, src_buf), k.arg.metadata)) + else: schedule.append(ScheduleItem(ast, (ubufs[0], src_buf), k.arg.metadata)) # COPY ONE -> ONE + else: + assert all(isinstance(x, MultiBuffer) for x in ubufs), "kernel must all be multibuffer" + dnums = [x for x in ast.variables() if x.arg[0] == '_device_num'] + for i,bufs in enumerate(zip(*[x.bufs for x in cast(tuple[MultiBuffer, ...], ubufs)])): + schedule.append(ScheduleItem(ast, bufs, k.arg.metadata, {dnums[0]:i} if len(dnums) else {})) + else: + schedule.append(ScheduleItem(ast, cast(tuple[Buffer, ...], ubufs), k.arg.metadata)) + for x in children[k]: in_degree[x] -= 1 if in_degree[x] == 0: queue.append(x) - # confirm everything was scheduled correctly - if len(schedule) != (groups:=len(prescheduled)): raise RuntimeError(f"cycle detected in graph, grouped {groups} but only scheduled {len(schedule)}") - if DEBUG >= 1 and len(schedule) >= 10: print(f"scheduled {len(schedule)} kernels") - return schedule, ctx.var_vals -def create_schedule(outs:list[UOp]) -> list[ScheduleItem]: - schedule, var_vals = create_schedule_with_vars(outs) - assert len(var_vals) == 0 - return schedule + # map ASSIGN to BUFFER after ScheduleItems are constructed + becomes_map = {u:u.buf_uop for u in toposort if u.op is Ops.ASSIGN} + assert all(u.op in {Ops.BUFFER, Ops.BUFFER_VIEW} for u in becomes_map.values()), f"Schedule didn't end with BUFFER {becomes_map.values()}" + + return schedule, var_vals, becomes_map diff --git a/tinygrad_repo/tinygrad/engine/search.py b/tinygrad_repo/tinygrad/engine/search.py index ea255f4e41..739b74df13 100644 --- a/tinygrad_repo/tinygrad/engine/search.py +++ b/tinygrad_repo/tinygrad/engine/search.py @@ -1,26 +1,28 @@ -from typing import List, cast, DefaultDict, Optional, Callable -import itertools, functools, random, math, time, multiprocessing, traceback, signal +from typing import cast, Optional, Callable +import itertools, functools, random, math, time, multiprocessing, traceback, signal, atexit from collections import defaultdict from dataclasses import replace -from tinygrad.ops import UOp, Ops, Variable, sym_infer +from tinygrad.uop.ops import UOp, Ops, Variable, sym_infer from tinygrad.device import Device, Buffer, Compiler -from tinygrad.helpers import prod, flatten, DEBUG, CACHELEVEL, diskcache_get, diskcache_put, getenv, Context, colored, to_function_name +from tinygrad.helpers import prod, flatten, DEBUG, CACHELEVEL, diskcache_get, diskcache_put, getenv, Context, colored, time_to_str +from tinygrad.helpers import IGNORE_BEAM_CACHE, TC_SEARCH_OVER_SHAPE from tinygrad.dtype import ImageDType, PtrDType from tinygrad.codegen.kernel import Kernel, Opt, OptOps, KernelOptError from tinygrad.tensor import Tensor from tinygrad.engine.realize import CompiledRunner from tinygrad.renderer import ProgramSpec -actions = [Opt(op=OptOps.UPCAST, axis=axis, amt=amt) for amt in [0,2,3,4,5,7] for axis in range(6)] -actions += [Opt(op=OptOps.UNROLL, axis=axis, amt=amt) for amt in [0,4,7] for axis in range(5)] -actions += [Opt(op=OptOps.LOCAL, axis=axis, amt=amt) for amt in [2,3,4,8,13,16,29] for axis in range(6)] -actions += [Opt(op=OptOps.GROUPTOP, axis=axis, amt=amt) for amt in [13,16,28,29,32,49,64,256] for axis in range(3)] -actions += [Opt(op=OptOps.GROUP, axis=axis, amt=amt) for amt in [0,4,8,16] for axis in range(3)] -if getenv("BEAM_PADTO", 1): actions += [Opt(op=OptOps.PADTO, axis=axis, amt=amt) for amt in [32] for axis in range(7)] -actions += [Opt(op=OptOps.LOCAL, axis=0, amt=32), Opt(op=OptOps.LOCAL, axis=6, amt=2)] -actions += [Opt(op=OptOps.TC, axis=0, amt=0)] -actions += [Opt(op=OptOps.TC, axis=axis, amt=getenv("TC_OPT", 2)) for axis in range(9)] # covers resnet kernels (3 global * 3 reduce) -actions += [Opt(op=OptOps.SWAP, axis=axis, amt=amt) for axis in range(5) for amt in range(axis+1, 5)] +actions = [Opt(op=OptOps.UPCAST, axis=axis, arg=amt) for amt in [0,2,3,4,5,7] for axis in range(6)] +actions += [Opt(op=OptOps.UNROLL, axis=axis, arg=amt) for amt in [0,4,7] for axis in range(5)] +actions += [Opt(op=OptOps.LOCAL, axis=axis, arg=amt) for amt in [2,3,4,8,13,16,29] for axis in range(6)] +actions += [Opt(op=OptOps.GROUPTOP, axis=axis, arg=amt) for amt in [13,16,28,29,32,49,64,256] for axis in range(3)] +actions += [Opt(op=OptOps.GROUP, axis=axis, arg=amt) for amt in [0,4,8,16] for axis in range(3)] +if getenv("BEAM_PADTO", 1): actions += [Opt(op=OptOps.PADTO, axis=axis, arg=amt) for amt in [32] for axis in range(7)] +actions += [Opt(op=OptOps.LOCAL, axis=0, arg=32), Opt(op=OptOps.LOCAL, axis=6, arg=2)] +actions += [Opt(op=OptOps.TC, axis=0, arg=(-1, 0, getenv("TC", 1)))] +# covers resnet kernels (3 global * 3 reduce) +actions += [Opt(op=OptOps.TC, axis=axis, arg=(-1, getenv("TC_OPT", 2), getenv("TC", 1))) for axis in range(9)] +actions += [Opt(op=OptOps.SWAP, axis=axis_0, arg=axis_1) for axis_0 in range(5) for axis_1 in range(axis_0+1, 5)] if getenv("NOLOCALS"): actions += [Opt(op=OptOps.NOLOCALS)] def _get_test_global_size(global_size, max_global_size, var_vals): @@ -34,9 +36,9 @@ def _get_test_global_size(global_size, max_global_size, var_vals): return test_global_size, factor def _time_program(p:ProgramSpec, lib:bytes, var_vals:dict[Variable, int], rawbufs:list[Buffer], early_stop:Optional[float]=None, - max_global_size:Optional[int]=65536, clear_l2=False, cnt=3, name="test") -> list[float]: + allow_test_size:int=True, max_global_size:Optional[int]=65536, clear_l2=False, cnt=3, name="test") -> list[float]: factor = 1 - if p.global_size is not None and max_global_size is not None: + if allow_test_size and p.global_size is not None and max_global_size is not None: global_size, factor = _get_test_global_size(p.global_size, max_global_size, var_vals) p = replace(p, global_size=global_size) try: car = CompiledRunner(p, precompiled=lib) @@ -64,7 +66,9 @@ def _try_compile_linearized_w_idx(x:tuple[int,Kernel], compiler:Compiler) -> tup try: p = x[1].to_program(name_override="test") assert p.uops is not None, "uop list wasn't generated?" - if len(p.uops) >= getenv("BEAM_UOPS_MAX", 3000) > 0: raise RuntimeError("too many uops") + if len(p.uops) >= (uops_max:=getenv("BEAM_UOPS_MAX", 3000)) > 0: + if getenv("BEAM_LOG_SURPASS_MAX"): print(f"too many uops. {len(p.uops)=}, {uops_max=}") + raise RuntimeError("too many uops") st = time.perf_counter() prog = compiler.compile(p.src) et = time.perf_counter() - st @@ -80,45 +84,58 @@ def _try_compile_linearized_w_idx(x:tuple[int,Kernel], compiler:Compiler) -> tup # workers should ignore ctrl c def _init_worker(): signal.signal(signal.SIGINT, signal.SIG_IGN) -def _ensure_buffer_alloc(bufs:list[Buffer]) -> list[Buffer]: return [buf.ensure_allocated() for buf in bufs] +def _ensure_buffer_alloc(bufs:list[Buffer]) -> list[Buffer]: return [buf.ensure_allocated() if buf is not None else buf for buf in bufs] # *** external API *** # get (scrap) buffers for timing the linearizer def bufs_from_lin(lin:Kernel, allocate:bool=True) -> list[Buffer]: - bufsts: DefaultDict[int, list[UOp]] = defaultdict(list) + bufsts: defaultdict[int, list[UOp]] = defaultdict(list) for x in lin.bufs: if x.src[0].op is Ops.DEFINE_GLOBAL: bufsts[x.src[0].arg].append(x) - rawbufs: list[Optional[Buffer]] = [None]*len(bufsts) + # TODO: Nones are staying in here if buffers are optimized out! + # TODO: add a test for this + rawbufs: list[Optional[Buffer]] = [None]*(max(bufsts)+1) for k,lx in bufsts.items(): buf_size = prod(dtype.shape) if isinstance(dtype:=lx[0].src[0].dtype, ImageDType) else max(y.st_arg.real_size() for y in lx) assert isinstance(dtype, (PtrDType, ImageDType)) if buf_size == 0: buf_size = 1 # create a size 1 buffer if no cell is accessed in kernel. # TODO: remove from kernel input in this case. buf_dtype = dtype if isinstance(dtype, ImageDType) else dtype.base rawbufs[k] = Buffer(lin.opts.device, buf_size, buf_dtype).allocate() if allocate else Buffer(lin.opts.device, buf_size, buf_dtype) - assert all(r is not None for r in rawbufs) + #assert all(r is not None for r in rawbufs) return cast(list[Buffer], rawbufs) # get dictionary of all possible actions def get_kernel_actions(lin:Kernel, include_0=True) -> dict[int, Kernel]: acted_lins, max_up, max_lcl = {0:lin} if include_0 else {}, getenv("BEAM_UPCAST_MAX", 256), getenv("BEAM_LOCAL_MAX", 1024) - for i,a in enumerate(actions): + kernel_actions = actions.copy() + + if TC_SEARCH_OVER_SHAPE and len(lin.applied_opts) == 0: # tensor core opts must be first + for i, action in enumerate(kernel_actions): + if action.op == OptOps.TC and (tc_arg := cast(tuple, action.arg))[0] == -1: + # replace every tc_action with default tc with one tc_action for each available tc + kernel_actions[i:i+1] = \ + [Opt(op=OptOps.TC, axis=action.axis, arg=(tc_select, tc_arg[1], tc_arg[2])) for tc_select,_ in enumerate(lin.opts.tensor_cores)] + + for i,a in enumerate(kernel_actions): if a.axis is not None and a.op is not OptOps.TC: - if ((ax:=a.real_axis(lin)) >= lin.shape_len) or (lin.full_shape[ax] == a.amt and Opt(a.op, ax, 0) in actions): continue + if ((ax:=lin.real_axis(a)) >= lin.shape_len) or (lin.full_shape[ax] == a.arg and Opt(a.op, ax, 0) in kernel_actions): continue lin2 = lin.copy() try: lin2.apply_opt(a) - up, lcl, tc_up = 1, 1, prod(tc.dims)//prod([x[1] for x in tc.threads]) if (tc:=lin2.tensor_core) else 1 + up, lcl, tc_up = 1, 1, prod(tc.dims)//tc.threads if (tc:=lin2.tensor_core) else 1 for s,c in zip(lin2.full_shape, lin2.colors()): if c in {"magenta", "yellow"}: up *= s elif c in {"cyan", "green", "white"}: lcl *= s - if up//tc_up > max_up or lcl > max_lcl: continue + if up//tc_up > max_up or lcl > max_lcl: + if getenv("BEAM_LOG_SURPASS_MAX"): print(f"too many upcast/local. {up//tc_up=}, {max_up=}, {lcl=}, {max_lcl=}") + continue acted_lins[i+1] = lin2 except KernelOptError: pass return acted_lins beam_pool, BEAM_DEBUG = None, getenv("BEAM_DEBUG") -def beam_search(lin:Kernel, rawbufs:list[Buffer], amt:int, allow_test_size=True, disable_cache=getenv("IGNORE_BEAM_CACHE")) -> Kernel: +def beam_search(lin:Kernel, rawbufs:list[Buffer], amt:int, allow_test_size=True, disable_cache=IGNORE_BEAM_CACHE.value) -> Kernel: global beam_pool key = {"ast": lin.ast.key, "amt": amt, "allow_test_size": allow_test_size, "device": lin.opts.device, "suffix": lin.opts.suffix} if not disable_cache and CACHELEVEL >= 1 and (val:=diskcache_get("beam_search", key)) is not None: @@ -129,13 +146,15 @@ def beam_search(lin:Kernel, rawbufs:list[Buffer], amt:int, allow_test_size=True, beam: list[tuple[Kernel, float]] = [(lin, float("inf"))] seen_libs = set() - default_parallel = multiprocessing.cpu_count() if lin.opts.device in {"CUDA", "AMD", "NV", "METAL"} else 0 + default_parallel = multiprocessing.cpu_count() if lin.opts.device in {"CUDA", "AMD", "NV", "METAL", "HIP"} else 0 if beam_pool is None and (workers := getenv("PARALLEL", default_parallel)): beam_pool = multiprocessing.get_context("spawn").Pool(workers, _init_worker, (), getenv("BEAM_MAX_TASKS_PER_CHILD", 16)) + @atexit.register + def close_pool(): beam_pool.close() min_progress = getenv("BEAM_MIN_PROGRESS", 0.01)/1e6 if BEAM_DEBUG: print(f"BEAM_SEARCH:\n{lin.ast}") - if DEBUG >= 2: print(f" 0.00s: from 1 -> 1 actions {lin.colored_shape()}") + if DEBUG >= 2: print(f" 0.00s: from 1 -> 1 actions {lin.colored_shape()}") try: rawbufs = _ensure_buffer_alloc(rawbufs) @@ -155,24 +174,25 @@ def beam_search(lin:Kernel, rawbufs:list[Buffer], amt:int, allow_test_size=True, least_compute_ops = min(this_compute_ops:=sym_infer(p.estimates.ops, var_vals), least_compute_ops) if least_compute_ops*1000 < this_compute_ops: continue seen_libs.add(lib) - try: tms = _time_program(p, lib, var_vals, rawbufs, early_stop=beam[0][1]*3 if len(beam) else 1.0, clear_l2=hasattr(dev, 'invalidate_caches')) + try: tms = _time_program(p, lib, var_vals, rawbufs, early_stop=beam[0][1]*3 if len(beam) else 1.0, + allow_test_size=allow_test_size, clear_l2=hasattr(dev, 'invalidate_caches')) except RuntimeError: continue # for runtime issues timed_lins.append((acted_lins[i], min(tms))) - if BEAM_DEBUG > 1: print(f"{time.perf_counter() - st:7.2f}s: {i:5d} {len(cast(List, p.uops)):5d} uops {compile_et*1e6:12.2f} us compile/{timed_lins[-1][1]*1e6:12.2f} us run {len(timed_lins):4d}/{len(acted_lins):4d} {timed_lins[-1][0].colored_shape()}") # noqa: E501 - elif DEBUG >= 2: print(f"\r{time.perf_counter() - st:7.2f}s: {timed_lins[-1][1]*1e6:12.2f} us {len(timed_lins):4d}/{len(acted_lins):4d} {timed_lins[-1][0].colored_shape()}\033[K", end="") # noqa: E501 + if BEAM_DEBUG > 1: print(f"{time.perf_counter() - st:7.2f}s: {i:5d} {len(cast(list, p.uops)):5d} uops {time_to_str(compile_et, w=12)} compile/{time_to_str(timed_lins[-1][1], w=12)} run {len(timed_lins):4d}/{len(acted_lins):4d} {timed_lins[-1][0].colored_shape()}") # noqa: E501 + elif DEBUG >= 2: print(f"\r{time.perf_counter() - st:7.2f}s: {time_to_str(timed_lins[-1][1], w=12)} {len(timed_lins):4d}/{len(acted_lins):4d} {timed_lins[-1][0].colored_shape()}\033[K", end="") # noqa: E501 # done opts = sorted(timed_lins, key=lambda x: x[1]) exiting = len(opts) == 0 or (opts[0][1] < min_progress) or (len(beam) > 0 and ((beam[0][1]-opts[0][1]) < min_progress)) if not exiting: beam = opts[:amt] elif len(opts) > 0 and opts[0][1] < beam[0][1]: beam = opts[:1] - if DEBUG >= 2: print(f"\r{time.perf_counter() - st:7.2f}s:", colored(f"{beam[0][1]*1e6:12.2f} us", "green" if exiting else None), f"from {len(acted_lins):3d} -> {len(opts):3d} actions\033[K", beam[0][0].colored_shape()) # noqa: E501 + if DEBUG >= 2: print(f"\r{time.perf_counter() - st:7.2f}s:", colored(time_to_str(beam[0][1], w=12), "green" if exiting else None), f"from {len(acted_lins):3d} -> {len(opts):3d} actions\033[K", beam[0][0].colored_shape()) # noqa: E501 except KeyboardInterrupt as e: if beam_pool is not None: beam_pool.terminate() raise e if CACHELEVEL >= 1: diskcache_put("beam_search", key, beam[0][0].applied_opts) - if BEAM_DEBUG: print(f"BEAM_SEARCH: final tm={beam[0][1]*1e6:0.2f} us, applied_opts={beam[0][0].applied_opts}") + if BEAM_DEBUG: print(f"BEAM_SEARCH: final tm={time_to_str(beam[0][1], w=0)}, applied_opts={beam[0][0].applied_opts}") return beam[0][0] def optimize_local_size(_prg:Callable, global_size:list[int], rawbufs:list[Buffer]) -> list[int]: @@ -186,20 +206,3 @@ def optimize_local_size(_prg:Callable, global_size:list[int], rawbufs:list[Buffe ret = min([(try_exec(local_size), local_size) for local_size in random.sample(local_sizes, len(local_sizes))]) assert not math.isinf(ret[0]), "all optimize_local_size exec failed" return ret[1] - -def time_linearizer(lin:Kernel, rawbufs:list[Buffer], allow_test_size=True, max_global_size=65536, cnt=3, disable_cache=False, clear_l2=False) -> float: # noqa: E501 - key = {"ast": lin.ast.key, "opts": str(lin.applied_opts), "allow_test_size": allow_test_size, - "max_global_size": max_global_size, "clear_l2": clear_l2, "device": lin.opts.device, "suffix": lin.opts.suffix} - if not disable_cache and CACHELEVEL >= 2 and (val:=diskcache_get("time_linearizer", key)) is not None: return min(val) - - dev = Device[lin.opts.device] - assert dev.compiler is not None - - rawbufs = _ensure_buffer_alloc(rawbufs) - var_vals: dict[Variable, int] = {k:int(k.vmax+k.vmin)//2 for k in lin.ast.variables()} - p = lin.to_program() - tms = _time_program(p, dev.compiler.compile(p.src), var_vals, rawbufs, - max_global_size=max_global_size if allow_test_size else None, clear_l2=clear_l2, cnt=cnt, name=to_function_name(lin.name)) - - if CACHELEVEL >= 2: diskcache_put("time_linearizer", key, tms) - return min(tms) diff --git a/panda/tests/__init__.py b/tinygrad_repo/tinygrad/frontend/__init__.py similarity index 100% rename from panda/tests/__init__.py rename to tinygrad_repo/tinygrad/frontend/__init__.py diff --git a/tinygrad_repo/tinygrad/frontend/onnx.py b/tinygrad_repo/tinygrad/frontend/onnx.py new file mode 100644 index 0000000000..5c886163b7 --- /dev/null +++ b/tinygrad_repo/tinygrad/frontend/onnx.py @@ -0,0 +1,5 @@ +# type: ignore +import sys, pathlib +sys.path.append(pathlib.Path(__file__).parent.parent.as_posix()) +try: from extra.onnx import OnnxRunner # noqa: F401 # pylint: disable=unused-import +except ImportError as e: raise ImportError("onnx frontend not in release\nTo fix, install tinygrad from a git checkout with pip install -e .") from e \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/frontend/torch.py b/tinygrad_repo/tinygrad/frontend/torch.py new file mode 100644 index 0000000000..079256f674 --- /dev/null +++ b/tinygrad_repo/tinygrad/frontend/torch.py @@ -0,0 +1,5 @@ +# type: ignore +import sys, pathlib +sys.path.append(pathlib.Path(__file__).parent.parent.as_posix()) +try: import extra.torch_backend.backend # noqa: F401 # pylint: disable=unused-import +except ImportError as e: raise ImportError("torch frontend not in release\nTo fix, install tinygrad from a git checkout with pip install -e .") from e \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/function.py b/tinygrad_repo/tinygrad/function.py deleted file mode 100644 index 96b53d10a3..0000000000 --- a/tinygrad_repo/tinygrad/function.py +++ /dev/null @@ -1,200 +0,0 @@ -"""This is where the forwards and backwards passes live.""" -import math -from tinygrad.helpers import argsort -from tinygrad.dtype import dtypes, DType, sum_acc_dtype -from tinygrad.ops import Ops, resolve, sint, UOp -from tinygrad.tensor import Function - -class Contiguous(Function): - def forward(self, x:UOp) -> UOp: return x.contiguous() - def backward(self, grad_output:UOp) -> UOp: return grad_output - -class ContiguousBackward(Function): - def forward(self, x:UOp) -> UOp: return x - def backward(self, grad_output:UOp) -> UOp: return grad_output.contiguous() - -class Cast(Function): - def forward(self, x:UOp, dtype:DType, bitcast:bool=False) -> UOp: - self.input_dtype, self.bitcast = x.dtype, bitcast - return x.bitcast(dtype) if self.bitcast else x.cast(dtype) - - def backward(self, grad_output:UOp) -> UOp: - if self.bitcast: raise RuntimeError("bitcast cannot backward") - return grad_output.cast(self.input_dtype) - -# ************* unary ops ************* - -class Reciprocal(Function): - def forward(self, x:UOp) -> UOp: - self.ret = x.reciprocal() - return self.ret - - def backward(self, grad_output:UOp) -> UOp: return -grad_output * self.ret * self.ret - -class Sin(Function): - def forward(self, x:UOp) -> UOp: - self.x = x - return x.sin() - - def backward(self, grad_output:UOp) -> UOp: return (math.pi/2 - self.x).sin() * grad_output - -class Relu(Function): - def forward(self, x:UOp) -> UOp: - self.ret = (x>0).where(x, 0) - return self.ret - - def backward(self, grad_output:UOp) -> UOp: return (self.ret>0).cast(grad_output.dtype) * grad_output - -class Log(Function): - def forward(self, x:UOp) -> UOp: - self.x = x - return x.log2() * math.log(2) - - def backward(self, grad_output:UOp) -> UOp: return grad_output / self.x - -class Exp(Function): - def forward(self, x:UOp) -> UOp: - self.ret = (x * (1/math.log(2))).exp2() - return self.ret - - def backward(self, grad_output:UOp) -> UOp: return self.ret * grad_output - -class Sqrt(Function): - def forward(self, x:UOp) -> UOp: - self.ret = x.sqrt() - return self.ret - - def backward(self, grad_output:UOp) -> UOp: return grad_output / (self.ret*2) - -class Sign(Function): - # NOTE: the x*0 is to match torch behavior without function.py - def forward(self, x:UOp) -> UOp: return x.ne(0).where((x<0).where(x.const_like(-1), x.const_like(1)), x.const_like(0)) + x*0 - # backward always return 0 to match torch - def backward(self, grad_output:UOp) -> UOp: return grad_output.const_like(0) - -# ************* binary ops ************* - -class Less(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x tuple[UOp|None, UOp|None]: return None, None - -class Neq(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x.ne(y) - def backward(self, grad_output:UOp) -> tuple[UOp|None, UOp|None]: return None, None - -class Xor(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x^y - -class BitwiseAnd(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x&y - -class BitwiseOr(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x|y - -class Threefry(Function): - def forward(self, x:UOp, seed:UOp) -> UOp: return x.threefry(seed) - -class Add(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x+y - - def backward(self, grad_output:UOp) -> tuple[UOp|None, UOp|None]: - return grad_output if self.needs_input_grad[0] else None, \ - grad_output if self.needs_input_grad[1] else None - -class Mul(Function): - def forward(self, x:UOp, y:UOp) -> UOp: - self.x, self.y = x, y - return x * y - - def backward(self, grad_output:UOp) -> tuple[UOp|None, UOp|None]: - return (self.y * grad_output) if self.needs_input_grad[0] else None, \ - (self.x * grad_output) if self.needs_input_grad[1] else None - -class IDiv(Function): - def forward(self, x:UOp, y:UOp) -> UOp: return x // y - -# ************* ternary ops ************* - -class Where(Function): - def forward(self, x:UOp, y:UOp, z:UOp) -> UOp: - self.x = x - return self.x.where(y, z) - - def backward(self, grad_output:UOp) -> tuple[None, UOp|None, UOp|None]: - return None, \ - self.x.where(grad_output, grad_output.const_like(0)) if self.needs_input_grad[1] else None, \ - self.x.where(grad_output.const_like(0), grad_output) if self.needs_input_grad[2] else None - -# ************* reduce ops ************* - -class Sum(Function): - def forward(self, x:UOp, axis:tuple[int, ...]) -> UOp: - self.input_shape = x.shape - return x.r(Ops.ADD, axis) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.expand(self.input_shape) - -class Prod(Function): - def forward(self, x:UOp, axis:tuple[int, ...]) -> UOp: - self.x, self.ret = x, x.r(Ops.MUL, axis) - return self.ret - - def backward(self, grad_output:UOp) -> UOp: - return (grad_output * self.ret).expand(self.x.shape) / self.x - -class Max(Function): - def forward(self, x:UOp, axis:tuple[int, ...]) -> UOp: - self.x, self.ret, self.axis = x, x.r(Ops.MAX, axis), axis - return self.ret - - def backward(self, grad_output:UOp) -> UOp: - # 1s in locations where the max was chosen (can be two locations) - max_is_1s = self.x.ne(self.ret.expand(self.x.shape)).ne(self.x.const_like(1).cast(dtypes.bool)).cast(grad_output.dtype) - div = max_is_1s.r(Ops.ADD, self.axis).expand(self.x.shape) - return (max_is_1s/div) * grad_output.expand(self.x.shape) - -# ************* movement ops ************* - -# NOTE: this is sum in reverse -class Expand(Function): - def forward(self, x:UOp, shape:tuple[int, ...]) -> UOp: - self.expanded_axis = tuple(i for i, (si, so) in enumerate(zip(x.shape, shape)) if resolve(si != so)) - return x.expand(shape) - - def backward(self, grad_output:UOp) -> UOp: - return grad_output.cast(sum_acc_dtype(grad_output.dtype)).r(Ops.ADD, self.expanded_axis).cast(grad_output.dtype) - -class Reshape(Function): - def forward(self, x:UOp, shape:tuple[int, ...]) -> UOp: - self.input_shape = x.shape - return x.reshape(shape) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.reshape(self.input_shape) - -class Permute(Function): - def forward(self, x:UOp, order:tuple[int, ...]) -> UOp: - self.input_order = order - return x.permute(order) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.permute(argsort(self.input_order)) - -class Pad(Function): - def forward(self, x:UOp, arg:tuple[tuple[int, int], ...]) -> UOp: - self.narg = tuple([(p[0], s+p[0]) for s,p in zip(x.shape, arg)]) - return x.pad(arg) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.shrink(self.narg) - -class Shrink(Function): - def forward(self, x:UOp, arg:tuple[tuple[sint, sint], ...]) -> UOp: - self.narg = tuple([(p[0], s-p[1]) for s,p in zip(x.shape, arg)]) - return x.shrink(arg) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.pad(self.narg) - -class Flip(Function): - def forward(self, x:UOp, axis:tuple[int, ...]) -> UOp: - self.arg = tuple([-1 if i in axis else 1 for i in range(len(x.shape))]) - return x.stride(self.arg) - - def backward(self, grad_output:UOp) -> UOp: return grad_output.stride(self.arg) diff --git a/tinygrad_repo/tinygrad/gradient.py b/tinygrad_repo/tinygrad/gradient.py index c9ea1d8028..cebaad1b71 100644 --- a/tinygrad_repo/tinygrad/gradient.py +++ b/tinygrad_repo/tinygrad/gradient.py @@ -1,7 +1,7 @@ from typing import cast -import math, functools +import math, dataclasses from tinygrad.dtype import dtypes, sum_acc_dtype -from tinygrad.ops import UOp, PatternMatcher, UPat, Ops +from tinygrad.uop.ops import UOp, PatternMatcher, UPat, Ops, all_metadata from tinygrad.helpers import argsort def reduce_gradient(ctx:UOp, ret:UOp): @@ -22,39 +22,37 @@ pm_gradient = PatternMatcher([ (UPat(Ops.SQRT, name="ret"), lambda ctx, ret: (ctx / (ret*2),)), (UPat((Ops.CMPLT, Ops.CMPNE)), lambda: (None, None)), (UPat(Ops.ADD), lambda ctx: (ctx, ctx)), + (UPat(Ops.POW, name="ret"), lambda ctx, ret: + (ctx*(ret.src[0].eq(0) & ret.src[1].eq(0)).where(ret.src[1], ret.src[1]*ret.src[0].pow(ret.src[1]-1)), + ctx*ret.src[0].eq(0).where((ret.src[1]<0).where(ret.const_like(-math.inf), ret.const_like(0)), ret*ret.src[0].log2()*math.log(2.0)))), (UPat(Ops.MAX, name="ret"), lambda ctx, ret: ((ret.src[0]>ret.src[1]).where(ctx, (ret.src[0]!=ret.src[1]).where(ctx.const_like(0), ctx * 0.5)), (ret.src[0] bool: return any(u in targets or is_in_target_path(u) for u in x.src) - def _walk(node:UOp, visited:set[UOp]): - visited.add(node) - if node.op is Ops.DETACH: return - if is_in_target_path(node): - for i in node.src: - if i not in visited: yield from _walk(i, visited) - yield node - return list(_walk(root, set())) +def _deepwalk(root:UOp, targets:set[UOp]) -> list[UOp]: + # compute the target path (top down) + in_target_path: dict[UOp, bool] = {} + for u in root.toposort(): in_target_path[u] = any(x in targets or in_target_path[x] for x in u.src) + # don't flow through DETACH/ASSIGN or anything not in target path + return list(root.toposort(lambda node: node.op not in {Ops.DETACH, Ops.ASSIGN} and in_target_path[node])) -def compute_gradient(root:UOp, root_grad:UOp, targets:list[UOp]) -> dict[UOp, UOp]: +def compute_gradient(root:UOp, root_grad:UOp, targets:set[UOp]) -> dict[UOp, UOp]: grads = {root: root_grad} for t0 in reversed(_deepwalk(root, targets)): if t0 not in grads: continue @@ -65,4 +63,5 @@ def compute_gradient(root:UOp, root_grad:UOp, targets:list[UOp]) -> dict[UOp, UO if v is None: continue if k in grads: grads[k] = grads[k] + v else: grads[k] = v + if (forward_metadata:=all_metadata.get(t0)) is not None: all_metadata[v] = dataclasses.replace(forward_metadata, backward=True) return grads diff --git a/tinygrad_repo/tinygrad/helpers.py b/tinygrad_repo/tinygrad/helpers.py index f050f9ffce..41217d3e71 100644 --- a/tinygrad_repo/tinygrad/helpers.py +++ b/tinygrad_repo/tinygrad/helpers.py @@ -1,8 +1,8 @@ from __future__ import annotations -import os, functools, platform, time, re, contextlib, operator, hashlib, pickle, sqlite3, tempfile, pathlib, string, ctypes, sys, gzip -import urllib.request, subprocess, shutil, math, contextvars, types, copyreg, inspect, importlib +import os, functools, platform, time, re, contextlib, operator, hashlib, pickle, sqlite3, tempfile, pathlib, string, ctypes, sys, gzip, getpass +import urllib.request, subprocess, shutil, math, types, copyreg, inspect, importlib from dataclasses import dataclass -from typing import Dict, Union, ClassVar, Optional, Iterable, Any, TypeVar, Callable, Sequence, TypeGuard +from typing import Union, ClassVar, Optional, Iterable, Any, TypeVar, Callable, Sequence, TypeGuard, Iterator, Generic T = TypeVar("T") U = TypeVar("U") @@ -27,7 +27,7 @@ def all_same(items:Union[tuple[T, ...], list[T]]): return all(x == items[0] for def all_int(t: Sequence[Any]) -> TypeGuard[tuple[int, ...]]: return all(isinstance(s, int) for s in t) def colored(st, color:Optional[str], background=False): return f"\u001b[{10*background+60*(color.upper() == color)+30+['black', 'red', 'green', 'yellow', 'blue', 'magenta', 'cyan', 'white'].index(color.lower())}m{st}\u001b[0m" if color is not None else st # replace the termcolor library with one line # noqa: E501 def colorize_float(x: float): return colored(f"{x:7.2f}x", 'green' if x < 0.75 else 'red' if x > 1.15 else 'yellow') -def memsize_to_str(_bytes: int) -> str: return [f"{(_bytes / d):.2f} {pr}" for d,pr in [(1e9,"GB"),(1e6,"MB"),(1e3,"KB"),(1,"B")] if _bytes > d][0] +def time_to_str(t:float, w=8) -> str: return next((f"{t * d:{w}.2f}{pr}" for d,pr in [(1, "s "),(1e3, "ms")] if t > 10/d), f"{t * 1e6:{w}.2f}us") def ansistrip(s:str): return re.sub('\x1b\\[(K|.*?m)', '', s) def ansilen(s:str): return len(ansistrip(s)) def make_tuple(x:Union[int, Sequence[int]], cnt:int) -> tuple[int, ...]: return (x,)*cnt if isinstance(x, int) else tuple(x) @@ -43,8 +43,15 @@ def fromimport(mod, frm): return getattr(__import__(mod, fromlist=[frm]), frm) def strip_parens(fst:str): return fst[1:-1] if fst[0] == '(' and fst[-1] == ')' and fst[1:-1].find('(') <= fst[1:-1].find(')') else fst def ceildiv(num, amt): return int(ret) if isinstance((ret:=-(num//-amt)), float) else ret def round_up(num:int, amt:int) -> int: return (num+amt-1)//amt * amt +# cstyle div and mod +def cdiv(x:int, y:int) -> int: return abs(x)//abs(y)*(1,-1)[x*y<0] if y != 0 else 0 +def cmod(x:int, y:int) -> int: return x-cdiv(x,y)*y +def lo32(x:Any) -> Any: return x & 0xFFFFFFFF # Any is sint +def hi32(x:Any) -> Any: return x >> 32 # Any is sint def data64(data:Any) -> tuple[Any, Any]: return (data >> 32, data & 0xFFFFFFFF) # Any is sint def data64_le(data:Any) -> tuple[Any, Any]: return (data & 0xFFFFFFFF, data >> 32) # Any is sint +def getbits(value: int, start: int, end: int): return (value >> start) & ((1 << (end - start + 1)) - 1) +def i2u(bits: int, value: int): return value if value >= 0 else (1< dict[T,U]: kvs = set([(k,v) for d in ds for k,v in d.items()]) assert len(kvs) == len(set(kv[0] for kv in kvs)), f"cannot merge, {kvs} contains different values for the same key" @@ -66,32 +73,32 @@ def get_child(obj, key): else: obj = getattr(obj, k) return obj def word_wrap(x, wrap=80): return x if len(x) <= wrap or '\n' in x[0:wrap] else (x[0:wrap] + "\n" + word_wrap(x[wrap:], wrap)) +def pluralize(st:str, cnt:int): return f"{cnt} {st}"+('' if cnt == 1 else 's') # for length N coefficients `p`, returns p[0] * x**(N-1) + p[1] * x**(N-2) + ... + p[-2] * x + p[-1] def polyN(x:T, p:list[float]) -> T: return functools.reduce(lambda acc,c: acc*x+c, p, 0.0) # type: ignore -@functools.lru_cache(maxsize=None) +@functools.cache def to_function_name(s:str): return ''.join([c if c in (string.ascii_letters+string.digits+'_') else f'{ord(c):02X}' for c in ansistrip(s)]) -@functools.lru_cache(maxsize=None) +@functools.cache def getenv(key:str, default=0): return type(default)(os.getenv(key, default)) -def temp(x:str) -> str: return (pathlib.Path(tempfile.gettempdir()) / x).as_posix() +def temp(x:str, append_user:bool=False) -> str: + return (pathlib.Path(tempfile.gettempdir()) / (f"{x}.{getpass.getuser()}" if append_user else x)).as_posix() class Context(contextlib.ContextDecorator): - stack: ClassVar[list[dict[str, int]]] = [{}] def __init__(self, **kwargs): self.kwargs = kwargs def __enter__(self): - Context.stack[-1] = {k:o.value for k,o in ContextVar._cache.items()} # Store current state. - for k,v in self.kwargs.items(): ContextVar._cache[k].value = v # Update to new temporary state. - Context.stack.append(self.kwargs) # Store the temporary state so we know what to undo later. + self.old_context:dict[str, int] = {k:v.value for k,v in ContextVar._cache.items()} + for k,v in self.kwargs.items(): ContextVar._cache[k].value = v def __exit__(self, *args): - for k in Context.stack.pop(): ContextVar._cache[k].value = Context.stack[-1].get(k, ContextVar._cache[k].value) + for k,v in self.old_context.items(): ContextVar._cache[k].value = v class ContextVar: _cache: ClassVar[dict[str, ContextVar]] = {} value: int key: str def __init__(self, key, default_value): - assert key not in ContextVar._cache, f"attempt to recreate ContextVar {key}" + if key in ContextVar._cache: raise RuntimeError(f"attempt to recreate ContextVar {key}") ContextVar._cache[key] = self self.value, self.key = getenv(key, default_value), key def __bool__(self): return bool(self.value) @@ -99,12 +106,18 @@ class ContextVar: def __gt__(self, x): return self.value > x def __lt__(self, x): return self.value < x -DEBUG, IMAGE, BEAM, NOOPT, JIT = ContextVar("DEBUG", 0), ContextVar("IMAGE", 0), ContextVar("BEAM", 0), ContextVar("NOOPT", 0), ContextVar("JIT", 1) -WINO, CAPTURING, TRACEMETA, PROFILE = ContextVar("WINO", 0), ContextVar("CAPTURING", 1), ContextVar("TRACEMETA", 1), ContextVar("PROFILE", 0) -USE_TC, TC_OPT, AMX, TRANSCENDENTAL = ContextVar("TC", 1), ContextVar("TC_OPT", 0), ContextVar("AMX", 0), ContextVar("TRANSCENDENTAL", 1) +DEBUG, IMAGE, BEAM, NOOPT = ContextVar("DEBUG", 0), ContextVar("IMAGE", 0), ContextVar("BEAM", 0), ContextVar("NOOPT", 0) +JIT = ContextVar("JIT", 2 if platform.system() == 'Darwin' and ('Intel' in platform.processor() or 'i386' in platform.processor()) else 1) +WINO, CAPTURING, TRACEMETA = ContextVar("WINO", 0), ContextVar("CAPTURING", 1), ContextVar("TRACEMETA", 1) +USE_TC, TC_SELECT, TC_OPT, AMX = ContextVar("TC", 1), ContextVar("TC_SELECT", -1), ContextVar("TC_OPT", 0), ContextVar("AMX", 0) +TRANSCENDENTAL, TC_SEARCH_OVER_SHAPE = ContextVar("TRANSCENDENTAL", 1), ContextVar("TC_SEARCH_OVER_SHAPE", 1) FUSE_ARANGE, FUSE_CONV_BW = ContextVar("FUSE_ARANGE", 0), ContextVar("FUSE_CONV_BW", 0) SPLIT_REDUCEOP, NO_MEMORY_PLANNER, RING = ContextVar("SPLIT_REDUCEOP", 1), ContextVar("NO_MEMORY_PLANNER", 0), ContextVar("RING", 1) -PICKLE_BUFFERS = ContextVar("PICKLE_BUFFERS", 1) +PICKLE_BUFFERS, PROFILE, LRU = ContextVar("PICKLE_BUFFERS", 1), ContextVar("PROFILE", getenv("VIZ")), ContextVar("LRU", 1) +CACHELEVEL, IGNORE_BEAM_CACHE, DEVECTORIZE = ContextVar("CACHELEVEL", 2), ContextVar("IGNORE_BEAM_CACHE", 0), ContextVar("DEVECTORIZE", 1) +DISABLE_COMPILER_CACHE = ContextVar("DISABLE_COMPILER_CACHE", 0) +DONT_REALIZE_EXPAND, DONT_GROUP_REDUCES = ContextVar("DONT_REALIZE_EXPAND", 0), ContextVar("DONT_GROUP_REDUCES", 0) +QUANTIZE, VALIDATE_WITH_CPU, IGNORE_OOB = ContextVar("QUANTIZE", 0), ContextVar("VALIDATE_WITH_CPU", 0), ContextVar("IGNORE_OOB", 1) @dataclass(frozen=True) class Metadata: @@ -114,7 +127,6 @@ class Metadata: def __hash__(self): return hash(self.name) def __repr__(self): return str(self) + (f" - {self.caller}" if self.caller else "") def __str__(self): return self.name + (" bw" if self.backward else "") -_METADATA: contextvars.ContextVar[Optional[Metadata]] = contextvars.ContextVar("_METADATA", default=None) # **************** global state Counters **************** @@ -161,9 +173,8 @@ class Profiling(contextlib.ContextDecorator): cache_dir: str = os.path.join(getenv("XDG_CACHE_HOME", os.path.expanduser("~/Library/Caches" if OSX else "~/.cache")), "tinygrad") CACHEDB: str = getenv("CACHEDB", os.path.abspath(os.path.join(cache_dir, "cache.db"))) -CACHELEVEL = getenv("CACHELEVEL", 2) -VERSION = 17 +VERSION = 19 _db_connection = None def db_connection(): global _db_connection @@ -173,7 +184,7 @@ def db_connection(): # another connection has set it already or is in the process of setting it # that connection will lock the database with contextlib.suppress(sqlite3.OperationalError): _db_connection.execute("PRAGMA journal_mode=WAL").fetchone() - if DEBUG >= 7: _db_connection.set_trace_callback(print) + if DEBUG >= 8: _db_connection.set_trace_callback(print) return _db_connection def diskcache_clear(): @@ -181,11 +192,10 @@ def diskcache_clear(): drop_tables = cur.execute("SELECT 'DROP TABLE IF EXISTS ' || quote(name) || ';' FROM sqlite_master WHERE type = 'table';").fetchall() cur.executescript("\n".join([s[0] for s in drop_tables] + ["VACUUM;"])) -def diskcache_get(table:str, key:Union[Dict, str, int]) -> Any: - if CACHELEVEL == 0: return None +def diskcache_get(table:str, key:Union[dict, str, int]) -> Any: + if CACHELEVEL < 1: return None if isinstance(key, (str,int)): key = {"key": key} - conn = db_connection() - cur = conn.cursor() + cur = db_connection().cursor() try: res = cur.execute(f"SELECT val FROM '{table}_{VERSION}' WHERE {' AND '.join([f'{x}=?' for x in key.keys()])}", tuple(key.values())) except sqlite3.OperationalError: @@ -194,8 +204,8 @@ def diskcache_get(table:str, key:Union[Dict, str, int]) -> Any: return None _db_tables = set() -def diskcache_put(table:str, key:Union[Dict, str, int], val:Any, prepickled=False): - if CACHELEVEL == 0: return val +def diskcache_put(table:str, key:Union[dict, str, int], val:Any, prepickled=False): + if CACHELEVEL < 1: return val if isinstance(key, (str,int)): key = {"key": key} conn = db_connection() cur = conn.cursor() @@ -204,7 +214,7 @@ def diskcache_put(table:str, key:Union[Dict, str, int], val:Any, prepickled=Fals ltypes = ', '.join(f"{k} {TYPES[type(key[k])]}" for k in key.keys()) cur.execute(f"CREATE TABLE IF NOT EXISTS '{table}_{VERSION}' ({ltypes}, val blob, PRIMARY KEY ({', '.join(key.keys())}))") _db_tables.add(table) - cur.execute(f"REPLACE INTO '{table}_{VERSION}' ({', '.join(key.keys())}, val) VALUES ({', '.join(['?']*len(key.keys()))}, ?)", tuple(key.values()) + (val if prepickled else pickle.dumps(val), )) # noqa: E501 + cur.execute(f"REPLACE INTO '{table}_{VERSION}' ({', '.join(key.keys())}, val) VALUES ({', '.join(['?']*len(key))}, ?)", tuple(key.values()) + (val if prepickled else pickle.dumps(val), )) # noqa: E501 conn.commit() cur.close() return val @@ -212,10 +222,14 @@ def diskcache_put(table:str, key:Union[Dict, str, int], val:Any, prepickled=Fals def diskcache(func): def wrapper(*args, **kwargs) -> bytes: table, key = f"cache_{func.__name__}", hashlib.sha256(pickle.dumps((args, kwargs))).hexdigest() - if (ret:=diskcache_get(table, key)): return ret + if (ret:=diskcache_get(table, key)) is not None: return ret return diskcache_put(table, key, func(*args, **kwargs)) return wrapper +# *** process replay *** + +CAPTURE_PROCESS_REPLAY = getenv("CAPTURE_PROCESS_REPLAY") + # *** http support *** def _ensure_downloads_dir() -> pathlib.Path: @@ -240,7 +254,7 @@ def fetch(url:str, name:Optional[Union[pathlib.Path, str]]=None, subdir:Optional assert r.status == 200, r.status length = int(r.headers.get('content-length', 0)) if not gunzip else None readfile = gzip.GzipFile(fileobj=r) if gunzip else r - progress_bar = tqdm(total=length, unit='B', unit_scale=True, desc=f"{url}", disable=CI) + progress_bar:tqdm = tqdm(total=length, unit='B', unit_scale=True, desc=f"{url}", disable=CI) with tempfile.NamedTemporaryFile(dir=_dir, delete=False) as f: while chunk := readfile.read(16384): progress_bar.update(f.write(chunk)) f.close() @@ -261,16 +275,27 @@ def cpu_objdump(lib, objdump_tool='objdump'): pathlib.Path(f.name).write_bytes(lib) print(subprocess.check_output([objdump_tool, '-d', f.name]).decode('utf-8')) +def capstone_flatdump(lib: bytes): + import capstone + match platform.machine(): + case 'x86_64' | 'AMD64': cs = capstone.Cs(capstone.CS_ARCH_X86, capstone.CS_MODE_64) + case 'aarch64' | 'arm64': cs = capstone.Cs(capstone.CS_ARCH_ARM64, capstone.CS_MODE_ARM) + case machine: raise NotImplementedError(f"Capstone disassembly isn't supported for {machine}") + cs.skipdata = True + for instr in cs.disasm(lib, 0): + print(f"{instr.address:#08x}: {instr.mnemonic}\t{instr.op_str}") + sys.stdout.flush() + # *** ctypes helpers # TODO: make this work with read only memoryviews (if possible) def from_mv(mv:memoryview, to_type=ctypes.c_char): return ctypes.cast(ctypes.addressof(to_type.from_buffer(mv)), ctypes.POINTER(to_type * len(mv))).contents def to_mv(ptr:int, sz:int) -> memoryview: return memoryview(ctypes.cast(ptr, ctypes.POINTER(ctypes.c_uint8 * sz)).contents).cast("B") -def mv_address(mv:memoryview): return ctypes.addressof(ctypes.c_char.from_buffer(mv)) +def mv_address(mv): return ctypes.addressof(ctypes.c_char.from_buffer(mv)) def to_char_p_p(options: list[bytes], to_type=ctypes.c_char): return (ctypes.POINTER(to_type) * len(options))(*[ctypes.cast(ctypes.create_string_buffer(o), ctypes.POINTER(to_type)) for o in options]) -@functools.lru_cache(maxsize=None) +@functools.cache def init_c_struct_t(fields: tuple[tuple[str, ctypes._SimpleCData], ...]): class CStruct(ctypes.Structure): _pack_, _fields_ = 1, fields @@ -280,13 +305,15 @@ def flat_mv(mv:memoryview): return mv if len(mv) == 0 else mv.cast("B", shape=(m # *** tqdm -class tqdm: - def __init__(self, iterable=None, desc:str='', disable:bool=False, unit:str='it', unit_scale=False, total:Optional[int]=None, rate:int=100): +class tqdm(Generic[T]): + def __init__(self, iterable:Iterable[T]|None=None, desc:str='', disable:bool=False, + unit:str='it', unit_scale=False, total:Optional[int]=None, rate:int=100): self.iterable, self.disable, self.unit, self.unit_scale, self.rate = iterable, disable, unit, unit_scale, rate self.st, self.i, self.n, self.skip, self.t = time.perf_counter(), -1, 0, 1, getattr(iterable, "__len__", lambda:0)() if total is None else total self.set_description(desc) self.update(0) - def __iter__(self): + def __iter__(self) -> Iterator[T]: + assert self.iterable is not None, "need an iterable to iterate" for item in self.iterable: yield item self.update(1) @@ -298,9 +325,10 @@ class tqdm: self.n, self.i = self.n+n, self.i+1 if self.disable or (not close and self.i % self.skip != 0): return prog, elapsed, ncols = self.n/self.t if self.t else 0, time.perf_counter()-self.st, shutil.get_terminal_size().columns - if self.i/elapsed > self.rate and self.i: self.skip = max(int(self.i/elapsed)//self.rate,1) + if elapsed and self.i/elapsed > self.rate and self.i: self.skip = max(int(self.i/elapsed)//self.rate,1) def HMS(t): return ':'.join(f'{x:02d}' if i else str(x) for i,x in enumerate([int(t)//3600,int(t)%3600//60,int(t)%60]) if i or x) - def SI(x): return (f"{x/1000**int(g:=math.log(x,1000)):.{int(3-3*math.fmod(g,1))}f}"[:4].rstrip('.')+' kMGTPEZY'[int(g)].strip()) if x else '0.00' + def SI(x): + return (f"{x/1000**int(g:=round(math.log(x,1000),6)):.{int(3-3*math.fmod(g,1))}f}"[:4].rstrip('.')+' kMGTPEZY'[int(g)].strip()) if x else '0.00' prog_text = f'{SI(self.n)}{f"/{SI(self.t)}" if self.t else self.unit}' if self.unit_scale else f'{self.n}{f"/{self.t}" if self.t else self.unit}' est_text = f'<{HMS(elapsed/prog-elapsed) if self.n else "?"}' if self.t else '' it_text = (SI(self.n/elapsed) if self.unit_scale else f"{self.n/elapsed:5.2f}") if self.n else "?" diff --git a/tinygrad_repo/tinygrad/multi.py b/tinygrad_repo/tinygrad/multi.py deleted file mode 100644 index f056e9ae91..0000000000 --- a/tinygrad_repo/tinygrad/multi.py +++ /dev/null @@ -1,180 +0,0 @@ -from __future__ import annotations -import functools, itertools, operator -from tinygrad.helpers import all_same, all_int, dedup, prod, DEBUG, RING, getenv -from tinygrad.dtype import DType -from tinygrad.ops import Ops, MathTrait, UOp -from tinygrad.shape.shapetracker import sint - -def all_reduce(bop: Ops, lbs: list[UOp]) -> list[UOp]: - assert all_int(lbs[0].shape), f"does not support symbolic shape {lbs[0].shape}" - assert all_same([lb.shape[0] for lb in lbs]), "allreduce with uneven shards is undefined" - n_lbs, shape, numel = len(lbs), lbs[0].shape, prod(lbs[0].shape) - # ring allreduce doesn't provide a benefit with only 2 nodes or where number of elements is less than 256k (empirically) - # fallback to naive allreduce to save on kernel dispatch, chunking and reassembling chunks. - use_ring = (RING >= 2 or (n_lbs > 2 and numel > getenv("RING_ALLREDUCE_THRESHOLD", 256_000) and RING >= 1)) - if DEBUG >= 2: print(f"{'RING ALLREDUCE' if use_ring else 'NAIVE ALLREDUCE'} {n_lbs}x{numel} | {lbs[0].dtype}") - if not use_ring: return [functools.reduce(lambda x,y: x.alu(bop, y), [x.copy_to_device(lb.device) for x in lbs]) for lb in lbs] - - factor = next(f for f in [32, 16, 8, 4, 2, 1] if numel % f == 0) - base, left = (numel // factor) // n_lbs, (numel // factor) % n_lbs - chunk_sizes = [(base + 1) * factor] * left + [base * factor] * (n_lbs - left) - acc = 0 - chunks = [(acc, (acc := acc + i)) for i in chunk_sizes if i > 0] - chunked = [[lb.reshape((numel,)).shrink(((s,e),)) for s,e in chunks] for lb in lbs] - - # scatter-reduce - for step in range(n_lbs-1): - for i in range(len(chunks)): - src, dest = (i+step)%n_lbs, (i+step+1)%n_lbs - chunked[dest][i] = chunked[dest][i].alu(bop, chunked[src][i].copy_to_device(chunked[dest][i].device, force=True)) - - # allgather - for step in range(n_lbs-1): - for i in range(len(chunks)): - src, dest = (i+step-1)%n_lbs, (i+step)%n_lbs - chunked[dest][i] = chunked[src][i].copy_to_device(chunked[dest][i].device, force=True) - - # assemble chunks back - pads = [((s,numel-e),) for s,e in chunks] - return [functools.reduce(operator.add, [c.pad(pad) for pad,c in zip(pads,lb_c)]).reshape(shape) for lb_c in chunked] - -def to_sharded(lbs:list[UOp], axis:int, bounds: tuple[tuple[int, int], ...]) -> list[UOp]: - if DEBUG >= 3 and lbs[0].shape[axis] % len(lbs) != 0: print(f"multi axis uneven: {lbs[0].shape=} {axis=} {len(lbs)=}, bounds={bounds}") - return [lb.shrink(tuple((0,s) if a != axis else bound for a,s in enumerate(lb.shape))) for i, (bound, lb) in enumerate(zip(bounds, lbs))] - -class MultiLazyBuffer(MathTrait): - def __init__(self, lbs:list[UOp], axis:int|None, real:list[bool]|None=None): - assert all(isinstance(x, UOp) for x in lbs) and len(lbs), "all lbs must be LazyBuffers, and we need at least one of them" - assert all_same([x.dtype for x in lbs]), f"all multilazybuffer needs same dtype, getting {[x.dtype for x in lbs]}" - self.lbs, self.axis, self.dtype, self.device, self.real = lbs, axis, lbs[0].dtype, tuple(x.device for x in lbs), real or [True]*len(lbs) - if axis is not None: - splits = list(itertools.accumulate([lb.shape[axis] for lb in lbs], initial=0)) - self.bounds = tuple(zip(splits, splits[1:])) - - @property - def shape(self): return tuple(sum(y.shape[a] for y in self.real_lbs) if a == self.axis else s for a,s in enumerate(self.real_lbs[0].shape)) - - @property - def size(self): return sum(x.size for x in self.real_lbs) - - @property - def real_lbs(self): return [lb for lb,r in zip(self.lbs, self.real) if r] - - def __repr__(self): return f"" - - @staticmethod - def from_sharded(lb:UOp, devices:tuple[str, ...], axis:int|None, bounds:tuple[tuple[int, int], ...]|None): - assert (axis is None) == (bounds is None), "must specify bounds iff axis is specified" - lbs = [lb] * len(devices) - sharded_lbs = [lb.copy_to_device(d) for lb,d in zip(to_sharded(lbs, axis, bounds) if axis is not None and bounds is not None else lbs, devices)] - return MultiLazyBuffer([lb if lb.is_unrealized_unmasked_const() else lb.contiguous(allow_buffer_view=False) for lb in sharded_lbs], axis) - - def copy_to_device(self, device:str) -> UOp: - if self.axis is None: - # if we already have a copy on the device, return that - return next((lb for lb in self.real_lbs if lb.device == device), self.real_lbs[0].copy_to_device(device)) - # copy lbs to device, pad to final shape, and sum - llbs:list[UOp] = [] - for lb,real,(start,end) in zip(self.lbs, self.real, self.bounds): - if not real: continue - pad_arg = tuple((0,0) if a != self.axis else (start, self.bounds[-1][1]-end) for a in range(len(lb.shape))) - llbs.append(lb.copy_to_device(device).pad(pad_arg)) - return functools.reduce(operator.add, llbs) - - # passthroughs - @property - def is_realized(self) -> bool: return all(lb.base.realized is not None for lb in self.real_lbs) - def cast(self, dtype:DType, bitcast:bool=False, allow_buffer_view=True): - return MultiLazyBuffer([x.cast(dtype, bitcast, allow_buffer_view) for x in self.lbs], self.axis, self.real) - def const_like(self, b) -> MultiLazyBuffer: return MultiLazyBuffer([x.const_like(b) for x in self.lbs], self.axis, self.real) - def assign(self, x:MultiLazyBuffer): return MultiLazyBuffer([s.assign(d) for s,d in zip(self.lbs, x.lbs)], self.axis, self.real) - def contiguous(self): return MultiLazyBuffer([x.contiguous() for x in self.lbs], self.axis, self.real) - def clone(self) -> MultiLazyBuffer: return MultiLazyBuffer([lb.clone() for lb in self.lbs], self.axis, self.real) - def detach(self) -> MultiLazyBuffer: return MultiLazyBuffer([lb.detach() for lb in self.lbs], self.axis, self.real) - - # elementwise is simple - def alu(self, op:Ops, *in_srcs:MultiLazyBuffer) -> MultiLazyBuffer: - msrcs = (self,)+in_srcs - assert all(isinstance(x, MultiLazyBuffer) for x in msrcs), f"all buffers must be MultiLazyBuffer {msrcs}" - assert all_same([x.device for x in msrcs]), f"all buffers must have the same device {[x.device for x in msrcs]}" - - # NOTE: they all have to share an axis, we always choose [-1] - axis, bounds = axes[-1] if len(axes := dedup([(x.axis, x.bounds) for x in msrcs if x.axis is not None])) else (None, None) - srcs:list[list[UOp]] = [] - not_all_real = not all(all(mlb.real) for mlb in msrcs) - new_real = [all(transposed) for transposed in zip(*[mlb.real for mlb in msrcs])] if not_all_real else self.real - assert any(new_real), "output contains no real lb" - for mlb in msrcs: - if (mlb.axis == axis and (mlb.axis is None or mlb.bounds == bounds)) or not_all_real: srcs.append(mlb.lbs) - elif mlb.axis is None and axis is not None: - assert bounds is not None - srcs.append(to_sharded(mlb.lbs, axis, bounds)) - else: - assert axis is not None and bounds is not None - srcs.append(to_sharded([mlb.copy_to_device(lb.device) for lb in mlb.lbs], axis, bounds)) - new_real_lbs:dict[int,UOp] = {i:lsrcs[0].alu(op, *lsrcs[1:]) for i,(lsrcs,r) in enumerate(zip(zip(*srcs), new_real)) if r} - # NOTE: const dtype should match real - new_dtype = next(iter(new_real_lbs.values())).dtype - return MultiLazyBuffer([new_real_lbs.get(i, lsrcs[0].const_like(0).cast(new_dtype)) for i,lsrcs in enumerate(zip(*srcs))], axis, new_real) - - def r(self, op:Ops, axis:tuple[int, ...]) -> MultiLazyBuffer: - if self.axis is not None and self.axis in axis: - # all-reduce on sharded axes - reduced_parts = [(x if r else x.const_like(0)).r(op, axis) for x,r in zip(self.lbs, self.real)] - # if all partitions are real, do all_reduce - if all(self.real): return MultiLazyBuffer(all_reduce(op, reduced_parts), None) - # only one partition is real, keep it - return MultiLazyBuffer(reduced_parts, None, self.real) - # reduce on non sharded axes, piecewise is fine. if axis is None this is also correct - return MultiLazyBuffer([x.r(op, axis) for x in self.lbs], self.axis, self.real) - - # *** movement ops *** - - def _shape_to_single_shard(self, shape:tuple[sint, ...], lb:UOp) -> tuple[sint, ...]: - return tuple(lb.shape[self.axis] if a == self.axis else s for a,s in enumerate(shape)) - - def reshape(self, arg:tuple[sint, ...]): - if self.axis is None: return MultiLazyBuffer([x.reshape(arg) for x in self.lbs], None, self.real) - assert prod(self.shape) == prod(arg), "reshape must maintain prod(shape)" - arg_acc:list[sint] = list(itertools.accumulate(arg, operator.mul, initial=1)) - # new_axis is the last one that preserves prod(prior to new_axis) and must not move items between shards - # todo: what to do about shrinking to self.shape[self.axis]==1 len(self.real_lbs)==1? - new_axis = len(arg_acc) - arg_acc[::-1].index(prod(self.shape[:self.axis])) - 1 - assert all(prod(lb.shape[self.axis:])%prod(arg[new_axis+1:])==0 for lb in self.lbs), f"reshape cannot move items between shards {self=} {arg=}" - lbs = [x.reshape(tuple(s if a!=new_axis else prod(x.shape[self.axis:])//prod(arg[new_axis+1:]) for a,s in enumerate(arg))) for x in self.lbs] - return MultiLazyBuffer(lbs, new_axis, self.real) - - def pad(self, arg:tuple[tuple[sint, sint], ...]): - assert self.axis is None or arg[self.axis] == (0,0) or not all(self.real), f"padding not supported for {arg=}" - # pad on shard axis -> fill others with zeros and set real to all True - if self.axis is not None and arg[self.axis] != (0,0): - # pad back to whole axis, remove real mask - assert all(arg[i] == (0, 0) for i in range(len(self.shape)) if i != self.axis), "cannot pad sharded and non-sharded axis at the same time" - dim, bound = sum(lb.shape[self.axis] for lb in self.lbs), self.bounds[self.real.index(True)] - assert arg[self.axis] == (bound[0], dim-bound[1]), "can only pad to whole axis" - return MultiLazyBuffer([x if r else x.const_like(0) for x,r in zip(self.lbs, self.real)], self.axis) - return MultiLazyBuffer([x.pad(arg) for x in self.lbs], self.axis, self.real) - - def expand(self, arg:tuple[sint, ...]): - # NOTE: this assert isn't needed, sharded axis can have dim 1 - assert self.axis is None or arg[self.axis] == self.shape[self.axis], f"expand not supported on sharded axis {arg=}" - return MultiLazyBuffer([x.expand(self._shape_to_single_shard(arg, x)) for x in self.lbs], self.axis, self.real) - - def permute(self, arg:tuple[int, ...]): - # all permutes supported! - return MultiLazyBuffer([x.permute(arg) for x in self.lbs], arg.index(self.axis) if self.axis is not None else None, self.real) - - def shrink(self, arg:tuple[tuple[sint, sint], ...]): - assert self.axis is None or arg[self.axis] == (0, self.shape[self.axis]) or arg[self.axis] in self.bounds, f"shrinking not supported for {arg=}" - if self.axis is not None and arg[self.axis] in self.bounds and arg[self.axis] != (0, self.shape[self.axis]): - assert all(arg[i] == (0, s) or i == self.axis for i,s in enumerate(self.shape)), "cannot shrink sharded and non-sharded axis at the same time" - # NOTE: shrink on the shard axis is only allowed when result is a single partition, denoted by the new real - idx = self.bounds.index(arg[self.axis]) - # zero out other lbs to not create lb reference - return MultiLazyBuffer([lb if i==idx else lb.const_like(0) for i,lb in enumerate(self.lbs)], self.axis, [i==idx for i in range(len(self.lbs))]) - return MultiLazyBuffer([x.shrink(tuple((0, x.shape[self.axis]) if a == self.axis else s for a,s in enumerate(arg))) for x in self.lbs], - self.axis, self.real) - - def stride(self, arg:tuple[int, ...]): - assert self.axis is None or arg[self.axis] == 1, "flipping not supported on sharded axis" - return MultiLazyBuffer([x.stride(arg) for x in self.lbs], self.axis, self.real) diff --git a/tinygrad_repo/tinygrad/nn/__init__.py b/tinygrad_repo/tinygrad/nn/__init__.py index 088b45df5a..b813995010 100644 --- a/tinygrad_repo/tinygrad/nn/__init__.py +++ b/tinygrad_repo/tinygrad/nn/__init__.py @@ -1,6 +1,7 @@ from __future__ import annotations import math -from tinygrad.tensor import Tensor, dtypes +from tinygrad.tensor import Tensor +from tinygrad.dtype import dtypes from tinygrad.device import is_dtype_supported from tinygrad.helpers import prod, make_tuple, flatten from tinygrad.nn import optim, state, datasets # noqa: F401 @@ -298,11 +299,15 @@ class RMSNorm: print(norm(t).numpy()) ``` """ - def __init__(self, dim:int, eps=1e-6): self.eps, self.weight = eps, Tensor.ones(dim) + def __init__(self, dim:int, eps=1e-6, elementwise_affine=True): + self.eps = eps + self.weight = Tensor.ones(dim) if elementwise_affine else None def _norm(self, x:Tensor) -> Tensor: return x * (x.square().mean(-1, keepdim=True) + self.eps).rsqrt() - def __call__(self, x:Tensor) -> Tensor: return self._norm(x.float()).cast(x.dtype) * self.weight + def __call__(self, x:Tensor) -> Tensor: + x = self._norm(x.float()).cast(x.dtype) + return x if self.weight is None else x * self.weight class Embedding: """ @@ -322,7 +327,7 @@ class Embedding: if not hasattr(self, 'arange'): self.arange = Tensor.arange(self.vocab_sz, requires_grad=False, device=self.weight.device).unsqueeze(-1) big_shp = idx.shape+(self.vocab_sz, self.embed_sz) arange, idx, vals = self.arange.expand(big_shp), idx.reshape(idx.shape+(1, 1)).expand(big_shp), self.weight.expand(big_shp) - return (arange == idx).mul(vals).sum(-2, acc_dtype=vals.dtype) + return (arange == idx).mul(vals).sum(-2, dtype=vals.dtype) class LSTMCell: """ diff --git a/tinygrad_repo/tinygrad/nn/optim.py b/tinygrad_repo/tinygrad/nn/optim.py index db1d84b345..e6736bca70 100644 --- a/tinygrad_repo/tinygrad/nn/optim.py +++ b/tinygrad_repo/tinygrad/nn/optim.py @@ -31,14 +31,16 @@ class Optimizer: Performs a single optimization step. """ Tensor.realize(*self.schedule_step()) + def schedule_step(self) -> list[Tensor]: """ Returns the tensors that need to be realized to perform a single optimization step. """ - assert Tensor.training, ( + if not Tensor.training: raise RuntimeError( f"""Tensor.training={Tensor.training}, Tensor.training must be enabled to use the optimizer. - help: Consider setting Tensor.training=True before calling Optimizer.step().""") return self.schedule_step_with_grads([unwrap(t.grad) for t in self.params])+self.params+self.buffers + def schedule_step_with_grads(self, grads:list[Tensor]) -> list[Tensor]: raise NotImplementedError class OptimizerGroup(Optimizer): @@ -52,7 +54,7 @@ class OptimizerGroup(Optimizer): def zero_grad(self): [o.zero_grad() for o in self.optimizers] def schedule_step(self) -> list[Tensor]: return [x for o in self.optimizers for x in o.schedule_step()] -# LARS is essentially just trust ratio to SGD so if we just set the trust coeff 0.0 its just standard SGD. +# LARS is essentially just trust ratio to SGD so if we just set the trust coeff 0.0 it's just standard SGD. def SGD(params: list[Tensor], lr=0.001, momentum=0.0, weight_decay=0.0, nesterov=False, classic=False): """ Stochastic Gradient Descent (SGD) optimizer with optional momentum and weight decay. @@ -73,30 +75,30 @@ class LARS(Optimizer): def __init__(self, params:list[Tensor], lr=0.001, momentum=0.9, weight_decay=1e-4, nesterov=False, classic=True, tcoef=0.001): super().__init__(params, lr) self.momentum, self.wd, self.nesterov, self.classic, self.tcoef = momentum, weight_decay, nesterov, classic, tcoef - self.b = [Tensor.zeros(*t.shape, dtype=t.dtype, device=t.device, requires_grad=False) for t in self.params] if self.momentum else [] + self.b = [Tensor.zeros(*t.shape, dtype=dtypes.float32, device=t.device, requires_grad=False).contiguous() for t in self.params] \ + if self.momentum else [] def schedule_step_with_grads(self, grads:list[Tensor]) -> list[Tensor]: for i, (t, g) in enumerate(zip(self.params, grads)): - # contiguous is needed since the grads can allegedly form a "diamond" - # TODO: fix this in lazy.py - g = g.contiguous() if self.tcoef != 0: r1 = t.detach().square().sum().sqrt() r2 = g.square().sum().sqrt() - r = (r1 > 0).where((r2 > 0).where(self.tcoef * r1 / (r2 + self.wd * r1), 1.0), 1.0) + r:Tensor|float = (r1 > 0).where((r2 > 0).where(self.tcoef * r1 / (r2 + self.wd * r1), 1.0), 1.0) else: r = 1.0 g = g + self.wd * t.detach() # classic momentum does post learning rate update if self.classic: g = g * r * self.lr if self.momentum: - self.b[i].assign(self.momentum * self.b[i] + g) # NOTE: self.b[i] is zero on the first run, no if required + # TODO: this contiguous is required for correctness because self.b[i] becomes a non contiguous view + # the scheduler should detect this and just insert contiguous + self.b[i].assign(self.momentum * self.b[i].contiguous() + g) # NOTE: self.b[i] is zero on the first run, no if required g = (g + self.momentum * self.b[i]) if self.nesterov else self.b[i] # popular momentum does pre learning rate update if not self.classic: g = g * r * self.lr t.assign((t.detach() - g).cast(t.dtype)) return self.b -# LAMB is essentially just the trust ratio part of LARS applied to Adam/W so if we just set the trust ratio to 1.0 its just Adam/W. +# LAMB is essentially just the trust ratio part of LARS applied to Adam/W so if we just set the trust ratio to 1.0 it's just Adam/W. def AdamW(params: list[Tensor], lr=0.001, b1=0.9, b2=0.999, eps=1e-8, weight_decay=0.01): """ AdamW optimizer with optional weight decay. @@ -140,7 +142,7 @@ class LAMB(Optimizer): if not self.adam: r1 = t.detach().square().sum().sqrt() r2 = up.square().sum().sqrt() - r = Tensor.where(r1 > 0, Tensor.where(r2 > 0, r1 / r2, 1.0), 1.0) + r: Tensor|float = Tensor.where(r1 > 0, Tensor.where(r2 > 0, r1 / r2, 1.0), 1.0) else: r = 1.0 t.assign((t.detach() - self.lr * r * up).cast(t.dtype)) diff --git a/tinygrad_repo/tinygrad/nn/state.py b/tinygrad_repo/tinygrad/nn/state.py index 0830d5049c..9ab16ca738 100644 --- a/tinygrad_repo/tinygrad/nn/state.py +++ b/tinygrad_repo/tinygrad/nn/state.py @@ -1,19 +1,19 @@ import json, pathlib, zipfile, pickle, tarfile, struct, functools, io +from collections import OrderedDict from typing import Union, Optional, Any, Callable, BinaryIO, Iterable from tinygrad.tensor import Tensor from tinygrad.dtype import dtypes from tinygrad.helpers import prod, argsort, DEBUG, Timing, CI, unwrap, GlobalCounters, tqdm, round_up, T from tinygrad.shape.view import strides_for_shape -from tinygrad.multi import MultiLazyBuffer class TensorIO(io.RawIOBase, BinaryIO): def __init__(self, t: Tensor): - if len(t.shape) != 1 or t.dtype != dtypes.uint8: raise ValueError("Tensor must be 1d and of dtype uint8!") + if t.ndim != 1 or t.dtype != dtypes.uint8: raise ValueError("Tensor must be 1d and of dtype uint8!") self._position, self._tensor = 0, t def readable(self) -> bool: return True def read(self, size: int = -1) -> bytes: - if (buf:=super().read(size)) is None: raise ValueError("io.RawIOBase.read returned None") # only happens, if readinto returns None (never) + if (buf:=super().read(size)) is None: raise ValueError("io.RawIOBase.read returned None") # only happens if readinto returns None (never) return buf def readinto(self, buffer: Any) -> int: data = self._tensor[self._position:self._position+len(buffer)].data() @@ -43,14 +43,14 @@ def accept_filename(func: Callable[[Tensor], T]) -> Callable[[Union[Tensor, str, @accept_filename def safe_load_metadata(t:Tensor) -> tuple[Tensor, int, dict[str, Any]]: """ - Loads a .safetensor file from disk, returning the data, metadata length, and metadata. + Loads a .safetensor file, returning the source tensor, data start position, and metadata. """ data_start = int.from_bytes(t[0:8].data(), "little") + 8 return t, data_start, json.loads(t[8:data_start].data().tobytes()) def safe_load(fn:Union[Tensor, str, pathlib.Path]) -> dict[str, Tensor]: """ - Loads a .safetensor file from disk, returning the state_dict. + Loads a .safetensor file, returning the `state_dict`. ```python state_dict = nn.state.safe_load("test.safetensor") @@ -63,7 +63,7 @@ def safe_load(fn:Union[Tensor, str, pathlib.Path]) -> dict[str, Tensor]: def safe_save(tensors:dict[str, Tensor], fn:str, metadata:Optional[dict[str, Any]]=None): """ - Saves a state_dict to disk in a .safetensor file with optional metadata. + Saves a `state_dict` to disk in a .safetensor file with optional metadata. ```python t = Tensor([1, 2, 3]) @@ -76,7 +76,7 @@ def safe_save(tensors:dict[str, Tensor], fn:str, metadata:Optional[dict[str, Any headers[k] = {'dtype': inverse_safe_dtypes[v.dtype], 'shape': list(v.shape), 'data_offsets':[offset, offset+v.nbytes()]} offset += v.nbytes() j = json.dumps(headers, separators=(',', ':')) - j += "\x20"*((8-len(j)%8)%8) + j += "\x20"*(round_up(len(j),8)-len(j)) pathlib.Path(fn).unlink(missing_ok=True) t = Tensor.empty(8+len(j)+offset, dtype=dtypes.uint8, device=f"disk:{fn}") t[0:8].bitcast(dtypes.int64).assign([len(j)]) @@ -85,10 +85,9 @@ def safe_save(tensors:dict[str, Tensor], fn:str, metadata:Optional[dict[str, Any # state dict -from collections import OrderedDict def get_state_dict(obj, prefix:str='', tensor_type=Tensor) -> dict[str, Tensor]: """ - Returns a state_dict of the object, with optional prefix. + Returns a `state_dict` of the object, with optional prefix. ```python exec="true" source="above" session="tensor" result="python" class Net: @@ -110,6 +109,7 @@ def get_state_dict(obj, prefix:str='', tensor_type=Tensor) -> dict[str, Tensor]: elif isinstance(obj, dict): for k,v in obj.items(): state_dict.update(get_state_dict(v, f"{prefix}{str(k)}.", tensor_type)) return state_dict + def get_parameters(obj) -> list[Tensor]: """ ```python exec="true" source="above" session="tensor" result="python" @@ -124,9 +124,9 @@ def get_parameters(obj) -> list[Tensor]: """ return list(get_state_dict(obj).values()) -def load_state_dict(model, state_dict:dict[str, Tensor], strict=True, verbose=True, consume=False) -> None: +def load_state_dict(model, state_dict:dict[str, Tensor], strict=True, verbose=True, consume=False, realize=True) -> list[Tensor]: """ - Loads a state_dict into a model. + Loads a `state_dict` into a model. Return the loaded Tensors. ```python class Net: @@ -140,7 +140,9 @@ def load_state_dict(model, state_dict:dict[str, Tensor], strict=True, verbose=Tr ``` """ start_mem_used = GlobalCounters.mem_used - with Timing("loaded weights in ", lambda et_ns: f", {(B:=(GlobalCounters.mem_used-start_mem_used))/1e9:.2f} GB loaded at {B/et_ns:.2f} GB/s"): + ret = [] + with Timing("loaded weights in ", + lambda et_ns: f", {(B:=(GlobalCounters.mem_used-start_mem_used))/1e9:.2f} GB loaded at {B/et_ns:.2f} GB/s", enabled=verbose): model_state_dict = get_state_dict(model) if DEBUG >= 1 and len(state_dict) > len(model_state_dict): print("WARNING: unused weights in state_dict", sorted(list(state_dict.keys() - model_state_dict.keys()))) @@ -151,16 +153,23 @@ def load_state_dict(model, state_dict:dict[str, Tensor], strict=True, verbose=Tr continue if v.shape != state_dict[k].shape: raise ValueError(f'Shape mismatch in layer `{k}`: Expected shape {v.shape}, but found {state_dict[k].shape} in state dict.') - if isinstance((mlb:=v.lazydata), MultiLazyBuffer): - if isinstance(state_dict[k].lazydata, MultiLazyBuffer): v.replace(state_dict[k]).realize() - else: v.replace(state_dict[k].shard(mlb.device, mlb.axis)).realize() - else: v.replace(state_dict[k].to(v.device)).realize() + if isinstance(v.device, tuple): + if isinstance(state_dict[k].device, tuple): v.replace(state_dict[k]) + else: v.replace(state_dict[k].shard(v.device, v.lazydata.axis)) + else: v.replace(state_dict[k].to(v.device)) + if realize: v.realize() if consume: del state_dict[k] + ret.append(v) + return ret @accept_filename def tar_extract(t: Tensor) -> dict[str, Tensor]: """ - Extracts files from a tar archive and returns them as dictionary of names (keys) and tensors (values). + ```python + tar_extract(fn: Tensor | str | Path) -> dict[str, Tensor] + ``` + + Extracts files from a tar archive and returns them as a dictionary of names (keys) and tensors (values). ```python tensors = nn.state.tar_extract(Tensor(pathlib.Path("archive.tar"))) @@ -174,7 +183,11 @@ def tar_extract(t: Tensor) -> dict[str, Tensor]: @accept_filename def torch_load(t:Tensor) -> dict[str, Tensor]: """ - Loads a torch .pth file from disk. + ```python + torch_load(fn: Tensor | str | Path) -> dict[str, Tensor] + ``` + + Loads a torch .pth file, returning the `state_dict`. ```python state_dict = nn.state.torch_load("test.pth") @@ -195,8 +208,8 @@ def torch_load(t:Tensor) -> dict[str, Tensor]: if tuple(permute_indexes) != tuple(range(len(permute_indexes))): intermediate_shape = tuple([shape_strides[x][0] for x in argsort(permute_indexes)]) assert tuple([shape_strides[i][1] for i in argsort(permute_indexes)]) == strides_for_shape(intermediate_shape), "nonpermutable strides" - if DEBUG >= 3: print(f"WARNING: this torch load is slow. CLANG to permute {intermediate_shape} with {permute_indexes}") - assert storage[1] != dtypes.bfloat16, "can't CLANG permute BF16" + if DEBUG >= 3: print(f"WARNING: this torch load is slow. to permute {intermediate_shape} with {permute_indexes}") + assert storage[1] != dtypes.bfloat16, "can't permute BF16" # TODO: find a nice way to support all shapetracker on disktensors ret = ret.to(None).reshape(intermediate_shape).permute(permute_indexes) @@ -292,13 +305,14 @@ def ggml_data_to_tensor(t: Tensor, n: int, ggml_type: int) -> Tensor: @accept_filename def gguf_load(tensor: Tensor) -> tuple[dict, dict[str, Tensor]]: """ - Loads a gguf file from a tensor. + Loads a .gguf file, returning the `kv_data` and `state_dict`. ```python - fn = "Meta-Llama-3-8B-Instruct.Q4_0.gguf" - gguf_tensor = Tensor.empty(os.stat(fn).st_size, dtype=dtypes.uint8, device=f"disk:{fn}").to(Device.DEFAULT) - kv_data, state_dict = gguf_load(gguf_tensor) + gguf_tensor = Tensor(pathlib.Path("Meta-Llama-3-8B-Instruct.Q4_0.gguf")).to(Device.DEFAULT) + kv_data, state_dict = nn.state.gguf_load(gguf_tensor) ``` + + NOTE: The provided tensor must be on a device that supports execution. """ reader, kv_data, state_dict = io.BufferedReader(TensorIO(tensor), 1_000_000), {}, {} def read_unpack(fmt: str, n: int): return struct.unpack(fmt, reader.read(n))[0] diff --git a/tinygrad_repo/tinygrad/ops.py b/tinygrad_repo/tinygrad/ops.py deleted file mode 100644 index d4c1b3a806..0000000000 --- a/tinygrad_repo/tinygrad/ops.py +++ /dev/null @@ -1,1315 +0,0 @@ -from __future__ import annotations -from typing import Any, Optional, Set, Union, Tuple, Callable, cast, TYPE_CHECKING, Type, DefaultDict, Literal, get_args -import sys, time, functools, itertools, math, operator, hashlib, os, types, pickle, pathlib, inspect, weakref -from enum import auto, IntEnum, Enum -from dataclasses import dataclass, field -from collections import defaultdict -from tinygrad.dtype import ConstType, ImageDType, PtrDType, dtypes, DType, truncate -from tinygrad.helpers import ContextVar, all_int, prod, getenv, all_same, Context, partition, temp, unwrap, T, argfix, Metadata, _METADATA, flatten -from tinygrad.helpers import PICKLE_BUFFERS, SPLIT_REDUCEOP, DEBUG -if TYPE_CHECKING: - from tinygrad.shape.shapetracker import ShapeTracker - from tinygrad.device import Buffer - -# wrapper around IntEnum that preserves Enum.__str__ and makes auto() unique across all FastEnum subclasses -class FastEnum(IntEnum): - def __str__(self): return Enum.__str__(self) - @staticmethod - def _generate_next_value_(_, __, ___, last_values): return 1 + max([0, *last_values, *[max(c) for c in FastEnum.__subclasses__()]]) - -class SimpleMathTrait: - # required to implement - def alu(self:T, arg:Ops, *src) -> T: raise NotImplementedError - def const_like(self:T, b:ConstLike) -> T: raise NotImplementedError - - # great functions you get! - def ufix(self, x): return self.const_like(x) if not isinstance(x, MathTrait) else x - def _binop(self, op, x, reverse): return self.ufix(x).alu(op, self) if reverse else self.alu(op, self.ufix(x)) - def logical_not(self): return self.ne(True) - def neg(self): - if (dtype:=getattr(self, 'dtype')) is None: raise TypeError(f"MathTraits __neg__ requires a dtype, {self=}") - return self.logical_not() if dtype.scalar() == dtypes.bool else self*(-1) - def add(self, x, reverse=False): return self._binop(Ops.ADD, x, reverse) - def mul(self, x, reverse=False): return self._binop(Ops.MUL, x, reverse) - def bitwise_and(self, x, reverse=False): return self._binop(Ops.AND, x, reverse) - def bitwise_or(self, x, reverse=False): return self._binop(Ops.OR, x, reverse) - def xor(self, x, reverse=False): return self._binop(Ops.XOR, x, reverse) - def idiv(self, x, reverse=False): return self._binop(Ops.IDIV, x, reverse) - def sub(self, x, reverse=False): return self.ufix(x).alu(Ops.ADD, -self) if reverse else self.alu(Ops.ADD, self.ufix(-x)) - def div(self, x, reverse=False): return (self.ufix(x)*self.alu(Ops.RECIP)) if reverse else (self*self.ufix(x).alu(Ops.RECIP)) - - def __neg__(self): return self.neg() - - def __add__(self, x): return self.add(x) - def __sub__(self, x): return self.sub(x) - def __mul__(self, x): return self.mul(x) - def __truediv__(self, x): return self.div(x) - def __floordiv__(self, x): return self.idiv(x) - def __and__(self, x): return self.bitwise_and(x) - def __or__(self, x): return self.bitwise_or(x) - def __xor__(self, x): return self.xor(x) - - def __radd__(self, x): return self.add(x, True) - def __rsub__(self, x): return self.sub(x, True) - def __rmul__(self, x): return self.mul(x, True) - def __rtruediv__(self, x): return self.div(x, True) - def __rfloordiv__(self, x): return self.idiv(x, True) - def __rand__(self, x): return self.bitwise_and(x, True) - def __ror__(self, x): return self.bitwise_or(x, True) - def __rxor__(self, x): return self.xor(x, True) - - def __lt__(self, x): return self.alu(Ops.CMPLT, self.ufix(x)) - def __gt__(self, x): return self.ufix(x).alu(Ops.CMPLT, self) - def __ge__(self, x): return (self < x).logical_not() - def __le__(self, x): return (self > x).logical_not() - - def ne(self, x): return self.alu(Ops.CMPNE, self.ufix(x)) - def eq(self, x): return self.ne(x).logical_not() - def __ne__(self, x): return self.ne(x) - # NOTE: __eq__ isn't overridden, and means the same thing as is by default - -class MathTrait(SimpleMathTrait): - # TODO: move to Tensor when new backward is done - def lshift(self, x, reverse=False): return self._binop(Ops.SHL, x, reverse) - def rshift(self, x, reverse=False): return self._binop(Ops.SHR, x, reverse) - def __lshift__(self, x): return self.lshift(x) - def __rshift__(self, x): return self.rshift(x) - def __rlshift__(self, x): return self.lshift(x, True) - def __rrshift__(self, x): return self.rshift(x, True) - - # not in Tensor - def __mod__(self, x): return self.alu(Ops.MOD, self.ufix(x)) - def __rmod__(self, x): return self.ufix(x).alu(Ops.MOD, self) - - def maximum(self, x): return self.alu(Ops.MAX, self.ufix(x)) - def minimum(self, x): return -(-self).maximum(-x) - def where(self, x, y): return self.alu(Ops.WHERE, x, x.ufix(y)) - def threefry(self, seed): return self.alu(Ops.THREEFRY, seed) - def reciprocal(self): return self.alu(Ops.RECIP) - def sqrt(self): return self.alu(Ops.SQRT) - def sin(self): return self.alu(Ops.SIN) - def log2(self): return self.alu(Ops.LOG2) - def exp2(self): return self.alu(Ops.EXP2) - -# the order of these Ops controls the order of the toposort -class Ops(FastEnum): - # uops that aren't rendered - SINK = auto(); CONTIGUOUS = auto(); DETACH = auto(); PRELOAD = auto() # noqa: E702 - - # MetaOps - COPY = auto(); EMPTY = auto(); BUFFER_VIEW = auto() # noqa: E702 - - # blocks in linearizer - BLOCK = auto(); BLOCKSTART = auto(); BLOCKFORK = auto(); BLOCKEND = auto() # noqa: E702 - - # movement ops! - RESHAPE = auto(); PERMUTE = auto(); EXPAND = auto(); PAD = auto(); SHRINK = auto(); STRIDE = auto() # noqa: E702 - - # misc ops - UNROLL = auto(); CONTRACT = auto() # noqa: E702 - VIEW = auto(); DEFINE_GLOBAL = auto(); BUFFER = auto() # noqa: E702 - DEFINE_VAR = auto(); DEFINE_LOCAL = auto(); DEFINE_ACC = auto() # noqa: E702 - VALID = auto(); SPECIAL = auto(); NOOP = auto() # noqa: E702 - - # reduce - REDUCE_AXIS = auto() - - # helper ops - GEP = auto(); VECTORIZE = auto() # noqa: E702 - - # UnaryOps - CAST = auto(); BITCAST = auto(); EXP2 = auto(); LOG2 = auto(); SIN = auto(); SQRT = auto(); RECIP = auto(); NEG = auto() # noqa: E702 - - # load/store before math - LOAD = auto(); STORE = auto() # noqa: E702 - - # early INDEX - INDEX = auto() - - # math ops - WMMA = auto() - - # BinaryOps - ADD = auto(); MUL = auto(); IDIV = auto(); MAX = auto(); MOD = auto(); CMPLT = auto(); CMPNE = auto(); XOR = auto() # noqa: E702 - SHL = auto(); SHR = auto(); OR = auto(); AND = auto(); THREEFRY = auto(); SUB = auto(); FDIV = auto() # noqa: E702 - - # TernaryOps - WHERE = auto(); MULACC = auto() # noqa: E702 - - # assignment ops - ASSIGN = auto() - BIND = auto() - - # control flow ops - BARRIER = auto(); RANGE = auto(); IF = auto(); ENDRANGE = auto(); ENDIF = auto() # noqa: E702 - - # consts last! - VCONST = auto(); CONST = auto() # noqa: E702 - - # device - DEVICE = auto() - -class GroupOp: - Unary = {Ops.EXP2, Ops.LOG2, Ops.SIN, Ops.SQRT, Ops.RECIP, Ops.NEG} - Binary = {Ops.ADD, Ops.MUL, Ops.IDIV, Ops.MAX, Ops.MOD, Ops.CMPLT, Ops.CMPNE, Ops.XOR, Ops.SHL, Ops.SHR, Ops.OR, Ops.AND, Ops.THREEFRY, - Ops.SUB, Ops.FDIV} - Ternary = {Ops.WHERE, Ops.MULACC} - ALU = set.union(Unary, Binary, Ternary) - - Irreducible = {Ops.CONST, Ops.DEFINE_VAR, Ops.SPECIAL, Ops.RANGE} - Movement = {Ops.RESHAPE, Ops.EXPAND, Ops.PERMUTE, Ops.PAD, Ops.SHRINK, Ops.STRIDE} - - # meta ops - Meta = {Ops.COPY, Ops.EMPTY, Ops.BUFFER_VIEW} - Buffer = {Ops.LOAD, Ops.PRELOAD, Ops.STORE, Ops.VALID} - Block = {Ops.BLOCK, Ops.BLOCKEND, Ops.BLOCKFORK, Ops.BLOCKSTART} - - # BinaryOps that can be flipped - Commutative = {Ops.ADD, Ops.MUL, Ops.MAX, Ops.CMPNE, Ops.XOR, Ops.AND, Ops.OR} - - # BinaryOps where f(f(a,b),c) = f(a,f(b,c)) - Associative = {Ops.ADD, Ops.MUL, Ops.AND, Ops.OR} - - # BinaryOps that satisfy f(x,x)=x see https://en.wikipedia.org/wiki/Idempotence - Idempotent = {Ops.OR, Ops.AND, Ops.MAX} - - # do not preserve f(0) = 0 - UnsafePad = {Ops.RECIP, Ops.LOG2, Ops.EXP2, Ops.IDIV} - -# some BUFFER ops can be processed with only a view -view_supported_devices = {"LLVM", "CLANG", "CUDA", "NV", "AMD", "METAL", "QCOM", "DSP", "DISK"} - -# https://en.wikipedia.org/wiki/Identity_element -def identity_element(op:Ops, dt:DType) -> ConstType: return dtypes.as_const({Ops.ADD:0, Ops.MUL:1, Ops.MAX:dtypes.min(dt)}[op], dt) - -def can_pad(u:UOp, edges:dict[UOp, UOp], visisted:set[UOp]) -> bool: - if u.op in GroupOp.UnsafePad: return False - if (len(u.src) == 2 and u.src[0] in edges) or u in visisted: return True - visisted.add(u) - return all(can_pad(x.base, edges, visisted) for x in u.src) - -# With True as the default, this matches the old symbolic behavior -def resolve(x, default:bool=True): - if not isinstance(x, UOp): return bool(x) - assert x.dtype is dtypes.bool, "UOp in resolve must be bool" - # NOTE: generating the text for the exception is expensive, so we do this - return bool(sx.vmin) if (sx:=x.simplify()).vmin == sx.vmax else default - -# smax/smin are replacements for max/min that preserve symbolic -def _suop(lst, uop_fxn, python_fxn): - uops, nums = partition(lst, lambda x: isinstance(x, UOp)) - return ssimplify(functools.reduce(uop_fxn, uops + ([python_fxn(nums)] if nums else []))) -def smax(*lst): return _suop(argfix(*lst), UOp.maximum, max) -def smin(*lst): return _suop(argfix(*lst), UOp.minimum, min) - -def ssimplify(uop): return uop.ssimplify() if isinstance(uop, UOp) else uop -def sym_infer(uop: Union[UOp, int], var_vals: dict[UOp, int]) -> int: return uop.sym_infer(var_vals) if isinstance(uop, UOp) else uop - -# used for UOp and UPat -def pretty_print(x:Any, rep:Callable, srcfn=lambda x: x.src, cache=None, d=0)->str: - def dfs(x:Any, cache:dict): - for s in srcfn(x) or []: - cache.setdefault(s, [len(cache), 0, False])[1] += 1 - if cache[s][1] == 1: dfs(s, cache) - if cache is None: dfs(x, cache:={}) - if (cx:=cache.setdefault(x, [0,0,False]))[2]: return f"{' '*d} x{cx[0]}" - cx[2], srcs = True, ('None' if srcfn(x) is None else ''.join(f'\n{pretty_print(s, rep, srcfn, cache, d+2)},' for s in srcfn(x))) - return f"{' '*d}{f'x{cx[0]}:=' * (cx[1]>1)}{rep(x)}" % srcs - -class UOpMetaClass(type): - ucache:dict[Tuple, weakref.ReferenceType[UOp]] = {} - def __call__(cls, op:Ops, dtype:DType=dtypes.void, src:tuple[UOp,...]=tuple(), arg:Any=None, _buffer=None): - if (wret:=UOpMetaClass.ucache.get(key:=(op, dtype, src, arg), None)) is not None and (ret:=wret()) is not None: return ret - UOpMetaClass.ucache[key] = weakref.ref(created:=super().__call__(*key)) - # NOTE: this will soon be set by Tensor once we remove function.py - if (metadata:=_METADATA.get()) is not None: all_metadata[created] = metadata - return created - -# some uops map to other stuff -buffers:weakref.WeakKeyDictionary[UOp, Buffer] = weakref.WeakKeyDictionary() # this maps BUFFER uops to their device Buffers -all_metadata:weakref.WeakKeyDictionary[UOp, Metadata] = weakref.WeakKeyDictionary() -forced_realize:weakref.WeakSet[UOp] = weakref.WeakSet() - -# NOTE: this should be frozen, but frozen is slower -@dataclass(eq=False, slots=True) -class UOp(MathTrait, metaclass=UOpMetaClass): - op:Ops - dtype:DType = dtypes.void - src:tuple[UOp, ...] = tuple() - arg:Any = None - def __del__(self): - if self.op is Ops.BUFFER and (buffer:=buffers.get(self)) is not None: buffer.ref(-1) - if (k:=(self.op, self.dtype, self.src, self.arg)) in UOpMetaClass.ucache: - del UOpMetaClass.ucache[k] - def __reduce__(self): - args = [self.op, self.dtype, self.src, self.arg] - if (_device_buffer:=self.realized) is not None and PICKLE_BUFFERS: args.extend([_device_buffer]) - return UOp, tuple(args) - def replace(self, **kwargs) -> UOp: - new_args = (kwargs.pop("op", self.op), kwargs.pop("dtype", self.dtype), kwargs.pop("src", self.src), kwargs.pop("arg", self.arg)) - assert len(kwargs) == 0, f"unused kwargs in replace {list(kwargs)}" - if (self.op, self.dtype, self.src, self.arg) == new_args: return self - return UOp(*new_args) - @functools.cached_property - def key(self) -> bytes: - return hashlib.sha256(str((self.op, self.dtype, self.arg)).encode() + b"".join([s.key for s in self.src])).digest() - def __repr__(self): return pretty_print(self, lambda x: f"{type(self).__name__}({x.op}, {x.dtype}, arg={x.argstr()}, src=(%s))") - def argstr(self): return f'({", ".join(map(str, self.arg))})' if self.op is Ops.REDUCE_AXIS else self.arg - - @property - def toposort(self) -> dict[UOp, None]: - def _toposort(u:UOp, cache:dict[UOp, dict[UOp, None]]): - if (cret:=cache.get(u)) is not None: return cret - nodes: dict[UOp, None] = {} - # NOTE: this is a lot faster than the comprehension in parents - for parent in u.src: nodes.update(_toposort(parent, cache)) - nodes[u] = None - cache[u] = nodes - return nodes - return _toposort(self, cache={}) - - @functools.cached_property - def tuplize(self:UOp) -> tuple[int, Any, Optional[DType], Tuple]: - return (self.op.value, self.arg, self.dtype, tuple(x.tuplize for x in self.src)) - - # *** uop shape stuff *** - - @property - def has_st(self) -> bool: return self.op not in {Ops.DEFINE_LOCAL, Ops.DEFINE_GLOBAL, Ops.BUFFER, Ops.CONST, Ops.DEFINE_VAR} - @functools.cached_property - def st(self) -> Optional[ShapeTracker]: - if self.op is Ops.VIEW: return self.arg - if self.op in GroupOp.Movement: return unwrap(self.src[0].st).mop(self.op, self.arg) - # buffer ops can have a non contiguous shapetracker - if self.op in GroupOp.Buffer and len(src_sts:=[unwrap(x.st) for x in self.src if x.op is Ops.VIEW]) != 0: return src_sts[0] - if len(src_sts:=[x.st for x in self.src if x.st is not None]) == 0: return None - assert all_same([x.shape for x in src_sts]), f"UOp parents must have the same shape {self} {[x.shape for x in src_sts]}" - # all other ops have a contiguous shapetracker - from tinygrad.shape.shapetracker import ShapeTracker - return ShapeTracker.from_shape(src_sts[0].reduce(self.axis_arg) if self.op in (Ops.REDUCE_AXIS, Ops.WMMA) else src_sts[0].shape) - @functools.cached_property - def full_shape(self) -> tuple[sint, ...]: - return self.shape if self.op is Ops.VIEW else tuple(smax(x) for x in zip(*[x.full_shape for x in self.src if x.has_st])) - @property - def shape(self) -> tuple[sint, ...]: return unwrap(self.st).shape - @property - def size(self) -> int: return self.arg[-1] if self.op is Ops.BUFFER else unwrap(self.st).size - - # *** uop evaluation *** - - def simplify(self): - with Context(TRACK_MATCH_STATS=0): - return graph_rewrite(self, symbolic) - def ssimplify(self) -> Union[UOp, ConstType]: return ret.arg if (ret:=self.simplify()).op is Ops.CONST else ret - def _eval(self, dtype, expected_type:Type[T]) -> T: - assert self.dtype in dtype, f"eval with wrong dtype {self}" - vmin, vmax = (simple_self:=self.simplify())._min_max - if vmin != vmax: raise ValueError(f"eval failed to be a single number, range is {vmin} to {vmax} in {simple_self.render()}") - assert isinstance(vmin, expected_type), f"vmin is wrong dtype {type(vmin)} != {expected_type}" - return vmin - def __bool__(self): return self._eval((dtypes.bool,), bool) - def __int__(self): return self._eval(dtypes.ints, int) - def __float__(self): return self._eval(dtypes.floats, float) - def substitute(self, dvars:dict[UOp, UOp]): - with Context(TRACK_MATCH_STATS=0): - return graph_rewrite(self, _substitute, dvars, bottom_up=True) - - # *** uop syntactic sugar *** - - @property - def st_arg(self) -> ShapeTracker: - assert self.op in GroupOp.Buffer, f"st_arg called on {self.op}" - ret = self.src[0 if self.op is Ops.VALID else 1] - assert ret.op is Ops.VIEW, f"st_arg trying to return {ret}" - return ret.arg - @property - def const_arg(self) -> ConstType: - match self.base.op: - case Ops.CONST: ret = self.base.arg - case Ops.VIEW: ret = self.base.src[1].const_arg - case op: raise AssertionError(f"const_arg called on {op}") - assert isinstance(ret, get_args(ConstType)), f"const_arg trying to return {ret}" - return ret - @property - def axis_arg(self) -> tuple[int, ...]: - assert self.op in {Ops.REDUCE_AXIS, Ops.WMMA}, f"axis_arg called on {self.op}" - ret = self.arg[1] if self.op is Ops.REDUCE_AXIS else self.arg[7] - assert isinstance(ret, tuple) and all(isinstance(x, int) for x in ret), f"axis_arg trying to return {ret}" - return ret - def sink(self, *srcs:UOp): return UOp(Ops.SINK, dtypes.void, (self,)+srcs) - def detach(self): return UOp(Ops.DETACH, self.dtype, (self,)) - def index(self, idx:UOp, valid:UOp|None=None): return UOp(Ops.INDEX, self.dtype, (self,idx,valid) if valid is not None else (self,idx)) - def const_like(self, b:ConstLike): - if self._device is not None: return UOp.metaop(Ops.CONST, self.shape, self.dtype, self.device, b) - return UOp.const(self.dtype, b) if self.st is None else UOp.const_with_shape(self.dtype, b, self.shape) - def broadcast(self, count:int): - assert self.dtype.count == 1 - if count == 1: return self - return UOp(Ops.VECTORIZE, self.dtype.vec(count), (self,)*count) - def cast(self, dtype:DType, bitcast=False, allow_buffer_view=True): - if self.dtype == dtype: return self # TODO: move this to the scheduler - if bitcast: return self.bitcast(dtype, allow_buffer_view) - if self._device is not None and self._device.startswith("DISK"): raise RuntimeError("CAST isn't supported on DISK") - if getenv("CAST_BEFORE_VIEW", 1) and dtype.itemsize <= self.dtype.itemsize and self is not self.base: - # NOTE: we have to apply the movementops here, we can't use VIEW (yet) - # TODO: move this to the scheduler - ret = self.base.cast(dtype, bitcast) - op_arg = [] - mop = self - while mop is not self.base: - op_arg.append((mop.op, mop.arg)) - mop = mop.src[0] - for op,arg in reversed(op_arg): ret = UOp(op, ret.dtype, (ret,), arg) - return ret - return UOp(Ops.CAST, dtype, (self,)) - def bitcast(self, dtype:DType, allow_buffer_view=True): - if self.can_view() and allow_buffer_view: - if self.dtype.itemsize == dtype.itemsize: output_shape = self.shape - else: - if not self.device.startswith("DISK") or not all_int(self.shape): raise RuntimeError(f"shape changing bitcast not supported on {self}") - # https://pytorch.org/docs/stable/generated/torch.Tensor.view.html - if (self.shape[-1]*self.dtype.itemsize) % dtype.itemsize != 0: raise RuntimeError("unsupported size in bitcast") - output_shape = self.shape[:-1]+((self.shape[-1]*self.dtype.itemsize) // dtype.itemsize,) - return UOp.metaop(Ops.BUFFER_VIEW, output_shape, dtype, self.device, None, (self,)) - return UOp(Ops.BITCAST, dtype, (self,)) - def gep(self, i:Union[tuple[int, ...], int]): - if isinstance(i, int): - # NOTE: these are just shortcuts to not have to create and fold later - if self.op is Ops.VECTORIZE: return self.src[i] - if self.op is Ops.VCONST: return UOp.const(self.dtype.scalar(), self.arg[i]) - if self.op is Ops.CONST: return UOp.const(self.dtype.scalar(), self.arg) - i = (i,) - if (self.dtype.vcount == len(i) and i == tuple(range(len(i)))) or self.dtype == dtypes.void: return self - return UOp(Ops.GEP, self.dtype.scalar().vec(len(i)) if len(i) > 1 else self.dtype.scalar(), (self,), i) - def load(self, *src:UOp, **kwargs): return UOp(Ops.LOAD, src=(self,)+src, **kwargs) - def store(self, *src:UOp, **kwargs): return UOp(Ops.STORE, dtypes.void, (self,)+src, **kwargs) - def alu(self, arg, *src:UOp): - out_dtype = (self, *src)[-1].dtype - if arg in {Ops.CMPLT, Ops.CMPNE}: out_dtype = dtypes.bool.vec(out_dtype.count) if out_dtype.count > 1 else dtypes.bool - return UOp(arg, out_dtype, (self,)+src) - @staticmethod - def const(dtype:DType, b:ConstLike): - if isinstance(b, UOp): return b.unbind()[0] if b.op is Ops.BIND else b - if isinstance(b, tuple) and all_same(b): b = b[0] # doesn't have to be a VCONST if they are all the same - return UOp(Ops.VCONST if isinstance(b, tuple) else Ops.CONST, dtype, arg=dtypes.as_const(b, dtype)) - @staticmethod - def range(dtype:DType, start:sint, end:sint, idx:int): return UOp(Ops.RANGE, dtype=dtype, src=(sint_to_uop(start), sint_to_uop(end)), arg=idx) - def _reduce_op(self, op:Ops, axis:tuple[int, ...]): - axis = tuple(sorted([x for x in axis if resolve(self.shape[x] != 1)])) - return self if len(axis) == 0 else UOp(Ops.REDUCE_AXIS, self.dtype, (self,), (op, axis)) - def r(self, op:Ops, axis:tuple[int, ...]) -> UOp: - new_shape = unwrap(self.st).reduce(axis) - - # TODO: can we split symbolic shape if the reduce axis is not symbolic? - if not SPLIT_REDUCEOP or not all_int(self.shape) or (0 in self.shape) or \ - prod(self.shape) // prod(new_shape) < getenv("REDUCEOP_SPLIT_THRESHOLD", 32768): - return self._reduce_op(op, axis) - - # if there are few globals, make some reduces into globals by splitting into two kernels - # cap output buffer to 2**22: heuristic number of global outputs to achieve max occupancy with enough locals+upcasts for gemm - # ~2**10 should be enough if GROUP is used - # 256 split maximum should be "negligible reduce" for low prod(new_shape), 8 split minimum. - # split is moved to the end to provide maximum locality for the second phase reduce. - self_real_strides = unwrap(self.st).real_strides(ignore_valid=True) - split_candidates = [(i, x) for i in axis for x in range(min(256,2**getenv("REDUCEOP_SPLIT_SIZE",22)//prod(new_shape)),8-1,-1) - if self.shape[i] % x == 0 and self_real_strides[i] != 0] - if not split_candidates: return self._reduce_op(op, axis) - dim_to_split, divisor = split_candidates[0] - splitted_shape = self.shape[:dim_to_split] + (divisor,) + (self.shape[dim_to_split]//divisor,) + self.shape[dim_to_split+1:] - splitted = self.reshape(splitted_shape).permute(tuple([x for x in range(len(splitted_shape)) if x != dim_to_split]+[dim_to_split])) - if DEBUG >= 3: print(f"split {divisor}: {self.shape} -> {splitted.shape} -> {new_shape}") - return splitted._reduce_op(op, axis)._reduce_op(op, (len(new_shape),)).reshape(new_shape) # reduce original axes, then split - def assign(self, x:UOp): return UOp(Ops.ASSIGN, self.dtype, (self,x), None if self.st is None or self.st.contiguous else self.st) - def contiguous(self, allow_buffer_view=True): - if not unwrap(self.st).contiguous or self.size != self.base.size or self.is_unrealized_const(): - if allow_buffer_view and self.can_view(): return self.metaop(Ops.BUFFER_VIEW, self.shape, self.dtype, self.device, None, (self,)) - return self.alu(Ops.CONTIGUOUS) - forced_realize.add(self.base) - return self - - # *** from LazyBuffer *** - - @staticmethod - def const_with_shape(dtype:DType, val:ConstLike, shape:tuple[sint,...]) -> UOp: - from tinygrad.shape.shapetracker import ShapeTracker - return UOp(Ops.VALID, dtypes.bool, (ShapeTracker.from_shape(()).reshape((1,)*len(shape)).expand(shape).to_uop(),)).where(UOp.const(dtype, val), 0) - @staticmethod - def metaop(op:Ops, shape:tuple[sint, ...], dtype:DType, device:str, arg=None, src:tuple[UOp, ...]=()) -> UOp: - from tinygrad.shape.shapetracker import ShapeTracker - if op is Ops.CONST: - # NOTE: we embed device on CONST with a fake BUFFER uop - fake = UOp(Ops.BUFFER, dtype, (UOp(Ops.DEVICE, arg=device),), (-1, 1)) - # NOTE: BIND stays BIND, UOp.const unbinds here - const_uop = arg if isinstance(arg, UOp) else UOp.const(dtype, unwrap(arg)) - return UOp(Ops.VIEW, dtype, (fake, const_uop), ShapeTracker.from_shape(())).reshape((1,)*len(shape)).expand(shape) - # otherwise it's a contiguous st - return UOp(Ops.VIEW, dtype, (UOp.new_buffer(device, (st:=ShapeTracker.from_shape(shape)).size, dtype), UOp(op, dtype, src, arg)), st) - def copy_to_device(self, device:str, force=False, clone:bool=False) -> UOp: - # no COPY - if self.device == device and not clone: return self - # TODO: hack const metaop early here, fix this in multi - if self.is_unrealized_const(): return UOp.metaop(Ops.CONST, (), self.dtype, device, self.const_arg).view(unwrap(self.st)) - # if it's a shrink, do the shrink before the copy with CONTIGUOUS - if prod(self.shape) < prod(self.base.shape): return self.contiguous().copy_to_device(device) - # copy the base and apply the shapetracker on the new device - if not unwrap((src:=self.base).st).contiguous: raise RuntimeError(f"can only copy contiguous {self}") - return UOp.metaop(Ops.COPY, src.shape, src.dtype, device, (device, clone), (src,)).view(unwrap(self.st)) - def clone(self) -> UOp: return self.copy_to_device(self.device, clone=True) - def is_unrealized_const(self): return (s:=self.base).op is Ops.VIEW and len(s.src) == 2 and s.realized is None and s.src[1].op is Ops.CONST - def is_unrealized_unmasked_const(self): return self.is_unrealized_const() and all(v.mask is None for v in unwrap(self.st).views) - def can_view(self): - return (self.st is not None and self._device is not None and self.st.consecutive and not self.is_unrealized_const() and - not isinstance(self.dtype, ImageDType) and self.device.split(":")[0] in view_supported_devices) - @property - def lbs(self): return [self] - @property - def metadata(self): return all_metadata.get(self, None) - @property - def forced_realize(self): return self in forced_realize - - # *** danger zone *** - - # CAUTION: MUTABILITY! - def become(self, u:UOp): - del UOpMetaClass.ucache[(self.op, self.dtype, self.src, self.arg)] - self.op, self.dtype, self.src, self.arg = u.op, u.dtype, u.src, u.arg - - # *** uop movement ops *** - - @property - def base(self) -> UOp: - if self.op in GroupOp.Movement: return self.src[0].base - return self.src[0] if self.op is Ops.VIEW and len(self.src) == 1 and self.src[0].op is not Ops.BUFFER else self - def view(self, new_st:ShapeTracker) -> UOp: - if self.st is None: return UOp(Ops.VIEW, self.dtype.base if not isinstance(self.dtype, ImageDType) else self.dtype, (self,), new_st) - ret = UOp(Ops.VIEW, self.dtype, (self.base,), new_st) - # instant folding rules - if self.st.size == 0 or (new_st.views[-1].mask is not None and any((x[1]-x[0]) == 0 for x in new_st.views[-1].mask)): return ret.const_like(0) - if new_st.contiguous and self.base.shape == new_st.shape: return self.base - return ret - - def _mop(self, op:Ops, arg): - ret = UOp(op, self.dtype, (self,), arg) - if self.st == ret.st: return self # ignore NOOPs, also check ret.st - return ret - - def reshape(self, arg:tuple[sint, ...]): return self._mop(Ops.RESHAPE, arg) - def pad(self, arg:tuple[tuple[sint, sint], ...]): return self._mop(Ops.PAD, arg) - def expand(self, arg:tuple[sint, ...]): return self._mop(Ops.EXPAND, arg) - def permute(self, arg:tuple[sint, ...]): return self._mop(Ops.PERMUTE, arg) - def shrink(self, arg:tuple[tuple[sint, sint], ...]): return self._mop(Ops.SHRINK, arg) - def stride(self, arg:tuple[sint, ...]): return self._mop(Ops.STRIDE, arg) - - # *** uop Buffer stuff *** - - buffer_num = itertools.count(0) - @staticmethod - def new_buffer(device:str, size:int, dtype:DType) -> UOp: - return UOp(Ops.BUFFER, dtype, (UOp(Ops.DEVICE, arg=device),), (next(UOp.buffer_num), size)) - @property - def device(self) -> str: return unwrap(self._device) - @functools.cached_property - def _device(self) -> Optional[str]: - if self.op is Ops.DEVICE: return self.arg - # TODO: why does this fail? - #if self.op is Ops.COPY: return self.arg[0] - return dsrcs[0]._device if len(dsrcs:=[x for x in self.src if x._device is not None]) != 0 else None - @property - def buf_uop(self) -> UOp: - if self.op is Ops.BUFFER: return self - assert self.base.op in {*GroupOp.Buffer, Ops.ASSIGN, Ops.VIEW}, f"buf_uop called on {self.op}" - return self.src[0].buf_uop - def buf_uop_view(self) -> UOp: return self.buf_uop.view(unwrap(self.st)) - @property - def buffer(self) -> Buffer: - if self.base.realized is not None: return self.base.realized - if (ret:=buffers.get(self)) is not None: return ret - if self.op is Ops.VIEW: - assert unwrap(self.st).contiguous, "VIEW only works here if it's contiguous" - return self.src[0].buffer - assert self.op is Ops.BUFFER, f"must be BUFFER {self.op}" - from tinygrad.device import Buffer - buffers[self] = ret = Buffer(self.device, self.size, self.dtype if isinstance(self.dtype, ImageDType) else self.dtype.base) - return ret - @property - def realized(self) -> Optional[Buffer]: - if self.op is Ops.VIEW and len(self.src) == 1 and self.src[0].op is Ops.BUFFER: return buffers[self.src[0]] - return None - @property - def is_realized(self) -> bool: return self.base.realized is not None - - # *** uop Variable stuff *** - - @staticmethod - def variable(name:str, min_val:ConstType, max_val:ConstType, dtype:DType=dtypes.int): - assert not isinstance(min_val, UOp) and not isinstance(max_val, UOp), f"can't create Variable {name} with {min_val}/{max_val}" - return UOp(Ops.DEFINE_VAR, dtype, arg=(name, min_val, max_val)) - @property - def expr(self): - assert self.op is Ops.DEFINE_VAR, f"op is {self.op}, need DEFINE_VAR" - return self.arg[0] - def bind(self, val:int): - assert self.op is Ops.DEFINE_VAR, f"op is {self.op}, need DEFINE_VAR" - assert self.arg[1] <= val and val <= self.arg[2], f"bind {val} not in range [{self.arg[1]}, {self.arg[2]}]" - return UOp(Ops.BIND, self.dtype, (self, self.const_like(val))) - def unbind(self) -> tuple[Variable, int]: - assert self.op is Ops.BIND and self.src[0].op is Ops.DEFINE_VAR and self.src[1].op is Ops.CONST, f"can't unbind {self}" - return self.src[0], self.src[1].arg - @property - def val(self) -> int: return self.unbind()[1] - def vars(self) -> set[UOp]: - bound_vars = set([x for x in self.toposort if x.op is Ops.BIND and x.src[0].op is Ops.DEFINE_VAR]) - bound_var_base = set(x.src[0] for x in bound_vars) - all_vars = set([x for x in self.toposort if x.op is Ops.DEFINE_VAR]) - return bound_vars.union(set([x for x in all_vars if x not in bound_var_base])) - def variables(self) -> list[Variable]: - st_vars: list[set[Variable]] = [x.st_arg.vars() for x in self.toposort if x.op in GroupOp.Buffer] - return sorted(set.union(*st_vars, [x.unbind()[0] if x.op is not Ops.DEFINE_VAR else x for x in self.vars()]), key=lambda v: v.arg) - - # *** uop symbolic stuff *** - - def const_factor(self) -> int: - """largest known int that divides self""" - if self.op is Ops.CONST: return self.arg - if self.op is Ops.VCONST: return math.gcd(*self.arg) - if self.op is Ops.ADD: return math.gcd(self.src[0].const_factor(), self.src[1].const_factor()) - if self.op is Ops.MUL: return self.src[0].arg if self.src[0].op is Ops.CONST else self.src[1].arg if self.src[1].op is Ops.CONST else 1 - return 1 - def divides(self, v) -> UOp|None: - if v==1: return self - if self.op is Ops.CONST: return self.const_like(self.arg//v) if self.arg%v == 0 else None - if self.op is Ops.VCONST: return self.const_like(tuple(x//v for x in self.arg)) if all(x%v == 0 for x in self.arg) else None - if self.op is Ops.ADD: return d0+d1 if (d0:=self.src[0].divides(v)) is not None and (d1:=self.src[1].divides(v)) is not None else None - if self.op is Ops.MUL: - if (d0:=self.src[0].divides(v)) is not None: return d0 * self.src[1] - if (d1:=self.src[1].divides(v)) is not None: return self.src[0] * d1 - return None # generic None if we aren't sure - @property - def vmin(self) -> ConstType: return self._min_max[0] - @property - def vmax(self) -> ConstType: return self._min_max[1] - @functools.cached_property - def _min_max(self) -> tuple[ConstType, ConstType]: - if self.op in GroupOp.Binary and not dtypes.is_float(self.dtype): - (s0_vmin, s0_vmax), (s1_vmin, s1_vmax) = self.src[0]._min_max, self.src[1]._min_max - if self.op is Ops.ADD: return s0_vmin+s1_vmin, s0_vmax+s1_vmax - if self.op is Ops.MUL: return min(vals:=(s0_vmin*s1_vmin, s0_vmin*s1_vmax, s0_vmax*s1_vmin, s0_vmax*s1_vmax)), max(vals) - # SHL/SHR on consts only - if self.op is Ops.SHL and s1_vmin == s1_vmax and all_int(t:=(s0_vmin, s0_vmax, s1_vmin)): return t[0] << t[2], t[1] << t[2] - if self.op is Ops.SHR and s1_vmin == s1_vmax and all_int(t:=(s0_vmin, s0_vmax, s1_vmin)): return t[0] >> t[2], t[1] >> t[2] - if self.op is Ops.MOD and s1_vmin > 0: return 0, s1_vmax-1 - if self.op is Ops.IDIV: - if s1_vmin == s1_vmax: # min/max are equal in a CONST - if s1_vmin > 0: return s0_vmin//s1_vmin, s0_vmax//s1_vmin - if s1_vmin < 0 and s0_vmin >= 0: return -(s0_vmax//-s1_vmin), -(s0_vmin//-s1_vmin) - # don't know exact bounds, but know the sign - if (s0_vmax <= 0 and s1_vmin < 0) or (s0_vmin >= 0 and s1_vmin > 0): return 0, dtypes.max(self.dtype) - if (s0_vmax <= 0 and s1_vmin > 0) or (s0_vmin >= 0 and s1_vmin < 0): return dtypes.min(self.dtype), 0 - if self.op is Ops.MAX: return max(s0_vmin, s1_vmin), max(s0_vmax, s1_vmax) - if self.op is Ops.CMPLT: return (s0_vmax str: - ret = graph_rewrite(self.simplify() if simplify else self, renderer) - return ret.arg if ret.op is Ops.NOOP else str(ret) - -@dataclass(frozen=True) -class KernelInfo: - local_dims: int = 0 # number of local dimensions (this is remapping RANGE to SPECIAL) - upcasted: int = 0 # count that are upcasted (this is remapping RANGE to UNROLL) - dont_use_locals: bool = False # don't use local indexing - -# ***** ops in python ***** - -def safe_exp2(x): - try: return 2 ** x - except OverflowError: return math.inf - -python_alu: dict[Ops, Callable] = { - Ops.LOG2: lambda x: math.log2(x) if x > 0 else -math.inf if x == 0 else math.nan, Ops.EXP2: safe_exp2, - Ops.SQRT: lambda x: math.sqrt(x) if x >= 0 else math.nan, Ops.RECIP: lambda x: 1/x if x != 0 else math.copysign(math.inf, x), - Ops.SIN: lambda x: math.sin(x) if not math.isinf(x) else math.nan, - Ops.NEG: operator.neg, Ops.ADD: operator.add, Ops.SUB: operator.sub, Ops.MUL: operator.mul, Ops.CMPNE: operator.ne, Ops.CMPLT: operator.lt, - Ops.XOR: operator.xor, Ops.OR: operator.or_, Ops.AND: operator.and_, Ops.SHR: operator.rshift, Ops.SHL: operator.lshift, Ops.MAX: max, - Ops.MOD: lambda x,y: abs(int(x))%abs(int(y))*(1,-1)[x<0], Ops.IDIV: lambda x,y: abs(x)//abs(y)*(1,-1)[x*y<0] if y != 0 else 0, - Ops.MULACC: lambda x,y,z: (x*y)+z, Ops.WHERE: lambda x,y,z: y if x else z} - -def exec_alu(op:Ops, dtype:DType, operands, truncate_output=True): - if dtype.count > 1: - return tuple([exec_alu(op, dtype.scalar(), [x[i] if isinstance(x, tuple) else x for x in operands]) for i in range(dtype.count)]) - alu = python_alu[op](*operands) - return truncate.get(dtype, lambda x: x)(alu) if truncate_output else alu - -# ***** uop helpers ***** - -def print_uops(uops:list[UOp]): - for i,u in enumerate(uops): - formatted_parents = [(uops.index(x) if x.op is not Ops.CONST else f"{x.arg}") if x in uops else "--" for x in u.src] - print(f"{i:4d} {str(u.op):20s}: {str(u.dtype):30s} " f"{str(formatted_parents):32s} {u.arg}") - -# ***** pattern matcher ***** - -def get_location() -> tuple[str, int]: - frm = sys._getframe(1) - # find the real frame in the file that has the UPat, TODO: is there a better way to do this? - while frm.f_back is not None and pathlib.Path(frm.f_back.f_code.co_filename).name in {"ops.py", "uopgraph.py", "schedule.py", - "lowerer.py", "cstyle.py", "linearize.py"}: - frm = frm.f_back - return frm.f_code.co_filename, frm.f_lineno -@functools.lru_cache(None) -def lines(fn) -> list[str]: - with open(fn) as f: return f.readlines() - -class UPat(MathTrait): - __slots__ = ("op", "dtype", "arg", "name", "src") - def __init__(self, op:Optional[Union[Ops, tuple[Ops, ...], set[Ops]]]=None, dtype:Optional[Union[DType, tuple[DType, ...]]]=None, - src:Optional[Union[tuple[UPat, ...], list[UPat], UPat]]=None, arg:Any=None, - name:Optional[str]=None, allow_any_len:bool=False, location=None, custom_early_reject:Optional[set[Ops]]=None): - assert op is None or isinstance(op, Ops) or isinstance(op, tuple) or isinstance(op, set), "op must be Ops or tuple of Ops" - self.op: Optional[tuple[Ops, ...]] = (op,) if isinstance(op, Ops) else (tuple(op) if isinstance(op, set) else op) - self.dtype: Optional[tuple[DType, ...]] = (dtype,) if isinstance(dtype, DType) else dtype - self.arg, self.name, self._in_src, self.custom_early_reject = arg, name, src, custom_early_reject - self.src: Any = None - assert self.name != "ctx", "UPat can't be named ctx" - - # try all permutations if it's a list - if isinstance(src, list): self.src = list(itertools.permutations(src)) if not all_same(src) else [src] - # only one if it's a tuple - elif isinstance(src, tuple): self.src = [src] - # repeat if it's a UPat - elif isinstance(src, UPat): self.src = [itertools.repeat(src)] - - self.allowed_len: int = -1 if allow_any_len or isinstance(src, UPat) or src is None else len(src) - self.location = location or get_location() - - if custom_early_reject is not None: self.early_reject = custom_early_reject - else: - upat_match = [src] if isinstance(src, UPat) else ([] if src is None else self.src[0]) - self.early_reject = {pp.op[0] for pp in upat_match if pp.op is not None and len(pp.op) == 1} - - def named(self, name:str): return UPat(self.op, self.dtype, self._in_src, self.arg, name, self.allowed_len == -1, self.custom_early_reject) - - @staticmethod - def any(*src): return UPatAny(src=src) - - @staticmethod - @functools.lru_cache(None) - def var(name:Optional[str]=None, dtype:Optional[Union[DType, tuple[DType, ...]]]=None): return UPat(dtype=dtype, name=name) - @staticmethod - @functools.lru_cache(None) - def cvar(name:Optional[str]=None, dtype:Optional[DType]=None, vec=True): return UPat((Ops.CONST,Ops.VCONST) if vec else Ops.CONST, dtype, name=name) - @staticmethod - def const(dtype:Optional[Union[DType, tuple[DType, ...]]], b:ConstType): return UPat(Ops.CONST, dtype=dtype, arg=b) - - # copied from UOp - def index(self, idx:UPat, valid:Optional[UPat]=None): return UPat(Ops.INDEX, self.dtype, (self,idx,valid) if valid is not None else (self,idx)) - def view(self, st=None, **kwargs): return UPat(Ops.VIEW, self.dtype, (self,), st, **kwargs) - def cast(self, dtype=None): return UPat(Ops.CAST, dtype, (self,)) - def bitcast(self, dtype=None): return UPat(Ops.BITCAST, dtype, (self,)) - def gep(self, i:int): return UPat(Ops.GEP, None, (self,), (i,)) - def load(self, *src:UPat, **kwargs): return UPat(Ops.LOAD, src=(self,)+src, **kwargs) - def store(self, *src:UPat, **kwargs): return UPat(Ops.STORE, dtypes.void, (self,)+src, **kwargs) - def assign(self, x:UPat): return UPat(Ops.ASSIGN, self.dtype, (self,x)) - - def const_like(self, b:ConstLike): return UPat.const(self.dtype, cast(ConstType, b)) - def alu(self, op:Ops, *src:UPat): - asrc = (self,)+src - return UPat(op, dtypes.bool if op in {Ops.CMPLT, Ops.CMPNE} else asrc[-1].dtype, list(asrc) if op in GroupOp.Commutative else asrc) - - def printable(self:UPat) -> str: - try: return lines(self.location[0])[self.location[1]-1].strip() - except FileNotFoundError: return "" - - def __repr__(self): - def rep(x): - form = "UPat(%s, %s, name=%s, dtype=%s, allow_any_len=%s, src=%s)" - return form % (None if x.op is None else ('(%s)'%', '.join(map(str, x.op))), x.arg, repr(x.name), - set(x.dtype) if x.dtype else None, x.allowed_len == 0, "[%s]" if x.src and len(x.src)>1 else "(%s)") - return pretty_print(self, rep, srcfn=lambda x:None if x.src is None else [next(x.src[0])] if isinstance(x.src[0], itertools.repeat) else x.src[0]) - - def match(self:UPat, uop:UOp, store:dict[str, UOp]) -> list[dict[str, UOp]]: - if (self.op is not None and uop.op not in self.op) or \ - (self.name is not None and store.setdefault(self.name, uop) is not uop) or \ - (self.dtype is not None and uop.dtype not in self.dtype and uop.dtype.scalar() not in self.dtype) or \ - (self.arg is not None and self.arg != uop.arg) or \ - (self.allowed_len != -1 and len(uop.src) != self.allowed_len): return [] - if self.src is None: return [store] - res: list[dict[str, UOp]] = [] - for vp in self.src: - stores, new_stores = [store.copy()], [] - for uu, vv in zip(uop.src, vp): - for s in stores: new_stores.extend(vv.match(uu, s)) - stores, new_stores = new_stores, [] - res.extend(stores) - return res - -class UPatAny(UPat): - def match(self:UPat, uop:UOp, store:dict[str, UOp]) -> list[dict[str, UOp]]: - matches = [x.match(uop, store.copy()) for x in self.src[0]] - return flatten([x for x in matches if x is not None]) - -def deconstruct_function(fxn:Callable) -> Tuple: - new_globals = {k:v for k,v in fxn.__globals__.items() if k in fxn.__code__.co_names} - for co in fxn.__code__.co_consts: - if isinstance(co, types.CodeType): new_globals.update({k:v for k,v in fxn.__globals__.items() if k in co.co_names}) - # NOTE: optional round trip through pickle! - assert fxn.__closure__ is None, "closures are not supported in pattern matchers" - ret = fxn.__code__, new_globals, fxn.__name__, fxn.__defaults__ - return pickle.loads(pickle.dumps(ret)) if getenv("TEST_PICKLE") else ret - -class PatternMatcher: - def __init__(self, patterns:list[tuple[UPat, Callable]]): - self.patterns = patterns - # NOTE: use of DefaultDict here is very dangerous! all keys will live for the lifetime of the PatternMatcher! - self.pdict: dict[Ops, list[tuple[UPat, Callable, Set, bool]]] = {} - # uop is required, arg is optional - for p,fxn in self.patterns: - assert p.op is not None - tuple_fxn = fxn if isinstance(fxn, tuple) else deconstruct_function(fxn) - real_fxn = types.FunctionType(*tuple_fxn) - for uop in p.op: self.pdict.setdefault(uop, []).append((p, real_fxn, p.early_reject, 'ctx' in inspect.signature(real_fxn).parameters)) - - def __reduce__(self): return PatternMatcher, ([(x,deconstruct_function(fxn) if fxn.__name__ == "" else fxn) for x,fxn in self.patterns],) - - @functools.lru_cache(None) # pylint: disable=method-cache-max-size-none - def __add__(self, more:PatternMatcher): return PatternMatcher(self.patterns+more.patterns) - - def rewrite(self, uop:UOp, ctx=None) -> UOp|None: - ler = {u.op for u in uop.src} - for p,fxn,early_reject,has_ctx in self.pdict.get(uop.op, []): - if not early_reject.issubset(ler): continue - for match in p.match(uop, {}): - if (ret:=(fxn(ctx=ctx, **match) if has_ctx else fxn(**match))) is not None: return ret - return None - -# *** tracking pattern matcher *** - -TRACK_MATCH_STATS = ContextVar("TRACK_MATCH_STATS", 2 if getenv("VIZ") else 0) -match_stats:dict[UPat, list[Union[int, float]]] = dict() -@dataclass(frozen=True) -class TrackedGraphRewrite: - loc: tuple[str, int] # location that called graph_rewrite - sink: bytes # sanpshot of the graph_rewrite input sink - matches: list[tuple[bytes, Optional[bytes], Optional[UPat], float]] = field(default_factory=list) # before+after snapshot of all the matches -tracked_keys:list[Any] = [] -tracked_ctxs:list[list[TrackedGraphRewrite]] = [] -_name_cnt:dict[str, int] = {} -def track_rewrites(named=False): - def _decorator(func): - def __wrapper(self, *args, **kwargs): - if TRACK_MATCH_STATS >= 2: - if named: _name_cnt[func.__name__] = _name_cnt.get(func.__name__, 0)+1 - tracked_keys.append(f"{func.__name__}_{_name_cnt[func.__name__]}" if named else self) - tracked_ctxs.append([]) - return func(self, *args, **kwargs) - return __wrapper - return _decorator - -class TrackedPatternMatcher(PatternMatcher): - def rewrite(self, uop:UOp, ctx=None) -> UOp|None: - ret = None - ler = {u.op for u in uop.src} - for p,fxn,early_reject,has_ctx in self.pdict.get(uop.op, []): - if p not in match_stats: match_stats[p] = [0,0,0.0,0.0] - st = time.perf_counter() - if not early_reject.issubset(ler): - match_stats[p][2] += time.perf_counter()-st - continue - match_stats[p][1] += 1 - for match in p.match(uop, {}): - if (ret:=(fxn(ctx=ctx, **match) if has_ctx else fxn(**match))) is not None: - match_stats[p][0] += 1 - match_stats[p][3] += (et:=time.perf_counter()-st) - if TRACK_MATCH_STATS >= 3: print(f"{et*1e6:7.2f} us -- ", p.printable()) - if TRACK_MATCH_STATS >= 2 and isinstance(ret, UOp) and len(tracked_ctxs) != 0: - with Context(PICKLE_BUFFERS=0): tracked_ctxs[-1][-1].matches.append((pickle.dumps(uop), pickle.dumps(ret), p, et)) - return ret # NOTE: if it returns None, we keep trying to match - match_stats[p][2] += time.perf_counter()-st - if TRACK_MATCH_STATS >= 2 and len(tracked_ctxs) != 0: - with Context(PICKLE_BUFFERS=0): tracked_ctxs[-1][-1].matches.append((pickle.dumps(uop), None, None, 0)) - return None - -if TRACK_MATCH_STATS: - PatternMatcher = TrackedPatternMatcher # type: ignore - import atexit - @atexit.register - def print_match_stats(): - if TRACK_MATCH_STATS >= 2: - with open(fn:=temp("rewrites.pkl"), "wb") as f: - print(f"rewrote {len(tracked_ctxs)} graphs and matched {sum(len(r.matches) for x in tracked_ctxs for r in x)} times, saved to {fn}") - pickle.dump((tracked_keys, tracked_ctxs), f) - launch_viz("VIZ", temp("rewrites.pkl")) - if getenv("PRINT_MATCH_STATS", 1): - ret = [0,0,0.0,0.0] - for k,v in sorted(list(match_stats.items()), key=lambda x: x[1][2]+x[1][3]): - loc_str = f"{k.location[0].split('/')[-1]}:{k.location[1]}" - if v[1] != 0: print(f"{v[0]:6d} / {v[1]:7d} -- {v[3]*1000.:9.2f} / {(v[2]+v[3])*1000.:9.2f} ms -- {loc_str:15s}", k.printable()) - ret = [x+y for x,y in zip(ret, v)] - print(f"{ret[0]:6d} / {ret[1]:7d} -- {ret[3]*1000.:9.2f} / {(ret[2]+ret[3])*1000.:9.2f} ms -- TOTAL") - -def launch_viz(env_str:str, data:str): - os.environ[env_str] = "0" - os.environ[f"{env_str}_DATA"] = data - if not int(os.getenv("VIZ", "0")) and not int(os.getenv("PROFILE", "0")): - args = ['--kernels', getenv("VIZ_DATA", "")] if getenv("VIZ_DATA", "") else [] - args += ['--profile', getenv("PROFILE_DATA", "")] if getenv("PROFILE_DATA", "") else [] - os.execv(sys.executable, [sys.executable] + [os.path.join(os.path.dirname(__file__), ".", "viz", "serve.py")] + args) - -# *** simple graph rewrite engine *** - -class RewriteContext: - def __init__(self, pm, ctx): - self.pm: PatternMatcher = pm - self.ctx = ctx - self.replace: dict[UOp, UOp] = {} - def rewrite(self, n:UOp) -> UOp: - if (rn := self.replace.get(n)) is not None: return rn - new_src = tuple(map(self.rewrite, n.src)) - new_n = self.pm.rewrite(n, self.ctx) if new_src == n.src else UOp(n.op, n.dtype, new_src, n.arg) - self.replace[n] = ret = n if new_n is None else self.rewrite(new_n) - return ret - def bottom_up_rewrite(self, n:UOp) -> UOp: - if (rn := self.replace.get(n)) is not None: return rn - new_n: UOp|None = n - while new_n is not None: last_n, new_n = new_n, self.pm.rewrite(new_n, self.ctx) - new_src = tuple(map(self.bottom_up_rewrite, last_n.src)) - self.replace[n] = ret = last_n if new_src == last_n.src else self.bottom_up_rewrite(UOp(last_n.op, last_n.dtype, new_src, last_n.arg)) - return ret - -def graph_rewrite(sink:UOp, pm:PatternMatcher, ctx=None, bottom_up=False) -> UOp: - if TRACK_MATCH_STATS >= 2 and not bottom_up and len(tracked_ctxs) != 0: # TODO: make viz work with bottom_up=True - with Context(PICKLE_BUFFERS=0): - tracked_ctxs[-1].append(TrackedGraphRewrite(((frm:=sys._getframe(1)).f_code.co_filename, frm.f_lineno), pickle.dumps(sink))) - return RewriteContext(pm, ctx).bottom_up_rewrite(sink) if bottom_up else RewriteContext(pm, ctx).rewrite(sink) - -# ***** uop type spec ***** - -# this is the matcher for the final rendered UOps -# matcher functions returns True or False (or None to not match) -spec = PatternMatcher([ - (UPat(Ops.DEFINE_GLOBAL, name="x"), lambda x: isinstance(x.dtype, (PtrDType, ImageDType)) and not x.dtype.local), - (UPat(Ops.DEFINE_LOCAL, name="x"), lambda x: isinstance(x.dtype, PtrDType) and x.dtype.local), - (UPat(Ops.DEFINE_ACC, src=(UPat.var("c"),), name="x", allow_any_len=True), - lambda x,c: all(y.op is Ops.RANGE for y in x.src[1:]) and c.dtype == x.dtype), - (UPat(Ops.DEFINE_VAR, src=(), name="x"), lambda x: isinstance(x.arg[1], int) and isinstance(x.arg[2], int)), - - (UPat(Ops.RANGE, src=(UPat(name="x"), UPat(name="y")), name="rng"), lambda rng,x,y: rng.dtype == x.dtype == y.dtype and isinstance(rng.arg, int)), - (UPat(Ops.SPECIAL, src=()), lambda: True), - - # TODO: confirm the args of both of these are shapetrackers - (UPat(Ops.VIEW, dtypes.void, src=()), lambda: True), - (UPat(Ops.VIEW, src=(UPat.var("src"),), name="x"), lambda x,src: src.op is not Ops.STORE and x.dtype == src.dtype), - - (UPat(Ops.VALID, dtypes.bool, (UPat(Ops.VIEW),)), lambda: True), - (UPat(Ops.CONST, name="x"), lambda x: x.dtype == x.dtype.scalar() and (type(x.arg) is type(dtypes.as_const(x.arg, x.dtype)))), - - # early LOAD has a - (UPat(Ops.LOAD, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW))), lambda: True), - (UPat(Ops.LOAD, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW), UPat(Ops.STORE))), lambda: True), - - # early STORE has a - (UPat(Ops.STORE, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW), UPat())), lambda: True), - - # **** new style load/store **** - - # INDEX is used in new style load/store - (UPat(Ops.INDEX, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat())), lambda: True), - - # LOAD takes a - (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)),)), lambda: True), - (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)), UPat((Ops.IF, Ops.BARRIER)))), lambda: True), - (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)), UPat(name="alt"), UPat(dtype=dtypes.bool)), name="ld"), lambda ld,alt: ld.dtype == alt.dtype), - - # STORE takes a - (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat())), lambda: True), - (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat(), UPat(dtype=dtypes.bool))), lambda: True), - (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat(), UPat(Ops.IF))), lambda: True), - - # most ALUs have all matching dtypes, except CMPLT, CMPNE, and WHERE - (UPat(Ops.WHERE, name="w", src=(UPat(dtype=dtypes.bool), UPat(name="x"), UPat(name="y"))), lambda w,x,y: w.dtype == x.dtype == y.dtype), - (UPat((Ops.CMPLT, Ops.CMPNE), dtype=dtypes.bool, src=(UPat(name="x"), UPat(name="y"))), lambda x,y: x.dtype == y.dtype), - # and SHL/SHR, the shift distance can be an int - (UPat((Ops.SHL, Ops.SHR), src=(UPat(name="x"), UPat(name="y")), name="a"), lambda a,x,y: a.dtype == x.dtype and y.dtype in (x.dtype, dtypes.uint)), - (UPat(Ops.IDIV, name="x"), lambda x: None if dtypes.is_int(x.dtype) else False), - (UPat(GroupOp.ALU, name="x"), lambda x: all(x.dtype == y.dtype for y in x.src)), - - (UPat(Ops.ASSIGN, src=(UPat((Ops.DEFINE_ACC, Ops.DEFINE_GLOBAL)), UPat())), lambda: True), - (UPat(Ops.ENDRANGE, dtype=dtypes.void, src=(UPat(Ops.RANGE),)), lambda: True), - - # all WMMA has 3 args, - (UPat(Ops.WMMA, src=(UPat(), UPat(), UPat())), lambda: True), - (UPat(Ops.CONTRACT, name="x"), lambda x: x.dtype.count == prod(y[1] for y in x.arg)), - (UPat(Ops.UNROLL, name="x"), lambda x: x.src[0].dtype.count == prod(y[1] for y in x.arg)), - - # if has a - (UPat(Ops.IF, dtype=dtypes.void, src=(UPat(),)), lambda: True), - (UPat(Ops.IF, dtype=dtypes.void, src=(UPat(), UPat(Ops.BARRIER))), lambda: True), - (UPat(Ops.ENDIF, dtype=dtypes.void, src=(UPat(Ops.IF),)), lambda: True), - - (UPat(Ops.REDUCE_AXIS, name="x"), lambda x: isinstance(x.arg, tuple) and len(x.arg) == 2 and x.arg[0] in {Ops.ADD, Ops.MUL, Ops.MAX}), - (UPat(Ops.GEP, src=(UPat(name="src"),), name="gep"), lambda gep,src: gep.dtype == src.dtype.scalar()), - (UPat(Ops.VECTORIZE, name="x"), lambda x: len(x.src)>1 and len(x.src) == x.dtype.count and all(x.dtype == y.dtype.vec(len(x.src)) for y in x.src)), - (UPat((Ops.BITCAST, Ops.CAST), src=(UPat(),), name="x"), lambda x: x.arg is None), - (UPat(Ops.BARRIER, dtypes.void, src=UPat(Ops.STORE, allow_any_len=True)), lambda: True), # NOTE: all pointers must be local - - # NOTE: for testing, we let sinks be anything - #(UPat(UOps.SINK, src=UPat(UOps.STORE)), lambda: True), - (UPat(Ops.SINK, dtypes.void), lambda: True), - (UPat(Ops.NOOP), lambda: True), - - # PTX LOAD/STORE - (UPat((Ops.LOAD, Ops.STORE), src=(UPat(dtype=dtypes.int64),), allow_any_len=True), lambda: True), -]) - -def type_verify(uops:list[UOp]): - for i,u in enumerate(uops): - if not spec.rewrite(u): - print_uops(uops) - raise RuntimeError(f"UOp verification failed at {i} on {u.op} {u.dtype} {len(u.src)} {[x.op for x in u.src]} {u.arg}") - -# *** most of symbolic lives here now *** - -def split_uop(x:UOp, sep:Ops): - if x.op is sep: - for s in x.src: yield from split_uop(s, sep) - else: yield x - -def div_and_mod_folding(x: UOp, c: int, which: Literal[Ops.MOD, Ops.IDIV], split_rem: bool=False) -> UOp|None: - # simplify x // c or x % c, None means no change, c must be > 0 - assert c > 0 - if x.dtype.count > 1: return None - # simple cancel div/mod case - if (q:=x.vmin//c) == (x.vmax//c): - if which is Ops.MOD: return x - q*c - return x.const_like(q) - - svars, factors, quotients, remainders, gcd, div, const, offset, something_changed = [], [], [], [], c, 1, 0, 0, False - for u in split_uop(x, Ops.ADD): - if u.op is Ops.MOD and which is Ops.MOD and u.src[1].op is Ops.CONST and u.src[1].arg%c == 0: - u = u.src[0] - something_changed = True - v: UOp = u.divides(f:=u.const_factor()) - q, r = divmod(f, c) - if r==0 or ((which is Ops.MOD or split_rem or u.op is Ops.CONST) and r!=f): something_changed = True - offset += r*v.vmin - if u.op is Ops.CONST: const += f - else: # div is the smallest common divisor of all terms - if f > 1 and c % f == 0 and (div == 1 or div > f): div = f - gcd = math.gcd(r, gcd) - factors.append(f); svars.append(v); quotients.append(q); remainders.append(r) # noqa: E702 - - lbound = ubound = offset = offset % c - # we can fold if the expression has only one non-constant term and this term can only take on two values - if len(svars)==1 and (v:=svars[0]).vmax-v.vmin == 1: - r = (offset+remainders[0])%c - offset%c - offset -= r * v.vmin - if which is Ops.MOD: return r*v + offset - return (factors[0]-r)//c * v + (const-offset)//c - - # a//c = (a-a%c)/c, if we can fold a%c, we can fold a//c - # within a mod we can freely subtract multiples of c, we use this to see if a is congruent to an expression whose vmin/vmax are between 0 and c - for (r, v) in zip(remainders, svars): - if r > c//2: - if (lbound := lbound + (r:=r-c) * (v.vmax-v.vmin)) < 0: break - elif (ubound := ubound + r * (v.vmax-v.vmin)) >= c: break - offset -= r * v.vmin # determine what the new offset would be - else: # vmin/vmax of the remainder is between 0 and c, we can remove the mod/div - remainders = [min(r, r-c, key=abs) for r in remainders] - if which is Ops.MOD: return functools.reduce(operator.add, [r*v for r,v in zip(remainders,svars)], x.const_like(offset)) - return functools.reduce(operator.add, [(f-r)//c * v for f,r,v in zip(factors, remainders,svars)], x.const_like((const-offset)//c)) - - if gcd != 1: something_changed = True - if not something_changed: - if which is Ops.IDIV and (1 < div < c) and (newx:=div_and_mod_folding(x, div, Ops.IDIV)) is not None: return newx//(c//div) - return None - quo, rem = x.const_like(const//c), x.const_like((const%c)//gcd) - for q,r,f,v in zip(quotients, remainders, factors, svars): - if which is Ops.IDIV and (not split_rem) and r!=0: - rem += f//gcd * v - else: - rem += r//gcd * v - quo += q * v - - if which is Ops.MOD: return gcd*(rem % (c//gcd)) + const%gcd - return rem//(c//gcd)+quo - -def lt_folding(x:UOp, c:int) -> UOp|None: - p, np = partition(split_uop(x, Ops.ADD), lambda u: u.const_factor() == 1) - if np and (d:=math.gcd(*[u.const_factor() for u in np], c)) > 1 and 0 <= sum(u.vmin for u in p) and sum(u.vmax for u in p) < d: - return cast(UOp, functools.reduce(operator.add, np).divides(d))<(c//d) - return None - -def fold_unrolled_divs(divs:UOp): - # div pattern in unrolled arange - # example: (x//4+(x+1)//4+(x+2)//4+(x+3)//4 -> x - add_chain, denominator, seen_const, ans = list(split_uop(divs, Ops.ADD)), None, [], None - for u in add_chain: - if not (u.op is Ops.IDIV and u.src[1].op is Ops.CONST): return None - if denominator is None: denominator = u.src[1].arg - if denominator != u.src[1].arg: return None - # assumed CONST is the last of an ADD - if (s0:=u.src[0]).op is Ops.ADD and s0.src[1].op is Ops.CONST and s0.src[1].op is Ops.CONST: - seen_const.append(s0.src[1].arg) - s0 = s0.src[0] - else: seen_const.append(0) - if ans is None: ans = s0 - if ans is not s0: return None - if denominator is None: return None - # the first (denominator-len(seen_const)) terms may have been folded to 0 already - for i in range(denominator-len(seen_const)): - if ans is not None and 0 <= ans.vmin and ans.vmax + i < denominator: seen_const.append(i) - return ans if ans is not None and sorted(seen_const)==list(range(denominator)) else None - -def canonicalize_simplex(X:UOp) -> UOp|None: - # (X := a0*x0 + a1*x1 + ...) > 0 is equivalent to x0 + x1 + ... > 0 if xi >= 0 and ai > 0 for ints. - # returns x0 + x1 + ... in such case, or None if not - changed, ret = False, [] - for u in split_uop(X, Ops.ADD): - # assumed the const is the last src of MUL - if u.op is Ops.MUL and u.src[1].op is Ops.CONST and u.src[1].arg > 0: - changed = True - u = u.src[0] - if not (u.op in GroupOp.Irreducible and u.vmin >= 0): return None - ret.append(u) - return functools.reduce(operator.add, ret) if changed else None - -def is_increasing(f:UOp) -> bool: - # is f a monotonically increasing function regards its input - if f.op in GroupOp.Irreducible: return True - if f.op is Ops.ADD: return is_increasing(f.src[0]) and is_increasing(f.src[1]) - if f.op in (Ops.MUL, Ops.IDIV) and f.src[1].op is Ops.CONST and f.src[1].arg >= 0: return is_increasing(f.src[0]) - return False # False if not sure - -def parse_valid(valid:UOp) -> tuple[UOp, bool, int]: - # if it's X <= c, returns X, True, c - # if it's X >= c, returns X, False, c - - # (X < c).ne(True) -> X >= c - if valid.op is Ops.CMPNE and valid.src[1].op is Ops.CONST and valid.src[1].arg == 1 and \ - (s0:=valid.src[0]).op is Ops.CMPLT and s0.src[1].op is Ops.CONST: return s0.src[0], False, s0.src[1].arg - # X < c -> X <= c-1 - if valid.op is Ops.CMPLT and valid.src[1].op is Ops.CONST: return valid.src[0], True, valid.src[1].arg-1 - raise ValueError(f"not able to parse {valid=}") - -def uop_given_valid(valid:UOp, uop:UOp) -> UOp|None: - # return None if valid is always False, otherwise the simplified uop (might be the same as input) - - # first, parse valid into {expr: (lower_bound, upper_bound)} - bounds:DefaultDict[UOp, list[Optional[ConstType]]] = defaultdict(lambda: [None, None]) - for stmt in split_uop(valid, Ops.AND): - try: expr, is_upper, c = parse_valid(stmt) - except ValueError: return uop # give up if we cannot parse the valid - bounds[expr][int(is_upper)] = c - - # simplify uop given that valid is True - for expr,v in bounds.items(): - # some expr has lower bound > upper bound -> valid is an empty set and we return None - if v[0] is not None and v[1] is not None and v[0] > v[1]: return None - - # every candidate is a set of contrained UOp based on valid, and if every item in a set simplifies the uop into a same output, we rewrite uop - candidates = [] - if expr.op is Ops.ADD and v[0] == 1 and all(u.op in GroupOp.Irreducible for u in split_uop(expr, Ops.ADD)): - # if the constraint is a simplex: X0 + X1 + ... > 0, we can check if all Xi > 0 simplify into the same output - candidates.append([(Xi, UOp.variable("fake", 1, Xi.vmax, Xi.dtype)) for Xi in split_uop(expr, Ops.ADD)]) - # try checking the whole clause - if expr in uop.toposort: - candidates.append([(expr, UOp.variable("fake", expr.vmin if v[0] is None else v[0], expr.vmax if v[1] is None else v[1], expr.dtype))]) - - for candidate in candidates: - # if every branch in candidate gives the same simplified uop, we can rewrite the uop - newuops = [uop.substitute({X:newX}).simplify().substitute({newX:X}).simplify() for X,newX in candidate] - if uop.op is Ops.VECTORIZE and len(uop.src) == 2: - if all_same([uops.src[0] for uops in newuops]): uop = uop.replace(src=(newuops[0].src[0], uop.src[1])) - if all_same([uops.src[1] for uops in newuops]): uop = uop.replace(src=(uop.src[0], newuops[0].src[1])) - elif all_same(newuops): uop = newuops[0] - - return uop - -def _valid_priority(v: UOp, valids:list[UOp]): - # we want valid that's in other valids' parents to be first, so it's more likely the other valids get simplified - try: return sum(-1 if parse_valid(v)[0] in other.toposort else 0 for other in valids) - except ValueError: return 0 - -def simplify_valid(valid:UOp) -> UOp|None: - ret:list[UOp] = [] - something_changed = False - valids = list(split_uop(valid, Ops.AND)) - for stmt in sorted(valids, key=lambda v: _valid_priority(v, valids)): - ret.append(newstmt if ret and (newstmt:=uop_given_valid(functools.reduce(operator.and_, ret), stmt)) is not None else stmt) - if ret[-1] is not stmt: something_changed = True - return functools.reduce(operator.and_, ret) if something_changed else None - -def max_var_const(x:UOp, c1:UOp, c2:UOp): - if x.vmin >= 0: return x*c1 if c1.arg >= c2.arg else x*c2 - if x.vmax <= 0: return x*c2 if c1.arg >= c2.arg else x*c1 - -def sint_to_uop(x:sint, dtype:DType=dtypes.int) -> UOp: return UOp.const(dtype, x) if isinstance(x, int) else x - -symbolic_simple = PatternMatcher([ - # ** self folding ** - (UPat.var("x") + 0, lambda x: x), # x+0 -> x - (UPat.var("x") * 1, lambda x: x), # x*1 -> x - (UPat.var("x") // UPat.var("x"), lambda x: x.const_like(1)), # x//x -> 1 - (UPat.var("x") // 1, lambda x: x), # x//1 -> x - (UPat.var("x") // -1, lambda x: -x), # x//-1 -> -x - (UPat.var("x") / UPat.var("x"), lambda x: x.const_like(1)), # x/x -> 1 - ((UPat.var("x") * UPat.var("x2")) / UPat.var("x2"), lambda x,x2: x), # (x*x2)/x2 -> x - ((UPat.var() % UPat.var("y")).named("base") % UPat.var("y"), lambda base,y: base), # (x%y)%y = -> x%y (rewritten with base for speed) - (UPat.var("x")%UPat.cvar("c")+(UPat.var("x")//UPat.cvar("c"))*UPat.cvar("c"), lambda x,c: x), # (x%c)+(x//c)*c = x - ((UPat.var("x")//UPat.cvar("c1"))*UPat.cvar("c3")+UPat.var("x")%UPat.cvar("c1")*UPat.cvar("c2"), - lambda x,c1,c2,c3: x*c2 if c1.arg*c2.arg==c3.arg else None), # (x%c1)*c2+(x//c1)*c3 = x*c2 if c1*c2==c3 - (UPat.var("x", dtype=dtypes.bool) & UPat.cvar("c", vec=False), lambda x,c: x if c.arg else c), - (UPat.var("x", dtype=dtypes.bool) | UPat.cvar("c", vec=False), lambda x,c: c if c.arg else x), - (UPat(GroupOp.Idempotent, src=(UPat.var("x"), UPat.var("x"))), lambda x: x), - (UPat.var("x", dtype=dtypes.bool).logical_not().logical_not(), lambda x: x), - (UPat.var("x", dtype=dtypes.bool).where(UPat.const(dtypes.bool, True), UPat.const(dtypes.bool, False)), lambda x: x), - # ** zero folding ** - (UPat.var("x") < UPat.var("x"), lambda x: UOp.const(dtypes.bool.vec(x.dtype.count), False)), # x < x -> False - (UPat.var("x", dtype=dtypes.ints) != UPat.var("x", dtype=dtypes.ints), - lambda x: UOp.const(dtypes.bool.vec(x.dtype.count), False)), # x != x -> False (only ints) - # x*0 -> 0 or 0*x -> 0 - # if x is nan or inf it should render the nan value. - # NOTE: this can be wrong for loaded NaN - (UPat.var("x") * 0, lambda x: x.const_like(float("nan") if isinstance(x.arg, float) and (math.isnan(x.arg) or math.isinf(x.arg)) else 0)), - # ** constant folding ** - (UPat(GroupOp.ALU, name="a", src=UPat((Ops.VCONST, Ops.CONST))), lambda a: a.const_like(exec_alu(a.op, a.dtype, [x.arg for x in a.src], False))), - # bool MUL is AND, ADD/MAX is OR. prevents other rules to rewrite bool ADD/MUL incorrectly - (UPat.var('x', dtype=dtypes.bool) * UPat.var('y', dtype=dtypes.bool), lambda x,y: x&y), - (UPat.var('x', dtype=dtypes.bool) + UPat.var('y', dtype=dtypes.bool), lambda x,y: x|y), - (UPat.var('x', dtype=dtypes.bool).maximum(UPat.var('y', dtype=dtypes.bool)), lambda x,y: x|y), - # *** cast *** - (UPat(Ops.CAST, name="root", src=UPat.cvar("c")), lambda root, c: root.const_like(c.arg)), - (UPat(Ops.CAST, name="root"), lambda root: root.src[0] if root.dtype == root.src[0].dtype else None), -]) - -symbolic = symbolic_simple+PatternMatcher([ - # ** COMMUTATIVE flipping ** - (UPat(GroupOp.Commutative, name='x'), lambda x: x.replace(src=x.src[::-1]) if x.src[1].tuplize < x.src[0].tuplize else None), - # group like - ((UPat.var("x") + UPat.var("y")) + UPat.var("x") * UPat.cvar("c"), lambda x,y,c: (x+x*c)+y), - # ** boolean algebra ** - (UPat.var("x") | (UPat.var("x") & UPat.var()), lambda x: x), # x|(x&y) -> x - # ** combine terms ** - (UPat.var("x") * UPat.cvar("c0") + UPat.var("x") * UPat.cvar("c1"), lambda x,c0,c1: x*(c0+c1)), # (x*c0)+(x*c1) -> x*(c0+c1) - (UPat.var("x") + UPat.var("x") * UPat.cvar("c"), lambda x,c: x*(c+1)), # (x+x*c)-> x*(c+1) - (UPat.var("x") + UPat.var("x"), lambda x: x*2), # (x+x)-> x*2 - ((UPat.var("x") / UPat.var("x2")) / UPat.var("x3"), lambda x,x2,x3: x/(x2*x3)), # (x/x2)/x3 -> x/(x2*x3) - (-1 * (UPat.var("x") + UPat.cvar("c")), lambda x,c: (-x)+(-c)), # -(x+c) -> -x + -c - # a conditional with the same results either way is a noop, also fold const conditionals - (UPat.var().where(UPat.var("val"), UPat.var("val")), lambda val: val), - (UPat.cvar("gate", vec=False).where(UPat.var("c0"), UPat.var("c1")), lambda gate, c0, c1: c0 if gate.arg else c1), - # alu of two where with same conds can combine, only do if true branch or false branch is const - (UPat(GroupOp.Binary, name="alu", src=(UPat.var("c").where(UPat.var("t"), UPat.var("f")), UPat.var("c").where(UPat.var("tt"), UPat.var("ff")))), \ - lambda alu,c,t,tt,f,ff: c.where(t.alu(alu.op, tt), f.alu(alu.op, ff)) if t.op == tt.op == Ops.CONST or f.op == ff.op == Ops.CONST else None), - # ALU min==max -> CONST (slow!) - (UPat(GroupOp.ALU, name="x"), lambda x: x.const_like(x.vmin) if x.vmin == x.vmax else None), - # max folding - (UPat.maximum(UPat.var("x"), UPat.var("y")), lambda x,y: x if x.vmin >= y.vmax else y if x.vmax <= y.vmin else None), - # TODO: why does this rule break beautiful_mnist? - #((UPat.var("x")+UPat.var("z")).maximum(UPat.var("y")+UPat.var("z")), lambda x,y,z: x.maximum(y) + z), - ((UPat.var("x")*UPat.cvar("c1")).maximum(UPat.var("x")*UPat.cvar("c2")), max_var_const), - # ** two stage ALU folding ** - *((UPat.var("x").alu(op, UPat.cvar("c1")).alu(op, UPat.cvar("c2")).named("f"), - lambda f,x,c1,c2: x.alu(f.op,c1.alu(f.op,c2))) for op in GroupOp.Associative), - ((UPat.cvar("c0") + UPat.var("x")) < UPat.cvar("c1"), lambda x,c0,c1: x<(c1-c0)), # c0 + x < c1 -> x < c1 - c0 - ((UPat.var("x") // UPat.cvar("c1")) // UPat.cvar("c2"), lambda x,c1,c2: x//(c1*c2)), # (x//c1)//c2 -> x//(c1*c2) - # ** lt ** - # c0*x 0 and c1.arg > 0 else None), - # c0*x 0 else None), - # ** move add/mul consts to end (NOTE: this is still happening before constant folding) ** - (UPat(Ops.ADD, src=(UPat.var("x"), UPat.cvar("c1"))) + UPat.var("y"), lambda x,c1,y: (x+y)+c1), - (UPat(Ops.MUL, src=(UPat.var("x"), UPat.cvar("c1"))) * UPat.var("y"), lambda x,c1,y: (x*y)*c1), - # *** rules from symbolic *** - # unrolled arange div folding - (UPat(Ops.ADD, name="divs", src=[UPat(), UPat(Ops.IDIV)]), fold_unrolled_divs), - # generic lt folding - (UPat.var("x", dtypes.sints) 0 - # not x < 1 -> X > 0 - ((UPat.var("x", dtypes.ints)<1).ne(True), lambda x: (newx<1).ne(True) if (newx:=canonicalize_simplex(x)) is not None else None), - # ** div ** - # div folding - ((UPat.var("x")//UPat.cvar("c") + UPat.cvar("a"))//UPat.cvar("d"), lambda x,c,a,d: (x+a*c)//(c*d)), # (x//c+a)//d -> (x+a*c)//(c*d) - (UPat.var("x", dtypes.sints) // UPat.cvar("c", vec=False), lambda x,c: div_and_mod_folding(x,c.arg,Ops.IDIV) if 0 < c.arg else None), - # ** mod ** - # mod folding - (UPat.var("x") % UPat.cvar("c", vec=False), lambda x,c: div_and_mod_folding(x,c.arg,Ops.MOD) if 0 < c.arg else None), -]) - - -symbolic_flat = symbolic+PatternMatcher([ - # ** combine terms (opinionated) ** - (-1 * (UPat.var("x") + UPat.var("y")), lambda x,y: (-x)+(-y)), # -(x+y) -> -x + -y - # (x+y)*c -> x*c+y*c. only for int, float has inf*0=nan issue - ((UPat.var("x", dtypes.ints) + UPat.var("y")) * UPat.cvar("c"), lambda x,y,c: x*c+y*c), -]) - -_substitute = PatternMatcher([(UPat(tuple(Ops), name="x"), lambda ctx,x: ctx.get(x,None))]) - -# for debug -syms = { Ops.ADD: "+", Ops.SUB: "-", Ops.IDIV: "//", Ops.MOD: "%", Ops.SHL: "<<", Ops.SHR: ">>", - Ops.MUL: "*", Ops.CMPLT: "<", Ops.CMPNE: "!=", Ops.AND: "&", Ops.OR: "|", Ops.XOR: "^"} -renderer = PatternMatcher([ - (UPat((Ops.DEFINE_VAR, Ops.SPECIAL), name="x"), lambda x: UOp(Ops.NOOP, arg=x.arg[0])), - (UPat(Ops.RANGE, name="x"), lambda x: UOp(Ops.NOOP, arg=f"ridx{x.arg}")), - (UPat(Ops.CONST, name="x"), lambda x: UOp(Ops.NOOP, arg=str(x.arg))), - (UPat(Ops.BIND, src=UPat(Ops.NOOP), name="x"), lambda x: x.src[0]), - (UPat(Ops.NEG, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"(-{x.src[0].arg})")), - (UPat(Ops.MAX, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"max({x.src[0].arg}, {x.src[1].arg})")), - (UPat(Ops.MULACC, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[0].arg}*{x.src[1].arg}+{x.src[2].arg})")), - (UPat(Ops.WHERE, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[1].arg} if {x.src[0].arg} else {x.src[2].arg})")), - (UPat(GroupOp.ALU, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[0].arg}{syms[x.op]}{x.src[1].arg})")), -]) - -# *** what was symbolic.py *** - -sint = Union[int, UOp] -Variable = UOp - -ConstLike = Union[ConstType, Variable, tuple[ConstType, ...]] - -# *** uop swizzling *** - -merge_views = PatternMatcher([(UPat(Ops.VIEW, name="s0").view(name="s1"), lambda s0,s1: s0.replace(arg=s0.st+s1.st))]) - -# push VIEW to loads -view_left = merge_views+PatternMatcher([ - # VIEW before elementwise ops - (UPat({*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.ASSIGN}, name="e").view(name="v"), - lambda e,v: e.replace(src=tuple(s if not s.has_st else s.view(v.st) if s is s.base else s.base.view(s.st+v.st) for s in e.src))), - # early merge VIEW buffer ops - (UPat(GroupOp.Buffer, name="b").view(name="v"), lambda b,v: b.replace(src=tuple((s.st+v.st).to_uop() if s.op is Ops.VIEW else s for s in b.src))), -]) diff --git a/tinygrad_repo/tinygrad/renderer/__init__.py b/tinygrad_repo/tinygrad/renderer/__init__.py index 9bb71dc2d0..24b536ff8d 100644 --- a/tinygrad_repo/tinygrad/renderer/__init__.py +++ b/tinygrad_repo/tinygrad/renderer/__init__.py @@ -1,27 +1,46 @@ from __future__ import annotations -from typing import Optional, Callable -import functools +from typing import Optional, Callable, cast +import functools, math +from enum import Enum, auto from dataclasses import dataclass, field, replace from tinygrad.helpers import to_function_name, dedup, prod -from tinygrad.ops import Ops, UOp, sym_infer, sint, Variable, ssimplify, GroupOp, PatternMatcher +from tinygrad.uop.ops import Ops, UOp, sym_infer, sint, Variable, ssimplify, GroupOp, PatternMatcher from tinygrad.dtype import DType +class OptOps(Enum): + TC = auto(); UPCAST = auto(); UNROLL = auto(); LOCAL = auto() # noqa: E702 + GROUP = auto(); GROUPTOP = auto(); NOLOCALS = auto(); PADTO = auto(); SWAP = auto() # noqa: E702 + def __lt__(self, x:OptOps): return self.value < x.value + +@dataclass(frozen=True, order=True) +class Opt: + op: OptOps + axis: Optional[int] = None + arg: Optional[int | tuple] = None + def __repr__(self): return f"Opt(op={self.op}, axis={self.axis}, arg={self.arg})" + @dataclass(frozen=True) class TensorCore: # D = A * B + C, A is (M x K), B is (K x N), C and D are (M x N) dims: tuple[int,int,int] # N, M, K + threads: int # number of threads that construct the warp + elements_per_thread: tuple[int, int, int] # elements per-thread to load/store from A/B/C dtype_in: DType # dtype for A and B dtype_out: DType # dtype for C and D - threads: list[tuple[int,int]] # list of (TC dim,amt) that construct the warp thread structure - reduce_axes: list[tuple[int,int]] # list of (TC dim,amt) that constructs the shape of the reduce dim - @property - def early_upcast_axes(self) -> list[tuple[int,int]]: # list of (TC dim,amt) that upcasts the threads remainders of dims [0,1] - return [(d,self.dims[d]//sz) for d,sz in [(dim,prod(sz for d,sz in self.threads if d==dim)) for dim in range(2)] if self.dims[d]>sz] - upcast_axes: tuple[list[tuple[int,int]], list[tuple[int,int]], list[tuple[int,int]]] # list of (TC dim,amt) that upcast A, B and C - st1_pattern: Optional[tuple[tuple[tuple[int,int], ...], tuple[tuple[int,int], ...]]] = None # pattern to fix shapetracker for A - st2_pattern: Optional[tuple[tuple[tuple[int,int], ...], tuple[tuple[int,int], ...]]] = None # pattern to fix shapetracker for B - expanded_shape: Optional[tuple[int, ...]] = None - opts_seq: tuple[str,str] = ("UP","LC") # upcast input, local the thread pattern + opts: tuple[str, ...] # ordered tuple of "ux" or "lx" specifing kernel opts to perform. "ux" upcasts dim x and "lx" localizes dim x + swizzle: tuple[Optional[tuple[tuple[int, ...], tuple[int, ...]]], Optional[tuple[tuple[int, ...], tuple[int, ...]]]] = (None, None) + def get_reduce_axes(self): return [(i, 2) for i in range(int(math.log2(self.dims[2])))] + def get_upcast_axes(self): return [opt for opt in self.opts if opt[0] == "u"] + def get_local_axes(self): return [opt for opt in self.opts if opt[0] == "l"] def __str__(self): return "_".join(["WMMA"] + list(map(str, self.dims)) + [self.dtype_in.name, self.dtype_out.name]) + def __post_init__(self): + local_axes, upcast_axes, reduce_axes = len(self.get_local_axes()), len(self.get_upcast_axes()), len(self.get_reduce_axes()) + assert self.dims[0] * self.dims[1] == 2**(local_axes + upcast_axes), ( + f"N({self.dims[0]}) x M({self.dims[1]}) != local({2**local_axes}) x upcast({2**upcast_axes}) with opts({self.opts})") + assert 2**local_axes == self.threads, f"{self.threads} threads construct the warp but found {2**local_axes} in {self.opts}" + assert 2**upcast_axes == self.elements_per_thread[2], ( + f"{self.elements_per_thread[2]} elements from C are processed per thread but found {2**upcast_axes} in {self.opts}") + assert all(len(perm[0]) == local_axes and len(perm[1]) == reduce_axes + upcast_axes for perm in self.swizzle if perm), ( + f"swizzle perm should be of len (({local_axes})({reduce_axes + upcast_axes}))") @dataclass(frozen=True) class Estimates: @@ -43,14 +62,16 @@ class Estimates: if ignore_indexing: for u in uops: if u.op in {Ops.LOAD, Ops.STORE}: - dont_count = dont_count.union(u.src[0].toposort) - if len(u.src) > 2: dont_count = dont_count.union(u.src[2].toposort) + dont_count = dont_count.union(u.src[0].toposort()) + if len(u.src) > 2: dont_count = dont_count.union(u.src[2].toposort()) elif u.op is Ops.IF: - dont_count = dont_count.union(u.src[0].toposort) + dont_count = dont_count.union(u.src[0].toposort()) for u in uops: if u.op is Ops.RANGE: mult_stack.append(mults) - mults *= (u.src[1] - u.src[0]).ssimplify() + mults *= cast(sint, u.src[0].ssimplify()) + # SPECIAL are already counted in mults + mults = mults.substitute({x:x.const_like(0) for x in mults.toposort() if x.op is Ops.SPECIAL}) if isinstance(mults, UOp) else mults elif u.op is Ops.ENDRANGE: mults = mult_stack.pop(-1) elif u.op is Ops.SPECIAL: mults *= u.arg[1] # NOTE: we don't push to the mult_stack here, you can't end these elif u.op is Ops.LOAD: lds += u.dtype.itemsize * mults @@ -64,7 +85,9 @@ class ProgramSpec: name:str src:str device:str + ast:UOp # save the base ast (this is method cache key) uops:Optional[list[UOp]]=None + applied_opts:Optional[list[Opt]]=None mem_estimate:sint=0 # TODO: get this from the load/store uops once min/max are good # filled in from uops (if we have uops) @@ -73,6 +96,7 @@ class ProgramSpec: vars:list[Variable]=field(default_factory=list) globals:list[int]=field(default_factory=list) outs:list[int]=field(default_factory=list) + ins:list[int]=field(default_factory=list) _ran_post_init:bool=False # NOTE: this is needed if you call replace on the Program def __post_init__(self): @@ -81,15 +105,16 @@ class ProgramSpec: for u in self.uops: if u.op is Ops.DEFINE_VAR: self.vars.append(u) if u.op is Ops.DEFINE_GLOBAL: self.globals.append(u.arg) - if u.op is Ops.STORE: self.outs.extend([x.arg for x in u.src[0].toposort if x.op is Ops.DEFINE_GLOBAL]) + if u.op is Ops.STORE: self.outs.extend([x.arg for x in u.src[0].toposort() if x.op is Ops.DEFINE_GLOBAL]) + if u.op is Ops.LOAD: self.ins.extend([x.arg for x in u.src[0].toposort() if x.op is Ops.DEFINE_GLOBAL]) if u.op is Ops.SPECIAL: # NOTE: you have to set local_size and global_size to the base [1,1,1] outside this if u.arg[0][0] == 'i': self.local_size = None special_size = self.local_size if u.arg[0][0] == 'l' else self.global_size - assert special_size is not None - special_size[int(u.arg[0][-1])] = u.arg[1] + if special_size is not None: special_size[int(u.arg[0][-1])] = u.arg[1] self.vars = sorted(self.vars, key=lambda v: v.arg) self.outs = sorted(dedup(self.outs)) + self.ins = sorted(dedup(self.ins)) self._ran_post_init = True @functools.cached_property @@ -112,12 +137,13 @@ class Renderer: has_local: bool = True has_shared: bool = True # NOTE: these two should be in (x,y,z) order to match the max_sizes argument in get_grouped_dims - global_max: Optional[tuple[int, ...]] = (0x8FFFFFFF,) * (3) # TODO: UOps.SPECIAL int32 indexes right now - local_max: Optional[tuple[int, ...]] = (0x8FFFFFFF,) * (3) # TODO: UOps.SPECIAL int32 indexes right now + global_max: Optional[tuple[int, ...]] = (0x8FFFFFFF,) * (3) # TODO: Ops.SPECIAL int32 indexes right now + local_max: Optional[tuple[int, ...]] = (0x8FFFFFFF,) * (3) # TODO: Ops.SPECIAL int32 indexes right now shared_max: int = 32768 tensor_cores: list[TensorCore] = [] + pre_matcher: Optional[PatternMatcher] = None extra_matcher: Optional[PatternMatcher] = None code_for_op: dict[Ops, Callable] = {} def __reduce__(self): return self.__class__, () - def render(self, name:str, uops:list[UOp]) -> str: raise NotImplementedError("needs a renderer") + def render(self, uops:list[UOp]) -> str: raise NotImplementedError("needs a renderer") diff --git a/tinygrad_repo/tinygrad/renderer/cstyle.py b/tinygrad_repo/tinygrad/renderer/cstyle.py index 5ab62c76ee..efbffe1330 100644 --- a/tinygrad_repo/tinygrad/renderer/cstyle.py +++ b/tinygrad_repo/tinygrad/renderer/cstyle.py @@ -1,10 +1,11 @@ -from typing import Dict, Optional, Union, DefaultDict, Literal, Callable, cast -import os, math +from typing import Literal, Callable, cast +import os, math, sys from collections import defaultdict, Counter -from tinygrad.ops import GroupOp, Ops, UOp, PatternMatcher, UPat +from tinygrad.uop.ops import GroupOp, Ops, UOp, PatternMatcher, UPat from tinygrad.helpers import strip_parens, getenv, prod, dedup, AMX from tinygrad.dtype import ImageDType, dtypes, DType, PtrDType from tinygrad.renderer import Renderer, TensorCore +from tinygrad.codegen.devectorizer import no_vectorized_alu base_rewrite = PatternMatcher([ (UPat(Ops.DEFINE_ACC, name="x"), lambda ctx,x: ctx[x.src[0]]), @@ -14,13 +15,15 @@ base_rewrite = PatternMatcher([ (UPat(Ops.WMMA, name="x"), lambda ctx,x: f"__{x.arg[0]}({ctx[x.src[0]]}, {ctx[x.src[1]]}, {ctx[x.src[2]]})"), # r method accesses (UPat(Ops.RANGE, name="x"), - lambda ctx,x: f"for ({ctx.render_dtype(x.dtype)} {ctx[x]} = {ctx[x.src[0]]}; {ctx[x]} < {ctx[x.src[1]]}; {ctx[x]}++) {{"), + lambda ctx,x: f"for ({ctx.render_dtype(x.dtype)} {ctx[x]} = 0; {ctx[x]} < {ctx[x.src[0]]}; {ctx[x]}++) {{"), (UPat(Ops.VECTORIZE, name="x"), lambda ctx,x: f"{ctx.float4.replace('float4', ctx.render_dtype(x.dtype))}" + \ - (f"{{{','.join([ctx[y] for y in x.src])}}}" if ctx.device == "CLANG" else f"({','.join([ctx[y] for y in x.src])})")), + f"{ctx.float4_style[0]}{','.join([ctx[y] for y in x.src])}{ctx.float4_style[1]}"), + (UPat(Ops.CAST, name="x"), lambda ctx,x: + f"__builtin_convertvector({ctx[x.src[0]]}, {ctx.render_dtype(x.dtype)})" if x.dtype.count > 1 and not isinstance(x.dtype, PtrDType) else None), (UPat(Ops.CAST, name="x"), lambda ctx,x: f"({ctx.render_cast(x.dtype, ctx[x.src[0]])})"), (UPat(Ops.BITCAST, name="x"), lambda ctx,x: f"(*(({ctx.buffer_prefix}{ctx.render_dtype(x.dtype)}*)&{ctx[x.src[0]]}))"), - (UPat(Ops.DEFINE_LOCAL, name="x"), lambda ctx,x: f"{ctx.smem_align}{ctx.smem_prefix}{ctx.render_dtype(x.dtype.base)} {ctx[x]}[{x.arg[1]}];"), + (UPat(Ops.DEFINE_LOCAL, name="x"), lambda ctx,x: f"{ctx.smem_align}{ctx.smem_prefix}{ctx.render_dtype(x.dtype.base)} {ctx[x]}[{x.dtype.size}];"), (UPat(Ops.BARRIER), lambda ctx: ctx.barrier), (UPat(Ops.NOOP, name="x"), lambda ctx,x: ctx[x.src[0]]), (UPat(Ops.SPECIAL, name="x"), lambda ctx,x: f"{ctx.code_for_workitem[x.arg[0][0]](x.arg[0][-1])}; /* {x.arg[1]} */"), @@ -40,24 +43,33 @@ base_rewrite = PatternMatcher([ # default const render (UPat(Ops.CONST, name="x"), lambda ctx,x: str(x.arg)), # new load/store - (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var('idx'))), + (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var('idx')), allow_any_len=True), lambda ctx,buf,idx: f"({ctx[buf]}+{strip_parens(ctx[idx]) if idx.arg == Ops.ADD else ctx[idx]})"), - (UPat(Ops.LOAD, src=(UPat.var('bidx'), UPat.var("var"), UPat.var("gate"))), lambda ctx,bidx,var,gate: f"({ctx[gate]}?*{ctx[bidx]}:{ctx[var]})"), + (UPat(Ops.LOAD, src=(UPat(Ops.INDEX, src=(UPat(), UPat(), UPat.var("gate"))).or_casted("bidx"), UPat.var("var")), allow_any_len=True), + lambda ctx,bidx,var,gate: f"({ctx[gate]}?*{ctx[bidx]}:{ctx[var]})"), (UPat(Ops.LOAD, src=(UPat.var('bidx'),), allow_any_len=True), lambda ctx,bidx: f"*{ctx[bidx]}"), (UPat(Ops.STORE, src=(UPat.var('bidx'), UPat.var("var")), allow_any_len=True), lambda ctx,bidx,var: f"*{ctx[bidx]} = {ctx[var]};"), # alu/gep (UPat(GroupOp.ALU, name="x"), lambda ctx,x: ctx.code_for_op[x.op]( *([strip_parens(ctx[v]) if v.op == x.op and x.op in {Ops.ADD, Ops.MUL, Ops.XOR} else ctx[v] for v in x.src]), x.dtype)), (UPat(Ops.GEP, name="x"), lambda ctx,x: ctx[x.src[0]] + \ - (f"[{x.arg[0]}]" if x.src[0].dtype.count > (8 if ctx.device in {"CUDA", "NV"} else 4) or ctx.device == 'CLANG' else f".{'xyzwabcd'[x.arg[0]]}")), + (f"[{x.arg[0]}]" if x.src[0].dtype.count > ctx.gep_arr_threshold else f".{'xyzwabcd'[x.arg[0]]}")), + # custom passes through with format + (UPat((Ops.CUSTOM, Ops.CUSTOMI), name="x"), lambda ctx,x: x.arg.format(*[ctx[y] for y in x.src])), ]) extra_pm = PatternMatcher([ # insert a NOOP before BITCAST to force it to be rendered. not needed on all backends? (UPat(Ops.BITCAST, name="x"), - lambda x: UOp(Ops.BITCAST, x.dtype, (UOp(Ops.NOOP, x.src[0].dtype, x.src),)) if x.src[0].op is not Ops.NOOP else None), + lambda x: UOp(Ops.BITCAST, x.dtype, (UOp(Ops.NOOP, x.src[0].dtype, x.src),)) if x.src[0].op not in {Ops.NOOP, Ops.LOAD, Ops.CUSTOM} else None), # rewrite MAX to CMPLT + WHERE (max function is annoying on many cstyle backends) (UPat(Ops.MAX, name="m"), lambda m: (m.src[0] < m.src[1]).where(m.src[1], m.src[0])), + # devectorize any bools + (UPat((*GroupOp.ALU, Ops.CAST, Ops.BITCAST, Ops.ASSIGN, Ops.INDEX), dtype=dtypes.bool, name="alu"), no_vectorized_alu), + # CAST (from bool) can't be vectorized + (UPat(Ops.CAST, src=(UPat(dtype=dtypes.bool),), name="alu"), no_vectorized_alu), + # WHERE can't be vectorized + (UPat(Ops.WHERE, name="alu"), no_vectorized_alu), ]) def uops_to_dtypes(uops:list[UOp]) -> list[DType]: return dedup(u.dtype for u in uops if not isinstance(u.dtype, (ImageDType, PtrDType))) @@ -71,13 +83,15 @@ class CStyleLanguage(Renderer): smem_prefix_for_cast: bool = True arg_int_prefix: str = "const int" barrier: str = "" - code_for_workitem: dict[Union[Literal["g"], Literal["l"], Literal["i"]], Callable] = {} + code_for_workitem: dict[Literal["g", "l", "i"], Callable] = {} extra_args: list[str] = [] - float4: Optional[str] = None + float4: str|None = None + float4_style: tuple[str, str] = ('(', ')') + gep_arr_threshold: int = 4 type_map: dict[DType, str] = {} infinity: str = "INFINITY" nan: str = "NAN" - code_for_op: Dict = { + code_for_op: dict = { Ops.SQRT: lambda x,dtype: f"sqrt({x})", Ops.RECIP: lambda x,dtype: f"(1/{x})", Ops.NEG: lambda x,dtype: f"-{x}", Ops.EXP2: lambda x,dtype: f"exp2({x})", Ops.LOG2: lambda x,dtype: f"log2({x})", Ops.SIN: lambda x,dtype: f"sin({x})", Ops.AND: lambda a,b,dtype: f"({a}&{b})", Ops.XOR: lambda a,b,dtype: f"({a}^{b})", Ops.OR: lambda a,b,dtype: f"({a}|{b})", @@ -101,15 +115,14 @@ class CStyleLanguage(Renderer): def render_cast(self, dt:DType, val: str) -> str: return f"({self.render_dtype(dt)})({val})" def render_dtype(self, dt:DType, mutable=True) -> str: - if isinstance(dt, ImageDType): - return f"{'write_only' if mutable else 'read_only'} image2d_t" + if isinstance(dt, ImageDType): return f"{'write_only' if mutable else 'read_only'} image2d_t" if isinstance(dt, PtrDType): - return (self.smem_prefix if dt.local and self.smem_prefix_for_cast else self.buffer_prefix) + \ - self.render_dtype(dt.base) + ("*" if isinstance(dt, PtrDType) else "") - return self.type_map.get(scalar:=dt.scalar(), scalar.name) + (str(dt.count) if (dt.count) > 1 else "") + return (self.smem_prefix if dt.local and self.smem_prefix_for_cast else self.buffer_prefix) + self.render_dtype(dt.base) + "*" + if dt.count > 1: return self.type_map.get(scalar:=dt.scalar(), scalar.name).replace(" ", "_") + str(dt.count) + return self.type_map.get(scalar:=dt.scalar(), scalar.name) def __getitem__(self, key): return self.r[key] # hacky helper - def render(self, name:str, uops:list[UOp]) -> str: + def _render(self, uops:list[UOp]) -> tuple[str, list[str], list[tuple[str,tuple[DType,bool]]]]: r: dict[UOp, str] = {} self.r = r @@ -117,8 +130,12 @@ class CStyleLanguage(Renderer): bufs: dict[UOp, tuple[str, tuple[DType, bool]]] = {} kernel = [] depth = 1 - c: DefaultDict[str, int] = defaultdict(int) + c: defaultdict[str, int] = defaultdict(int) + name = "test" for u in uops: + if u.op is Ops.SINK: + if u.arg is not None: name = u.arg.name + continue if u.op in (Ops.DEFINE_GLOBAL, Ops.DEFINE_VAR): r[u] = f"data{u.arg}" if u.op is Ops.DEFINE_GLOBAL else u.arg[0] bufs[u] = (r[u], (u.dtype, False)) @@ -126,15 +143,15 @@ class CStyleLanguage(Renderer): # mark buffers that we store to writable if u.op is Ops.STORE: - for up in u.src[0].toposort: + for up in u.src[0].toposort(): if up.op is Ops.DEFINE_GLOBAL: bufs[up] = (bufs[up][0], (bufs[up][1][0], True)) # naming prefix = None - if u.op is Ops.SPECIAL: - r[u] = u.arg[0] + if u.op is Ops.SPECIAL: r[u] = u.arg[0] + elif u.op is Ops.RANGE: r[u] = f"ridx{u.arg}" else: - prefix = {Ops.RANGE: "ridx", Ops.WMMA: "wmma", Ops.DEFINE_LOCAL: "temp", Ops.CONST: "const", + prefix = {Ops.WMMA: "wmma", Ops.DEFINE_LOCAL: "temp", Ops.CONST: "const", Ops.CAST: "cast", Ops.BITCAST: "cast", Ops.GEP: "gep", Ops.VECTORIZE: "cast", Ops.NOOP: "precast", Ops.INDEX: "bidx", Ops.DEFINE_ACC: "acc", Ops.LOAD: "val"}.get(u.op, "alu") r[u] = f"{prefix}{c[prefix]}" @@ -143,8 +160,8 @@ class CStyleLanguage(Renderer): assert l is not None, f"failed to render {u.op} {u.dtype} {[(x.op,x.dtype) for x in u.src]} {u.arg}" if u.op in {Ops.ENDIF, Ops.ENDRANGE}: depth -= 1 - if u.op in {Ops.CONST, Ops.GEP, Ops.INDEX} or (u.op in {Ops.VECTORIZE, *GroupOp.ALU, Ops.CAST, Ops.BITCAST} - and child_count[u] == 1 and not getenv("EXPAND_SSA")): + if (u.op is not Ops.CAST or u.dtype.vcount == 1) and (u.op in {Ops.CONST, Ops.GEP, Ops.INDEX, Ops.CUSTOMI} or \ + (u.op in {Ops.VECTORIZE, *(GroupOp.ALU-{Ops.WHERE}), Ops.CAST, Ops.BITCAST} and child_count[u] == 1 and not getenv("EXPAND_SSA"))): r[u] = l else: if u.op in {Ops.RANGE, Ops.ASSIGN, Ops.DEFINE_LOCAL} or u.dtype == dtypes.void: @@ -157,15 +174,21 @@ class CStyleLanguage(Renderer): del self.r # NOTE: this relies on bufs dict preserving order - return self.render_kernel(name, kernel, list(bufs.values()), uops) + return (name, kernel, list(bufs.values())) + def render(self, uops:list[UOp]) -> str: return self.render_kernel(*self._render(uops), uops) class ClangRenderer(CStyleLanguage): - device = "CLANG" + device = "CPU" float4 = "(float4)" + float4_style = ('{', '}') + gep_arr_threshold = 0 has_local = False global_max = None infinity = "__builtin_inff()" nan = '__builtin_nanf("")' + amx_tc = [TensorCore(dims=(sz,sz,1), threads=1, elements_per_thread=(sz,sz,sz*sz), dtype_in=dt, dtype_out=dt, swizzle=(None,((),(4,5,6,7,0,1,2,3))), + opts=("u0","u0","u0","u0","u1","u1","u1","u1")) for dt,sz in [(dt, 64 // dt.itemsize) for dt in [dtypes.float]]] + if AMX: tensor_cores = amx_tc # language options buffer_suffix = " restrict" @@ -173,17 +196,17 @@ class ClangRenderer(CStyleLanguage): code_for_op = {**({k:v for k,v in CStyleLanguage.code_for_op.items() if k not in [Ops.EXP2, Ops.SIN, Ops.LOG2]}), Ops.SQRT: lambda x,dtype: f"__builtin_sqrt({x})" if dtype == dtypes.float64 else f"__builtin_sqrtf({x})"} # LLVM legalizes double => half cast on systems that don't support it natively (like x86 cpus without AVX512-FP16) into a compiler-rt libcall. - extra_matcher = PatternMatcher([(UPat.var("x", dtypes.float64).cast(dtypes.float16), lambda x: x.cast(dtypes.float32).cast(dtypes.float16))]) + \ - CStyleLanguage.extra_matcher - - if AMX: - tensor_cores = [TensorCore(dims=(sz,sz,1), threads=[], reduce_axes=[], upcast_axes=([(1,sz)],[(0,sz)],[(1,sz),(0,sz)]), dtype_in=dt, dtype_out=dt) - for dt, sz in [(dt, 64//dt.itemsize) for dt in [dtypes.float]]] + extra_matcher = PatternMatcher([(UPat.var("x", dtypes.float64).cast(dtypes.float16), lambda x: x.cast(dtypes.float32).cast(dtypes.float16)), + (UPat(Ops.SQRT, name="alu"), no_vectorized_alu),]) + CStyleLanguage.extra_matcher + if sys.platform == 'win32': + kernel_prefix = "__attribute__((ms_abi)) " def render_vector_prefix(self, dt:DType) -> str: - return f"typedef {self.render_dtype(dt.scalar())} {self.render_dtype(dt)} __attribute__((aligned({(sz:=dt.itemsize)}),vector_size({sz})));" + # round (down) to power of two (this is actually the default clang behavior) + alignment = 2**int(math.log2(dt.itemsize)) if getenv("ALIGNED", 1) else 1 + return f"typedef {self.render_dtype(dt.scalar())} {self.render_dtype(dt)} __attribute__((aligned({alignment}),vector_size({dt.itemsize})));" - def render_kernel(self, function_name, kernel, bufs, uops, prefix=None) -> str: + def _render_defines(self, uops) -> list[str]: prefix = [self.render_vector_prefix(dt) for dt in uops_to_dtypes(uops) if dt.count > 1] # https://github.com/corsix/amx for name, (N, M, _), dtype_in, _, _, _, _, _ in dedup([uop.arg for uop in uops if uop.op is Ops.WMMA]): @@ -191,11 +214,20 @@ class ClangRenderer(CStyleLanguage): '#define AMX_SET(imm5) __asm("nop\\nnop\\nnop\\n.word (0x201000+(%0<<5)+%1)" : : "i"(17), "i"(imm5) : "memory")', '#define AMX(op, gpr, btf) __asm(".word (0x201000+(%0 << 5)+0%1-((0%1>>4)*6))" : : "i"(op), "r"((unsigned long long)(gpr)+(btf)) : "memory")', ] - prefix += [f"""{(out := self.render_dtype(dtype_in.vec(N*N)))} __{name}({self.render_dtype(dtype_in.vec(N))} data1, {self.render_dtype(dtype_in.vec(M))} data2, {out} data0){{ + # 'static' in C roughly means that function symbol isn't exported. LLVM puts those symbols at the end of object file which allows Clang JIT + # to just jump at the start of a shellcode whithout having to deal with symbols or trampolines at all. This is better than having to inline + # wmma function every time it is called or wasting complexity on a symbol parsing and a memory page on trampoline. + prefix += [f"""static {(out := self.render_dtype(dtype_in.vec(N*N)))} __{name}({self.render_dtype(dtype_in.vec(N))} data1, {self.render_dtype(dtype_in.vec(M))} data2, {out} data0){{ AMX_SET(0);\n for(int ridx0 = 0; ridx0 < 16; ridx0++){{ AMX(4, (int *)(&data0), 0ull<<62 | (ridx0*4ull)<<56 | ridx0*64ull); }} AMX(0, (int *)(&data2), 0ull<<62); AMX(1, (int *)(&data1), 0ull<<62); AMX(12, 0, 0ull); for(int ridx0 = 0; ridx0 < 16; ridx0++){{ AMX(5, (int *)(&data0), 0ull<<62 | (ridx0*4ull)<<56 | ridx0*64ull); }}\n AMX_SET(1);\n return data0;\n}}"""] # noqa: E501 - return super().render_kernel(function_name, kernel, bufs, uops, prefix) + return prefix + def _render_body(self, function_name, kernel, bufs, uops, pref=None) -> str: return super().render_kernel(function_name, kernel, bufs, uops, pref) + def _render_entry(self, function_name:str, bufs:list[tuple[str,tuple[DType,bool]]]) -> str: return "" + + def render_kernel(self, function_name, kernel, bufs, uops, prefix=None) -> str: + defines = '\n'.join(self._render_defines(uops)) + return defines + "\n" + self._render_body(function_name, kernel, bufs, uops, prefix) + "\n" + self._render_entry(function_name, bufs) class OpenCLRenderer(CStyleLanguage): device = "GPU" @@ -208,13 +240,13 @@ class OpenCLRenderer(CStyleLanguage): barrier = "barrier(CLK_LOCAL_MEM_FENCE);" float4 = "(float4)" code_for_workitem = {"g": lambda x: f"get_group_id({x})", "l": lambda x: f"get_local_id({x})", "i": lambda x: f"get_global_id({x})"} - type_map = { dtypes.int8:"char", dtypes.uint8: "uchar", dtypes.uint32: "uint", dtypes.uint16: "ushort", dtypes.uint64: "ulong", + type_map = { dtypes.int8: "char", dtypes.uint8: "uchar", dtypes.uint32: "uint", dtypes.uint16: "ushort", dtypes.uint64: "ulong", dtypes.bfloat16: "ushort" } string_rewrite = PatternMatcher([ (UPat(Ops.BITCAST, name="x"), lambda ctx,x: f"as_{ctx.render_dtype(x.dtype)}({ctx[x.src[0]]})"), # load/store image (OpenCL) - (UPat(Ops.LOAD, dtype=dtypes.float.vec(4), src=(UPat.var('buf').index(UPat.var('idx', dtypes.int.vec(2))), UPat.var("var"), UPat.var("gate"))), + (UPat(Ops.LOAD, dtype=dtypes.float.vec(4), src=(UPat.var('buf').index(UPat.var('idx', dtypes.int.vec(2)), UPat.var("gate")), UPat.var("var"))), lambda ctx,buf,idx,var,gate: f"({ctx[gate]}?read_imagef({ctx[buf]}, smp, {ctx[idx]}):{ctx[var]})"), (UPat(Ops.LOAD, dtype=dtypes.float.vec(4), src=(UPat.var('buf').index(UPat.var('idx', dtypes.int.vec(2))),)), lambda ctx,buf,idx: f"read_imagef({ctx[buf]}, smp, {ctx[idx]})"), @@ -223,17 +255,17 @@ class OpenCLRenderer(CStyleLanguage): ]) + base_rewrite def render_kernel(self, function_name, kernel, bufs, uops, prefix=None) -> str: - if any(uop.dtype == dtypes.half for uop in uops): prefix = (["#pragma OPENCL EXTENSION cl_khr_fp16 : enable"] + (prefix or [])) + if any(uop.dtype.base == dtypes.half for uop in uops): prefix = (["#pragma OPENCL EXTENSION cl_khr_fp16 : enable"] + (prefix or [])) return super().render_kernel(function_name, kernel, bufs, uops, prefix) class IntelRenderer(OpenCLRenderer): device, suffix, kernel_prefix = "GPU", "INTEL", "__attribute__((intel_reqd_sub_group_size(8)))\n" + "__kernel " - tensor_cores = [TensorCore(dims=(8,8,16),threads=[(0,8)],dtype_in=di,dtype_out=do,reduce_axes=[(0,16)],upcast_axes=([(0,16)],[(0,16)],[(1,8)]), - st1_pattern=(((1,0),),((1,2),(1,1),(0,0))),expanded_shape=(8,2,8)) for di,do in [(dtypes.half,dtypes.float),(dtypes.bfloat16,dtypes.float)]] + tensor_cores = [TensorCore(dims=(8,8,16), threads=8, elements_per_thread=(16,16,8), dtype_in=dtypes.half, dtype_out=dtypes.float, + opts=("l0","l0","l0","u1","u1","u1"), swizzle=(((4,5,6),(0,1,2,3,7,8,9)), ((0,1,2),(7,8,9,3,4,5,6))))] string_rewrite = PatternMatcher([ - (UPat(Ops.CAST, dtype=dtypes.bfloat16, src=(UPat.var('x', dtype=dtypes.float))), lambda ctx,x: f"intel_convert_bfloat16_as_ushort({ctx[x[0]]})"), - (UPat(Ops.CAST, dtype=dtypes.float, src=(UPat.var('x', dtype=dtypes.bfloat16))), lambda ctx,x: f"intel_convert_as_bfloat16_float({ctx[x[0]]})"), + (UPat(Ops.CAST, dtype=dtypes.bfloat16, src=(UPat.var('x', dtype=dtypes.float),)), lambda ctx,x: f"intel_convert_bfloat16_as_ushort({ctx[x]})"), + (UPat(Ops.CAST, dtype=dtypes.float, src=(UPat.var('x', dtype=dtypes.bfloat16),)), lambda ctx,x: f"intel_convert_as_bfloat16_float({ctx[x]})"), ]) + OpenCLRenderer.string_rewrite def render_kernel(self, function_name, kernel, bufs, uops, prefix=None) -> str: @@ -247,10 +279,9 @@ class IntelRenderer(OpenCLRenderer): class MetalRenderer(CStyleLanguage): device = "METAL" shared_max = 32768 - tensor_cores = [TensorCore(dims=(8,8,8),threads=[(0,2),(1,4),(0,2),(1,2)],expanded_shape=(2,2,2,2),upcast_axes=([(1,2)],[(1,2)],[(1,2)]), - st1_pattern=(((1,1),(0,1),(1,0),(0,3)),((0,0),(0,2),(1,3),(1,2))),st2_pattern=(((0,0),(1,1),(1,2),(0,2),(1,0)),((0,1),(0,3),(1,3))), - dtype_in=di,dtype_out=do,reduce_axes=[(0,8)]) for di,do in [(dtypes.float,dtypes.float),(dtypes.half,dtypes.float),(dtypes.half,dtypes.half), - (dtypes.bfloat16,dtypes.float),(dtypes.bfloat16,dtypes.bfloat16)]] + tensor_cores = [TensorCore(dims=(8,8,8), threads=32, elements_per_thread=(2,2,2), dtype_in=di, dtype_out=do, opts=("u0","l0","l1","l1","l0","l1"), + swizzle=(((6,1,2,7,4),(8,0,3,5)), ((0,5,6,3,7),(1,2,4,8)))) for di,do in [(dtypes.float,dtypes.float),(dtypes.half,dtypes.float), + (dtypes.half,dtypes.half),(dtypes.bfloat16,dtypes.float),(dtypes.bfloat16,dtypes.bfloat16)]] def __init__(self): self.tensor_cores = MetalRenderer.tensor_cores if hasattr(os, 'uname') and os.uname().machine == "arm64" else [] # language options @@ -290,18 +321,27 @@ class MetalRenderer(CStyleLanguage): return super().render_kernel(function_name, kernel, bufs, uops, prefix) _nms = "xyzwabcdefghijkl" +cuda_tc_opts = ("u0","l0","l0","l1","l1","l1","u1") # shared by all shapes with M=16 N=8 class CUDARenderer(CStyleLanguage): device = "CUDA" global_max = (2147483647, 65535, 65535) local_max = (1024, 1024, 64) shared_max = 49152 - # https://docs.nvidia.com/cuda/parallel-thread-execution/#warp-level-matrix-fragment-mma-16816-float - tensor_cores = [TensorCore(dims=(8,16,16), threads=[(0,2),(0,2),(1,2),(1,2),(1,2)], dtype_in=di, dtype_out=do, expanded_shape=(2,2,2,2,2,2), - st1_pattern=(((1,1),(1,0),(0,2),(0,3),(0,4)),((1,3),(1,5),(1,2),(0,0),(0,1),(1,4))), - st2_pattern=(((1,1),(1,0),(1,4),(0,0),(0,1)),((0,4),(0,2),(1,5),(0,3),(1,3),(1,2))), reduce_axes=[(0,8),(1,2)], - upcast_axes=([(0,8)],[(2,2),(3,2)],[(3,2),(2,2)])) for di, do in ([(dtypes.half,dtypes.float),(dtypes.bfloat16,dtypes.float)])] - def __init__(self, arch:str): self.tensor_cores, self.arch = CUDARenderer.tensor_cores if int(arch[3:]) >= 80 else [], arch + # https://docs.nvidia.com/cuda/parallel-thread-execution/#warp-level-matrix-multiply-accumulate-instructions + tc_81616 = [TensorCore(dims=(8,16,16), threads=32, elements_per_thread=(8,4,4), dtype_in=di, dtype_out=do, opts=cuda_tc_opts, + swizzle=(((6,7,2,3,4),(0,1,9,5,10,8)), ((6,7,9,0,1),(2,3,4,10,5,8)))) for di,do in [(dtypes.half,dtypes.float), (dtypes.bfloat16,dtypes.float), + (dtypes.half,dtypes.half)]] + tc_8168_f16 = [TensorCore(dims=(8,16,8), threads=32, elements_per_thread=(4,2,4), dtype_in=di, dtype_out=do, opts=cuda_tc_opts, + swizzle=(((6,7,2,3,4),(0,1,8,5,9)), ((6,7,8,0,1),(2,3,4,9,5)))) for di,do in [(dtypes.half,dtypes.float), (dtypes.half,dtypes.half)]] + tc_8168_tf32 = [TensorCore(dims=(8,16,8), threads=32, elements_per_thread=(4,2,4), dtype_in=dtypes.float, dtype_out=dtypes.float, opts=cuda_tc_opts, + swizzle=(((5,6,2,3,4),(0,1,8,9,7)), ((5,6,8,0,1),(2,3,4,9,7))))] + + tc_sm80 = tc_81616 + tc_8168_f16 + if getenv("ALLOW_TF32", 0): tc_sm80 += tc_8168_tf32 + tc_sm75 = tc_8168_f16 + def __init__(self, arch:str): + self.tensor_cores, self.arch = CUDARenderer.tc_sm80 if int(arch[3:]) >= 80 else CUDARenderer.tc_sm75 if int(arch[3:]) >= 75 else [], arch def __reduce__(self): return self.__class__, (self.arch,) # language options @@ -310,6 +350,7 @@ class CUDARenderer(CStyleLanguage): smem_prefix_for_cast = False barrier = "__syncthreads();" float4 = "make_float4" + gep_arr_threshold = 8 code_for_workitem = {"g": lambda x: f"blockIdx.{chr(120+int(x))}", "l": lambda x: f"threadIdx.{chr(120+int(x))}", "i": lambda x: f"(blockIdx.{chr(120+int(x))}*blockDim.{chr(120+int(x))}+threadIdx.{chr(120+int(x))})"} code_for_op = { **CStyleLanguage.code_for_op, @@ -334,7 +375,8 @@ class CUDARenderer(CStyleLanguage): if any(dt.scalar() == dtypes.bfloat16 for dt in used_dtypes): prefix.append("#include ") prefix += [self.render_vector_prefix(dt) for dt in used_dtypes if dt.count in (4,8) and dt.scalar() in {dtypes.half, dtypes.bfloat16}] - dt_map = { dtypes.half: "f16", dtypes.bfloat16: "bf16" } + dt_map_in = { dtypes.float: "tf32", dtypes.half: "f16", dtypes.bfloat16: "bf16" } + dt_map_out = { dtypes.float: "f32", dtypes.half: "f16" } for name, (N, M, K), dtype_in, dtype_out, _, _, upcast_axes, _ in dedup([uop.arg for uop in uops if uop.op is Ops.WMMA]): upcast_sizes = [prod(size for _, size in upcast) for upcast in upcast_axes] wmma_dtypes = [self.render_dtype(dtype.vec(size)) for dtype, size in zip([dtype_in, dtype_in, dtype_out], upcast_sizes)] @@ -343,10 +385,11 @@ class CUDARenderer(CStyleLanguage): # mma operands => {c}, {a}, {b}, {c} prefix.append(f"""__device__ {wmma_dtypes[2]} __{name}({wmma_dtypes[0]} a, {wmma_dtypes[1]} b, {wmma_dtypes[2]} c){{ - int *a_pk = (int *)(&a), *b_pk = (int *)(&b);\n asm("mma.sync.aligned.m{M}n{N}k{K}.row.col.f32.{dt_map[dtype_in]}.{dt_map[dtype_in]}.f32" + int *a_pk = (int *)(&a), *b_pk = (int *)(&b), *c_pk = (int *)(&c); + asm("mma.sync.aligned.m{M}n{N}k{K}.row.col.{dt_map_out[dtype_out]}.{dt_map_in[dtype_in]}.{dt_map_in[dtype_in]}.{dt_map_out[dtype_out]}" "{{{", ".join(operands[:n_operands[2]])}}}, {{{", ".join(operands[n_operands[2]:n_operands[2]+n_operands[0]])}}}," "{{{", ".join(operands[-n_operands[1]:])}}}, {{{", ".join(operands[:n_operands[2]])}}};" - : {", ".join([f'"+f"(c.{_nms[i]})' for i in range(n_operands[2])])} + : {", ".join([f'"+r"(c_pk[{i}])' for i in range(n_operands[2])])} : {", ".join([f'"r"(a_pk[{i}])' for i in range(n_operands[0])])}, {", ".join([f'"r"(b_pk[{i}])' for i in range(n_operands[1])])}); return c;\n}}""") @@ -366,10 +409,30 @@ def cast_float_to_bf16(x: UOp) -> UOp: class AMDRenderer(CStyleLanguage): device = "AMD" shared_max = 65536 + # NOTE: this is only really needed on gfx12, even though gfx11 reports the same limitation + global_max = (2147483647, 65535, 65535) # https://gpuopen.com/learn/wmma_on_rdna3/ - tensor_cores = [TensorCore(dims=(16,16,16), threads=[(0,8),(0,2),(1,2)], dtype_in=di, dtype_out=do, reduce_axes=[(0,16)], opts_seq=("LC","UP"), - upcast_axes = ([(0,16)],[(0,16)],[(1,8)]), st1_pattern=(((1,2),(0,2),(1,1),(0,1)),((1,0),(0,0))), expanded_shape=(16,2,4)) - for (di, do) in [(dtypes.half, dtypes.float), (dtypes.half, dtypes.half)]] + tensor_cores = [TensorCore(dims=(16,16,16), threads=32, elements_per_thread=(16,16,8), dtype_in=di, dtype_out=do, + opts=("l0","l0","l0","l0","l1","u1","u1","u1"), swizzle=(((4,9,10,11,0),(1,2,3,5,6,7,8)), ((0,1,2,3,4),(9,10,11,5,6,7,8)))) + for di,do in [(dtypes.half,dtypes.float),(dtypes.half,dtypes.half),(dtypes.bfloat16,dtypes.float)]] + tensor_cores_rdna4 = [TensorCore(dims=(16,16,16), threads=32, elements_per_thread=(8,8,8), dtype_in=di, dtype_out=do, + opts=("l0","l0","l0","l0","u1","u1","u1","l1"), swizzle=(((9,10,11,4,7),(0,1,2,3,5,6,8)),((0,1,2,3,7),(4,9,10,11,5,6,8)))) + for di,do in [(dtypes.half,dtypes.float),(dtypes.half,dtypes.half),(dtypes.bfloat16,dtypes.float),(dtypes.bfloat16,dtypes.bfloat16)]] + # https://gpuopen.com/learn/amd-lab-notes/amd-lab-notes-matrix-cores-readme + tensor_cores_mfma = [TensorCore(dims=(16,16,16), threads=64, elements_per_thread=(4,4,4), dtype_in=di, dtype_out=do, + opts=("l0","l0","l0","l0","u1","u1","l1","l1"), swizzle=(((10,11,4,5,8,9),(0,1,2,3,6,7)),((0,1,2,3,8,9),(4,5,10,11,6,7)))) + for di,do in [(dtypes.half,dtypes.float),(dtypes.bfloat16,dtypes.float)]] + + @staticmethod + def get_tensor_cores(arch): + return {"gfx942": AMDRenderer.tensor_cores_mfma, "gfx1201": AMDRenderer.tensor_cores_rdna4}.get(arch.split(":")[0], AMDRenderer.tensor_cores) + def __init__(self, arch:str): # gfx942 => MI300, gfx1100 => RX 7900, gfx1201 => RX 9700 + self.arch = arch + self.tensor_cores = self.get_tensor_cores(arch) + if self.arch.split(":")[0] == "gfx942": + self.string_rewrite = PatternMatcher([ + (UPat(Ops.WMMA, name="x"), lambda ctx,x: f"__{x.arg[0]}({ctx[x.src[0]]}, {ctx[x.src[1]]}, {ctx[x.src[2]]}, 0, 0, 0)")]) + base_rewrite + def __reduce__(self): return self.__class__, (self.arch,) # language options ockl = [(f"__ockl_get_{name}", "unsigned int", "size_t", "const") for name in ["local_id", "group_id", "local_size"]] @@ -387,6 +450,7 @@ class AMDRenderer(CStyleLanguage): Ops.EXP2: lambda x,dtype: f"__ocml_exp2_f{ {dtypes.half:16, dtypes.double:64}.get(dtype, 32)}({x})", Ops.SQRT: lambda x,dtype: f"__ocml_sqrt_f{ {dtypes.half:16, dtypes.double:64}.get(dtype, 32)}({x})" } smem_prefix = "__attribute__((shared))" + smem_prefix_for_cast: bool = False barrier = '__builtin_amdgcn_fence(__ATOMIC_RELEASE, "workgroup");' + '__builtin_amdgcn_s_barrier();' + \ '__builtin_amdgcn_fence(__ATOMIC_ACQUIRE, "workgroup");' float4 = "make_float4" @@ -400,12 +464,15 @@ class AMDRenderer(CStyleLanguage): (UPat(GroupOp.ALU, dtypes.bool, name="alu", src=(UPat.var("x", dtype=dtypes.bfloat16), UPat.var("y", dtype=dtypes.bfloat16))), lambda alu,x,y: UOp(alu.op, dtypes.bool, (x.cast(dtypes.float), y.cast(dtypes.float)), alu.arg)), # add float intermediate casting for bfloat16 - (UPat(Ops.CAST, name="x", src=UPat.var("y", dtypes.bfloat16)),lambda x,y: y.cast(dtypes.float).cast(x.dtype) if x.dtype!=dtypes.float else None), - (UPat(Ops.CAST, dtypes.bfloat16, UPat.var("x")),lambda x: x.cast(dtypes.float).cast(dtypes.bfloat16) if x.dtype!=dtypes.float else None), + (UPat(Ops.CAST, name="x", src=(UPat.var("y", dtypes.bfloat16),)), + lambda x,y: y.cast(dtypes.float).cast(x.dtype) if x.dtype!=dtypes.float else None), + (UPat(Ops.CAST, dtypes.bfloat16, (UPat.var("x"),)), + lambda x: x.cast(dtypes.float).cast(dtypes.bfloat16) if x.dtype!=dtypes.float else None), # bfloat16 casting (UPat.cvar('x', dtypes.bfloat16), lambda x: cast_float_to_bf16(UOp.const(dtypes.float, x.arg))), - (UPat(Ops.CAST, dtypes.float, UPat.var("x", dtypes.bfloat16)), lambda x: (x.bitcast(dtypes.ushort).cast(dtypes.uint)<<16).bitcast(dtypes.float)), - (UPat(Ops.CAST, dtype=dtypes.bfloat16, src=UPat.var("x", dtype=dtypes.float)), cast_float_to_bf16)]) + extra_pm + (UPat(Ops.CAST, dtypes.float, (UPat.var("x", dtypes.bfloat16),)), + lambda x: (x.bitcast(dtypes.ushort).cast(dtypes.uint)<<16).bitcast(dtypes.float)), + (UPat(Ops.CAST, dtype=dtypes.bfloat16, src=(UPat.var("x", dtype=dtypes.float),)), cast_float_to_bf16)]) + extra_pm def render_vector_prefix(self, dtype:DType) -> str: vec, scal = self.render_dtype(dtype), self.render_dtype(dtype.scalar()) @@ -414,13 +481,19 @@ class AMDRenderer(CStyleLanguage): def render_kernel(self, function_name, kernel, bufs, uops, prefix=None) -> str: prefix = ["#define INFINITY (__builtin_inff())","#define NAN (__builtin_nanf(\"\"))","typedef long unsigned int size_t;","#define half _Float16"] - + type_map = { dtypes.bfloat16: "bf16", dtypes.float: "f32", dtypes.half: "f16" } used_dtypes = uops_to_dtypes(uops) if any(dt.scalar() == dtypes.bfloat16 for dt in used_dtypes): prefix.append("typedef unsigned short hip_bfloat16;") prefix += [self.render_vector_prefix(dt) for dt in used_dtypes if dt.count > 1] for arg in dedup([uop.arg for uop in uops if uop.op is Ops.WMMA]): # TODO: handle TCs f32_bf16 and bf16_bf16 w/ wrapper - if arg[3] == dtypes.float: prefix.append(f"#define __{arg[0]} __builtin_amdgcn_wmma_f32_16x16x16_f16_w32") + if self.arch.split(":")[0] == "gfx942": + prefix.append(f"#define __{arg[0]} __builtin_amdgcn_mfma_f32_16x16x16{'f16' if arg[2] == dtypes.half else 'bf16_1k'}") + # #define __WMMA_16_16_16_half_half __builtin_amdgcn_wmma_f16_16x16x16_f16_w32_gfx12 + elif self.arch.split(":")[0] == "gfx1201": + prefix.append(f"#define __{arg[0]} __builtin_amdgcn_wmma_{type_map[arg[3]]}_16x16x16_{type_map[arg[2]]}_w32_gfx12") + elif arg[3] == dtypes.float: + prefix.append(f"#define __{arg[0]} __builtin_amdgcn_wmma_f32_16x16x16_{'f16' if arg[2] == dtypes.half else 'bf16'}_w32") else: prefix.append(f"static inline __attribute__((device)) half8 __{arg[0]}"+"""(half16 a, half16 b, half8 c) { half16 c_frag = {}; half8 d; for (int n = 0; n < 8; n++) { c_frag[n*2] = c[n]; } c_frag = __builtin_amdgcn_wmma_f16_16x16x16_f16_w32(a, b, c_frag, false); diff --git a/tinygrad_repo/tinygrad/renderer/llvmir.py b/tinygrad_repo/tinygrad/renderer/llvmir.py index 725d20a30e..69b645256c 100644 --- a/tinygrad_repo/tinygrad/renderer/llvmir.py +++ b/tinygrad_repo/tinygrad/renderer/llvmir.py @@ -1,14 +1,17 @@ from typing import cast -import math, struct +import math, struct, sys from tinygrad.renderer import Renderer -from tinygrad.ops import UOp, PatternMatcher, UPat, Ops, GroupOp +from tinygrad.renderer.cstyle import ClangRenderer, AMDRenderer +from tinygrad.uop.ops import UOp, PatternMatcher, UPat, Ops, GroupOp from tinygrad.dtype import dtypes, DType, PtrDType, truncate +from tinygrad.helpers import prod, AMX def ldt(dt:DType): + if dt.vcount > 1: return f"<{dt.vcount} x {ldt(dt.scalar())}>" if isinstance(dt, PtrDType): return ldt(dt.base) + "*" - return {dtypes.int8: "i8", dtypes.int16: "i16", dtypes.int32: "i32", dtypes.int64: "i64", + return {dtypes.void: "void", dtypes.bool: "i1", dtypes.int8: "i8", dtypes.int16: "i16", dtypes.int32: "i32", dtypes.int64: "i64", dtypes.uint8: "i8", dtypes.uint16: "i16", dtypes.uint32: "i32", dtypes.uint64: "i64", - dtypes.float16: "half", dtypes.float32: "float", dtypes.float64: "double", dtypes.bool: "i1", dtypes.void: "void"}[dt] + dtypes.float16: "half", dtypes.bfloat16: "bfloat", dtypes.float32: "float", dtypes.float64: "double"}[dt] def lconst(x, dtype:DType): if dtype in dtypes.floats: @@ -20,7 +23,7 @@ def lcast(input_type:DType, output_type:DType): if dtypes.is_float(input_type): if dtypes.is_float(output_type): return 'fpext' if output_type.itemsize > input_type.itemsize else 'fptrunc' if dtypes.is_int(output_type): return 'fptoui' if dtypes.is_unsigned(output_type) else 'fptosi' - if dtypes.is_unsigned(input_type) or input_type == dtypes.bool: + if dtypes.is_unsigned(input_type) or dtypes.is_bool(input_type): if dtypes.is_float(output_type): return 'uitofp' if dtypes.is_int(output_type): return 'trunc' if output_type.itemsize < input_type.itemsize else 'zext' if dtypes.is_int(input_type): @@ -28,33 +31,63 @@ def lcast(input_type:DType, output_type:DType): if dtypes.is_int(output_type): return 'trunc' if output_type.itemsize < input_type.itemsize else 'sext' raise NotImplementedError(f"cast from {input_type} -> {output_type} not implemented") +# https://github.com/corsix/amx +def render_wmma_amx(ctx, wmma: UOp) -> str: + def AMX(op, gpr): return f'call void asm sideeffect ".word (0x201000+($0<<5)+0$1-((0$1>>4)*6))", "i,r,~{{memory}}"(i32 {op}, i64 {gpr}) #0; AMX' + + return "\n".join([ + *[f' store {ldt(src.dtype)} {ctx[src]}, {ldt(src.dtype.ptr())} {ctx[wmma]}_amx{i}, align {src.dtype.itemsize}' for i,src in enumerate(wmma.src)], + f' call void asm sideeffect "nop\\0Anop\\0Anop\\0A.word ({0x201000 + (17 << 5) + 0})", "~{{memory}}"() #0; AMX set', # set + *[f' {ctx[wmma]}_ld{i} = add i64 {ctx[wmma]}_ptr_amx2, {i*4<<56 | i*64}\n {AMX(4,f"{ctx[wmma]}_ld{i}")} ldz' for i in range(16)], # ldz + f' {AMX(0, f"{ctx[wmma]}_ptr_amx1")} ldx\n {AMX(1, f"{ctx[wmma]}_ptr_amx0")} ldy\n {AMX(12, 0)} fma32', # ldx ldy fma + *[f' {ctx[wmma]}_st{i} = add i64 {ctx[wmma]}_ptr_amx2, {i*4<<56 | i*64}\n {AMX(5,f"{ctx[wmma]}_st{i}")} stz' for i in range(16)], # stz + f' call void asm sideeffect "nop\\0Anop\\0Anop\\0A.word ({0x201000 + (17 << 5) + 1})", "~{{memory}}"() #0; AMX clr', # clr + f' {ctx[wmma]} = load {ldt(wmma.dtype)}, ptr {ctx[wmma]}_amx2, align {wmma.dtype.itemsize}']) + +def render_wmma_amd(ctx, wmma: UOp) -> str: + dt_map = {dtypes.half: "f16", dtypes.float: "f32", dtypes.bfloat16: "bf16", dtypes.ushort: "bf16"} + # https://github.com/llvm/llvm-project/blob/main/llvm/test/CodeGen/AMDGPU/GlobalISel/llvm.amdgcn.wmma_32.ll + # example: %wmma0 = call <8 x float> @llvm.amdgcn.wmma.f32.16x16x16.f16(<16 x half> %v99,<16 x half> %v100,<8 x float> %v101) + return f" {ctx[wmma]} = call {ldt(wmma.dtype)} @llvm.amdgcn.wmma.{dt_map[wmma.src[-1].dtype.scalar()]}.16x16x16." + \ + f"{dt_map[wmma.src[0].dtype.scalar()]}(" + ", ".join([f"{ldt(w.dtype)} {ctx[w]}" for w in wmma.src]) + (", i1 false)" \ + if wmma.dtype.scalar() != dtypes.float else ")") + # llvm ops, lop[][] unsigned_lop = { Ops.ADD: "add", Ops.MUL: "mul", Ops.IDIV: "udiv", Ops.MOD: "urem", Ops.CMPLT: "icmp ult", Ops.CMPNE: "icmp ne", Ops.OR: "or", Ops.AND: "and", Ops.XOR: "xor", } -signed_lop = {**unsigned_lop, Ops.CMPLT: "icmp slt", Ops.IDIV: "sdiv", Ops.MOD: "srem"} +signed_lop = {**unsigned_lop, Ops.ADD: "add nsw", Ops.CMPLT: "icmp slt", Ops.IDIV: "sdiv", Ops.MOD: "srem"} flags = " nsz arcp contract afn" float_lop = {Ops.ADD: "fadd"+flags, Ops.MUL: "fmul"+flags, Ops.CMPLT: f"fcmp{flags} ult", Ops.CMPNE: f"fcmp{flags} une", Ops.FDIV: "fdiv"+flags} lop = {**{x:unsigned_lop for x in (dtypes.bool,)+dtypes.uints}, **{x:signed_lop for x in dtypes.sints}, **{x:float_lop for x in dtypes.floats}} -llvm_rewrite = PatternMatcher([ +base_rewrite = PatternMatcher([ # memory load/store (UPat(Ops.INDEX, name="x"), lambda ctx,x: f" {ctx[x]} = getelementptr inbounds {ldt(x.dtype.base)}, {ldt(x.src[0].dtype)} {ctx[x.src[0]]}, {ldt(x.src[1].dtype)} {ctx[x.src[1]]}"), - (UPat(Ops.LOAD, src=(UPat.var('idx'), UPat.var('alt'), UPat.var('mask')), name="x"), lambda ctx,x,idx,alt,mask: + (UPat(Ops.LOAD, src=(UPat(Ops.INDEX, src=(UPat(), UPat(), UPat.var("mask"))).or_casted("idx"), UPat.var("alt")), name="x"), + lambda ctx,x,idx,alt,mask: f" br label {ctx[x]}_entry\n{ctx[x][1:]}_entry:\n" f" br i1 {ctx[mask]}, label {ctx[x]}_load, label {ctx[x]}_exit\n{ctx[x][1:]}_load:\n" f" {ctx[x]}_yes = load {ldt(x.dtype)}, {ldt(idx.dtype)} {ctx[idx]}\n" f" br label {ctx[x]}_exit\n{ctx[x][1:]}_exit:\n" f" {ctx[x]} = phi {ldt(x.dtype)} [{ctx[x]}_yes, {ctx[x]}_load], [{ctx[alt]}, {ctx[x]}_entry]"), - (UPat(Ops.LOAD, src=(UPat.var('idx'),), name="x"), lambda ctx,x,idx: f" {ctx[x]} = load {ldt(x.dtype)}, {ldt(idx.dtype)} {ctx[idx]}"), + (UPat(Ops.LOAD, src=(UPat.var('idx'),), allow_any_len=True, name="x"), + lambda ctx,x,idx: f" {ctx[x]} = load {ldt(x.dtype)}, {ldt(idx.dtype)} {ctx[idx]}"), (UPat(Ops.STORE, name="x"), lambda ctx,x: f" store {ldt(x.src[1].dtype)} {ctx[x.src[1]]}, {ldt(x.src[0].dtype)} {ctx[x.src[0]]}"), + # GEP/VECTORIZE/CAST for float4 support + (UPat(Ops.GEP, name="x"), lambda ctx,x: f" {ctx[x]} = extractelement {ldt(x.src[0].dtype)} {ctx[x.src[0]]}, i32 {x.arg[0]}"), + (UPat(Ops.VECTORIZE, src=UPat.var('y'), name="x"), lambda ctx,x,y: + f" {ctx[x]}_z = insertelement <1 x {ldt(y.dtype)}> poison, {ldt(y.dtype)} {ctx[y]}, i32 0\n" + f" {ctx[x]} = shufflevector <1 x {ldt(y.dtype)}> {ctx[x]}_z, <1 x {ldt(y.dtype)}> poison, <{x.dtype.count} x i32> zeroinitializer"), + (UPat(Ops.VECTORIZE, name="x"), lambda ctx,x: "\n".join([(f" {ctx[x]}_{i}" if i+1 != len(x.src) else f" {ctx[x]}")+ + f" = insertelement {ldt(x.dtype)} "+(f"{ctx[x]}_{i-1}" if i != 0 else "poison")+ + f", {ldt(u.dtype)} {ctx[u]}, i32 {i}" for i,u in enumerate(x.src)])), # unary/binary/ternary ops - (UPat(Ops.SQRT, name="x"), lambda ctx,x: - f" {ctx[x]} = call{flags} {ldt(x.dtype)} @llvm.sqrt.{ldt(x.src[0].dtype)}({ldt(x.src[0].dtype)} {ctx[x.src[0]]})"), (UPat(Ops.BITCAST, name="x"), lambda ctx,x: f" {ctx[x]} = bitcast {ldt(x.src[0].dtype)} {ctx[x.src[0]]} to {ldt(x.dtype)}"), (UPat(Ops.CAST, name="x"), lambda ctx,x: f" {ctx[x]} = {lcast(x.src[0].dtype, x.dtype)} {ldt(x.src[0].dtype)} {ctx[x.src[0]]} to {ldt(x.dtype)}"), - (UPat(GroupOp.Binary, name="x"), lambda ctx,x: f" {ctx[x]} = {lop[x.src[0].dtype][x.op]} {ldt(x.src[0].dtype)} {ctx[x.src[0]]}, {ctx[x.src[1]]}"), + (UPat(GroupOp.Binary, name="x"), lambda ctx,x: + f" {ctx[x]} = {lop[x.src[0].dtype.scalar()][x.op]} {ldt(x.src[0].dtype)} {ctx[x.src[0]]}, {ctx[x.src[1]]}"), (UPat(Ops.WHERE, name="x"), lambda ctx,x: f" {ctx[x]} = select {ldt(x.src[0].dtype)} {ctx[x.src[0]]}, {ldt(x.src[1].dtype)} {ctx[x.src[1]]}, {ldt(x.src[2].dtype)} {ctx[x.src[2]]}"), @@ -62,23 +95,27 @@ llvm_rewrite = PatternMatcher([ (UPat(Ops.RANGE, name="x"), lambda ctx,x: f" br label %loop_entry_{x.arg}\nloop_entry_{x.arg}:\n" f" br label %loop_body_{x.arg}\nloop_body_{x.arg}:\n" - f" {ctx[x]} = phi {ldt(x.dtype)} [{ctx[x.src[0]]}, %loop_entry_{x.arg}], [{ctx[x]}phi, %loop_latch_{x.arg}]"), + f" {ctx[x]} = phi {ldt(x.dtype)} [ 0, %loop_entry_{x.arg} ], [ {ctx[x]}phi, %loop_latch_{x.arg} ]"), (UPat(Ops.ENDRANGE, name="x"), lambda ctx,x: f" br label %loop_latch_{x.src[0].arg}\nloop_latch_{x.src[0].arg}:\n" - f" {ctx[x.src[0]]}phi = add i32 {ctx[x.src[0]]}, 1\n {ctx[x]} = icmp ult i32 {ctx[x.src[0]]}phi, {ctx[x.src[0].src[1]]}\n" + f" {ctx[x.src[0]]}phi = add i32 {ctx[x.src[0]]}, 1\n {ctx[x]} = icmp ult i32 {ctx[x.src[0]]}phi, {ctx[x.src[0].src[0]]}\n" f" br i1 {ctx[x]}, label %loop_body_{x.src[0].arg}, label %loop_exit_{x.src[0].arg}\nloop_exit_{x.src[0].arg}:"), # if (UPat(Ops.IF, name="x"), lambda ctx,x: f" br i1 {ctx[x.src[0]]}, label %ifbody_{ctx[x][1:]}, label %ifskip_{ctx[x][1:]}\nifbody_{ctx[x][1:]}:"), (UPat(Ops.ENDIF, name="x"), lambda ctx,x: f" br label %ifskip_{ctx[x.src[0]][1:]}\nifskip_{ctx[x.src[0]][1:]}:"), + + (UPat(Ops.BARRIER), lambda ctx: "") ]) class LLVMRenderer(Renderer): device = "LLVM" - supports_float4 = False + abi = 'win64cc' if sys.platform == 'win32' else None + supports_float4 = True has_local = False - has_shared = False - global_max = None + global_max: tuple[int, ...] | None = None + string_rewrite = base_rewrite + PatternMatcher([(UPat(Ops.WMMA, name="wmma"), render_wmma_amx)]) + if AMX: tensor_cores = ClangRenderer.amx_tc extra_matcher = PatternMatcher([ # rewrite RECIP with FDIV @@ -87,35 +124,62 @@ class LLVMRenderer(Renderer): (UPat(Ops.CAST, dtype=dtypes.bool, name="x"), lambda x: x.src[0] != x.src[0].const_like(0)), # rewrite MAX to CMPLT + WHERE (UPat(Ops.MAX, name="m"), lambda m: (m.src[0] < m.src[1]).where(m.src[1], m.src[0])), + # copied from cstyle.py, upcast to float32 all the ops that don't support bfloat16 + (UPat((Ops.SQRT, Ops.EXP2, Ops.LOG2, Ops.SIN), dtype=dtypes.bfloat16, name="x"), + lambda x: (UOp(x.op, dtypes.float, tuple(vv.cast(dtypes.float) for vv in x.src), x.arg).cast(dtypes.bfloat16))), + # copied from cstyle.py, add float intermediate casting + (UPat(Ops.CAST, name="x", src=UPat.var("y", dtypes.bfloat16)),lambda x,y: y.cast(dtypes.float).cast(x.dtype) if x.dtype!=dtypes.float else None), + (UPat(Ops.CAST, dtypes.bfloat16, UPat.var("x")),lambda x: x.cast(dtypes.float).cast(dtypes.bfloat16) if x.dtype!=dtypes.float else None), ]) - def render(self, name: str, uops: list[UOp]) -> str: + def render(self, uops: list[UOp]) -> str: return "\n".join((k:=self._render_kernel(uops))[0] + (k[1], self._render_footer(uops))) + def _render_footer(self, uops: list[UOp]) -> str: return 'attributes #0 = { alwaysinline nounwind "no-builtins" "no-trapping-math"="true" }' + def _render_fn(self, name:str, args:list[tuple[str,DType]], kernel:list[str], prefix:list[str]|None=None) -> str: + # NOTE: MallocAllocator promises 0x20 alignment + sargs = ", ".join([f"{ldt(dt)}{' noalias align 32' if isinstance(dt, PtrDType) else ''} {name}" for name,dt in args]) + sprefix = "".join([f" {x}" for x in (prefix or []) + [self.abi] if x is not None]) + return "\n".join([f"define{sprefix} void @{name}({sargs}) #0", "{"] + kernel + [" ret void\n}"]) + def _render_kernel(self, uops: list[UOp], prefix:list[str]|None=None) -> tuple[tuple[str, ...], str]: r: dict[UOp, str] = {} - args: list[str] = [] + args: list[tuple[str, DType]] = [] kernel: list[str] = [] - end_lines: dict[str, None] = {} vc = -1 - # prealloc all assigns + local_args: list[str] = [] acc_to_assign: dict[UOp, UOp] = {} for u in uops: - if u.op is Ops.ASSIGN: + if u.op is Ops.ASSIGN: # prealloc all assigns vc += 1 r[u] = r[u.src[1]] = f"%assign{vc}" assert u.src[0] not in acc_to_assign, "can't assign to DEFINE_ACC twice" acc_to_assign[u.src[0]] = u.src[1] + if AMX and u.op is Ops.WMMA: # prealloc aux buffers as AMX can only load from memory + vc += 1 + r[u] = f"%wmma{vc}" + for i, dtype in enumerate(u.arg[2].vec(sz) for sz in [prod(size for _, size in upcast) for upcast in u.arg[6]]): + kernel += [f" {r[u]}_amx{i} = alloca {ldt(dtype)}, align {dtype.itemsize}", + f" {r[u]}_ptr_amx{i} = ptrtoint {ldt(dtype.ptr())} {r[u]}_amx{i} to i64"] + name = "test" for u in uops: - # hack for defining sqrt function (TODO: can we get a transcendental for this?) - if u.op is Ops.SQRT: end_lines[f'declare {ldt(u.dtype)} @llvm.sqrt.{ldt(u.dtype)}({ldt(u.dtype)} %".1")'] = None - + if u.op is Ops.SINK: + if u.arg is not None: name = u.arg.name + continue if u.op in (Ops.DEFINE_GLOBAL, Ops.DEFINE_VAR): r[u] = f"%data{u.arg}" if u.op is Ops.DEFINE_GLOBAL else f"%{u.arg[0]}" - args.append(f"{ldt(u.dtype)}{' noalias' if isinstance(u.dtype, PtrDType) else ''} {r[u]}") + args.append((r[u], u.dtype)) + elif u.op == Ops.DEFINE_LOCAL: + r[u] = f"%local_{u.arg}" + assert isinstance(u.dtype, PtrDType) + if self.device == "LLVM": kernel.append(f" {r[u]} = alloca [{u.dtype.size} x {ldt(u.dtype)}], align 16") + else: + local_args.append(f"@{r[u][1:]} = internal unnamed_addr addrspace(3) global [{u.dtype.size} x {ldt(u.dtype)}] undef, align 16") + kernel.append(f" {r[u]} = addrspacecast [{u.dtype.size} x {ldt(u.dtype)}] addrspace(3)* @{r[u][1:]} to [{u.dtype.size} x {ldt(u.dtype)}]*") elif u.op is Ops.ASSIGN: pass # assign is already handled by the first pass elif u.op is Ops.DEFINE_ACC: r[u] = r[u.src[0]] # a define acc can be used and never be assigned to elif u.op is Ops.CONST: r[u] = lconst(u.arg, u.dtype) - elif u.op is Ops.CAST and ldt(u.dtype) == ldt(u.src[0].dtype): r[u] = r[u.src[0]] # cast from signed to unsigned of the same size is a noop + elif u.op is Ops.CAST and (ldt(u.dtype) == ldt(u.src[0].dtype) or isinstance(u.dtype, PtrDType)): + r[u] = r[u.src[0]] # cast from signed to unsigned of the same size is a noop, or pointer cast else: # if it's an assign target, it's already preallocated if u not in r: @@ -123,16 +187,61 @@ class LLVMRenderer(Renderer): r[u] = f"%v{vc}" # do the rendering of the llvm ir code - if (l:=llvm_rewrite.rewrite(u, ctx=r)) is None: raise RuntimeError(f"failed to render {u.op} with {u.dtype} srcs {[x.dtype for x in u.src]}") + if (l:=self.string_rewrite.rewrite(u, ctx=r)) is None: + raise RuntimeError(f"failed to render {u.op} with {u.dtype} srcs {[x.dtype for x in u.src]}") kernel.append(cast(str, l)) # generate the phi nodes for the assigns if u.op is Ops.RANGE: for x in acc_to_assign: - if u in x.src: # if this range is relevent for this acc + if u in x.src: # if this range is relevant for this acc vc += 1 - kernel.append(f" %acc{vc} = phi {ldt(x.dtype)}" f"[{r[x]}, %loop_entry_{u.arg}], [{r[acc_to_assign[x]]}, %loop_latch_{u.arg}]") + kernel.append(f" %acc{vc} = phi {ldt(x.dtype)} [ {r[x]}, %loop_entry_{u.arg} ], [ {r[acc_to_assign[x]]}, %loop_latch_{u.arg} ]") r[x] = f"%acc{vc}" - - # output the function - return f"define void @{name}({','.join(args)}) {{\n" + '\n'.join(kernel) + "\n ret void\n}\n"+'\n'.join(end_lines.keys()) + return tuple(local_args), self._render_fn(name, args, kernel, prefix) + +barrier = 'fence syncscope("workgroup") release\ntail call void @llvm.amdgcn.s.barrier()\nfence syncscope("workgroup") acquire\n' +code_for_workitem = {"g": lambda x: f"tail call i32 @llvm.amdgcn.workgroup.id.{chr(120+int(x))}()", + "l": lambda x: f"tail call i32 @llvm.amdgcn.workitem.id.{chr(120+int(x))}()"} +class AMDLLVMRenderer(LLVMRenderer): + device = "AMD" + has_local = True + shared_max = AMDRenderer.shared_max + global_max = AMDRenderer.global_max + abi = "amdgpu_kernel" + string_rewrite = PatternMatcher([ + (UPat(Ops.SPECIAL, name="x"), lambda ctx, x: f" {ctx[x]} = " + f"{ code_for_workitem[x.arg[0][0]](x.arg[0][-1])}; "), + (UPat(Ops.BARRIER), lambda ctx: barrier), + (UPat(Ops.CAST, name="x", dtype=dtypes.half.vec(16), src=UPat.var("y", dtypes.half.vec(8))), lambda ctx, x, y: f" {ctx[x]} = shufflevector "\ + f"<8 x half> {ctx[y]}, <8 x half> zeroinitializer, <16 x i32> <{', '.join([f'i32 {i}, i32 {j}' for i, j in zip(range(0, 8), range(8, 16))])}>"), + (UPat(Ops.CAST, name="x", dtype=dtypes.half.vec(8), src=UPat.var("y", dtypes.half.vec(16))), lambda ctx, x, y: + f" {ctx[x]}= shufflevector <16 x half> {ctx[y]}, <16 x half> undef, <8 x i32> <{', '.join([f'i32 {x}' for x in range(0, 16, 2)])}>"), + (UPat(Ops.WMMA, name="wmma"), render_wmma_amd), + ]) + base_rewrite + extra_matcher = LLVMRenderer.extra_matcher + def _render_footer(self, uops: list[UOp]) -> str: + # TODO: this is copied from cstyle + requiredMaxThreadsPerBlock = prod(u.arg[1] for u in uops if u.op is Ops.SPECIAL and u.arg[0][0] == "l") + attributes = ["alwaysinline", "nounwind", '"no-builtins"', + f'"amdgpu-flat-work-group-size"="1,{requiredMaxThreadsPerBlock}"', '"no-trapping-math"="true"'] + return 'attributes #0 = { ' + ' '.join(attributes) + ' }' + def __init__(self, arch:str): + self.arch = arch + self.tensor_cores = AMDRenderer.get_tensor_cores(arch) + if self.arch.split(":")[0] == "gfx1100": + self.extra_matcher += PatternMatcher([ + (UPat(Ops.WMMA, name="x", dtype=dtypes.half.vec(8)), + lambda x: UOp(Ops.WMMA, dtypes.half.vec(16), (x.src[0], x.src[1], x.src[2].cast(dtypes.half.vec(16))), (*x.arg,)).cast(dtypes.half.vec(8))), + (UPat(Ops.WMMA, name="x"), lambda x: UOp(Ops.WMMA, x.dtype, (x.src[0].bitcast(dtypes.uint16.vec(16)), x.src[1].bitcast(dtypes.uint16.vec(16)), + x.src[2]), x.arg) if x.src[0].dtype == dtypes.bfloat16.vec(16) else None), + ]) + if self.arch.split(":")[0] == "gfx1201": + self.extra_matcher += PatternMatcher([ + (UPat(Ops.WMMA, name="x", dtype=dtypes.bfloat16.vec(8)), lambda x: UOp(Ops.WMMA, dtypes.uint16.vec(8), + (x.src[0].bitcast(dtypes.uint16.vec(8)), x.src[1].bitcast(dtypes.uint16.vec(8)), x.src[2].bitcast(dtypes.uint16.vec(8))), (*x.arg,)) + .bitcast(dtypes.bfloat16.vec(8)) if x.src[0].dtype == dtypes.bfloat16.vec(8) else None), + (UPat(Ops.WMMA, name="x", dtype=dtypes.float.vec(8)), + lambda x: UOp(Ops.WMMA, dtypes.float.vec(8), (x.src[0].bitcast(dtypes.uint16.vec(8)), x.src[1].bitcast(dtypes.uint16.vec(8)), + x.src[2]), (*x.arg,)) if x.src[0].dtype == dtypes.bfloat16.vec(8) else None) + ]) + def __reduce__(self): return self.__class__, (self.arch,) diff --git a/tinygrad_repo/tinygrad/renderer/ptx.py b/tinygrad_repo/tinygrad/renderer/ptx.py index 0503c0b386..c47074d682 100644 --- a/tinygrad_repo/tinygrad/renderer/ptx.py +++ b/tinygrad_repo/tinygrad/renderer/ptx.py @@ -1,11 +1,11 @@ from typing import cast, Callable import struct from collections import defaultdict -from tinygrad.ops import Ops, UOp, PatternMatcher, UPat, GroupOp +from tinygrad.uop.ops import Ops, UOp, PatternMatcher, UPat, GroupOp from tinygrad.dtype import dtypes, DType, PtrDType from tinygrad.renderer import Renderer from tinygrad.renderer.cstyle import CUDARenderer -from tinygrad.helpers import prod, flatten, get_single_element +from tinygrad.helpers import flatten, get_single_element def render_val(x, dtype): if dtypes.is_float(dtype): @@ -32,7 +32,7 @@ asm_for_op: dict[Ops, Callable] = { f"selp.{'b16' if name == 'f16' else name} {d}, {b}, {c}, {a};" } -supports_half: list[Ops] = [Ops.EXP2, Ops.ADD, Ops.MUL, Ops.MAX, Ops.CMPLT, Ops.WHERE] +supports_half = (Ops.EXP2, Ops.ADD, Ops.MUL, Ops.MAX, Ops.CMPLT, Ops.WHERE) doesnt_support_half: tuple[Ops, ...] = tuple(op for op in asm_for_op.keys() if op not in supports_half) ptx_matcher = PatternMatcher([ # bool CMPNE is XOR, bool CMPLT is XOR+AND (universal makes this slow, this is for renderer only) @@ -48,27 +48,35 @@ ptx_matcher = PatternMatcher([ lambda x: UOp(x.op, dtypes.void, x.src[0:1] + (x.src[1].cast(dtypes.uint8),) + x.src[2:])), # load/store use pointer arithmetic, and the cast does nothing (UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("idx"))), lambda buf,idx: buf.cast(dtypes.int64) + idx.cast(dtypes.int64)*buf.dtype.itemsize), - (UPat(Ops.CAST, name="x"), lambda x: x.src[0] if isinstance(x.dtype, PtrDType) else None), + (UPat(Ops.CAST, name="x"), lambda x: x.src[0] if isinstance(x.dtype, PtrDType) or x.src[0].dtype == dtypes.void else None), + # move mask from INDEX to the load/store to enable pointer arithmetic + (UPat(Ops.LOAD, src=(UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("idx"), UPat.var("gate"))), UPat.var("alt"))), + lambda buf,idx,gate,alt: UOp(Ops.LOAD, alt.dtype, (buf.index(idx), alt, gate))), + (UPat(Ops.STORE, src=(UPat(Ops.INDEX, src=(UPat.var("buf"), UPat.var("idx"), UPat())), UPat.var("val"), UPat.var("gate"))), + lambda buf,idx,val,gate: UOp.store(buf.index(idx), val, gate)), # ptx shr and shl instructions require y to be uint (UPat.var("x") << UPat.var("y"), lambda x,y: UOp(Ops.SHL, x.dtype, (x,y.cast(dtypes.uint))) if y.dtype != dtypes.uint else None), (UPat.var("x") >> UPat.var("y"), lambda x,y: UOp(Ops.SHR, x.dtype, (x,y.cast(dtypes.uint))) if y.dtype != dtypes.uint else None), ]) -def mem_type(x: UOp): return 'shared' if any(_x.op is Ops.DEFINE_LOCAL for _x in x.src[0].toposort) else 'global' +def mem_type(x: UOp): return 'shared' if any(_x.op is Ops.DEFINE_LOCAL for _x in x.src[0].toposort()) else 'global' -def render_wmma(ctx: "PTXRenderer", x: UOp): +def render_wmma(ctx: "PTXRenderer", wmma: UOp): assert ctx.wmma_r, "registry values for wmma must be populated" - _, (N, M, K), dtype_in, _, _, _, upcast_axes, _ = x.arg - n_operands = tuple(prod(sz for _, sz in upc)*dtype_in.itemsize//4 for upc in upcast_axes[:2]) - dt_map = { dtypes.half: "f16" } - _i = 0 - for vv in x.src[:2]: - for i in range(0, len(ctx.r[vv]), 2): - yield f"mov.b32 {ctx.wmma_r[_i]}, {{{', '.join(ctx.r[vv][i:i+2])}}};" - _i += 1 - yield f'mma.sync.aligned.m{M}n{N}k{K}.row.col.f32.{dt_map[dtype_in]}.{dt_map[dtype_in]}.f32{" "*12}' +\ - f'{{{", ".join(ctx.r[x])}}}, {{{", ".join(ctx.wmma_r[:n_operands[0]])}}}, {{{", ".join(ctx.wmma_r[-n_operands[1]:])}}}, ' + \ - f'{{{", ".join(ctx.r[x.src[2]])}}};' + (N, M, K), dtype_in, dtype_out = wmma.arg[1], wmma.arg[2], wmma.arg[3] + + for src, regs in zip(wmma.src, ctx.wmma_r): + for i, reg in enumerate(regs): # pack input and acc registers + if (elems_per_reg := 4 // src.dtype.scalar().itemsize) == 1: yield f"mov.b32 {reg}, {ctx.r[src][i]};" + else: yield f"mov.b32 {reg}, {{{', '.join(ctx.r[src][i * elems_per_reg : (i+1) * elems_per_reg])}}};" + + dt_map_in, dt_map_out = {dtypes.float: "tf32", dtypes.half: "f16"}, {dtypes.float: "f32", dtypes.half: "f16"} + yield f'mma.sync.aligned.m{M}n{N}k{K}.row.col.{dt_map_out[dtype_out]}.{dt_map_in[dtype_in]}.{dt_map_in[dtype_in]}.{dt_map_out[dtype_out]}{" "*12}'+\ + f'{{{", ".join(ctx.wmma_r[2])}}}, {{{", ".join(ctx.wmma_r[0])}}}, {{{", ".join(ctx.wmma_r[1])}}}, {{{", ".join(ctx.wmma_r[2])}}};' + + for i, reg in enumerate(ctx.wmma_r[2]): # unpack acc registers + if (elems_per_reg := 4 // dtype_out.itemsize) == 1: yield f"mov.b32 {ctx.r[wmma][i]}, {reg};" + else: yield f"mov.b32 {{{', '.join(ctx.r[wmma][i * elems_per_reg : (i+1) * elems_per_reg])}}}, {reg};" def modifier(a: DType, b: DType): return '.rzi' if dtypes.is_int(a) and dtypes.is_float(b) else '.rn' if dtypes.is_float(a) and \ (a.itemsize < b.itemsize or dtypes.is_int(b) or b == dtypes.bool) else '' @@ -98,21 +106,21 @@ string_rewrite = PatternMatcher([ f"@{ctx.r[gate]} ld.{mem_type(x)}.{ctx.mem_types[x.dtype.scalar()]} {ctx.r[x]}, [{ctx.r[loc]}+0];", f"@!{ctx.r[gate]} mov.b{ctx.types[x.dtype.scalar()][1:]} {ctx.r[x]}, {ctx.r[alt]};"]), (UPat(Ops.LOAD, name="x", src=(UPat.var('loc'),), allow_any_len=True), - lambda ctx, x, loc: f" ld.{mem_type(x)}.v{x.dtype.count}.{ctx.mem_types[x.dtype.scalar()]} {{{', '.join(ctx.r[x])}}}, [{ctx.r[loc]}+0];" \ + lambda ctx, x, loc: f"ld.{mem_type(x)}.v{x.dtype.count}.{ctx.mem_types[x.dtype.scalar()]} {{{', '.join(ctx.r[x])}}}, [{ctx.r[loc]}+0];" \ if x.dtype.count > 1 else f"ld.{mem_type(x)}.{ctx.mem_types[x.dtype]} {ctx.r[x]}, [{ctx.r[loc]}+0];"), (UPat(Ops.DEFINE_ACC, name="x", src=(UPat.cvar("pred", dtype=dtypes.bool),), allow_any_len=True), lambda ctx, x, pred: [ f"setp.ne.s16 {ctx.r[pred]}, {render_val(pred.arg, pred.dtype)}, 0;", f"mov.pred {ctx.r[x]}, {ctx.r[pred]};"]), (UPat(Ops.DEFINE_ACC, name="x", src=(UPat.cvar("pred"),), allow_any_len=True), lambda ctx, x, pred: f"mov.b{ctx.types[x.dtype][1:]} {ctx.r[x]}, {render_val(pred.arg, x.dtype)};"), - (UPat(Ops.RANGE, name="x"), lambda ctx, x: [f"mov.u32 {ctx.r[x]}, {ctx.r[x.src[0]]};", "LOOP_" + f"{ctx.r[x][1:]}:"]), + (UPat(Ops.RANGE, name="x"), lambda ctx, x: [f"mov.u32 {ctx.r[x]}, 0;", "LOOP_" + f"{ctx.r[x][1:]}:"]), (UPat(Ops.ASSIGN, name="x", dtype=dtypes.bool), lambda ctx, x: [f"mov.pred {ctx.r[x.src[0]]}, {ctx.r[x.src[1]]};"]), (UPat(Ops.ASSIGN, name="x"), lambda ctx, x: f"mov.b{ctx.types[x.dtype][1:]} {ctx.r[x.src[0]]}, {ctx.r[x.src[1]]};"), (UPat(Ops.ENDRANGE, name="x", src=(UPat.var("src0"),)), lambda ctx, x, src0: [ ctx.code_for_op[Ops.ADD](ctx.r[src0], ctx.r[src0], "1", dtypes.int, ctx.types[dtypes.int]), - ctx.code_for_op[Ops.CMPLT](ctx.r[x], ctx.r[x.src[0]], ctx.r[src0.src[1]], dtypes.int, ctx.types[dtypes.int]), + ctx.code_for_op[Ops.CMPLT](ctx.r[x], ctx.r[x.src[0]], ctx.r[src0.src[0]], dtypes.int, ctx.types[dtypes.int]), f"@{ctx.r[x]} bra LOOP_{ctx.r[src0][1:]};"]), (UPat(Ops.DEFINE_LOCAL, name="x"), - lambda ctx, x: [f".shared .align 4 .b8 {x.arg[0]}[{x.arg[1]*x.dtype.itemsize}];", f"mov.u64 {ctx.r[x]}, {x.arg[0]}[0];"]), + lambda ctx, x: [f".shared .align 4 .b8 {x.arg}[{x.dtype.size*x.dtype.itemsize}];", f"mov.u64 {ctx.r[x]}, {x.arg}[0];"]), (UPat(Ops.IF, name="x"), lambda ctx, x: f"@!{ctx.r[x.src[0]]} bra IF_{ctx.r[x.src[0]][1:]}_{ctx.uops.index(x)};"), (UPat(Ops.ENDIF, name="x"), lambda ctx, x: f"IF_{ctx.r[x.src[0].src[0]][1:]}_{ctx.uops.index(x.src[0])}:"), (UPat(Ops.WMMA, name="x"), lambda ctx, x: list(render_wmma(ctx, x))), @@ -124,11 +132,12 @@ class PTXRenderer(Renderer): device = "CUDA" suffix = "PTX" global_max, local_max, shared_max = CUDARenderer.global_max, CUDARenderer.local_max, CUDARenderer.shared_max - tensor_cores = [tc for tc in CUDARenderer.tensor_cores if tc.dtype_in == dtypes.half] + tc_sm80 = [tc for tc in CUDARenderer.tc_sm80 if tc.dtype_in in [dtypes.half, dtypes.float]] code_for_op = asm_for_op extra_matcher = ptx_matcher def __init__(self, arch:str, device="CUDA"): - self.device, self.tensor_cores, self.arch = device, PTXRenderer.tensor_cores if int(arch[3:]) >= 80 else [], arch + self.device, self.arch = device, arch + self.tensor_cores = PTXRenderer.tc_sm80 if int(arch[3:]) >= 80 else CUDARenderer.tc_sm75 if int(arch[3:]) >= 75 else [] def __reduce__(self): return self.__class__, (self.arch, self.device) # language options @@ -137,14 +146,12 @@ class PTXRenderer(Renderer): .address_size 64 .visible .entry""" barrier = "bar.sync\t0;" - supports_half = supports_half # HACK: Use s16 and u16 for int8 and uint8 buffers. This can be wrong in cast. types: dict[DType, str] = { dtypes.int8: "s16", dtypes.int16: "s16", dtypes.int32: "s32", dtypes.int64: "s64", dtypes.uint8: "u16", dtypes.uint16: "u16", dtypes.uint32: "u32", dtypes.uint64: "u64", dtypes.float16: "f16", dtypes.float32: "f32", dtypes.float64: "f64", dtypes.bool: "pred" } - mem_types: dict[DType, str] = types.copy() - mem_types.update({dtypes.int8: "s8", dtypes.uint8: "u8", dtypes.bool: "u8", dtypes.float16: "b16"}) + mem_types: dict[DType, str] = {**types, dtypes.int8: "s8", dtypes.uint8: "u8", dtypes.bool: "u8", dtypes.float16: "b16"} def render_kernel(self, kernel, function_name, bufs, regs) -> str: def fmt(line): return line if line[0]=="$" else "\t" + line.replace(" ", "\t" if len(line.split(" ")[0]) > 7 else "\t\t", 1) @@ -152,7 +159,7 @@ class PTXRenderer(Renderer): params = ',\n\t'.join([f".param .{'u64' if dtype.__class__ == PtrDType else self.types[dtype]} {name}" for name,dtype in bufs]) return f"{self.kernel_prefix} {function_name}(\n\t{params}\n)\n{{\n{kernel}\n}}" - def render(self, name:str, uops:list[UOp]) -> str: + def render(self, uops:list[UOp]) -> str: kernel:list[str] = [] bufs = [] @@ -167,7 +174,11 @@ class PTXRenderer(Renderer): c[prefix] += 1 return f"%{prefix}{c[prefix]-1}" + name = "test" for u in uops: + if u.op is Ops.SINK: + if u.arg is not None: name = u.arg.name + continue if u.op is Ops.VECTORIZE: r[u] = [cast(str,r[x]) for x in u.src] continue @@ -177,15 +188,17 @@ class PTXRenderer(Renderer): if u.op in {Ops.CAST, Ops.BITCAST} and (u.src[0].dtype == u.dtype or isinstance(u.src[0].dtype, PtrDType)): r[u] = r[u.src[0]] continue - if u.op is Ops.DEFINE_ACC and u.dtype in [dtypes.half, dtypes.bool]: r[u.src[0]] = ssa("const", u.src[0]) - elif u.op is Ops.SPECIAL: r[u] = "%" + u.arg[0] + if u.op is Ops.SPECIAL: r[u] = "%" + u.arg[0] elif u.op is Ops.DEFINE_VAR: bufs.append((u.arg[0], u.dtype)) elif u.op is Ops.LOAD: assert u.src[0].dtype == dtypes.int64, "load isn't int64" r[u] = [ssa('val', dtype=self.types[u.dtype.scalar()]) for _ in range(u.dtype.count)] if u.dtype.count > 1 else ssa('val', u) elif u.op is Ops.DEFINE_GLOBAL: bufs.append((f"data{u.arg}", u.dtype)) elif u.op is Ops.WMMA: - self.wmma_r = [ssa("wmma", dtype="b32") for vv in u.src[:2] for i in range(0, len(r[vv]), 2)] + # registers for packing/unpacking input and acc + self.wmma_r = [[ssa("wmma_in", dtype="b32") for _ in range(0, len(r[u.src[0]]), 4 // u.arg[2].itemsize)], + [ssa("wmma_in", dtype="b32") for _ in range(0, len(r[u.src[1]]), 4 // u.arg[2].itemsize)], + [ssa("wmma_acc", dtype="b32") for _ in range(0, len(r[u.src[2]]), 4 // u.arg[3].itemsize)]] r[u] = [ssa("wmma", dtype=self.types[u.dtype.scalar()]) for _ in range(u.dtype.count)] prefix, dtype = {Ops.CAST: ("cast", None), Ops.BITCAST: ("cast", None), Ops.ENDRANGE: ("pred", "pred"), Ops.RANGE: ("ridx", None), Ops.DEFINE_ACC: ("acc", None), Ops.DEFINE_VAR: ("dat", None), Ops.CONST: ("const", None), Ops.DEFINE_LOCAL:("local",self.types[dtypes.ulong]), diff --git a/tinygrad_repo/tinygrad/renderer/wgsl.py b/tinygrad_repo/tinygrad/renderer/wgsl.py index c00eff4135..03337f8e3e 100644 --- a/tinygrad_repo/tinygrad/renderer/wgsl.py +++ b/tinygrad_repo/tinygrad/renderer/wgsl.py @@ -1,5 +1,5 @@ from tinygrad.dtype import DType, PtrDType, dtypes -from tinygrad.ops import UOp, Ops, PatternMatcher, UPat +from tinygrad.uop.ops import UOp, Ops, PatternMatcher, UPat from tinygrad.renderer.cstyle import CStyleLanguage, base_rewrite, extra_pm from tinygrad.helpers import strip_parens import math @@ -20,21 +20,24 @@ def packed_store(bidx:UOp, var:UOp): def packed_load(root:UOp, bidx:UOp, dtype:DType, var:UOp|None=None): div_idx = bidx.src[1]//(4//dtype.itemsize) shift_am = (bidx.src[1].cast(dtypes.uint32)%UOp.const(dtypes.uint32, 4//dtype.itemsize))*UOp.const(dtypes.uint32, 8*dtype.itemsize) - if var is not None: load = UOp.load(UOp(Ops.INDEX, bidx.dtype, (bidx.src[0], div_idx)), var, root.src[2], dtype=dtypes.uint32, arg=root.arg) + if var is not None: load = UOp.load(UOp(Ops.INDEX, bidx.dtype, (bidx.src[0], div_idx, bidx.src[2])), var, dtype=dtypes.uint32, arg=root.arg) else: load = UOp.load(UOp(Ops.INDEX, bidx.dtype, (bidx.src[0], div_idx)), *root.src[1:], dtype=dtypes.uint32, arg=root.arg) val = (load.cast(dtypes.uint32) >> shift_am) & (0xFF if dtype.itemsize == 1 else 0xFFFF) return sign_extend(val, 8*dtype.itemsize).cast(dtype) if dtype in [dtypes.char, dtypes.short] else val.cast(dtype) +def is_packed(dt:DType) -> bool: return dt.itemsize < 4 and dt.base != dtypes.half + wgsl_matcher = PatternMatcher([ - (UPat((Ops.CMPLT, Ops.XOR), src=(UPat(name="a", dtype=dtypes.bool), UPat(name="b")), name="c"), + (UPat((Ops.CMPLT, Ops.XOR), src=(UPat(name="a", dtype=dtypes.bool), UPat.var("b")), name="c"), lambda a,b,c: a.cast(dtypes.int).alu(c.op, b.cast(dtypes.int)).cast(dtypes.bool)), - (UPat(Ops.LOAD, name="l", src=(UPat.var('b'),)), lambda l,b: packed_load(l,b,l.dtype) if l.dtype.itemsize < 4 else None), - (UPat(Ops.LOAD, name="l", src=(UPat.var('b'), UPat.var('c'), UPat())), - lambda l,b,c: packed_load(l,b,l.dtype,c.cast(dtypes.uint32)) if l.dtype.itemsize < 4 else None), - (UPat.store(UPat.var("bidx"), UPat.var("var"), allow_any_len=True), lambda bidx,var: packed_store(bidx,var) if var.dtype.itemsize < 4 else None), + (UPat(Ops.LOAD, name="l", src=(UPat.var("b"),)), lambda l,b: packed_load(l, b, l.dtype) if is_packed(l.dtype) else None), + (UPat(Ops.LOAD, name="l", src=(UPat.var("b"), UPat.cvar("c"))), + lambda l,b,c: packed_load(l,b,l.dtype,c.cast(dtypes.uint32)) if is_packed(l.dtype) else None), + (UPat.store(UPat.var("bidx"), UPat.var("var"), allow_any_len=True), lambda bidx,var: packed_store(bidx,var) if is_packed(var.dtype) else None), # TODO: why is this needed, and only for this MUL order (UPat(Ops.MUL, src=(UPat.var("a"), UPat.var("g").where(UPat.cvar("c1"), UPat.cvar("c2")))), lambda a,g,c1,c2: g.where(c1, a) if math.isnan(c1.arg) and c2.arg == 1.0 else None), + (UPat.var("a") << UPat.var("b"),lambda a,b:(a.bitcast(dtypes.uint32)<({x.arg})" \ - if x.arg < 0 else f"{x.arg&0xFFFFFFFF}u"), - (UPat(Ops.DEFINE_LOCAL, name="x"), lambda ctx,x: f"var {ctx[x]}: array<{ctx.buf_map(x.dtype.base)}, {x.arg[1]}>;"), - (UPat(Ops.BITCAST, name="x"), lambda ctx,x: f"bitcast<{ctx.type_map[x.dtype]}>({ctx[x.src[0]]}{['&0xFF','&0xFFFF','',''][x.dtype.itemsize-1]})"), - (UPat.load(UPat.var("b"),UPat.var("v"),UPat.var("g")),lambda ctx,b,v,g:f"select({ctx[v]}, {ctx.render_load(ctx[b],b.src[0].dtype)}, {ctx[g]})"), - (UPat.load(UPat.var("b"), allow_any_len=True), lambda ctx, b: ctx.render_load(ctx[b], b.src[0].dtype)), - (UPat.index(UPat.var("b"), UPat.var("idx")), lambda ctx,b,idx: f"{ctx[b]}[{strip_parens(ctx[idx]) if idx.arg == Ops.ADD else ctx[idx]}]"), - (UPat.store(UPat.var('b'), UPat.var("v"), allow_any_len=True),lambda ctx,b,v:\ + (UPat.cvar("x", dtype=dtypes.bool), lambda x: "true" if x.arg else "false"), + (UPat(Ops.CONST, dtype=(dtypes.uchar, dtypes.ushort, dtypes.uint32), name="x"), + lambda x: f"bitcast({x.arg})" if x.arg < 0 else f"{x.arg&0xFFFFFFFF}u"), + (UPat(Ops.DEFINE_LOCAL, name="x"), lambda ctx,x: f"var {ctx[x]}: array<{ctx.buf_map(x.dtype.base)}, {x.dtype.size}>;"), + (UPat(Ops.BITCAST, dtype=dtypes.half, name="x", src=(UPat(dtype=(dtypes.short, dtypes.ushort, dtypes.uint32),),)), + lambda ctx,x: f"bitcast>({ctx[x.src[0]]})[0]"), + (UPat(Ops.BITCAST, dtype=(dtypes.char, dtypes.uchar), name="x"), lambda ctx,x: f"bitcast<{ctx.type_map[x.dtype]}>({ctx[x.src[0]]}&0xFF)"), + (UPat(Ops.BITCAST, dtype=(dtypes.short, dtypes.ushort), name="x"),lambda ctx,x:f"bitcast<{ctx.type_map[x.dtype]}>(vec2({ctx[x.src[0]]},0))" \ + if x.src[0].dtype == dtypes.half else f"bitcast<{ctx.type_map[x.dtype]}>({ctx[x.src[0]]}&0xFFFF)"), + (UPat(Ops.BITCAST, name="x"), lambda ctx,x: f"bitcast<{ctx.type_map[x.dtype]}>({ctx[x.src[0]]})"), + (UPat.load(UPat.var("b"), UPat.cvar("v")),lambda ctx,b,v: f"select({ctx[v]}, {ctx.render_load(ctx[b],b.src[0].dtype)}, {ctx[b.src[2]]})"), + (UPat.load(UPat.var("b"), allow_any_len=True), lambda ctx, b: ctx.render_load(ctx[b], b.dtype)), + (UPat.store(UPat.var("b"), UPat.var("v"), allow_any_len=True),lambda ctx,b,v:\ # (load & mask) | var -> mask = v.src[0].src[1], var = v.src[1] - f"atomicAnd(&{ctx[b]},{ctx[v.src[0].src[1]]});\n atomicAdd(&{ctx[b]},{ctx[v.src[1]]});" if b.src[0].dtype.itemsize < 4 \ + f"atomicAnd(&{ctx[b]},{ctx[v.src[0].src[1]]});\n atomicAdd(&{ctx[b]},{ctx[v.src[1]]});" if is_packed(b.src[0].dtype) \ else f"{ctx[b]} = {ctx[v]};"), + (UPat(Ops.INDEX, src=(UPat.var("b"), UPat.var("idx")), allow_any_len=True), + lambda ctx,b,idx: f"{ctx[b]}[{strip_parens(ctx[idx]) if idx.arg is Ops.ADD else ctx[idx]}]"), # fix nan check: 'a != a -> is_nan()' - (UPat.var("a") != UPat.var("a"), lambda ctx,a: f"is_nan({ctx[a]})"), + (UPat.var("a") != UPat.var("a"), lambda ctx,a: f"(min({ctx[a]}, 1.0) == 1.0 && max({ctx[a]}, -1.0) == -1.0)"), ]) + base_rewrite def render_cast(self, dt:DType, val: str) -> str: return f"{self.type_map[dt]}({val})" def render_dtype(self, dt:DType, mutable=True) -> str: return "var" - def render_load(self, x:str, dt:DType) -> str: return f"atomicLoad(&{x})" if dt.itemsize < 4 else x - def buf_map(self, dt:DType) -> str: return "atomic" if dt.itemsize < 4 else self.type_map[dt.base] + def render_load(self, x:str, dt:DType) -> str: return f"atomicLoad(&{x})" if is_packed(dt) else x + def buf_map(self, dt:DType) -> str: return "atomic" if is_packed(dt) else self.type_map[dt.base] def render_kernel(self, function_name:str, kernel:list[str], bufs:list[tuple[str,tuple[DType,bool]]], uops:list[UOp], prefix=None) -> str: local_size = [num for _, num in sorted([u.arg for u in uops if u.op is Ops.SPECIAL and u.arg[0][0] == 'l'], key=lambda x: x[0])] if not local_size: local_size = [1] bind_it = iter(range(len(bufs))) external_local_bufs = [line.lstrip() for line in kernel if "var" in line] kernel[:] = [line for line in kernel if "var" not in line] - prg = "fn nan() -> f32 { let bits = 0xffffffffu; return bitcast(bits); }\n" - # trick to obfuscate compiler so that nan is detected properly - prg += "fn is_nan(v:f32) -> bool { return min(v, 1.0) == 1.0 && max(v, -1.0) == -1.0; }\n@group(0) @binding(0)\nvar INFINITY : f32;\n" + prg = "enable f16;\n" if any(uop.dtype.base == dtypes.half for uop in uops) else "" + prg += "fn nan() -> f32 { let bits = 0xffffffffu; return bitcast(bits); }\n" + prg += "@group(0) @binding(0)\nvar INFINITY : f32;\n" prg += "\n".join((external_local_bufs or [])+[f"@group(0) @binding({next(bind_it)+1})" + f"{'var' if isinstance(dtype, PtrDType) else 'var'}" + f"{name}:{f'array<{self.buf_map(dtype.base)}>' if isinstance(dtype,PtrDType) else self.buf_map(dtype)};" for name,(dtype,_) in bufs]) diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/am.py b/tinygrad_repo/tinygrad/runtime/autogen/am/am.py new file mode 100644 index 0000000000..0bbfe1b886 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/am.py @@ -0,0 +1,5861 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-include', 'stdint.h'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + +def string_cast(char_pointer, encoding='utf-8', errors='strict'): + value = ctypes.cast(char_pointer, ctypes.c_char_p).value + if value is not None and encoding is not None: + value = value.decode(encoding, errors=errors) + return value + + +def char_pointer_cast(string, encoding='utf-8'): + if encoding is not None: + try: + string = string.encode(encoding) + except AttributeError: + # In Python3, bytes has no encode attribute + pass + string = ctypes.c_char_p(string) + return ctypes.cast(string, ctypes.POINTER(ctypes.c_char)) + + + + + +V11_STRUCTS_H_ = True # macro +uint32_t = True # macro +uint8_t = True # macro +uint16_t = True # macro +uint64_t = True # macro +class struct_v11_gfx_mqd(Structure): + pass + +struct_v11_gfx_mqd._pack_ = 1 # source:False +struct_v11_gfx_mqd._fields_ = [ + ('shadow_base_lo', ctypes.c_uint32), + ('shadow_base_hi', ctypes.c_uint32), + ('gds_bkup_base_lo', ctypes.c_uint32), + ('gds_bkup_base_hi', ctypes.c_uint32), + ('fw_work_area_base_lo', ctypes.c_uint32), + ('fw_work_area_base_hi', ctypes.c_uint32), + ('shadow_initialized', ctypes.c_uint32), + ('ib_vmid', ctypes.c_uint32), + ('reserved_8', ctypes.c_uint32), + ('reserved_9', ctypes.c_uint32), + ('reserved_10', ctypes.c_uint32), + ('reserved_11', ctypes.c_uint32), + ('reserved_12', ctypes.c_uint32), + ('reserved_13', ctypes.c_uint32), + ('reserved_14', ctypes.c_uint32), + ('reserved_15', ctypes.c_uint32), + ('reserved_16', ctypes.c_uint32), + ('reserved_17', ctypes.c_uint32), + ('reserved_18', ctypes.c_uint32), + ('reserved_19', ctypes.c_uint32), + ('reserved_20', ctypes.c_uint32), + ('reserved_21', ctypes.c_uint32), + ('reserved_22', ctypes.c_uint32), + ('reserved_23', ctypes.c_uint32), + ('reserved_24', ctypes.c_uint32), + ('reserved_25', ctypes.c_uint32), + ('reserved_26', ctypes.c_uint32), + ('reserved_27', ctypes.c_uint32), + ('reserved_28', ctypes.c_uint32), + ('reserved_29', ctypes.c_uint32), + ('reserved_30', ctypes.c_uint32), + ('reserved_31', ctypes.c_uint32), + ('reserved_32', ctypes.c_uint32), + ('reserved_33', ctypes.c_uint32), + ('reserved_34', ctypes.c_uint32), + ('reserved_35', ctypes.c_uint32), + ('reserved_36', ctypes.c_uint32), + ('reserved_37', ctypes.c_uint32), + ('reserved_38', ctypes.c_uint32), + ('reserved_39', ctypes.c_uint32), + ('reserved_40', ctypes.c_uint32), + ('reserved_41', ctypes.c_uint32), + ('reserved_42', ctypes.c_uint32), + ('reserved_43', ctypes.c_uint32), + ('reserved_44', ctypes.c_uint32), + ('reserved_45', ctypes.c_uint32), + ('reserved_46', ctypes.c_uint32), + ('reserved_47', ctypes.c_uint32), + ('reserved_48', ctypes.c_uint32), + ('reserved_49', ctypes.c_uint32), + ('reserved_50', ctypes.c_uint32), + ('reserved_51', ctypes.c_uint32), + ('reserved_52', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('reserved_59', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('reserved_65', ctypes.c_uint32), + ('reserved_66', ctypes.c_uint32), + ('reserved_67', ctypes.c_uint32), + ('reserved_68', ctypes.c_uint32), + ('reserved_69', ctypes.c_uint32), + ('reserved_70', ctypes.c_uint32), + ('reserved_71', ctypes.c_uint32), + ('reserved_72', ctypes.c_uint32), + ('reserved_73', ctypes.c_uint32), + ('reserved_74', ctypes.c_uint32), + ('reserved_75', ctypes.c_uint32), + ('reserved_76', ctypes.c_uint32), + ('reserved_77', ctypes.c_uint32), + ('reserved_78', ctypes.c_uint32), + ('reserved_79', ctypes.c_uint32), + ('reserved_80', ctypes.c_uint32), + ('reserved_81', ctypes.c_uint32), + ('reserved_82', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('checksum_lo', ctypes.c_uint32), + ('checksum_hi', ctypes.c_uint32), + ('cp_mqd_query_time_lo', ctypes.c_uint32), + ('cp_mqd_query_time_hi', ctypes.c_uint32), + ('reserved_88', ctypes.c_uint32), + ('reserved_89', ctypes.c_uint32), + ('reserved_90', ctypes.c_uint32), + ('reserved_91', ctypes.c_uint32), + ('cp_mqd_query_wave_count', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_rptr', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_wptr', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_offset', ctypes.c_uint32), + ('reserved_96', ctypes.c_uint32), + ('reserved_97', ctypes.c_uint32), + ('reserved_98', ctypes.c_uint32), + ('reserved_99', ctypes.c_uint32), + ('reserved_100', ctypes.c_uint32), + ('reserved_101', ctypes.c_uint32), + ('reserved_102', ctypes.c_uint32), + ('reserved_103', ctypes.c_uint32), + ('control_buf_addr_lo', ctypes.c_uint32), + ('control_buf_addr_hi', ctypes.c_uint32), + ('disable_queue', ctypes.c_uint32), + ('reserved_107', ctypes.c_uint32), + ('reserved_108', ctypes.c_uint32), + ('reserved_109', ctypes.c_uint32), + ('reserved_110', ctypes.c_uint32), + ('reserved_111', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('reserved_114', ctypes.c_uint32), + ('reserved_115', ctypes.c_uint32), + ('reserved_116', ctypes.c_uint32), + ('reserved_117', ctypes.c_uint32), + ('reserved_118', ctypes.c_uint32), + ('reserved_119', ctypes.c_uint32), + ('reserved_120', ctypes.c_uint32), + ('reserved_121', ctypes.c_uint32), + ('reserved_122', ctypes.c_uint32), + ('reserved_123', ctypes.c_uint32), + ('reserved_124', ctypes.c_uint32), + ('reserved_125', ctypes.c_uint32), + ('reserved_126', ctypes.c_uint32), + ('reserved_127', ctypes.c_uint32), + ('cp_mqd_base_addr', ctypes.c_uint32), + ('cp_mqd_base_addr_hi', ctypes.c_uint32), + ('cp_gfx_hqd_active', ctypes.c_uint32), + ('cp_gfx_hqd_vmid', ctypes.c_uint32), + ('reserved_131', ctypes.c_uint32), + ('reserved_132', ctypes.c_uint32), + ('cp_gfx_hqd_queue_priority', ctypes.c_uint32), + ('cp_gfx_hqd_quantum', ctypes.c_uint32), + ('cp_gfx_hqd_base', ctypes.c_uint32), + ('cp_gfx_hqd_base_hi', ctypes.c_uint32), + ('cp_gfx_hqd_rptr', ctypes.c_uint32), + ('cp_gfx_hqd_rptr_addr', ctypes.c_uint32), + ('cp_gfx_hqd_rptr_addr_hi', ctypes.c_uint32), + ('cp_rb_wptr_poll_addr_lo', ctypes.c_uint32), + ('cp_rb_wptr_poll_addr_hi', ctypes.c_uint32), + ('cp_rb_doorbell_control', ctypes.c_uint32), + ('cp_gfx_hqd_offset', ctypes.c_uint32), + ('cp_gfx_hqd_cntl', ctypes.c_uint32), + ('reserved_146', ctypes.c_uint32), + ('reserved_147', ctypes.c_uint32), + ('cp_gfx_hqd_csmd_rptr', ctypes.c_uint32), + ('cp_gfx_hqd_wptr', ctypes.c_uint32), + ('cp_gfx_hqd_wptr_hi', ctypes.c_uint32), + ('reserved_151', ctypes.c_uint32), + ('reserved_152', ctypes.c_uint32), + ('reserved_153', ctypes.c_uint32), + ('reserved_154', ctypes.c_uint32), + ('reserved_155', ctypes.c_uint32), + ('cp_gfx_hqd_mapped', ctypes.c_uint32), + ('cp_gfx_hqd_que_mgr_control', ctypes.c_uint32), + ('reserved_158', ctypes.c_uint32), + ('reserved_159', ctypes.c_uint32), + ('cp_gfx_hqd_hq_status0', ctypes.c_uint32), + ('cp_gfx_hqd_hq_control0', ctypes.c_uint32), + ('cp_gfx_mqd_control', ctypes.c_uint32), + ('reserved_163', ctypes.c_uint32), + ('reserved_164', ctypes.c_uint32), + ('reserved_165', ctypes.c_uint32), + ('reserved_166', ctypes.c_uint32), + ('reserved_167', ctypes.c_uint32), + ('reserved_168', ctypes.c_uint32), + ('reserved_169', ctypes.c_uint32), + ('cp_num_prim_needed_count0_lo', ctypes.c_uint32), + ('cp_num_prim_needed_count0_hi', ctypes.c_uint32), + ('cp_num_prim_needed_count1_lo', ctypes.c_uint32), + ('cp_num_prim_needed_count1_hi', ctypes.c_uint32), + ('cp_num_prim_needed_count2_lo', ctypes.c_uint32), + ('cp_num_prim_needed_count2_hi', ctypes.c_uint32), + ('cp_num_prim_needed_count3_lo', ctypes.c_uint32), + ('cp_num_prim_needed_count3_hi', ctypes.c_uint32), + ('cp_num_prim_written_count0_lo', ctypes.c_uint32), + ('cp_num_prim_written_count0_hi', ctypes.c_uint32), + ('cp_num_prim_written_count1_lo', ctypes.c_uint32), + ('cp_num_prim_written_count1_hi', ctypes.c_uint32), + ('cp_num_prim_written_count2_lo', ctypes.c_uint32), + ('cp_num_prim_written_count2_hi', ctypes.c_uint32), + ('cp_num_prim_written_count3_lo', ctypes.c_uint32), + ('cp_num_prim_written_count3_hi', ctypes.c_uint32), + ('reserved_186', ctypes.c_uint32), + ('reserved_187', ctypes.c_uint32), + ('reserved_188', ctypes.c_uint32), + ('reserved_189', ctypes.c_uint32), + ('mp1_smn_fps_cnt', ctypes.c_uint32), + ('sq_thread_trace_buf0_base', ctypes.c_uint32), + ('sq_thread_trace_buf0_size', ctypes.c_uint32), + ('sq_thread_trace_buf1_base', ctypes.c_uint32), + ('sq_thread_trace_buf1_size', ctypes.c_uint32), + ('sq_thread_trace_wptr', ctypes.c_uint32), + ('sq_thread_trace_mask', ctypes.c_uint32), + ('sq_thread_trace_token_mask', ctypes.c_uint32), + ('sq_thread_trace_ctrl', ctypes.c_uint32), + ('sq_thread_trace_status', ctypes.c_uint32), + ('sq_thread_trace_dropped_cntr', ctypes.c_uint32), + ('sq_thread_trace_finish_done_debug', ctypes.c_uint32), + ('sq_thread_trace_gfx_draw_cntr', ctypes.c_uint32), + ('sq_thread_trace_gfx_marker_cntr', ctypes.c_uint32), + ('sq_thread_trace_hp3d_draw_cntr', ctypes.c_uint32), + ('sq_thread_trace_hp3d_marker_cntr', ctypes.c_uint32), + ('reserved_206', ctypes.c_uint32), + ('reserved_207', ctypes.c_uint32), + ('cp_sc_psinvoc_count0_lo', ctypes.c_uint32), + ('cp_sc_psinvoc_count0_hi', ctypes.c_uint32), + ('cp_pa_cprim_count_lo', ctypes.c_uint32), + ('cp_pa_cprim_count_hi', ctypes.c_uint32), + ('cp_pa_cinvoc_count_lo', ctypes.c_uint32), + ('cp_pa_cinvoc_count_hi', ctypes.c_uint32), + ('cp_vgt_vsinvoc_count_lo', ctypes.c_uint32), + ('cp_vgt_vsinvoc_count_hi', ctypes.c_uint32), + ('cp_vgt_gsinvoc_count_lo', ctypes.c_uint32), + ('cp_vgt_gsinvoc_count_hi', ctypes.c_uint32), + ('cp_vgt_gsprim_count_lo', ctypes.c_uint32), + ('cp_vgt_gsprim_count_hi', ctypes.c_uint32), + ('cp_vgt_iaprim_count_lo', ctypes.c_uint32), + ('cp_vgt_iaprim_count_hi', ctypes.c_uint32), + ('cp_vgt_iavert_count_lo', ctypes.c_uint32), + ('cp_vgt_iavert_count_hi', ctypes.c_uint32), + ('cp_vgt_hsinvoc_count_lo', ctypes.c_uint32), + ('cp_vgt_hsinvoc_count_hi', ctypes.c_uint32), + ('cp_vgt_dsinvoc_count_lo', ctypes.c_uint32), + ('cp_vgt_dsinvoc_count_hi', ctypes.c_uint32), + ('cp_vgt_csinvoc_count_lo', ctypes.c_uint32), + ('cp_vgt_csinvoc_count_hi', ctypes.c_uint32), + ('reserved_230', ctypes.c_uint32), + ('reserved_231', ctypes.c_uint32), + ('reserved_232', ctypes.c_uint32), + ('reserved_233', ctypes.c_uint32), + ('reserved_234', ctypes.c_uint32), + ('reserved_235', ctypes.c_uint32), + ('reserved_236', ctypes.c_uint32), + ('reserved_237', ctypes.c_uint32), + ('reserved_238', ctypes.c_uint32), + ('reserved_239', ctypes.c_uint32), + ('reserved_240', ctypes.c_uint32), + ('reserved_241', ctypes.c_uint32), + ('reserved_242', ctypes.c_uint32), + ('reserved_243', ctypes.c_uint32), + ('reserved_244', ctypes.c_uint32), + ('reserved_245', ctypes.c_uint32), + ('reserved_246', ctypes.c_uint32), + ('reserved_247', ctypes.c_uint32), + ('reserved_248', ctypes.c_uint32), + ('reserved_249', ctypes.c_uint32), + ('reserved_250', ctypes.c_uint32), + ('reserved_251', ctypes.c_uint32), + ('reserved_252', ctypes.c_uint32), + ('reserved_253', ctypes.c_uint32), + ('reserved_254', ctypes.c_uint32), + ('reserved_255', ctypes.c_uint32), + ('reserved_256', ctypes.c_uint32), + ('reserved_257', ctypes.c_uint32), + ('reserved_258', ctypes.c_uint32), + ('reserved_259', ctypes.c_uint32), + ('reserved_260', ctypes.c_uint32), + ('reserved_261', ctypes.c_uint32), + ('reserved_262', ctypes.c_uint32), + ('reserved_263', ctypes.c_uint32), + ('reserved_264', ctypes.c_uint32), + ('reserved_265', ctypes.c_uint32), + ('reserved_266', ctypes.c_uint32), + ('reserved_267', ctypes.c_uint32), + ('vgt_strmout_buffer_filled_size_0', ctypes.c_uint32), + ('vgt_strmout_buffer_filled_size_1', ctypes.c_uint32), + ('vgt_strmout_buffer_filled_size_2', ctypes.c_uint32), + ('vgt_strmout_buffer_filled_size_3', ctypes.c_uint32), + ('reserved_272', ctypes.c_uint32), + ('reserved_273', ctypes.c_uint32), + ('reserved_274', ctypes.c_uint32), + ('reserved_275', ctypes.c_uint32), + ('vgt_dma_max_size', ctypes.c_uint32), + ('vgt_dma_num_instances', ctypes.c_uint32), + ('reserved_278', ctypes.c_uint32), + ('reserved_279', ctypes.c_uint32), + ('reserved_280', ctypes.c_uint32), + ('reserved_281', ctypes.c_uint32), + ('reserved_282', ctypes.c_uint32), + ('reserved_283', ctypes.c_uint32), + ('reserved_284', ctypes.c_uint32), + ('reserved_285', ctypes.c_uint32), + ('reserved_286', ctypes.c_uint32), + ('reserved_287', ctypes.c_uint32), + ('it_set_base_ib_addr_lo', ctypes.c_uint32), + ('it_set_base_ib_addr_hi', ctypes.c_uint32), + ('reserved_290', ctypes.c_uint32), + ('reserved_291', ctypes.c_uint32), + ('reserved_292', ctypes.c_uint32), + ('reserved_293', ctypes.c_uint32), + ('reserved_294', ctypes.c_uint32), + ('reserved_295', ctypes.c_uint32), + ('reserved_296', ctypes.c_uint32), + ('reserved_297', ctypes.c_uint32), + ('reserved_298', ctypes.c_uint32), + ('reserved_299', ctypes.c_uint32), + ('reserved_300', ctypes.c_uint32), + ('reserved_301', ctypes.c_uint32), + ('reserved_302', ctypes.c_uint32), + ('reserved_303', ctypes.c_uint32), + ('reserved_304', ctypes.c_uint32), + ('reserved_305', ctypes.c_uint32), + ('reserved_306', ctypes.c_uint32), + ('reserved_307', ctypes.c_uint32), + ('reserved_308', ctypes.c_uint32), + ('reserved_309', ctypes.c_uint32), + ('reserved_310', ctypes.c_uint32), + ('reserved_311', ctypes.c_uint32), + ('reserved_312', ctypes.c_uint32), + ('reserved_313', ctypes.c_uint32), + ('reserved_314', ctypes.c_uint32), + ('reserved_315', ctypes.c_uint32), + ('reserved_316', ctypes.c_uint32), + ('reserved_317', ctypes.c_uint32), + ('reserved_318', ctypes.c_uint32), + ('reserved_319', ctypes.c_uint32), + ('reserved_320', ctypes.c_uint32), + ('reserved_321', ctypes.c_uint32), + ('reserved_322', ctypes.c_uint32), + ('reserved_323', ctypes.c_uint32), + ('reserved_324', ctypes.c_uint32), + ('reserved_325', ctypes.c_uint32), + ('reserved_326', ctypes.c_uint32), + ('reserved_327', ctypes.c_uint32), + ('reserved_328', ctypes.c_uint32), + ('reserved_329', ctypes.c_uint32), + ('reserved_330', ctypes.c_uint32), + ('reserved_331', ctypes.c_uint32), + ('reserved_332', ctypes.c_uint32), + ('reserved_333', ctypes.c_uint32), + ('reserved_334', ctypes.c_uint32), + ('reserved_335', ctypes.c_uint32), + ('reserved_336', ctypes.c_uint32), + ('reserved_337', ctypes.c_uint32), + ('reserved_338', ctypes.c_uint32), + ('reserved_339', ctypes.c_uint32), + ('reserved_340', ctypes.c_uint32), + ('reserved_341', ctypes.c_uint32), + ('reserved_342', ctypes.c_uint32), + ('reserved_343', ctypes.c_uint32), + ('reserved_344', ctypes.c_uint32), + ('reserved_345', ctypes.c_uint32), + ('reserved_346', ctypes.c_uint32), + ('reserved_347', ctypes.c_uint32), + ('reserved_348', ctypes.c_uint32), + ('reserved_349', ctypes.c_uint32), + ('reserved_350', ctypes.c_uint32), + ('reserved_351', ctypes.c_uint32), + ('reserved_352', ctypes.c_uint32), + ('reserved_353', ctypes.c_uint32), + ('reserved_354', ctypes.c_uint32), + ('reserved_355', ctypes.c_uint32), + ('spi_shader_pgm_rsrc3_ps', ctypes.c_uint32), + ('spi_shader_pgm_rsrc3_vs', ctypes.c_uint32), + ('spi_shader_pgm_rsrc3_gs', ctypes.c_uint32), + ('spi_shader_pgm_rsrc3_hs', ctypes.c_uint32), + ('spi_shader_pgm_rsrc4_ps', ctypes.c_uint32), + ('spi_shader_pgm_rsrc4_vs', ctypes.c_uint32), + ('spi_shader_pgm_rsrc4_gs', ctypes.c_uint32), + ('spi_shader_pgm_rsrc4_hs', ctypes.c_uint32), + ('db_occlusion_count0_low_00', ctypes.c_uint32), + ('db_occlusion_count0_hi_00', ctypes.c_uint32), + ('db_occlusion_count1_low_00', ctypes.c_uint32), + ('db_occlusion_count1_hi_00', ctypes.c_uint32), + ('db_occlusion_count2_low_00', ctypes.c_uint32), + ('db_occlusion_count2_hi_00', ctypes.c_uint32), + ('db_occlusion_count3_low_00', ctypes.c_uint32), + ('db_occlusion_count3_hi_00', ctypes.c_uint32), + ('db_occlusion_count0_low_01', ctypes.c_uint32), + ('db_occlusion_count0_hi_01', ctypes.c_uint32), + ('db_occlusion_count1_low_01', ctypes.c_uint32), + ('db_occlusion_count1_hi_01', ctypes.c_uint32), + ('db_occlusion_count2_low_01', ctypes.c_uint32), + ('db_occlusion_count2_hi_01', ctypes.c_uint32), + ('db_occlusion_count3_low_01', ctypes.c_uint32), + ('db_occlusion_count3_hi_01', ctypes.c_uint32), + ('db_occlusion_count0_low_02', ctypes.c_uint32), + ('db_occlusion_count0_hi_02', ctypes.c_uint32), + ('db_occlusion_count1_low_02', ctypes.c_uint32), + ('db_occlusion_count1_hi_02', ctypes.c_uint32), + ('db_occlusion_count2_low_02', ctypes.c_uint32), + ('db_occlusion_count2_hi_02', ctypes.c_uint32), + ('db_occlusion_count3_low_02', ctypes.c_uint32), + ('db_occlusion_count3_hi_02', ctypes.c_uint32), + ('db_occlusion_count0_low_03', ctypes.c_uint32), + ('db_occlusion_count0_hi_03', ctypes.c_uint32), + ('db_occlusion_count1_low_03', ctypes.c_uint32), + ('db_occlusion_count1_hi_03', ctypes.c_uint32), + ('db_occlusion_count2_low_03', ctypes.c_uint32), + ('db_occlusion_count2_hi_03', ctypes.c_uint32), + ('db_occlusion_count3_low_03', ctypes.c_uint32), + ('db_occlusion_count3_hi_03', ctypes.c_uint32), + ('db_occlusion_count0_low_04', ctypes.c_uint32), + ('db_occlusion_count0_hi_04', ctypes.c_uint32), + ('db_occlusion_count1_low_04', ctypes.c_uint32), + ('db_occlusion_count1_hi_04', ctypes.c_uint32), + ('db_occlusion_count2_low_04', ctypes.c_uint32), + ('db_occlusion_count2_hi_04', ctypes.c_uint32), + ('db_occlusion_count3_low_04', ctypes.c_uint32), + ('db_occlusion_count3_hi_04', ctypes.c_uint32), + ('db_occlusion_count0_low_05', ctypes.c_uint32), + ('db_occlusion_count0_hi_05', ctypes.c_uint32), + ('db_occlusion_count1_low_05', ctypes.c_uint32), + ('db_occlusion_count1_hi_05', ctypes.c_uint32), + ('db_occlusion_count2_low_05', ctypes.c_uint32), + ('db_occlusion_count2_hi_05', ctypes.c_uint32), + ('db_occlusion_count3_low_05', ctypes.c_uint32), + ('db_occlusion_count3_hi_05', ctypes.c_uint32), + ('db_occlusion_count0_low_06', ctypes.c_uint32), + ('db_occlusion_count0_hi_06', ctypes.c_uint32), + ('db_occlusion_count1_low_06', ctypes.c_uint32), + ('db_occlusion_count1_hi_06', ctypes.c_uint32), + ('db_occlusion_count2_low_06', ctypes.c_uint32), + ('db_occlusion_count2_hi_06', ctypes.c_uint32), + ('db_occlusion_count3_low_06', ctypes.c_uint32), + ('db_occlusion_count3_hi_06', ctypes.c_uint32), + ('db_occlusion_count0_low_07', ctypes.c_uint32), + ('db_occlusion_count0_hi_07', ctypes.c_uint32), + ('db_occlusion_count1_low_07', ctypes.c_uint32), + ('db_occlusion_count1_hi_07', ctypes.c_uint32), + ('db_occlusion_count2_low_07', ctypes.c_uint32), + ('db_occlusion_count2_hi_07', ctypes.c_uint32), + ('db_occlusion_count3_low_07', ctypes.c_uint32), + ('db_occlusion_count3_hi_07', ctypes.c_uint32), + ('db_occlusion_count0_low_10', ctypes.c_uint32), + ('db_occlusion_count0_hi_10', ctypes.c_uint32), + ('db_occlusion_count1_low_10', ctypes.c_uint32), + ('db_occlusion_count1_hi_10', ctypes.c_uint32), + ('db_occlusion_count2_low_10', ctypes.c_uint32), + ('db_occlusion_count2_hi_10', ctypes.c_uint32), + ('db_occlusion_count3_low_10', ctypes.c_uint32), + ('db_occlusion_count3_hi_10', ctypes.c_uint32), + ('db_occlusion_count0_low_11', ctypes.c_uint32), + ('db_occlusion_count0_hi_11', ctypes.c_uint32), + ('db_occlusion_count1_low_11', ctypes.c_uint32), + ('db_occlusion_count1_hi_11', ctypes.c_uint32), + ('db_occlusion_count2_low_11', ctypes.c_uint32), + ('db_occlusion_count2_hi_11', ctypes.c_uint32), + ('db_occlusion_count3_low_11', ctypes.c_uint32), + ('db_occlusion_count3_hi_11', ctypes.c_uint32), + ('db_occlusion_count0_low_12', ctypes.c_uint32), + ('db_occlusion_count0_hi_12', ctypes.c_uint32), + ('db_occlusion_count1_low_12', ctypes.c_uint32), + ('db_occlusion_count1_hi_12', ctypes.c_uint32), + ('db_occlusion_count2_low_12', ctypes.c_uint32), + ('db_occlusion_count2_hi_12', ctypes.c_uint32), + ('db_occlusion_count3_low_12', ctypes.c_uint32), + ('db_occlusion_count3_hi_12', ctypes.c_uint32), + ('db_occlusion_count0_low_13', ctypes.c_uint32), + ('db_occlusion_count0_hi_13', ctypes.c_uint32), + ('db_occlusion_count1_low_13', ctypes.c_uint32), + ('db_occlusion_count1_hi_13', ctypes.c_uint32), + ('db_occlusion_count2_low_13', ctypes.c_uint32), + ('db_occlusion_count2_hi_13', ctypes.c_uint32), + ('db_occlusion_count3_low_13', ctypes.c_uint32), + ('db_occlusion_count3_hi_13', ctypes.c_uint32), + ('db_occlusion_count0_low_14', ctypes.c_uint32), + ('db_occlusion_count0_hi_14', ctypes.c_uint32), + ('db_occlusion_count1_low_14', ctypes.c_uint32), + ('db_occlusion_count1_hi_14', ctypes.c_uint32), + ('db_occlusion_count2_low_14', ctypes.c_uint32), + ('db_occlusion_count2_hi_14', ctypes.c_uint32), + ('db_occlusion_count3_low_14', ctypes.c_uint32), + ('db_occlusion_count3_hi_14', ctypes.c_uint32), + ('db_occlusion_count0_low_15', ctypes.c_uint32), + ('db_occlusion_count0_hi_15', ctypes.c_uint32), + ('db_occlusion_count1_low_15', ctypes.c_uint32), + ('db_occlusion_count1_hi_15', ctypes.c_uint32), + ('db_occlusion_count2_low_15', ctypes.c_uint32), + ('db_occlusion_count2_hi_15', ctypes.c_uint32), + ('db_occlusion_count3_low_15', ctypes.c_uint32), + ('db_occlusion_count3_hi_15', ctypes.c_uint32), + ('db_occlusion_count0_low_16', ctypes.c_uint32), + ('db_occlusion_count0_hi_16', ctypes.c_uint32), + ('db_occlusion_count1_low_16', ctypes.c_uint32), + ('db_occlusion_count1_hi_16', ctypes.c_uint32), + ('db_occlusion_count2_low_16', ctypes.c_uint32), + ('db_occlusion_count2_hi_16', ctypes.c_uint32), + ('db_occlusion_count3_low_16', ctypes.c_uint32), + ('db_occlusion_count3_hi_16', ctypes.c_uint32), + ('db_occlusion_count0_low_17', ctypes.c_uint32), + ('db_occlusion_count0_hi_17', ctypes.c_uint32), + ('db_occlusion_count1_low_17', ctypes.c_uint32), + ('db_occlusion_count1_hi_17', ctypes.c_uint32), + ('db_occlusion_count2_low_17', ctypes.c_uint32), + ('db_occlusion_count2_hi_17', ctypes.c_uint32), + ('db_occlusion_count3_low_17', ctypes.c_uint32), + ('db_occlusion_count3_hi_17', ctypes.c_uint32), + ('reserved_492', ctypes.c_uint32), + ('reserved_493', ctypes.c_uint32), + ('reserved_494', ctypes.c_uint32), + ('reserved_495', ctypes.c_uint32), + ('reserved_496', ctypes.c_uint32), + ('reserved_497', ctypes.c_uint32), + ('reserved_498', ctypes.c_uint32), + ('reserved_499', ctypes.c_uint32), + ('reserved_500', ctypes.c_uint32), + ('reserved_501', ctypes.c_uint32), + ('reserved_502', ctypes.c_uint32), + ('reserved_503', ctypes.c_uint32), + ('reserved_504', ctypes.c_uint32), + ('reserved_505', ctypes.c_uint32), + ('reserved_506', ctypes.c_uint32), + ('reserved_507', ctypes.c_uint32), + ('reserved_508', ctypes.c_uint32), + ('reserved_509', ctypes.c_uint32), + ('reserved_510', ctypes.c_uint32), + ('reserved_511', ctypes.c_uint32), +] + +class struct_v11_sdma_mqd(Structure): + pass + +struct_v11_sdma_mqd._pack_ = 1 # source:False +struct_v11_sdma_mqd._fields_ = [ + ('sdmax_rlcx_rb_cntl', ctypes.c_uint32), + ('sdmax_rlcx_rb_base', ctypes.c_uint32), + ('sdmax_rlcx_rb_base_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_ib_cntl', ctypes.c_uint32), + ('sdmax_rlcx_ib_rptr', ctypes.c_uint32), + ('sdmax_rlcx_ib_offset', ctypes.c_uint32), + ('sdmax_rlcx_ib_base_lo', ctypes.c_uint32), + ('sdmax_rlcx_ib_base_hi', ctypes.c_uint32), + ('sdmax_rlcx_ib_size', ctypes.c_uint32), + ('sdmax_rlcx_skip_cntl', ctypes.c_uint32), + ('sdmax_rlcx_context_status', ctypes.c_uint32), + ('sdmax_rlcx_doorbell', ctypes.c_uint32), + ('sdmax_rlcx_doorbell_log', ctypes.c_uint32), + ('sdmax_rlcx_doorbell_offset', ctypes.c_uint32), + ('sdmax_rlcx_csa_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_csa_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_sched_cntl', ctypes.c_uint32), + ('sdmax_rlcx_ib_sub_remain', ctypes.c_uint32), + ('sdmax_rlcx_preempt', ctypes.c_uint32), + ('sdmax_rlcx_dummy_reg', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_poll_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_poll_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_rb_aql_cntl', ctypes.c_uint32), + ('sdmax_rlcx_minor_ptr_update', ctypes.c_uint32), + ('sdmax_rlcx_rb_preempt', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data0', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data1', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data2', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data3', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data4', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data5', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data6', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data7', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data8', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data9', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data10', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_cntl', ctypes.c_uint32), + ('sdmax_rlcx_f32_dbg0', ctypes.c_uint32), + ('sdmax_rlcx_f32_dbg1', ctypes.c_uint32), + ('reserved_45', ctypes.c_uint32), + ('reserved_46', ctypes.c_uint32), + ('reserved_47', ctypes.c_uint32), + ('reserved_48', ctypes.c_uint32), + ('reserved_49', ctypes.c_uint32), + ('reserved_50', ctypes.c_uint32), + ('reserved_51', ctypes.c_uint32), + ('reserved_52', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('reserved_59', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('reserved_65', ctypes.c_uint32), + ('reserved_66', ctypes.c_uint32), + ('reserved_67', ctypes.c_uint32), + ('reserved_68', ctypes.c_uint32), + ('reserved_69', ctypes.c_uint32), + ('reserved_70', ctypes.c_uint32), + ('reserved_71', ctypes.c_uint32), + ('reserved_72', ctypes.c_uint32), + ('reserved_73', ctypes.c_uint32), + ('reserved_74', ctypes.c_uint32), + ('reserved_75', ctypes.c_uint32), + ('reserved_76', ctypes.c_uint32), + ('reserved_77', ctypes.c_uint32), + ('reserved_78', ctypes.c_uint32), + ('reserved_79', ctypes.c_uint32), + ('reserved_80', ctypes.c_uint32), + ('reserved_81', ctypes.c_uint32), + ('reserved_82', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('reserved_84', ctypes.c_uint32), + ('reserved_85', ctypes.c_uint32), + ('reserved_86', ctypes.c_uint32), + ('reserved_87', ctypes.c_uint32), + ('reserved_88', ctypes.c_uint32), + ('reserved_89', ctypes.c_uint32), + ('reserved_90', ctypes.c_uint32), + ('reserved_91', ctypes.c_uint32), + ('reserved_92', ctypes.c_uint32), + ('reserved_93', ctypes.c_uint32), + ('reserved_94', ctypes.c_uint32), + ('reserved_95', ctypes.c_uint32), + ('reserved_96', ctypes.c_uint32), + ('reserved_97', ctypes.c_uint32), + ('reserved_98', ctypes.c_uint32), + ('reserved_99', ctypes.c_uint32), + ('reserved_100', ctypes.c_uint32), + ('reserved_101', ctypes.c_uint32), + ('reserved_102', ctypes.c_uint32), + ('reserved_103', ctypes.c_uint32), + ('reserved_104', ctypes.c_uint32), + ('reserved_105', ctypes.c_uint32), + ('reserved_106', ctypes.c_uint32), + ('reserved_107', ctypes.c_uint32), + ('reserved_108', ctypes.c_uint32), + ('reserved_109', ctypes.c_uint32), + ('reserved_110', ctypes.c_uint32), + ('reserved_111', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('reserved_114', ctypes.c_uint32), + ('reserved_115', ctypes.c_uint32), + ('reserved_116', ctypes.c_uint32), + ('reserved_117', ctypes.c_uint32), + ('reserved_118', ctypes.c_uint32), + ('reserved_119', ctypes.c_uint32), + ('reserved_120', ctypes.c_uint32), + ('reserved_121', ctypes.c_uint32), + ('reserved_122', ctypes.c_uint32), + ('reserved_123', ctypes.c_uint32), + ('reserved_124', ctypes.c_uint32), + ('reserved_125', ctypes.c_uint32), + ('sdma_engine_id', ctypes.c_uint32), + ('sdma_queue_id', ctypes.c_uint32), +] + +class struct_v11_compute_mqd(Structure): + pass + +struct_v11_compute_mqd._pack_ = 1 # source:False +struct_v11_compute_mqd._fields_ = [ + ('header', ctypes.c_uint32), + ('compute_dispatch_initiator', ctypes.c_uint32), + ('compute_dim_x', ctypes.c_uint32), + ('compute_dim_y', ctypes.c_uint32), + ('compute_dim_z', ctypes.c_uint32), + ('compute_start_x', ctypes.c_uint32), + ('compute_start_y', ctypes.c_uint32), + ('compute_start_z', ctypes.c_uint32), + ('compute_num_thread_x', ctypes.c_uint32), + ('compute_num_thread_y', ctypes.c_uint32), + ('compute_num_thread_z', ctypes.c_uint32), + ('compute_pipelinestat_enable', ctypes.c_uint32), + ('compute_perfcount_enable', ctypes.c_uint32), + ('compute_pgm_lo', ctypes.c_uint32), + ('compute_pgm_hi', ctypes.c_uint32), + ('compute_dispatch_pkt_addr_lo', ctypes.c_uint32), + ('compute_dispatch_pkt_addr_hi', ctypes.c_uint32), + ('compute_dispatch_scratch_base_lo', ctypes.c_uint32), + ('compute_dispatch_scratch_base_hi', ctypes.c_uint32), + ('compute_pgm_rsrc1', ctypes.c_uint32), + ('compute_pgm_rsrc2', ctypes.c_uint32), + ('compute_vmid', ctypes.c_uint32), + ('compute_resource_limits', ctypes.c_uint32), + ('compute_static_thread_mgmt_se0', ctypes.c_uint32), + ('compute_static_thread_mgmt_se1', ctypes.c_uint32), + ('compute_tmpring_size', ctypes.c_uint32), + ('compute_static_thread_mgmt_se2', ctypes.c_uint32), + ('compute_static_thread_mgmt_se3', ctypes.c_uint32), + ('compute_restart_x', ctypes.c_uint32), + ('compute_restart_y', ctypes.c_uint32), + ('compute_restart_z', ctypes.c_uint32), + ('compute_thread_trace_enable', ctypes.c_uint32), + ('compute_misc_reserved', ctypes.c_uint32), + ('compute_dispatch_id', ctypes.c_uint32), + ('compute_threadgroup_id', ctypes.c_uint32), + ('compute_req_ctrl', ctypes.c_uint32), + ('reserved_36', ctypes.c_uint32), + ('compute_user_accum_0', ctypes.c_uint32), + ('compute_user_accum_1', ctypes.c_uint32), + ('compute_user_accum_2', ctypes.c_uint32), + ('compute_user_accum_3', ctypes.c_uint32), + ('compute_pgm_rsrc3', ctypes.c_uint32), + ('compute_ddid_index', ctypes.c_uint32), + ('compute_shader_chksum', ctypes.c_uint32), + ('compute_static_thread_mgmt_se4', ctypes.c_uint32), + ('compute_static_thread_mgmt_se5', ctypes.c_uint32), + ('compute_static_thread_mgmt_se6', ctypes.c_uint32), + ('compute_static_thread_mgmt_se7', ctypes.c_uint32), + ('compute_dispatch_interleave', ctypes.c_uint32), + ('compute_relaunch', ctypes.c_uint32), + ('compute_wave_restore_addr_lo', ctypes.c_uint32), + ('compute_wave_restore_addr_hi', ctypes.c_uint32), + ('compute_wave_restore_control', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('reserved_59', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('compute_user_data_0', ctypes.c_uint32), + ('compute_user_data_1', ctypes.c_uint32), + ('compute_user_data_2', ctypes.c_uint32), + ('compute_user_data_3', ctypes.c_uint32), + ('compute_user_data_4', ctypes.c_uint32), + ('compute_user_data_5', ctypes.c_uint32), + ('compute_user_data_6', ctypes.c_uint32), + ('compute_user_data_7', ctypes.c_uint32), + ('compute_user_data_8', ctypes.c_uint32), + ('compute_user_data_9', ctypes.c_uint32), + ('compute_user_data_10', ctypes.c_uint32), + ('compute_user_data_11', ctypes.c_uint32), + ('compute_user_data_12', ctypes.c_uint32), + ('compute_user_data_13', ctypes.c_uint32), + ('compute_user_data_14', ctypes.c_uint32), + ('compute_user_data_15', ctypes.c_uint32), + ('cp_compute_csinvoc_count_lo', ctypes.c_uint32), + ('cp_compute_csinvoc_count_hi', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('reserved_84', ctypes.c_uint32), + ('reserved_85', ctypes.c_uint32), + ('cp_mqd_query_time_lo', ctypes.c_uint32), + ('cp_mqd_query_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_start_time_lo', ctypes.c_uint32), + ('cp_mqd_connect_start_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_end_time_lo', ctypes.c_uint32), + ('cp_mqd_connect_end_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_end_wf_count', ctypes.c_uint32), + ('cp_mqd_connect_end_pq_rptr', ctypes.c_uint32), + ('cp_mqd_connect_end_pq_wptr', ctypes.c_uint32), + ('cp_mqd_connect_end_ib_rptr', ctypes.c_uint32), + ('cp_mqd_readindex_lo', ctypes.c_uint32), + ('cp_mqd_readindex_hi', ctypes.c_uint32), + ('cp_mqd_save_start_time_lo', ctypes.c_uint32), + ('cp_mqd_save_start_time_hi', ctypes.c_uint32), + ('cp_mqd_save_end_time_lo', ctypes.c_uint32), + ('cp_mqd_save_end_time_hi', ctypes.c_uint32), + ('cp_mqd_restore_start_time_lo', ctypes.c_uint32), + ('cp_mqd_restore_start_time_hi', ctypes.c_uint32), + ('cp_mqd_restore_end_time_lo', ctypes.c_uint32), + ('cp_mqd_restore_end_time_hi', ctypes.c_uint32), + ('disable_queue', ctypes.c_uint32), + ('reserved_107', ctypes.c_uint32), + ('gds_cs_ctxsw_cnt0', ctypes.c_uint32), + ('gds_cs_ctxsw_cnt1', ctypes.c_uint32), + ('gds_cs_ctxsw_cnt2', ctypes.c_uint32), + ('gds_cs_ctxsw_cnt3', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('cp_pq_exe_status_lo', ctypes.c_uint32), + ('cp_pq_exe_status_hi', ctypes.c_uint32), + ('cp_packet_id_lo', ctypes.c_uint32), + ('cp_packet_id_hi', ctypes.c_uint32), + ('cp_packet_exe_status_lo', ctypes.c_uint32), + ('cp_packet_exe_status_hi', ctypes.c_uint32), + ('gds_save_base_addr_lo', ctypes.c_uint32), + ('gds_save_base_addr_hi', ctypes.c_uint32), + ('gds_save_mask_lo', ctypes.c_uint32), + ('gds_save_mask_hi', ctypes.c_uint32), + ('ctx_save_base_addr_lo', ctypes.c_uint32), + ('ctx_save_base_addr_hi', ctypes.c_uint32), + ('reserved_126', ctypes.c_uint32), + ('reserved_127', ctypes.c_uint32), + ('cp_mqd_base_addr_lo', ctypes.c_uint32), + ('cp_mqd_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_active', ctypes.c_uint32), + ('cp_hqd_vmid', ctypes.c_uint32), + ('cp_hqd_persistent_state', ctypes.c_uint32), + ('cp_hqd_pipe_priority', ctypes.c_uint32), + ('cp_hqd_queue_priority', ctypes.c_uint32), + ('cp_hqd_quantum', ctypes.c_uint32), + ('cp_hqd_pq_base_lo', ctypes.c_uint32), + ('cp_hqd_pq_base_hi', ctypes.c_uint32), + ('cp_hqd_pq_rptr', ctypes.c_uint32), + ('cp_hqd_pq_rptr_report_addr_lo', ctypes.c_uint32), + ('cp_hqd_pq_rptr_report_addr_hi', ctypes.c_uint32), + ('cp_hqd_pq_wptr_poll_addr_lo', ctypes.c_uint32), + ('cp_hqd_pq_wptr_poll_addr_hi', ctypes.c_uint32), + ('cp_hqd_pq_doorbell_control', ctypes.c_uint32), + ('reserved_144', ctypes.c_uint32), + ('cp_hqd_pq_control', ctypes.c_uint32), + ('cp_hqd_ib_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_ib_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_ib_rptr', ctypes.c_uint32), + ('cp_hqd_ib_control', ctypes.c_uint32), + ('cp_hqd_iq_timer', ctypes.c_uint32), + ('cp_hqd_iq_rptr', ctypes.c_uint32), + ('cp_hqd_dequeue_request', ctypes.c_uint32), + ('cp_hqd_dma_offload', ctypes.c_uint32), + ('cp_hqd_sema_cmd', ctypes.c_uint32), + ('cp_hqd_msg_type', ctypes.c_uint32), + ('cp_hqd_atomic0_preop_lo', ctypes.c_uint32), + ('cp_hqd_atomic0_preop_hi', ctypes.c_uint32), + ('cp_hqd_atomic1_preop_lo', ctypes.c_uint32), + ('cp_hqd_atomic1_preop_hi', ctypes.c_uint32), + ('cp_hqd_hq_status0', ctypes.c_uint32), + ('cp_hqd_hq_control0', ctypes.c_uint32), + ('cp_mqd_control', ctypes.c_uint32), + ('cp_hqd_hq_status1', ctypes.c_uint32), + ('cp_hqd_hq_control1', ctypes.c_uint32), + ('cp_hqd_eop_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_eop_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_eop_control', ctypes.c_uint32), + ('cp_hqd_eop_rptr', ctypes.c_uint32), + ('cp_hqd_eop_wptr', ctypes.c_uint32), + ('cp_hqd_eop_done_events', ctypes.c_uint32), + ('cp_hqd_ctx_save_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_ctx_save_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_ctx_save_control', ctypes.c_uint32), + ('cp_hqd_cntl_stack_offset', ctypes.c_uint32), + ('cp_hqd_cntl_stack_size', ctypes.c_uint32), + ('cp_hqd_wg_state_offset', ctypes.c_uint32), + ('cp_hqd_ctx_save_size', ctypes.c_uint32), + ('cp_hqd_gds_resource_state', ctypes.c_uint32), + ('cp_hqd_error', ctypes.c_uint32), + ('cp_hqd_eop_wptr_mem', ctypes.c_uint32), + ('cp_hqd_aql_control', ctypes.c_uint32), + ('cp_hqd_pq_wptr_lo', ctypes.c_uint32), + ('cp_hqd_pq_wptr_hi', ctypes.c_uint32), + ('reserved_184', ctypes.c_uint32), + ('reserved_185', ctypes.c_uint32), + ('reserved_186', ctypes.c_uint32), + ('reserved_187', ctypes.c_uint32), + ('reserved_188', ctypes.c_uint32), + ('reserved_189', ctypes.c_uint32), + ('reserved_190', ctypes.c_uint32), + ('reserved_191', ctypes.c_uint32), + ('iqtimer_pkt_header', ctypes.c_uint32), + ('iqtimer_pkt_dw0', ctypes.c_uint32), + ('iqtimer_pkt_dw1', ctypes.c_uint32), + ('iqtimer_pkt_dw2', ctypes.c_uint32), + ('iqtimer_pkt_dw3', ctypes.c_uint32), + ('iqtimer_pkt_dw4', ctypes.c_uint32), + ('iqtimer_pkt_dw5', ctypes.c_uint32), + ('iqtimer_pkt_dw6', ctypes.c_uint32), + ('iqtimer_pkt_dw7', ctypes.c_uint32), + ('iqtimer_pkt_dw8', ctypes.c_uint32), + ('iqtimer_pkt_dw9', ctypes.c_uint32), + ('iqtimer_pkt_dw10', ctypes.c_uint32), + ('iqtimer_pkt_dw11', ctypes.c_uint32), + ('iqtimer_pkt_dw12', ctypes.c_uint32), + ('iqtimer_pkt_dw13', ctypes.c_uint32), + ('iqtimer_pkt_dw14', ctypes.c_uint32), + ('iqtimer_pkt_dw15', ctypes.c_uint32), + ('iqtimer_pkt_dw16', ctypes.c_uint32), + ('iqtimer_pkt_dw17', ctypes.c_uint32), + ('iqtimer_pkt_dw18', ctypes.c_uint32), + ('iqtimer_pkt_dw19', ctypes.c_uint32), + ('iqtimer_pkt_dw20', ctypes.c_uint32), + ('iqtimer_pkt_dw21', ctypes.c_uint32), + ('iqtimer_pkt_dw22', ctypes.c_uint32), + ('iqtimer_pkt_dw23', ctypes.c_uint32), + ('iqtimer_pkt_dw24', ctypes.c_uint32), + ('iqtimer_pkt_dw25', ctypes.c_uint32), + ('iqtimer_pkt_dw26', ctypes.c_uint32), + ('iqtimer_pkt_dw27', ctypes.c_uint32), + ('iqtimer_pkt_dw28', ctypes.c_uint32), + ('iqtimer_pkt_dw29', ctypes.c_uint32), + ('iqtimer_pkt_dw30', ctypes.c_uint32), + ('iqtimer_pkt_dw31', ctypes.c_uint32), + ('reserved_225', ctypes.c_uint32), + ('reserved_226', ctypes.c_uint32), + ('reserved_227', ctypes.c_uint32), + ('set_resources_header', ctypes.c_uint32), + ('set_resources_dw1', ctypes.c_uint32), + ('set_resources_dw2', ctypes.c_uint32), + ('set_resources_dw3', ctypes.c_uint32), + ('set_resources_dw4', ctypes.c_uint32), + ('set_resources_dw5', ctypes.c_uint32), + ('set_resources_dw6', ctypes.c_uint32), + ('set_resources_dw7', ctypes.c_uint32), + ('reserved_236', ctypes.c_uint32), + ('reserved_237', ctypes.c_uint32), + ('reserved_238', ctypes.c_uint32), + ('reserved_239', ctypes.c_uint32), + ('queue_doorbell_id0', ctypes.c_uint32), + ('queue_doorbell_id1', ctypes.c_uint32), + ('queue_doorbell_id2', ctypes.c_uint32), + ('queue_doorbell_id3', ctypes.c_uint32), + ('queue_doorbell_id4', ctypes.c_uint32), + ('queue_doorbell_id5', ctypes.c_uint32), + ('queue_doorbell_id6', ctypes.c_uint32), + ('queue_doorbell_id7', ctypes.c_uint32), + ('queue_doorbell_id8', ctypes.c_uint32), + ('queue_doorbell_id9', ctypes.c_uint32), + ('queue_doorbell_id10', ctypes.c_uint32), + ('queue_doorbell_id11', ctypes.c_uint32), + ('queue_doorbell_id12', ctypes.c_uint32), + ('queue_doorbell_id13', ctypes.c_uint32), + ('queue_doorbell_id14', ctypes.c_uint32), + ('queue_doorbell_id15', ctypes.c_uint32), + ('control_buf_addr_lo', ctypes.c_uint32), + ('control_buf_addr_hi', ctypes.c_uint32), + ('control_buf_wptr_lo', ctypes.c_uint32), + ('control_buf_wptr_hi', ctypes.c_uint32), + ('control_buf_dptr_lo', ctypes.c_uint32), + ('control_buf_dptr_hi', ctypes.c_uint32), + ('control_buf_num_entries', ctypes.c_uint32), + ('draw_ring_addr_lo', ctypes.c_uint32), + ('draw_ring_addr_hi', ctypes.c_uint32), + ('reserved_265', ctypes.c_uint32), + ('reserved_266', ctypes.c_uint32), + ('reserved_267', ctypes.c_uint32), + ('reserved_268', ctypes.c_uint32), + ('reserved_269', ctypes.c_uint32), + ('reserved_270', ctypes.c_uint32), + ('reserved_271', ctypes.c_uint32), + ('reserved_272', ctypes.c_uint32), + ('reserved_273', ctypes.c_uint32), + ('reserved_274', ctypes.c_uint32), + ('reserved_275', ctypes.c_uint32), + ('reserved_276', ctypes.c_uint32), + ('reserved_277', ctypes.c_uint32), + ('reserved_278', ctypes.c_uint32), + ('reserved_279', ctypes.c_uint32), + ('reserved_280', ctypes.c_uint32), + ('reserved_281', ctypes.c_uint32), + ('reserved_282', ctypes.c_uint32), + ('reserved_283', ctypes.c_uint32), + ('reserved_284', ctypes.c_uint32), + ('reserved_285', ctypes.c_uint32), + ('reserved_286', ctypes.c_uint32), + ('reserved_287', ctypes.c_uint32), + ('reserved_288', ctypes.c_uint32), + ('reserved_289', ctypes.c_uint32), + ('reserved_290', ctypes.c_uint32), + ('reserved_291', ctypes.c_uint32), + ('reserved_292', ctypes.c_uint32), + ('reserved_293', ctypes.c_uint32), + ('reserved_294', ctypes.c_uint32), + ('reserved_295', ctypes.c_uint32), + ('reserved_296', ctypes.c_uint32), + ('reserved_297', ctypes.c_uint32), + ('reserved_298', ctypes.c_uint32), + ('reserved_299', ctypes.c_uint32), + ('reserved_300', ctypes.c_uint32), + ('reserved_301', ctypes.c_uint32), + ('reserved_302', ctypes.c_uint32), + ('reserved_303', ctypes.c_uint32), + ('reserved_304', ctypes.c_uint32), + ('reserved_305', ctypes.c_uint32), + ('reserved_306', ctypes.c_uint32), + ('reserved_307', ctypes.c_uint32), + ('reserved_308', ctypes.c_uint32), + ('reserved_309', ctypes.c_uint32), + ('reserved_310', ctypes.c_uint32), + ('reserved_311', ctypes.c_uint32), + ('reserved_312', ctypes.c_uint32), + ('reserved_313', ctypes.c_uint32), + ('reserved_314', ctypes.c_uint32), + ('reserved_315', ctypes.c_uint32), + ('reserved_316', ctypes.c_uint32), + ('reserved_317', ctypes.c_uint32), + ('reserved_318', ctypes.c_uint32), + ('reserved_319', ctypes.c_uint32), + ('reserved_320', ctypes.c_uint32), + ('reserved_321', ctypes.c_uint32), + ('reserved_322', ctypes.c_uint32), + ('reserved_323', ctypes.c_uint32), + ('reserved_324', ctypes.c_uint32), + ('reserved_325', ctypes.c_uint32), + ('reserved_326', ctypes.c_uint32), + ('reserved_327', ctypes.c_uint32), + ('reserved_328', ctypes.c_uint32), + ('reserved_329', ctypes.c_uint32), + ('reserved_330', ctypes.c_uint32), + ('reserved_331', ctypes.c_uint32), + ('reserved_332', ctypes.c_uint32), + ('reserved_333', ctypes.c_uint32), + ('reserved_334', ctypes.c_uint32), + ('reserved_335', ctypes.c_uint32), + ('reserved_336', ctypes.c_uint32), + ('reserved_337', ctypes.c_uint32), + ('reserved_338', ctypes.c_uint32), + ('reserved_339', ctypes.c_uint32), + ('reserved_340', ctypes.c_uint32), + ('reserved_341', ctypes.c_uint32), + ('reserved_342', ctypes.c_uint32), + ('reserved_343', ctypes.c_uint32), + ('reserved_344', ctypes.c_uint32), + ('reserved_345', ctypes.c_uint32), + ('reserved_346', ctypes.c_uint32), + ('reserved_347', ctypes.c_uint32), + ('reserved_348', ctypes.c_uint32), + ('reserved_349', ctypes.c_uint32), + ('reserved_350', ctypes.c_uint32), + ('reserved_351', ctypes.c_uint32), + ('reserved_352', ctypes.c_uint32), + ('reserved_353', ctypes.c_uint32), + ('reserved_354', ctypes.c_uint32), + ('reserved_355', ctypes.c_uint32), + ('reserved_356', ctypes.c_uint32), + ('reserved_357', ctypes.c_uint32), + ('reserved_358', ctypes.c_uint32), + ('reserved_359', ctypes.c_uint32), + ('reserved_360', ctypes.c_uint32), + ('reserved_361', ctypes.c_uint32), + ('reserved_362', ctypes.c_uint32), + ('reserved_363', ctypes.c_uint32), + ('reserved_364', ctypes.c_uint32), + ('reserved_365', ctypes.c_uint32), + ('reserved_366', ctypes.c_uint32), + ('reserved_367', ctypes.c_uint32), + ('reserved_368', ctypes.c_uint32), + ('reserved_369', ctypes.c_uint32), + ('reserved_370', ctypes.c_uint32), + ('reserved_371', ctypes.c_uint32), + ('reserved_372', ctypes.c_uint32), + ('reserved_373', ctypes.c_uint32), + ('reserved_374', ctypes.c_uint32), + ('reserved_375', ctypes.c_uint32), + ('reserved_376', ctypes.c_uint32), + ('reserved_377', ctypes.c_uint32), + ('reserved_378', ctypes.c_uint32), + ('reserved_379', ctypes.c_uint32), + ('reserved_380', ctypes.c_uint32), + ('reserved_381', ctypes.c_uint32), + ('reserved_382', ctypes.c_uint32), + ('reserved_383', ctypes.c_uint32), + ('reserved_384', ctypes.c_uint32), + ('reserved_385', ctypes.c_uint32), + ('reserved_386', ctypes.c_uint32), + ('reserved_387', ctypes.c_uint32), + ('reserved_388', ctypes.c_uint32), + ('reserved_389', ctypes.c_uint32), + ('reserved_390', ctypes.c_uint32), + ('reserved_391', ctypes.c_uint32), + ('reserved_392', ctypes.c_uint32), + ('reserved_393', ctypes.c_uint32), + ('reserved_394', ctypes.c_uint32), + ('reserved_395', ctypes.c_uint32), + ('reserved_396', ctypes.c_uint32), + ('reserved_397', ctypes.c_uint32), + ('reserved_398', ctypes.c_uint32), + ('reserved_399', ctypes.c_uint32), + ('reserved_400', ctypes.c_uint32), + ('reserved_401', ctypes.c_uint32), + ('reserved_402', ctypes.c_uint32), + ('reserved_403', ctypes.c_uint32), + ('reserved_404', ctypes.c_uint32), + ('reserved_405', ctypes.c_uint32), + ('reserved_406', ctypes.c_uint32), + ('reserved_407', ctypes.c_uint32), + ('reserved_408', ctypes.c_uint32), + ('reserved_409', ctypes.c_uint32), + ('reserved_410', ctypes.c_uint32), + ('reserved_411', ctypes.c_uint32), + ('reserved_412', ctypes.c_uint32), + ('reserved_413', ctypes.c_uint32), + ('reserved_414', ctypes.c_uint32), + ('reserved_415', ctypes.c_uint32), + ('reserved_416', ctypes.c_uint32), + ('reserved_417', ctypes.c_uint32), + ('reserved_418', ctypes.c_uint32), + ('reserved_419', ctypes.c_uint32), + ('reserved_420', ctypes.c_uint32), + ('reserved_421', ctypes.c_uint32), + ('reserved_422', ctypes.c_uint32), + ('reserved_423', ctypes.c_uint32), + ('reserved_424', ctypes.c_uint32), + ('reserved_425', ctypes.c_uint32), + ('reserved_426', ctypes.c_uint32), + ('reserved_427', ctypes.c_uint32), + ('reserved_428', ctypes.c_uint32), + ('reserved_429', ctypes.c_uint32), + ('reserved_430', ctypes.c_uint32), + ('reserved_431', ctypes.c_uint32), + ('reserved_432', ctypes.c_uint32), + ('reserved_433', ctypes.c_uint32), + ('reserved_434', ctypes.c_uint32), + ('reserved_435', ctypes.c_uint32), + ('reserved_436', ctypes.c_uint32), + ('reserved_437', ctypes.c_uint32), + ('reserved_438', ctypes.c_uint32), + ('reserved_439', ctypes.c_uint32), + ('reserved_440', ctypes.c_uint32), + ('reserved_441', ctypes.c_uint32), + ('reserved_442', ctypes.c_uint32), + ('reserved_443', ctypes.c_uint32), + ('reserved_444', ctypes.c_uint32), + ('reserved_445', ctypes.c_uint32), + ('reserved_446', ctypes.c_uint32), + ('reserved_447', ctypes.c_uint32), + ('gws_0_val', ctypes.c_uint32), + ('gws_1_val', ctypes.c_uint32), + ('gws_2_val', ctypes.c_uint32), + ('gws_3_val', ctypes.c_uint32), + ('gws_4_val', ctypes.c_uint32), + ('gws_5_val', ctypes.c_uint32), + ('gws_6_val', ctypes.c_uint32), + ('gws_7_val', ctypes.c_uint32), + ('gws_8_val', ctypes.c_uint32), + ('gws_9_val', ctypes.c_uint32), + ('gws_10_val', ctypes.c_uint32), + ('gws_11_val', ctypes.c_uint32), + ('gws_12_val', ctypes.c_uint32), + ('gws_13_val', ctypes.c_uint32), + ('gws_14_val', ctypes.c_uint32), + ('gws_15_val', ctypes.c_uint32), + ('gws_16_val', ctypes.c_uint32), + ('gws_17_val', ctypes.c_uint32), + ('gws_18_val', ctypes.c_uint32), + ('gws_19_val', ctypes.c_uint32), + ('gws_20_val', ctypes.c_uint32), + ('gws_21_val', ctypes.c_uint32), + ('gws_22_val', ctypes.c_uint32), + ('gws_23_val', ctypes.c_uint32), + ('gws_24_val', ctypes.c_uint32), + ('gws_25_val', ctypes.c_uint32), + ('gws_26_val', ctypes.c_uint32), + ('gws_27_val', ctypes.c_uint32), + ('gws_28_val', ctypes.c_uint32), + ('gws_29_val', ctypes.c_uint32), + ('gws_30_val', ctypes.c_uint32), + ('gws_31_val', ctypes.c_uint32), + ('gws_32_val', ctypes.c_uint32), + ('gws_33_val', ctypes.c_uint32), + ('gws_34_val', ctypes.c_uint32), + ('gws_35_val', ctypes.c_uint32), + ('gws_36_val', ctypes.c_uint32), + ('gws_37_val', ctypes.c_uint32), + ('gws_38_val', ctypes.c_uint32), + ('gws_39_val', ctypes.c_uint32), + ('gws_40_val', ctypes.c_uint32), + ('gws_41_val', ctypes.c_uint32), + ('gws_42_val', ctypes.c_uint32), + ('gws_43_val', ctypes.c_uint32), + ('gws_44_val', ctypes.c_uint32), + ('gws_45_val', ctypes.c_uint32), + ('gws_46_val', ctypes.c_uint32), + ('gws_47_val', ctypes.c_uint32), + ('gws_48_val', ctypes.c_uint32), + ('gws_49_val', ctypes.c_uint32), + ('gws_50_val', ctypes.c_uint32), + ('gws_51_val', ctypes.c_uint32), + ('gws_52_val', ctypes.c_uint32), + ('gws_53_val', ctypes.c_uint32), + ('gws_54_val', ctypes.c_uint32), + ('gws_55_val', ctypes.c_uint32), + ('gws_56_val', ctypes.c_uint32), + ('gws_57_val', ctypes.c_uint32), + ('gws_58_val', ctypes.c_uint32), + ('gws_59_val', ctypes.c_uint32), + ('gws_60_val', ctypes.c_uint32), + ('gws_61_val', ctypes.c_uint32), + ('gws_62_val', ctypes.c_uint32), + ('gws_63_val', ctypes.c_uint32), +] + +V12_STRUCTS_H_ = True # macro +class struct_v12_gfx_mqd(Structure): + pass + +struct_v12_gfx_mqd._pack_ = 1 # source:False +struct_v12_gfx_mqd._fields_ = [ + ('shadow_base_lo', ctypes.c_uint32), + ('shadow_base_hi', ctypes.c_uint32), + ('reserved_2', ctypes.c_uint32), + ('reserved_3', ctypes.c_uint32), + ('fw_work_area_base_lo', ctypes.c_uint32), + ('fw_work_area_base_hi', ctypes.c_uint32), + ('shadow_initialized', ctypes.c_uint32), + ('ib_vmid', ctypes.c_uint32), + ('reserved_8', ctypes.c_uint32), + ('reserved_9', ctypes.c_uint32), + ('reserved_10', ctypes.c_uint32), + ('reserved_11', ctypes.c_uint32), + ('reserved_12', ctypes.c_uint32), + ('reserved_13', ctypes.c_uint32), + ('reserved_14', ctypes.c_uint32), + ('reserved_15', ctypes.c_uint32), + ('reserved_16', ctypes.c_uint32), + ('reserved_17', ctypes.c_uint32), + ('reserved_18', ctypes.c_uint32), + ('reserved_19', ctypes.c_uint32), + ('reserved_20', ctypes.c_uint32), + ('reserved_21', ctypes.c_uint32), + ('reserved_22', ctypes.c_uint32), + ('reserved_23', ctypes.c_uint32), + ('reserved_24', ctypes.c_uint32), + ('reserved_25', ctypes.c_uint32), + ('reserved_26', ctypes.c_uint32), + ('reserved_27', ctypes.c_uint32), + ('reserved_28', ctypes.c_uint32), + ('reserved_29', ctypes.c_uint32), + ('reserved_30', ctypes.c_uint32), + ('reserved_31', ctypes.c_uint32), + ('reserved_32', ctypes.c_uint32), + ('reserved_33', ctypes.c_uint32), + ('reserved_34', ctypes.c_uint32), + ('reserved_35', ctypes.c_uint32), + ('reserved_36', ctypes.c_uint32), + ('reserved_37', ctypes.c_uint32), + ('reserved_38', ctypes.c_uint32), + ('reserved_39', ctypes.c_uint32), + ('reserved_40', ctypes.c_uint32), + ('reserved_41', ctypes.c_uint32), + ('reserved_42', ctypes.c_uint32), + ('reserved_43', ctypes.c_uint32), + ('reserved_44', ctypes.c_uint32), + ('reserved_45', ctypes.c_uint32), + ('reserved_46', ctypes.c_uint32), + ('reserved_47', ctypes.c_uint32), + ('reserved_48', ctypes.c_uint32), + ('reserved_49', ctypes.c_uint32), + ('reserved_50', ctypes.c_uint32), + ('reserved_51', ctypes.c_uint32), + ('reserved_52', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('reserved_59', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('reserved_65', ctypes.c_uint32), + ('reserved_66', ctypes.c_uint32), + ('reserved_67', ctypes.c_uint32), + ('reserved_68', ctypes.c_uint32), + ('reserved_69', ctypes.c_uint32), + ('reserved_70', ctypes.c_uint32), + ('reserved_71', ctypes.c_uint32), + ('reserved_72', ctypes.c_uint32), + ('reserved_73', ctypes.c_uint32), + ('reserved_74', ctypes.c_uint32), + ('reserved_75', ctypes.c_uint32), + ('reserved_76', ctypes.c_uint32), + ('reserved_77', ctypes.c_uint32), + ('reserved_78', ctypes.c_uint32), + ('reserved_79', ctypes.c_uint32), + ('reserved_80', ctypes.c_uint32), + ('reserved_81', ctypes.c_uint32), + ('reserved_82', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('checksum_lo', ctypes.c_uint32), + ('checksum_hi', ctypes.c_uint32), + ('cp_mqd_query_time_lo', ctypes.c_uint32), + ('cp_mqd_query_time_hi', ctypes.c_uint32), + ('reserved_88', ctypes.c_uint32), + ('reserved_89', ctypes.c_uint32), + ('reserved_90', ctypes.c_uint32), + ('reserved_91', ctypes.c_uint32), + ('cp_mqd_query_wave_count', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_rptr', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_wptr', ctypes.c_uint32), + ('cp_mqd_query_gfx_hqd_offset', ctypes.c_uint32), + ('reserved_96', ctypes.c_uint32), + ('reserved_97', ctypes.c_uint32), + ('reserved_98', ctypes.c_uint32), + ('reserved_99', ctypes.c_uint32), + ('reserved_100', ctypes.c_uint32), + ('reserved_101', ctypes.c_uint32), + ('reserved_102', ctypes.c_uint32), + ('reserved_103', ctypes.c_uint32), + ('task_shader_control_buf_addr_lo', ctypes.c_uint32), + ('task_shader_control_buf_addr_hi', ctypes.c_uint32), + ('task_shader_read_rptr_lo', ctypes.c_uint32), + ('task_shader_read_rptr_hi', ctypes.c_uint32), + ('task_shader_num_entries', ctypes.c_uint32), + ('task_shader_num_entries_bits', ctypes.c_uint32), + ('task_shader_ring_buffer_addr_lo', ctypes.c_uint32), + ('task_shader_ring_buffer_addr_hi', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('reserved_114', ctypes.c_uint32), + ('reserved_115', ctypes.c_uint32), + ('reserved_116', ctypes.c_uint32), + ('reserved_117', ctypes.c_uint32), + ('reserved_118', ctypes.c_uint32), + ('reserved_119', ctypes.c_uint32), + ('reserved_120', ctypes.c_uint32), + ('reserved_121', ctypes.c_uint32), + ('reserved_122', ctypes.c_uint32), + ('reserved_123', ctypes.c_uint32), + ('reserved_124', ctypes.c_uint32), + ('reserved_125', ctypes.c_uint32), + ('reserved_126', ctypes.c_uint32), + ('reserved_127', ctypes.c_uint32), + ('cp_mqd_base_addr', ctypes.c_uint32), + ('cp_mqd_base_addr_hi', ctypes.c_uint32), + ('cp_gfx_hqd_active', ctypes.c_uint32), + ('cp_gfx_hqd_vmid', ctypes.c_uint32), + ('reserved_132', ctypes.c_uint32), + ('reserved_133', ctypes.c_uint32), + ('cp_gfx_hqd_queue_priority', ctypes.c_uint32), + ('cp_gfx_hqd_quantum', ctypes.c_uint32), + ('cp_gfx_hqd_base', ctypes.c_uint32), + ('cp_gfx_hqd_base_hi', ctypes.c_uint32), + ('cp_gfx_hqd_rptr', ctypes.c_uint32), + ('cp_gfx_hqd_rptr_addr', ctypes.c_uint32), + ('cp_gfx_hqd_rptr_addr_hi', ctypes.c_uint32), + ('cp_rb_wptr_poll_addr_lo', ctypes.c_uint32), + ('cp_rb_wptr_poll_addr_hi', ctypes.c_uint32), + ('cp_rb_doorbell_control', ctypes.c_uint32), + ('cp_gfx_hqd_offset', ctypes.c_uint32), + ('cp_gfx_hqd_cntl', ctypes.c_uint32), + ('reserved_146', ctypes.c_uint32), + ('reserved_147', ctypes.c_uint32), + ('cp_gfx_hqd_csmd_rptr', ctypes.c_uint32), + ('cp_gfx_hqd_wptr', ctypes.c_uint32), + ('cp_gfx_hqd_wptr_hi', ctypes.c_uint32), + ('reserved_151', ctypes.c_uint32), + ('reserved_152', ctypes.c_uint32), + ('reserved_153', ctypes.c_uint32), + ('reserved_154', ctypes.c_uint32), + ('reserved_155', ctypes.c_uint32), + ('cp_gfx_hqd_mapped', ctypes.c_uint32), + ('cp_gfx_hqd_que_mgr_control', ctypes.c_uint32), + ('reserved_158', ctypes.c_uint32), + ('reserved_159', ctypes.c_uint32), + ('cp_gfx_hqd_hq_status0', ctypes.c_uint32), + ('cp_gfx_hqd_hq_control0', ctypes.c_uint32), + ('cp_gfx_mqd_control', ctypes.c_uint32), + ('reserved_163', ctypes.c_uint32), + ('reserved_164', ctypes.c_uint32), + ('reserved_165', ctypes.c_uint32), + ('reserved_166', ctypes.c_uint32), + ('reserved_167', ctypes.c_uint32), + ('reserved_168', ctypes.c_uint32), + ('reserved_169', ctypes.c_uint32), + ('reserved_170', ctypes.c_uint32), + ('reserved_171', ctypes.c_uint32), + ('reserved_172', ctypes.c_uint32), + ('reserved_173', ctypes.c_uint32), + ('reserved_174', ctypes.c_uint32), + ('reserved_175', ctypes.c_uint32), + ('reserved_176', ctypes.c_uint32), + ('reserved_177', ctypes.c_uint32), + ('reserved_178', ctypes.c_uint32), + ('reserved_179', ctypes.c_uint32), + ('reserved_180', ctypes.c_uint32), + ('reserved_181', ctypes.c_uint32), + ('reserved_182', ctypes.c_uint32), + ('reserved_183', ctypes.c_uint32), + ('reserved_184', ctypes.c_uint32), + ('reserved_185', ctypes.c_uint32), + ('reserved_186', ctypes.c_uint32), + ('reserved_187', ctypes.c_uint32), + ('reserved_188', ctypes.c_uint32), + ('reserved_189', ctypes.c_uint32), + ('reserved_190', ctypes.c_uint32), + ('reserved_191', ctypes.c_uint32), + ('reserved_192', ctypes.c_uint32), + ('reserved_193', ctypes.c_uint32), + ('reserved_194', ctypes.c_uint32), + ('reserved_195', ctypes.c_uint32), + ('reserved_196', ctypes.c_uint32), + ('reserved_197', ctypes.c_uint32), + ('reserved_198', ctypes.c_uint32), + ('reserved_199', ctypes.c_uint32), + ('reserved_200', ctypes.c_uint32), + ('reserved_201', ctypes.c_uint32), + ('reserved_202', ctypes.c_uint32), + ('reserved_203', ctypes.c_uint32), + ('reserved_204', ctypes.c_uint32), + ('reserved_205', ctypes.c_uint32), + ('reserved_206', ctypes.c_uint32), + ('reserved_207', ctypes.c_uint32), + ('reserved_208', ctypes.c_uint32), + ('reserved_209', ctypes.c_uint32), + ('reserved_210', ctypes.c_uint32), + ('reserved_211', ctypes.c_uint32), + ('reserved_212', ctypes.c_uint32), + ('reserved_213', ctypes.c_uint32), + ('reserved_214', ctypes.c_uint32), + ('reserved_215', ctypes.c_uint32), + ('reserved_216', ctypes.c_uint32), + ('reserved_217', ctypes.c_uint32), + ('reserved_218', ctypes.c_uint32), + ('reserved_219', ctypes.c_uint32), + ('reserved_220', ctypes.c_uint32), + ('reserved_221', ctypes.c_uint32), + ('reserved_222', ctypes.c_uint32), + ('reserved_223', ctypes.c_uint32), + ('reserved_224', ctypes.c_uint32), + ('reserved_225', ctypes.c_uint32), + ('reserved_226', ctypes.c_uint32), + ('reserved_227', ctypes.c_uint32), + ('reserved_228', ctypes.c_uint32), + ('reserved_229', ctypes.c_uint32), + ('reserved_230', ctypes.c_uint32), + ('reserved_231', ctypes.c_uint32), + ('reserved_232', ctypes.c_uint32), + ('reserved_233', ctypes.c_uint32), + ('reserved_234', ctypes.c_uint32), + ('reserved_235', ctypes.c_uint32), + ('reserved_236', ctypes.c_uint32), + ('reserved_237', ctypes.c_uint32), + ('reserved_238', ctypes.c_uint32), + ('reserved_239', ctypes.c_uint32), + ('reserved_240', ctypes.c_uint32), + ('reserved_241', ctypes.c_uint32), + ('reserved_242', ctypes.c_uint32), + ('reserved_243', ctypes.c_uint32), + ('reserved_244', ctypes.c_uint32), + ('reserved_245', ctypes.c_uint32), + ('reserved_246', ctypes.c_uint32), + ('reserved_247', ctypes.c_uint32), + ('reserved_248', ctypes.c_uint32), + ('reserved_249', ctypes.c_uint32), + ('reserved_250', ctypes.c_uint32), + ('reserved_251', ctypes.c_uint32), + ('reserved_252', ctypes.c_uint32), + ('reserved_253', ctypes.c_uint32), + ('reserved_254', ctypes.c_uint32), + ('reserved_255', ctypes.c_uint32), + ('reserved_256', ctypes.c_uint32), + ('reserved_257', ctypes.c_uint32), + ('reserved_258', ctypes.c_uint32), + ('reserved_259', ctypes.c_uint32), + ('reserved_260', ctypes.c_uint32), + ('reserved_261', ctypes.c_uint32), + ('reserved_262', ctypes.c_uint32), + ('reserved_263', ctypes.c_uint32), + ('reserved_264', ctypes.c_uint32), + ('reserved_265', ctypes.c_uint32), + ('reserved_266', ctypes.c_uint32), + ('reserved_267', ctypes.c_uint32), + ('reserved_268', ctypes.c_uint32), + ('reserved_269', ctypes.c_uint32), + ('reserved_270', ctypes.c_uint32), + ('reserved_271', ctypes.c_uint32), + ('dfwx_flags', ctypes.c_uint32), + ('dfwx_slot', ctypes.c_uint32), + ('dfwx_client_data_addr_lo', ctypes.c_uint32), + ('dfwx_client_data_addr_hi', ctypes.c_uint32), + ('reserved_276', ctypes.c_uint32), + ('reserved_277', ctypes.c_uint32), + ('reserved_278', ctypes.c_uint32), + ('reserved_279', ctypes.c_uint32), + ('reserved_280', ctypes.c_uint32), + ('reserved_281', ctypes.c_uint32), + ('reserved_282', ctypes.c_uint32), + ('reserved_283', ctypes.c_uint32), + ('reserved_284', ctypes.c_uint32), + ('reserved_285', ctypes.c_uint32), + ('reserved_286', ctypes.c_uint32), + ('reserved_287', ctypes.c_uint32), + ('reserved_288', ctypes.c_uint32), + ('reserved_289', ctypes.c_uint32), + ('reserved_290', ctypes.c_uint32), + ('reserved_291', ctypes.c_uint32), + ('reserved_292', ctypes.c_uint32), + ('reserved_293', ctypes.c_uint32), + ('reserved_294', ctypes.c_uint32), + ('reserved_295', ctypes.c_uint32), + ('reserved_296', ctypes.c_uint32), + ('reserved_297', ctypes.c_uint32), + ('reserved_298', ctypes.c_uint32), + ('reserved_299', ctypes.c_uint32), + ('reserved_300', ctypes.c_uint32), + ('reserved_301', ctypes.c_uint32), + ('reserved_302', ctypes.c_uint32), + ('reserved_303', ctypes.c_uint32), + ('reserved_304', ctypes.c_uint32), + ('reserved_305', ctypes.c_uint32), + ('reserved_306', ctypes.c_uint32), + ('reserved_307', ctypes.c_uint32), + ('reserved_308', ctypes.c_uint32), + ('reserved_309', ctypes.c_uint32), + ('reserved_310', ctypes.c_uint32), + ('reserved_311', ctypes.c_uint32), + ('reserved_312', ctypes.c_uint32), + ('reserved_313', ctypes.c_uint32), + ('reserved_314', ctypes.c_uint32), + ('reserved_315', ctypes.c_uint32), + ('reserved_316', ctypes.c_uint32), + ('reserved_317', ctypes.c_uint32), + ('reserved_318', ctypes.c_uint32), + ('reserved_319', ctypes.c_uint32), + ('reserved_320', ctypes.c_uint32), + ('reserved_321', ctypes.c_uint32), + ('reserved_322', ctypes.c_uint32), + ('reserved_323', ctypes.c_uint32), + ('reserved_324', ctypes.c_uint32), + ('reserved_325', ctypes.c_uint32), + ('reserved_326', ctypes.c_uint32), + ('reserved_327', ctypes.c_uint32), + ('reserved_328', ctypes.c_uint32), + ('reserved_329', ctypes.c_uint32), + ('reserved_330', ctypes.c_uint32), + ('reserved_331', ctypes.c_uint32), + ('reserved_332', ctypes.c_uint32), + ('reserved_333', ctypes.c_uint32), + ('reserved_334', ctypes.c_uint32), + ('reserved_335', ctypes.c_uint32), + ('reserved_336', ctypes.c_uint32), + ('reserved_337', ctypes.c_uint32), + ('reserved_338', ctypes.c_uint32), + ('reserved_339', ctypes.c_uint32), + ('reserved_340', ctypes.c_uint32), + ('reserved_341', ctypes.c_uint32), + ('reserved_342', ctypes.c_uint32), + ('reserved_343', ctypes.c_uint32), + ('reserved_344', ctypes.c_uint32), + ('reserved_345', ctypes.c_uint32), + ('reserved_346', ctypes.c_uint32), + ('reserved_347', ctypes.c_uint32), + ('reserved_348', ctypes.c_uint32), + ('reserved_349', ctypes.c_uint32), + ('reserved_350', ctypes.c_uint32), + ('reserved_351', ctypes.c_uint32), + ('reserved_352', ctypes.c_uint32), + ('reserved_353', ctypes.c_uint32), + ('reserved_354', ctypes.c_uint32), + ('reserved_355', ctypes.c_uint32), + ('reserved_356', ctypes.c_uint32), + ('reserved_357', ctypes.c_uint32), + ('reserved_358', ctypes.c_uint32), + ('reserved_359', ctypes.c_uint32), + ('reserved_360', ctypes.c_uint32), + ('reserved_361', ctypes.c_uint32), + ('reserved_362', ctypes.c_uint32), + ('reserved_363', ctypes.c_uint32), + ('reserved_364', ctypes.c_uint32), + ('reserved_365', ctypes.c_uint32), + ('reserved_366', ctypes.c_uint32), + ('reserved_367', ctypes.c_uint32), + ('reserved_368', ctypes.c_uint32), + ('reserved_369', ctypes.c_uint32), + ('reserved_370', ctypes.c_uint32), + ('reserved_371', ctypes.c_uint32), + ('reserved_372', ctypes.c_uint32), + ('reserved_373', ctypes.c_uint32), + ('reserved_374', ctypes.c_uint32), + ('reserved_375', ctypes.c_uint32), + ('reserved_376', ctypes.c_uint32), + ('reserved_377', ctypes.c_uint32), + ('reserved_378', ctypes.c_uint32), + ('reserved_379', ctypes.c_uint32), + ('reserved_380', ctypes.c_uint32), + ('reserved_381', ctypes.c_uint32), + ('reserved_382', ctypes.c_uint32), + ('reserved_383', ctypes.c_uint32), + ('reserved_384', ctypes.c_uint32), + ('reserved_385', ctypes.c_uint32), + ('reserved_386', ctypes.c_uint32), + ('reserved_387', ctypes.c_uint32), + ('reserved_388', ctypes.c_uint32), + ('reserved_389', ctypes.c_uint32), + ('reserved_390', ctypes.c_uint32), + ('reserved_391', ctypes.c_uint32), + ('reserved_392', ctypes.c_uint32), + ('reserved_393', ctypes.c_uint32), + ('reserved_394', ctypes.c_uint32), + ('reserved_395', ctypes.c_uint32), + ('reserved_396', ctypes.c_uint32), + ('reserved_397', ctypes.c_uint32), + ('reserved_398', ctypes.c_uint32), + ('reserved_399', ctypes.c_uint32), + ('reserved_400', ctypes.c_uint32), + ('reserved_401', ctypes.c_uint32), + ('reserved_402', ctypes.c_uint32), + ('reserved_403', ctypes.c_uint32), + ('reserved_404', ctypes.c_uint32), + ('reserved_405', ctypes.c_uint32), + ('reserved_406', ctypes.c_uint32), + ('reserved_407', ctypes.c_uint32), + ('reserved_408', ctypes.c_uint32), + ('reserved_409', ctypes.c_uint32), + ('reserved_410', ctypes.c_uint32), + ('reserved_411', ctypes.c_uint32), + ('reserved_412', ctypes.c_uint32), + ('reserved_413', ctypes.c_uint32), + ('reserved_414', ctypes.c_uint32), + ('reserved_415', ctypes.c_uint32), + ('reserved_416', ctypes.c_uint32), + ('reserved_417', ctypes.c_uint32), + ('reserved_418', ctypes.c_uint32), + ('reserved_419', ctypes.c_uint32), + ('reserved_420', ctypes.c_uint32), + ('reserved_421', ctypes.c_uint32), + ('reserved_422', ctypes.c_uint32), + ('reserved_423', ctypes.c_uint32), + ('reserved_424', ctypes.c_uint32), + ('reserved_425', ctypes.c_uint32), + ('reserved_426', ctypes.c_uint32), + ('reserved_427', ctypes.c_uint32), + ('reserved_428', ctypes.c_uint32), + ('reserved_429', ctypes.c_uint32), + ('reserved_430', ctypes.c_uint32), + ('reserved_431', ctypes.c_uint32), + ('reserved_432', ctypes.c_uint32), + ('reserved_433', ctypes.c_uint32), + ('reserved_434', ctypes.c_uint32), + ('reserved_435', ctypes.c_uint32), + ('reserved_436', ctypes.c_uint32), + ('reserved_437', ctypes.c_uint32), + ('reserved_438', ctypes.c_uint32), + ('reserved_439', ctypes.c_uint32), + ('reserved_440', ctypes.c_uint32), + ('reserved_441', ctypes.c_uint32), + ('reserved_442', ctypes.c_uint32), + ('reserved_443', ctypes.c_uint32), + ('reserved_444', ctypes.c_uint32), + ('reserved_445', ctypes.c_uint32), + ('reserved_446', ctypes.c_uint32), + ('reserved_447', ctypes.c_uint32), + ('reserved_448', ctypes.c_uint32), + ('reserved_449', ctypes.c_uint32), + ('reserved_450', ctypes.c_uint32), + ('reserved_451', ctypes.c_uint32), + ('reserved_452', ctypes.c_uint32), + ('reserved_453', ctypes.c_uint32), + ('reserved_454', ctypes.c_uint32), + ('reserved_455', ctypes.c_uint32), + ('reserved_456', ctypes.c_uint32), + ('reserved_457', ctypes.c_uint32), + ('reserved_458', ctypes.c_uint32), + ('reserved_459', ctypes.c_uint32), + ('reserved_460', ctypes.c_uint32), + ('reserved_461', ctypes.c_uint32), + ('reserved_462', ctypes.c_uint32), + ('reserved_463', ctypes.c_uint32), + ('reserved_464', ctypes.c_uint32), + ('reserved_465', ctypes.c_uint32), + ('reserved_466', ctypes.c_uint32), + ('reserved_467', ctypes.c_uint32), + ('reserved_468', ctypes.c_uint32), + ('reserved_469', ctypes.c_uint32), + ('reserved_470', ctypes.c_uint32), + ('reserved_471', ctypes.c_uint32), + ('reserved_472', ctypes.c_uint32), + ('reserved_473', ctypes.c_uint32), + ('reserved_474', ctypes.c_uint32), + ('reserved_475', ctypes.c_uint32), + ('reserved_476', ctypes.c_uint32), + ('reserved_477', ctypes.c_uint32), + ('reserved_478', ctypes.c_uint32), + ('reserved_479', ctypes.c_uint32), + ('reserved_480', ctypes.c_uint32), + ('reserved_481', ctypes.c_uint32), + ('reserved_482', ctypes.c_uint32), + ('reserved_483', ctypes.c_uint32), + ('reserved_484', ctypes.c_uint32), + ('reserved_485', ctypes.c_uint32), + ('reserved_486', ctypes.c_uint32), + ('reserved_487', ctypes.c_uint32), + ('reserved_488', ctypes.c_uint32), + ('reserved_489', ctypes.c_uint32), + ('reserved_490', ctypes.c_uint32), + ('reserved_491', ctypes.c_uint32), + ('reserved_492', ctypes.c_uint32), + ('reserved_493', ctypes.c_uint32), + ('reserved_494', ctypes.c_uint32), + ('reserved_495', ctypes.c_uint32), + ('reserved_496', ctypes.c_uint32), + ('reserved_497', ctypes.c_uint32), + ('reserved_498', ctypes.c_uint32), + ('reserved_499', ctypes.c_uint32), + ('reserved_500', ctypes.c_uint32), + ('reserved_501', ctypes.c_uint32), + ('reserved_502', ctypes.c_uint32), + ('reserved_503', ctypes.c_uint32), + ('reserved_504', ctypes.c_uint32), + ('reserved_505', ctypes.c_uint32), + ('reserved_506', ctypes.c_uint32), + ('reserved_507', ctypes.c_uint32), + ('reserved_508', ctypes.c_uint32), + ('reserved_509', ctypes.c_uint32), + ('reserved_510', ctypes.c_uint32), + ('reserved_511', ctypes.c_uint32), +] + +class struct_v12_sdma_mqd(Structure): + pass + +struct_v12_sdma_mqd._pack_ = 1 # source:False +struct_v12_sdma_mqd._fields_ = [ + ('sdmax_rlcx_rb_cntl', ctypes.c_uint32), + ('sdmax_rlcx_rb_base', ctypes.c_uint32), + ('sdmax_rlcx_rb_base_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_rb_rptr_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_ib_cntl', ctypes.c_uint32), + ('sdmax_rlcx_ib_rptr', ctypes.c_uint32), + ('sdmax_rlcx_ib_offset', ctypes.c_uint32), + ('sdmax_rlcx_ib_base_lo', ctypes.c_uint32), + ('sdmax_rlcx_ib_base_hi', ctypes.c_uint32), + ('sdmax_rlcx_ib_size', ctypes.c_uint32), + ('sdmax_rlcx_doorbell', ctypes.c_uint32), + ('sdmax_rlcx_doorbell_log', ctypes.c_uint32), + ('sdmax_rlcx_doorbell_offset', ctypes.c_uint32), + ('sdmax_rlcx_csa_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_csa_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_sched_cntl', ctypes.c_uint32), + ('sdmax_rlcx_ib_sub_remain', ctypes.c_uint32), + ('sdmax_rlcx_preempt', ctypes.c_uint32), + ('sdmax_rlcx_dummy_reg', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_poll_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_rb_wptr_poll_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_rb_aql_cntl', ctypes.c_uint32), + ('sdmax_rlcx_minor_ptr_update', ctypes.c_uint32), + ('sdmax_rlcx_mcu_dbg0', ctypes.c_uint32), + ('sdmax_rlcx_mcu_dbg1', ctypes.c_uint32), + ('sdmax_rlcx_context_switch_status', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_cntl', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data0', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data1', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data2', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data3', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data4', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data5', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data6', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data7', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data8', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data9', ctypes.c_uint32), + ('sdmax_rlcx_midcmd_data10', ctypes.c_uint32), + ('sdmax_rlcx_wait_unsatisfied_thd', ctypes.c_uint32), + ('sdmax_rlcx_mqd_base_addr_lo', ctypes.c_uint32), + ('sdmax_rlcx_mqd_base_addr_hi', ctypes.c_uint32), + ('sdmax_rlcx_mqd_control', ctypes.c_uint32), + ('reserved_47', ctypes.c_uint32), + ('reserved_48', ctypes.c_uint32), + ('reserved_49', ctypes.c_uint32), + ('reserved_50', ctypes.c_uint32), + ('reserved_51', ctypes.c_uint32), + ('reserved_52', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('reserved_59', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('reserved_65', ctypes.c_uint32), + ('reserved_66', ctypes.c_uint32), + ('reserved_67', ctypes.c_uint32), + ('reserved_68', ctypes.c_uint32), + ('reserved_69', ctypes.c_uint32), + ('reserved_70', ctypes.c_uint32), + ('reserved_71', ctypes.c_uint32), + ('reserved_72', ctypes.c_uint32), + ('reserved_73', ctypes.c_uint32), + ('reserved_74', ctypes.c_uint32), + ('reserved_75', ctypes.c_uint32), + ('reserved_76', ctypes.c_uint32), + ('reserved_77', ctypes.c_uint32), + ('reserved_78', ctypes.c_uint32), + ('reserved_79', ctypes.c_uint32), + ('reserved_80', ctypes.c_uint32), + ('reserved_81', ctypes.c_uint32), + ('reserved_82', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('reserved_84', ctypes.c_uint32), + ('reserved_85', ctypes.c_uint32), + ('reserved_86', ctypes.c_uint32), + ('reserved_87', ctypes.c_uint32), + ('reserved_88', ctypes.c_uint32), + ('reserved_89', ctypes.c_uint32), + ('reserved_90', ctypes.c_uint32), + ('reserved_91', ctypes.c_uint32), + ('reserved_92', ctypes.c_uint32), + ('reserved_93', ctypes.c_uint32), + ('reserved_94', ctypes.c_uint32), + ('reserved_95', ctypes.c_uint32), + ('reserved_96', ctypes.c_uint32), + ('reserved_97', ctypes.c_uint32), + ('reserved_98', ctypes.c_uint32), + ('reserved_99', ctypes.c_uint32), + ('reserved_100', ctypes.c_uint32), + ('reserved_101', ctypes.c_uint32), + ('reserved_102', ctypes.c_uint32), + ('reserved_103', ctypes.c_uint32), + ('reserved_104', ctypes.c_uint32), + ('reserved_105', ctypes.c_uint32), + ('reserved_106', ctypes.c_uint32), + ('reserved_107', ctypes.c_uint32), + ('reserved_108', ctypes.c_uint32), + ('reserved_109', ctypes.c_uint32), + ('reserved_110', ctypes.c_uint32), + ('reserved_111', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('reserved_114', ctypes.c_uint32), + ('reserved_115', ctypes.c_uint32), + ('reserved_116', ctypes.c_uint32), + ('reserved_117', ctypes.c_uint32), + ('reserved_118', ctypes.c_uint32), + ('reserved_119', ctypes.c_uint32), + ('reserved_120', ctypes.c_uint32), + ('reserved_121', ctypes.c_uint32), + ('reserved_122', ctypes.c_uint32), + ('reserved_123', ctypes.c_uint32), + ('reserved_124', ctypes.c_uint32), + ('reserved_125', ctypes.c_uint32), + ('sdma_engine_id', ctypes.c_uint32), + ('sdma_queue_id', ctypes.c_uint32), +] + +class struct_v12_compute_mqd(Structure): + pass + +struct_v12_compute_mqd._pack_ = 1 # source:False +struct_v12_compute_mqd._fields_ = [ + ('header', ctypes.c_uint32), + ('compute_dispatch_initiator', ctypes.c_uint32), + ('compute_dim_x', ctypes.c_uint32), + ('compute_dim_y', ctypes.c_uint32), + ('compute_dim_z', ctypes.c_uint32), + ('compute_start_x', ctypes.c_uint32), + ('compute_start_y', ctypes.c_uint32), + ('compute_start_z', ctypes.c_uint32), + ('compute_num_thread_x', ctypes.c_uint32), + ('compute_num_thread_y', ctypes.c_uint32), + ('compute_num_thread_z', ctypes.c_uint32), + ('compute_pipelinestat_enable', ctypes.c_uint32), + ('compute_perfcount_enable', ctypes.c_uint32), + ('compute_pgm_lo', ctypes.c_uint32), + ('compute_pgm_hi', ctypes.c_uint32), + ('compute_dispatch_pkt_addr_lo', ctypes.c_uint32), + ('compute_dispatch_pkt_addr_hi', ctypes.c_uint32), + ('compute_dispatch_scratch_base_lo', ctypes.c_uint32), + ('compute_dispatch_scratch_base_hi', ctypes.c_uint32), + ('compute_pgm_rsrc1', ctypes.c_uint32), + ('compute_pgm_rsrc2', ctypes.c_uint32), + ('compute_vmid', ctypes.c_uint32), + ('compute_resource_limits', ctypes.c_uint32), + ('compute_static_thread_mgmt_se0', ctypes.c_uint32), + ('compute_static_thread_mgmt_se1', ctypes.c_uint32), + ('compute_tmpring_size', ctypes.c_uint32), + ('compute_static_thread_mgmt_se2', ctypes.c_uint32), + ('compute_static_thread_mgmt_se3', ctypes.c_uint32), + ('compute_restart_x', ctypes.c_uint32), + ('compute_restart_y', ctypes.c_uint32), + ('compute_restart_z', ctypes.c_uint32), + ('compute_thread_trace_enable', ctypes.c_uint32), + ('compute_misc_reserved', ctypes.c_uint32), + ('compute_dispatch_id', ctypes.c_uint32), + ('compute_threadgroup_id', ctypes.c_uint32), + ('compute_req_ctrl', ctypes.c_uint32), + ('reserved_36', ctypes.c_uint32), + ('compute_user_accum_0', ctypes.c_uint32), + ('compute_user_accum_1', ctypes.c_uint32), + ('compute_user_accum_2', ctypes.c_uint32), + ('compute_user_accum_3', ctypes.c_uint32), + ('compute_pgm_rsrc3', ctypes.c_uint32), + ('compute_ddid_index', ctypes.c_uint32), + ('compute_shader_chksum', ctypes.c_uint32), + ('compute_static_thread_mgmt_se4', ctypes.c_uint32), + ('compute_static_thread_mgmt_se5', ctypes.c_uint32), + ('compute_static_thread_mgmt_se6', ctypes.c_uint32), + ('compute_static_thread_mgmt_se7', ctypes.c_uint32), + ('compute_dispatch_interleave', ctypes.c_uint32), + ('compute_relaunch', ctypes.c_uint32), + ('compute_wave_restore_addr_lo', ctypes.c_uint32), + ('compute_wave_restore_addr_hi', ctypes.c_uint32), + ('compute_wave_restore_control', ctypes.c_uint32), + ('reserved_53', ctypes.c_uint32), + ('reserved_54', ctypes.c_uint32), + ('reserved_55', ctypes.c_uint32), + ('reserved_56', ctypes.c_uint32), + ('reserved_57', ctypes.c_uint32), + ('reserved_58', ctypes.c_uint32), + ('compute_static_thread_mgmt_se8', ctypes.c_uint32), + ('reserved_60', ctypes.c_uint32), + ('reserved_61', ctypes.c_uint32), + ('reserved_62', ctypes.c_uint32), + ('reserved_63', ctypes.c_uint32), + ('reserved_64', ctypes.c_uint32), + ('compute_user_data_0', ctypes.c_uint32), + ('compute_user_data_1', ctypes.c_uint32), + ('compute_user_data_2', ctypes.c_uint32), + ('compute_user_data_3', ctypes.c_uint32), + ('compute_user_data_4', ctypes.c_uint32), + ('compute_user_data_5', ctypes.c_uint32), + ('compute_user_data_6', ctypes.c_uint32), + ('compute_user_data_7', ctypes.c_uint32), + ('compute_user_data_8', ctypes.c_uint32), + ('compute_user_data_9', ctypes.c_uint32), + ('compute_user_data_10', ctypes.c_uint32), + ('compute_user_data_11', ctypes.c_uint32), + ('compute_user_data_12', ctypes.c_uint32), + ('compute_user_data_13', ctypes.c_uint32), + ('compute_user_data_14', ctypes.c_uint32), + ('compute_user_data_15', ctypes.c_uint32), + ('cp_compute_csinvoc_count_lo', ctypes.c_uint32), + ('cp_compute_csinvoc_count_hi', ctypes.c_uint32), + ('reserved_83', ctypes.c_uint32), + ('reserved_84', ctypes.c_uint32), + ('reserved_85', ctypes.c_uint32), + ('cp_mqd_query_time_lo', ctypes.c_uint32), + ('cp_mqd_query_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_start_time_lo', ctypes.c_uint32), + ('cp_mqd_connect_start_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_end_time_lo', ctypes.c_uint32), + ('cp_mqd_connect_end_time_hi', ctypes.c_uint32), + ('cp_mqd_connect_end_wf_count', ctypes.c_uint32), + ('cp_mqd_connect_end_pq_rptr', ctypes.c_uint32), + ('cp_mqd_connect_end_pq_wptr', ctypes.c_uint32), + ('cp_mqd_connect_end_ib_rptr', ctypes.c_uint32), + ('cp_mqd_readindex_lo', ctypes.c_uint32), + ('cp_mqd_readindex_hi', ctypes.c_uint32), + ('cp_mqd_save_start_time_lo', ctypes.c_uint32), + ('cp_mqd_save_start_time_hi', ctypes.c_uint32), + ('cp_mqd_save_end_time_lo', ctypes.c_uint32), + ('cp_mqd_save_end_time_hi', ctypes.c_uint32), + ('cp_mqd_restore_start_time_lo', ctypes.c_uint32), + ('cp_mqd_restore_start_time_hi', ctypes.c_uint32), + ('cp_mqd_restore_end_time_lo', ctypes.c_uint32), + ('cp_mqd_restore_end_time_hi', ctypes.c_uint32), + ('disable_queue', ctypes.c_uint32), + ('reserved_107', ctypes.c_uint32), + ('reserved_108', ctypes.c_uint32), + ('reserved_109', ctypes.c_uint32), + ('reserved_110', ctypes.c_uint32), + ('reserved_111', ctypes.c_uint32), + ('reserved_112', ctypes.c_uint32), + ('reserved_113', ctypes.c_uint32), + ('cp_pq_exe_status_lo', ctypes.c_uint32), + ('cp_pq_exe_status_hi', ctypes.c_uint32), + ('cp_packet_id_lo', ctypes.c_uint32), + ('cp_packet_id_hi', ctypes.c_uint32), + ('cp_packet_exe_status_lo', ctypes.c_uint32), + ('cp_packet_exe_status_hi', ctypes.c_uint32), + ('reserved_120', ctypes.c_uint32), + ('reserved_121', ctypes.c_uint32), + ('reserved_122', ctypes.c_uint32), + ('reserved_123', ctypes.c_uint32), + ('ctx_save_base_addr_lo', ctypes.c_uint32), + ('ctx_save_base_addr_hi', ctypes.c_uint32), + ('reserved_126', ctypes.c_uint32), + ('reserved_127', ctypes.c_uint32), + ('cp_mqd_base_addr_lo', ctypes.c_uint32), + ('cp_mqd_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_active', ctypes.c_uint32), + ('cp_hqd_vmid', ctypes.c_uint32), + ('cp_hqd_persistent_state', ctypes.c_uint32), + ('cp_hqd_pipe_priority', ctypes.c_uint32), + ('cp_hqd_queue_priority', ctypes.c_uint32), + ('cp_hqd_quantum', ctypes.c_uint32), + ('cp_hqd_pq_base_lo', ctypes.c_uint32), + ('cp_hqd_pq_base_hi', ctypes.c_uint32), + ('cp_hqd_pq_rptr', ctypes.c_uint32), + ('cp_hqd_pq_rptr_report_addr_lo', ctypes.c_uint32), + ('cp_hqd_pq_rptr_report_addr_hi', ctypes.c_uint32), + ('cp_hqd_pq_wptr_poll_addr_lo', ctypes.c_uint32), + ('cp_hqd_pq_wptr_poll_addr_hi', ctypes.c_uint32), + ('cp_hqd_pq_doorbell_control', ctypes.c_uint32), + ('reserved_144', ctypes.c_uint32), + ('cp_hqd_pq_control', ctypes.c_uint32), + ('cp_hqd_ib_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_ib_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_ib_rptr', ctypes.c_uint32), + ('cp_hqd_ib_control', ctypes.c_uint32), + ('cp_hqd_iq_timer', ctypes.c_uint32), + ('cp_hqd_iq_rptr', ctypes.c_uint32), + ('cp_hqd_dequeue_request', ctypes.c_uint32), + ('cp_hqd_dma_offload', ctypes.c_uint32), + ('cp_hqd_sema_cmd', ctypes.c_uint32), + ('cp_hqd_msg_type', ctypes.c_uint32), + ('cp_hqd_atomic0_preop_lo', ctypes.c_uint32), + ('cp_hqd_atomic0_preop_hi', ctypes.c_uint32), + ('cp_hqd_atomic1_preop_lo', ctypes.c_uint32), + ('cp_hqd_atomic1_preop_hi', ctypes.c_uint32), + ('cp_hqd_hq_status0', ctypes.c_uint32), + ('cp_hqd_hq_control0', ctypes.c_uint32), + ('cp_mqd_control', ctypes.c_uint32), + ('cp_hqd_hq_status1', ctypes.c_uint32), + ('cp_hqd_hq_control1', ctypes.c_uint32), + ('cp_hqd_eop_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_eop_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_eop_control', ctypes.c_uint32), + ('cp_hqd_eop_rptr', ctypes.c_uint32), + ('cp_hqd_eop_wptr', ctypes.c_uint32), + ('cp_hqd_eop_done_events', ctypes.c_uint32), + ('cp_hqd_ctx_save_base_addr_lo', ctypes.c_uint32), + ('cp_hqd_ctx_save_base_addr_hi', ctypes.c_uint32), + ('cp_hqd_ctx_save_control', ctypes.c_uint32), + ('cp_hqd_cntl_stack_offset', ctypes.c_uint32), + ('cp_hqd_cntl_stack_size', ctypes.c_uint32), + ('cp_hqd_wg_state_offset', ctypes.c_uint32), + ('cp_hqd_ctx_save_size', ctypes.c_uint32), + ('reserved_178', ctypes.c_uint32), + ('cp_hqd_error', ctypes.c_uint32), + ('cp_hqd_eop_wptr_mem', ctypes.c_uint32), + ('cp_hqd_aql_control', ctypes.c_uint32), + ('cp_hqd_pq_wptr_lo', ctypes.c_uint32), + ('cp_hqd_pq_wptr_hi', ctypes.c_uint32), + ('reserved_184', ctypes.c_uint32), + ('reserved_185', ctypes.c_uint32), + ('reserved_186', ctypes.c_uint32), + ('reserved_187', ctypes.c_uint32), + ('reserved_188', ctypes.c_uint32), + ('reserved_189', ctypes.c_uint32), + ('reserved_190', ctypes.c_uint32), + ('reserved_191', ctypes.c_uint32), + ('iqtimer_pkt_header', ctypes.c_uint32), + ('iqtimer_pkt_dw0', ctypes.c_uint32), + ('iqtimer_pkt_dw1', ctypes.c_uint32), + ('iqtimer_pkt_dw2', ctypes.c_uint32), + ('iqtimer_pkt_dw3', ctypes.c_uint32), + ('iqtimer_pkt_dw4', ctypes.c_uint32), + ('iqtimer_pkt_dw5', ctypes.c_uint32), + ('iqtimer_pkt_dw6', ctypes.c_uint32), + ('iqtimer_pkt_dw7', ctypes.c_uint32), + ('iqtimer_pkt_dw8', ctypes.c_uint32), + ('iqtimer_pkt_dw9', ctypes.c_uint32), + ('iqtimer_pkt_dw10', ctypes.c_uint32), + ('iqtimer_pkt_dw11', ctypes.c_uint32), + ('iqtimer_pkt_dw12', ctypes.c_uint32), + ('iqtimer_pkt_dw13', ctypes.c_uint32), + ('iqtimer_pkt_dw14', ctypes.c_uint32), + ('iqtimer_pkt_dw15', ctypes.c_uint32), + ('iqtimer_pkt_dw16', ctypes.c_uint32), + ('iqtimer_pkt_dw17', ctypes.c_uint32), + ('iqtimer_pkt_dw18', ctypes.c_uint32), + ('iqtimer_pkt_dw19', ctypes.c_uint32), + ('iqtimer_pkt_dw20', ctypes.c_uint32), + ('iqtimer_pkt_dw21', ctypes.c_uint32), + ('iqtimer_pkt_dw22', ctypes.c_uint32), + ('iqtimer_pkt_dw23', ctypes.c_uint32), + ('iqtimer_pkt_dw24', ctypes.c_uint32), + ('iqtimer_pkt_dw25', ctypes.c_uint32), + ('iqtimer_pkt_dw26', ctypes.c_uint32), + ('iqtimer_pkt_dw27', ctypes.c_uint32), + ('iqtimer_pkt_dw28', ctypes.c_uint32), + ('iqtimer_pkt_dw29', ctypes.c_uint32), + ('iqtimer_pkt_dw30', ctypes.c_uint32), + ('iqtimer_pkt_dw31', ctypes.c_uint32), + ('reserved_225', ctypes.c_uint32), + ('reserved_226', ctypes.c_uint32), + ('reserved_227', ctypes.c_uint32), + ('set_resources_header', ctypes.c_uint32), + ('set_resources_dw1', ctypes.c_uint32), + ('set_resources_dw2', ctypes.c_uint32), + ('set_resources_dw3', ctypes.c_uint32), + ('set_resources_dw4', ctypes.c_uint32), + ('set_resources_dw5', ctypes.c_uint32), + ('set_resources_dw6', ctypes.c_uint32), + ('set_resources_dw7', ctypes.c_uint32), + ('reserved_236', ctypes.c_uint32), + ('reserved_237', ctypes.c_uint32), + ('reserved_238', ctypes.c_uint32), + ('reserved_239', ctypes.c_uint32), + ('queue_doorbell_id0', ctypes.c_uint32), + ('queue_doorbell_id1', ctypes.c_uint32), + ('queue_doorbell_id2', ctypes.c_uint32), + ('queue_doorbell_id3', ctypes.c_uint32), + ('queue_doorbell_id4', ctypes.c_uint32), + ('queue_doorbell_id5', ctypes.c_uint32), + ('queue_doorbell_id6', ctypes.c_uint32), + ('queue_doorbell_id7', ctypes.c_uint32), + ('queue_doorbell_id8', ctypes.c_uint32), + ('queue_doorbell_id9', ctypes.c_uint32), + ('queue_doorbell_id10', ctypes.c_uint32), + ('queue_doorbell_id11', ctypes.c_uint32), + ('queue_doorbell_id12', ctypes.c_uint32), + ('queue_doorbell_id13', ctypes.c_uint32), + ('queue_doorbell_id14', ctypes.c_uint32), + ('queue_doorbell_id15', ctypes.c_uint32), + ('control_buf_addr_lo', ctypes.c_uint32), + ('control_buf_addr_hi', ctypes.c_uint32), + ('control_buf_wptr_lo', ctypes.c_uint32), + ('control_buf_wptr_hi', ctypes.c_uint32), + ('control_buf_dptr_lo', ctypes.c_uint32), + ('control_buf_dptr_hi', ctypes.c_uint32), + ('control_buf_num_entries', ctypes.c_uint32), + ('draw_ring_addr_lo', ctypes.c_uint32), + ('draw_ring_addr_hi', ctypes.c_uint32), + ('reserved_265', ctypes.c_uint32), + ('reserved_266', ctypes.c_uint32), + ('reserved_267', ctypes.c_uint32), + ('reserved_268', ctypes.c_uint32), + ('reserved_269', ctypes.c_uint32), + ('reserved_270', ctypes.c_uint32), + ('reserved_271', ctypes.c_uint32), + ('dfwx_flags', ctypes.c_uint32), + ('dfwx_slot', ctypes.c_uint32), + ('dfwx_client_data_addr_lo', ctypes.c_uint32), + ('dfwx_client_data_addr_hi', ctypes.c_uint32), + ('reserved_276', ctypes.c_uint32), + ('reserved_277', ctypes.c_uint32), + ('reserved_278', ctypes.c_uint32), + ('reserved_279', ctypes.c_uint32), + ('reserved_280', ctypes.c_uint32), + ('reserved_281', ctypes.c_uint32), + ('reserved_282', ctypes.c_uint32), + ('reserved_283', ctypes.c_uint32), + ('reserved_284', ctypes.c_uint32), + ('reserved_285', ctypes.c_uint32), + ('reserved_286', ctypes.c_uint32), + ('reserved_287', ctypes.c_uint32), + ('reserved_288', ctypes.c_uint32), + ('reserved_289', ctypes.c_uint32), + ('reserved_290', ctypes.c_uint32), + ('reserved_291', ctypes.c_uint32), + ('reserved_292', ctypes.c_uint32), + ('reserved_293', ctypes.c_uint32), + ('reserved_294', ctypes.c_uint32), + ('reserved_295', ctypes.c_uint32), + ('reserved_296', ctypes.c_uint32), + ('reserved_297', ctypes.c_uint32), + ('reserved_298', ctypes.c_uint32), + ('reserved_299', ctypes.c_uint32), + ('reserved_300', ctypes.c_uint32), + ('reserved_301', ctypes.c_uint32), + ('reserved_302', ctypes.c_uint32), + ('reserved_303', ctypes.c_uint32), + ('reserved_304', ctypes.c_uint32), + ('reserved_305', ctypes.c_uint32), + ('reserved_306', ctypes.c_uint32), + ('reserved_307', ctypes.c_uint32), + ('reserved_308', ctypes.c_uint32), + ('reserved_309', ctypes.c_uint32), + ('reserved_310', ctypes.c_uint32), + ('reserved_311', ctypes.c_uint32), + ('reserved_312', ctypes.c_uint32), + ('reserved_313', ctypes.c_uint32), + ('reserved_314', ctypes.c_uint32), + ('reserved_315', ctypes.c_uint32), + ('reserved_316', ctypes.c_uint32), + ('reserved_317', ctypes.c_uint32), + ('reserved_318', ctypes.c_uint32), + ('reserved_319', ctypes.c_uint32), + ('reserved_320', ctypes.c_uint32), + ('reserved_321', ctypes.c_uint32), + ('reserved_322', ctypes.c_uint32), + ('reserved_323', ctypes.c_uint32), + ('reserved_324', ctypes.c_uint32), + ('reserved_325', ctypes.c_uint32), + ('reserved_326', ctypes.c_uint32), + ('reserved_327', ctypes.c_uint32), + ('reserved_328', ctypes.c_uint32), + ('reserved_329', ctypes.c_uint32), + ('reserved_330', ctypes.c_uint32), + ('reserved_331', ctypes.c_uint32), + ('reserved_332', ctypes.c_uint32), + ('reserved_333', ctypes.c_uint32), + ('reserved_334', ctypes.c_uint32), + ('reserved_335', ctypes.c_uint32), + ('reserved_336', ctypes.c_uint32), + ('reserved_337', ctypes.c_uint32), + ('reserved_338', ctypes.c_uint32), + ('reserved_339', ctypes.c_uint32), + ('reserved_340', ctypes.c_uint32), + ('reserved_341', ctypes.c_uint32), + ('reserved_342', ctypes.c_uint32), + ('reserved_343', ctypes.c_uint32), + ('reserved_344', ctypes.c_uint32), + ('reserved_345', ctypes.c_uint32), + ('reserved_346', ctypes.c_uint32), + ('reserved_347', ctypes.c_uint32), + ('reserved_348', ctypes.c_uint32), + ('reserved_349', ctypes.c_uint32), + ('reserved_350', ctypes.c_uint32), + ('reserved_351', ctypes.c_uint32), + ('reserved_352', ctypes.c_uint32), + ('reserved_353', ctypes.c_uint32), + ('reserved_354', ctypes.c_uint32), + ('reserved_355', ctypes.c_uint32), + ('reserved_356', ctypes.c_uint32), + ('reserved_357', ctypes.c_uint32), + ('reserved_358', ctypes.c_uint32), + ('reserved_359', ctypes.c_uint32), + ('reserved_360', ctypes.c_uint32), + ('reserved_361', ctypes.c_uint32), + ('reserved_362', ctypes.c_uint32), + ('reserved_363', ctypes.c_uint32), + ('reserved_364', ctypes.c_uint32), + ('reserved_365', ctypes.c_uint32), + ('reserved_366', ctypes.c_uint32), + ('reserved_367', ctypes.c_uint32), + ('reserved_368', ctypes.c_uint32), + ('reserved_369', ctypes.c_uint32), + ('reserved_370', ctypes.c_uint32), + ('reserved_371', ctypes.c_uint32), + ('reserved_372', ctypes.c_uint32), + ('reserved_373', ctypes.c_uint32), + ('reserved_374', ctypes.c_uint32), + ('reserved_375', ctypes.c_uint32), + ('reserved_376', ctypes.c_uint32), + ('reserved_377', ctypes.c_uint32), + ('reserved_378', ctypes.c_uint32), + ('reserved_379', ctypes.c_uint32), + ('reserved_380', ctypes.c_uint32), + ('reserved_381', ctypes.c_uint32), + ('reserved_382', ctypes.c_uint32), + ('reserved_383', ctypes.c_uint32), + ('reserved_384', ctypes.c_uint32), + ('reserved_385', ctypes.c_uint32), + ('reserved_386', ctypes.c_uint32), + ('reserved_387', ctypes.c_uint32), + ('reserved_388', ctypes.c_uint32), + ('reserved_389', ctypes.c_uint32), + ('reserved_390', ctypes.c_uint32), + ('reserved_391', ctypes.c_uint32), + ('reserved_392', ctypes.c_uint32), + ('reserved_393', ctypes.c_uint32), + ('reserved_394', ctypes.c_uint32), + ('reserved_395', ctypes.c_uint32), + ('reserved_396', ctypes.c_uint32), + ('reserved_397', ctypes.c_uint32), + ('reserved_398', ctypes.c_uint32), + ('reserved_399', ctypes.c_uint32), + ('reserved_400', ctypes.c_uint32), + ('reserved_401', ctypes.c_uint32), + ('reserved_402', ctypes.c_uint32), + ('reserved_403', ctypes.c_uint32), + ('reserved_404', ctypes.c_uint32), + ('reserved_405', ctypes.c_uint32), + ('reserved_406', ctypes.c_uint32), + ('reserved_407', ctypes.c_uint32), + ('reserved_408', ctypes.c_uint32), + ('reserved_409', ctypes.c_uint32), + ('reserved_410', ctypes.c_uint32), + ('reserved_411', ctypes.c_uint32), + ('reserved_412', ctypes.c_uint32), + ('reserved_413', ctypes.c_uint32), + ('reserved_414', ctypes.c_uint32), + ('reserved_415', ctypes.c_uint32), + ('reserved_416', ctypes.c_uint32), + ('reserved_417', ctypes.c_uint32), + ('reserved_418', ctypes.c_uint32), + ('reserved_419', ctypes.c_uint32), + ('reserved_420', ctypes.c_uint32), + ('reserved_421', ctypes.c_uint32), + ('reserved_422', ctypes.c_uint32), + ('reserved_423', ctypes.c_uint32), + ('reserved_424', ctypes.c_uint32), + ('reserved_425', ctypes.c_uint32), + ('reserved_426', ctypes.c_uint32), + ('reserved_427', ctypes.c_uint32), + ('reserved_428', ctypes.c_uint32), + ('reserved_429', ctypes.c_uint32), + ('reserved_430', ctypes.c_uint32), + ('reserved_431', ctypes.c_uint32), + ('reserved_432', ctypes.c_uint32), + ('reserved_433', ctypes.c_uint32), + ('reserved_434', ctypes.c_uint32), + ('reserved_435', ctypes.c_uint32), + ('reserved_436', ctypes.c_uint32), + ('reserved_437', ctypes.c_uint32), + ('reserved_438', ctypes.c_uint32), + ('reserved_439', ctypes.c_uint32), + ('reserved_440', ctypes.c_uint32), + ('reserved_441', ctypes.c_uint32), + ('reserved_442', ctypes.c_uint32), + ('reserved_443', ctypes.c_uint32), + ('reserved_444', ctypes.c_uint32), + ('reserved_445', ctypes.c_uint32), + ('reserved_446', ctypes.c_uint32), + ('reserved_447', ctypes.c_uint32), + ('gws_0_val', ctypes.c_uint32), + ('gws_1_val', ctypes.c_uint32), + ('gws_2_val', ctypes.c_uint32), + ('gws_3_val', ctypes.c_uint32), + ('gws_4_val', ctypes.c_uint32), + ('gws_5_val', ctypes.c_uint32), + ('gws_6_val', ctypes.c_uint32), + ('gws_7_val', ctypes.c_uint32), + ('gws_8_val', ctypes.c_uint32), + ('gws_9_val', ctypes.c_uint32), + ('gws_10_val', ctypes.c_uint32), + ('gws_11_val', ctypes.c_uint32), + ('gws_12_val', ctypes.c_uint32), + ('gws_13_val', ctypes.c_uint32), + ('gws_14_val', ctypes.c_uint32), + ('gws_15_val', ctypes.c_uint32), + ('gws_16_val', ctypes.c_uint32), + ('gws_17_val', ctypes.c_uint32), + ('gws_18_val', ctypes.c_uint32), + ('gws_19_val', ctypes.c_uint32), + ('gws_20_val', ctypes.c_uint32), + ('gws_21_val', ctypes.c_uint32), + ('gws_22_val', ctypes.c_uint32), + ('gws_23_val', ctypes.c_uint32), + ('gws_24_val', ctypes.c_uint32), + ('gws_25_val', ctypes.c_uint32), + ('gws_26_val', ctypes.c_uint32), + ('gws_27_val', ctypes.c_uint32), + ('gws_28_val', ctypes.c_uint32), + ('gws_29_val', ctypes.c_uint32), + ('gws_30_val', ctypes.c_uint32), + ('gws_31_val', ctypes.c_uint32), + ('gws_32_val', ctypes.c_uint32), + ('gws_33_val', ctypes.c_uint32), + ('gws_34_val', ctypes.c_uint32), + ('gws_35_val', ctypes.c_uint32), + ('gws_36_val', ctypes.c_uint32), + ('gws_37_val', ctypes.c_uint32), + ('gws_38_val', ctypes.c_uint32), + ('gws_39_val', ctypes.c_uint32), + ('gws_40_val', ctypes.c_uint32), + ('gws_41_val', ctypes.c_uint32), + ('gws_42_val', ctypes.c_uint32), + ('gws_43_val', ctypes.c_uint32), + ('gws_44_val', ctypes.c_uint32), + ('gws_45_val', ctypes.c_uint32), + ('gws_46_val', ctypes.c_uint32), + ('gws_47_val', ctypes.c_uint32), + ('gws_48_val', ctypes.c_uint32), + ('gws_49_val', ctypes.c_uint32), + ('gws_50_val', ctypes.c_uint32), + ('gws_51_val', ctypes.c_uint32), + ('gws_52_val', ctypes.c_uint32), + ('gws_53_val', ctypes.c_uint32), + ('gws_54_val', ctypes.c_uint32), + ('gws_55_val', ctypes.c_uint32), + ('gws_56_val', ctypes.c_uint32), + ('gws_57_val', ctypes.c_uint32), + ('gws_58_val', ctypes.c_uint32), + ('gws_59_val', ctypes.c_uint32), + ('gws_60_val', ctypes.c_uint32), + ('gws_61_val', ctypes.c_uint32), + ('gws_62_val', ctypes.c_uint32), + ('gws_63_val', ctypes.c_uint32), +] + +__AMDGPU_VM_H__ = True # macro +AMDGPU_VM_MAX_UPDATE_SIZE = 0x3FFFF # macro +# def AMDGPU_VM_PTE_COUNT(adev): # macro +# return (1<<(adev)->vm_manager.block_size) +AMDGPU_PTE_VALID = (1<<0) # macro +AMDGPU_PTE_SYSTEM = (1<<1) # macro +AMDGPU_PTE_SNOOPED = (1<<2) # macro +AMDGPU_PTE_TMZ = (1<<3) # macro +AMDGPU_PTE_EXECUTABLE = (1<<4) # macro +AMDGPU_PTE_READABLE = (1<<5) # macro +AMDGPU_PTE_WRITEABLE = (1<<6) # macro +def AMDGPU_PTE_FRAG(x): # macro + return ((x&0x1f)<<7) +AMDGPU_PTE_PRT = (1<<51) # macro +AMDGPU_PDE_PTE = (1<<54) # macro +AMDGPU_PTE_LOG = (1<<55) # macro +AMDGPU_PTE_TF = (1<<56) # macro +AMDGPU_PTE_NOALLOC = (1<<58) # macro +def AMDGPU_PDE_BFS(a): # macro + return ( a<<59) +AMDGPU_VM_NORETRY_FLAGS = ((1<<4)|(1<<54)|(1<<56)) # macro +AMDGPU_VM_NORETRY_FLAGS_TF = ((1<<0)|(1<<1)|(1<<51)) # macro +def AMDGPU_PTE_MTYPE_VG10_SHIFT(mtype): # macro + return ( (mtype)<<57) +AMDGPU_PTE_MTYPE_VG10_MASK = AMDGPU_PTE_MTYPE_VG10_SHIFT ( 3 ) # macro +def AMDGPU_PTE_MTYPE_VG10(flags, mtype): # macro + return (( (flags)&(~AMDGPU_PTE_MTYPE_VG10_SHIFT(3)))|AMDGPU_PTE_MTYPE_VG10_SHIFT(mtype)) +AMDGPU_MTYPE_NC = 0 # macro +AMDGPU_MTYPE_CC = 2 # macro +AMDGPU_PTE_DEFAULT_ATC = ((1<<1)|(1<<2)|(1<<4)|(1<<5)|(1<<6)|AMDGPU_PTE_MTYPE_VG10(0, 2)) # macro +def AMDGPU_PTE_MTYPE_NV10_SHIFT(mtype): # macro + return ( (mtype)<<48) +AMDGPU_PTE_MTYPE_NV10_MASK = AMDGPU_PTE_MTYPE_NV10_SHIFT ( 7 ) # macro +def AMDGPU_PTE_MTYPE_NV10(flags, mtype): # macro + return (( (flags)&(~AMDGPU_PTE_MTYPE_NV10_SHIFT(7)))|AMDGPU_PTE_MTYPE_NV10_SHIFT(mtype)) +AMDGPU_PTE_PRT_GFX12 = (1<<56) # macro +def AMDGPU_PTE_MTYPE_GFX12_SHIFT(mtype): # macro + return ( (mtype)<<54) +AMDGPU_PTE_MTYPE_GFX12_MASK = AMDGPU_PTE_MTYPE_GFX12_SHIFT ( 3 ) # macro +def AMDGPU_PTE_MTYPE_GFX12(flags, mtype): # macro + return (( (flags)&(~AMDGPU_PTE_MTYPE_GFX12_SHIFT(3)))|AMDGPU_PTE_MTYPE_GFX12_SHIFT(mtype)) +AMDGPU_PTE_IS_PTE = (1<<63) # macro +def AMDGPU_PDE_BFS_GFX12(a): # macro + return ( ((a)&0x1f)<<58) +AMDGPU_PDE_PTE_GFX12 = (1<<63) # macro +AMDGPU_VM_FAULT_STOP_NEVER = 0 # macro +AMDGPU_VM_FAULT_STOP_FIRST = 1 # macro +AMDGPU_VM_FAULT_STOP_ALWAYS = 2 # macro +AMDGPU_VM_RESERVED_VRAM = (8<<20) # macro +AMDGPU_MAX_VMHUBS = 13 # macro +AMDGPU_GFXHUB_START = 0 # macro +AMDGPU_MMHUB0_START = 8 # macro +AMDGPU_MMHUB1_START = 12 # macro +def AMDGPU_GFXHUB(x): # macro + return (0+(x)) +def AMDGPU_MMHUB0(x): # macro + return (8+(x)) +def AMDGPU_MMHUB1(x): # macro + return (12+(x)) +def AMDGPU_IS_GFXHUB(x): # macro + return ((x)>=0 and (x)<8) +def AMDGPU_IS_MMHUB0(x): # macro + return ((x)>=8 and (x)<12) +def AMDGPU_IS_MMHUB1(x): # macro + return ((x)>=12 and (x)<13) +AMDGPU_VA_RESERVED_CSA_SIZE = (2<<20) # macro +# def AMDGPU_VA_RESERVED_CSA_START(adev): # macro +# return (((adev)->vm_manager.max_pfn<=IP_VERSION(12,0,0))?(1<<56):(1<<51)) +# def AMDGPU_PDE_BFS_FLAG(adev, a): # macro +# return ((amdgpu_ip_version((adev),GC_HWIP,0)>=IP_VERSION(12,0,0))?AMDGPU_PDE_BFS_GFX12(a):AMDGPU_PDE_BFS(a)) +# def AMDGPU_PDE_PTE_FLAG(adev): # macro +# return ((amdgpu_ip_version((adev),GC_HWIP,0)>=IP_VERSION(12,0,0))?(1<<63):(1<<54)) +hw_id_map = [['GC_HWIP', '11'],['HDP_HWIP', '41'],['SDMA0_HWIP', '42'],['SDMA1_HWIP', '43'],['SDMA2_HWIP', '68'],['SDMA3_HWIP', '69'],['LSDMA_HWIP', '91'],['MMHUB_HWIP', '34'],['ATHUB_HWIP', '35'],['NBIO_HWIP', '108'],['MP0_HWIP', '255'],['MP1_HWIP', '1'],['UVD_HWIP', '12'],['VCE_HWIP', '32'],['DF_HWIP', '46'],['DCE_HWIP', '271'],['OSSSYS_HWIP', '40'],['SMUIO_HWIP', '4'],['PWR_HWIP', '10'],['NBIF_HWIP', '108'],['THM_HWIP', '3'],['CLK_HWIP', '6'],['UMC_HWIP', '150'],['XGMI_HWIP', '200'],['DCI_HWIP', '15'],['PCIE_HWIP', '70'],['VPE_HWIP', '21'],['ISP_HWIP', '44']] # Variable ctypes.c_int32 * 35 +__AMDGPU_UCODE_H__ = True # macro +int32_t = True # macro +int8_t = True # macro +int16_t = True # macro +bool = True # macro +u32 = True # macro +AMDGPU_SDMA0_UCODE_LOADED = 0x00000001 # macro +AMDGPU_SDMA1_UCODE_LOADED = 0x00000002 # macro +AMDGPU_CPCE_UCODE_LOADED = 0x00000004 # macro +AMDGPU_CPPFP_UCODE_LOADED = 0x00000008 # macro +AMDGPU_CPME_UCODE_LOADED = 0x00000010 # macro +AMDGPU_CPMEC1_UCODE_LOADED = 0x00000020 # macro +AMDGPU_CPMEC2_UCODE_LOADED = 0x00000040 # macro +AMDGPU_CPRLC_UCODE_LOADED = 0x00000100 # macro +class struct_common_firmware_header(Structure): + pass + +struct_common_firmware_header._pack_ = 1 # source:False +struct_common_firmware_header._fields_ = [ + ('size_bytes', ctypes.c_uint32), + ('header_size_bytes', ctypes.c_uint32), + ('header_version_major', ctypes.c_uint16), + ('header_version_minor', ctypes.c_uint16), + ('ip_version_major', ctypes.c_uint16), + ('ip_version_minor', ctypes.c_uint16), + ('ucode_version', ctypes.c_uint32), + ('ucode_size_bytes', ctypes.c_uint32), + ('ucode_array_offset_bytes', ctypes.c_uint32), + ('crc32', ctypes.c_uint32), +] + +class struct_mc_firmware_header_v1_0(Structure): + pass + +struct_mc_firmware_header_v1_0._pack_ = 1 # source:False +struct_mc_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('io_debug_size_bytes', ctypes.c_uint32), + ('io_debug_array_offset_bytes', ctypes.c_uint32), +] + +class struct_smc_firmware_header_v1_0(Structure): + pass + +struct_smc_firmware_header_v1_0._pack_ = 1 # source:False +struct_smc_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_start_addr', ctypes.c_uint32), +] + +class struct_smc_firmware_header_v2_0(Structure): + pass + +struct_smc_firmware_header_v2_0._pack_ = 1 # source:False +struct_smc_firmware_header_v2_0._fields_ = [ + ('v1_0', struct_smc_firmware_header_v1_0), + ('ppt_offset_bytes', ctypes.c_uint32), + ('ppt_size_bytes', ctypes.c_uint32), +] + +class struct_smc_soft_pptable_entry(Structure): + pass + +struct_smc_soft_pptable_entry._pack_ = 1 # source:False +struct_smc_soft_pptable_entry._fields_ = [ + ('id', ctypes.c_uint32), + ('ppt_offset_bytes', ctypes.c_uint32), + ('ppt_size_bytes', ctypes.c_uint32), +] + +class struct_smc_firmware_header_v2_1(Structure): + pass + +struct_smc_firmware_header_v2_1._pack_ = 1 # source:False +struct_smc_firmware_header_v2_1._fields_ = [ + ('v1_0', struct_smc_firmware_header_v1_0), + ('pptable_count', ctypes.c_uint32), + ('pptable_entry_offset', ctypes.c_uint32), +] + +class struct_psp_fw_legacy_bin_desc(Structure): + pass + +struct_psp_fw_legacy_bin_desc._pack_ = 1 # source:False +struct_psp_fw_legacy_bin_desc._fields_ = [ + ('fw_version', ctypes.c_uint32), + ('offset_bytes', ctypes.c_uint32), + ('size_bytes', ctypes.c_uint32), +] + +class struct_psp_firmware_header_v1_0(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('header', struct_common_firmware_header), + ('sos', struct_psp_fw_legacy_bin_desc), + ] + +class struct_psp_firmware_header_v1_1(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('v1_0', struct_psp_firmware_header_v1_0), + ('toc', struct_psp_fw_legacy_bin_desc), + ('kdb', struct_psp_fw_legacy_bin_desc), + ] + +class struct_psp_firmware_header_v1_2(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('v1_0', struct_psp_firmware_header_v1_0), + ('res', struct_psp_fw_legacy_bin_desc), + ('kdb', struct_psp_fw_legacy_bin_desc), + ] + +class struct_psp_firmware_header_v1_3(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('v1_1', struct_psp_firmware_header_v1_1), + ('spl', struct_psp_fw_legacy_bin_desc), + ('rl', struct_psp_fw_legacy_bin_desc), + ('sys_drv_aux', struct_psp_fw_legacy_bin_desc), + ('sos_aux', struct_psp_fw_legacy_bin_desc), + ] + +class struct_psp_fw_bin_desc(Structure): + pass + +struct_psp_fw_bin_desc._pack_ = 1 # source:False +struct_psp_fw_bin_desc._fields_ = [ + ('fw_type', ctypes.c_uint32), + ('fw_version', ctypes.c_uint32), + ('offset_bytes', ctypes.c_uint32), + ('size_bytes', ctypes.c_uint32), +] + +# UCODE_MAX_PSP_PACKAGING = (((ctypes.sizeof(amdgpu_firmware_header)-ctypes.sizeof(struct_common_firmware_header)-4)/ctypes.sizeof(struct_psp_fw_bin_desc))*2) # macro + +# values for enumeration 'psp_fw_type' +psp_fw_type__enumvalues = { + 0: 'PSP_FW_TYPE_UNKOWN', + 1: 'PSP_FW_TYPE_PSP_SOS', + 2: 'PSP_FW_TYPE_PSP_SYS_DRV', + 3: 'PSP_FW_TYPE_PSP_KDB', + 4: 'PSP_FW_TYPE_PSP_TOC', + 5: 'PSP_FW_TYPE_PSP_SPL', + 6: 'PSP_FW_TYPE_PSP_RL', + 7: 'PSP_FW_TYPE_PSP_SOC_DRV', + 8: 'PSP_FW_TYPE_PSP_INTF_DRV', + 9: 'PSP_FW_TYPE_PSP_DBG_DRV', + 10: 'PSP_FW_TYPE_PSP_RAS_DRV', + 11: 'PSP_FW_TYPE_PSP_IPKEYMGR_DRV', + 12: 'PSP_FW_TYPE_MAX_INDEX', +} +PSP_FW_TYPE_UNKOWN = 0 +PSP_FW_TYPE_PSP_SOS = 1 +PSP_FW_TYPE_PSP_SYS_DRV = 2 +PSP_FW_TYPE_PSP_KDB = 3 +PSP_FW_TYPE_PSP_TOC = 4 +PSP_FW_TYPE_PSP_SPL = 5 +PSP_FW_TYPE_PSP_RL = 6 +PSP_FW_TYPE_PSP_SOC_DRV = 7 +PSP_FW_TYPE_PSP_INTF_DRV = 8 +PSP_FW_TYPE_PSP_DBG_DRV = 9 +PSP_FW_TYPE_PSP_RAS_DRV = 10 +PSP_FW_TYPE_PSP_IPKEYMGR_DRV = 11 +PSP_FW_TYPE_MAX_INDEX = 12 +psp_fw_type = ctypes.c_uint32 # enum +class struct_psp_firmware_header_v2_0(Structure): + pass + +struct_psp_firmware_header_v2_0._pack_ = 1 # source:False +struct_psp_firmware_header_v2_0._fields_ = [ + ('header', struct_common_firmware_header), + ('psp_fw_bin_count', ctypes.c_uint32), + ('psp_fw_bin', struct_psp_fw_bin_desc * 1), +] + +class struct_psp_firmware_header_v2_1(Structure): + pass + +struct_psp_firmware_header_v2_1._pack_ = 1 # source:False +struct_psp_firmware_header_v2_1._fields_ = [ + ('header', struct_common_firmware_header), + ('psp_fw_bin_count', ctypes.c_uint32), + ('psp_aux_fw_bin_index', ctypes.c_uint32), + ('psp_fw_bin', struct_psp_fw_bin_desc * 1), +] + +class struct_ta_firmware_header_v1_0(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('header', struct_common_firmware_header), + ('xgmi', struct_psp_fw_legacy_bin_desc), + ('ras', struct_psp_fw_legacy_bin_desc), + ('hdcp', struct_psp_fw_legacy_bin_desc), + ('dtm', struct_psp_fw_legacy_bin_desc), + ('securedisplay', struct_psp_fw_legacy_bin_desc), + ] + + +# values for enumeration 'ta_fw_type' +ta_fw_type__enumvalues = { + 0: 'TA_FW_TYPE_UNKOWN', + 1: 'TA_FW_TYPE_PSP_ASD', + 2: 'TA_FW_TYPE_PSP_XGMI', + 3: 'TA_FW_TYPE_PSP_RAS', + 4: 'TA_FW_TYPE_PSP_HDCP', + 5: 'TA_FW_TYPE_PSP_DTM', + 6: 'TA_FW_TYPE_PSP_RAP', + 7: 'TA_FW_TYPE_PSP_SECUREDISPLAY', + 8: 'TA_FW_TYPE_MAX_INDEX', +} +TA_FW_TYPE_UNKOWN = 0 +TA_FW_TYPE_PSP_ASD = 1 +TA_FW_TYPE_PSP_XGMI = 2 +TA_FW_TYPE_PSP_RAS = 3 +TA_FW_TYPE_PSP_HDCP = 4 +TA_FW_TYPE_PSP_DTM = 5 +TA_FW_TYPE_PSP_RAP = 6 +TA_FW_TYPE_PSP_SECUREDISPLAY = 7 +TA_FW_TYPE_MAX_INDEX = 8 +ta_fw_type = ctypes.c_uint32 # enum +class struct_ta_firmware_header_v2_0(Structure): + pass + +struct_ta_firmware_header_v2_0._pack_ = 1 # source:False +struct_ta_firmware_header_v2_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ta_fw_bin_count', ctypes.c_uint32), + ('ta_fw_bin', struct_psp_fw_bin_desc * 1), +] + +class struct_gfx_firmware_header_v1_0(Structure): + pass + +struct_gfx_firmware_header_v1_0._pack_ = 1 # source:False +struct_gfx_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('jt_offset', ctypes.c_uint32), + ('jt_size', ctypes.c_uint32), +] + +class struct_gfx_firmware_header_v2_0(Structure): + pass + +struct_gfx_firmware_header_v2_0._pack_ = 1 # source:False +struct_gfx_firmware_header_v2_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('ucode_size_bytes', ctypes.c_uint32), + ('ucode_offset_bytes', ctypes.c_uint32), + ('data_size_bytes', ctypes.c_uint32), + ('data_offset_bytes', ctypes.c_uint32), + ('ucode_start_addr_lo', ctypes.c_uint32), + ('ucode_start_addr_hi', ctypes.c_uint32), +] + +class struct_mes_firmware_header_v1_0(Structure): + pass + +struct_mes_firmware_header_v1_0._pack_ = 1 # source:False +struct_mes_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('mes_ucode_version', ctypes.c_uint32), + ('mes_ucode_size_bytes', ctypes.c_uint32), + ('mes_ucode_offset_bytes', ctypes.c_uint32), + ('mes_ucode_data_version', ctypes.c_uint32), + ('mes_ucode_data_size_bytes', ctypes.c_uint32), + ('mes_ucode_data_offset_bytes', ctypes.c_uint32), + ('mes_uc_start_addr_lo', ctypes.c_uint32), + ('mes_uc_start_addr_hi', ctypes.c_uint32), + ('mes_data_start_addr_lo', ctypes.c_uint32), + ('mes_data_start_addr_hi', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v1_0(Structure): + pass + +struct_rlc_firmware_header_v1_0._pack_ = 1 # source:False +struct_rlc_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('save_and_restore_offset', ctypes.c_uint32), + ('clear_state_descriptor_offset', ctypes.c_uint32), + ('avail_scratch_ram_locations', ctypes.c_uint32), + ('master_pkt_description_offset', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v2_0(Structure): + pass + +struct_rlc_firmware_header_v2_0._pack_ = 1 # source:False +struct_rlc_firmware_header_v2_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('jt_offset', ctypes.c_uint32), + ('jt_size', ctypes.c_uint32), + ('save_and_restore_offset', ctypes.c_uint32), + ('clear_state_descriptor_offset', ctypes.c_uint32), + ('avail_scratch_ram_locations', ctypes.c_uint32), + ('reg_restore_list_size', ctypes.c_uint32), + ('reg_list_format_start', ctypes.c_uint32), + ('reg_list_format_separate_start', ctypes.c_uint32), + ('starting_offsets_start', ctypes.c_uint32), + ('reg_list_format_size_bytes', ctypes.c_uint32), + ('reg_list_format_array_offset_bytes', ctypes.c_uint32), + ('reg_list_size_bytes', ctypes.c_uint32), + ('reg_list_array_offset_bytes', ctypes.c_uint32), + ('reg_list_format_separate_size_bytes', ctypes.c_uint32), + ('reg_list_format_separate_array_offset_bytes', ctypes.c_uint32), + ('reg_list_separate_size_bytes', ctypes.c_uint32), + ('reg_list_separate_array_offset_bytes', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v2_1(Structure): + pass + +struct_rlc_firmware_header_v2_1._pack_ = 1 # source:False +struct_rlc_firmware_header_v2_1._fields_ = [ + ('v2_0', struct_rlc_firmware_header_v2_0), + ('reg_list_format_direct_reg_list_length', ctypes.c_uint32), + ('save_restore_list_cntl_ucode_ver', ctypes.c_uint32), + ('save_restore_list_cntl_feature_ver', ctypes.c_uint32), + ('save_restore_list_cntl_size_bytes', ctypes.c_uint32), + ('save_restore_list_cntl_offset_bytes', ctypes.c_uint32), + ('save_restore_list_gpm_ucode_ver', ctypes.c_uint32), + ('save_restore_list_gpm_feature_ver', ctypes.c_uint32), + ('save_restore_list_gpm_size_bytes', ctypes.c_uint32), + ('save_restore_list_gpm_offset_bytes', ctypes.c_uint32), + ('save_restore_list_srm_ucode_ver', ctypes.c_uint32), + ('save_restore_list_srm_feature_ver', ctypes.c_uint32), + ('save_restore_list_srm_size_bytes', ctypes.c_uint32), + ('save_restore_list_srm_offset_bytes', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v2_2(Structure): + pass + +struct_rlc_firmware_header_v2_2._pack_ = 1 # source:False +struct_rlc_firmware_header_v2_2._fields_ = [ + ('v2_1', struct_rlc_firmware_header_v2_1), + ('rlc_iram_ucode_size_bytes', ctypes.c_uint32), + ('rlc_iram_ucode_offset_bytes', ctypes.c_uint32), + ('rlc_dram_ucode_size_bytes', ctypes.c_uint32), + ('rlc_dram_ucode_offset_bytes', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v2_3(Structure): + pass + +struct_rlc_firmware_header_v2_3._pack_ = 1 # source:False +struct_rlc_firmware_header_v2_3._fields_ = [ + ('v2_2', struct_rlc_firmware_header_v2_2), + ('rlcp_ucode_version', ctypes.c_uint32), + ('rlcp_ucode_feature_version', ctypes.c_uint32), + ('rlcp_ucode_size_bytes', ctypes.c_uint32), + ('rlcp_ucode_offset_bytes', ctypes.c_uint32), + ('rlcv_ucode_version', ctypes.c_uint32), + ('rlcv_ucode_feature_version', ctypes.c_uint32), + ('rlcv_ucode_size_bytes', ctypes.c_uint32), + ('rlcv_ucode_offset_bytes', ctypes.c_uint32), +] + +class struct_rlc_firmware_header_v2_4(Structure): + pass + +struct_rlc_firmware_header_v2_4._pack_ = 1 # source:False +struct_rlc_firmware_header_v2_4._fields_ = [ + ('v2_3', struct_rlc_firmware_header_v2_3), + ('global_tap_delays_ucode_size_bytes', ctypes.c_uint32), + ('global_tap_delays_ucode_offset_bytes', ctypes.c_uint32), + ('se0_tap_delays_ucode_size_bytes', ctypes.c_uint32), + ('se0_tap_delays_ucode_offset_bytes', ctypes.c_uint32), + ('se1_tap_delays_ucode_size_bytes', ctypes.c_uint32), + ('se1_tap_delays_ucode_offset_bytes', ctypes.c_uint32), + ('se2_tap_delays_ucode_size_bytes', ctypes.c_uint32), + ('se2_tap_delays_ucode_offset_bytes', ctypes.c_uint32), + ('se3_tap_delays_ucode_size_bytes', ctypes.c_uint32), + ('se3_tap_delays_ucode_offset_bytes', ctypes.c_uint32), +] + +class struct_sdma_firmware_header_v1_0(Structure): + pass + +struct_sdma_firmware_header_v1_0._pack_ = 1 # source:False +struct_sdma_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('ucode_change_version', ctypes.c_uint32), + ('jt_offset', ctypes.c_uint32), + ('jt_size', ctypes.c_uint32), +] + +class struct_sdma_firmware_header_v1_1(Structure): + pass + +struct_sdma_firmware_header_v1_1._pack_ = 1 # source:False +struct_sdma_firmware_header_v1_1._fields_ = [ + ('v1_0', struct_sdma_firmware_header_v1_0), + ('digest_size', ctypes.c_uint32), +] + +class struct_sdma_firmware_header_v2_0(Structure): + pass + +struct_sdma_firmware_header_v2_0._pack_ = 1 # source:False +struct_sdma_firmware_header_v2_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('ctx_ucode_size_bytes', ctypes.c_uint32), + ('ctx_jt_offset', ctypes.c_uint32), + ('ctx_jt_size', ctypes.c_uint32), + ('ctl_ucode_offset', ctypes.c_uint32), + ('ctl_ucode_size_bytes', ctypes.c_uint32), + ('ctl_jt_offset', ctypes.c_uint32), + ('ctl_jt_size', ctypes.c_uint32), +] + +class struct_vpe_firmware_header_v1_0(Structure): + pass + +struct_vpe_firmware_header_v1_0._pack_ = 1 # source:False +struct_vpe_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('ctx_ucode_size_bytes', ctypes.c_uint32), + ('ctx_jt_offset', ctypes.c_uint32), + ('ctx_jt_size', ctypes.c_uint32), + ('ctl_ucode_offset', ctypes.c_uint32), + ('ctl_ucode_size_bytes', ctypes.c_uint32), + ('ctl_jt_offset', ctypes.c_uint32), + ('ctl_jt_size', ctypes.c_uint32), +] + +class struct_umsch_mm_firmware_header_v1_0(Structure): + pass + +struct_umsch_mm_firmware_header_v1_0._pack_ = 1 # source:False +struct_umsch_mm_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('umsch_mm_ucode_version', ctypes.c_uint32), + ('umsch_mm_ucode_size_bytes', ctypes.c_uint32), + ('umsch_mm_ucode_offset_bytes', ctypes.c_uint32), + ('umsch_mm_ucode_data_version', ctypes.c_uint32), + ('umsch_mm_ucode_data_size_bytes', ctypes.c_uint32), + ('umsch_mm_ucode_data_offset_bytes', ctypes.c_uint32), + ('umsch_mm_irq_start_addr_lo', ctypes.c_uint32), + ('umsch_mm_irq_start_addr_hi', ctypes.c_uint32), + ('umsch_mm_uc_start_addr_lo', ctypes.c_uint32), + ('umsch_mm_uc_start_addr_hi', ctypes.c_uint32), + ('umsch_mm_data_start_addr_lo', ctypes.c_uint32), + ('umsch_mm_data_start_addr_hi', ctypes.c_uint32), +] + +class struct_sdma_firmware_header_v3_0(Structure): + pass + +struct_sdma_firmware_header_v3_0._pack_ = 1 # source:False +struct_sdma_firmware_header_v3_0._fields_ = [ + ('header', struct_common_firmware_header), + ('ucode_feature_version', ctypes.c_uint32), + ('ucode_offset_bytes', ctypes.c_uint32), + ('ucode_size_bytes', ctypes.c_uint32), +] + +class struct_gpu_info_firmware_v1_0(Structure): + pass + +struct_gpu_info_firmware_v1_0._pack_ = 1 # source:False +struct_gpu_info_firmware_v1_0._fields_ = [ + ('gc_num_se', ctypes.c_uint32), + ('gc_num_cu_per_sh', ctypes.c_uint32), + ('gc_num_sh_per_se', ctypes.c_uint32), + ('gc_num_rb_per_se', ctypes.c_uint32), + ('gc_num_tccs', ctypes.c_uint32), + ('gc_num_gprs', ctypes.c_uint32), + ('gc_num_max_gs_thds', ctypes.c_uint32), + ('gc_gs_table_depth', ctypes.c_uint32), + ('gc_gsprim_buff_depth', ctypes.c_uint32), + ('gc_parameter_cache_depth', ctypes.c_uint32), + ('gc_double_offchip_lds_buffer', ctypes.c_uint32), + ('gc_wave_size', ctypes.c_uint32), + ('gc_max_waves_per_simd', ctypes.c_uint32), + ('gc_max_scratch_slots_per_cu', ctypes.c_uint32), + ('gc_lds_size', ctypes.c_uint32), +] + +class struct_gpu_info_firmware_v1_1(Structure): + pass + +struct_gpu_info_firmware_v1_1._pack_ = 1 # source:False +struct_gpu_info_firmware_v1_1._fields_ = [ + ('v1_0', struct_gpu_info_firmware_v1_0), + ('num_sc_per_sh', ctypes.c_uint32), + ('num_packer_per_sc', ctypes.c_uint32), +] + +class struct_gpu_info_firmware_header_v1_0(Structure): + pass + +struct_gpu_info_firmware_header_v1_0._pack_ = 1 # source:False +struct_gpu_info_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('version_major', ctypes.c_uint16), + ('version_minor', ctypes.c_uint16), +] + +class struct_dmcu_firmware_header_v1_0(Structure): + pass + +struct_dmcu_firmware_header_v1_0._pack_ = 1 # source:False +struct_dmcu_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('intv_offset_bytes', ctypes.c_uint32), + ('intv_size_bytes', ctypes.c_uint32), +] + +class struct_dmcub_firmware_header_v1_0(Structure): + pass + +struct_dmcub_firmware_header_v1_0._pack_ = 1 # source:False +struct_dmcub_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('inst_const_bytes', ctypes.c_uint32), + ('bss_data_bytes', ctypes.c_uint32), +] + +class struct_imu_firmware_header_v1_0(Structure): + pass + +struct_imu_firmware_header_v1_0._pack_ = 1 # source:False +struct_imu_firmware_header_v1_0._fields_ = [ + ('header', struct_common_firmware_header), + ('imu_iram_ucode_size_bytes', ctypes.c_uint32), + ('imu_iram_ucode_offset_bytes', ctypes.c_uint32), + ('imu_dram_ucode_size_bytes', ctypes.c_uint32), + ('imu_dram_ucode_offset_bytes', ctypes.c_uint32), +] + +class union_amdgpu_firmware_header(Union): + pass + +union_amdgpu_firmware_header._pack_ = 1 # source:False +union_amdgpu_firmware_header._fields_ = [ + ('common', struct_common_firmware_header), + ('mc', struct_mc_firmware_header_v1_0), + ('smc', struct_smc_firmware_header_v1_0), + ('smc_v2_0', struct_smc_firmware_header_v2_0), + ('psp', struct_psp_firmware_header_v1_0), + ('psp_v1_1', struct_psp_firmware_header_v1_1), + ('psp_v1_3', struct_psp_firmware_header_v1_3), + ('psp_v2_0', struct_psp_firmware_header_v2_0), + ('psp_v2_1', struct_psp_firmware_header_v2_0), + ('ta', struct_ta_firmware_header_v1_0), + ('ta_v2_0', struct_ta_firmware_header_v2_0), + ('gfx', struct_gfx_firmware_header_v1_0), + ('gfx_v2_0', struct_gfx_firmware_header_v2_0), + ('rlc', struct_rlc_firmware_header_v1_0), + ('rlc_v2_0', struct_rlc_firmware_header_v2_0), + ('rlc_v2_1', struct_rlc_firmware_header_v2_1), + ('rlc_v2_2', struct_rlc_firmware_header_v2_2), + ('rlc_v2_3', struct_rlc_firmware_header_v2_3), + ('rlc_v2_4', struct_rlc_firmware_header_v2_4), + ('sdma', struct_sdma_firmware_header_v1_0), + ('sdma_v1_1', struct_sdma_firmware_header_v1_1), + ('sdma_v2_0', struct_sdma_firmware_header_v2_0), + ('sdma_v3_0', struct_sdma_firmware_header_v3_0), + ('gpu_info', struct_gpu_info_firmware_header_v1_0), + ('dmcu', struct_dmcu_firmware_header_v1_0), + ('dmcub', struct_dmcub_firmware_header_v1_0), + ('imu', struct_imu_firmware_header_v1_0), + ('raw', ctypes.c_ubyte * 256), +] + + +# values for enumeration 'AMDGPU_UCODE_ID' +AMDGPU_UCODE_ID__enumvalues = { + 0: 'AMDGPU_UCODE_ID_CAP', + 1: 'AMDGPU_UCODE_ID_SDMA0', + 2: 'AMDGPU_UCODE_ID_SDMA1', + 3: 'AMDGPU_UCODE_ID_SDMA2', + 4: 'AMDGPU_UCODE_ID_SDMA3', + 5: 'AMDGPU_UCODE_ID_SDMA4', + 6: 'AMDGPU_UCODE_ID_SDMA5', + 7: 'AMDGPU_UCODE_ID_SDMA6', + 8: 'AMDGPU_UCODE_ID_SDMA7', + 9: 'AMDGPU_UCODE_ID_SDMA_UCODE_TH0', + 10: 'AMDGPU_UCODE_ID_SDMA_UCODE_TH1', + 11: 'AMDGPU_UCODE_ID_SDMA_RS64', + 12: 'AMDGPU_UCODE_ID_CP_CE', + 13: 'AMDGPU_UCODE_ID_CP_PFP', + 14: 'AMDGPU_UCODE_ID_CP_ME', + 15: 'AMDGPU_UCODE_ID_CP_RS64_PFP', + 16: 'AMDGPU_UCODE_ID_CP_RS64_ME', + 17: 'AMDGPU_UCODE_ID_CP_RS64_MEC', + 18: 'AMDGPU_UCODE_ID_CP_RS64_PFP_P0_STACK', + 19: 'AMDGPU_UCODE_ID_CP_RS64_PFP_P1_STACK', + 20: 'AMDGPU_UCODE_ID_CP_RS64_ME_P0_STACK', + 21: 'AMDGPU_UCODE_ID_CP_RS64_ME_P1_STACK', + 22: 'AMDGPU_UCODE_ID_CP_RS64_MEC_P0_STACK', + 23: 'AMDGPU_UCODE_ID_CP_RS64_MEC_P1_STACK', + 24: 'AMDGPU_UCODE_ID_CP_RS64_MEC_P2_STACK', + 25: 'AMDGPU_UCODE_ID_CP_RS64_MEC_P3_STACK', + 26: 'AMDGPU_UCODE_ID_CP_MEC1', + 27: 'AMDGPU_UCODE_ID_CP_MEC1_JT', + 28: 'AMDGPU_UCODE_ID_CP_MEC2', + 29: 'AMDGPU_UCODE_ID_CP_MEC2_JT', + 30: 'AMDGPU_UCODE_ID_CP_MES', + 31: 'AMDGPU_UCODE_ID_CP_MES_DATA', + 32: 'AMDGPU_UCODE_ID_CP_MES1', + 33: 'AMDGPU_UCODE_ID_CP_MES1_DATA', + 34: 'AMDGPU_UCODE_ID_IMU_I', + 35: 'AMDGPU_UCODE_ID_IMU_D', + 36: 'AMDGPU_UCODE_ID_GLOBAL_TAP_DELAYS', + 37: 'AMDGPU_UCODE_ID_SE0_TAP_DELAYS', + 38: 'AMDGPU_UCODE_ID_SE1_TAP_DELAYS', + 39: 'AMDGPU_UCODE_ID_SE2_TAP_DELAYS', + 40: 'AMDGPU_UCODE_ID_SE3_TAP_DELAYS', + 41: 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_CNTL', + 42: 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_GPM_MEM', + 43: 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_SRM_MEM', + 44: 'AMDGPU_UCODE_ID_RLC_IRAM', + 45: 'AMDGPU_UCODE_ID_RLC_DRAM', + 46: 'AMDGPU_UCODE_ID_RLC_P', + 47: 'AMDGPU_UCODE_ID_RLC_V', + 48: 'AMDGPU_UCODE_ID_RLC_G', + 49: 'AMDGPU_UCODE_ID_STORAGE', + 50: 'AMDGPU_UCODE_ID_SMC', + 51: 'AMDGPU_UCODE_ID_PPTABLE', + 52: 'AMDGPU_UCODE_ID_UVD', + 53: 'AMDGPU_UCODE_ID_UVD1', + 54: 'AMDGPU_UCODE_ID_VCE', + 55: 'AMDGPU_UCODE_ID_VCN', + 56: 'AMDGPU_UCODE_ID_VCN1', + 57: 'AMDGPU_UCODE_ID_DMCU_ERAM', + 58: 'AMDGPU_UCODE_ID_DMCU_INTV', + 59: 'AMDGPU_UCODE_ID_VCN0_RAM', + 60: 'AMDGPU_UCODE_ID_VCN1_RAM', + 61: 'AMDGPU_UCODE_ID_DMCUB', + 62: 'AMDGPU_UCODE_ID_VPE_CTX', + 63: 'AMDGPU_UCODE_ID_VPE_CTL', + 64: 'AMDGPU_UCODE_ID_VPE', + 65: 'AMDGPU_UCODE_ID_UMSCH_MM_UCODE', + 66: 'AMDGPU_UCODE_ID_UMSCH_MM_DATA', + 67: 'AMDGPU_UCODE_ID_UMSCH_MM_CMD_BUFFER', + 68: 'AMDGPU_UCODE_ID_P2S_TABLE', + 69: 'AMDGPU_UCODE_ID_JPEG_RAM', + 70: 'AMDGPU_UCODE_ID_ISP', + 71: 'AMDGPU_UCODE_ID_MAXIMUM', +} +AMDGPU_UCODE_ID_CAP = 0 +AMDGPU_UCODE_ID_SDMA0 = 1 +AMDGPU_UCODE_ID_SDMA1 = 2 +AMDGPU_UCODE_ID_SDMA2 = 3 +AMDGPU_UCODE_ID_SDMA3 = 4 +AMDGPU_UCODE_ID_SDMA4 = 5 +AMDGPU_UCODE_ID_SDMA5 = 6 +AMDGPU_UCODE_ID_SDMA6 = 7 +AMDGPU_UCODE_ID_SDMA7 = 8 +AMDGPU_UCODE_ID_SDMA_UCODE_TH0 = 9 +AMDGPU_UCODE_ID_SDMA_UCODE_TH1 = 10 +AMDGPU_UCODE_ID_SDMA_RS64 = 11 +AMDGPU_UCODE_ID_CP_CE = 12 +AMDGPU_UCODE_ID_CP_PFP = 13 +AMDGPU_UCODE_ID_CP_ME = 14 +AMDGPU_UCODE_ID_CP_RS64_PFP = 15 +AMDGPU_UCODE_ID_CP_RS64_ME = 16 +AMDGPU_UCODE_ID_CP_RS64_MEC = 17 +AMDGPU_UCODE_ID_CP_RS64_PFP_P0_STACK = 18 +AMDGPU_UCODE_ID_CP_RS64_PFP_P1_STACK = 19 +AMDGPU_UCODE_ID_CP_RS64_ME_P0_STACK = 20 +AMDGPU_UCODE_ID_CP_RS64_ME_P1_STACK = 21 +AMDGPU_UCODE_ID_CP_RS64_MEC_P0_STACK = 22 +AMDGPU_UCODE_ID_CP_RS64_MEC_P1_STACK = 23 +AMDGPU_UCODE_ID_CP_RS64_MEC_P2_STACK = 24 +AMDGPU_UCODE_ID_CP_RS64_MEC_P3_STACK = 25 +AMDGPU_UCODE_ID_CP_MEC1 = 26 +AMDGPU_UCODE_ID_CP_MEC1_JT = 27 +AMDGPU_UCODE_ID_CP_MEC2 = 28 +AMDGPU_UCODE_ID_CP_MEC2_JT = 29 +AMDGPU_UCODE_ID_CP_MES = 30 +AMDGPU_UCODE_ID_CP_MES_DATA = 31 +AMDGPU_UCODE_ID_CP_MES1 = 32 +AMDGPU_UCODE_ID_CP_MES1_DATA = 33 +AMDGPU_UCODE_ID_IMU_I = 34 +AMDGPU_UCODE_ID_IMU_D = 35 +AMDGPU_UCODE_ID_GLOBAL_TAP_DELAYS = 36 +AMDGPU_UCODE_ID_SE0_TAP_DELAYS = 37 +AMDGPU_UCODE_ID_SE1_TAP_DELAYS = 38 +AMDGPU_UCODE_ID_SE2_TAP_DELAYS = 39 +AMDGPU_UCODE_ID_SE3_TAP_DELAYS = 40 +AMDGPU_UCODE_ID_RLC_RESTORE_LIST_CNTL = 41 +AMDGPU_UCODE_ID_RLC_RESTORE_LIST_GPM_MEM = 42 +AMDGPU_UCODE_ID_RLC_RESTORE_LIST_SRM_MEM = 43 +AMDGPU_UCODE_ID_RLC_IRAM = 44 +AMDGPU_UCODE_ID_RLC_DRAM = 45 +AMDGPU_UCODE_ID_RLC_P = 46 +AMDGPU_UCODE_ID_RLC_V = 47 +AMDGPU_UCODE_ID_RLC_G = 48 +AMDGPU_UCODE_ID_STORAGE = 49 +AMDGPU_UCODE_ID_SMC = 50 +AMDGPU_UCODE_ID_PPTABLE = 51 +AMDGPU_UCODE_ID_UVD = 52 +AMDGPU_UCODE_ID_UVD1 = 53 +AMDGPU_UCODE_ID_VCE = 54 +AMDGPU_UCODE_ID_VCN = 55 +AMDGPU_UCODE_ID_VCN1 = 56 +AMDGPU_UCODE_ID_DMCU_ERAM = 57 +AMDGPU_UCODE_ID_DMCU_INTV = 58 +AMDGPU_UCODE_ID_VCN0_RAM = 59 +AMDGPU_UCODE_ID_VCN1_RAM = 60 +AMDGPU_UCODE_ID_DMCUB = 61 +AMDGPU_UCODE_ID_VPE_CTX = 62 +AMDGPU_UCODE_ID_VPE_CTL = 63 +AMDGPU_UCODE_ID_VPE = 64 +AMDGPU_UCODE_ID_UMSCH_MM_UCODE = 65 +AMDGPU_UCODE_ID_UMSCH_MM_DATA = 66 +AMDGPU_UCODE_ID_UMSCH_MM_CMD_BUFFER = 67 +AMDGPU_UCODE_ID_P2S_TABLE = 68 +AMDGPU_UCODE_ID_JPEG_RAM = 69 +AMDGPU_UCODE_ID_ISP = 70 +AMDGPU_UCODE_ID_MAXIMUM = 71 +AMDGPU_UCODE_ID = ctypes.c_uint32 # enum + +# values for enumeration 'AMDGPU_UCODE_STATUS' +AMDGPU_UCODE_STATUS__enumvalues = { + 0: 'AMDGPU_UCODE_STATUS_INVALID', + 1: 'AMDGPU_UCODE_STATUS_NOT_LOADED', + 2: 'AMDGPU_UCODE_STATUS_LOADED', +} +AMDGPU_UCODE_STATUS_INVALID = 0 +AMDGPU_UCODE_STATUS_NOT_LOADED = 1 +AMDGPU_UCODE_STATUS_LOADED = 2 +AMDGPU_UCODE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'amdgpu_firmware_load_type' +amdgpu_firmware_load_type__enumvalues = { + 0: 'AMDGPU_FW_LOAD_DIRECT', + 1: 'AMDGPU_FW_LOAD_PSP', + 2: 'AMDGPU_FW_LOAD_SMU', + 3: 'AMDGPU_FW_LOAD_RLC_BACKDOOR_AUTO', +} +AMDGPU_FW_LOAD_DIRECT = 0 +AMDGPU_FW_LOAD_PSP = 1 +AMDGPU_FW_LOAD_SMU = 2 +AMDGPU_FW_LOAD_RLC_BACKDOOR_AUTO = 3 +amdgpu_firmware_load_type = ctypes.c_uint32 # enum +class struct_amdgpu_firmware_info(Structure): + pass + +class struct_firmware(Structure): + pass + +struct_amdgpu_firmware_info._pack_ = 1 # source:False +struct_amdgpu_firmware_info._fields_ = [ + ('ucode_id', AMDGPU_UCODE_ID), + ('PADDING_0', ctypes.c_ubyte * 4), + ('fw', ctypes.POINTER(struct_firmware)), + ('mc_addr', ctypes.c_uint64), + ('kaddr', ctypes.POINTER(None)), + ('ucode_size', ctypes.c_uint32), + ('tmr_mc_addr_lo', ctypes.c_uint32), + ('tmr_mc_addr_hi', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +_PSP_TEE_GFX_IF_H_ = True # macro +PSP_GFX_CMD_BUF_VERSION = 0x00000001 # macro +GFX_CMD_STATUS_MASK = 0x0000FFFF # macro +GFX_CMD_ID_MASK = 0x000F0000 # macro +GFX_CMD_RESERVED_MASK = 0x7FF00000 # macro +GFX_CMD_RESPONSE_MASK = 0x80000000 # macro +C2PMSG_CMD_GFX_USB_PD_FW_VER = 0x2000000 # macro +GFX_FLAG_RESPONSE = 0x80000000 # macro +GFX_BUF_MAX_DESC = 64 # macro +FRAME_TYPE_DESTROY = 1 # macro +PSP_ERR_UNKNOWN_COMMAND = 0x00000100 # macro + +# values for enumeration 'psp_gfx_crtl_cmd_id' +psp_gfx_crtl_cmd_id__enumvalues = { + 65536: 'GFX_CTRL_CMD_ID_INIT_RBI_RING', + 131072: 'GFX_CTRL_CMD_ID_INIT_GPCOM_RING', + 196608: 'GFX_CTRL_CMD_ID_DESTROY_RINGS', + 262144: 'GFX_CTRL_CMD_ID_CAN_INIT_RINGS', + 327680: 'GFX_CTRL_CMD_ID_ENABLE_INT', + 393216: 'GFX_CTRL_CMD_ID_DISABLE_INT', + 458752: 'GFX_CTRL_CMD_ID_MODE1_RST', + 524288: 'GFX_CTRL_CMD_ID_GBR_IH_SET', + 589824: 'GFX_CTRL_CMD_ID_CONSUME_CMD', + 786432: 'GFX_CTRL_CMD_ID_DESTROY_GPCOM_RING', + 983040: 'GFX_CTRL_CMD_ID_MAX', +} +GFX_CTRL_CMD_ID_INIT_RBI_RING = 65536 +GFX_CTRL_CMD_ID_INIT_GPCOM_RING = 131072 +GFX_CTRL_CMD_ID_DESTROY_RINGS = 196608 +GFX_CTRL_CMD_ID_CAN_INIT_RINGS = 262144 +GFX_CTRL_CMD_ID_ENABLE_INT = 327680 +GFX_CTRL_CMD_ID_DISABLE_INT = 393216 +GFX_CTRL_CMD_ID_MODE1_RST = 458752 +GFX_CTRL_CMD_ID_GBR_IH_SET = 524288 +GFX_CTRL_CMD_ID_CONSUME_CMD = 589824 +GFX_CTRL_CMD_ID_DESTROY_GPCOM_RING = 786432 +GFX_CTRL_CMD_ID_MAX = 983040 +psp_gfx_crtl_cmd_id = ctypes.c_uint32 # enum +class struct_psp_gfx_ctrl(Structure): + pass + +struct_psp_gfx_ctrl._pack_ = 1 # source:False +struct_psp_gfx_ctrl._fields_ = [ + ('cmd_resp', ctypes.c_uint32), + ('rbi_wptr', ctypes.c_uint32), + ('rbi_rptr', ctypes.c_uint32), + ('gpcom_wptr', ctypes.c_uint32), + ('gpcom_rptr', ctypes.c_uint32), + ('ring_addr_lo', ctypes.c_uint32), + ('ring_addr_hi', ctypes.c_uint32), + ('ring_buf_size', ctypes.c_uint32), +] + + +# values for enumeration 'psp_gfx_cmd_id' +psp_gfx_cmd_id__enumvalues = { + 1: 'GFX_CMD_ID_LOAD_TA', + 2: 'GFX_CMD_ID_UNLOAD_TA', + 3: 'GFX_CMD_ID_INVOKE_CMD', + 4: 'GFX_CMD_ID_LOAD_ASD', + 5: 'GFX_CMD_ID_SETUP_TMR', + 6: 'GFX_CMD_ID_LOAD_IP_FW', + 7: 'GFX_CMD_ID_DESTROY_TMR', + 8: 'GFX_CMD_ID_SAVE_RESTORE', + 9: 'GFX_CMD_ID_SETUP_VMR', + 10: 'GFX_CMD_ID_DESTROY_VMR', + 11: 'GFX_CMD_ID_PROG_REG', + 15: 'GFX_CMD_ID_GET_FW_ATTESTATION', + 32: 'GFX_CMD_ID_LOAD_TOC', + 33: 'GFX_CMD_ID_AUTOLOAD_RLC', + 34: 'GFX_CMD_ID_BOOT_CFG', + 39: 'GFX_CMD_ID_SRIOV_SPATIAL_PART', +} +GFX_CMD_ID_LOAD_TA = 1 +GFX_CMD_ID_UNLOAD_TA = 2 +GFX_CMD_ID_INVOKE_CMD = 3 +GFX_CMD_ID_LOAD_ASD = 4 +GFX_CMD_ID_SETUP_TMR = 5 +GFX_CMD_ID_LOAD_IP_FW = 6 +GFX_CMD_ID_DESTROY_TMR = 7 +GFX_CMD_ID_SAVE_RESTORE = 8 +GFX_CMD_ID_SETUP_VMR = 9 +GFX_CMD_ID_DESTROY_VMR = 10 +GFX_CMD_ID_PROG_REG = 11 +GFX_CMD_ID_GET_FW_ATTESTATION = 15 +GFX_CMD_ID_LOAD_TOC = 32 +GFX_CMD_ID_AUTOLOAD_RLC = 33 +GFX_CMD_ID_BOOT_CFG = 34 +GFX_CMD_ID_SRIOV_SPATIAL_PART = 39 +psp_gfx_cmd_id = ctypes.c_uint32 # enum + +# values for enumeration 'psp_gfx_boot_config_cmd' +psp_gfx_boot_config_cmd__enumvalues = { + 1: 'BOOTCFG_CMD_SET', + 2: 'BOOTCFG_CMD_GET', + 3: 'BOOTCFG_CMD_INVALIDATE', +} +BOOTCFG_CMD_SET = 1 +BOOTCFG_CMD_GET = 2 +BOOTCFG_CMD_INVALIDATE = 3 +psp_gfx_boot_config_cmd = ctypes.c_uint32 # enum + +# values for enumeration 'psp_gfx_boot_config' +psp_gfx_boot_config__enumvalues = { + 1: 'BOOT_CONFIG_GECC', +} +BOOT_CONFIG_GECC = 1 +psp_gfx_boot_config = ctypes.c_uint32 # enum +class struct_psp_gfx_cmd_load_ta(Structure): + pass + +struct_psp_gfx_cmd_load_ta._pack_ = 1 # source:False +struct_psp_gfx_cmd_load_ta._fields_ = [ + ('app_phy_addr_lo', ctypes.c_uint32), + ('app_phy_addr_hi', ctypes.c_uint32), + ('app_len', ctypes.c_uint32), + ('cmd_buf_phy_addr_lo', ctypes.c_uint32), + ('cmd_buf_phy_addr_hi', ctypes.c_uint32), + ('cmd_buf_len', ctypes.c_uint32), +] + +class struct_psp_gfx_cmd_unload_ta(Structure): + pass + +struct_psp_gfx_cmd_unload_ta._pack_ = 1 # source:False +struct_psp_gfx_cmd_unload_ta._fields_ = [ + ('session_id', ctypes.c_uint32), +] + +class struct_psp_gfx_buf_desc(Structure): + pass + +struct_psp_gfx_buf_desc._pack_ = 1 # source:False +struct_psp_gfx_buf_desc._fields_ = [ + ('buf_phy_addr_lo', ctypes.c_uint32), + ('buf_phy_addr_hi', ctypes.c_uint32), + ('buf_size', ctypes.c_uint32), +] + +class struct_psp_gfx_buf_list(Structure): + pass + +struct_psp_gfx_buf_list._pack_ = 1 # source:False +struct_psp_gfx_buf_list._fields_ = [ + ('num_desc', ctypes.c_uint32), + ('total_size', ctypes.c_uint32), + ('buf_desc', struct_psp_gfx_buf_desc * 64), +] + +class struct_psp_gfx_cmd_invoke_cmd(Structure): + pass + +struct_psp_gfx_cmd_invoke_cmd._pack_ = 1 # source:False +struct_psp_gfx_cmd_invoke_cmd._fields_ = [ + ('session_id', ctypes.c_uint32), + ('ta_cmd_id', ctypes.c_uint32), + ('buf', struct_psp_gfx_buf_list), +] + +class struct_psp_gfx_cmd_setup_tmr(Structure): + pass + +class union_psp_gfx_cmd_setup_tmr_0(Union): + pass + +class struct_psp_gfx_cmd_setup_tmr_0_bitfield(Structure): + pass + +struct_psp_gfx_cmd_setup_tmr_0_bitfield._pack_ = 1 # source:False +struct_psp_gfx_cmd_setup_tmr_0_bitfield._fields_ = [ + ('sriov_enabled', ctypes.c_uint32, 1), + ('virt_phy_addr', ctypes.c_uint32, 1), + ('reserved', ctypes.c_uint32, 30), +] + +union_psp_gfx_cmd_setup_tmr_0._pack_ = 1 # source:False +union_psp_gfx_cmd_setup_tmr_0._fields_ = [ + ('bitfield', struct_psp_gfx_cmd_setup_tmr_0_bitfield), + ('tmr_flags', ctypes.c_uint32), +] + +struct_psp_gfx_cmd_setup_tmr._pack_ = 1 # source:False +struct_psp_gfx_cmd_setup_tmr._anonymous_ = ('_0',) +struct_psp_gfx_cmd_setup_tmr._fields_ = [ + ('buf_phy_addr_lo', ctypes.c_uint32), + ('buf_phy_addr_hi', ctypes.c_uint32), + ('buf_size', ctypes.c_uint32), + ('_0', union_psp_gfx_cmd_setup_tmr_0), + ('system_phy_addr_lo', ctypes.c_uint32), + ('system_phy_addr_hi', ctypes.c_uint32), +] + + +# values for enumeration 'psp_gfx_fw_type' +psp_gfx_fw_type__enumvalues = { + 0: 'GFX_FW_TYPE_NONE', + 1: 'GFX_FW_TYPE_CP_ME', + 2: 'GFX_FW_TYPE_CP_PFP', + 3: 'GFX_FW_TYPE_CP_CE', + 4: 'GFX_FW_TYPE_CP_MEC', + 5: 'GFX_FW_TYPE_CP_MEC_ME1', + 6: 'GFX_FW_TYPE_CP_MEC_ME2', + 7: 'GFX_FW_TYPE_RLC_V', + 8: 'GFX_FW_TYPE_RLC_G', + 9: 'GFX_FW_TYPE_SDMA0', + 10: 'GFX_FW_TYPE_SDMA1', + 11: 'GFX_FW_TYPE_DMCU_ERAM', + 12: 'GFX_FW_TYPE_DMCU_ISR', + 13: 'GFX_FW_TYPE_VCN', + 14: 'GFX_FW_TYPE_UVD', + 15: 'GFX_FW_TYPE_VCE', + 16: 'GFX_FW_TYPE_ISP', + 17: 'GFX_FW_TYPE_ACP', + 18: 'GFX_FW_TYPE_SMU', + 19: 'GFX_FW_TYPE_MMSCH', + 20: 'GFX_FW_TYPE_RLC_RESTORE_LIST_GPM_MEM', + 21: 'GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_MEM', + 22: 'GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_CNTL', + 23: 'GFX_FW_TYPE_UVD1', + 24: 'GFX_FW_TYPE_TOC', + 25: 'GFX_FW_TYPE_RLC_P', + 26: 'GFX_FW_TYPE_RLC_IRAM', + 27: 'GFX_FW_TYPE_GLOBAL_TAP_DELAYS', + 28: 'GFX_FW_TYPE_SE0_TAP_DELAYS', + 29: 'GFX_FW_TYPE_SE1_TAP_DELAYS', + 30: 'GFX_FW_TYPE_GLOBAL_SE0_SE1_SKEW_DELAYS', + 31: 'GFX_FW_TYPE_SDMA0_JT', + 32: 'GFX_FW_TYPE_SDMA1_JT', + 33: 'GFX_FW_TYPE_CP_MES', + 34: 'GFX_FW_TYPE_MES_STACK', + 35: 'GFX_FW_TYPE_RLC_SRM_DRAM_SR', + 36: 'GFX_FW_TYPE_RLCG_SCRATCH_SR', + 37: 'GFX_FW_TYPE_RLCP_SCRATCH_SR', + 38: 'GFX_FW_TYPE_RLCV_SCRATCH_SR', + 39: 'GFX_FW_TYPE_RLX6_DRAM_SR', + 40: 'GFX_FW_TYPE_SDMA0_PG_CONTEXT', + 41: 'GFX_FW_TYPE_SDMA1_PG_CONTEXT', + 42: 'GFX_FW_TYPE_GLOBAL_MUX_SELECT_RAM', + 43: 'GFX_FW_TYPE_SE0_MUX_SELECT_RAM', + 44: 'GFX_FW_TYPE_SE1_MUX_SELECT_RAM', + 45: 'GFX_FW_TYPE_ACCUM_CTRL_RAM', + 46: 'GFX_FW_TYPE_RLCP_CAM', + 47: 'GFX_FW_TYPE_RLC_SPP_CAM_EXT', + 48: 'GFX_FW_TYPE_RLC_DRAM_BOOT', + 49: 'GFX_FW_TYPE_VCN0_RAM', + 50: 'GFX_FW_TYPE_VCN1_RAM', + 51: 'GFX_FW_TYPE_DMUB', + 52: 'GFX_FW_TYPE_SDMA2', + 53: 'GFX_FW_TYPE_SDMA3', + 54: 'GFX_FW_TYPE_SDMA4', + 55: 'GFX_FW_TYPE_SDMA5', + 56: 'GFX_FW_TYPE_SDMA6', + 57: 'GFX_FW_TYPE_SDMA7', + 58: 'GFX_FW_TYPE_VCN1', + 62: 'GFX_FW_TYPE_CAP', + 65: 'GFX_FW_TYPE_SE2_TAP_DELAYS', + 66: 'GFX_FW_TYPE_SE3_TAP_DELAYS', + 67: 'GFX_FW_TYPE_REG_LIST', + 68: 'GFX_FW_TYPE_IMU_I', + 69: 'GFX_FW_TYPE_IMU_D', + 70: 'GFX_FW_TYPE_LSDMA', + 71: 'GFX_FW_TYPE_SDMA_UCODE_TH0', + 72: 'GFX_FW_TYPE_SDMA_UCODE_TH1', + 73: 'GFX_FW_TYPE_PPTABLE', + 74: 'GFX_FW_TYPE_DISCRETE_USB4', + 75: 'GFX_FW_TYPE_TA', + 76: 'GFX_FW_TYPE_RS64_MES', + 77: 'GFX_FW_TYPE_RS64_MES_STACK', + 78: 'GFX_FW_TYPE_RS64_KIQ', + 79: 'GFX_FW_TYPE_RS64_KIQ_STACK', + 80: 'GFX_FW_TYPE_ISP_DATA', + 81: 'GFX_FW_TYPE_CP_MES_KIQ', + 82: 'GFX_FW_TYPE_MES_KIQ_STACK', + 83: 'GFX_FW_TYPE_UMSCH_DATA', + 84: 'GFX_FW_TYPE_UMSCH_UCODE', + 85: 'GFX_FW_TYPE_UMSCH_CMD_BUFFER', + 86: 'GFX_FW_TYPE_USB_DP_COMBO_PHY', + 87: 'GFX_FW_TYPE_RS64_PFP', + 88: 'GFX_FW_TYPE_RS64_ME', + 89: 'GFX_FW_TYPE_RS64_MEC', + 90: 'GFX_FW_TYPE_RS64_PFP_P0_STACK', + 91: 'GFX_FW_TYPE_RS64_PFP_P1_STACK', + 92: 'GFX_FW_TYPE_RS64_ME_P0_STACK', + 93: 'GFX_FW_TYPE_RS64_ME_P1_STACK', + 94: 'GFX_FW_TYPE_RS64_MEC_P0_STACK', + 95: 'GFX_FW_TYPE_RS64_MEC_P1_STACK', + 96: 'GFX_FW_TYPE_RS64_MEC_P2_STACK', + 97: 'GFX_FW_TYPE_RS64_MEC_P3_STACK', + 100: 'GFX_FW_TYPE_VPEC_FW1', + 101: 'GFX_FW_TYPE_VPEC_FW2', + 102: 'GFX_FW_TYPE_VPE', + 128: 'GFX_FW_TYPE_JPEG_RAM', + 129: 'GFX_FW_TYPE_P2S_TABLE', + 130: 'GFX_FW_TYPE_MAX', +} +GFX_FW_TYPE_NONE = 0 +GFX_FW_TYPE_CP_ME = 1 +GFX_FW_TYPE_CP_PFP = 2 +GFX_FW_TYPE_CP_CE = 3 +GFX_FW_TYPE_CP_MEC = 4 +GFX_FW_TYPE_CP_MEC_ME1 = 5 +GFX_FW_TYPE_CP_MEC_ME2 = 6 +GFX_FW_TYPE_RLC_V = 7 +GFX_FW_TYPE_RLC_G = 8 +GFX_FW_TYPE_SDMA0 = 9 +GFX_FW_TYPE_SDMA1 = 10 +GFX_FW_TYPE_DMCU_ERAM = 11 +GFX_FW_TYPE_DMCU_ISR = 12 +GFX_FW_TYPE_VCN = 13 +GFX_FW_TYPE_UVD = 14 +GFX_FW_TYPE_VCE = 15 +GFX_FW_TYPE_ISP = 16 +GFX_FW_TYPE_ACP = 17 +GFX_FW_TYPE_SMU = 18 +GFX_FW_TYPE_MMSCH = 19 +GFX_FW_TYPE_RLC_RESTORE_LIST_GPM_MEM = 20 +GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_MEM = 21 +GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_CNTL = 22 +GFX_FW_TYPE_UVD1 = 23 +GFX_FW_TYPE_TOC = 24 +GFX_FW_TYPE_RLC_P = 25 +GFX_FW_TYPE_RLC_IRAM = 26 +GFX_FW_TYPE_GLOBAL_TAP_DELAYS = 27 +GFX_FW_TYPE_SE0_TAP_DELAYS = 28 +GFX_FW_TYPE_SE1_TAP_DELAYS = 29 +GFX_FW_TYPE_GLOBAL_SE0_SE1_SKEW_DELAYS = 30 +GFX_FW_TYPE_SDMA0_JT = 31 +GFX_FW_TYPE_SDMA1_JT = 32 +GFX_FW_TYPE_CP_MES = 33 +GFX_FW_TYPE_MES_STACK = 34 +GFX_FW_TYPE_RLC_SRM_DRAM_SR = 35 +GFX_FW_TYPE_RLCG_SCRATCH_SR = 36 +GFX_FW_TYPE_RLCP_SCRATCH_SR = 37 +GFX_FW_TYPE_RLCV_SCRATCH_SR = 38 +GFX_FW_TYPE_RLX6_DRAM_SR = 39 +GFX_FW_TYPE_SDMA0_PG_CONTEXT = 40 +GFX_FW_TYPE_SDMA1_PG_CONTEXT = 41 +GFX_FW_TYPE_GLOBAL_MUX_SELECT_RAM = 42 +GFX_FW_TYPE_SE0_MUX_SELECT_RAM = 43 +GFX_FW_TYPE_SE1_MUX_SELECT_RAM = 44 +GFX_FW_TYPE_ACCUM_CTRL_RAM = 45 +GFX_FW_TYPE_RLCP_CAM = 46 +GFX_FW_TYPE_RLC_SPP_CAM_EXT = 47 +GFX_FW_TYPE_RLC_DRAM_BOOT = 48 +GFX_FW_TYPE_VCN0_RAM = 49 +GFX_FW_TYPE_VCN1_RAM = 50 +GFX_FW_TYPE_DMUB = 51 +GFX_FW_TYPE_SDMA2 = 52 +GFX_FW_TYPE_SDMA3 = 53 +GFX_FW_TYPE_SDMA4 = 54 +GFX_FW_TYPE_SDMA5 = 55 +GFX_FW_TYPE_SDMA6 = 56 +GFX_FW_TYPE_SDMA7 = 57 +GFX_FW_TYPE_VCN1 = 58 +GFX_FW_TYPE_CAP = 62 +GFX_FW_TYPE_SE2_TAP_DELAYS = 65 +GFX_FW_TYPE_SE3_TAP_DELAYS = 66 +GFX_FW_TYPE_REG_LIST = 67 +GFX_FW_TYPE_IMU_I = 68 +GFX_FW_TYPE_IMU_D = 69 +GFX_FW_TYPE_LSDMA = 70 +GFX_FW_TYPE_SDMA_UCODE_TH0 = 71 +GFX_FW_TYPE_SDMA_UCODE_TH1 = 72 +GFX_FW_TYPE_PPTABLE = 73 +GFX_FW_TYPE_DISCRETE_USB4 = 74 +GFX_FW_TYPE_TA = 75 +GFX_FW_TYPE_RS64_MES = 76 +GFX_FW_TYPE_RS64_MES_STACK = 77 +GFX_FW_TYPE_RS64_KIQ = 78 +GFX_FW_TYPE_RS64_KIQ_STACK = 79 +GFX_FW_TYPE_ISP_DATA = 80 +GFX_FW_TYPE_CP_MES_KIQ = 81 +GFX_FW_TYPE_MES_KIQ_STACK = 82 +GFX_FW_TYPE_UMSCH_DATA = 83 +GFX_FW_TYPE_UMSCH_UCODE = 84 +GFX_FW_TYPE_UMSCH_CMD_BUFFER = 85 +GFX_FW_TYPE_USB_DP_COMBO_PHY = 86 +GFX_FW_TYPE_RS64_PFP = 87 +GFX_FW_TYPE_RS64_ME = 88 +GFX_FW_TYPE_RS64_MEC = 89 +GFX_FW_TYPE_RS64_PFP_P0_STACK = 90 +GFX_FW_TYPE_RS64_PFP_P1_STACK = 91 +GFX_FW_TYPE_RS64_ME_P0_STACK = 92 +GFX_FW_TYPE_RS64_ME_P1_STACK = 93 +GFX_FW_TYPE_RS64_MEC_P0_STACK = 94 +GFX_FW_TYPE_RS64_MEC_P1_STACK = 95 +GFX_FW_TYPE_RS64_MEC_P2_STACK = 96 +GFX_FW_TYPE_RS64_MEC_P3_STACK = 97 +GFX_FW_TYPE_VPEC_FW1 = 100 +GFX_FW_TYPE_VPEC_FW2 = 101 +GFX_FW_TYPE_VPE = 102 +GFX_FW_TYPE_JPEG_RAM = 128 +GFX_FW_TYPE_P2S_TABLE = 129 +GFX_FW_TYPE_MAX = 130 +psp_gfx_fw_type = ctypes.c_uint32 # enum +class struct_psp_gfx_cmd_load_ip_fw(Structure): + pass + +struct_psp_gfx_cmd_load_ip_fw._pack_ = 1 # source:False +struct_psp_gfx_cmd_load_ip_fw._fields_ = [ + ('fw_phy_addr_lo', ctypes.c_uint32), + ('fw_phy_addr_hi', ctypes.c_uint32), + ('fw_size', ctypes.c_uint32), + ('fw_type', psp_gfx_fw_type), +] + +class struct_psp_gfx_cmd_save_restore_ip_fw(Structure): + pass + +struct_psp_gfx_cmd_save_restore_ip_fw._pack_ = 1 # source:False +struct_psp_gfx_cmd_save_restore_ip_fw._fields_ = [ + ('save_fw', ctypes.c_uint32), + ('save_restore_addr_lo', ctypes.c_uint32), + ('save_restore_addr_hi', ctypes.c_uint32), + ('buf_size', ctypes.c_uint32), + ('fw_type', psp_gfx_fw_type), +] + +class struct_psp_gfx_cmd_reg_prog(Structure): + pass + +struct_psp_gfx_cmd_reg_prog._pack_ = 1 # source:False +struct_psp_gfx_cmd_reg_prog._fields_ = [ + ('reg_value', ctypes.c_uint32), + ('reg_id', ctypes.c_uint32), +] + +class struct_psp_gfx_cmd_load_toc(Structure): + pass + +struct_psp_gfx_cmd_load_toc._pack_ = 1 # source:False +struct_psp_gfx_cmd_load_toc._fields_ = [ + ('toc_phy_addr_lo', ctypes.c_uint32), + ('toc_phy_addr_hi', ctypes.c_uint32), + ('toc_size', ctypes.c_uint32), +] + +class struct_psp_gfx_cmd_boot_cfg(Structure): + pass + +struct_psp_gfx_cmd_boot_cfg._pack_ = 1 # source:False +struct_psp_gfx_cmd_boot_cfg._fields_ = [ + ('timestamp', ctypes.c_uint32), + ('sub_cmd', psp_gfx_boot_config_cmd), + ('boot_config', ctypes.c_uint32), + ('boot_config_valid', ctypes.c_uint32), +] + +class struct_psp_gfx_cmd_sriov_spatial_part(Structure): + pass + +struct_psp_gfx_cmd_sriov_spatial_part._pack_ = 1 # source:False +struct_psp_gfx_cmd_sriov_spatial_part._fields_ = [ + ('mode', ctypes.c_uint32), + ('override_ips', ctypes.c_uint32), + ('override_xcds_avail', ctypes.c_uint32), + ('override_this_aid', ctypes.c_uint32), +] + +class union_psp_gfx_commands(Union): + pass + +union_psp_gfx_commands._pack_ = 1 # source:False +union_psp_gfx_commands._fields_ = [ + ('cmd_load_ta', struct_psp_gfx_cmd_load_ta), + ('cmd_unload_ta', struct_psp_gfx_cmd_unload_ta), + ('cmd_invoke_cmd', struct_psp_gfx_cmd_invoke_cmd), + ('cmd_setup_tmr', struct_psp_gfx_cmd_setup_tmr), + ('cmd_load_ip_fw', struct_psp_gfx_cmd_load_ip_fw), + ('cmd_save_restore_ip_fw', struct_psp_gfx_cmd_save_restore_ip_fw), + ('cmd_setup_reg_prog', struct_psp_gfx_cmd_reg_prog), + ('cmd_setup_vmr', struct_psp_gfx_cmd_setup_tmr), + ('cmd_load_toc', struct_psp_gfx_cmd_load_toc), + ('boot_cfg', struct_psp_gfx_cmd_boot_cfg), + ('cmd_spatial_part', struct_psp_gfx_cmd_sriov_spatial_part), + ('PADDING_0', ctypes.c_ubyte * 768), +] + +class struct_psp_gfx_uresp_reserved(Structure): + pass + +struct_psp_gfx_uresp_reserved._pack_ = 1 # source:False +struct_psp_gfx_uresp_reserved._fields_ = [ + ('reserved', ctypes.c_uint32 * 8), +] + +class struct_psp_gfx_uresp_fwar_db_info(Structure): + pass + +struct_psp_gfx_uresp_fwar_db_info._pack_ = 1 # source:False +struct_psp_gfx_uresp_fwar_db_info._fields_ = [ + ('fwar_db_addr_lo', ctypes.c_uint32), + ('fwar_db_addr_hi', ctypes.c_uint32), +] + +class struct_psp_gfx_uresp_bootcfg(Structure): + pass + +struct_psp_gfx_uresp_bootcfg._pack_ = 1 # source:False +struct_psp_gfx_uresp_bootcfg._fields_ = [ + ('boot_cfg', ctypes.c_uint32), +] + +class union_psp_gfx_uresp(Union): + pass + +union_psp_gfx_uresp._pack_ = 1 # source:False +union_psp_gfx_uresp._fields_ = [ + ('reserved', struct_psp_gfx_uresp_reserved), + ('boot_cfg', struct_psp_gfx_uresp_bootcfg), + ('fwar_db_info', struct_psp_gfx_uresp_fwar_db_info), + ('PADDING_0', ctypes.c_ubyte * 24), +] + +class struct_psp_gfx_resp(Structure): + pass + +struct_psp_gfx_resp._pack_ = 1 # source:False +struct_psp_gfx_resp._fields_ = [ + ('status', ctypes.c_uint32), + ('session_id', ctypes.c_uint32), + ('fw_addr_lo', ctypes.c_uint32), + ('fw_addr_hi', ctypes.c_uint32), + ('tmr_size', ctypes.c_uint32), + ('reserved', ctypes.c_uint32 * 11), + ('uresp', union_psp_gfx_uresp), +] + +class struct_psp_gfx_cmd_resp(Structure): + pass + +struct_psp_gfx_cmd_resp._pack_ = 1 # source:False +struct_psp_gfx_cmd_resp._fields_ = [ + ('buf_size', ctypes.c_uint32), + ('buf_version', ctypes.c_uint32), + ('cmd_id', ctypes.c_uint32), + ('resp_buf_addr_lo', ctypes.c_uint32), + ('resp_buf_addr_hi', ctypes.c_uint32), + ('resp_offset', ctypes.c_uint32), + ('resp_buf_size', ctypes.c_uint32), + ('cmd', union_psp_gfx_commands), + ('reserved_1', ctypes.c_ubyte * 52), + ('resp', struct_psp_gfx_resp), + ('reserved_2', ctypes.c_ubyte * 64), +] + +class struct_psp_gfx_rb_frame(Structure): + pass + +struct_psp_gfx_rb_frame._pack_ = 1 # source:False +struct_psp_gfx_rb_frame._fields_ = [ + ('cmd_buf_addr_lo', ctypes.c_uint32), + ('cmd_buf_addr_hi', ctypes.c_uint32), + ('cmd_buf_size', ctypes.c_uint32), + ('fence_addr_lo', ctypes.c_uint32), + ('fence_addr_hi', ctypes.c_uint32), + ('fence_value', ctypes.c_uint32), + ('sid_lo', ctypes.c_uint32), + ('sid_hi', ctypes.c_uint32), + ('vmid', ctypes.c_ubyte), + ('frame_type', ctypes.c_ubyte), + ('reserved1', ctypes.c_ubyte * 2), + ('reserved2', ctypes.c_uint32 * 7), +] + + +# values for enumeration 'tee_error_code' +tee_error_code__enumvalues = { + 0: 'TEE_SUCCESS', + 4294901770: 'TEE_ERROR_NOT_SUPPORTED', +} +TEE_SUCCESS = 0 +TEE_ERROR_NOT_SUPPORTED = 4294901770 +tee_error_code = ctypes.c_uint32 # enum +__AMDGPU_PSP_H__ = True # macro +PSP_FENCE_BUFFER_SIZE = 0x1000 # macro +PSP_CMD_BUFFER_SIZE = 0x1000 # macro +PSP_1_MEG = 0x100000 # macro +# def PSP_TMR_SIZE(adev): # macro +# return ((adev)->asic_type==CHIP_ALDEBARAN?0x800000:0x400000) +PSP_TMR_ALIGNMENT = 0x100000 # macro +PSP_FW_NAME_LEN = 0x24 # macro +AMDGPU_XGMI_MAX_CONNECTED_NODES = 64 # macro +MEM_TRAIN_SYSTEM_SIGNATURE = 0x54534942 # macro +GDDR6_MEM_TRAINING_DATA_SIZE_IN_BYTES = 0x1000 # macro +GDDR6_MEM_TRAINING_OFFSET = 0x8000 # macro +BIST_MEM_TRAINING_ENCROACHED_SIZE = 0x2000000 # macro +PSP_RUNTIME_DB_SIZE_IN_BYTES = 0x10000 # macro +PSP_RUNTIME_DB_OFFSET = 0x100000 # macro +PSP_RUNTIME_DB_COOKIE_ID = 0x0ed5 # macro +PSP_RUNTIME_DB_VER_1 = 0x0100 # macro +PSP_RUNTIME_DB_DIAG_ENTRY_MAX_COUNT = 0x40 # macro + +# values for enumeration 'psp_shared_mem_size' +psp_shared_mem_size__enumvalues = { + 0: 'PSP_ASD_SHARED_MEM_SIZE', + 16384: 'PSP_XGMI_SHARED_MEM_SIZE', + 16384: 'PSP_RAS_SHARED_MEM_SIZE', + 16384: 'PSP_HDCP_SHARED_MEM_SIZE', + 16384: 'PSP_DTM_SHARED_MEM_SIZE', + 16384: 'PSP_RAP_SHARED_MEM_SIZE', + 16384: 'PSP_SECUREDISPLAY_SHARED_MEM_SIZE', +} +PSP_ASD_SHARED_MEM_SIZE = 0 +PSP_XGMI_SHARED_MEM_SIZE = 16384 +PSP_RAS_SHARED_MEM_SIZE = 16384 +PSP_HDCP_SHARED_MEM_SIZE = 16384 +PSP_DTM_SHARED_MEM_SIZE = 16384 +PSP_RAP_SHARED_MEM_SIZE = 16384 +PSP_SECUREDISPLAY_SHARED_MEM_SIZE = 16384 +psp_shared_mem_size = ctypes.c_uint32 # enum + +# values for enumeration 'ta_type_id' +ta_type_id__enumvalues = { + 1: 'TA_TYPE_XGMI', + 2: 'TA_TYPE_RAS', + 3: 'TA_TYPE_HDCP', + 4: 'TA_TYPE_DTM', + 5: 'TA_TYPE_RAP', + 6: 'TA_TYPE_SECUREDISPLAY', + 7: 'TA_TYPE_MAX_INDEX', +} +TA_TYPE_XGMI = 1 +TA_TYPE_RAS = 2 +TA_TYPE_HDCP = 3 +TA_TYPE_DTM = 4 +TA_TYPE_RAP = 5 +TA_TYPE_SECUREDISPLAY = 6 +TA_TYPE_MAX_INDEX = 7 +ta_type_id = ctypes.c_uint32 # enum +class struct_psp_context(Structure): + pass + +class struct_psp_xgmi_node_info(Structure): + pass + +class struct_psp_xgmi_topology_info(Structure): + pass + +class struct_psp_bin_desc(Structure): + pass + + +# values for enumeration 'psp_bootloader_cmd' +psp_bootloader_cmd__enumvalues = { + 65536: 'PSP_BL__LOAD_SYSDRV', + 131072: 'PSP_BL__LOAD_SOSDRV', + 524288: 'PSP_BL__LOAD_KEY_DATABASE', + 720896: 'PSP_BL__LOAD_SOCDRV', + 786432: 'PSP_BL__LOAD_DBGDRV', + 786432: 'PSP_BL__LOAD_HADDRV', + 851968: 'PSP_BL__LOAD_INTFDRV', + 917504: 'PSP_BL__LOAD_RASDRV', + 983040: 'PSP_BL__LOAD_IPKEYMGRDRV', + 1048576: 'PSP_BL__DRAM_LONG_TRAIN', + 2097152: 'PSP_BL__DRAM_SHORT_TRAIN', + 268435456: 'PSP_BL__LOAD_TOS_SPL_TABLE', +} +PSP_BL__LOAD_SYSDRV = 65536 +PSP_BL__LOAD_SOSDRV = 131072 +PSP_BL__LOAD_KEY_DATABASE = 524288 +PSP_BL__LOAD_SOCDRV = 720896 +PSP_BL__LOAD_DBGDRV = 786432 +PSP_BL__LOAD_HADDRV = 786432 +PSP_BL__LOAD_INTFDRV = 851968 +PSP_BL__LOAD_RASDRV = 917504 +PSP_BL__LOAD_IPKEYMGRDRV = 983040 +PSP_BL__DRAM_LONG_TRAIN = 1048576 +PSP_BL__DRAM_SHORT_TRAIN = 2097152 +PSP_BL__LOAD_TOS_SPL_TABLE = 268435456 +psp_bootloader_cmd = ctypes.c_uint32 # enum + +# values for enumeration 'psp_ring_type' +psp_ring_type__enumvalues = { + 0: 'PSP_RING_TYPE__INVALID', + 1: 'PSP_RING_TYPE__UM', + 2: 'PSP_RING_TYPE__KM', +} +PSP_RING_TYPE__INVALID = 0 +PSP_RING_TYPE__UM = 1 +PSP_RING_TYPE__KM = 2 +psp_ring_type = ctypes.c_uint32 # enum + +# values for enumeration 'psp_reg_prog_id' +psp_reg_prog_id__enumvalues = { + 0: 'PSP_REG_IH_RB_CNTL', + 1: 'PSP_REG_IH_RB_CNTL_RING1', + 2: 'PSP_REG_IH_RB_CNTL_RING2', + 3: 'PSP_REG_LAST', +} +PSP_REG_IH_RB_CNTL = 0 +PSP_REG_IH_RB_CNTL_RING1 = 1 +PSP_REG_IH_RB_CNTL_RING2 = 2 +PSP_REG_LAST = 3 +psp_reg_prog_id = ctypes.c_uint32 # enum + +# values for enumeration 'psp_memory_training_init_flag' +psp_memory_training_init_flag__enumvalues = { + 0: 'PSP_MEM_TRAIN_NOT_SUPPORT', + 1: 'PSP_MEM_TRAIN_SUPPORT', + 2: 'PSP_MEM_TRAIN_INIT_FAILED', + 4: 'PSP_MEM_TRAIN_RESERVE_SUCCESS', + 8: 'PSP_MEM_TRAIN_INIT_SUCCESS', +} +PSP_MEM_TRAIN_NOT_SUPPORT = 0 +PSP_MEM_TRAIN_SUPPORT = 1 +PSP_MEM_TRAIN_INIT_FAILED = 2 +PSP_MEM_TRAIN_RESERVE_SUCCESS = 4 +PSP_MEM_TRAIN_INIT_SUCCESS = 8 +psp_memory_training_init_flag = ctypes.c_uint32 # enum + +# values for enumeration 'psp_memory_training_ops' +psp_memory_training_ops__enumvalues = { + 1: 'PSP_MEM_TRAIN_SEND_LONG_MSG', + 2: 'PSP_MEM_TRAIN_SAVE', + 4: 'PSP_MEM_TRAIN_RESTORE', + 8: 'PSP_MEM_TRAIN_SEND_SHORT_MSG', + 1: 'PSP_MEM_TRAIN_COLD_BOOT', + 8: 'PSP_MEM_TRAIN_RESUME', +} +PSP_MEM_TRAIN_SEND_LONG_MSG = 1 +PSP_MEM_TRAIN_SAVE = 2 +PSP_MEM_TRAIN_RESTORE = 4 +PSP_MEM_TRAIN_SEND_SHORT_MSG = 8 +PSP_MEM_TRAIN_COLD_BOOT = 1 +PSP_MEM_TRAIN_RESUME = 8 +psp_memory_training_ops = ctypes.c_uint32 # enum + +# values for enumeration 'psp_runtime_entry_type' +psp_runtime_entry_type__enumvalues = { + 0: 'PSP_RUNTIME_ENTRY_TYPE_INVALID', + 1: 'PSP_RUNTIME_ENTRY_TYPE_TEST', + 2: 'PSP_RUNTIME_ENTRY_TYPE_MGPU_COMMON', + 3: 'PSP_RUNTIME_ENTRY_TYPE_MGPU_WAFL', + 4: 'PSP_RUNTIME_ENTRY_TYPE_MGPU_XGMI', + 5: 'PSP_RUNTIME_ENTRY_TYPE_BOOT_CONFIG', + 6: 'PSP_RUNTIME_ENTRY_TYPE_PPTABLE_ERR_STATUS', +} +PSP_RUNTIME_ENTRY_TYPE_INVALID = 0 +PSP_RUNTIME_ENTRY_TYPE_TEST = 1 +PSP_RUNTIME_ENTRY_TYPE_MGPU_COMMON = 2 +PSP_RUNTIME_ENTRY_TYPE_MGPU_WAFL = 3 +PSP_RUNTIME_ENTRY_TYPE_MGPU_XGMI = 4 +PSP_RUNTIME_ENTRY_TYPE_BOOT_CONFIG = 5 +PSP_RUNTIME_ENTRY_TYPE_PPTABLE_ERR_STATUS = 6 +psp_runtime_entry_type = ctypes.c_uint32 # enum + +# values for enumeration 'psp_runtime_boot_cfg_feature' +psp_runtime_boot_cfg_feature__enumvalues = { + 1: 'BOOT_CFG_FEATURE_GECC', + 2: 'BOOT_CFG_FEATURE_TWO_STAGE_DRAM_TRAINING', +} +BOOT_CFG_FEATURE_GECC = 1 +BOOT_CFG_FEATURE_TWO_STAGE_DRAM_TRAINING = 2 +psp_runtime_boot_cfg_feature = ctypes.c_uint32 # enum + +# values for enumeration 'psp_runtime_scpm_authentication' +psp_runtime_scpm_authentication__enumvalues = { + 0: 'SCPM_DISABLE', + 1: 'SCPM_ENABLE', + 2: 'SCPM_ENABLE_WITH_SCPM_ERR', +} +SCPM_DISABLE = 0 +SCPM_ENABLE = 1 +SCPM_ENABLE_WITH_SCPM_ERR = 2 +psp_runtime_scpm_authentication = ctypes.c_uint32 # enum +__AMDGPU_IRQ_H__ = True # macro +AMDGPU_MAX_IRQ_SRC_ID = 0x100 # macro +AMDGPU_MAX_IRQ_CLIENT_ID = 0x100 # macro +AMDGPU_IRQ_CLIENTID_LEGACY = 0 # macro +AMDGPU_IRQ_SRC_DATA_MAX_SIZE_DW = 4 # macro +class struct_amdgpu_device(Structure): + pass + + +# values for enumeration 'amdgpu_interrupt_state' +amdgpu_interrupt_state__enumvalues = { + 0: 'AMDGPU_IRQ_STATE_DISABLE', + 1: 'AMDGPU_IRQ_STATE_ENABLE', +} +AMDGPU_IRQ_STATE_DISABLE = 0 +AMDGPU_IRQ_STATE_ENABLE = 1 +amdgpu_interrupt_state = ctypes.c_uint32 # enum +class struct_amdgpu_iv_entry(Structure): + pass + +struct_amdgpu_iv_entry._pack_ = 1 # source:False +struct_amdgpu_iv_entry._fields_ = [ + ('client_id', ctypes.c_uint32), + ('src_id', ctypes.c_uint32), + ('ring_id', ctypes.c_uint32), + ('vmid', ctypes.c_uint32), + ('vmid_src', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('timestamp', ctypes.c_uint64), + ('timestamp_src', ctypes.c_uint32), + ('pasid', ctypes.c_uint32), + ('node_id', ctypes.c_uint32), + ('src_data', ctypes.c_uint32 * 4), + ('PADDING_1', ctypes.c_ubyte * 4), + ('iv_entry', ctypes.POINTER(ctypes.c_uint32)), +] + + +# values for enumeration 'interrupt_node_id_per_aid' +interrupt_node_id_per_aid__enumvalues = { + 0: 'AID0_NODEID', + 1: 'XCD0_NODEID', + 2: 'XCD1_NODEID', + 4: 'AID1_NODEID', + 5: 'XCD2_NODEID', + 6: 'XCD3_NODEID', + 8: 'AID2_NODEID', + 9: 'XCD4_NODEID', + 10: 'XCD5_NODEID', + 12: 'AID3_NODEID', + 13: 'XCD6_NODEID', + 14: 'XCD7_NODEID', + 15: 'NODEID_MAX', +} +AID0_NODEID = 0 +XCD0_NODEID = 1 +XCD1_NODEID = 2 +AID1_NODEID = 4 +XCD2_NODEID = 5 +XCD3_NODEID = 6 +AID2_NODEID = 8 +XCD4_NODEID = 9 +XCD5_NODEID = 10 +AID3_NODEID = 12 +XCD6_NODEID = 13 +XCD7_NODEID = 14 +NODEID_MAX = 15 +interrupt_node_id_per_aid = ctypes.c_uint32 # enum +AMDGPU_DOORBELL_H = True # macro + +# values for enumeration 'AMDGPU_DOORBELL_ASSIGNMENT' +AMDGPU_DOORBELL_ASSIGNMENT__enumvalues = { + 0: 'AMDGPU_DOORBELL_KIQ', + 1: 'AMDGPU_DOORBELL_HIQ', + 2: 'AMDGPU_DOORBELL_DIQ', + 16: 'AMDGPU_DOORBELL_MEC_RING0', + 17: 'AMDGPU_DOORBELL_MEC_RING1', + 18: 'AMDGPU_DOORBELL_MEC_RING2', + 19: 'AMDGPU_DOORBELL_MEC_RING3', + 20: 'AMDGPU_DOORBELL_MEC_RING4', + 21: 'AMDGPU_DOORBELL_MEC_RING5', + 22: 'AMDGPU_DOORBELL_MEC_RING6', + 23: 'AMDGPU_DOORBELL_MEC_RING7', + 32: 'AMDGPU_DOORBELL_GFX_RING0', + 480: 'AMDGPU_DOORBELL_sDMA_ENGINE0', + 481: 'AMDGPU_DOORBELL_sDMA_ENGINE1', + 488: 'AMDGPU_DOORBELL_IH', + 1023: 'AMDGPU_DOORBELL_MAX_ASSIGNMENT', + 65535: 'AMDGPU_DOORBELL_INVALID', +} +AMDGPU_DOORBELL_KIQ = 0 +AMDGPU_DOORBELL_HIQ = 1 +AMDGPU_DOORBELL_DIQ = 2 +AMDGPU_DOORBELL_MEC_RING0 = 16 +AMDGPU_DOORBELL_MEC_RING1 = 17 +AMDGPU_DOORBELL_MEC_RING2 = 18 +AMDGPU_DOORBELL_MEC_RING3 = 19 +AMDGPU_DOORBELL_MEC_RING4 = 20 +AMDGPU_DOORBELL_MEC_RING5 = 21 +AMDGPU_DOORBELL_MEC_RING6 = 22 +AMDGPU_DOORBELL_MEC_RING7 = 23 +AMDGPU_DOORBELL_GFX_RING0 = 32 +AMDGPU_DOORBELL_sDMA_ENGINE0 = 480 +AMDGPU_DOORBELL_sDMA_ENGINE1 = 481 +AMDGPU_DOORBELL_IH = 488 +AMDGPU_DOORBELL_MAX_ASSIGNMENT = 1023 +AMDGPU_DOORBELL_INVALID = 65535 +AMDGPU_DOORBELL_ASSIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'AMDGPU_VEGA20_DOORBELL_ASSIGNMENT' +AMDGPU_VEGA20_DOORBELL_ASSIGNMENT__enumvalues = { + 0: 'AMDGPU_VEGA20_DOORBELL_KIQ', + 1: 'AMDGPU_VEGA20_DOORBELL_HIQ', + 2: 'AMDGPU_VEGA20_DOORBELL_DIQ', + 3: 'AMDGPU_VEGA20_DOORBELL_MEC_RING0', + 4: 'AMDGPU_VEGA20_DOORBELL_MEC_RING1', + 5: 'AMDGPU_VEGA20_DOORBELL_MEC_RING2', + 6: 'AMDGPU_VEGA20_DOORBELL_MEC_RING3', + 7: 'AMDGPU_VEGA20_DOORBELL_MEC_RING4', + 8: 'AMDGPU_VEGA20_DOORBELL_MEC_RING5', + 9: 'AMDGPU_VEGA20_DOORBELL_MEC_RING6', + 10: 'AMDGPU_VEGA20_DOORBELL_MEC_RING7', + 11: 'AMDGPU_VEGA20_DOORBELL_USERQUEUE_START', + 138: 'AMDGPU_VEGA20_DOORBELL_USERQUEUE_END', + 139: 'AMDGPU_VEGA20_DOORBELL_GFX_RING0', + 256: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE0', + 266: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE1', + 276: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE2', + 286: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE3', + 296: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE4', + 306: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE5', + 316: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE6', + 326: 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE7', + 376: 'AMDGPU_VEGA20_DOORBELL_IH', + 392: 'AMDGPU_VEGA20_DOORBELL64_VCN0_1', + 393: 'AMDGPU_VEGA20_DOORBELL64_VCN2_3', + 394: 'AMDGPU_VEGA20_DOORBELL64_VCN4_5', + 395: 'AMDGPU_VEGA20_DOORBELL64_VCN6_7', + 396: 'AMDGPU_VEGA20_DOORBELL64_VCN8_9', + 397: 'AMDGPU_VEGA20_DOORBELL64_VCNa_b', + 398: 'AMDGPU_VEGA20_DOORBELL64_VCNc_d', + 399: 'AMDGPU_VEGA20_DOORBELL64_VCNe_f', + 392: 'AMDGPU_VEGA20_DOORBELL64_UVD_RING0_1', + 393: 'AMDGPU_VEGA20_DOORBELL64_UVD_RING2_3', + 394: 'AMDGPU_VEGA20_DOORBELL64_UVD_RING4_5', + 395: 'AMDGPU_VEGA20_DOORBELL64_UVD_RING6_7', + 396: 'AMDGPU_VEGA20_DOORBELL64_VCE_RING0_1', + 397: 'AMDGPU_VEGA20_DOORBELL64_VCE_RING2_3', + 398: 'AMDGPU_VEGA20_DOORBELL64_VCE_RING4_5', + 399: 'AMDGPU_VEGA20_DOORBELL64_VCE_RING6_7', + 256: 'AMDGPU_VEGA20_DOORBELL64_FIRST_NON_CP', + 399: 'AMDGPU_VEGA20_DOORBELL64_LAST_NON_CP', + 400: 'AMDGPU_VEGA20_DOORBELL_XCC1_KIQ_START', + 407: 'AMDGPU_VEGA20_DOORBELL_XCC1_MEC_RING0_START', + 464: 'AMDGPU_VEGA20_DOORBELL_AID1_sDMA_START', + 503: 'AMDGPU_VEGA20_DOORBELL_MAX_ASSIGNMENT', + 65535: 'AMDGPU_VEGA20_DOORBELL_INVALID', +} +AMDGPU_VEGA20_DOORBELL_KIQ = 0 +AMDGPU_VEGA20_DOORBELL_HIQ = 1 +AMDGPU_VEGA20_DOORBELL_DIQ = 2 +AMDGPU_VEGA20_DOORBELL_MEC_RING0 = 3 +AMDGPU_VEGA20_DOORBELL_MEC_RING1 = 4 +AMDGPU_VEGA20_DOORBELL_MEC_RING2 = 5 +AMDGPU_VEGA20_DOORBELL_MEC_RING3 = 6 +AMDGPU_VEGA20_DOORBELL_MEC_RING4 = 7 +AMDGPU_VEGA20_DOORBELL_MEC_RING5 = 8 +AMDGPU_VEGA20_DOORBELL_MEC_RING6 = 9 +AMDGPU_VEGA20_DOORBELL_MEC_RING7 = 10 +AMDGPU_VEGA20_DOORBELL_USERQUEUE_START = 11 +AMDGPU_VEGA20_DOORBELL_USERQUEUE_END = 138 +AMDGPU_VEGA20_DOORBELL_GFX_RING0 = 139 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE0 = 256 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE1 = 266 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE2 = 276 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE3 = 286 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE4 = 296 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE5 = 306 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE6 = 316 +AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE7 = 326 +AMDGPU_VEGA20_DOORBELL_IH = 376 +AMDGPU_VEGA20_DOORBELL64_VCN0_1 = 392 +AMDGPU_VEGA20_DOORBELL64_VCN2_3 = 393 +AMDGPU_VEGA20_DOORBELL64_VCN4_5 = 394 +AMDGPU_VEGA20_DOORBELL64_VCN6_7 = 395 +AMDGPU_VEGA20_DOORBELL64_VCN8_9 = 396 +AMDGPU_VEGA20_DOORBELL64_VCNa_b = 397 +AMDGPU_VEGA20_DOORBELL64_VCNc_d = 398 +AMDGPU_VEGA20_DOORBELL64_VCNe_f = 399 +AMDGPU_VEGA20_DOORBELL64_UVD_RING0_1 = 392 +AMDGPU_VEGA20_DOORBELL64_UVD_RING2_3 = 393 +AMDGPU_VEGA20_DOORBELL64_UVD_RING4_5 = 394 +AMDGPU_VEGA20_DOORBELL64_UVD_RING6_7 = 395 +AMDGPU_VEGA20_DOORBELL64_VCE_RING0_1 = 396 +AMDGPU_VEGA20_DOORBELL64_VCE_RING2_3 = 397 +AMDGPU_VEGA20_DOORBELL64_VCE_RING4_5 = 398 +AMDGPU_VEGA20_DOORBELL64_VCE_RING6_7 = 399 +AMDGPU_VEGA20_DOORBELL64_FIRST_NON_CP = 256 +AMDGPU_VEGA20_DOORBELL64_LAST_NON_CP = 399 +AMDGPU_VEGA20_DOORBELL_XCC1_KIQ_START = 400 +AMDGPU_VEGA20_DOORBELL_XCC1_MEC_RING0_START = 407 +AMDGPU_VEGA20_DOORBELL_AID1_sDMA_START = 464 +AMDGPU_VEGA20_DOORBELL_MAX_ASSIGNMENT = 503 +AMDGPU_VEGA20_DOORBELL_INVALID = 65535 +AMDGPU_VEGA20_DOORBELL_ASSIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'AMDGPU_NAVI10_DOORBELL_ASSIGNMENT' +AMDGPU_NAVI10_DOORBELL_ASSIGNMENT__enumvalues = { + 0: 'AMDGPU_NAVI10_DOORBELL_KIQ', + 1: 'AMDGPU_NAVI10_DOORBELL_HIQ', + 2: 'AMDGPU_NAVI10_DOORBELL_DIQ', + 3: 'AMDGPU_NAVI10_DOORBELL_MEC_RING0', + 4: 'AMDGPU_NAVI10_DOORBELL_MEC_RING1', + 5: 'AMDGPU_NAVI10_DOORBELL_MEC_RING2', + 6: 'AMDGPU_NAVI10_DOORBELL_MEC_RING3', + 7: 'AMDGPU_NAVI10_DOORBELL_MEC_RING4', + 8: 'AMDGPU_NAVI10_DOORBELL_MEC_RING5', + 9: 'AMDGPU_NAVI10_DOORBELL_MEC_RING6', + 10: 'AMDGPU_NAVI10_DOORBELL_MEC_RING7', + 11: 'AMDGPU_NAVI10_DOORBELL_MES_RING0', + 12: 'AMDGPU_NAVI10_DOORBELL_MES_RING1', + 13: 'AMDGPU_NAVI10_DOORBELL_USERQUEUE_START', + 138: 'AMDGPU_NAVI10_DOORBELL_USERQUEUE_END', + 139: 'AMDGPU_NAVI10_DOORBELL_GFX_RING0', + 140: 'AMDGPU_NAVI10_DOORBELL_GFX_RING1', + 141: 'AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_START', + 255: 'AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_END', + 256: 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0', + 266: 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE1', + 276: 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE2', + 286: 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE3', + 376: 'AMDGPU_NAVI10_DOORBELL_IH', + 392: 'AMDGPU_NAVI10_DOORBELL64_VCN0_1', + 393: 'AMDGPU_NAVI10_DOORBELL64_VCN2_3', + 394: 'AMDGPU_NAVI10_DOORBELL64_VCN4_5', + 395: 'AMDGPU_NAVI10_DOORBELL64_VCN6_7', + 396: 'AMDGPU_NAVI10_DOORBELL64_VCN8_9', + 397: 'AMDGPU_NAVI10_DOORBELL64_VCNa_b', + 398: 'AMDGPU_NAVI10_DOORBELL64_VCNc_d', + 399: 'AMDGPU_NAVI10_DOORBELL64_VCNe_f', + 400: 'AMDGPU_NAVI10_DOORBELL64_VPE', + 256: 'AMDGPU_NAVI10_DOORBELL64_FIRST_NON_CP', + 400: 'AMDGPU_NAVI10_DOORBELL64_LAST_NON_CP', + 400: 'AMDGPU_NAVI10_DOORBELL_MAX_ASSIGNMENT', + 65535: 'AMDGPU_NAVI10_DOORBELL_INVALID', +} +AMDGPU_NAVI10_DOORBELL_KIQ = 0 +AMDGPU_NAVI10_DOORBELL_HIQ = 1 +AMDGPU_NAVI10_DOORBELL_DIQ = 2 +AMDGPU_NAVI10_DOORBELL_MEC_RING0 = 3 +AMDGPU_NAVI10_DOORBELL_MEC_RING1 = 4 +AMDGPU_NAVI10_DOORBELL_MEC_RING2 = 5 +AMDGPU_NAVI10_DOORBELL_MEC_RING3 = 6 +AMDGPU_NAVI10_DOORBELL_MEC_RING4 = 7 +AMDGPU_NAVI10_DOORBELL_MEC_RING5 = 8 +AMDGPU_NAVI10_DOORBELL_MEC_RING6 = 9 +AMDGPU_NAVI10_DOORBELL_MEC_RING7 = 10 +AMDGPU_NAVI10_DOORBELL_MES_RING0 = 11 +AMDGPU_NAVI10_DOORBELL_MES_RING1 = 12 +AMDGPU_NAVI10_DOORBELL_USERQUEUE_START = 13 +AMDGPU_NAVI10_DOORBELL_USERQUEUE_END = 138 +AMDGPU_NAVI10_DOORBELL_GFX_RING0 = 139 +AMDGPU_NAVI10_DOORBELL_GFX_RING1 = 140 +AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_START = 141 +AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_END = 255 +AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0 = 256 +AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE1 = 266 +AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE2 = 276 +AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE3 = 286 +AMDGPU_NAVI10_DOORBELL_IH = 376 +AMDGPU_NAVI10_DOORBELL64_VCN0_1 = 392 +AMDGPU_NAVI10_DOORBELL64_VCN2_3 = 393 +AMDGPU_NAVI10_DOORBELL64_VCN4_5 = 394 +AMDGPU_NAVI10_DOORBELL64_VCN6_7 = 395 +AMDGPU_NAVI10_DOORBELL64_VCN8_9 = 396 +AMDGPU_NAVI10_DOORBELL64_VCNa_b = 397 +AMDGPU_NAVI10_DOORBELL64_VCNc_d = 398 +AMDGPU_NAVI10_DOORBELL64_VCNe_f = 399 +AMDGPU_NAVI10_DOORBELL64_VPE = 400 +AMDGPU_NAVI10_DOORBELL64_FIRST_NON_CP = 256 +AMDGPU_NAVI10_DOORBELL64_LAST_NON_CP = 400 +AMDGPU_NAVI10_DOORBELL_MAX_ASSIGNMENT = 400 +AMDGPU_NAVI10_DOORBELL_INVALID = 65535 +AMDGPU_NAVI10_DOORBELL_ASSIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'AMDGPU_DOORBELL64_ASSIGNMENT' +AMDGPU_DOORBELL64_ASSIGNMENT__enumvalues = { + 0: 'AMDGPU_DOORBELL64_KIQ', + 1: 'AMDGPU_DOORBELL64_HIQ', + 2: 'AMDGPU_DOORBELL64_DIQ', + 3: 'AMDGPU_DOORBELL64_MEC_RING0', + 4: 'AMDGPU_DOORBELL64_MEC_RING1', + 5: 'AMDGPU_DOORBELL64_MEC_RING2', + 6: 'AMDGPU_DOORBELL64_MEC_RING3', + 7: 'AMDGPU_DOORBELL64_MEC_RING4', + 8: 'AMDGPU_DOORBELL64_MEC_RING5', + 9: 'AMDGPU_DOORBELL64_MEC_RING6', + 10: 'AMDGPU_DOORBELL64_MEC_RING7', + 11: 'AMDGPU_DOORBELL64_USERQUEUE_START', + 138: 'AMDGPU_DOORBELL64_USERQUEUE_END', + 139: 'AMDGPU_DOORBELL64_GFX_RING0', + 240: 'AMDGPU_DOORBELL64_sDMA_ENGINE0', + 241: 'AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE0', + 242: 'AMDGPU_DOORBELL64_sDMA_ENGINE1', + 243: 'AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE1', + 244: 'AMDGPU_DOORBELL64_IH', + 245: 'AMDGPU_DOORBELL64_IH_RING1', + 246: 'AMDGPU_DOORBELL64_IH_RING2', + 248: 'AMDGPU_DOORBELL64_VCN0_1', + 249: 'AMDGPU_DOORBELL64_VCN2_3', + 250: 'AMDGPU_DOORBELL64_VCN4_5', + 251: 'AMDGPU_DOORBELL64_VCN6_7', + 248: 'AMDGPU_DOORBELL64_UVD_RING0_1', + 249: 'AMDGPU_DOORBELL64_UVD_RING2_3', + 250: 'AMDGPU_DOORBELL64_UVD_RING4_5', + 251: 'AMDGPU_DOORBELL64_UVD_RING6_7', + 252: 'AMDGPU_DOORBELL64_VCE_RING0_1', + 253: 'AMDGPU_DOORBELL64_VCE_RING2_3', + 254: 'AMDGPU_DOORBELL64_VCE_RING4_5', + 255: 'AMDGPU_DOORBELL64_VCE_RING6_7', + 240: 'AMDGPU_DOORBELL64_FIRST_NON_CP', + 255: 'AMDGPU_DOORBELL64_LAST_NON_CP', + 255: 'AMDGPU_DOORBELL64_MAX_ASSIGNMENT', + 65535: 'AMDGPU_DOORBELL64_INVALID', +} +AMDGPU_DOORBELL64_KIQ = 0 +AMDGPU_DOORBELL64_HIQ = 1 +AMDGPU_DOORBELL64_DIQ = 2 +AMDGPU_DOORBELL64_MEC_RING0 = 3 +AMDGPU_DOORBELL64_MEC_RING1 = 4 +AMDGPU_DOORBELL64_MEC_RING2 = 5 +AMDGPU_DOORBELL64_MEC_RING3 = 6 +AMDGPU_DOORBELL64_MEC_RING4 = 7 +AMDGPU_DOORBELL64_MEC_RING5 = 8 +AMDGPU_DOORBELL64_MEC_RING6 = 9 +AMDGPU_DOORBELL64_MEC_RING7 = 10 +AMDGPU_DOORBELL64_USERQUEUE_START = 11 +AMDGPU_DOORBELL64_USERQUEUE_END = 138 +AMDGPU_DOORBELL64_GFX_RING0 = 139 +AMDGPU_DOORBELL64_sDMA_ENGINE0 = 240 +AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE0 = 241 +AMDGPU_DOORBELL64_sDMA_ENGINE1 = 242 +AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE1 = 243 +AMDGPU_DOORBELL64_IH = 244 +AMDGPU_DOORBELL64_IH_RING1 = 245 +AMDGPU_DOORBELL64_IH_RING2 = 246 +AMDGPU_DOORBELL64_VCN0_1 = 248 +AMDGPU_DOORBELL64_VCN2_3 = 249 +AMDGPU_DOORBELL64_VCN4_5 = 250 +AMDGPU_DOORBELL64_VCN6_7 = 251 +AMDGPU_DOORBELL64_UVD_RING0_1 = 248 +AMDGPU_DOORBELL64_UVD_RING2_3 = 249 +AMDGPU_DOORBELL64_UVD_RING4_5 = 250 +AMDGPU_DOORBELL64_UVD_RING6_7 = 251 +AMDGPU_DOORBELL64_VCE_RING0_1 = 252 +AMDGPU_DOORBELL64_VCE_RING2_3 = 253 +AMDGPU_DOORBELL64_VCE_RING4_5 = 254 +AMDGPU_DOORBELL64_VCE_RING6_7 = 255 +AMDGPU_DOORBELL64_FIRST_NON_CP = 240 +AMDGPU_DOORBELL64_LAST_NON_CP = 255 +AMDGPU_DOORBELL64_MAX_ASSIGNMENT = 255 +AMDGPU_DOORBELL64_INVALID = 65535 +AMDGPU_DOORBELL64_ASSIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'AMDGPU_DOORBELL_ASSIGNMENT_LAYOUT1' +AMDGPU_DOORBELL_ASSIGNMENT_LAYOUT1__enumvalues = { + 0: 'AMDGPU_DOORBELL_LAYOUT1_KIQ_START', + 1: 'AMDGPU_DOORBELL_LAYOUT1_HIQ', + 2: 'AMDGPU_DOORBELL_LAYOUT1_DIQ', + 8: 'AMDGPU_DOORBELL_LAYOUT1_MEC_RING_START', + 15: 'AMDGPU_DOORBELL_LAYOUT1_MEC_RING_END', + 16: 'AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_START', + 31: 'AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_END', + 32: 'AMDGPU_DOORBELL_LAYOUT1_XCC_RANGE', + 256: 'AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_START', + 415: 'AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_END', + 416: 'AMDGPU_DOORBELL_LAYOUT1_IH', + 432: 'AMDGPU_DOORBELL_LAYOUT1_VCN_START', + 488: 'AMDGPU_DOORBELL_LAYOUT1_VCN_END', + 256: 'AMDGPU_DOORBELL_LAYOUT1_FIRST_NON_CP', + 488: 'AMDGPU_DOORBELL_LAYOUT1_LAST_NON_CP', + 488: 'AMDGPU_DOORBELL_LAYOUT1_MAX_ASSIGNMENT', + 65535: 'AMDGPU_DOORBELL_LAYOUT1_INVALID', +} +AMDGPU_DOORBELL_LAYOUT1_KIQ_START = 0 +AMDGPU_DOORBELL_LAYOUT1_HIQ = 1 +AMDGPU_DOORBELL_LAYOUT1_DIQ = 2 +AMDGPU_DOORBELL_LAYOUT1_MEC_RING_START = 8 +AMDGPU_DOORBELL_LAYOUT1_MEC_RING_END = 15 +AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_START = 16 +AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_END = 31 +AMDGPU_DOORBELL_LAYOUT1_XCC_RANGE = 32 +AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_START = 256 +AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_END = 415 +AMDGPU_DOORBELL_LAYOUT1_IH = 416 +AMDGPU_DOORBELL_LAYOUT1_VCN_START = 432 +AMDGPU_DOORBELL_LAYOUT1_VCN_END = 488 +AMDGPU_DOORBELL_LAYOUT1_FIRST_NON_CP = 256 +AMDGPU_DOORBELL_LAYOUT1_LAST_NON_CP = 488 +AMDGPU_DOORBELL_LAYOUT1_MAX_ASSIGNMENT = 488 +AMDGPU_DOORBELL_LAYOUT1_INVALID = 65535 +AMDGPU_DOORBELL_ASSIGNMENT_LAYOUT1 = ctypes.c_uint32 # enum +__SOC15_IH_CLIENTID_H__ = True # macro + +# values for enumeration 'soc15_ih_clientid' +soc15_ih_clientid__enumvalues = { + 0: 'SOC15_IH_CLIENTID_IH', + 1: 'SOC15_IH_CLIENTID_ACP', + 2: 'SOC15_IH_CLIENTID_ATHUB', + 3: 'SOC15_IH_CLIENTID_BIF', + 4: 'SOC15_IH_CLIENTID_DCE', + 5: 'SOC15_IH_CLIENTID_ISP', + 6: 'SOC15_IH_CLIENTID_PCIE0', + 7: 'SOC15_IH_CLIENTID_RLC', + 8: 'SOC15_IH_CLIENTID_SDMA0', + 9: 'SOC15_IH_CLIENTID_SDMA1', + 10: 'SOC15_IH_CLIENTID_SE0SH', + 11: 'SOC15_IH_CLIENTID_SE1SH', + 12: 'SOC15_IH_CLIENTID_SE2SH', + 13: 'SOC15_IH_CLIENTID_SE3SH', + 14: 'SOC15_IH_CLIENTID_UVD1', + 15: 'SOC15_IH_CLIENTID_THM', + 16: 'SOC15_IH_CLIENTID_UVD', + 17: 'SOC15_IH_CLIENTID_VCE0', + 18: 'SOC15_IH_CLIENTID_VMC', + 19: 'SOC15_IH_CLIENTID_XDMA', + 20: 'SOC15_IH_CLIENTID_GRBM_CP', + 21: 'SOC15_IH_CLIENTID_ATS', + 22: 'SOC15_IH_CLIENTID_ROM_SMUIO', + 23: 'SOC15_IH_CLIENTID_DF', + 24: 'SOC15_IH_CLIENTID_VCE1', + 25: 'SOC15_IH_CLIENTID_PWR', + 26: 'SOC15_IH_CLIENTID_RESERVED', + 27: 'SOC15_IH_CLIENTID_UTCL2', + 28: 'SOC15_IH_CLIENTID_EA', + 29: 'SOC15_IH_CLIENTID_UTCL2LOG', + 30: 'SOC15_IH_CLIENTID_MP0', + 31: 'SOC15_IH_CLIENTID_MP1', + 32: 'SOC15_IH_CLIENTID_MAX', + 16: 'SOC15_IH_CLIENTID_VCN', + 14: 'SOC15_IH_CLIENTID_VCN1', + 1: 'SOC15_IH_CLIENTID_SDMA2', + 4: 'SOC15_IH_CLIENTID_SDMA3', + 5: 'SOC15_IH_CLIENTID_SDMA3_Sienna_Cichlid', + 5: 'SOC15_IH_CLIENTID_SDMA4', + 17: 'SOC15_IH_CLIENTID_SDMA5', + 19: 'SOC15_IH_CLIENTID_SDMA6', + 24: 'SOC15_IH_CLIENTID_SDMA7', + 6: 'SOC15_IH_CLIENTID_VMC1', +} +SOC15_IH_CLIENTID_IH = 0 +SOC15_IH_CLIENTID_ACP = 1 +SOC15_IH_CLIENTID_ATHUB = 2 +SOC15_IH_CLIENTID_BIF = 3 +SOC15_IH_CLIENTID_DCE = 4 +SOC15_IH_CLIENTID_ISP = 5 +SOC15_IH_CLIENTID_PCIE0 = 6 +SOC15_IH_CLIENTID_RLC = 7 +SOC15_IH_CLIENTID_SDMA0 = 8 +SOC15_IH_CLIENTID_SDMA1 = 9 +SOC15_IH_CLIENTID_SE0SH = 10 +SOC15_IH_CLIENTID_SE1SH = 11 +SOC15_IH_CLIENTID_SE2SH = 12 +SOC15_IH_CLIENTID_SE3SH = 13 +SOC15_IH_CLIENTID_UVD1 = 14 +SOC15_IH_CLIENTID_THM = 15 +SOC15_IH_CLIENTID_UVD = 16 +SOC15_IH_CLIENTID_VCE0 = 17 +SOC15_IH_CLIENTID_VMC = 18 +SOC15_IH_CLIENTID_XDMA = 19 +SOC15_IH_CLIENTID_GRBM_CP = 20 +SOC15_IH_CLIENTID_ATS = 21 +SOC15_IH_CLIENTID_ROM_SMUIO = 22 +SOC15_IH_CLIENTID_DF = 23 +SOC15_IH_CLIENTID_VCE1 = 24 +SOC15_IH_CLIENTID_PWR = 25 +SOC15_IH_CLIENTID_RESERVED = 26 +SOC15_IH_CLIENTID_UTCL2 = 27 +SOC15_IH_CLIENTID_EA = 28 +SOC15_IH_CLIENTID_UTCL2LOG = 29 +SOC15_IH_CLIENTID_MP0 = 30 +SOC15_IH_CLIENTID_MP1 = 31 +SOC15_IH_CLIENTID_MAX = 32 +SOC15_IH_CLIENTID_VCN = 16 +SOC15_IH_CLIENTID_VCN1 = 14 +SOC15_IH_CLIENTID_SDMA2 = 1 +SOC15_IH_CLIENTID_SDMA3 = 4 +SOC15_IH_CLIENTID_SDMA3_Sienna_Cichlid = 5 +SOC15_IH_CLIENTID_SDMA4 = 5 +SOC15_IH_CLIENTID_SDMA5 = 17 +SOC15_IH_CLIENTID_SDMA6 = 19 +SOC15_IH_CLIENTID_SDMA7 = 24 +SOC15_IH_CLIENTID_VMC1 = 6 +soc15_ih_clientid = ctypes.c_uint32 # enum +AMDGPU_IRQ_CLIENTID_MAX = SOC15_IH_CLIENTID_MAX # macro +soc15_ih_clientid_name = [] # Variable ctypes.POINTER(ctypes.c_char) * 0 + +# values for enumeration 'soc21_ih_clientid' +soc21_ih_clientid__enumvalues = { + 0: 'SOC21_IH_CLIENTID_IH', + 2: 'SOC21_IH_CLIENTID_ATHUB', + 3: 'SOC21_IH_CLIENTID_BIF', + 4: 'SOC21_IH_CLIENTID_DCN', + 5: 'SOC21_IH_CLIENTID_ISP', + 6: 'SOC21_IH_CLIENTID_MP3', + 7: 'SOC21_IH_CLIENTID_RLC', + 10: 'SOC21_IH_CLIENTID_GFX', + 11: 'SOC21_IH_CLIENTID_IMU', + 14: 'SOC21_IH_CLIENTID_VCN1', + 15: 'SOC21_IH_CLIENTID_THM', + 16: 'SOC21_IH_CLIENTID_VCN', + 17: 'SOC21_IH_CLIENTID_VPE1', + 18: 'SOC21_IH_CLIENTID_VMC', + 20: 'SOC21_IH_CLIENTID_GRBM_CP', + 22: 'SOC21_IH_CLIENTID_ROM_SMUIO', + 23: 'SOC21_IH_CLIENTID_DF', + 24: 'SOC21_IH_CLIENTID_VPE', + 25: 'SOC21_IH_CLIENTID_PWR', + 26: 'SOC21_IH_CLIENTID_LSDMA', + 30: 'SOC21_IH_CLIENTID_MP0', + 31: 'SOC21_IH_CLIENTID_MP1', + 32: 'SOC21_IH_CLIENTID_MAX', +} +SOC21_IH_CLIENTID_IH = 0 +SOC21_IH_CLIENTID_ATHUB = 2 +SOC21_IH_CLIENTID_BIF = 3 +SOC21_IH_CLIENTID_DCN = 4 +SOC21_IH_CLIENTID_ISP = 5 +SOC21_IH_CLIENTID_MP3 = 6 +SOC21_IH_CLIENTID_RLC = 7 +SOC21_IH_CLIENTID_GFX = 10 +SOC21_IH_CLIENTID_IMU = 11 +SOC21_IH_CLIENTID_VCN1 = 14 +SOC21_IH_CLIENTID_THM = 15 +SOC21_IH_CLIENTID_VCN = 16 +SOC21_IH_CLIENTID_VPE1 = 17 +SOC21_IH_CLIENTID_VMC = 18 +SOC21_IH_CLIENTID_GRBM_CP = 20 +SOC21_IH_CLIENTID_ROM_SMUIO = 22 +SOC21_IH_CLIENTID_DF = 23 +SOC21_IH_CLIENTID_VPE = 24 +SOC21_IH_CLIENTID_PWR = 25 +SOC21_IH_CLIENTID_LSDMA = 26 +SOC21_IH_CLIENTID_MP0 = 30 +SOC21_IH_CLIENTID_MP1 = 31 +SOC21_IH_CLIENTID_MAX = 32 +soc21_ih_clientid = ctypes.c_uint32 # enum +__all__ = \ + ['ACP_HWID', 'AID0_NODEID', 'AID1_NODEID', 'AID2_NODEID', + 'AID3_NODEID', 'AMDGPU_CPCE_UCODE_LOADED', + 'AMDGPU_CPMEC1_UCODE_LOADED', 'AMDGPU_CPMEC2_UCODE_LOADED', + 'AMDGPU_CPME_UCODE_LOADED', 'AMDGPU_CPPFP_UCODE_LOADED', + 'AMDGPU_CPRLC_UCODE_LOADED', 'AMDGPU_DOORBELL64_ASSIGNMENT', + 'AMDGPU_DOORBELL64_DIQ', 'AMDGPU_DOORBELL64_FIRST_NON_CP', + 'AMDGPU_DOORBELL64_GFX_RING0', 'AMDGPU_DOORBELL64_HIQ', + 'AMDGPU_DOORBELL64_IH', 'AMDGPU_DOORBELL64_IH_RING1', + 'AMDGPU_DOORBELL64_IH_RING2', 'AMDGPU_DOORBELL64_INVALID', + 'AMDGPU_DOORBELL64_KIQ', 'AMDGPU_DOORBELL64_LAST_NON_CP', + 'AMDGPU_DOORBELL64_MAX_ASSIGNMENT', 'AMDGPU_DOORBELL64_MEC_RING0', + 'AMDGPU_DOORBELL64_MEC_RING1', 'AMDGPU_DOORBELL64_MEC_RING2', + 'AMDGPU_DOORBELL64_MEC_RING3', 'AMDGPU_DOORBELL64_MEC_RING4', + 'AMDGPU_DOORBELL64_MEC_RING5', 'AMDGPU_DOORBELL64_MEC_RING6', + 'AMDGPU_DOORBELL64_MEC_RING7', 'AMDGPU_DOORBELL64_USERQUEUE_END', + 'AMDGPU_DOORBELL64_USERQUEUE_START', + 'AMDGPU_DOORBELL64_UVD_RING0_1', 'AMDGPU_DOORBELL64_UVD_RING2_3', + 'AMDGPU_DOORBELL64_UVD_RING4_5', 'AMDGPU_DOORBELL64_UVD_RING6_7', + 'AMDGPU_DOORBELL64_VCE_RING0_1', 'AMDGPU_DOORBELL64_VCE_RING2_3', + 'AMDGPU_DOORBELL64_VCE_RING4_5', 'AMDGPU_DOORBELL64_VCE_RING6_7', + 'AMDGPU_DOORBELL64_VCN0_1', 'AMDGPU_DOORBELL64_VCN2_3', + 'AMDGPU_DOORBELL64_VCN4_5', 'AMDGPU_DOORBELL64_VCN6_7', + 'AMDGPU_DOORBELL64_sDMA_ENGINE0', + 'AMDGPU_DOORBELL64_sDMA_ENGINE1', + 'AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE0', + 'AMDGPU_DOORBELL64_sDMA_HI_PRI_ENGINE1', + 'AMDGPU_DOORBELL_ASSIGNMENT', + 'AMDGPU_DOORBELL_ASSIGNMENT_LAYOUT1', 'AMDGPU_DOORBELL_DIQ', + 'AMDGPU_DOORBELL_GFX_RING0', 'AMDGPU_DOORBELL_H', + 'AMDGPU_DOORBELL_HIQ', 'AMDGPU_DOORBELL_IH', + 'AMDGPU_DOORBELL_INVALID', 'AMDGPU_DOORBELL_KIQ', + 'AMDGPU_DOORBELL_LAYOUT1_DIQ', + 'AMDGPU_DOORBELL_LAYOUT1_FIRST_NON_CP', + 'AMDGPU_DOORBELL_LAYOUT1_HIQ', 'AMDGPU_DOORBELL_LAYOUT1_IH', + 'AMDGPU_DOORBELL_LAYOUT1_INVALID', + 'AMDGPU_DOORBELL_LAYOUT1_KIQ_START', + 'AMDGPU_DOORBELL_LAYOUT1_LAST_NON_CP', + 'AMDGPU_DOORBELL_LAYOUT1_MAX_ASSIGNMENT', + 'AMDGPU_DOORBELL_LAYOUT1_MEC_RING_END', + 'AMDGPU_DOORBELL_LAYOUT1_MEC_RING_START', + 'AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_END', + 'AMDGPU_DOORBELL_LAYOUT1_USERQUEUE_START', + 'AMDGPU_DOORBELL_LAYOUT1_VCN_END', + 'AMDGPU_DOORBELL_LAYOUT1_VCN_START', + 'AMDGPU_DOORBELL_LAYOUT1_XCC_RANGE', + 'AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_END', + 'AMDGPU_DOORBELL_LAYOUT1_sDMA_ENGINE_START', + 'AMDGPU_DOORBELL_MAX_ASSIGNMENT', 'AMDGPU_DOORBELL_MEC_RING0', + 'AMDGPU_DOORBELL_MEC_RING1', 'AMDGPU_DOORBELL_MEC_RING2', + 'AMDGPU_DOORBELL_MEC_RING3', 'AMDGPU_DOORBELL_MEC_RING4', + 'AMDGPU_DOORBELL_MEC_RING5', 'AMDGPU_DOORBELL_MEC_RING6', + 'AMDGPU_DOORBELL_MEC_RING7', 'AMDGPU_DOORBELL_sDMA_ENGINE0', + 'AMDGPU_DOORBELL_sDMA_ENGINE1', 'AMDGPU_FW_LOAD_DIRECT', + 'AMDGPU_FW_LOAD_PSP', 'AMDGPU_FW_LOAD_RLC_BACKDOOR_AUTO', + 'AMDGPU_FW_LOAD_SMU', 'AMDGPU_GFXHUB_START', + 'AMDGPU_IRQ_CLIENTID_LEGACY', 'AMDGPU_IRQ_CLIENTID_MAX', + 'AMDGPU_IRQ_SRC_DATA_MAX_SIZE_DW', 'AMDGPU_IRQ_STATE_DISABLE', + 'AMDGPU_IRQ_STATE_ENABLE', 'AMDGPU_MAX_IRQ_CLIENT_ID', + 'AMDGPU_MAX_IRQ_SRC_ID', 'AMDGPU_MAX_VMHUBS', + 'AMDGPU_MMHUB0_START', 'AMDGPU_MMHUB1_START', 'AMDGPU_MTYPE_CC', + 'AMDGPU_MTYPE_NC', 'AMDGPU_NAVI10_DOORBELL64_FIRST_NON_CP', + 'AMDGPU_NAVI10_DOORBELL64_LAST_NON_CP', + 'AMDGPU_NAVI10_DOORBELL64_VCN0_1', + 'AMDGPU_NAVI10_DOORBELL64_VCN2_3', + 'AMDGPU_NAVI10_DOORBELL64_VCN4_5', + 'AMDGPU_NAVI10_DOORBELL64_VCN6_7', + 'AMDGPU_NAVI10_DOORBELL64_VCN8_9', + 'AMDGPU_NAVI10_DOORBELL64_VCNa_b', + 'AMDGPU_NAVI10_DOORBELL64_VCNc_d', + 'AMDGPU_NAVI10_DOORBELL64_VCNe_f', 'AMDGPU_NAVI10_DOORBELL64_VPE', + 'AMDGPU_NAVI10_DOORBELL_ASSIGNMENT', 'AMDGPU_NAVI10_DOORBELL_DIQ', + 'AMDGPU_NAVI10_DOORBELL_GFX_RING0', + 'AMDGPU_NAVI10_DOORBELL_GFX_RING1', + 'AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_END', + 'AMDGPU_NAVI10_DOORBELL_GFX_USERQUEUE_START', + 'AMDGPU_NAVI10_DOORBELL_HIQ', 'AMDGPU_NAVI10_DOORBELL_IH', + 'AMDGPU_NAVI10_DOORBELL_INVALID', 'AMDGPU_NAVI10_DOORBELL_KIQ', + 'AMDGPU_NAVI10_DOORBELL_MAX_ASSIGNMENT', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING0', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING1', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING2', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING3', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING4', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING5', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING6', + 'AMDGPU_NAVI10_DOORBELL_MEC_RING7', + 'AMDGPU_NAVI10_DOORBELL_MES_RING0', + 'AMDGPU_NAVI10_DOORBELL_MES_RING1', + 'AMDGPU_NAVI10_DOORBELL_USERQUEUE_END', + 'AMDGPU_NAVI10_DOORBELL_USERQUEUE_START', + 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0', + 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE1', + 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE2', + 'AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE3', 'AMDGPU_PDE_PTE', + 'AMDGPU_PDE_PTE_GFX12', 'AMDGPU_PTE_DEFAULT_ATC', + 'AMDGPU_PTE_EXECUTABLE', 'AMDGPU_PTE_IS_PTE', 'AMDGPU_PTE_LOG', + 'AMDGPU_PTE_MTYPE_GFX12_MASK', 'AMDGPU_PTE_MTYPE_NV10_MASK', + 'AMDGPU_PTE_MTYPE_VG10_MASK', 'AMDGPU_PTE_NOALLOC', + 'AMDGPU_PTE_PRT', 'AMDGPU_PTE_PRT_GFX12', 'AMDGPU_PTE_READABLE', + 'AMDGPU_PTE_SNOOPED', 'AMDGPU_PTE_SYSTEM', 'AMDGPU_PTE_TF', + 'AMDGPU_PTE_TMZ', 'AMDGPU_PTE_VALID', 'AMDGPU_PTE_WRITEABLE', + 'AMDGPU_SDMA0_UCODE_LOADED', 'AMDGPU_SDMA1_UCODE_LOADED', + 'AMDGPU_UCODE_ID', 'AMDGPU_UCODE_ID_CAP', 'AMDGPU_UCODE_ID_CP_CE', + 'AMDGPU_UCODE_ID_CP_ME', 'AMDGPU_UCODE_ID_CP_MEC1', + 'AMDGPU_UCODE_ID_CP_MEC1_JT', 'AMDGPU_UCODE_ID_CP_MEC2', + 'AMDGPU_UCODE_ID_CP_MEC2_JT', 'AMDGPU_UCODE_ID_CP_MES', + 'AMDGPU_UCODE_ID_CP_MES1', 'AMDGPU_UCODE_ID_CP_MES1_DATA', + 'AMDGPU_UCODE_ID_CP_MES_DATA', 'AMDGPU_UCODE_ID_CP_PFP', + 'AMDGPU_UCODE_ID_CP_RS64_ME', 'AMDGPU_UCODE_ID_CP_RS64_MEC', + 'AMDGPU_UCODE_ID_CP_RS64_MEC_P0_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_MEC_P1_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_MEC_P2_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_MEC_P3_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_ME_P0_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_ME_P1_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_PFP', + 'AMDGPU_UCODE_ID_CP_RS64_PFP_P0_STACK', + 'AMDGPU_UCODE_ID_CP_RS64_PFP_P1_STACK', 'AMDGPU_UCODE_ID_DMCUB', + 'AMDGPU_UCODE_ID_DMCU_ERAM', 'AMDGPU_UCODE_ID_DMCU_INTV', + 'AMDGPU_UCODE_ID_GLOBAL_TAP_DELAYS', 'AMDGPU_UCODE_ID_IMU_D', + 'AMDGPU_UCODE_ID_IMU_I', 'AMDGPU_UCODE_ID_ISP', + 'AMDGPU_UCODE_ID_JPEG_RAM', 'AMDGPU_UCODE_ID_MAXIMUM', + 'AMDGPU_UCODE_ID_P2S_TABLE', 'AMDGPU_UCODE_ID_PPTABLE', + 'AMDGPU_UCODE_ID_RLC_DRAM', 'AMDGPU_UCODE_ID_RLC_G', + 'AMDGPU_UCODE_ID_RLC_IRAM', 'AMDGPU_UCODE_ID_RLC_P', + 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_CNTL', + 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_GPM_MEM', + 'AMDGPU_UCODE_ID_RLC_RESTORE_LIST_SRM_MEM', + 'AMDGPU_UCODE_ID_RLC_V', 'AMDGPU_UCODE_ID_SDMA0', + 'AMDGPU_UCODE_ID_SDMA1', 'AMDGPU_UCODE_ID_SDMA2', + 'AMDGPU_UCODE_ID_SDMA3', 'AMDGPU_UCODE_ID_SDMA4', + 'AMDGPU_UCODE_ID_SDMA5', 'AMDGPU_UCODE_ID_SDMA6', + 'AMDGPU_UCODE_ID_SDMA7', 'AMDGPU_UCODE_ID_SDMA_RS64', + 'AMDGPU_UCODE_ID_SDMA_UCODE_TH0', + 'AMDGPU_UCODE_ID_SDMA_UCODE_TH1', + 'AMDGPU_UCODE_ID_SE0_TAP_DELAYS', + 'AMDGPU_UCODE_ID_SE1_TAP_DELAYS', + 'AMDGPU_UCODE_ID_SE2_TAP_DELAYS', + 'AMDGPU_UCODE_ID_SE3_TAP_DELAYS', 'AMDGPU_UCODE_ID_SMC', + 'AMDGPU_UCODE_ID_STORAGE', 'AMDGPU_UCODE_ID_UMSCH_MM_CMD_BUFFER', + 'AMDGPU_UCODE_ID_UMSCH_MM_DATA', 'AMDGPU_UCODE_ID_UMSCH_MM_UCODE', + 'AMDGPU_UCODE_ID_UVD', 'AMDGPU_UCODE_ID_UVD1', + 'AMDGPU_UCODE_ID_VCE', 'AMDGPU_UCODE_ID_VCN', + 'AMDGPU_UCODE_ID_VCN0_RAM', 'AMDGPU_UCODE_ID_VCN1', + 'AMDGPU_UCODE_ID_VCN1_RAM', 'AMDGPU_UCODE_ID_VPE', + 'AMDGPU_UCODE_ID_VPE_CTL', 'AMDGPU_UCODE_ID_VPE_CTX', + 'AMDGPU_UCODE_STATUS', 'AMDGPU_UCODE_STATUS_INVALID', + 'AMDGPU_UCODE_STATUS_LOADED', 'AMDGPU_UCODE_STATUS_NOT_LOADED', + 'AMDGPU_VA_RESERVED_BOTTOM', 'AMDGPU_VA_RESERVED_CSA_SIZE', + 'AMDGPU_VA_RESERVED_SEQ64_SIZE', 'AMDGPU_VA_RESERVED_TOP', + 'AMDGPU_VA_RESERVED_TRAP_SIZE', + 'AMDGPU_VEGA20_DOORBELL64_FIRST_NON_CP', + 'AMDGPU_VEGA20_DOORBELL64_LAST_NON_CP', + 'AMDGPU_VEGA20_DOORBELL64_UVD_RING0_1', + 'AMDGPU_VEGA20_DOORBELL64_UVD_RING2_3', + 'AMDGPU_VEGA20_DOORBELL64_UVD_RING4_5', + 'AMDGPU_VEGA20_DOORBELL64_UVD_RING6_7', + 'AMDGPU_VEGA20_DOORBELL64_VCE_RING0_1', + 'AMDGPU_VEGA20_DOORBELL64_VCE_RING2_3', + 'AMDGPU_VEGA20_DOORBELL64_VCE_RING4_5', + 'AMDGPU_VEGA20_DOORBELL64_VCE_RING6_7', + 'AMDGPU_VEGA20_DOORBELL64_VCN0_1', + 'AMDGPU_VEGA20_DOORBELL64_VCN2_3', + 'AMDGPU_VEGA20_DOORBELL64_VCN4_5', + 'AMDGPU_VEGA20_DOORBELL64_VCN6_7', + 'AMDGPU_VEGA20_DOORBELL64_VCN8_9', + 'AMDGPU_VEGA20_DOORBELL64_VCNa_b', + 'AMDGPU_VEGA20_DOORBELL64_VCNc_d', + 'AMDGPU_VEGA20_DOORBELL64_VCNe_f', + 'AMDGPU_VEGA20_DOORBELL_AID1_sDMA_START', + 'AMDGPU_VEGA20_DOORBELL_ASSIGNMENT', 'AMDGPU_VEGA20_DOORBELL_DIQ', + 'AMDGPU_VEGA20_DOORBELL_GFX_RING0', 'AMDGPU_VEGA20_DOORBELL_HIQ', + 'AMDGPU_VEGA20_DOORBELL_IH', 'AMDGPU_VEGA20_DOORBELL_INVALID', + 'AMDGPU_VEGA20_DOORBELL_KIQ', + 'AMDGPU_VEGA20_DOORBELL_MAX_ASSIGNMENT', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING0', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING1', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING2', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING3', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING4', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING5', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING6', + 'AMDGPU_VEGA20_DOORBELL_MEC_RING7', + 'AMDGPU_VEGA20_DOORBELL_USERQUEUE_END', + 'AMDGPU_VEGA20_DOORBELL_USERQUEUE_START', + 'AMDGPU_VEGA20_DOORBELL_XCC1_KIQ_START', + 'AMDGPU_VEGA20_DOORBELL_XCC1_MEC_RING0_START', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE0', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE1', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE2', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE3', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE4', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE5', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE6', + 'AMDGPU_VEGA20_DOORBELL_sDMA_ENGINE7', + 'AMDGPU_VM_FAULT_STOP_ALWAYS', 'AMDGPU_VM_FAULT_STOP_FIRST', + 'AMDGPU_VM_FAULT_STOP_NEVER', 'AMDGPU_VM_MAX_UPDATE_SIZE', + 'AMDGPU_VM_NORETRY_FLAGS', 'AMDGPU_VM_NORETRY_FLAGS_TF', + 'AMDGPU_VM_PDB0', 'AMDGPU_VM_PDB1', 'AMDGPU_VM_PDB2', + 'AMDGPU_VM_PTB', 'AMDGPU_VM_RESERVED_VRAM', + 'AMDGPU_VM_USE_CPU_FOR_COMPUTE', 'AMDGPU_VM_USE_CPU_FOR_GFX', + 'AMDGPU_XGMI_MAX_CONNECTED_NODES', 'ATHUB_HWID', 'ATHUB_HWIP', + 'AUDIO_AZ_HWID', 'BINARY_SIGNATURE', + 'BIST_MEM_TRAINING_ENCROACHED_SIZE', 'BOOTCFG_CMD_GET', + 'BOOTCFG_CMD_INVALIDATE', 'BOOTCFG_CMD_SET', + 'BOOT_CFG_FEATURE_GECC', + 'BOOT_CFG_FEATURE_TWO_STAGE_DRAM_TRAINING', 'BOOT_CONFIG_GECC', + 'C2PMSG_CMD_GFX_USB_PD_FW_VER', 'CCXSEC_HWID', 'CLKA_HWID', + 'CLKB_HWID', 'CLK_HWIP', 'DAZ_HWID', 'DBGU0_HWID', 'DBGU1_HWID', + 'DBGU_IO_HWID', 'DBGU_NBIO_HWID', 'DCEAZ_HWID', 'DCE_HWIP', + 'DCI_HWID', 'DCI_HWIP', 'DCO_HWID', 'DDCL_HWID', 'DFX_DAP_HWID', + 'DFX_HWID', 'DF_HWID', 'DF_HWIP', 'DIO_HWID', + 'DISCOVERY_TABLE_SIGNATURE', 'DMU_HWID', 'FCH_HWID', + 'FCH_USB_PD_HWID', 'FRAME_TYPE_DESTROY', 'FUSE_HWID', 'GC', + 'GC_HWID', 'GC_HWIP', 'GC_TABLE_ID', + 'GDDR6_MEM_TRAINING_DATA_SIZE_IN_BYTES', + 'GDDR6_MEM_TRAINING_OFFSET', 'GFX_BUF_MAX_DESC', + 'GFX_CMD_ID_AUTOLOAD_RLC', 'GFX_CMD_ID_BOOT_CFG', + 'GFX_CMD_ID_DESTROY_TMR', 'GFX_CMD_ID_DESTROY_VMR', + 'GFX_CMD_ID_GET_FW_ATTESTATION', 'GFX_CMD_ID_INVOKE_CMD', + 'GFX_CMD_ID_LOAD_ASD', 'GFX_CMD_ID_LOAD_IP_FW', + 'GFX_CMD_ID_LOAD_TA', 'GFX_CMD_ID_LOAD_TOC', 'GFX_CMD_ID_MASK', + 'GFX_CMD_ID_PROG_REG', 'GFX_CMD_ID_SAVE_RESTORE', + 'GFX_CMD_ID_SETUP_TMR', 'GFX_CMD_ID_SETUP_VMR', + 'GFX_CMD_ID_SRIOV_SPATIAL_PART', 'GFX_CMD_ID_UNLOAD_TA', + 'GFX_CMD_RESERVED_MASK', 'GFX_CMD_RESPONSE_MASK', + 'GFX_CMD_STATUS_MASK', 'GFX_CTRL_CMD_ID_CAN_INIT_RINGS', + 'GFX_CTRL_CMD_ID_CONSUME_CMD', + 'GFX_CTRL_CMD_ID_DESTROY_GPCOM_RING', + 'GFX_CTRL_CMD_ID_DESTROY_RINGS', 'GFX_CTRL_CMD_ID_DISABLE_INT', + 'GFX_CTRL_CMD_ID_ENABLE_INT', 'GFX_CTRL_CMD_ID_GBR_IH_SET', + 'GFX_CTRL_CMD_ID_INIT_GPCOM_RING', + 'GFX_CTRL_CMD_ID_INIT_RBI_RING', 'GFX_CTRL_CMD_ID_MAX', + 'GFX_CTRL_CMD_ID_MODE1_RST', 'GFX_FLAG_RESPONSE', + 'GFX_FW_TYPE_ACCUM_CTRL_RAM', 'GFX_FW_TYPE_ACP', + 'GFX_FW_TYPE_CAP', 'GFX_FW_TYPE_CP_CE', 'GFX_FW_TYPE_CP_ME', + 'GFX_FW_TYPE_CP_MEC', 'GFX_FW_TYPE_CP_MEC_ME1', + 'GFX_FW_TYPE_CP_MEC_ME2', 'GFX_FW_TYPE_CP_MES', + 'GFX_FW_TYPE_CP_MES_KIQ', 'GFX_FW_TYPE_CP_PFP', + 'GFX_FW_TYPE_DISCRETE_USB4', 'GFX_FW_TYPE_DMCU_ERAM', + 'GFX_FW_TYPE_DMCU_ISR', 'GFX_FW_TYPE_DMUB', + 'GFX_FW_TYPE_GLOBAL_MUX_SELECT_RAM', + 'GFX_FW_TYPE_GLOBAL_SE0_SE1_SKEW_DELAYS', + 'GFX_FW_TYPE_GLOBAL_TAP_DELAYS', 'GFX_FW_TYPE_IMU_D', + 'GFX_FW_TYPE_IMU_I', 'GFX_FW_TYPE_ISP', 'GFX_FW_TYPE_ISP_DATA', + 'GFX_FW_TYPE_JPEG_RAM', 'GFX_FW_TYPE_LSDMA', 'GFX_FW_TYPE_MAX', + 'GFX_FW_TYPE_MES_KIQ_STACK', 'GFX_FW_TYPE_MES_STACK', + 'GFX_FW_TYPE_MMSCH', 'GFX_FW_TYPE_NONE', 'GFX_FW_TYPE_P2S_TABLE', + 'GFX_FW_TYPE_PPTABLE', 'GFX_FW_TYPE_REG_LIST', + 'GFX_FW_TYPE_RLCG_SCRATCH_SR', 'GFX_FW_TYPE_RLCP_CAM', + 'GFX_FW_TYPE_RLCP_SCRATCH_SR', 'GFX_FW_TYPE_RLCV_SCRATCH_SR', + 'GFX_FW_TYPE_RLC_DRAM_BOOT', 'GFX_FW_TYPE_RLC_G', + 'GFX_FW_TYPE_RLC_IRAM', 'GFX_FW_TYPE_RLC_P', + 'GFX_FW_TYPE_RLC_RESTORE_LIST_GPM_MEM', + 'GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_CNTL', + 'GFX_FW_TYPE_RLC_RESTORE_LIST_SRM_MEM', + 'GFX_FW_TYPE_RLC_SPP_CAM_EXT', 'GFX_FW_TYPE_RLC_SRM_DRAM_SR', + 'GFX_FW_TYPE_RLC_V', 'GFX_FW_TYPE_RLX6_DRAM_SR', + 'GFX_FW_TYPE_RS64_KIQ', 'GFX_FW_TYPE_RS64_KIQ_STACK', + 'GFX_FW_TYPE_RS64_ME', 'GFX_FW_TYPE_RS64_MEC', + 'GFX_FW_TYPE_RS64_MEC_P0_STACK', 'GFX_FW_TYPE_RS64_MEC_P1_STACK', + 'GFX_FW_TYPE_RS64_MEC_P2_STACK', 'GFX_FW_TYPE_RS64_MEC_P3_STACK', + 'GFX_FW_TYPE_RS64_MES', 'GFX_FW_TYPE_RS64_MES_STACK', + 'GFX_FW_TYPE_RS64_ME_P0_STACK', 'GFX_FW_TYPE_RS64_ME_P1_STACK', + 'GFX_FW_TYPE_RS64_PFP', 'GFX_FW_TYPE_RS64_PFP_P0_STACK', + 'GFX_FW_TYPE_RS64_PFP_P1_STACK', 'GFX_FW_TYPE_SDMA0', + 'GFX_FW_TYPE_SDMA0_JT', 'GFX_FW_TYPE_SDMA0_PG_CONTEXT', + 'GFX_FW_TYPE_SDMA1', 'GFX_FW_TYPE_SDMA1_JT', + 'GFX_FW_TYPE_SDMA1_PG_CONTEXT', 'GFX_FW_TYPE_SDMA2', + 'GFX_FW_TYPE_SDMA3', 'GFX_FW_TYPE_SDMA4', 'GFX_FW_TYPE_SDMA5', + 'GFX_FW_TYPE_SDMA6', 'GFX_FW_TYPE_SDMA7', + 'GFX_FW_TYPE_SDMA_UCODE_TH0', 'GFX_FW_TYPE_SDMA_UCODE_TH1', + 'GFX_FW_TYPE_SE0_MUX_SELECT_RAM', 'GFX_FW_TYPE_SE0_TAP_DELAYS', + 'GFX_FW_TYPE_SE1_MUX_SELECT_RAM', 'GFX_FW_TYPE_SE1_TAP_DELAYS', + 'GFX_FW_TYPE_SE2_TAP_DELAYS', 'GFX_FW_TYPE_SE3_TAP_DELAYS', + 'GFX_FW_TYPE_SMU', 'GFX_FW_TYPE_TA', 'GFX_FW_TYPE_TOC', + 'GFX_FW_TYPE_UMSCH_CMD_BUFFER', 'GFX_FW_TYPE_UMSCH_DATA', + 'GFX_FW_TYPE_UMSCH_UCODE', 'GFX_FW_TYPE_USB_DP_COMBO_PHY', + 'GFX_FW_TYPE_UVD', 'GFX_FW_TYPE_UVD1', 'GFX_FW_TYPE_VCE', + 'GFX_FW_TYPE_VCN', 'GFX_FW_TYPE_VCN0_RAM', 'GFX_FW_TYPE_VCN1', + 'GFX_FW_TYPE_VCN1_RAM', 'GFX_FW_TYPE_VPE', 'GFX_FW_TYPE_VPEC_FW1', + 'GFX_FW_TYPE_VPEC_FW2', 'HARVEST_INFO', 'HARVEST_TABLE_SIGNATURE', + 'HDP_HWID', 'HDP_HWIP', 'HWIP_MAX_INSTANCE', 'HW_ID_MAX', + 'IOAGR_HWID', 'IOAPIC_HWID', 'IOHC_HWID', 'IP_DISCOVERY', + 'ISP_HWID', 'ISP_HWIP', 'JPEG_HWIP', 'L1IMU10_HWID', + 'L1IMU11_HWID', 'L1IMU12_HWID', 'L1IMU13_HWID', 'L1IMU14_HWID', + 'L1IMU15_HWID', 'L1IMU3_HWID', 'L1IMU4_HWID', 'L1IMU5_HWID', + 'L1IMU6_HWID', 'L1IMU7_HWID', 'L1IMU8_HWID', 'L1IMU9_HWID', + 'L1IMU_IOAGR_HWID', 'L1IMU_NBIF_HWID', 'L1IMU_PCIE_HWID', + 'L2IMU_HWID', 'LSDMA_HWID', 'LSDMA_HWIP', 'MALL_INFO', + 'MALL_INFO_TABLE_ID', 'MAX_HWIP', 'MEM_TRAIN_SYSTEM_SIGNATURE', + 'MMHUB_HWID', 'MMHUB_HWIP', 'MP0_HWID', 'MP0_HWIP', 'MP1_HWID', + 'MP1_HWIP', 'MP2_HWID', 'NBIF_HWID', 'NBIF_HWIP', 'NBIO_HWIP', + 'NODEID_MAX', 'NPS_INFO', 'NPS_INFO_TABLE_ID', + 'NPS_INFO_TABLE_MAX_NUM_INSTANCES', 'NTBCCP_HWID', 'NTB_HWID', + 'OSSSYS_HWID', 'OSSSYS_HWIP', 'PCIE_HWID', 'PCIE_HWIP', + 'PCS_HWID', 'PSP_1_MEG', 'PSP_ASD_SHARED_MEM_SIZE', + 'PSP_BL__DRAM_LONG_TRAIN', 'PSP_BL__DRAM_SHORT_TRAIN', + 'PSP_BL__LOAD_DBGDRV', 'PSP_BL__LOAD_HADDRV', + 'PSP_BL__LOAD_INTFDRV', 'PSP_BL__LOAD_IPKEYMGRDRV', + 'PSP_BL__LOAD_KEY_DATABASE', 'PSP_BL__LOAD_RASDRV', + 'PSP_BL__LOAD_SOCDRV', 'PSP_BL__LOAD_SOSDRV', + 'PSP_BL__LOAD_SYSDRV', 'PSP_BL__LOAD_TOS_SPL_TABLE', + 'PSP_CMD_BUFFER_SIZE', 'PSP_DTM_SHARED_MEM_SIZE', + 'PSP_ERR_UNKNOWN_COMMAND', 'PSP_FENCE_BUFFER_SIZE', + 'PSP_FW_NAME_LEN', 'PSP_FW_TYPE_MAX_INDEX', + 'PSP_FW_TYPE_PSP_DBG_DRV', 'PSP_FW_TYPE_PSP_INTF_DRV', + 'PSP_FW_TYPE_PSP_IPKEYMGR_DRV', 'PSP_FW_TYPE_PSP_KDB', + 'PSP_FW_TYPE_PSP_RAS_DRV', 'PSP_FW_TYPE_PSP_RL', + 'PSP_FW_TYPE_PSP_SOC_DRV', 'PSP_FW_TYPE_PSP_SOS', + 'PSP_FW_TYPE_PSP_SPL', 'PSP_FW_TYPE_PSP_SYS_DRV', + 'PSP_FW_TYPE_PSP_TOC', 'PSP_FW_TYPE_UNKOWN', + 'PSP_GFX_CMD_BUF_VERSION', 'PSP_HDCP_SHARED_MEM_SIZE', + 'PSP_HEADER_SIZE', 'PSP_MEM_TRAIN_COLD_BOOT', + 'PSP_MEM_TRAIN_INIT_FAILED', 'PSP_MEM_TRAIN_INIT_SUCCESS', + 'PSP_MEM_TRAIN_NOT_SUPPORT', 'PSP_MEM_TRAIN_RESERVE_SUCCESS', + 'PSP_MEM_TRAIN_RESTORE', 'PSP_MEM_TRAIN_RESUME', + 'PSP_MEM_TRAIN_SAVE', 'PSP_MEM_TRAIN_SEND_LONG_MSG', + 'PSP_MEM_TRAIN_SEND_SHORT_MSG', 'PSP_MEM_TRAIN_SUPPORT', + 'PSP_RAP_SHARED_MEM_SIZE', 'PSP_RAS_SHARED_MEM_SIZE', + 'PSP_REG_IH_RB_CNTL', 'PSP_REG_IH_RB_CNTL_RING1', + 'PSP_REG_IH_RB_CNTL_RING2', 'PSP_REG_LAST', + 'PSP_RING_TYPE__INVALID', 'PSP_RING_TYPE__KM', + 'PSP_RING_TYPE__UM', 'PSP_RUNTIME_DB_COOKIE_ID', + 'PSP_RUNTIME_DB_DIAG_ENTRY_MAX_COUNT', 'PSP_RUNTIME_DB_OFFSET', + 'PSP_RUNTIME_DB_SIZE_IN_BYTES', 'PSP_RUNTIME_DB_VER_1', + 'PSP_RUNTIME_ENTRY_TYPE_BOOT_CONFIG', + 'PSP_RUNTIME_ENTRY_TYPE_INVALID', + 'PSP_RUNTIME_ENTRY_TYPE_MGPU_COMMON', + 'PSP_RUNTIME_ENTRY_TYPE_MGPU_WAFL', + 'PSP_RUNTIME_ENTRY_TYPE_MGPU_XGMI', + 'PSP_RUNTIME_ENTRY_TYPE_PPTABLE_ERR_STATUS', + 'PSP_RUNTIME_ENTRY_TYPE_TEST', + 'PSP_SECUREDISPLAY_SHARED_MEM_SIZE', 'PSP_TMR_ALIGNMENT', + 'PSP_XGMI_SHARED_MEM_SIZE', 'PWR_HWID', 'PWR_HWIP', 'RSMU_HWIP', + 'SATA_HWID', 'SCPM_DISABLE', 'SCPM_ENABLE', + 'SCPM_ENABLE_WITH_SCPM_ERR', 'SDMA0_HWID', 'SDMA0_HWIP', + 'SDMA1_HWID', 'SDMA1_HWIP', 'SDMA2_HWID', 'SDMA2_HWIP', + 'SDMA3_HWID', 'SDMA3_HWIP', 'SDMA4_HWIP', 'SDMA5_HWIP', + 'SDMA6_HWIP', 'SDMA7_HWIP', 'SDPMUX_HWID', 'SMUIO_HWID', + 'SMUIO_HWIP', 'SOC15_IH_CLIENTID_ACP', 'SOC15_IH_CLIENTID_ATHUB', + 'SOC15_IH_CLIENTID_ATS', 'SOC15_IH_CLIENTID_BIF', + 'SOC15_IH_CLIENTID_DCE', 'SOC15_IH_CLIENTID_DF', + 'SOC15_IH_CLIENTID_EA', 'SOC15_IH_CLIENTID_GRBM_CP', + 'SOC15_IH_CLIENTID_IH', 'SOC15_IH_CLIENTID_ISP', + 'SOC15_IH_CLIENTID_MAX', 'SOC15_IH_CLIENTID_MP0', + 'SOC15_IH_CLIENTID_MP1', 'SOC15_IH_CLIENTID_PCIE0', + 'SOC15_IH_CLIENTID_PWR', 'SOC15_IH_CLIENTID_RESERVED', + 'SOC15_IH_CLIENTID_RLC', 'SOC15_IH_CLIENTID_ROM_SMUIO', + 'SOC15_IH_CLIENTID_SDMA0', 'SOC15_IH_CLIENTID_SDMA1', + 'SOC15_IH_CLIENTID_SDMA2', 'SOC15_IH_CLIENTID_SDMA3', + 'SOC15_IH_CLIENTID_SDMA3_Sienna_Cichlid', + 'SOC15_IH_CLIENTID_SDMA4', 'SOC15_IH_CLIENTID_SDMA5', + 'SOC15_IH_CLIENTID_SDMA6', 'SOC15_IH_CLIENTID_SDMA7', + 'SOC15_IH_CLIENTID_SE0SH', 'SOC15_IH_CLIENTID_SE1SH', + 'SOC15_IH_CLIENTID_SE2SH', 'SOC15_IH_CLIENTID_SE3SH', + 'SOC15_IH_CLIENTID_THM', 'SOC15_IH_CLIENTID_UTCL2', + 'SOC15_IH_CLIENTID_UTCL2LOG', 'SOC15_IH_CLIENTID_UVD', + 'SOC15_IH_CLIENTID_UVD1', 'SOC15_IH_CLIENTID_VCE0', + 'SOC15_IH_CLIENTID_VCE1', 'SOC15_IH_CLIENTID_VCN', + 'SOC15_IH_CLIENTID_VCN1', 'SOC15_IH_CLIENTID_VMC', + 'SOC15_IH_CLIENTID_VMC1', 'SOC15_IH_CLIENTID_XDMA', + 'SOC21_IH_CLIENTID_ATHUB', 'SOC21_IH_CLIENTID_BIF', + 'SOC21_IH_CLIENTID_DCN', 'SOC21_IH_CLIENTID_DF', + 'SOC21_IH_CLIENTID_GFX', 'SOC21_IH_CLIENTID_GRBM_CP', + 'SOC21_IH_CLIENTID_IH', 'SOC21_IH_CLIENTID_IMU', + 'SOC21_IH_CLIENTID_ISP', 'SOC21_IH_CLIENTID_LSDMA', + 'SOC21_IH_CLIENTID_MAX', 'SOC21_IH_CLIENTID_MP0', + 'SOC21_IH_CLIENTID_MP1', 'SOC21_IH_CLIENTID_MP3', + 'SOC21_IH_CLIENTID_PWR', 'SOC21_IH_CLIENTID_RLC', + 'SOC21_IH_CLIENTID_ROM_SMUIO', 'SOC21_IH_CLIENTID_THM', + 'SOC21_IH_CLIENTID_VCN', 'SOC21_IH_CLIENTID_VCN1', + 'SOC21_IH_CLIENTID_VMC', 'SOC21_IH_CLIENTID_VPE', + 'SOC21_IH_CLIENTID_VPE1', 'SST_HWID', 'SYSTEMHUB_HWID', + 'TA_FW_TYPE_MAX_INDEX', 'TA_FW_TYPE_PSP_ASD', + 'TA_FW_TYPE_PSP_DTM', 'TA_FW_TYPE_PSP_HDCP', 'TA_FW_TYPE_PSP_RAP', + 'TA_FW_TYPE_PSP_RAS', 'TA_FW_TYPE_PSP_SECUREDISPLAY', + 'TA_FW_TYPE_PSP_XGMI', 'TA_FW_TYPE_UNKOWN', 'TA_TYPE_DTM', + 'TA_TYPE_HDCP', 'TA_TYPE_MAX_INDEX', 'TA_TYPE_RAP', 'TA_TYPE_RAS', + 'TA_TYPE_SECUREDISPLAY', 'TA_TYPE_XGMI', + 'TEE_ERROR_NOT_SUPPORTED', 'TEE_SUCCESS', 'THM_HWID', 'THM_HWIP', + 'TOTAL_TABLES', 'UMC_HWID', 'UMC_HWIP', 'USB_HWID', 'UVD_HWID', + 'UVD_HWIP', 'V11_STRUCTS_H_', 'V12_STRUCTS_H_', 'VCE_HWID', + 'VCE_HWIP', 'VCN1_HWIP', 'VCN_HWID', 'VCN_HWIP', 'VCN_INFO', + 'VCN_INFO_TABLE_ID', 'VCN_INFO_TABLE_MAX_NUM_INSTANCES', + 'VPE_HWID', 'VPE_HWIP', 'WAFLC_HWID', 'XCD0_NODEID', + 'XCD1_NODEID', 'XCD2_NODEID', 'XCD3_NODEID', 'XCD4_NODEID', + 'XCD5_NODEID', 'XCD6_NODEID', 'XCD7_NODEID', 'XDMA_HWID', + 'XGBE_HWID', 'XGMI_HWID', 'XGMI_HWIP', '_DISCOVERY_H_', + '_PSP_TEE_GFX_IF_H_', '__AMDGPU_IRQ_H__', '__AMDGPU_PSP_H__', + '__AMDGPU_UCODE_H__', '__AMDGPU_VM_H__', + '__SOC15_IH_CLIENTID_H__', 'amd_hw_ip_block_type', + 'amdgpu_firmware_load_type', 'amdgpu_interrupt_state', + 'amdgpu_vm_level', 'binary_header', 'bool', 'c__EA_table', + 'die_header', 'die_info', 'harvest_info', 'harvest_info_header', + 'harvest_table', 'hw_id_map', 'int16_t', 'int32_t', 'int8_t', + 'interrupt_node_id_per_aid', 'ip', 'ip_discovery_header', + 'ip_structure', 'ip_v3', 'ip_v4', 'psp_bootloader_cmd', + 'psp_fw_type', 'psp_gfx_boot_config', 'psp_gfx_boot_config_cmd', + 'psp_gfx_cmd_id', 'psp_gfx_crtl_cmd_id', 'psp_gfx_fw_type', + 'psp_memory_training_init_flag', 'psp_memory_training_ops', + 'psp_reg_prog_id', 'psp_ring_type', + 'psp_runtime_boot_cfg_feature', 'psp_runtime_entry_type', + 'psp_runtime_scpm_authentication', 'psp_shared_mem_size', + 'soc15_ih_clientid', 'soc15_ih_clientid_name', + 'soc21_ih_clientid', 'struct__fuse_data_bits', + 'struct_amdgpu_device', 'struct_amdgpu_firmware_info', + 'struct_amdgpu_iv_entry', 'struct_binary_header', + 'struct_common_firmware_header', 'struct_die', + 'struct_die_header', 'struct_die_info', + 'struct_dmcu_firmware_header_v1_0', + 'struct_dmcub_firmware_header_v1_0', 'struct_firmware', + 'struct_gc_info_v1_0', 'struct_gc_info_v1_1', + 'struct_gc_info_v1_2', 'struct_gc_info_v1_3', + 'struct_gc_info_v2_0', 'struct_gc_info_v2_1', + 'struct_gfx_firmware_header_v1_0', + 'struct_gfx_firmware_header_v2_0', + 'struct_gpu_info_firmware_header_v1_0', + 'struct_gpu_info_firmware_v1_0', 'struct_gpu_info_firmware_v1_1', + 'struct_gpu_info_header', 'struct_harvest_info', + 'struct_harvest_info_header', 'struct_harvest_table', + 'struct_imu_firmware_header_v1_0', 'struct_ip', + 'struct_ip_discovery_header', 'struct_ip_discovery_header_0_0', + 'struct_ip_structure', 'struct_ip_v3', 'struct_ip_v4', + 'struct_mall_info_header', 'struct_mall_info_v1_0', + 'struct_mall_info_v2_0', 'struct_mc_firmware_header_v1_0', + 'struct_mes_firmware_header_v1_0', 'struct_nps_info_header', + 'struct_nps_info_v1_0', 'struct_nps_instance_info_v1_0', + 'struct_psp_bin_desc', 'struct_psp_context', + 'struct_psp_firmware_header_v1_0', + 'struct_psp_firmware_header_v1_1', + 'struct_psp_firmware_header_v1_2', + 'struct_psp_firmware_header_v1_3', + 'struct_psp_firmware_header_v2_0', + 'struct_psp_firmware_header_v2_1', 'struct_psp_fw_bin_desc', + 'struct_psp_fw_legacy_bin_desc', 'struct_psp_gfx_buf_desc', + 'struct_psp_gfx_buf_list', 'struct_psp_gfx_cmd_boot_cfg', + 'struct_psp_gfx_cmd_invoke_cmd', 'struct_psp_gfx_cmd_load_ip_fw', + 'struct_psp_gfx_cmd_load_ta', 'struct_psp_gfx_cmd_load_toc', + 'struct_psp_gfx_cmd_reg_prog', 'struct_psp_gfx_cmd_resp', + 'struct_psp_gfx_cmd_save_restore_ip_fw', + 'struct_psp_gfx_cmd_setup_tmr', + 'struct_psp_gfx_cmd_setup_tmr_0_bitfield', + 'struct_psp_gfx_cmd_sriov_spatial_part', + 'struct_psp_gfx_cmd_unload_ta', 'struct_psp_gfx_ctrl', + 'struct_psp_gfx_rb_frame', 'struct_psp_gfx_resp', + 'struct_psp_gfx_uresp_bootcfg', + 'struct_psp_gfx_uresp_fwar_db_info', + 'struct_psp_gfx_uresp_reserved', 'struct_psp_xgmi_node_info', + 'struct_psp_xgmi_topology_info', + 'struct_rlc_firmware_header_v1_0', + 'struct_rlc_firmware_header_v2_0', + 'struct_rlc_firmware_header_v2_1', + 'struct_rlc_firmware_header_v2_2', + 'struct_rlc_firmware_header_v2_3', + 'struct_rlc_firmware_header_v2_4', + 'struct_sdma_firmware_header_v1_0', + 'struct_sdma_firmware_header_v1_1', + 'struct_sdma_firmware_header_v2_0', + 'struct_sdma_firmware_header_v3_0', + 'struct_smc_firmware_header_v1_0', + 'struct_smc_firmware_header_v2_0', + 'struct_smc_firmware_header_v2_1', + 'struct_smc_soft_pptable_entry', 'struct_ta_firmware_header_v1_0', + 'struct_ta_firmware_header_v2_0', 'struct_table_info', + 'struct_umsch_mm_firmware_header_v1_0', 'struct_v11_compute_mqd', + 'struct_v11_gfx_mqd', 'struct_v11_sdma_mqd', + 'struct_v12_compute_mqd', 'struct_v12_gfx_mqd', + 'struct_v12_sdma_mqd', 'struct_vcn_info_header', + 'struct_vcn_info_v1_0', 'struct_vcn_instance_info_v1_0', + 'struct_vpe_firmware_header_v1_0', 'ta_fw_type', 'ta_type_id', + 'table', 'table__enumvalues', 'table_info', 'tee_error_code', + 'u32', 'uint16_t', 'uint32_t', 'uint64_t', 'uint8_t', + 'union__fuse_data', 'union_amdgpu_firmware_header', 'union_die_0', + 'union_ip_discovery_header_0', 'union_psp_gfx_cmd_setup_tmr_0', + 'union_psp_gfx_commands', 'union_psp_gfx_uresp'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/navi10.py b/tinygrad_repo/tinygrad/runtime/autogen/am/navi10.py new file mode 100644 index 0000000000..1960cec8c7 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/navi10.py @@ -0,0 +1,40774 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + + + +_navi10_ENUM_HEADER = True # macro +ENUMS_GDS_PERFCOUNT_SELECT_H = True # macro +SQ_WAVE_TYPE_PS0 = 0x00000000 # macro +SQIND_GLOBAL_REGS_OFFSET = 0x00000000 # macro +SQIND_GLOBAL_REGS_SIZE = 0x00000008 # macro +SQIND_LOCAL_REGS_OFFSET = 0x00000008 # macro +SQIND_LOCAL_REGS_SIZE = 0x00000008 # macro +SQIND_WAVE_HWREGS_OFFSET = 0x00000100 # macro +SQIND_WAVE_HWREGS_SIZE = 0x00000100 # macro +SQIND_WAVE_SGPRS_OFFSET = 0x00000200 # macro +SQIND_WAVE_SGPRS_SIZE = 0x00000200 # macro +SQIND_WAVE_VGPRS_OFFSET = 0x00000400 # macro +SQIND_WAVE_VGPRS_SIZE = 0x00000400 # macro +SQ_GFXDEC_BEGIN = 0x0000a000 # macro +SQ_GFXDEC_END = 0x0000c000 # macro +SQ_GFXDEC_STATE_ID_SHIFT = 0x0000000a # macro +SQDEC_BEGIN = 0x00002300 # macro +SQDEC_END = 0x000023ff # macro +SQPERFSDEC_BEGIN = 0x0000d9c0 # macro +SQPERFSDEC_END = 0x0000da40 # macro +SQPERFDDEC_BEGIN = 0x0000d1c0 # macro +SQPERFDDEC_END = 0x0000d240 # macro +SQGFXUDEC_BEGIN = 0x0000c330 # macro +SQGFXUDEC_END = 0x0000c380 # macro +SQPWRDEC_BEGIN = 0x0000f08c # macro +SQPWRDEC_END = 0x0000f094 # macro +SQ_DISPATCHER_GFX_MIN = 0x00000010 # macro +SQ_DISPATCHER_GFX_CNT_PER_RING = 0x00000008 # macro +SQ_MAX_PGM_SGPRS = 0x00000068 # macro +SQ_MAX_PGM_VGPRS = 0x00000100 # macro +SQ_EX_MODE_EXCP_VALU_BASE = 0x00000000 # macro +SQ_EX_MODE_EXCP_VALU_SIZE = 0x00000007 # macro +SQ_EX_MODE_EXCP_INVALID = 0x00000000 # macro +SQ_EX_MODE_EXCP_INPUT_DENORM = 0x00000001 # macro +SQ_EX_MODE_EXCP_DIV0 = 0x00000002 # macro +SQ_EX_MODE_EXCP_OVERFLOW = 0x00000003 # macro +SQ_EX_MODE_EXCP_UNDERFLOW = 0x00000004 # macro +SQ_EX_MODE_EXCP_INEXACT = 0x00000005 # macro +SQ_EX_MODE_EXCP_INT_DIV0 = 0x00000006 # macro +SQ_EX_MODE_EXCP_ADDR_WATCH0 = 0x00000007 # macro +SQ_EX_MODE_EXCP_MEM_VIOL = 0x00000008 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH1 = 0x00000000 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH2 = 0x00000001 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH3 = 0x00000002 # macro +INST_ID_PRIV_START = 0x80000000 # macro +INST_ID_ECC_INTERRUPT_MSG = 0xfffffff0 # macro +INST_ID_TTRACE_NEW_PC_MSG = 0xfffffff1 # macro +INST_ID_HW_TRAP = 0xfffffff2 # macro +INST_ID_KILL_SEQ = 0xfffffff3 # macro +INST_ID_SPI_WREXEC = 0xfffffff4 # macro +INST_ID_HOST_REG_TRAP_MSG = 0xfffffffe # macro +SIMM16_WAITCNT_VM_CNT_START = 0x00000000 # macro +SIMM16_WAITCNT_VM_CNT_SIZE = 0x00000004 # macro +SIMM16_WAITCNT_EXP_CNT_START = 0x00000004 # macro +SIMM16_WAITCNT_EXP_CNT_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_LGKM_CNT_START = 0x00000008 # macro +SIMM16_WAITCNT_LGKM_CNT_SIZE = 0x00000004 # macro +SIMM16_WAITCNT_VM_CNT_HI_START = 0x0000000e # macro +SIMM16_WAITCNT_VM_CNT_HI_SIZE = 0x00000002 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_START = 0x00000000 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_START = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_START = 0x00000002 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_START = 0x00000008 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_START = 0x00000009 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_START = 0x0000000c # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE = 0x00000004 # macro +SQ_EDC_FUE_CNTL_SIMD0 = 0x00000000 # macro +SQ_EDC_FUE_CNTL_SIMD1 = 0x00000001 # macro +SQ_EDC_FUE_CNTL_SIMD2 = 0x00000002 # macro +SQ_EDC_FUE_CNTL_SIMD3 = 0x00000003 # macro +SQ_EDC_FUE_CNTL_SQ = 0x00000004 # macro +SQ_EDC_FUE_CNTL_LDS = 0x00000005 # macro +SQ_EDC_FUE_CNTL_TD = 0x00000006 # macro +SQ_EDC_FUE_CNTL_TA = 0x00000007 # macro +SQ_EDC_FUE_CNTL_TCP = 0x00000008 # macro +CSDATA_TYPE_WIDTH = 0x00000002 # macro +CSDATA_ADDR_WIDTH = 0x00000007 # macro +CSDATA_DATA_WIDTH = 0x00000020 # macro +CSCNTL_TYPE_WIDTH = 0x00000002 # macro +CSCNTL_ADDR_WIDTH = 0x00000007 # macro +CSCNTL_DATA_WIDTH = 0x00000020 # macro +GSTHREADID_SIZE = 0x00000002 # macro +SEM_ECC_ERROR = 0x00000000 # macro +SEM_TRANS_ERROR = 0x00000001 # macro +SEM_RESP_FAILED = 0x00000002 # macro +SEM_RESP_PASSED = 0x00000003 # macro +IQ_QUEUE_SLEEP = 0x00000000 # macro +IQ_OFFLOAD_RETRY = 0x00000001 # macro +IQ_SCH_WAVE_MSG = 0x00000002 # macro +IQ_SEM_REARM = 0x00000003 # macro +IQ_DEQUEUE_RETRY = 0x00000004 # macro +IQ_INTR_TYPE_PQ = 0x00000000 # macro +IQ_INTR_TYPE_IB = 0x00000001 # macro +IQ_INTR_TYPE_MQD = 0x00000002 # macro +VMID_SZ = 0x00000004 # macro +CONFIG_SPACE_START = 0x00002000 # macro +CONFIG_SPACE_END = 0x00009fff # macro +CONFIG_SPACE1_START = 0x00002000 # macro +CONFIG_SPACE1_END = 0x00002bff # macro +CONFIG_SPACE2_START = 0x00003000 # macro +CONFIG_SPACE2_END = 0x00009fff # macro +UCONFIG_SPACE_START = 0x0000c000 # macro +UCONFIG_SPACE_END = 0x0000ffff # macro +PERSISTENT_SPACE_START = 0x00002c00 # macro +PERSISTENT_SPACE_END = 0x00002fff # macro +CONTEXT_SPACE_START = 0x0000a000 # macro +CONTEXT_SPACE_END = 0x0000bfff # macro +ROM_SIGNATURE = 0x0000aa55 # macro +IP_USB_PD_REVISION_ID = 0x00000000 # macro + +# values for enumeration 'GDS_PERFCOUNT_SELECT' +GDS_PERFCOUNT_SELECT__enumvalues = { + 0: 'GDS_PERF_SEL_DS_ADDR_CONFL', + 1: 'GDS_PERF_SEL_DS_BANK_CONFL', + 2: 'GDS_PERF_SEL_WBUF_FLUSH', + 3: 'GDS_PERF_SEL_WR_COMP', + 4: 'GDS_PERF_SEL_WBUF_WR', + 5: 'GDS_PERF_SEL_RBUF_HIT', + 6: 'GDS_PERF_SEL_RBUF_MISS', + 7: 'GDS_PERF_SEL_SE0_SH0_NORET', + 8: 'GDS_PERF_SEL_SE0_SH0_RET', + 9: 'GDS_PERF_SEL_SE0_SH0_ORD_CNT', + 10: 'GDS_PERF_SEL_SE0_SH0_2COMP_REQ', + 11: 'GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID', + 12: 'GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID', + 13: 'GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD', + 14: 'GDS_PERF_SEL_SE0_SH0_GDS_WR_OP', + 15: 'GDS_PERF_SEL_SE0_SH0_GDS_RD_OP', + 16: 'GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP', + 17: 'GDS_PERF_SEL_SE0_SH0_GDS_REL_OP', + 18: 'GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP', + 19: 'GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP', + 20: 'GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP', + 21: 'GDS_PERF_SEL_SE0_SH1_NORET', + 22: 'GDS_PERF_SEL_SE0_SH1_RET', + 23: 'GDS_PERF_SEL_SE0_SH1_ORD_CNT', + 24: 'GDS_PERF_SEL_SE0_SH1_2COMP_REQ', + 25: 'GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID', + 26: 'GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID', + 27: 'GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD', + 28: 'GDS_PERF_SEL_SE0_SH1_GDS_WR_OP', + 29: 'GDS_PERF_SEL_SE0_SH1_GDS_RD_OP', + 30: 'GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP', + 31: 'GDS_PERF_SEL_SE0_SH1_GDS_REL_OP', + 32: 'GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP', + 33: 'GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP', + 34: 'GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP', + 35: 'GDS_PERF_SEL_SE1_SH0_NORET', + 36: 'GDS_PERF_SEL_SE1_SH0_RET', + 37: 'GDS_PERF_SEL_SE1_SH0_ORD_CNT', + 38: 'GDS_PERF_SEL_SE1_SH0_2COMP_REQ', + 39: 'GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID', + 40: 'GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID', + 41: 'GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD', + 42: 'GDS_PERF_SEL_SE1_SH0_GDS_WR_OP', + 43: 'GDS_PERF_SEL_SE1_SH0_GDS_RD_OP', + 44: 'GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP', + 45: 'GDS_PERF_SEL_SE1_SH0_GDS_REL_OP', + 46: 'GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP', + 47: 'GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP', + 48: 'GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP', + 49: 'GDS_PERF_SEL_SE1_SH1_NORET', + 50: 'GDS_PERF_SEL_SE1_SH1_RET', + 51: 'GDS_PERF_SEL_SE1_SH1_ORD_CNT', + 52: 'GDS_PERF_SEL_SE1_SH1_2COMP_REQ', + 53: 'GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID', + 54: 'GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID', + 55: 'GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD', + 56: 'GDS_PERF_SEL_SE1_SH1_GDS_WR_OP', + 57: 'GDS_PERF_SEL_SE1_SH1_GDS_RD_OP', + 58: 'GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP', + 59: 'GDS_PERF_SEL_SE1_SH1_GDS_REL_OP', + 60: 'GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP', + 61: 'GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP', + 62: 'GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP', + 63: 'GDS_PERF_SEL_SE2_SH0_NORET', + 64: 'GDS_PERF_SEL_SE2_SH0_RET', + 65: 'GDS_PERF_SEL_SE2_SH0_ORD_CNT', + 66: 'GDS_PERF_SEL_SE2_SH0_2COMP_REQ', + 67: 'GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID', + 68: 'GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID', + 69: 'GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD', + 70: 'GDS_PERF_SEL_SE2_SH0_GDS_WR_OP', + 71: 'GDS_PERF_SEL_SE2_SH0_GDS_RD_OP', + 72: 'GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP', + 73: 'GDS_PERF_SEL_SE2_SH0_GDS_REL_OP', + 74: 'GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP', + 75: 'GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP', + 76: 'GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP', + 77: 'GDS_PERF_SEL_SE2_SH1_NORET', + 78: 'GDS_PERF_SEL_SE2_SH1_RET', + 79: 'GDS_PERF_SEL_SE2_SH1_ORD_CNT', + 80: 'GDS_PERF_SEL_SE2_SH1_2COMP_REQ', + 81: 'GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID', + 82: 'GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID', + 83: 'GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD', + 84: 'GDS_PERF_SEL_SE2_SH1_GDS_WR_OP', + 85: 'GDS_PERF_SEL_SE2_SH1_GDS_RD_OP', + 86: 'GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP', + 87: 'GDS_PERF_SEL_SE2_SH1_GDS_REL_OP', + 88: 'GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP', + 89: 'GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP', + 90: 'GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP', + 91: 'GDS_PERF_SEL_SE3_SH0_NORET', + 92: 'GDS_PERF_SEL_SE3_SH0_RET', + 93: 'GDS_PERF_SEL_SE3_SH0_ORD_CNT', + 94: 'GDS_PERF_SEL_SE3_SH0_2COMP_REQ', + 95: 'GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID', + 96: 'GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID', + 97: 'GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD', + 98: 'GDS_PERF_SEL_SE3_SH0_GDS_WR_OP', + 99: 'GDS_PERF_SEL_SE3_SH0_GDS_RD_OP', + 100: 'GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP', + 101: 'GDS_PERF_SEL_SE3_SH0_GDS_REL_OP', + 102: 'GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP', + 103: 'GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP', + 104: 'GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP', + 105: 'GDS_PERF_SEL_SE3_SH1_NORET', + 106: 'GDS_PERF_SEL_SE3_SH1_RET', + 107: 'GDS_PERF_SEL_SE3_SH1_ORD_CNT', + 108: 'GDS_PERF_SEL_SE3_SH1_2COMP_REQ', + 109: 'GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID', + 110: 'GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID', + 111: 'GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD', + 112: 'GDS_PERF_SEL_SE3_SH1_GDS_WR_OP', + 113: 'GDS_PERF_SEL_SE3_SH1_GDS_RD_OP', + 114: 'GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP', + 115: 'GDS_PERF_SEL_SE3_SH1_GDS_REL_OP', + 116: 'GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP', + 117: 'GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP', + 118: 'GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP', + 119: 'GDS_PERF_SEL_GWS_RELEASED', + 120: 'GDS_PERF_SEL_GWS_BYPASS', +} +GDS_PERF_SEL_DS_ADDR_CONFL = 0 +GDS_PERF_SEL_DS_BANK_CONFL = 1 +GDS_PERF_SEL_WBUF_FLUSH = 2 +GDS_PERF_SEL_WR_COMP = 3 +GDS_PERF_SEL_WBUF_WR = 4 +GDS_PERF_SEL_RBUF_HIT = 5 +GDS_PERF_SEL_RBUF_MISS = 6 +GDS_PERF_SEL_SE0_SH0_NORET = 7 +GDS_PERF_SEL_SE0_SH0_RET = 8 +GDS_PERF_SEL_SE0_SH0_ORD_CNT = 9 +GDS_PERF_SEL_SE0_SH0_2COMP_REQ = 10 +GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID = 11 +GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID = 12 +GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD = 13 +GDS_PERF_SEL_SE0_SH0_GDS_WR_OP = 14 +GDS_PERF_SEL_SE0_SH0_GDS_RD_OP = 15 +GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP = 16 +GDS_PERF_SEL_SE0_SH0_GDS_REL_OP = 17 +GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP = 18 +GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP = 19 +GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP = 20 +GDS_PERF_SEL_SE0_SH1_NORET = 21 +GDS_PERF_SEL_SE0_SH1_RET = 22 +GDS_PERF_SEL_SE0_SH1_ORD_CNT = 23 +GDS_PERF_SEL_SE0_SH1_2COMP_REQ = 24 +GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID = 25 +GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID = 26 +GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD = 27 +GDS_PERF_SEL_SE0_SH1_GDS_WR_OP = 28 +GDS_PERF_SEL_SE0_SH1_GDS_RD_OP = 29 +GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP = 30 +GDS_PERF_SEL_SE0_SH1_GDS_REL_OP = 31 +GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP = 32 +GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP = 33 +GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP = 34 +GDS_PERF_SEL_SE1_SH0_NORET = 35 +GDS_PERF_SEL_SE1_SH0_RET = 36 +GDS_PERF_SEL_SE1_SH0_ORD_CNT = 37 +GDS_PERF_SEL_SE1_SH0_2COMP_REQ = 38 +GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID = 39 +GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID = 40 +GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD = 41 +GDS_PERF_SEL_SE1_SH0_GDS_WR_OP = 42 +GDS_PERF_SEL_SE1_SH0_GDS_RD_OP = 43 +GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP = 44 +GDS_PERF_SEL_SE1_SH0_GDS_REL_OP = 45 +GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP = 46 +GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP = 47 +GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP = 48 +GDS_PERF_SEL_SE1_SH1_NORET = 49 +GDS_PERF_SEL_SE1_SH1_RET = 50 +GDS_PERF_SEL_SE1_SH1_ORD_CNT = 51 +GDS_PERF_SEL_SE1_SH1_2COMP_REQ = 52 +GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID = 53 +GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID = 54 +GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD = 55 +GDS_PERF_SEL_SE1_SH1_GDS_WR_OP = 56 +GDS_PERF_SEL_SE1_SH1_GDS_RD_OP = 57 +GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP = 58 +GDS_PERF_SEL_SE1_SH1_GDS_REL_OP = 59 +GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP = 60 +GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP = 61 +GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP = 62 +GDS_PERF_SEL_SE2_SH0_NORET = 63 +GDS_PERF_SEL_SE2_SH0_RET = 64 +GDS_PERF_SEL_SE2_SH0_ORD_CNT = 65 +GDS_PERF_SEL_SE2_SH0_2COMP_REQ = 66 +GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID = 67 +GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID = 68 +GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD = 69 +GDS_PERF_SEL_SE2_SH0_GDS_WR_OP = 70 +GDS_PERF_SEL_SE2_SH0_GDS_RD_OP = 71 +GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP = 72 +GDS_PERF_SEL_SE2_SH0_GDS_REL_OP = 73 +GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP = 74 +GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP = 75 +GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP = 76 +GDS_PERF_SEL_SE2_SH1_NORET = 77 +GDS_PERF_SEL_SE2_SH1_RET = 78 +GDS_PERF_SEL_SE2_SH1_ORD_CNT = 79 +GDS_PERF_SEL_SE2_SH1_2COMP_REQ = 80 +GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID = 81 +GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID = 82 +GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD = 83 +GDS_PERF_SEL_SE2_SH1_GDS_WR_OP = 84 +GDS_PERF_SEL_SE2_SH1_GDS_RD_OP = 85 +GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP = 86 +GDS_PERF_SEL_SE2_SH1_GDS_REL_OP = 87 +GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP = 88 +GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP = 89 +GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP = 90 +GDS_PERF_SEL_SE3_SH0_NORET = 91 +GDS_PERF_SEL_SE3_SH0_RET = 92 +GDS_PERF_SEL_SE3_SH0_ORD_CNT = 93 +GDS_PERF_SEL_SE3_SH0_2COMP_REQ = 94 +GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID = 95 +GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID = 96 +GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD = 97 +GDS_PERF_SEL_SE3_SH0_GDS_WR_OP = 98 +GDS_PERF_SEL_SE3_SH0_GDS_RD_OP = 99 +GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP = 100 +GDS_PERF_SEL_SE3_SH0_GDS_REL_OP = 101 +GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP = 102 +GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP = 103 +GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP = 104 +GDS_PERF_SEL_SE3_SH1_NORET = 105 +GDS_PERF_SEL_SE3_SH1_RET = 106 +GDS_PERF_SEL_SE3_SH1_ORD_CNT = 107 +GDS_PERF_SEL_SE3_SH1_2COMP_REQ = 108 +GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID = 109 +GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID = 110 +GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD = 111 +GDS_PERF_SEL_SE3_SH1_GDS_WR_OP = 112 +GDS_PERF_SEL_SE3_SH1_GDS_RD_OP = 113 +GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP = 114 +GDS_PERF_SEL_SE3_SH1_GDS_REL_OP = 115 +GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP = 116 +GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP = 117 +GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP = 118 +GDS_PERF_SEL_GWS_RELEASED = 119 +GDS_PERF_SEL_GWS_BYPASS = 120 +GDS_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'GATCL1RequestType' +GATCL1RequestType__enumvalues = { + 0: 'GATCL1_TYPE_NORMAL', + 1: 'GATCL1_TYPE_SHOOTDOWN', + 2: 'GATCL1_TYPE_BYPASS', +} +GATCL1_TYPE_NORMAL = 0 +GATCL1_TYPE_SHOOTDOWN = 1 +GATCL1_TYPE_BYPASS = 2 +GATCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1RequestType' +UTCL1RequestType__enumvalues = { + 0: 'UTCL1_TYPE_NORMAL', + 1: 'UTCL1_TYPE_SHOOTDOWN', + 2: 'UTCL1_TYPE_BYPASS', +} +UTCL1_TYPE_NORMAL = 0 +UTCL1_TYPE_SHOOTDOWN = 1 +UTCL1_TYPE_BYPASS = 2 +UTCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1FaultType' +UTCL1FaultType__enumvalues = { + 0: 'UTCL1_XNACK_SUCCESS', + 1: 'UTCL1_XNACK_RETRY', + 2: 'UTCL1_XNACK_PRT', + 3: 'UTCL1_XNACK_NO_RETRY', +} +UTCL1_XNACK_SUCCESS = 0 +UTCL1_XNACK_RETRY = 1 +UTCL1_XNACK_PRT = 2 +UTCL1_XNACK_NO_RETRY = 3 +UTCL1FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0RequestType' +UTCL0RequestType__enumvalues = { + 0: 'UTCL0_TYPE_NORMAL', + 1: 'UTCL0_TYPE_SHOOTDOWN', + 2: 'UTCL0_TYPE_BYPASS', +} +UTCL0_TYPE_NORMAL = 0 +UTCL0_TYPE_SHOOTDOWN = 1 +UTCL0_TYPE_BYPASS = 2 +UTCL0RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0FaultType' +UTCL0FaultType__enumvalues = { + 0: 'UTCL0_XNACK_SUCCESS', + 1: 'UTCL0_XNACK_RETRY', + 2: 'UTCL0_XNACK_PRT', + 3: 'UTCL0_XNACK_NO_RETRY', +} +UTCL0_XNACK_SUCCESS = 0 +UTCL0_XNACK_RETRY = 1 +UTCL0_XNACK_PRT = 2 +UTCL0_XNACK_NO_RETRY = 3 +UTCL0FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'VMEMCMD_RETURN_ORDER' +VMEMCMD_RETURN_ORDER__enumvalues = { + 0: 'VMEMCMD_RETURN_OUT_OF_ORDER', + 1: 'VMEMCMD_RETURN_IN_ORDER', + 2: 'VMEMCMD_RETURN_IN_ORDER_READ', +} +VMEMCMD_RETURN_OUT_OF_ORDER = 0 +VMEMCMD_RETURN_IN_ORDER = 1 +VMEMCMD_RETURN_IN_ORDER_READ = 2 +VMEMCMD_RETURN_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'GL0V_CACHE_POLICIES' +GL0V_CACHE_POLICIES__enumvalues = { + 0: 'GL0V_CACHE_POLICY_MISS_LRU', + 1: 'GL0V_CACHE_POLICY_MISS_EVICT', + 2: 'GL0V_CACHE_POLICY_HIT_LRU', + 3: 'GL0V_CACHE_POLICY_HIT_EVICT', +} +GL0V_CACHE_POLICY_MISS_LRU = 0 +GL0V_CACHE_POLICY_MISS_EVICT = 1 +GL0V_CACHE_POLICY_HIT_LRU = 2 +GL0V_CACHE_POLICY_HIT_EVICT = 3 +GL0V_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_POLICIES' +GL1_CACHE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_POLICY_MISS_LRU', + 1: 'GL1_CACHE_POLICY_MISS_EVICT', + 2: 'GL1_CACHE_POLICY_HIT_LRU', + 3: 'GL1_CACHE_POLICY_HIT_EVICT', +} +GL1_CACHE_POLICY_MISS_LRU = 0 +GL1_CACHE_POLICY_MISS_EVICT = 1 +GL1_CACHE_POLICY_HIT_LRU = 2 +GL1_CACHE_POLICY_HIT_EVICT = 3 +GL1_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_STORE_POLICIES' +GL1_CACHE_STORE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_STORE_POLICY_BYPASS', +} +GL1_CACHE_STORE_POLICY_BYPASS = 0 +GL1_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_CACHE_POLICIES' +TCC_CACHE_POLICIES__enumvalues = { + 0: 'TCC_CACHE_POLICY_LRU', + 1: 'TCC_CACHE_POLICY_STREAM', +} +TCC_CACHE_POLICY_LRU = 0 +TCC_CACHE_POLICY_STREAM = 1 +TCC_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_MTYPE' +TCC_MTYPE__enumvalues = { + 0: 'MTYPE_NC', + 1: 'MTYPE_WC', + 2: 'MTYPE_CC', +} +MTYPE_NC = 0 +MTYPE_WC = 1 +MTYPE_CC = 2 +TCC_MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_CACHE_POLICIES' +GL2_CACHE_POLICIES__enumvalues = { + 0: 'GL2_CACHE_POLICY_LRU', + 1: 'GL2_CACHE_POLICY_STREAM', + 2: 'GL2_CACHE_POLICY_NOA', + 3: 'GL2_CACHE_POLICY_BYPASS', +} +GL2_CACHE_POLICY_LRU = 0 +GL2_CACHE_POLICY_STREAM = 1 +GL2_CACHE_POLICY_NOA = 2 +GL2_CACHE_POLICY_BYPASS = 3 +GL2_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'MTYPE' +MTYPE__enumvalues = { + 0: 'MTYPE_C_RW_US', + 1: 'MTYPE_RESERVED_1', + 2: 'MTYPE_C_RO_S', + 3: 'MTYPE_UC', + 4: 'MTYPE_C_RW_S', + 5: 'MTYPE_RESERVED_5', + 6: 'MTYPE_C_RO_US', + 7: 'MTYPE_RESERVED_7', +} +MTYPE_C_RW_US = 0 +MTYPE_RESERVED_1 = 1 +MTYPE_C_RO_S = 2 +MTYPE_UC = 3 +MTYPE_C_RW_S = 4 +MTYPE_RESERVED_5 = 5 +MTYPE_C_RO_US = 6 +MTYPE_RESERVED_7 = 7 +MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'RMI_CID' +RMI_CID__enumvalues = { + 0: 'RMI_CID_CC', + 1: 'RMI_CID_FC', + 2: 'RMI_CID_CM', + 3: 'RMI_CID_DC', + 4: 'RMI_CID_Z', + 5: 'RMI_CID_S', + 6: 'RMI_CID_TILE', + 7: 'RMI_CID_ZPCPSD', +} +RMI_CID_CC = 0 +RMI_CID_FC = 1 +RMI_CID_CM = 2 +RMI_CID_DC = 3 +RMI_CID_Z = 4 +RMI_CID_S = 5 +RMI_CID_TILE = 6 +RMI_CID_ZPCPSD = 7 +RMI_CID = ctypes.c_uint32 # enum + +# values for enumeration 'WritePolicy' +WritePolicy__enumvalues = { + 0: 'CACHE_LRU_WR', + 1: 'CACHE_STREAM', + 2: 'CACHE_BYPASS', + 3: 'UNCACHED_WR', +} +CACHE_LRU_WR = 0 +CACHE_STREAM = 1 +CACHE_BYPASS = 2 +UNCACHED_WR = 3 +WritePolicy = ctypes.c_uint32 # enum + +# values for enumeration 'ReadPolicy' +ReadPolicy__enumvalues = { + 0: 'CACHE_LRU_RD', + 1: 'CACHE_NOA', + 2: 'UNCACHED_RD', + 3: 'RESERVED_RDPOLICY', +} +CACHE_LRU_RD = 0 +CACHE_NOA = 1 +UNCACHED_RD = 2 +RESERVED_RDPOLICY = 3 +ReadPolicy = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_COUNTER_MODE' +PERFMON_COUNTER_MODE__enumvalues = { + 0: 'PERFMON_COUNTER_MODE_ACCUM', + 1: 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 2: 'PERFMON_COUNTER_MODE_MAX', + 3: 'PERFMON_COUNTER_MODE_DIRTY', + 4: 'PERFMON_COUNTER_MODE_SAMPLE', + 5: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 6: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 7: 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 8: 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 9: 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 15: 'PERFMON_COUNTER_MODE_RESERVED', +} +PERFMON_COUNTER_MODE_ACCUM = 0 +PERFMON_COUNTER_MODE_ACTIVE_CYCLES = 1 +PERFMON_COUNTER_MODE_MAX = 2 +PERFMON_COUNTER_MODE_DIRTY = 3 +PERFMON_COUNTER_MODE_SAMPLE = 4 +PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT = 5 +PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT = 6 +PERFMON_COUNTER_MODE_CYCLES_GE_HI = 7 +PERFMON_COUNTER_MODE_CYCLES_EQ_HI = 8 +PERFMON_COUNTER_MODE_INACTIVE_CYCLES = 9 +PERFMON_COUNTER_MODE_RESERVED = 15 +PERFMON_COUNTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_SPM_MODE' +PERFMON_SPM_MODE__enumvalues = { + 0: 'PERFMON_SPM_MODE_OFF', + 1: 'PERFMON_SPM_MODE_16BIT_CLAMP', + 2: 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 3: 'PERFMON_SPM_MODE_32BIT_CLAMP', + 4: 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 5: 'PERFMON_SPM_MODE_RESERVED_5', + 6: 'PERFMON_SPM_MODE_RESERVED_6', + 7: 'PERFMON_SPM_MODE_RESERVED_7', + 8: 'PERFMON_SPM_MODE_TEST_MODE_0', + 9: 'PERFMON_SPM_MODE_TEST_MODE_1', + 10: 'PERFMON_SPM_MODE_TEST_MODE_2', +} +PERFMON_SPM_MODE_OFF = 0 +PERFMON_SPM_MODE_16BIT_CLAMP = 1 +PERFMON_SPM_MODE_16BIT_NO_CLAMP = 2 +PERFMON_SPM_MODE_32BIT_CLAMP = 3 +PERFMON_SPM_MODE_32BIT_NO_CLAMP = 4 +PERFMON_SPM_MODE_RESERVED_5 = 5 +PERFMON_SPM_MODE_RESERVED_6 = 6 +PERFMON_SPM_MODE_RESERVED_7 = 7 +PERFMON_SPM_MODE_TEST_MODE_0 = 8 +PERFMON_SPM_MODE_TEST_MODE_1 = 9 +PERFMON_SPM_MODE_TEST_MODE_2 = 10 +PERFMON_SPM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceTiling' +SurfaceTiling__enumvalues = { + 0: 'ARRAY_LINEAR', + 1: 'ARRAY_TILED', +} +ARRAY_LINEAR = 0 +ARRAY_TILED = 1 +SurfaceTiling = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceArray' +SurfaceArray__enumvalues = { + 0: 'ARRAY_1D', + 1: 'ARRAY_2D', + 2: 'ARRAY_3D', + 3: 'ARRAY_3D_SLICE', +} +ARRAY_1D = 0 +ARRAY_2D = 1 +ARRAY_3D = 2 +ARRAY_3D_SLICE = 3 +SurfaceArray = ctypes.c_uint32 # enum + +# values for enumeration 'ColorArray' +ColorArray__enumvalues = { + 0: 'ARRAY_2D_ALT_COLOR', + 1: 'ARRAY_2D_COLOR', + 3: 'ARRAY_3D_SLICE_COLOR', +} +ARRAY_2D_ALT_COLOR = 0 +ARRAY_2D_COLOR = 1 +ARRAY_3D_SLICE_COLOR = 3 +ColorArray = ctypes.c_uint32 # enum + +# values for enumeration 'DepthArray' +DepthArray__enumvalues = { + 0: 'ARRAY_2D_ALT_DEPTH', + 1: 'ARRAY_2D_DEPTH', +} +ARRAY_2D_ALT_DEPTH = 0 +ARRAY_2D_DEPTH = 1 +DepthArray = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_NUM_SIMD_PER_CU' +ENUM_NUM_SIMD_PER_CU__enumvalues = { + 2: 'NUM_SIMD_PER_CU', +} +NUM_SIMD_PER_CU = 2 +ENUM_NUM_SIMD_PER_CU = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_ENABLE_ERROR_INJECT' +DSM_ENABLE_ERROR_INJECT__enumvalues = { + 0: 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 1: 'DSM_ENABLE_ERROR_INJECT_SINGLE', + 2: 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE', + 3: 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED', +} +DSM_ENABLE_ERROR_INJECT_FED_IN = 0 +DSM_ENABLE_ERROR_INJECT_SINGLE = 1 +DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE = 2 +DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED = 3 +DSM_ENABLE_ERROR_INJECT = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_SELECT_INJECT_DELAY' +DSM_SELECT_INJECT_DELAY__enumvalues = { + 0: 'DSM_SELECT_INJECT_DELAY_NO_DELAY', + 1: 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', +} +DSM_SELECT_INJECT_DELAY_NO_DELAY = 0 +DSM_SELECT_INJECT_DELAY_DELAY_ERROR = 1 +DSM_SELECT_INJECT_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_DATA_SEL' +DSM_DATA_SEL__enumvalues = { + 0: 'DSM_DATA_SEL_DISABLE', + 1: 'DSM_DATA_SEL_0', + 2: 'DSM_DATA_SEL_1', + 3: 'DSM_DATA_SEL_BOTH', +} +DSM_DATA_SEL_DISABLE = 0 +DSM_DATA_SEL_0 = 1 +DSM_DATA_SEL_1 = 2 +DSM_DATA_SEL_BOTH = 3 +DSM_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_SINGLE_WRITE' +DSM_SINGLE_WRITE__enumvalues = { + 0: 'DSM_SINGLE_WRITE_DIS', + 1: 'DSM_SINGLE_WRITE_EN', +} +DSM_SINGLE_WRITE_DIS = 0 +DSM_SINGLE_WRITE_EN = 1 +DSM_SINGLE_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'Hdp_SurfaceEndian' +Hdp_SurfaceEndian__enumvalues = { + 0: 'HDP_ENDIAN_NONE', + 1: 'HDP_ENDIAN_8IN16', + 2: 'HDP_ENDIAN_8IN32', + 3: 'HDP_ENDIAN_8IN64', +} +HDP_ENDIAN_NONE = 0 +HDP_ENDIAN_8IN16 = 1 +HDP_ENDIAN_8IN32 = 2 +HDP_ENDIAN_8IN64 = 3 +Hdp_SurfaceEndian = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_ENABLE' +CNVC_ENABLE__enumvalues = { + 0: 'CNVC_DIS', + 1: 'CNVC_EN', +} +CNVC_DIS = 0 +CNVC_EN = 1 +CNVC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_BYPASS' +CNVC_BYPASS__enumvalues = { + 0: 'CNVC_BYPASS_DISABLE', + 1: 'CNVC_BYPASS_EN', +} +CNVC_BYPASS_DISABLE = 0 +CNVC_BYPASS_EN = 1 +CNVC_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_PENDING' +CNVC_PENDING__enumvalues = { + 0: 'CNVC_NOT_PENDING', + 1: 'CNVC_YES_PENDING', +} +CNVC_NOT_PENDING = 0 +CNVC_YES_PENDING = 1 +CNVC_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'DENORM_TRUNCATE' +DENORM_TRUNCATE__enumvalues = { + 0: 'CNVC_ROUND', + 1: 'CNVC_TRUNCATE', +} +CNVC_ROUND = 0 +CNVC_TRUNCATE = 1 +DENORM_TRUNCATE = ctypes.c_uint32 # enum + +# values for enumeration 'PIX_EXPAND_MODE' +PIX_EXPAND_MODE__enumvalues = { + 0: 'PIX_DYNAMIC_EXPANSION', + 1: 'PIX_ZERO_EXPANSION', +} +PIX_DYNAMIC_EXPANSION = 0 +PIX_ZERO_EXPANSION = 1 +PIX_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_PIXEL_FORMAT' +SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'ARGB1555', + 2: 'RGBA5551', + 3: 'RGB565', + 4: 'BGR565', + 5: 'ARGB4444', + 6: 'RGBA4444', + 8: 'ARGB8888', + 9: 'RGBA8888', + 10: 'ARGB2101010', + 11: 'RGBA1010102', + 12: 'AYCrCb8888', + 13: 'YCrCbA8888', + 14: 'ACrYCb8888', + 15: 'CrYCbA8888', + 16: 'ARGB16161616_10MSB', + 17: 'RGBA16161616_10MSB', + 18: 'ARGB16161616_10LSB', + 19: 'RGBA16161616_10LSB', + 20: 'ARGB16161616_12MSB', + 21: 'RGBA16161616_12MSB', + 22: 'ARGB16161616_12LSB', + 23: 'RGBA16161616_12LSB', + 24: 'ARGB16161616_FLOAT', + 25: 'RGBA16161616_FLOAT', + 26: 'ARGB16161616_UNORM', + 27: 'RGBA16161616_UNORM', + 28: 'ARGB16161616_SNORM', + 29: 'RGBA16161616_SNORM', + 32: 'AYCrCb16161616_10MSB', + 33: 'AYCrCb16161616_10LSB', + 34: 'YCrCbA16161616_10MSB', + 35: 'YCrCbA16161616_10LSB', + 36: 'ACrYCb16161616_10MSB', + 37: 'ACrYCb16161616_10LSB', + 38: 'CrYCbA16161616_10MSB', + 39: 'CrYCbA16161616_10LSB', + 40: 'AYCrCb16161616_12MSB', + 41: 'AYCrCb16161616_12LSB', + 42: 'YCrCbA16161616_12MSB', + 43: 'YCrCbA16161616_12LSB', + 44: 'ACrYCb16161616_12MSB', + 45: 'ACrYCb16161616_12LSB', + 46: 'CrYCbA16161616_12MSB', + 47: 'CrYCbA16161616_12LSB', + 64: 'Y8_CrCb88_420_PLANAR', + 65: 'Y8_CbCr88_420_PLANAR', + 66: 'Y10_CrCb1010_420_PLANAR', + 67: 'Y10_CbCr1010_420_PLANAR', + 68: 'Y12_CrCb1212_420_PLANAR', + 69: 'Y12_CbCr1212_420_PLANAR', + 72: 'YCrYCb8888_422_PACKED', + 73: 'YCbYCr8888_422_PACKED', + 74: 'CrYCbY8888_422_PACKED', + 75: 'CbYCrY8888_422_PACKED', + 76: 'YCrYCb10101010_422_PACKED', + 77: 'YCbYCr10101010_422_PACKED', + 78: 'CrYCbY10101010_422_PACKED', + 79: 'CbYCrY10101010_422_PACKED', + 80: 'YCrYCb12121212_422_PACKED', + 81: 'YCbYCr12121212_422_PACKED', + 82: 'CrYCbY12121212_422_PACKED', + 83: 'CbYCrY12121212_422_PACKED', + 112: 'RGB111110_FIX', + 113: 'BGR101111_FIX', + 114: 'ACrYCb2101010', + 115: 'CrYCbA1010102', + 118: 'RGB111110_FLOAT', + 119: 'BGR101111_FLOAT', + 120: 'MONO_8', + 121: 'MONO_10MSB', + 122: 'MONO_10LSB', + 123: 'MONO_12MSB', + 124: 'MONO_12LSB', + 125: 'MONO_16', +} +ARGB1555 = 1 +RGBA5551 = 2 +RGB565 = 3 +BGR565 = 4 +ARGB4444 = 5 +RGBA4444 = 6 +ARGB8888 = 8 +RGBA8888 = 9 +ARGB2101010 = 10 +RGBA1010102 = 11 +AYCrCb8888 = 12 +YCrCbA8888 = 13 +ACrYCb8888 = 14 +CrYCbA8888 = 15 +ARGB16161616_10MSB = 16 +RGBA16161616_10MSB = 17 +ARGB16161616_10LSB = 18 +RGBA16161616_10LSB = 19 +ARGB16161616_12MSB = 20 +RGBA16161616_12MSB = 21 +ARGB16161616_12LSB = 22 +RGBA16161616_12LSB = 23 +ARGB16161616_FLOAT = 24 +RGBA16161616_FLOAT = 25 +ARGB16161616_UNORM = 26 +RGBA16161616_UNORM = 27 +ARGB16161616_SNORM = 28 +RGBA16161616_SNORM = 29 +AYCrCb16161616_10MSB = 32 +AYCrCb16161616_10LSB = 33 +YCrCbA16161616_10MSB = 34 +YCrCbA16161616_10LSB = 35 +ACrYCb16161616_10MSB = 36 +ACrYCb16161616_10LSB = 37 +CrYCbA16161616_10MSB = 38 +CrYCbA16161616_10LSB = 39 +AYCrCb16161616_12MSB = 40 +AYCrCb16161616_12LSB = 41 +YCrCbA16161616_12MSB = 42 +YCrCbA16161616_12LSB = 43 +ACrYCb16161616_12MSB = 44 +ACrYCb16161616_12LSB = 45 +CrYCbA16161616_12MSB = 46 +CrYCbA16161616_12LSB = 47 +Y8_CrCb88_420_PLANAR = 64 +Y8_CbCr88_420_PLANAR = 65 +Y10_CrCb1010_420_PLANAR = 66 +Y10_CbCr1010_420_PLANAR = 67 +Y12_CrCb1212_420_PLANAR = 68 +Y12_CbCr1212_420_PLANAR = 69 +YCrYCb8888_422_PACKED = 72 +YCbYCr8888_422_PACKED = 73 +CrYCbY8888_422_PACKED = 74 +CbYCrY8888_422_PACKED = 75 +YCrYCb10101010_422_PACKED = 76 +YCbYCr10101010_422_PACKED = 77 +CrYCbY10101010_422_PACKED = 78 +CbYCrY10101010_422_PACKED = 79 +YCrYCb12121212_422_PACKED = 80 +YCbYCr12121212_422_PACKED = 81 +CrYCbY12121212_422_PACKED = 82 +CbYCrY12121212_422_PACKED = 83 +RGB111110_FIX = 112 +BGR101111_FIX = 113 +ACrYCb2101010 = 114 +CrYCbA1010102 = 115 +RGB111110_FLOAT = 118 +BGR101111_FLOAT = 119 +MONO_8 = 120 +MONO_10MSB = 121 +MONO_10LSB = 122 +MONO_12MSB = 123 +MONO_12LSB = 124 +MONO_16 = 125 +SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'XNORM' +XNORM__enumvalues = { + 0: 'XNORM_A', + 1: 'XNORM_B', +} +XNORM_A = 0 +XNORM_B = 1 +XNORM = ctypes.c_uint32 # enum + +# values for enumeration 'COLOR_KEYER_MODE' +COLOR_KEYER_MODE__enumvalues = { + 0: 'FORCE_00', + 1: 'FORCE_FF', + 2: 'RANGE_00', + 3: 'RANGE_FF', +} +FORCE_00 = 0 +FORCE_FF = 1 +RANGE_00 = 2 +RANGE_FF = 3 +COLOR_KEYER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ENABLE' +CUR_ENABLE__enumvalues = { + 0: 'CUR_DIS', + 1: 'CUR_EN', +} +CUR_DIS = 0 +CUR_EN = 1 +CUR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_PENDING' +CUR_PENDING__enumvalues = { + 0: 'CUR_NOT_PENDING', + 1: 'CUR_YES_PENDING', +} +CUR_NOT_PENDING = 0 +CUR_YES_PENDING = 1 +CUR_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_EXPAND_MODE' +CUR_EXPAND_MODE__enumvalues = { + 0: 'CUR_DYNAMIC_EXPANSION', + 1: 'CUR_ZERO_EXPANSION', +} +CUR_DYNAMIC_EXPANSION = 0 +CUR_ZERO_EXPANSION = 1 +CUR_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ROM_EN' +CUR_ROM_EN__enumvalues = { + 0: 'CUR_FP_NO_ROM', + 1: 'CUR_FP_USE_ROM', +} +CUR_FP_NO_ROM = 0 +CUR_FP_USE_ROM = 1 +CUR_ROM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_MODE' +CUR_MODE__enumvalues = { + 0: 'MONO_2BIT', + 1: 'COLOR_24BIT_1BIT_AND', + 2: 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'COLOR_64BIT_FP_PREMULT', + 5: 'COLOR_64BIT_FP_UNPREMULT', +} +MONO_2BIT = 0 +COLOR_24BIT_1BIT_AND = 1 +COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +COLOR_64BIT_FP_PREMULT = 4 +COLOR_64BIT_FP_UNPREMULT = 5 +CUR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_INV_CLAMP' +CUR_INV_CLAMP__enumvalues = { + 0: 'CUR_CLAMP_DIS', + 1: 'CUR_CLAMP_EN', +} +CUR_CLAMP_DIS = 0 +CUR_CLAMP_EN = 1 +CUR_INV_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_FILTER_TYPE_SEL' +SCL_COEF_FILTER_TYPE_SEL__enumvalues = { + 0: 'SCL_COEF_LUMA_VERT_FILTER', + 1: 'SCL_COEF_LUMA_HORZ_FILTER', + 2: 'SCL_COEF_CHROMA_VERT_FILTER', + 3: 'SCL_COEF_CHROMA_HORZ_FILTER', + 4: 'SCL_COEF_ALPHA_VERT_FILTER', + 5: 'SCL_COEF_ALPHA_HORZ_FILTER', +} +SCL_COEF_LUMA_VERT_FILTER = 0 +SCL_COEF_LUMA_HORZ_FILTER = 1 +SCL_COEF_CHROMA_VERT_FILTER = 2 +SCL_COEF_CHROMA_HORZ_FILTER = 3 +SCL_COEF_ALPHA_VERT_FILTER = 4 +SCL_COEF_ALPHA_HORZ_FILTER = 5 +SCL_COEF_FILTER_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSCL_MODE_SEL' +DSCL_MODE_SEL__enumvalues = { + 0: 'DSCL_MODE_SCALING_444_BYPASS', + 1: 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 2: 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 3: 'DSCL_MODE_SCALING_YCBCR_ENABLE', + 4: 'DSCL_MODE_LUMA_SCALING_BYPASS', + 5: 'DSCL_MODE_CHROMA_SCALING_BYPASS', + 6: 'DSCL_MODE_DSCL_BYPASS', +} +DSCL_MODE_SCALING_444_BYPASS = 0 +DSCL_MODE_SCALING_444_RGB_ENABLE = 1 +DSCL_MODE_SCALING_444_YCBCR_ENABLE = 2 +DSCL_MODE_SCALING_YCBCR_ENABLE = 3 +DSCL_MODE_LUMA_SCALING_BYPASS = 4 +DSCL_MODE_CHROMA_SCALING_BYPASS = 5 +DSCL_MODE_DSCL_BYPASS = 6 +DSCL_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_AUTOCAL_MODE' +SCL_AUTOCAL_MODE__enumvalues = { + 0: 'AUTOCAL_MODE_OFF', + 1: 'AUTOCAL_MODE_AUTOSCALE', + 2: 'AUTOCAL_MODE_AUTOCENTER', + 3: 'AUTOCAL_MODE_AUTOREPLICATE', +} +AUTOCAL_MODE_OFF = 0 +AUTOCAL_MODE_AUTOSCALE = 1 +AUTOCAL_MODE_AUTOCENTER = 2 +AUTOCAL_MODE_AUTOREPLICATE = 3 +SCL_AUTOCAL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_RAM_SEL' +SCL_COEF_RAM_SEL__enumvalues = { + 0: 'SCL_COEF_RAM_SEL_0', + 1: 'SCL_COEF_RAM_SEL_1', +} +SCL_COEF_RAM_SEL_0 = 0 +SCL_COEF_RAM_SEL_1 = 1 +SCL_COEF_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_CHROMA_COEF' +SCL_CHROMA_COEF__enumvalues = { + 0: 'SCL_CHROMA_COEF_LUMA', + 1: 'SCL_CHROMA_COEF_CHROMA', +} +SCL_CHROMA_COEF_LUMA = 0 +SCL_CHROMA_COEF_CHROMA = 1 +SCL_CHROMA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_ALPHA_COEF' +SCL_ALPHA_COEF__enumvalues = { + 0: 'SCL_ALPHA_COEF_LUMA', + 1: 'SCL_ALPHA_COEF_ALPHA', +} +SCL_ALPHA_COEF_LUMA = 0 +SCL_ALPHA_COEF_ALPHA = 1 +SCL_ALPHA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'COEF_RAM_SELECT_RD' +COEF_RAM_SELECT_RD__enumvalues = { + 0: 'COEF_RAM_SELECT_BACK', + 1: 'COEF_RAM_SELECT_CURRENT', +} +COEF_RAM_SELECT_BACK = 0 +COEF_RAM_SELECT_CURRENT = 1 +COEF_RAM_SELECT_RD = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_2TAP_HARDCODE' +SCL_2TAP_HARDCODE__enumvalues = { + 0: 'SCL_COEF_2TAP_HARDCODE_OFF', + 1: 'SCL_COEF_2TAP_HARDCODE_ON', +} +SCL_COEF_2TAP_HARDCODE_OFF = 0 +SCL_COEF_2TAP_HARDCODE_ON = 1 +SCL_2TAP_HARDCODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_SHARP_EN' +SCL_SHARP_EN__enumvalues = { + 0: 'SCL_SHARP_DISABLE', + 1: 'SCL_SHARP_ENABLE', +} +SCL_SHARP_DISABLE = 0 +SCL_SHARP_ENABLE = 1 +SCL_SHARP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_BOUNDARY' +SCL_BOUNDARY__enumvalues = { + 0: 'SCL_BOUNDARY_EDGE', + 1: 'SCL_BOUNDARY_BLACK', +} +SCL_BOUNDARY_EDGE = 0 +SCL_BOUNDARY_BLACK = 1 +SCL_BOUNDARY = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERLEAVE_EN' +LB_INTERLEAVE_EN__enumvalues = { + 0: 'LB_INTERLEAVE_DISABLE', + 1: 'LB_INTERLEAVE_ENABLE', +} +LB_INTERLEAVE_DISABLE = 0 +LB_INTERLEAVE_ENABLE = 1 +LB_INTERLEAVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_ALPHA_EN' +LB_ALPHA_EN__enumvalues = { + 0: 'LB_ALPHA_DISABLE', + 1: 'LB_ALPHA_ENABLE', +} +LB_ALPHA_DISABLE = 0 +LB_ALPHA_ENABLE = 1 +LB_ALPHA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_BYPASS_SEL' +OBUF_BYPASS_SEL__enumvalues = { + 0: 'OBUF_BYPASS_DIS', + 1: 'OBUF_BYPASS_EN', +} +OBUF_BYPASS_DIS = 0 +OBUF_BYPASS_EN = 1 +OBUF_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_USE_FULL_BUFFER_SEL' +OBUF_USE_FULL_BUFFER_SEL__enumvalues = { + 0: 'OBUF_RECOUT', + 1: 'OBUF_FULL', +} +OBUF_RECOUT = 0 +OBUF_FULL = 1 +OBUF_USE_FULL_BUFFER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_IS_HALF_RECOUT_WIDTH_SEL' +OBUF_IS_HALF_RECOUT_WIDTH_SEL__enumvalues = { + 0: 'OBUF_FULL_RECOUT', + 1: 'OBUF_HALF_RECOUT', +} +OBUF_FULL_RECOUT = 0 +OBUF_HALF_RECOUT = 1 +OBUF_IS_HALF_RECOUT_WIDTH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_BYPASS' +CM_BYPASS__enumvalues = { + 0: 'NON_BYPASS', + 1: 'BYPASS_EN', +} +NON_BYPASS = 0 +BYPASS_EN = 1 +CM_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CM_EN' +CM_EN__enumvalues = { + 0: 'CM_DISABLE', + 1: 'CM_ENABLE', +} +CM_DISABLE = 0 +CM_ENABLE = 1 +CM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CM_PENDING' +CM_PENDING__enumvalues = { + 0: 'CM_NOT_PENDING', + 1: 'CM_YES_PENDING', +} +CM_NOT_PENDING = 0 +CM_YES_PENDING = 1 +CM_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CM_DATA_SIGNED' +CM_DATA_SIGNED__enumvalues = { + 0: 'UNSIGNED', + 1: 'SIGNED', +} +UNSIGNED = 0 +SIGNED = 1 +CM_DATA_SIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'CM_WRITE_BASE_ONLY' +CM_WRITE_BASE_ONLY__enumvalues = { + 0: 'WRITE_BOTH', + 1: 'WRITE_BASE_ONLY', +} +WRITE_BOTH = 0 +WRITE_BASE_ONLY = 1 +CM_WRITE_BASE_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_CONFIG_ENUM' +CM_LUT_4_CONFIG_ENUM__enumvalues = { + 0: 'LUT_4CFG_NO_MEMORY', + 1: 'LUT_4CFG_ROM_A', + 2: 'LUT_4CFG_ROM_B', + 3: 'LUT_4CFG_MEMORY_A', + 4: 'LUT_4CFG_MEMORY_B', +} +LUT_4CFG_NO_MEMORY = 0 +LUT_4CFG_ROM_A = 1 +LUT_4CFG_ROM_B = 2 +LUT_4CFG_MEMORY_A = 3 +LUT_4CFG_MEMORY_B = 4 +CM_LUT_4_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_CONFIG_ENUM' +CM_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'LUT_2CFG_NO_MEMORY', + 1: 'LUT_2CFG_MEMORY_A', + 2: 'LUT_2CFG_MEMORY_B', +} +LUT_2CFG_NO_MEMORY = 0 +LUT_2CFG_MEMORY_A = 1 +LUT_2CFG_MEMORY_B = 2 +CM_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_MODE_ENUM' +CM_LUT_4_MODE_ENUM__enumvalues = { + 0: 'LUT_4_MODE_BYPASS', + 1: 'LUT_4_MODE_ROMA_LUT', + 2: 'LUT_4_MODE_ROMB_LUT', + 3: 'LUT_4_MODE_RAMA_LUT', + 4: 'LUT_4_MODE_RAMB_LUT', +} +LUT_4_MODE_BYPASS = 0 +LUT_4_MODE_ROMA_LUT = 1 +LUT_4_MODE_ROMB_LUT = 2 +LUT_4_MODE_RAMA_LUT = 3 +LUT_4_MODE_RAMB_LUT = 4 +CM_LUT_4_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_MODE_ENUM' +CM_LUT_2_MODE_ENUM__enumvalues = { + 0: 'LUT_2_MODE_BYPASS', + 1: 'LUT_2_MODE_RAMA_LUT', + 2: 'LUT_2_MODE_RAMB_LUT', +} +LUT_2_MODE_BYPASS = 0 +LUT_2_MODE_RAMA_LUT = 1 +LUT_2_MODE_RAMB_LUT = 2 +CM_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_RAM_SEL' +CM_LUT_RAM_SEL__enumvalues = { + 0: 'RAMA_ACCESS', + 1: 'RAMB_ACCESS', +} +RAMA_ACCESS = 0 +RAMB_ACCESS = 1 +CM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_NUM_SEG' +CM_LUT_NUM_SEG__enumvalues = { + 0: 'SEGMENTS_1', + 1: 'SEGMENTS_2', + 2: 'SEGMENTS_4', + 3: 'SEGMENTS_8', + 4: 'SEGMENTS_16', + 5: 'SEGMENTS_32', + 6: 'SEGMENTS_64', + 7: 'SEGMENTS_128', +} +SEGMENTS_1 = 0 +SEGMENTS_2 = 1 +SEGMENTS_4 = 2 +SEGMENTS_8 = 3 +SEGMENTS_16 = 4 +SEGMENTS_32 = 5 +SEGMENTS_64 = 6 +SEGMENTS_128 = 7 +CM_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CM_ICSC_MODE_ENUM' +CM_ICSC_MODE_ENUM__enumvalues = { + 0: 'BYPASS_ICSC', + 1: 'COEF_ICSC', + 2: 'COEF_ICSC_B', +} +BYPASS_ICSC = 0 +COEF_ICSC = 1 +COEF_ICSC_B = 2 +CM_ICSC_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMUT_REMAP_MODE_ENUM' +CM_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'BYPASS_GAMUT', + 1: 'GAMUT_COEF', + 2: 'GAMUT_COEF_B', +} +BYPASS_GAMUT = 0 +GAMUT_COEF = 1 +GAMUT_COEF_B = 2 +CM_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_COEF_FORMAT_ENUM' +CM_COEF_FORMAT_ENUM__enumvalues = { + 0: 'FIX_S2_13', + 1: 'FIX_S3_12', +} +FIX_S2_13 = 0 +FIX_S3_12 = 1 +CM_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_CONFIG_ENUM' +CMC_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'CMC_LUT_2CFG_NO_MEMORY', + 1: 'CMC_LUT_2CFG_MEMORY_A', + 2: 'CMC_LUT_2CFG_MEMORY_B', +} +CMC_LUT_2CFG_NO_MEMORY = 0 +CMC_LUT_2CFG_MEMORY_A = 1 +CMC_LUT_2CFG_MEMORY_B = 2 +CMC_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_MODE_ENUM' +CMC_LUT_2_MODE_ENUM__enumvalues = { + 0: 'CMC_LUT_2_MODE_BYPASS', + 1: 'CMC_LUT_2_MODE_RAMA_LUT', + 2: 'CMC_LUT_2_MODE_RAMB_LUT', +} +CMC_LUT_2_MODE_BYPASS = 0 +CMC_LUT_2_MODE_RAMA_LUT = 1 +CMC_LUT_2_MODE_RAMB_LUT = 2 +CMC_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_RAM_SEL' +CMC_LUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAMA_ACCESS', + 1: 'CMC_RAMB_ACCESS', +} +CMC_RAMA_ACCESS = 0 +CMC_RAMB_ACCESS = 1 +CMC_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_RAM_SEL' +CMC_3DLUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAM0_ACCESS', + 1: 'CMC_RAM1_ACCESS', + 2: 'CMC_RAM2_ACCESS', + 3: 'CMC_RAM3_ACCESS', +} +CMC_RAM0_ACCESS = 0 +CMC_RAM1_ACCESS = 1 +CMC_RAM2_ACCESS = 2 +CMC_RAM3_ACCESS = 3 +CMC_3DLUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_NUM_SEG' +CMC_LUT_NUM_SEG__enumvalues = { + 0: 'CMC_SEGMENTS_1', + 1: 'CMC_SEGMENTS_2', + 2: 'CMC_SEGMENTS_4', + 3: 'CMC_SEGMENTS_8', + 4: 'CMC_SEGMENTS_16', + 5: 'CMC_SEGMENTS_32', + 6: 'CMC_SEGMENTS_64', + 7: 'CMC_SEGMENTS_128', +} +CMC_SEGMENTS_1 = 0 +CMC_SEGMENTS_2 = 1 +CMC_SEGMENTS_4 = 2 +CMC_SEGMENTS_8 = 3 +CMC_SEGMENTS_16 = 4 +CMC_SEGMENTS_32 = 5 +CMC_SEGMENTS_64 = 6 +CMC_SEGMENTS_128 = 7 +CMC_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_30BIT_ENUM' +CMC_3DLUT_30BIT_ENUM__enumvalues = { + 0: 'CMC_3DLUT_36BIT', + 1: 'CMC_3DLUT_30BIT', +} +CMC_3DLUT_36BIT = 0 +CMC_3DLUT_30BIT = 1 +CMC_3DLUT_30BIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_SIZE_ENUM' +CMC_3DLUT_SIZE_ENUM__enumvalues = { + 0: 'CMC_3DLUT_17CUBE', + 1: 'CMC_3DLUT_9CUBE', +} +CMC_3DLUT_17CUBE = 0 +CMC_3DLUT_9CUBE = 1 +CMC_3DLUT_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_SEL' +TEST_CLK_SEL__enumvalues = { + 0: 'TEST_CLK_SEL_0', + 1: 'TEST_CLK_SEL_1', + 2: 'TEST_CLK_SEL_2', + 3: 'TEST_CLK_SEL_3', + 4: 'TEST_CLK_SEL_4', + 5: 'TEST_CLK_SEL_5', + 6: 'TEST_CLK_SEL_6', + 7: 'TEST_CLK_SEL_7', + 8: 'TEST_CLK_SEL_8', +} +TEST_CLK_SEL_0 = 0 +TEST_CLK_SEL_1 = 1 +TEST_CLK_SEL_2 = 2 +TEST_CLK_SEL_3 = 3 +TEST_CLK_SEL_4 = 4 +TEST_CLK_SEL_5 = 5 +TEST_CLK_SEL_6 = 6 +TEST_CLK_SEL_7 = 7 +TEST_CLK_SEL_8 = 8 +TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_SRC_SEL' +CRC_SRC_SEL__enumvalues = { + 0: 'CRC_SRC_0', + 1: 'CRC_SRC_1', + 2: 'CRC_SRC_2', + 3: 'CRC_SRC_3', +} +CRC_SRC_0 = 0 +CRC_SRC_1 = 1 +CRC_SRC_2 = 2 +CRC_SRC_3 = 3 +CRC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_IN_PIX_SEL' +CRC_IN_PIX_SEL__enumvalues = { + 0: 'CRC_IN_PIX_0', + 1: 'CRC_IN_PIX_1', + 2: 'CRC_IN_PIX_2', + 3: 'CRC_IN_PIX_3', + 4: 'CRC_IN_PIX_4', + 5: 'CRC_IN_PIX_5', + 6: 'CRC_IN_PIX_6', + 7: 'CRC_IN_PIX_7', +} +CRC_IN_PIX_0 = 0 +CRC_IN_PIX_1 = 1 +CRC_IN_PIX_2 = 2 +CRC_IN_PIX_3 = 3 +CRC_IN_PIX_4 = 4 +CRC_IN_PIX_5 = 5 +CRC_IN_PIX_6 = 6 +CRC_IN_PIX_7 = 7 +CRC_IN_PIX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_CUR_BITS_SEL' +CRC_CUR_BITS_SEL__enumvalues = { + 0: 'CRC_CUR_BITS_0', + 1: 'CRC_CUR_BITS_1', +} +CRC_CUR_BITS_0 = 0 +CRC_CUR_BITS_1 = 1 +CRC_CUR_BITS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_IN_CUR_SEL' +CRC_IN_CUR_SEL__enumvalues = { + 0: 'CRC_IN_CUR_0', + 1: 'CRC_IN_CUR_1', +} +CRC_IN_CUR_0 = 0 +CRC_IN_CUR_1 = 1 +CRC_IN_CUR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_CUR_SEL' +CRC_CUR_SEL__enumvalues = { + 0: 'CRC_CUR_0', + 1: 'CRC_CUR_1', +} +CRC_CUR_0 = 0 +CRC_CUR_1 = 1 +CRC_CUR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_STEREO_SEL' +CRC_STEREO_SEL__enumvalues = { + 0: 'CRC_STEREO_0', + 1: 'CRC_STEREO_1', + 2: 'CRC_STEREO_2', + 3: 'CRC_STEREO_3', +} +CRC_STEREO_0 = 0 +CRC_STEREO_1 = 1 +CRC_STEREO_2 = 2 +CRC_STEREO_3 = 3 +CRC_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_INTERLACE_SEL' +CRC_INTERLACE_SEL__enumvalues = { + 0: 'CRC_INTERLACE_0', + 1: 'CRC_INTERLACE_1', + 2: 'CRC_INTERLACE_2', + 3: 'CRC_INTERLACE_3', +} +CRC_INTERLACE_0 = 0 +CRC_INTERLACE_1 = 1 +CRC_INTERLACE_2 = 2 +CRC_INTERLACE_3 = 3 +CRC_INTERLACE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CVALUE_SEL' +PERFCOUNTER_CVALUE_SEL__enumvalues = { + 0: 'PERFCOUNTER_CVALUE_SEL_47_0', + 1: 'PERFCOUNTER_CVALUE_SEL_15_0', + 2: 'PERFCOUNTER_CVALUE_SEL_31_16', + 3: 'PERFCOUNTER_CVALUE_SEL_47_32', + 4: 'PERFCOUNTER_CVALUE_SEL_11_0', + 5: 'PERFCOUNTER_CVALUE_SEL_23_12', + 6: 'PERFCOUNTER_CVALUE_SEL_35_24', + 7: 'PERFCOUNTER_CVALUE_SEL_47_36', +} +PERFCOUNTER_CVALUE_SEL_47_0 = 0 +PERFCOUNTER_CVALUE_SEL_15_0 = 1 +PERFCOUNTER_CVALUE_SEL_31_16 = 2 +PERFCOUNTER_CVALUE_SEL_47_32 = 3 +PERFCOUNTER_CVALUE_SEL_11_0 = 4 +PERFCOUNTER_CVALUE_SEL_23_12 = 5 +PERFCOUNTER_CVALUE_SEL_35_24 = 6 +PERFCOUNTER_CVALUE_SEL_47_36 = 7 +PERFCOUNTER_CVALUE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INC_MODE' +PERFCOUNTER_INC_MODE__enumvalues = { + 0: 'PERFCOUNTER_INC_MODE_MULTI_BIT', + 1: 'PERFCOUNTER_INC_MODE_BOTH_EDGE', + 2: 'PERFCOUNTER_INC_MODE_LSB', + 3: 'PERFCOUNTER_INC_MODE_POS_EDGE', + 4: 'PERFCOUNTER_INC_MODE_NEG_EDGE', +} +PERFCOUNTER_INC_MODE_MULTI_BIT = 0 +PERFCOUNTER_INC_MODE_BOTH_EDGE = 1 +PERFCOUNTER_INC_MODE_LSB = 2 +PERFCOUNTER_INC_MODE_POS_EDGE = 3 +PERFCOUNTER_INC_MODE_NEG_EDGE = 4 +PERFCOUNTER_INC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_CNTL_SEL' +PERFCOUNTER_HW_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', + 1: 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', +} +PERFCOUNTER_HW_CNTL_SEL_RUNEN = 0 +PERFCOUNTER_HW_CNTL_SEL_CNTOFF = 1 +PERFCOUNTER_HW_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RUNEN_MODE' +PERFCOUNTER_RUNEN_MODE__enumvalues = { + 0: 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 1: 'PERFCOUNTER_RUNEN_MODE_EDGE', +} +PERFCOUNTER_RUNEN_MODE_LEVEL = 0 +PERFCOUNTER_RUNEN_MODE_EDGE = 1 +PERFCOUNTER_RUNEN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTOFF_START_DIS' +PERFCOUNTER_CNTOFF_START_DIS__enumvalues = { + 0: 'PERFCOUNTER_CNTOFF_START_ENABLE', + 1: 'PERFCOUNTER_CNTOFF_START_DISABLE', +} +PERFCOUNTER_CNTOFF_START_ENABLE = 0 +PERFCOUNTER_CNTOFF_START_DISABLE = 1 +PERFCOUNTER_CNTOFF_START_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RESTART_EN' +PERFCOUNTER_RESTART_EN__enumvalues = { + 0: 'PERFCOUNTER_RESTART_DISABLE', + 1: 'PERFCOUNTER_RESTART_ENABLE', +} +PERFCOUNTER_RESTART_DISABLE = 0 +PERFCOUNTER_RESTART_ENABLE = 1 +PERFCOUNTER_RESTART_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_EN' +PERFCOUNTER_INT_EN__enumvalues = { + 0: 'PERFCOUNTER_INT_DISABLE', + 1: 'PERFCOUNTER_INT_ENABLE', +} +PERFCOUNTER_INT_DISABLE = 0 +PERFCOUNTER_INT_ENABLE = 1 +PERFCOUNTER_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_OFF_MASK' +PERFCOUNTER_OFF_MASK__enumvalues = { + 0: 'PERFCOUNTER_OFF_MASK_DISABLE', + 1: 'PERFCOUNTER_OFF_MASK_ENABLE', +} +PERFCOUNTER_OFF_MASK_DISABLE = 0 +PERFCOUNTER_OFF_MASK_ENABLE = 1 +PERFCOUNTER_OFF_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_ACTIVE' +PERFCOUNTER_ACTIVE__enumvalues = { + 0: 'PERFCOUNTER_IS_IDLE', + 1: 'PERFCOUNTER_IS_ACTIVE', +} +PERFCOUNTER_IS_IDLE = 0 +PERFCOUNTER_IS_ACTIVE = 1 +PERFCOUNTER_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_TYPE' +PERFCOUNTER_INT_TYPE__enumvalues = { + 0: 'PERFCOUNTER_INT_TYPE_LEVEL', + 1: 'PERFCOUNTER_INT_TYPE_PULSE', +} +PERFCOUNTER_INT_TYPE_LEVEL = 0 +PERFCOUNTER_INT_TYPE_PULSE = 1 +PERFCOUNTER_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_COUNTED_VALUE_TYPE' +PERFCOUNTER_COUNTED_VALUE_TYPE__enumvalues = { + 0: 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 1: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 2: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', +} +PERFCOUNTER_COUNTED_VALUE_TYPE_ACC = 0 +PERFCOUNTER_COUNTED_VALUE_TYPE_MAX = 1 +PERFCOUNTER_COUNTED_VALUE_TYPE_MIN = 2 +PERFCOUNTER_COUNTED_VALUE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP1_SEL' +PERFCOUNTER_HW_STOP1_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP1_0', + 1: 'PERFCOUNTER_HW_STOP1_1', +} +PERFCOUNTER_HW_STOP1_0 = 0 +PERFCOUNTER_HW_STOP1_1 = 1 +PERFCOUNTER_HW_STOP1_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP2_SEL' +PERFCOUNTER_HW_STOP2_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP2_0', + 1: 'PERFCOUNTER_HW_STOP2_1', +} +PERFCOUNTER_HW_STOP2_0 = 0 +PERFCOUNTER_HW_STOP2_1 = 1 +PERFCOUNTER_HW_STOP2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTL_SEL' +PERFCOUNTER_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_CNTL_SEL_0', + 1: 'PERFCOUNTER_CNTL_SEL_1', + 2: 'PERFCOUNTER_CNTL_SEL_2', + 3: 'PERFCOUNTER_CNTL_SEL_3', + 4: 'PERFCOUNTER_CNTL_SEL_4', + 5: 'PERFCOUNTER_CNTL_SEL_5', + 6: 'PERFCOUNTER_CNTL_SEL_6', + 7: 'PERFCOUNTER_CNTL_SEL_7', +} +PERFCOUNTER_CNTL_SEL_0 = 0 +PERFCOUNTER_CNTL_SEL_1 = 1 +PERFCOUNTER_CNTL_SEL_2 = 2 +PERFCOUNTER_CNTL_SEL_3 = 3 +PERFCOUNTER_CNTL_SEL_4 = 4 +PERFCOUNTER_CNTL_SEL_5 = 5 +PERFCOUNTER_CNTL_SEL_6 = 6 +PERFCOUNTER_CNTL_SEL_7 = 7 +PERFCOUNTER_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT0_STATE' +PERFCOUNTER_CNT0_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT0_STATE_RESET', + 1: 'PERFCOUNTER_CNT0_STATE_START', + 2: 'PERFCOUNTER_CNT0_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT0_STATE_HW', +} +PERFCOUNTER_CNT0_STATE_RESET = 0 +PERFCOUNTER_CNT0_STATE_START = 1 +PERFCOUNTER_CNT0_STATE_FREEZE = 2 +PERFCOUNTER_CNT0_STATE_HW = 3 +PERFCOUNTER_CNT0_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL0' +PERFCOUNTER_STATE_SEL0__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL0_LOCAL', +} +PERFCOUNTER_STATE_SEL0_GLOBAL = 0 +PERFCOUNTER_STATE_SEL0_LOCAL = 1 +PERFCOUNTER_STATE_SEL0 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT1_STATE' +PERFCOUNTER_CNT1_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT1_STATE_RESET', + 1: 'PERFCOUNTER_CNT1_STATE_START', + 2: 'PERFCOUNTER_CNT1_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT1_STATE_HW', +} +PERFCOUNTER_CNT1_STATE_RESET = 0 +PERFCOUNTER_CNT1_STATE_START = 1 +PERFCOUNTER_CNT1_STATE_FREEZE = 2 +PERFCOUNTER_CNT1_STATE_HW = 3 +PERFCOUNTER_CNT1_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL1' +PERFCOUNTER_STATE_SEL1__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL1_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL1_LOCAL', +} +PERFCOUNTER_STATE_SEL1_GLOBAL = 0 +PERFCOUNTER_STATE_SEL1_LOCAL = 1 +PERFCOUNTER_STATE_SEL1 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT2_STATE' +PERFCOUNTER_CNT2_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT2_STATE_RESET', + 1: 'PERFCOUNTER_CNT2_STATE_START', + 2: 'PERFCOUNTER_CNT2_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT2_STATE_HW', +} +PERFCOUNTER_CNT2_STATE_RESET = 0 +PERFCOUNTER_CNT2_STATE_START = 1 +PERFCOUNTER_CNT2_STATE_FREEZE = 2 +PERFCOUNTER_CNT2_STATE_HW = 3 +PERFCOUNTER_CNT2_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL2' +PERFCOUNTER_STATE_SEL2__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL2_LOCAL', +} +PERFCOUNTER_STATE_SEL2_GLOBAL = 0 +PERFCOUNTER_STATE_SEL2_LOCAL = 1 +PERFCOUNTER_STATE_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT3_STATE' +PERFCOUNTER_CNT3_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT3_STATE_RESET', + 1: 'PERFCOUNTER_CNT3_STATE_START', + 2: 'PERFCOUNTER_CNT3_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT3_STATE_HW', +} +PERFCOUNTER_CNT3_STATE_RESET = 0 +PERFCOUNTER_CNT3_STATE_START = 1 +PERFCOUNTER_CNT3_STATE_FREEZE = 2 +PERFCOUNTER_CNT3_STATE_HW = 3 +PERFCOUNTER_CNT3_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL3' +PERFCOUNTER_STATE_SEL3__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL3_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL3_LOCAL', +} +PERFCOUNTER_STATE_SEL3_GLOBAL = 0 +PERFCOUNTER_STATE_SEL3_LOCAL = 1 +PERFCOUNTER_STATE_SEL3 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT4_STATE' +PERFCOUNTER_CNT4_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT4_STATE_RESET', + 1: 'PERFCOUNTER_CNT4_STATE_START', + 2: 'PERFCOUNTER_CNT4_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT4_STATE_HW', +} +PERFCOUNTER_CNT4_STATE_RESET = 0 +PERFCOUNTER_CNT4_STATE_START = 1 +PERFCOUNTER_CNT4_STATE_FREEZE = 2 +PERFCOUNTER_CNT4_STATE_HW = 3 +PERFCOUNTER_CNT4_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL4' +PERFCOUNTER_STATE_SEL4__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL4_LOCAL', +} +PERFCOUNTER_STATE_SEL4_GLOBAL = 0 +PERFCOUNTER_STATE_SEL4_LOCAL = 1 +PERFCOUNTER_STATE_SEL4 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT5_STATE' +PERFCOUNTER_CNT5_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT5_STATE_RESET', + 1: 'PERFCOUNTER_CNT5_STATE_START', + 2: 'PERFCOUNTER_CNT5_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT5_STATE_HW', +} +PERFCOUNTER_CNT5_STATE_RESET = 0 +PERFCOUNTER_CNT5_STATE_START = 1 +PERFCOUNTER_CNT5_STATE_FREEZE = 2 +PERFCOUNTER_CNT5_STATE_HW = 3 +PERFCOUNTER_CNT5_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL5' +PERFCOUNTER_STATE_SEL5__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL5_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL5_LOCAL', +} +PERFCOUNTER_STATE_SEL5_GLOBAL = 0 +PERFCOUNTER_STATE_SEL5_LOCAL = 1 +PERFCOUNTER_STATE_SEL5 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT6_STATE' +PERFCOUNTER_CNT6_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT6_STATE_RESET', + 1: 'PERFCOUNTER_CNT6_STATE_START', + 2: 'PERFCOUNTER_CNT6_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT6_STATE_HW', +} +PERFCOUNTER_CNT6_STATE_RESET = 0 +PERFCOUNTER_CNT6_STATE_START = 1 +PERFCOUNTER_CNT6_STATE_FREEZE = 2 +PERFCOUNTER_CNT6_STATE_HW = 3 +PERFCOUNTER_CNT6_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL6' +PERFCOUNTER_STATE_SEL6__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL6_LOCAL', +} +PERFCOUNTER_STATE_SEL6_GLOBAL = 0 +PERFCOUNTER_STATE_SEL6_LOCAL = 1 +PERFCOUNTER_STATE_SEL6 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT7_STATE' +PERFCOUNTER_CNT7_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT7_STATE_RESET', + 1: 'PERFCOUNTER_CNT7_STATE_START', + 2: 'PERFCOUNTER_CNT7_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT7_STATE_HW', +} +PERFCOUNTER_CNT7_STATE_RESET = 0 +PERFCOUNTER_CNT7_STATE_START = 1 +PERFCOUNTER_CNT7_STATE_FREEZE = 2 +PERFCOUNTER_CNT7_STATE_HW = 3 +PERFCOUNTER_CNT7_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL7' +PERFCOUNTER_STATE_SEL7__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL7_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL7_LOCAL', +} +PERFCOUNTER_STATE_SEL7_GLOBAL = 0 +PERFCOUNTER_STATE_SEL7_LOCAL = 1 +PERFCOUNTER_STATE_SEL7 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_STATE' +PERFMON_STATE__enumvalues = { + 0: 'PERFMON_STATE_RESET', + 1: 'PERFMON_STATE_START', + 2: 'PERFMON_STATE_FREEZE', + 3: 'PERFMON_STATE_HW', +} +PERFMON_STATE_RESET = 0 +PERFMON_STATE_START = 1 +PERFMON_STATE_FREEZE = 2 +PERFMON_STATE_HW = 3 +PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_AND_OR' +PERFMON_CNTOFF_AND_OR__enumvalues = { + 0: 'PERFMON_CNTOFF_OR', + 1: 'PERFMON_CNTOFF_AND', +} +PERFMON_CNTOFF_OR = 0 +PERFMON_CNTOFF_AND = 1 +PERFMON_CNTOFF_AND_OR = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_EN' +PERFMON_CNTOFF_INT_EN__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_DISABLE', + 1: 'PERFMON_CNTOFF_INT_ENABLE', +} +PERFMON_CNTOFF_INT_DISABLE = 0 +PERFMON_CNTOFF_INT_ENABLE = 1 +PERFMON_CNTOFF_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_TYPE' +PERFMON_CNTOFF_INT_TYPE__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_TYPE_LEVEL', + 1: 'PERFMON_CNTOFF_INT_TYPE_PULSE', +} +PERFMON_CNTOFF_INT_TYPE_LEVEL = 0 +PERFMON_CNTOFF_INT_TYPE_PULSE = 1 +PERFMON_CNTOFF_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ROTATION_ANGLE' +ROTATION_ANGLE__enumvalues = { + 0: 'ROTATE_0_DEGREES', + 1: 'ROTATE_90_DEGREES', + 2: 'ROTATE_180_DEGREES', + 3: 'ROTATE_270_DEGREES', +} +ROTATE_0_DEGREES = 0 +ROTATE_90_DEGREES = 1 +ROTATE_180_DEGREES = 2 +ROTATE_270_DEGREES = 3 +ROTATION_ANGLE = ctypes.c_uint32 # enum + +# values for enumeration 'H_MIRROR_EN' +H_MIRROR_EN__enumvalues = { + 0: 'HW_MIRRORING_DISABLE', + 1: 'HW_MIRRORING_ENABLE', +} +HW_MIRRORING_DISABLE = 0 +HW_MIRRORING_ENABLE = 1 +H_MIRROR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_PIPES' +NUM_PIPES__enumvalues = { + 0: 'ONE_PIPE', + 1: 'TWO_PIPES', + 2: 'FOUR_PIPES', + 3: 'EIGHT_PIPES', + 4: 'SIXTEEN_PIPES', + 5: 'THIRTY_TWO_PIPES', + 6: 'SIXTY_FOUR_PIPES', +} +ONE_PIPE = 0 +TWO_PIPES = 1 +FOUR_PIPES = 2 +EIGHT_PIPES = 3 +SIXTEEN_PIPES = 4 +THIRTY_TWO_PIPES = 5 +SIXTY_FOUR_PIPES = 6 +NUM_PIPES = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_BANKS' +NUM_BANKS__enumvalues = { + 0: 'ONE_BANK', + 1: 'TWO_BANKS', + 2: 'FOUR_BANKS', + 3: 'EIGHT_BANKS', + 4: 'SIXTEEN_BANKS', +} +ONE_BANK = 0 +TWO_BANKS = 1 +FOUR_BANKS = 2 +EIGHT_BANKS = 3 +SIXTEEN_BANKS = 4 +NUM_BANKS = ctypes.c_uint32 # enum + +# values for enumeration 'SW_MODE' +SW_MODE__enumvalues = { + 0: 'SWIZZLE_LINEAR', + 5: 'SWIZZLE_4KB_S', + 6: 'SWIZZLE_4KB_D', + 9: 'SWIZZLE_64KB_S', + 10: 'SWIZZLE_64KB_D', + 13: 'SWIZZLE_VAR_S', + 14: 'SWIZZLE_VAR_D', + 17: 'SWIZZLE_64KB_S_T', + 18: 'SWIZZLE_64KB_D_T', + 21: 'SWIZZLE_4KB_S_X', + 22: 'SWIZZLE_4KB_D_X', + 25: 'SWIZZLE_64KB_S_X', + 26: 'SWIZZLE_64KB_D_X', + 27: 'SWIZZLE_64KB_R_X', + 29: 'SWIZZLE_VAR_S_X', + 30: 'SWIZZLE_VAR_D_X', +} +SWIZZLE_LINEAR = 0 +SWIZZLE_4KB_S = 5 +SWIZZLE_4KB_D = 6 +SWIZZLE_64KB_S = 9 +SWIZZLE_64KB_D = 10 +SWIZZLE_VAR_S = 13 +SWIZZLE_VAR_D = 14 +SWIZZLE_64KB_S_T = 17 +SWIZZLE_64KB_D_T = 18 +SWIZZLE_4KB_S_X = 21 +SWIZZLE_4KB_D_X = 22 +SWIZZLE_64KB_S_X = 25 +SWIZZLE_64KB_D_X = 26 +SWIZZLE_64KB_R_X = 27 +SWIZZLE_VAR_S_X = 29 +SWIZZLE_VAR_D_X = 30 +SW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_INTERLEAVE' +PIPE_INTERLEAVE__enumvalues = { + 0: 'PIPE_INTERLEAVE_256B', + 1: 'PIPE_INTERLEAVE_512B', + 2: 'PIPE_INTERLEAVE_1KB', +} +PIPE_INTERLEAVE_256B = 0 +PIPE_INTERLEAVE_512B = 1 +PIPE_INTERLEAVE_1KB = 2 +PIPE_INTERLEAVE = ctypes.c_uint32 # enum + +# values for enumeration 'LEGACY_PIPE_INTERLEAVE' +LEGACY_PIPE_INTERLEAVE__enumvalues = { + 0: 'LEGACY_PIPE_INTERLEAVE_256B', + 1: 'LEGACY_PIPE_INTERLEAVE_512B', +} +LEGACY_PIPE_INTERLEAVE_256B = 0 +LEGACY_PIPE_INTERLEAVE_512B = 1 +LEGACY_PIPE_INTERLEAVE = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_SE' +NUM_SE__enumvalues = { + 0: 'ONE_SHADER_ENGIN', + 1: 'TWO_SHADER_ENGINS', + 2: 'FOUR_SHADER_ENGINS', + 3: 'EIGHT_SHADER_ENGINS', +} +ONE_SHADER_ENGIN = 0 +TWO_SHADER_ENGINS = 1 +FOUR_SHADER_ENGINS = 2 +EIGHT_SHADER_ENGINS = 3 +NUM_SE = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_RB_PER_SE' +NUM_RB_PER_SE__enumvalues = { + 0: 'ONE_RB_PER_SE', + 1: 'TWO_RB_PER_SE', + 2: 'FOUR_RB_PER_SE', +} +ONE_RB_PER_SE = 0 +TWO_RB_PER_SE = 1 +FOUR_RB_PER_SE = 2 +NUM_RB_PER_SE = ctypes.c_uint32 # enum + +# values for enumeration 'MAX_COMPRESSED_FRAGS' +MAX_COMPRESSED_FRAGS__enumvalues = { + 0: 'ONE_FRAGMENT', + 1: 'TWO_FRAGMENTS', + 2: 'FOUR_FRAGMENTS', + 3: 'EIGHT_FRAGMENTS', +} +ONE_FRAGMENT = 0 +TWO_FRAGMENTS = 1 +FOUR_FRAGMENTS = 2 +EIGHT_FRAGMENTS = 3 +MAX_COMPRESSED_FRAGS = ctypes.c_uint32 # enum + +# values for enumeration 'DIM_TYPE' +DIM_TYPE__enumvalues = { + 0: 'DIM_TYPE_1D', + 1: 'DIM_TYPE_2D', + 2: 'DIM_TYPE_3D', + 3: 'DIM_TYPE_RESERVED', +} +DIM_TYPE_1D = 0 +DIM_TYPE_2D = 1 +DIM_TYPE_3D = 2 +DIM_TYPE_RESERVED = 3 +DIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'META_LINEAR' +META_LINEAR__enumvalues = { + 0: 'META_SURF_TILED', + 1: 'META_SURF_LINEAR', +} +META_SURF_TILED = 0 +META_SURF_LINEAR = 1 +META_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'RB_ALIGNED' +RB_ALIGNED__enumvalues = { + 0: 'RB_UNALIGNED_META_SURF', + 1: 'RB_ALIGNED_META_SURF', +} +RB_UNALIGNED_META_SURF = 0 +RB_ALIGNED_META_SURF = 1 +RB_ALIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_ALIGNED' +PIPE_ALIGNED__enumvalues = { + 0: 'PIPE_UNALIGNED_SURF', + 1: 'PIPE_ALIGNED_SURF', +} +PIPE_UNALIGNED_SURF = 0 +PIPE_ALIGNED_SURF = 1 +PIPE_ALIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'ARRAY_MODE' +ARRAY_MODE__enumvalues = { + 0: 'AM_LINEAR_GENERAL', + 1: 'AM_LINEAR_ALIGNED', + 2: 'AM_1D_TILED_THIN1', + 3: 'AM_1D_TILED_THICK', + 4: 'AM_2D_TILED_THIN1', + 5: 'AM_PRT_TILED_THIN1', + 6: 'AM_PRT_2D_TILED_THIN1', + 7: 'AM_2D_TILED_THICK', + 8: 'AM_2D_TILED_XTHICK', + 9: 'AM_PRT_TILED_THICK', + 10: 'AM_PRT_2D_TILED_THICK', + 11: 'AM_PRT_3D_TILED_THIN1', + 12: 'AM_3D_TILED_THIN1', + 13: 'AM_3D_TILED_THICK', + 14: 'AM_3D_TILED_XTHICK', + 15: 'AM_PRT_3D_TILED_THICK', +} +AM_LINEAR_GENERAL = 0 +AM_LINEAR_ALIGNED = 1 +AM_1D_TILED_THIN1 = 2 +AM_1D_TILED_THICK = 3 +AM_2D_TILED_THIN1 = 4 +AM_PRT_TILED_THIN1 = 5 +AM_PRT_2D_TILED_THIN1 = 6 +AM_2D_TILED_THICK = 7 +AM_2D_TILED_XTHICK = 8 +AM_PRT_TILED_THICK = 9 +AM_PRT_2D_TILED_THICK = 10 +AM_PRT_3D_TILED_THIN1 = 11 +AM_3D_TILED_THIN1 = 12 +AM_3D_TILED_THICK = 13 +AM_3D_TILED_XTHICK = 14 +AM_PRT_3D_TILED_THICK = 15 +ARRAY_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_CONFIG' +PIPE_CONFIG__enumvalues = { + 0: 'P2', + 4: 'P4_8x16', + 5: 'P4_16x16', + 6: 'P4_16x32', + 7: 'P4_32x32', + 8: 'P8_16x16_8x16', + 9: 'P8_16x32_8x16', + 10: 'P8_32x32_8x16', + 11: 'P8_16x32_16x16', + 12: 'P8_32x32_16x16', + 13: 'P8_32x32_16x32', + 14: 'P8_32x64_32x32', + 16: 'P16_32x32_8x16', + 17: 'P16_32x32_16x16', + 18: 'P16_ADDR_SURF', +} +P2 = 0 +P4_8x16 = 4 +P4_16x16 = 5 +P4_16x32 = 6 +P4_32x32 = 7 +P8_16x16_8x16 = 8 +P8_16x32_8x16 = 9 +P8_32x32_8x16 = 10 +P8_16x32_16x16 = 11 +P8_32x32_16x16 = 12 +P8_32x32_16x32 = 13 +P8_32x64_32x32 = 14 +P16_32x32_8x16 = 16 +P16_32x32_16x16 = 17 +P16_ADDR_SURF = 18 +PIPE_CONFIG = ctypes.c_uint32 # enum + +# values for enumeration 'MICRO_TILE_MODE_NEW' +MICRO_TILE_MODE_NEW__enumvalues = { + 0: 'DISPLAY_MICRO_TILING', + 1: 'THIN_MICRO_TILING', + 2: 'DEPTH_MICRO_TILING', + 3: 'ROTATED_MICRO_TILING', + 4: 'THICK_MICRO_TILING', +} +DISPLAY_MICRO_TILING = 0 +THIN_MICRO_TILING = 1 +DEPTH_MICRO_TILING = 2 +ROTATED_MICRO_TILING = 3 +THICK_MICRO_TILING = 4 +MICRO_TILE_MODE_NEW = ctypes.c_uint32 # enum + +# values for enumeration 'TILE_SPLIT' +TILE_SPLIT__enumvalues = { + 0: 'SURF_TILE_SPLIT_64B', + 1: 'SURF_TILE_SPLIT_128B', + 2: 'SURF_TILE_SPLIT_256B', + 3: 'SURF_TILE_SPLIT_512B', + 4: 'SURF_TILE_SPLIT_1KB', + 5: 'SURF_TILE_SPLIT_2KB', + 6: 'SURF_TILE_SPLIT_4KB', +} +SURF_TILE_SPLIT_64B = 0 +SURF_TILE_SPLIT_128B = 1 +SURF_TILE_SPLIT_256B = 2 +SURF_TILE_SPLIT_512B = 3 +SURF_TILE_SPLIT_1KB = 4 +SURF_TILE_SPLIT_2KB = 5 +SURF_TILE_SPLIT_4KB = 6 +TILE_SPLIT = ctypes.c_uint32 # enum + +# values for enumeration 'BANK_WIDTH' +BANK_WIDTH__enumvalues = { + 0: 'SURF_BANK_WIDTH_1', + 1: 'SURF_BANK_WIDTH_2', + 2: 'SURF_BANK_WIDTH_4', + 3: 'SURF_BANK_WIDTH_8', +} +SURF_BANK_WIDTH_1 = 0 +SURF_BANK_WIDTH_2 = 1 +SURF_BANK_WIDTH_4 = 2 +SURF_BANK_WIDTH_8 = 3 +BANK_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'BANK_HEIGHT' +BANK_HEIGHT__enumvalues = { + 0: 'SURF_BANK_HEIGHT_1', + 1: 'SURF_BANK_HEIGHT_2', + 2: 'SURF_BANK_HEIGHT_4', + 3: 'SURF_BANK_HEIGHT_8', +} +SURF_BANK_HEIGHT_1 = 0 +SURF_BANK_HEIGHT_2 = 1 +SURF_BANK_HEIGHT_4 = 2 +SURF_BANK_HEIGHT_8 = 3 +BANK_HEIGHT = ctypes.c_uint32 # enum + +# values for enumeration 'MACRO_TILE_ASPECT' +MACRO_TILE_ASPECT__enumvalues = { + 0: 'SURF_MACRO_ASPECT_1', + 1: 'SURF_MACRO_ASPECT_2', + 2: 'SURF_MACRO_ASPECT_4', + 3: 'SURF_MACRO_ASPECT_8', +} +SURF_MACRO_ASPECT_1 = 0 +SURF_MACRO_ASPECT_2 = 1 +SURF_MACRO_ASPECT_4 = 2 +SURF_MACRO_ASPECT_8 = 3 +MACRO_TILE_ASPECT = ctypes.c_uint32 # enum + +# values for enumeration 'LEGACY_NUM_BANKS' +LEGACY_NUM_BANKS__enumvalues = { + 0: 'SURF_2_BANK', + 1: 'SURF_4_BANK', + 2: 'SURF_8_BANK', + 3: 'SURF_16_BANK', +} +SURF_2_BANK = 0 +SURF_4_BANK = 1 +SURF_8_BANK = 2 +SURF_16_BANK = 3 +LEGACY_NUM_BANKS = ctypes.c_uint32 # enum + +# values for enumeration 'SWATH_HEIGHT' +SWATH_HEIGHT__enumvalues = { + 0: 'SWATH_HEIGHT_1L', + 1: 'SWATH_HEIGHT_2L', + 2: 'SWATH_HEIGHT_4L', + 3: 'SWATH_HEIGHT_8L', + 4: 'SWATH_HEIGHT_16L', +} +SWATH_HEIGHT_1L = 0 +SWATH_HEIGHT_2L = 1 +SWATH_HEIGHT_4L = 2 +SWATH_HEIGHT_8L = 3 +SWATH_HEIGHT_16L = 4 +SWATH_HEIGHT = ctypes.c_uint32 # enum + +# values for enumeration 'PTE_ROW_HEIGHT_LINEAR' +PTE_ROW_HEIGHT_LINEAR__enumvalues = { + 0: 'PTE_ROW_HEIGHT_LINEAR_8L', + 1: 'PTE_ROW_HEIGHT_LINEAR_16L', + 2: 'PTE_ROW_HEIGHT_LINEAR_32L', + 3: 'PTE_ROW_HEIGHT_LINEAR_64L', + 4: 'PTE_ROW_HEIGHT_LINEAR_128L', + 5: 'PTE_ROW_HEIGHT_LINEAR_256L', + 6: 'PTE_ROW_HEIGHT_LINEAR_512L', + 7: 'PTE_ROW_HEIGHT_LINEAR_1024L', +} +PTE_ROW_HEIGHT_LINEAR_8L = 0 +PTE_ROW_HEIGHT_LINEAR_16L = 1 +PTE_ROW_HEIGHT_LINEAR_32L = 2 +PTE_ROW_HEIGHT_LINEAR_64L = 3 +PTE_ROW_HEIGHT_LINEAR_128L = 4 +PTE_ROW_HEIGHT_LINEAR_256L = 5 +PTE_ROW_HEIGHT_LINEAR_512L = 6 +PTE_ROW_HEIGHT_LINEAR_1024L = 7 +PTE_ROW_HEIGHT_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CHUNK_SIZE' +CHUNK_SIZE__enumvalues = { + 0: 'CHUNK_SIZE_1KB', + 1: 'CHUNK_SIZE_2KB', + 2: 'CHUNK_SIZE_4KB', + 3: 'CHUNK_SIZE_8KB', + 4: 'CHUNK_SIZE_16KB', + 5: 'CHUNK_SIZE_32KB', + 6: 'CHUNK_SIZE_64KB', +} +CHUNK_SIZE_1KB = 0 +CHUNK_SIZE_2KB = 1 +CHUNK_SIZE_4KB = 2 +CHUNK_SIZE_8KB = 3 +CHUNK_SIZE_16KB = 4 +CHUNK_SIZE_32KB = 5 +CHUNK_SIZE_64KB = 6 +CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_CHUNK_SIZE' +MIN_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_CHUNK_SIZE', + 1: 'MIN_CHUNK_SIZE_256B', + 2: 'MIN_CHUNK_SIZE_512B', + 3: 'MIN_CHUNK_SIZE_1024B', +} +NO_MIN_CHUNK_SIZE = 0 +MIN_CHUNK_SIZE_256B = 1 +MIN_CHUNK_SIZE_512B = 2 +MIN_CHUNK_SIZE_1024B = 3 +MIN_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'META_CHUNK_SIZE' +META_CHUNK_SIZE__enumvalues = { + 0: 'META_CHUNK_SIZE_1KB', + 1: 'META_CHUNK_SIZE_2KB', + 2: 'META_CHUNK_SIZE_4KB', + 3: 'META_CHUNK_SIZE_8KB', +} +META_CHUNK_SIZE_1KB = 0 +META_CHUNK_SIZE_2KB = 1 +META_CHUNK_SIZE_4KB = 2 +META_CHUNK_SIZE_8KB = 3 +META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_META_CHUNK_SIZE' +MIN_META_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_META_CHUNK_SIZE', + 1: 'MIN_META_CHUNK_SIZE_64B', + 2: 'MIN_META_CHUNK_SIZE_128B', + 3: 'MIN_META_CHUNK_SIZE_256B', +} +NO_MIN_META_CHUNK_SIZE = 0 +MIN_META_CHUNK_SIZE_64B = 1 +MIN_META_CHUNK_SIZE_128B = 2 +MIN_META_CHUNK_SIZE_256B = 3 +MIN_META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DPTE_GROUP_SIZE' +DPTE_GROUP_SIZE__enumvalues = { + 0: 'DPTE_GROUP_SIZE_64B', + 1: 'DPTE_GROUP_SIZE_128B', + 2: 'DPTE_GROUP_SIZE_256B', + 3: 'DPTE_GROUP_SIZE_512B', + 4: 'DPTE_GROUP_SIZE_1024B', + 5: 'DPTE_GROUP_SIZE_2048B', + 6: 'DPTE_GROUP_SIZE_4096B', + 7: 'DPTE_GROUP_SIZE_8192B', +} +DPTE_GROUP_SIZE_64B = 0 +DPTE_GROUP_SIZE_128B = 1 +DPTE_GROUP_SIZE_256B = 2 +DPTE_GROUP_SIZE_512B = 3 +DPTE_GROUP_SIZE_1024B = 4 +DPTE_GROUP_SIZE_2048B = 5 +DPTE_GROUP_SIZE_4096B = 6 +DPTE_GROUP_SIZE_8192B = 7 +DPTE_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'MPTE_GROUP_SIZE' +MPTE_GROUP_SIZE__enumvalues = { + 0: 'MPTE_GROUP_SIZE_64B', + 1: 'MPTE_GROUP_SIZE_128B', + 2: 'MPTE_GROUP_SIZE_256B', + 3: 'MPTE_GROUP_SIZE_512B', + 4: 'MPTE_GROUP_SIZE_1024B', + 5: 'MPTE_GROUP_SIZE_2048B', + 6: 'MPTE_GROUP_SIZE_4096B', + 7: 'MPTE_GROUP_SIZE_8192B', +} +MPTE_GROUP_SIZE_64B = 0 +MPTE_GROUP_SIZE_128B = 1 +MPTE_GROUP_SIZE_256B = 2 +MPTE_GROUP_SIZE_512B = 3 +MPTE_GROUP_SIZE_1024B = 4 +MPTE_GROUP_SIZE_2048B = 5 +MPTE_GROUP_SIZE_4096B = 6 +MPTE_GROUP_SIZE_8192B = 7 +MPTE_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_BLANK_EN' +HUBP_BLANK_EN__enumvalues = { + 0: 'HUBP_BLANK_SW_DEASSERT', + 1: 'HUBP_BLANK_SW_ASSERT', +} +HUBP_BLANK_SW_DEASSERT = 0 +HUBP_BLANK_SW_ASSERT = 1 +HUBP_BLANK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_DISABLE' +HUBP_DISABLE__enumvalues = { + 0: 'HUBP_ENABLED', + 1: 'HUBP_DISABLED', +} +HUBP_ENABLED = 0 +HUBP_DISABLED = 1 +HUBP_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_TTU_DISABLE' +HUBP_TTU_DISABLE__enumvalues = { + 0: 'HUBP_TTU_ENABLED', + 1: 'HUBP_TTU_DISABLED', +} +HUBP_TTU_ENABLED = 0 +HUBP_TTU_DISABLED = 1 +HUBP_TTU_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_NO_OUTSTANDING_REQ' +HUBP_NO_OUTSTANDING_REQ__enumvalues = { + 0: 'OUTSTANDING_REQ', + 1: 'NO_OUTSTANDING_REQ', +} +OUTSTANDING_REQ = 0 +NO_OUTSTANDING_REQ = 1 +HUBP_NO_OUTSTANDING_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_IN_BLANK' +HUBP_IN_BLANK__enumvalues = { + 0: 'HUBP_IN_ACTIVE', + 1: 'HUBP_IN_VBLANK', +} +HUBP_IN_ACTIVE = 0 +HUBP_IN_VBLANK = 1 +HUBP_IN_BLANK = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VTG_SEL' +HUBP_VTG_SEL__enumvalues = { + 0: 'VTG_SEL_0', + 1: 'VTG_SEL_1', + 2: 'VTG_SEL_2', + 3: 'VTG_SEL_3', + 4: 'VTG_SEL_4', + 5: 'VTG_SEL_5', +} +VTG_SEL_0 = 0 +VTG_SEL_1 = 1 +VTG_SEL_2 = 2 +VTG_SEL_3 = 3 +VTG_SEL_4 = 4 +VTG_SEL_5 = 5 +HUBP_VTG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VREADY_AT_OR_AFTER_VSYNC' +HUBP_VREADY_AT_OR_AFTER_VSYNC__enumvalues = { + 0: 'VREADY_BEFORE_VSYNC', + 1: 'VREADY_AT_OR_AFTER_VSYNC', +} +VREADY_BEFORE_VSYNC = 0 +VREADY_AT_OR_AFTER_VSYNC = 1 +HUBP_VREADY_AT_OR_AFTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'VMPG_SIZE' +VMPG_SIZE__enumvalues = { + 0: 'VMPG_SIZE_4KB', + 1: 'VMPG_SIZE_64KB', +} +VMPG_SIZE_4KB = 0 +VMPG_SIZE_64KB = 1 +VMPG_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_MEASURE_WIN_MODE_DCFCLK' +HUBP_MEASURE_WIN_MODE_DCFCLK__enumvalues = { + 0: 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 1: 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 2: 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 3: 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', +} +HUBP_MEASURE_WIN_MODE_DCFCLK_0 = 0 +HUBP_MEASURE_WIN_MODE_DCFCLK_1 = 1 +HUBP_MEASURE_WIN_MODE_DCFCLK_2 = 2 +HUBP_MEASURE_WIN_MODE_DCFCLK_3 = 3 +HUBP_MEASURE_WIN_MODE_DCFCLK = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_TMZ' +SURFACE_TMZ__enumvalues = { + 0: 'SURFACE_IS_NOT_TMZ', + 1: 'SURFACE_IS_TMZ', +} +SURFACE_IS_NOT_TMZ = 0 +SURFACE_IS_TMZ = 1 +SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC' +SURFACE_DCC__enumvalues = { + 0: 'SURFACE_IS_NOT_DCC', + 1: 'SURFACE_IS_DCC', +} +SURFACE_IS_NOT_DCC = 0 +SURFACE_IS_DCC = 1 +SURFACE_DCC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_64B' +SURFACE_DCC_IND_64B__enumvalues = { + 0: 'SURFACE_DCC_IS_NOT_IND_64B', + 1: 'SURFACE_DCC_IS_IND_64B', +} +SURFACE_DCC_IS_NOT_IND_64B = 0 +SURFACE_DCC_IS_IND_64B = 1 +SURFACE_DCC_IND_64B = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_TYPE' +SURFACE_FLIP_TYPE__enumvalues = { + 0: 'SURFACE_V_FLIP', + 1: 'SURFACE_I_FLIP', +} +SURFACE_V_FLIP = 0 +SURFACE_I_FLIP = 1 +SURFACE_FLIP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_MODE_FOR_STEREOSYNC' +SURFACE_FLIP_MODE_FOR_STEREOSYNC__enumvalues = { + 0: 'FLIP_ANY_FRAME', + 1: 'FLIP_LEFT_EYE', + 2: 'FLIP_RIGHT_EYE', + 3: 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', +} +FLIP_ANY_FRAME = 0 +FLIP_LEFT_EYE = 1 +FLIP_RIGHT_EYE = 2 +SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED = 3 +SURFACE_FLIP_MODE_FOR_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_UPDATE_LOCK' +SURFACE_UPDATE_LOCK__enumvalues = { + 0: 'SURFACE_UPDATE_IS_UNLOCKED', + 1: 'SURFACE_UPDATE_IS_LOCKED', +} +SURFACE_UPDATE_IS_UNLOCKED = 0 +SURFACE_UPDATE_IS_LOCKED = 1 +SURFACE_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_IN_STEREOSYNC' +SURFACE_FLIP_IN_STEREOSYNC__enumvalues = { + 0: 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 1: 'SURFACE_FLIP_IN_STEREOSYNC_MODE', +} +SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE = 0 +SURFACE_FLIP_IN_STEREOSYNC_MODE = 1 +SURFACE_FLIP_IN_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_DISABLE' +SURFACE_FLIP_STEREO_SELECT_DISABLE__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 1: 'SURFACE_FLIP_STEREO_SELECT_DISABLED', +} +SURFACE_FLIP_STEREO_SELECT_ENABLED = 0 +SURFACE_FLIP_STEREO_SELECT_DISABLED = 1 +SURFACE_FLIP_STEREO_SELECT_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_POLARITY' +SURFACE_FLIP_STEREO_SELECT_POLARITY__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 1: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', +} +SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT = 0 +SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT = 1 +SURFACE_FLIP_STEREO_SELECT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_INUSE_RAED_NO_LATCH' +SURFACE_INUSE_RAED_NO_LATCH__enumvalues = { + 0: 'SURFACE_INUSE_IS_LATCHED', + 1: 'SURFACE_INUSE_IS_NOT_LATCHED', +} +SURFACE_INUSE_IS_LATCHED = 0 +SURFACE_INUSE_IS_NOT_LATCHED = 1 +SURFACE_INUSE_RAED_NO_LATCH = ctypes.c_uint32 # enum + +# values for enumeration 'INT_MASK' +INT_MASK__enumvalues = { + 0: 'INT_DISABLED', + 1: 'INT_ENABLED', +} +INT_DISABLED = 0 +INT_ENABLED = 1 +INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_INT_TYPE' +SURFACE_FLIP_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_INT_LEVEL', + 1: 'SURFACE_FLIP_INT_PULSE', +} +SURFACE_FLIP_INT_LEVEL = 0 +SURFACE_FLIP_INT_PULSE = 1 +SURFACE_FLIP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_AWAY_INT_TYPE' +SURFACE_FLIP_AWAY_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_AWAY_INT_LEVEL', + 1: 'SURFACE_FLIP_AWAY_INT_PULSE', +} +SURFACE_FLIP_AWAY_INT_LEVEL = 0 +SURFACE_FLIP_AWAY_INT_PULSE = 1 +SURFACE_FLIP_AWAY_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_VUPDATE_SKIP_NUM' +SURFACE_FLIP_VUPDATE_SKIP_NUM__enumvalues = { + 0: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 1: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 2: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 3: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 4: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 5: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 6: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 7: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 8: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 9: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', + 10: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 11: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 12: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 13: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 14: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 15: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', +} +SURFACE_FLIP_VUPDATE_SKIP_NUM_0 = 0 +SURFACE_FLIP_VUPDATE_SKIP_NUM_1 = 1 +SURFACE_FLIP_VUPDATE_SKIP_NUM_2 = 2 +SURFACE_FLIP_VUPDATE_SKIP_NUM_3 = 3 +SURFACE_FLIP_VUPDATE_SKIP_NUM_4 = 4 +SURFACE_FLIP_VUPDATE_SKIP_NUM_5 = 5 +SURFACE_FLIP_VUPDATE_SKIP_NUM_6 = 6 +SURFACE_FLIP_VUPDATE_SKIP_NUM_7 = 7 +SURFACE_FLIP_VUPDATE_SKIP_NUM_8 = 8 +SURFACE_FLIP_VUPDATE_SKIP_NUM_9 = 9 +SURFACE_FLIP_VUPDATE_SKIP_NUM_10 = 10 +SURFACE_FLIP_VUPDATE_SKIP_NUM_11 = 11 +SURFACE_FLIP_VUPDATE_SKIP_NUM_12 = 12 +SURFACE_FLIP_VUPDATE_SKIP_NUM_13 = 13 +SURFACE_FLIP_VUPDATE_SKIP_NUM_14 = 14 +SURFACE_FLIP_VUPDATE_SKIP_NUM_15 = 15 +SURFACE_FLIP_VUPDATE_SKIP_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_SIZE' +DFQ_SIZE__enumvalues = { + 0: 'DFQ_SIZE_0', + 1: 'DFQ_SIZE_1', + 2: 'DFQ_SIZE_2', + 3: 'DFQ_SIZE_3', + 4: 'DFQ_SIZE_4', + 5: 'DFQ_SIZE_5', + 6: 'DFQ_SIZE_6', + 7: 'DFQ_SIZE_7', +} +DFQ_SIZE_0 = 0 +DFQ_SIZE_1 = 1 +DFQ_SIZE_2 = 2 +DFQ_SIZE_3 = 3 +DFQ_SIZE_4 = 4 +DFQ_SIZE_5 = 5 +DFQ_SIZE_6 = 6 +DFQ_SIZE_7 = 7 +DFQ_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_MIN_FREE_ENTRIES' +DFQ_MIN_FREE_ENTRIES__enumvalues = { + 0: 'DFQ_MIN_FREE_ENTRIES_0', + 1: 'DFQ_MIN_FREE_ENTRIES_1', + 2: 'DFQ_MIN_FREE_ENTRIES_2', + 3: 'DFQ_MIN_FREE_ENTRIES_3', + 4: 'DFQ_MIN_FREE_ENTRIES_4', + 5: 'DFQ_MIN_FREE_ENTRIES_5', + 6: 'DFQ_MIN_FREE_ENTRIES_6', + 7: 'DFQ_MIN_FREE_ENTRIES_7', +} +DFQ_MIN_FREE_ENTRIES_0 = 0 +DFQ_MIN_FREE_ENTRIES_1 = 1 +DFQ_MIN_FREE_ENTRIES_2 = 2 +DFQ_MIN_FREE_ENTRIES_3 = 3 +DFQ_MIN_FREE_ENTRIES_4 = 4 +DFQ_MIN_FREE_ENTRIES_5 = 5 +DFQ_MIN_FREE_ENTRIES_6 = 6 +DFQ_MIN_FREE_ENTRIES_7 = 7 +DFQ_MIN_FREE_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_NUM_ENTRIES' +DFQ_NUM_ENTRIES__enumvalues = { + 0: 'DFQ_NUM_ENTRIES_0', + 1: 'DFQ_NUM_ENTRIES_1', + 2: 'DFQ_NUM_ENTRIES_2', + 3: 'DFQ_NUM_ENTRIES_3', + 4: 'DFQ_NUM_ENTRIES_4', + 5: 'DFQ_NUM_ENTRIES_5', + 6: 'DFQ_NUM_ENTRIES_6', + 7: 'DFQ_NUM_ENTRIES_7', + 8: 'DFQ_NUM_ENTRIES_8', +} +DFQ_NUM_ENTRIES_0 = 0 +DFQ_NUM_ENTRIES_1 = 1 +DFQ_NUM_ENTRIES_2 = 2 +DFQ_NUM_ENTRIES_3 = 3 +DFQ_NUM_ENTRIES_4 = 4 +DFQ_NUM_ENTRIES_5 = 5 +DFQ_NUM_ENTRIES_6 = 6 +DFQ_NUM_ENTRIES_7 = 7 +DFQ_NUM_ENTRIES_8 = 8 +DFQ_NUM_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'FLIP_RATE' +FLIP_RATE__enumvalues = { + 0: 'FLIP_RATE_0', + 1: 'FLIP_RATE_1', + 2: 'FLIP_RATE_2', + 3: 'FLIP_RATE_3', + 4: 'FLIP_RATE_4', + 5: 'FLIP_RATE_5', + 6: 'FLIP_RATE_6', + 7: 'FLIP_RATE_7', +} +FLIP_RATE_0 = 0 +FLIP_RATE_1 = 1 +FLIP_RATE_2 = 2 +FLIP_RATE_3 = 3 +FLIP_RATE_4 = 4 +FLIP_RATE_5 = 5 +FLIP_RATE_6 = 6 +FLIP_RATE_7 = 7 +FLIP_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DETILE_BUFFER_PACKER_ENABLE' +DETILE_BUFFER_PACKER_ENABLE__enumvalues = { + 0: 'DETILE_BUFFER_PACKER_IS_DISABLE', + 1: 'DETILE_BUFFER_PACKER_IS_ENABLE', +} +DETILE_BUFFER_PACKER_IS_DISABLE = 0 +DETILE_BUFFER_PACKER_IS_ENABLE = 1 +DETILE_BUFFER_PACKER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_ALPHA' +CROSSBAR_FOR_ALPHA__enumvalues = { + 0: 'ALPHA_DATA_ON_ALPHA_PORT', + 1: 'ALPHA_DATA_ON_Y_G_PORT', + 2: 'ALPHA_DATA_ON_CB_B_PORT', + 3: 'ALPHA_DATA_ON_CR_R_PORT', +} +ALPHA_DATA_ON_ALPHA_PORT = 0 +ALPHA_DATA_ON_Y_G_PORT = 1 +ALPHA_DATA_ON_CB_B_PORT = 2 +ALPHA_DATA_ON_CR_R_PORT = 3 +CROSSBAR_FOR_ALPHA = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_Y_G' +CROSSBAR_FOR_Y_G__enumvalues = { + 0: 'Y_G_DATA_ON_ALPHA_PORT', + 1: 'Y_G_DATA_ON_Y_G_PORT', + 2: 'Y_G_DATA_ON_CB_B_PORT', + 3: 'Y_G_DATA_ON_CR_R_PORT', +} +Y_G_DATA_ON_ALPHA_PORT = 0 +Y_G_DATA_ON_Y_G_PORT = 1 +Y_G_DATA_ON_CB_B_PORT = 2 +Y_G_DATA_ON_CR_R_PORT = 3 +CROSSBAR_FOR_Y_G = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CB_B' +CROSSBAR_FOR_CB_B__enumvalues = { + 0: 'CB_B_DATA_ON_ALPHA_PORT', + 1: 'CB_B_DATA_ON_Y_G_PORT', + 2: 'CB_B_DATA_ON_CB_B_PORT', + 3: 'CB_B_DATA_ON_CR_R_PORT', +} +CB_B_DATA_ON_ALPHA_PORT = 0 +CB_B_DATA_ON_Y_G_PORT = 1 +CB_B_DATA_ON_CB_B_PORT = 2 +CB_B_DATA_ON_CR_R_PORT = 3 +CROSSBAR_FOR_CB_B = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CR_R' +CROSSBAR_FOR_CR_R__enumvalues = { + 0: 'CR_R_DATA_ON_ALPHA_PORT', + 1: 'CR_R_DATA_ON_Y_G_PORT', + 2: 'CR_R_DATA_ON_CB_B_PORT', + 3: 'CR_R_DATA_ON_CR_R_PORT', +} +CR_R_DATA_ON_ALPHA_PORT = 0 +CR_R_DATA_ON_Y_G_PORT = 1 +CR_R_DATA_ON_CB_B_PORT = 2 +CR_R_DATA_ON_CR_R_PORT = 3 +CROSSBAR_FOR_CR_R = ctypes.c_uint32 # enum + +# values for enumeration 'DET_MEM_PWR_LIGHT_SLEEP_MODE' +DET_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'DET_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +DET_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +DET_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +DET_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE' +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', +} +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_ENABLE' +CURSOR_ENABLE__enumvalues = { + 0: 'CURSOR_IS_DISABLE', + 1: 'CURSOR_IS_ENABLE', +} +CURSOR_IS_DISABLE = 0 +CURSOR_IS_ENABLE = 1 +CURSOR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_2X_MAGNIFY' +CURSOR_2X_MAGNIFY__enumvalues = { + 0: 'CURSOR_2X_MAGNIFY_IS_DISABLE', + 1: 'CURSOR_2X_MAGNIFY_IS_ENABLE', +} +CURSOR_2X_MAGNIFY_IS_DISABLE = 0 +CURSOR_2X_MAGNIFY_IS_ENABLE = 1 +CURSOR_2X_MAGNIFY = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_MODE' +CURSOR_MODE__enumvalues = { + 0: 'CURSOR_MONO_2BIT', + 1: 'CURSOR_COLOR_24BIT_1BIT_AND', + 2: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'CURSOR_COLOR_64BIT_FP_PREMULT', + 5: 'CURSOR_COLOR_64BIT_FP_UNPREMULT', +} +CURSOR_MONO_2BIT = 0 +CURSOR_COLOR_24BIT_1BIT_AND = 1 +CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +CURSOR_COLOR_64BIT_FP_PREMULT = 4 +CURSOR_COLOR_64BIT_FP_UNPREMULT = 5 +CURSOR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SURFACE_TMZ' +CURSOR_SURFACE_TMZ__enumvalues = { + 0: 'CURSOR_SURFACE_IS_NOT_TMZ', + 1: 'CURSOR_SURFACE_IS_TMZ', +} +CURSOR_SURFACE_IS_NOT_TMZ = 0 +CURSOR_SURFACE_IS_TMZ = 1 +CURSOR_SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SNOOP' +CURSOR_SNOOP__enumvalues = { + 0: 'CURSOR_IS_NOT_SNOOP', + 1: 'CURSOR_IS_SNOOP', +} +CURSOR_IS_NOT_SNOOP = 0 +CURSOR_IS_SNOOP = 1 +CURSOR_SNOOP = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SYSTEM' +CURSOR_SYSTEM__enumvalues = { + 0: 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', + 1: 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', +} +CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS = 0 +CURSOR_IN_GUEST_PHYSICAL_ADDRESS = 1 +CURSOR_SYSTEM = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PITCH' +CURSOR_PITCH__enumvalues = { + 0: 'CURSOR_PITCH_64_PIXELS', + 1: 'CURSOR_PITCH_128_PIXELS', + 2: 'CURSOR_PITCH_256_PIXELS', +} +CURSOR_PITCH_64_PIXELS = 0 +CURSOR_PITCH_128_PIXELS = 1 +CURSOR_PITCH_256_PIXELS = 2 +CURSOR_PITCH = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_LINES_PER_CHUNK' +CURSOR_LINES_PER_CHUNK__enumvalues = { + 0: 'CURSOR_LINE_PER_CHUNK_1', + 1: 'CURSOR_LINE_PER_CHUNK_2', + 2: 'CURSOR_LINE_PER_CHUNK_4', + 3: 'CURSOR_LINE_PER_CHUNK_8', + 4: 'CURSOR_LINE_PER_CHUNK_16', +} +CURSOR_LINE_PER_CHUNK_1 = 0 +CURSOR_LINE_PER_CHUNK_2 = 1 +CURSOR_LINE_PER_CHUNK_4 = 2 +CURSOR_LINE_PER_CHUNK_8 = 3 +CURSOR_LINE_PER_CHUNK_16 = 4 +CURSOR_LINES_PER_CHUNK = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_EN' +CURSOR_PERFMON_LATENCY_MEASURE_EN__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', +} +CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED = 0 +CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED = 1 +CURSOR_PERFMON_LATENCY_MEASURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_SEL' +CURSOR_PERFMON_LATENCY_MEASURE_SEL__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', +} +CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY = 0 +CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY = 1 +CURSOR_PERFMON_LATENCY_MEASURE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_STEREO_EN' +CURSOR_STEREO_EN__enumvalues = { + 0: 'CURSOR_STEREO_IS_DISABLED', + 1: 'CURSOR_STEREO_IS_ENABLED', +} +CURSOR_STEREO_IS_DISABLED = 0 +CURSOR_STEREO_IS_ENABLED = 1 +CURSOR_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS' +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS__enumvalues = { + 0: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 1: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', +} +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0 = 0 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1 = 1 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CROB_MEM_PWR_LIGHT_SLEEP_MODE' +CROB_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +CROB_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UPDATED' +DMDATA_UPDATED__enumvalues = { + 0: 'DMDATA_NOT_UPDATED', + 1: 'DMDATA_WAS_UPDATED', +} +DMDATA_NOT_UPDATED = 0 +DMDATA_WAS_UPDATED = 1 +DMDATA_UPDATED = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_REPEAT' +DMDATA_REPEAT__enumvalues = { + 0: 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', + 1: 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', +} +DMDATA_USE_FOR_CURRENT_FRAME_ONLY = 0 +DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES = 1 +DMDATA_REPEAT = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_MODE' +DMDATA_MODE__enumvalues = { + 0: 'DMDATA_SOFTWARE_UPDATE_MODE', + 1: 'DMDATA_HARDWARE_UPDATE_MODE', +} +DMDATA_SOFTWARE_UPDATE_MODE = 0 +DMDATA_HARDWARE_UPDATE_MODE = 1 +DMDATA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_QOS_MODE' +DMDATA_QOS_MODE__enumvalues = { + 0: 'DMDATA_QOS_LEVEL_FROM_TTU', + 1: 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', +} +DMDATA_QOS_LEVEL_FROM_TTU = 0 +DMDATA_QOS_LEVEL_FROM_SOFTWARE = 1 +DMDATA_QOS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_DONE' +DMDATA_DONE__enumvalues = { + 0: 'DMDATA_NOT_SENT_TO_DIG', + 1: 'DMDATA_SENT_TO_DIG', +} +DMDATA_NOT_SENT_TO_DIG = 0 +DMDATA_SENT_TO_DIG = 1 +DMDATA_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW' +DMDATA_UNDERFLOW__enumvalues = { + 0: 'DMDATA_NOT_UNDERFLOW', + 1: 'DMDATA_UNDERFLOWED', +} +DMDATA_NOT_UNDERFLOW = 0 +DMDATA_UNDERFLOWED = 1 +DMDATA_UNDERFLOW = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW_CLEAR' +DMDATA_UNDERFLOW_CLEAR__enumvalues = { + 0: 'DMDATA_DONT_CLEAR', + 1: 'DMDATA_CLEAR_UNDERFLOW_STATUS', +} +DMDATA_DONT_CLEAR = 0 +DMDATA_CLEAR_UNDERFLOW_STATUS = 1 +DMDATA_UNDERFLOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_XFC_PIXEL_FORMAT_ENUM' +HUBP_XFC_PIXEL_FORMAT_ENUM__enumvalues = { + 0: 'HUBP_XFC_PIXEL_IS_32BPP', + 1: 'HUBP_XFC_PIXEL_IS_64BPP', +} +HUBP_XFC_PIXEL_IS_32BPP = 0 +HUBP_XFC_PIXEL_IS_64BPP = 1 +HUBP_XFC_PIXEL_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_XFC_FRAME_MODE_ENUM' +HUBP_XFC_FRAME_MODE_ENUM__enumvalues = { + 0: 'HUBP_XFC_PARTIAL_FRAME_MODE', + 1: 'HUBP_XFC_FULL_FRAME_MODE', +} +HUBP_XFC_PARTIAL_FRAME_MODE = 0 +HUBP_XFC_FULL_FRAME_MODE = 1 +HUBP_XFC_FRAME_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_XFC_CHUNK_SIZE_ENUM' +HUBP_XFC_CHUNK_SIZE_ENUM__enumvalues = { + 0: 'HUBP_XFC_CHUNK_SIZE_256B', + 1: 'HUBP_XFC_CHUNK_SIZE_512B', + 2: 'HUBP_XFC_CHUNK_SIZE_1KB', + 3: 'HUBP_XFC_CHUNK_SIZE_2KB', + 4: 'HUBP_XFC_CHUNK_SIZE_4KB', + 5: 'HUBP_XFC_CHUNK_SIZE_8KB', + 6: 'HUBP_XFC_CHUNK_SIZE_16KB', + 7: 'HUBP_XFC_CHUNK_SIZE_32KB', +} +HUBP_XFC_CHUNK_SIZE_256B = 0 +HUBP_XFC_CHUNK_SIZE_512B = 1 +HUBP_XFC_CHUNK_SIZE_1KB = 2 +HUBP_XFC_CHUNK_SIZE_2KB = 3 +HUBP_XFC_CHUNK_SIZE_4KB = 4 +HUBP_XFC_CHUNK_SIZE_8KB = 5 +HUBP_XFC_CHUNK_SIZE_16KB = 6 +HUBP_XFC_CHUNK_SIZE_32KB = 7 +HUBP_XFC_CHUNK_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MMHUBBUB_XFC_XFCMON_MODE_ENUM' +MMHUBBUB_XFC_XFCMON_MODE_ENUM__enumvalues = { + 0: 'MMHUBBUB_XFC_XFCMON_MODE_ONE_SHOT', + 1: 'MMHUBBUB_XFC_XFCMON_MODE_CONTINUOUS', + 2: 'MMHUBBUB_XFC_XFCMON_MODE_PERIODS', +} +MMHUBBUB_XFC_XFCMON_MODE_ONE_SHOT = 0 +MMHUBBUB_XFC_XFCMON_MODE_CONTINUOUS = 1 +MMHUBBUB_XFC_XFCMON_MODE_PERIODS = 2 +MMHUBBUB_XFC_XFCMON_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_ENUM' +MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_ENUM__enumvalues = { + 0: 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_SYSHUB', + 1: 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_MMHUB', +} +MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_SYSHUB = 0 +MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_MMHUB = 1 +MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MMHUBBUB_XFC_PIXEL_FORMAT_ENUM' +MMHUBBUB_XFC_PIXEL_FORMAT_ENUM__enumvalues = { + 0: 'MMHUBBUB_XFC_PIXEL_IS_32BPP', + 1: 'MMHUBBUB_XFC_PIXEL_IS_64BPP', +} +MMHUBBUB_XFC_PIXEL_IS_32BPP = 0 +MMHUBBUB_XFC_PIXEL_IS_64BPP = 1 +MMHUBBUB_XFC_PIXEL_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MMHUBBUB_XFC_FRAME_MODE_ENUM' +MMHUBBUB_XFC_FRAME_MODE_ENUM__enumvalues = { + 0: 'MMHUBBUB_XFC_PARTIAL_FRAME_MODE', + 1: 'MMHUBBUB_XFC_FULL_FRAME_MODE', +} +MMHUBBUB_XFC_PARTIAL_FRAME_MODE = 0 +MMHUBBUB_XFC_FULL_FRAME_MODE = 1 +MMHUBBUB_XFC_FRAME_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_MPC_TEST_CLK_SEL' +MPC_CFG_MPC_TEST_CLK_SEL__enumvalues = { + 0: 'MPC_CFG_MPC_TEST_CLK_SEL_0', + 1: 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 2: 'MPC_CFG_MPC_TEST_CLK_SEL_2', + 3: 'MPC_CFG_MPC_TEST_CLK_SEL_3', +} +MPC_CFG_MPC_TEST_CLK_SEL_0 = 0 +MPC_CFG_MPC_TEST_CLK_SEL_1 = 1 +MPC_CFG_MPC_TEST_CLK_SEL_2 = 2 +MPC_CFG_MPC_TEST_CLK_SEL_3 = 3 +MPC_CFG_MPC_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_MODE' +MPC_CRC_CALC_MODE__enumvalues = { + 0: 'MPC_CRC_ONE_SHOT_MODE', + 1: 'MPC_CRC_CONTINUOUS_MODE', +} +MPC_CRC_ONE_SHOT_MODE = 0 +MPC_CRC_CONTINUOUS_MODE = 1 +MPC_CRC_CALC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_STEREO_MODE' +MPC_CRC_CALC_STEREO_MODE__enumvalues = { + 0: 'MPC_CRC_STEREO_MODE_LEFT', + 1: 'MPC_CRC_STEREO_MODE_RIGHT', + 2: 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 3: 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', +} +MPC_CRC_STEREO_MODE_LEFT = 0 +MPC_CRC_STEREO_MODE_RIGHT = 1 +MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT = 2 +MPC_CRC_STEREO_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_INTERLACE_MODE' +MPC_CRC_CALC_INTERLACE_MODE__enumvalues = { + 0: 'MPC_CRC_INTERLACE_MODE_TOP', + 1: 'MPC_CRC_INTERLACE_MODE_BOTTOM', + 2: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 3: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', +} +MPC_CRC_INTERLACE_MODE_TOP = 0 +MPC_CRC_INTERLACE_MODE_BOTTOM = 1 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM = 2 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_SOURCE_SELECT' +MPC_CRC_SOURCE_SELECT__enumvalues = { + 0: 'MPC_CRC_SOURCE_SEL_DPP', + 1: 'MPC_CRC_SOURCE_SEL_OPP', + 2: 'MPC_CRC_SOURCE_SEL_DWB', + 3: 'MPC_CRC_SOURCE_SEL_OTHER', +} +MPC_CRC_SOURCE_SEL_DPP = 0 +MPC_CRC_SOURCE_SEL_OPP = 1 +MPC_CRC_SOURCE_SEL_DWB = 2 +MPC_CRC_SOURCE_SEL_OTHER = 3 +MPC_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CFG_VUPDATE_LOCK_SET' +MPC_CFG_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_RATE_CONTROL_DISABLE_SET' +MPC_OUT_RATE_CONTROL_DISABLE_SET__enumvalues = { + 0: 'MPC_OUT_RATE_CONTROL_SET_ENABLE', + 1: 'MPC_OUT_RATE_CONTROL_SET_DISABLE', +} +MPC_OUT_RATE_CONTROL_SET_ENABLE = 0 +MPC_OUT_RATE_CONTROL_SET_DISABLE = 1 +MPC_OUT_RATE_CONTROL_DISABLE_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE' +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE__enumvalues = { + 0: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 1: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 2: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 3: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 4: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 5: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 6: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 7: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', +} +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS = 0 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS = 1 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS = 2 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS = 3 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS = 4 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS = 5 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS = 6 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH = 7 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OCSC_COEF_FORMAT' +MPC_OCSC_COEF_FORMAT__enumvalues = { + 0: 'MPC_OCSC_COEF_FORMAT_S2_13', + 1: 'MPC_OCSC_COEF_FORMAT_S3_12', +} +MPC_OCSC_COEF_FORMAT_S2_13 = 0 +MPC_OCSC_COEF_FORMAT_S3_12 = 1 +MPC_OCSC_COEF_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_CSC_MODE' +MPC_OUT_CSC_MODE__enumvalues = { + 0: 'MPC_OUT_CSC_MODE_0', + 1: 'MPC_OUT_CSC_MODE_1', + 2: 'MPC_OUT_CSC_MODE_2', + 3: 'MPC_OUT_CSC_MODE_RSV', +} +MPC_OUT_CSC_MODE_0 = 0 +MPC_OUT_CSC_MODE_1 = 1 +MPC_OUT_CSC_MODE_2 = 2 +MPC_OUT_CSC_MODE_RSV = 3 +MPC_OUT_CSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_MODE' +MPCC_CONTROL_MPCC_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 1: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 2: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 3: 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', +} +MPCC_CONTROL_MPCC_MODE_BYPASS = 0 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH = 1 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY = 2 +MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING = 3 +MPCC_CONTROL_MPCC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE' +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 1: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 2: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 3: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', +} +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA = 0 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN = 1 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA = 2 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED = 3 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE' +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 1: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', +} +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE = 0 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE = 1 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY' +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 1: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', +} +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE = 0 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE = 1 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_EN' +MPCC_SM_CONTROL_MPCC_SM_EN__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_EN_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_EN_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_MODE' +MPCC_SM_CONTROL_MPCC_SM_MODE__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 2: 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 4: 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 6: 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', +} +MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE = 0 +MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING = 2 +MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING = 4 +MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING = 6 +MPCC_SM_CONTROL_MPCC_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT' +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT' +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK' +MPCC_STALL_STATUS_MPCC_STALL_INT_ACK__enumvalues = { + 0: 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_FALSE', + 1: 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_TRUE', +} +MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_FALSE = 0 +MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_TRUE = 1 +MPCC_STALL_STATUS_MPCC_STALL_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK' +MPCC_STALL_STATUS_MPCC_STALL_INT_MASK__enumvalues = { + 0: 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_FALSE', + 1: 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_TRUE', +} +MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_FALSE = 0 +MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_TRUE = 1 +MPCC_STALL_STATUS_MPCC_STALL_INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_BG_COLOR_BPC' +MPCC_BG_COLOR_BPC__enumvalues = { + 0: 'MPCC_BG_COLOR_BPC_8bit', + 1: 'MPCC_BG_COLOR_BPC_9bit', + 2: 'MPCC_BG_COLOR_BPC_10bit', + 3: 'MPCC_BG_COLOR_BPC_11bit', + 4: 'MPCC_BG_COLOR_BPC_12bit', +} +MPCC_BG_COLOR_BPC_8bit = 0 +MPCC_BG_COLOR_BPC_9bit = 1 +MPCC_BG_COLOR_BPC_10bit = 2 +MPCC_BG_COLOR_BPC_11bit = 3 +MPCC_BG_COLOR_BPC_12bit = 4 +MPCC_BG_COLOR_BPC = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE' +MPCC_CONTROL_MPCC_BOT_GAIN_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 1: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', +} +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0 = 0 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1 = 1 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL' +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 1: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', +} +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA = 0 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB = 1 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_MODE_MPCC_OGAM_MODE' +MPCC_OGAM_MODE_MPCC_OGAM_MODE__enumvalues = { + 0: 'MPCC_OGAM_MODE_0', + 1: 'MPCC_OGAM_MODE_1', + 2: 'MPCC_OGAM_MODE_2', + 3: 'MPCC_OGAM_MODE_RSV', +} +MPCC_OGAM_MODE_0 = 0 +MPCC_OGAM_MODE_1 = 1 +MPCC_OGAM_MODE_2 = 2 +MPCC_OGAM_MODE_RSV = 3 +MPCC_OGAM_MODE_MPCC_OGAM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_EN' +ENUM_DPG_EN__enumvalues = { + 0: 'ENUM_DPG_DISABLE', + 1: 'ENUM_DPG_ENABLE', +} +ENUM_DPG_DISABLE = 0 +ENUM_DPG_ENABLE = 1 +ENUM_DPG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_MODE' +ENUM_DPG_MODE__enumvalues = { + 0: 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 1: 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 2: 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 3: 'ENUM_DPG_MODE_VERTICAL_BAR', + 4: 'ENUM_DPG_MODE_HORIZONTAL_BAR', + 5: 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 6: 'ENUM_DPG_MODE_RGB_DUAL_RAMP', + 7: 'ENUM_DPG_MODE_RGB_XR_BIAS', +} +ENUM_DPG_MODE_RGB_COLOUR_BLOCK = 0 +ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK = 1 +ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK = 2 +ENUM_DPG_MODE_VERTICAL_BAR = 3 +ENUM_DPG_MODE_HORIZONTAL_BAR = 4 +ENUM_DPG_MODE_RGB_SINGLE_RAMP = 5 +ENUM_DPG_MODE_RGB_DUAL_RAMP = 6 +ENUM_DPG_MODE_RGB_XR_BIAS = 7 +ENUM_DPG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_DYNAMIC_RANGE' +ENUM_DPG_DYNAMIC_RANGE__enumvalues = { + 0: 'ENUM_DPG_DYNAMIC_RANGE_VESA', + 1: 'ENUM_DPG_DYNAMIC_RANGE_CEA', +} +ENUM_DPG_DYNAMIC_RANGE_VESA = 0 +ENUM_DPG_DYNAMIC_RANGE_CEA = 1 +ENUM_DPG_DYNAMIC_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_BIT_DEPTH' +ENUM_DPG_BIT_DEPTH__enumvalues = { + 0: 'ENUM_DPG_BIT_DEPTH_6BPC', + 1: 'ENUM_DPG_BIT_DEPTH_8BPC', + 2: 'ENUM_DPG_BIT_DEPTH_10BPC', + 3: 'ENUM_DPG_BIT_DEPTH_12BPC', +} +ENUM_DPG_BIT_DEPTH_6BPC = 0 +ENUM_DPG_BIT_DEPTH_8BPC = 1 +ENUM_DPG_BIT_DEPTH_10BPC = 2 +ENUM_DPG_BIT_DEPTH_12BPC = 3 +ENUM_DPG_BIT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_FIELD_POLARITY' +ENUM_DPG_FIELD_POLARITY__enumvalues = { + 0: 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 1: 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', +} +ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD = 0 +ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN = 1 +ENUM_DPG_FIELD_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_PIXEL_ENCODING' +FMT_CONTROL_PIXEL_ENCODING__enumvalues = { + 0: 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 1: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 2: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 3: 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', +} +FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444 = 0 +FMT_CONTROL_PIXEL_ENCODING_YCBCR422 = 1 +FMT_CONTROL_PIXEL_ENCODING_YCBCR420 = 2 +FMT_CONTROL_PIXEL_ENCODING_RESERVED = 3 +FMT_CONTROL_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_MODE' +FMT_CONTROL_SUBSAMPLING_MODE__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 1: 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 2: 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 3: 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', +} +FMT_CONTROL_SUBSAMPLING_MODE_DROP = 0 +FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE = 1 +FMT_CONTROL_SUBSAMPLING_MOME_3_TAP = 2 +FMT_CONTROL_SUBSAMPLING_MOME_RESERVED = 3 +FMT_CONTROL_SUBSAMPLING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_ORDER' +FMT_CONTROL_SUBSAMPLING_ORDER__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 1: 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', +} +FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR = 0 +FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB = 1 +FMT_CONTROL_SUBSAMPLING_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS' +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS__enumvalues = { + 0: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 1: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', +} +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE = 0 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE = 1 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2 = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4 = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL' +FMT_BIT_DEPTH_CONTROL_25FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 1: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 2: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 3: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei = 0 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi = 1 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi = 2 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL' +FMT_BIT_DEPTH_CONTROL_50FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 1: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 2: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 3: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', +} +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A = 0 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B = 1 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C = 2 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D = 3 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL' +FMT_BIT_DEPTH_CONTROL_75FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 1: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 2: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 3: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E = 0 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F = 1 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G = 2 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0' +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0__enumvalues = { + 0: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 1: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', +} +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR = 0 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB = 1 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0 = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CLAMP_CNTL_COLOR_FORMAT' +FMT_CLAMP_CNTL_COLOR_FORMAT__enumvalues = { + 0: 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 1: 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 2: 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 3: 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 4: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 5: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 6: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 7: 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', +} +FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC = 0 +FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC = 1 +FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC = 2 +FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC = 3 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1 = 4 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2 = 5 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3 = 6 +FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE = 7 +FMT_CLAMP_CNTL_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_MODE' +FMT_SPATIAL_DITHER_MODE__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_MODE_0', + 1: 'FMT_SPATIAL_DITHER_MODE_1', + 2: 'FMT_SPATIAL_DITHER_MODE_2', + 3: 'FMT_SPATIAL_DITHER_MODE_3', +} +FMT_SPATIAL_DITHER_MODE_0 = 0 +FMT_SPATIAL_DITHER_MODE_1 = 1 +FMT_SPATIAL_DITHER_MODE_2 = 2 +FMT_SPATIAL_DITHER_MODE_3 = 3 +FMT_SPATIAL_DITHER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DYNAMIC_EXP_MODE' +FMT_DYNAMIC_EXP_MODE__enumvalues = { + 0: 'FMT_DYNAMIC_EXP_MODE_10to12', + 1: 'FMT_DYNAMIC_EXP_MODE_8to12', +} +FMT_DYNAMIC_EXP_MODE_10to12 = 0 +FMT_DYNAMIC_EXP_MODE_8to12 = 1 +FMT_DYNAMIC_EXP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_FORCE_CTRL' +FMTMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'FMTMEM_NO_FORCE_REQUEST', + 1: 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', +} +FMTMEM_NO_FORCE_REQUEST = 0 +FMTMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +FMTMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +FMTMEM_FORCE_SHUT_DOWN_REQUEST = 3 +FMTMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_DIS_CTRL' +FMTMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 1: 'FMTMEM_DISABLE_MEM_PWR_CTRL', +} +FMTMEM_ENABLE_MEM_PWR_CTRL = 0 +FMTMEM_DISABLE_MEM_PWR_CTRL = 1 +FMTMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_POWER_STATE_ENUM' +FMT_POWER_STATE_ENUM__enumvalues = { + 0: 'FMT_POWER_STATE_ENUM_ON', + 1: 'FMT_POWER_STATE_ENUM_LS', + 2: 'FMT_POWER_STATE_ENUM_DS', + 3: 'FMT_POWER_STATE_ENUM_SD', +} +FMT_POWER_STATE_ENUM_ON = 0 +FMT_POWER_STATE_ENUM_LS = 1 +FMT_POWER_STATE_ENUM_DS = 2 +FMT_POWER_STATE_ENUM_SD = 3 +FMT_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_STEREOSYNC_OVERRIDE_CONTROL' +FMT_STEREOSYNC_OVERRIDE_CONTROL__enumvalues = { + 0: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 1: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', +} +FMT_STEREOSYNC_OVERRIDE_CONTROL_0 = 0 +FMT_STEREOSYNC_OVERRIDE_CONTROL_1 = 1 +FMT_STEREOSYNC_OVERRIDE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL' +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 1: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 2: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 3: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', +} +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP = 0 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1 = 1 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2 = 2 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED = 3 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_FRAME_RANDOM_ENABLE_CONTROL' +FMT_FRAME_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 1: 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', +} +FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME = 0 +FMT_FRAME_RANDOM_ENABLE_RESET_ONCE = 1 +FMT_FRAME_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_RGB_RANDOM_ENABLE_CONTROL' +FMT_RGB_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 1: 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', +} +FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE = 0 +FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE = 1 +FMT_RGB_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_FMT_PTI_FIELD_POLARITY' +ENUM_FMT_PTI_FIELD_POLARITY__enumvalues = { + 0: 'ENUM_FMT_PTI_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 1: 'ENUM_FMT_PTI_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', +} +ENUM_FMT_PTI_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD = 0 +ENUM_FMT_PTI_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN = 1 +ENUM_FMT_PTI_FIELD_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CLOCK_ENABLE_CONTROL' +OPP_PIPE_CLOCK_ENABLE_CONTROL__enumvalues = { + 0: 'OPP_PIPE_CLOCK_DISABLE', + 1: 'OPP_PIPE_CLOCK_ENABLE', +} +OPP_PIPE_CLOCK_DISABLE = 0 +OPP_PIPE_CLOCK_ENABLE = 1 +OPP_PIPE_CLOCK_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL' +OPP_PIPE_DIGTIAL_BYPASS_CONTROL__enumvalues = { + 0: 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 1: 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', +} +OPP_PIPE_DIGTIAL_BYPASS_DISABLE = 0 +OPP_PIPE_DIGTIAL_BYPASS_ENABLE = 1 +OPP_PIPE_DIGTIAL_BYPASS_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_EN' +OPP_PIPE_CRC_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_DISABLE', + 1: 'OPP_PIPE_CRC_ENABLE', +} +OPP_PIPE_CRC_DISABLE = 0 +OPP_PIPE_CRC_ENABLE = 1 +OPP_PIPE_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_CONT_EN' +OPP_PIPE_CRC_CONT_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_MODE_ONE_SHOT', + 1: 'OPP_PIPE_CRC_MODE_CONTINUOUS', +} +OPP_PIPE_CRC_MODE_ONE_SHOT = 0 +OPP_PIPE_CRC_MODE_CONTINUOUS = 1 +OPP_PIPE_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_MODE' +OPP_PIPE_CRC_STEREO_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_MODE_LEFT', + 1: 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 2: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 3: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', +} +OPP_PIPE_CRC_STEREO_MODE_LEFT = 0 +OPP_PIPE_CRC_STEREO_MODE_RIGHT = 1 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE = 2 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE = 3 +OPP_PIPE_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_EN' +OPP_PIPE_CRC_STEREO_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 1: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', +} +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO = 0 +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO = 1 +OPP_PIPE_CRC_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_MODE' +OPP_PIPE_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', + 1: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 3: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', +} +OPP_PIPE_CRC_INTERLACE_MODE_TOP = 0 +OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM = 1 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD = 2 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD = 3 +OPP_PIPE_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_EN' +OPP_PIPE_CRC_INTERLACE_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 1: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', +} +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE = 0 +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED = 1 +OPP_PIPE_CRC_INTERLACE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_PIXEL_SELECT' +OPP_PIPE_CRC_PIXEL_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 1: 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 2: 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 3: 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', +} +OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS = 0 +OPP_PIPE_CRC_PIXEL_SELECT_RESERVED = 1 +OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS = 2 +OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS = 3 +OPP_PIPE_CRC_PIXEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_SOURCE_SELECT' +OPP_PIPE_CRC_SOURCE_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 1: 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', +} +OPP_PIPE_CRC_SOURCE_SELECT_FMT = 0 +OPP_PIPE_CRC_SOURCE_SELECT_SFT = 1 +OPP_PIPE_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_ONE_SHOT_PENDING' +OPP_PIPE_CRC_ONE_SHOT_PENDING__enumvalues = { + 0: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 1: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', +} +OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING = 0 +OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING = 1 +OPP_PIPE_CRC_ONE_SHOT_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_GATING_CONTROL' +OPP_TOP_CLOCK_GATING_CONTROL__enumvalues = { + 0: 'OPP_TOP_CLOCK_GATING_ENABLED', + 1: 'OPP_TOP_CLOCK_GATING_DISABLED', +} +OPP_TOP_CLOCK_GATING_ENABLED = 0 +OPP_TOP_CLOCK_GATING_DISABLED = 1 +OPP_TOP_CLOCK_GATING_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_ENABLE_STATUS' +OPP_TOP_CLOCK_ENABLE_STATUS__enumvalues = { + 0: 'OPP_TOP_CLOCK_DISABLED_STATUS', + 1: 'OPP_TOP_CLOCK_ENABLED_STATUS', +} +OPP_TOP_CLOCK_DISABLED_STATUS = 0 +OPP_TOP_CLOCK_ENABLED_STATUS = 1 +OPP_TOP_CLOCK_ENABLE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TEST_CLK_SEL_CONTROL' +OPP_TEST_CLK_SEL_CONTROL__enumvalues = { + 0: 'OPP_TEST_CLK_SEL_DISPCLK_P', + 1: 'OPP_TEST_CLK_SEL_DISPCLK_R', + 2: 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', + 3: 'OPP_TEST_CLK_SEL_RESERVED0', + 4: 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', + 5: 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', + 6: 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', + 7: 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', + 8: 'OPP_TEST_CLK_SEL_DISPCLK_OPP4', + 9: 'OPP_TEST_CLK_SEL_DISPCLK_OPP5', +} +OPP_TEST_CLK_SEL_DISPCLK_P = 0 +OPP_TEST_CLK_SEL_DISPCLK_R = 1 +OPP_TEST_CLK_SEL_DISPCLK_ABM0 = 2 +OPP_TEST_CLK_SEL_RESERVED0 = 3 +OPP_TEST_CLK_SEL_DISPCLK_OPP0 = 4 +OPP_TEST_CLK_SEL_DISPCLK_OPP1 = 5 +OPP_TEST_CLK_SEL_DISPCLK_OPP2 = 6 +OPP_TEST_CLK_SEL_DISPCLK_OPP3 = 7 +OPP_TEST_CLK_SEL_DISPCLK_OPP4 = 8 +OPP_TEST_CLK_SEL_DISPCLK_OPP5 = 9 +OPP_TEST_CLK_SEL_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_START_POINT_CNTL' +OTG_CONTROL_OTG_START_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', +} +OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_START_POINT_CNTL_DP = 1 +OTG_CONTROL_OTG_START_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL' +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', +} +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL' +OTG_CONTROL_OTG_DISABLE_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 1: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 2: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_RESERVED', + 3: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', +} +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE = 0 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT = 1 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_RESERVED = 2 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST = 3 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY' +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', +} +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE' +OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE__enumvalues = { + 0: 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_FALSE', + 1: 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_TRUE', +} +OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_FALSE = 0 +OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_TRUE = 1 +OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_SOF_PULL_EN' +OTG_CONTROL_OTG_SOF_PULL_EN__enumvalues = { + 0: 'OTG_CONTROL_OTG_SOF_PULL_EN_FALSE', + 1: 'OTG_CONTROL_OTG_SOF_PULL_EN_TRUE', +} +OTG_CONTROL_OTG_SOF_PULL_EN_FALSE = 0 +OTG_CONTROL_OTG_SOF_PULL_EN_TRUE = 1 +OTG_CONTROL_OTG_SOF_PULL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN' +OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD' +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 1: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', +} +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0 = 0 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1 = 1 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK' +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK__enumvalues = { + 0: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE', + 1: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE', +} +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE = 0 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE = 1 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR' +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR__enumvalues = { + 0: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 1: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', +} +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE = 0 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE = 1 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN' +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN__enumvalues = { + 0: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 1: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', +} +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE = 0 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE = 1 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_DSI_FORCE_TOTAL', + 15: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_DSI_FORCE_TOTAL = 14 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', +} +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_DSI_FORCE_TOTAL', + 15: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_DSI_FORCE_TOTAL = 14 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG4', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG5', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG4 = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG5 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', +} +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG4', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG5', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG4 = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG5 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN' +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR' +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN' +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR' +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 2: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 3: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT = 2 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED = 3 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 2: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 3: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 4: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 5: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 6: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 7: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 8: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 9: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 10: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 11: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 12: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 13: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 14: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 15: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DSI_FREEZE', + 16: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 17: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 18: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 19: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0 = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1 = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA = 2 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB = 3 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC = 4 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD = 5 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE = 6 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF = 7 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1 = 8 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2 = 9 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA = 10 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK = 11 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA = 12 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK = 13 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 14 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DSI_FREEZE = 15 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK = 16 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC = 17 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA = 18 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB = 19 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE' +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE__enumvalues = { + 0: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 1: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 2: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 3: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', +} +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO = 0 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT = 1 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT = 2 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED = 3 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_MASTER_EN' +OTG_CONTROL_OTG_MASTER_EN__enumvalues = { + 0: 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 1: 'OTG_CONTROL_OTG_MASTER_EN_TRUE', +} +OTG_CONTROL_OTG_MASTER_EN_FALSE = 0 +OTG_CONTROL_OTG_MASTER_EN_TRUE = 1 +OTG_CONTROL_OTG_MASTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN' +OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN__enumvalues = { + 0: 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_FALSE', + 1: 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_TRUE', +} +OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_FALSE = 0 +OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_TRUE = 1 +OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE' +OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE__enumvalues = { + 0: 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_FALSE', + 1: 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_TRUE', +} +OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_FALSE = 0 +OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_TRUE = 1 +OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 2: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 3: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP = 2 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2 = 3 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY' +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_FALSE', + 1: 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_TRUE', +} +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_FALSE = 0 +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_TRUE = 1 +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT' +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT__enumvalues = { + 0: 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_FALSE', + 1: 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_TRUE', +} +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_FALSE = 0 +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_TRUE = 1 +OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN' +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN__enumvalues = { + 0: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 1: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', +} +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE = 0 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE = 1 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE' +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE__enumvalues = { + 0: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 1: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', +} +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE = 0 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE = 1 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR' +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', +} +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE = 0 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE = 1 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE' +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 2: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 3: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', +} +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE = 0 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA = 1 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB = 2 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED = 3 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EN' +OTG_STEREO_CONTROL_OTG_STEREO_EN__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR' +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR__enumvalues = { + 0: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 1: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', +} +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE = 0 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE = 1 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL' +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL__enumvalues = { + 0: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 1: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 2: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 3: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', +} +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE = 0 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA = 1 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB = 2 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED = 3 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY' +OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY__enumvalues = { + 0: 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_FALSE', + 1: 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_TRUE', +} +OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_FALSE = 0 +OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_TRUE = 1 +OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY' +OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY__enumvalues = { + 0: 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_FALSE', + 1: 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_TRUE', +} +OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_FALSE = 0 +OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_TRUE = 1 +OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN' +OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN__enumvalues = { + 0: 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_FALSE', + 1: 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_TRUE', +} +OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_FALSE = 0 +OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_TRUE = 1 +OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN' +OTG_START_LINE_CONTROL_OTG_PREFETCH_EN__enumvalues = { + 0: 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_FALSE', + 1: 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_TRUE', +} +OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_FALSE = 0 +OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_TRUE = 1 +OTG_START_LINE_CONTROL_OTG_PREFETCH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK' +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK__enumvalues = { + 0: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 1: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', +} +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE = 0 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE = 1 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY' +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN' +OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE' +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_0', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_1', + 2: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_2', + 3: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_3', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_0 = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_1 = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_2 = 2 +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_3 = 3 +OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE' +OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE__enumvalues = { + 0: 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_FALSE', + 1: 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_TRUE', +} +OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_FALSE = 0 +OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_TRUE = 1 +OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK' +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME' +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME__enumvalues = { + 0: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 1: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 2: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 3: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', +} +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME = 0 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME = 1 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME = 2 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME = 3 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK' +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE' +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE__enumvalues = { + 0: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 1: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 2: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 3: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', +} +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH = 0 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP = 1 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM = 2 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED = 3 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE' +OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE__enumvalues = { + 0: 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DISABLE', + 1: 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DEBUG', + 2: 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_NORMAL', +} +OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DISABLE = 0 +OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DEBUG = 1 +OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_NORMAL = 2 +OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR' +OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR__enumvalues = { + 0: 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_FALSE', + 1: 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_TRUE', +} +OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_FALSE = 0 +OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_TRUE = 1 +OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR' +OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR__enumvalues = { + 0: 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE', + 1: 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE', +} +OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE = 0 +OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE = 1 +OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR' +OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR__enumvalues = { + 0: 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_FALSE', + 1: 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_TRUE', +} +OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_FALSE = 0 +OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_TRUE = 1 +OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_EN' +OTG_CRC_CNTL_OTG_CRC_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_CONT_EN' +OTG_CRC_CNTL_OTG_CRC_CONT_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE' +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 1: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 2: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 3: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', +} +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT = 0 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT = 1 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES = 2 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS = 3 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE' +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 1: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 3: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', +} +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP = 0 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM = 1 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM = 2 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD = 3 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS' +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE' +OTG_CRC_CNTL2_OTG_CRC_DSC_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_FALSE', + 1: 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_TRUE', +} +OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_FALSE = 0 +OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_TRUE = 1 +OTG_CRC_CNTL2_OTG_CRC_DSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE' +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_FALSE', + 1: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_TRUE', +} +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_FALSE = 0 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_TRUE = 1 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE' +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_DSIABLE', + 1: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_1', + 2: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_2', + 3: 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_3', +} +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_DSIABLE = 0 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_1 = 1 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_2 = 2 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_3 = 3 +OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT' +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT__enumvalues = { + 0: 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_0', + 1: 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_1', + 2: 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_2', + 3: 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_3', +} +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_0 = 0 +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_1 = 1 +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_2 = 2 +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_3 = 3 +OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_DISABLE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_ONESHOT', + 2: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_CONTINUOUS', + 3: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_RESERVED', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_DISABLE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_ONESHOT = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_CONTINUOUS = 2 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_RESERVED = 3 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel', + 2: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel', + 3: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel = 2 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel = 3 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE' +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE', +} +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE = 0 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE = 1 +OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE' +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR' +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE', +} +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE = 0 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE = 1 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE' +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE', +} +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE = 0 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE = 1 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT' +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME', + 1: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME', + 2: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME', + 3: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME', + 4: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME', + 5: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME', + 6: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME', + 7: 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME', +} +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME = 0 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME = 1 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME = 2 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME = 3 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME = 4 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME = 5 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME = 6 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME = 7 +OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE' +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR' +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_TRUE', +} +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_FALSE = 0 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_TRUE = 1 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE' +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_TRUE', +} +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_FALSE = 0 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_TRUE = 1 +OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE' +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE', +} +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE = 0 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE = 1 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR' +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE', +} +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE = 0 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE = 1 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE' +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE__enumvalues = { + 0: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE', + 1: 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE', +} +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE = 0 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE = 1 +OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 2: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 3: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE = 2 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED = 3 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_SYNC_A_POL' +OTG_V_SYNC_A_POL__enumvalues = { + 0: 'OTG_V_SYNC_A_POL_HIGH', + 1: 'OTG_V_SYNC_A_POL_LOW', +} +OTG_V_SYNC_A_POL_HIGH = 0 +OTG_V_SYNC_A_POL_LOW = 1 +OTG_V_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_SYNC_A_POL' +OTG_H_SYNC_A_POL__enumvalues = { + 0: 'OTG_H_SYNC_A_POL_HIGH', + 1: 'OTG_H_SYNC_A_POL_LOW', +} +OTG_H_SYNC_A_POL_HIGH = 0 +OTG_H_SYNC_A_POL_LOW = 1 +OTG_H_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_HORZ_REPETITION_COUNT' +OTG_HORZ_REPETITION_COUNT__enumvalues = { + 0: 'OTG_HORZ_REPETITION_COUNT_0', + 1: 'OTG_HORZ_REPETITION_COUNT_1', + 2: 'OTG_HORZ_REPETITION_COUNT_2', + 3: 'OTG_HORZ_REPETITION_COUNT_3', + 4: 'OTG_HORZ_REPETITION_COUNT_4', + 5: 'OTG_HORZ_REPETITION_COUNT_5', + 6: 'OTG_HORZ_REPETITION_COUNT_6', + 7: 'OTG_HORZ_REPETITION_COUNT_7', + 8: 'OTG_HORZ_REPETITION_COUNT_8', + 9: 'OTG_HORZ_REPETITION_COUNT_9', + 10: 'OTG_HORZ_REPETITION_COUNT_10', + 11: 'OTG_HORZ_REPETITION_COUNT_11', + 12: 'OTG_HORZ_REPETITION_COUNT_12', + 13: 'OTG_HORZ_REPETITION_COUNT_13', + 14: 'OTG_HORZ_REPETITION_COUNT_14', + 15: 'OTG_HORZ_REPETITION_COUNT_15', +} +OTG_HORZ_REPETITION_COUNT_0 = 0 +OTG_HORZ_REPETITION_COUNT_1 = 1 +OTG_HORZ_REPETITION_COUNT_2 = 2 +OTG_HORZ_REPETITION_COUNT_3 = 3 +OTG_HORZ_REPETITION_COUNT_4 = 4 +OTG_HORZ_REPETITION_COUNT_5 = 5 +OTG_HORZ_REPETITION_COUNT_6 = 6 +OTG_HORZ_REPETITION_COUNT_7 = 7 +OTG_HORZ_REPETITION_COUNT_8 = 8 +OTG_HORZ_REPETITION_COUNT_9 = 9 +OTG_HORZ_REPETITION_COUNT_10 = 10 +OTG_HORZ_REPETITION_COUNT_11 = 11 +OTG_HORZ_REPETITION_COUNT_12 = 12 +OTG_HORZ_REPETITION_COUNT_13 = 13 +OTG_HORZ_REPETITION_COUNT_14 = 14 +OTG_HORZ_REPETITION_COUNT_15 = 15 +OTG_HORZ_REPETITION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_SEL' +MASTER_UPDATE_LOCK_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_SEL_0', + 1: 'MASTER_UPDATE_LOCK_SEL_1', + 2: 'MASTER_UPDATE_LOCK_SEL_2', + 3: 'MASTER_UPDATE_LOCK_SEL_3', + 4: 'MASTER_UPDATE_LOCK_SEL_4', + 5: 'MASTER_UPDATE_LOCK_SEL_5', +} +MASTER_UPDATE_LOCK_SEL_0 = 0 +MASTER_UPDATE_LOCK_SEL_1 = 1 +MASTER_UPDATE_LOCK_SEL_2 = 2 +MASTER_UPDATE_LOCK_SEL_3 = 3 +MASTER_UPDATE_LOCK_SEL_4 = 4 +MASTER_UPDATE_LOCK_SEL_5 = 5 +MASTER_UPDATE_LOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DRR_UPDATE_LOCK_SEL' +DRR_UPDATE_LOCK_SEL__enumvalues = { + 0: 'DRR_UPDATE_LOCK_SEL_0', + 1: 'DRR_UPDATE_LOCK_SEL_1', + 2: 'DRR_UPDATE_LOCK_SEL_2', + 3: 'DRR_UPDATE_LOCK_SEL_3', + 4: 'DRR_UPDATE_LOCK_SEL_4', + 5: 'DRR_UPDATE_LOCK_SEL_5', +} +DRR_UPDATE_LOCK_SEL_0 = 0 +DRR_UPDATE_LOCK_SEL_1 = 1 +DRR_UPDATE_LOCK_SEL_2 = 2 +DRR_UPDATE_LOCK_SEL_3 = 3 +DRR_UPDATE_LOCK_SEL_4 = 4 +DRR_UPDATE_LOCK_SEL_5 = 5 +DRR_UPDATE_LOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL' +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL__enumvalues = { + 0: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 1: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 2: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 3: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 4: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG4', + 5: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG5', +} +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0 = 0 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1 = 1 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2 = 2 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3 = 3 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG4 = 4 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG5 = 5 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 2: 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', +} +MASTER_UPDATE_LOCK_DB_FIELD_BOTH = 0 +MASTER_UPDATE_LOCK_DB_FIELD_TOP = 1 +MASTER_UPDATE_LOCK_DB_FIELD_RESERVED = 2 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 2: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 3: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', +} +MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH = 0 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT = 1 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT = 2 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED = 3 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_BY2' +OTG_H_TIMING_DIV_BY2__enumvalues = { + 0: 'OTG_H_TIMING_DIV_BY2_FALSE', + 1: 'OTG_H_TIMING_DIV_BY2_TRUE', +} +OTG_H_TIMING_DIV_BY2_FALSE = 0 +OTG_H_TIMING_DIV_BY2_TRUE = 1 +OTG_H_TIMING_DIV_BY2 = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE' +OTG_H_TIMING_DIV_BY2_UPDATE_MODE__enumvalues = { + 0: 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE_0', + 1: 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE_1', +} +OTG_H_TIMING_DIV_BY2_UPDATE_MODE_0 = 0 +OTG_H_TIMING_DIV_BY2_UPDATE_MODE_1 = 1 +OTG_H_TIMING_DIV_BY2_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL' +OTG_TRIGA_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FREQUENCY_SELECT' +OTG_TRIGA_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGA_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGA_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGA_FREQUENCY_SELECT_3', +} +OTG_TRIGA_FREQUENCY_SELECT_0 = 0 +OTG_TRIGA_FREQUENCY_SELECT_1 = 1 +OTG_TRIGA_FREQUENCY_SELECT_2 = 2 +OTG_TRIGA_FREQUENCY_SELECT_3 = 3 +OTG_TRIGA_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL' +OTG_TRIGB_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FREQUENCY_SELECT' +OTG_TRIGB_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGB_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGB_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGB_FREQUENCY_SELECT_3', +} +OTG_TRIGB_FREQUENCY_SELECT_0 = 0 +OTG_TRIGB_FREQUENCY_SELECT_1 = 1 +OTG_TRIGB_FREQUENCY_SELECT_2 = 2 +OTG_TRIGB_FREQUENCY_SELECT_3 = 3 +OTG_TRIGB_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_PIPE_ABORT' +OTG_PIPE_ABORT__enumvalues = { + 0: 'OTG_PIPE_ABORT_0', + 1: 'OTG_PIPE_ABORT_1', +} +OTG_PIPE_ABORT_0 = 0 +OTG_PIPE_ABORT_1 = 1 +OTG_PIPE_ABORT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_GSL_EN' +OTG_MASTER_UPDATE_LOCK_GSL_EN__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 1: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', +} +OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE = 0 +OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE = 1 +OTG_MASTER_UPDATE_LOCK_GSL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_PTI_CONTROL_OTG_PIT_EN' +OTG_PTI_CONTROL_OTG_PIT_EN__enumvalues = { + 0: 'OTG_PTI_CONTROL_OTG_PIT_EN_FALSE', + 1: 'OTG_PTI_CONTROL_OTG_PIT_EN_TRUE', +} +OTG_PTI_CONTROL_OTG_PIT_EN_FALSE = 0 +OTG_PTI_CONTROL_OTG_PIT_EN_TRUE = 1 +OTG_PTI_CONTROL_OTG_PIT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GSL_MASTER_MODE' +OTG_GSL_MASTER_MODE__enumvalues = { + 0: 'OTG_GSL_MASTER_MODE_0', + 1: 'OTG_GSL_MASTER_MODE_1', + 2: 'OTG_GSL_MASTER_MODE_2', + 3: 'OTG_GSL_MASTER_MODE_3', +} +OTG_GSL_MASTER_MODE_0 = 0 +OTG_GSL_MASTER_MODE_1 = 1 +OTG_GSL_MASTER_MODE_2 = 2 +OTG_GSL_MASTER_MODE_3 = 3 +OTG_GSL_MASTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_TIMER_WINDOW' +DC_DMCUB_TIMER_WINDOW__enumvalues = { + 0: 'BITS_31_0', + 1: 'BITS_32_1', + 2: 'BITS_33_2', + 3: 'BITS_34_3', + 4: 'BITS_35_4', + 5: 'BITS_36_5', + 6: 'BITS_37_6', + 7: 'BITS_38_7', +} +BITS_31_0 = 0 +BITS_32_1 = 1 +BITS_33_2 = 2 +BITS_34_3 = 3 +BITS_35_4 = 4 +BITS_36_5 = 5 +BITS_37_6 = 6 +BITS_38_7 = 7 +DC_DMCUB_TIMER_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_INT_TYPE' +DC_DMCUB_INT_TYPE__enumvalues = { + 0: 'INT_LEVEL', + 1: 'INT_PULSE', +} +INT_LEVEL = 0 +INT_PULSE = 1 +DC_DMCUB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'INVALID_REG_ACCESS_TYPE' +INVALID_REG_ACCESS_TYPE__enumvalues = { + 0: 'REG_UNALLOCATED_ADDR_WRITE', + 1: 'REG_UNALLOCATED_ADDR_READ', + 2: 'REG_VIRTUAL_WRITE', + 3: 'REG_VIRTUAL_READ', +} +REG_UNALLOCATED_ADDR_WRITE = 0 +REG_UNALLOCATED_ADDR_READ = 1 +REG_VIRTUAL_WRITE = 2 +REG_VIRTUAL_READ = 3 +INVALID_REG_ACCESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_START_POSITION' +DMU_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DMU_GPU_TIMER_START_0_END_27', + 1: 'DMU_GPU_TIMER_START_1_END_28', + 2: 'DMU_GPU_TIMER_START_2_END_29', + 3: 'DMU_GPU_TIMER_START_3_END_30', + 4: 'DMU_GPU_TIMER_START_4_END_31', + 5: 'DMU_GPU_TIMER_START_6_END_33', + 6: 'DMU_GPU_TIMER_START_8_END_35', + 7: 'DMU_GPU_TIMER_START_10_END_37', +} +DMU_GPU_TIMER_START_0_END_27 = 0 +DMU_GPU_TIMER_START_1_END_28 = 1 +DMU_GPU_TIMER_START_2_END_29 = 2 +DMU_GPU_TIMER_START_3_END_30 = 3 +DMU_GPU_TIMER_START_4_END_31 = 4 +DMU_GPU_TIMER_START_6_END_33 = 5 +DMU_GPU_TIMER_START_8_END_35 = 6 +DMU_GPU_TIMER_START_10_END_37 = 7 +DMU_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_READ_SELECT' +DMU_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 1: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 2: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 3: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 4: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 5: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 6: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 7: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 8: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_8', + 9: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_9', + 10: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_10', + 11: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_11', + 12: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 13: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 14: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 15: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 16: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 17: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 18: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 19: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 20: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_STARTUP_20', + 21: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_STARTUP_21', + 22: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_STARTUP_22', + 23: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_STARTUP_23', + 24: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 25: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 26: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 27: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 28: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 29: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 30: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 31: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 32: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM_32', + 33: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM_33', + 34: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM_34', + 35: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM_35', + 36: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 37: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 38: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 39: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 40: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 41: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 42: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 43: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 44: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VREADY_44', + 45: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VREADY_45', + 46: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VREADY_46', + 47: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VREADY_47', + 48: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 49: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 50: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 51: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 52: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 53: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 54: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 55: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 56: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_56', + 57: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_57', + 58: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_58', + 59: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_59', + 60: 'RESERVED_60', + 61: 'RESERVED_61', + 62: 'RESERVED_62', + 63: 'RESERVED_63', + 64: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 65: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 66: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 67: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 68: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 69: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 70: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 71: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 72: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_NO_LOCK_72', + 73: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_NO_LOCK_73', + 74: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_NO_LOCK_74', + 75: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_NO_LOCK_75', + 76: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 77: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 78: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 79: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 80: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 81: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 82: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 83: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 84: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_AWAY_84', + 85: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_AWAY_85', + 86: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_AWAY_86', + 87: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_AWAY_87', + 88: 'RESERVED_88', + 89: 'RESERVED_89', + 90: 'RESERVED_90', + 91: 'RESERVED_91', +} +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0 = 0 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1 = 1 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2 = 2 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3 = 3 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4 = 4 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5 = 5 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6 = 6 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7 = 7 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_8 = 8 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_9 = 9 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_10 = 10 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_11 = 11 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12 = 12 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13 = 13 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14 = 14 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15 = 15 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16 = 16 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17 = 17 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18 = 18 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19 = 19 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_STARTUP_20 = 20 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_STARTUP_21 = 21 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_STARTUP_22 = 22 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_STARTUP_23 = 23 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24 = 24 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25 = 25 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26 = 26 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27 = 27 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28 = 28 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29 = 29 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30 = 30 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31 = 31 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM_32 = 32 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM_33 = 33 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM_34 = 34 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM_35 = 35 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36 = 36 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37 = 37 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38 = 38 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39 = 39 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40 = 40 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41 = 41 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42 = 42 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43 = 43 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VREADY_44 = 44 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VREADY_45 = 45 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VREADY_46 = 46 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VREADY_47 = 47 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48 = 48 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49 = 49 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50 = 50 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51 = 51 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52 = 52 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53 = 53 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54 = 54 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55 = 55 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_56 = 56 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_57 = 57 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_58 = 58 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_59 = 59 +RESERVED_60 = 60 +RESERVED_61 = 61 +RESERVED_62 = 62 +RESERVED_63 = 63 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64 = 64 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65 = 65 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66 = 66 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67 = 67 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68 = 68 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69 = 69 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70 = 70 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71 = 71 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_NO_LOCK_72 = 72 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_NO_LOCK_73 = 73 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_NO_LOCK_74 = 74 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_NO_LOCK_75 = 75 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76 = 76 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77 = 77 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78 = 78 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79 = 79 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80 = 80 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81 = 81 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82 = 82 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83 = 83 +DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_AWAY_84 = 84 +DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_AWAY_85 = 85 +DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_AWAY_86 = 86 +DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_AWAY_87 = 87 +RESERVED_88 = 88 +RESERVED_89 = 89 +RESERVED_90 = 90 +RESERVED_91 = 91 +DMU_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'IHC_INTERRUPT_LINE_STATUS' +IHC_INTERRUPT_LINE_STATUS__enumvalues = { + 0: 'INTERRUPT_LINE_NOT_ASSERTED', + 1: 'INTERRUPT_LINE_ASSERTED', +} +INTERRUPT_LINE_NOT_ASSERTED = 0 +INTERRUPT_LINE_ASSERTED = 1 +IHC_INTERRUPT_LINE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_CLOCK_GATING_DISABLE' +DMU_CLOCK_GATING_DISABLE__enumvalues = { + 0: 'DMU_ENABLE_CLOCK_GATING', + 1: 'DMU_DISABLE_CLOCK_GATING', +} +DMU_ENABLE_CLOCK_GATING = 0 +DMU_DISABLE_CLOCK_GATING = 1 +DMU_CLOCK_GATING_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_CLOCK_ON' +DMU_CLOCK_ON__enumvalues = { + 0: 'DMU_CLOCK_STATUS_ON', + 1: 'DMU_CLOCK_STATUS_OFF', +} +DMU_CLOCK_STATUS_ON = 0 +DMU_CLOCK_STATUS_OFF = 1 +DMU_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'DC_SMU_INTERRUPT_ENABLE' +DC_SMU_INTERRUPT_ENABLE__enumvalues = { + 0: 'DISABLE_THE_INTERRUPT', + 1: 'ENABLE_THE_INTERRUPT', +} +DISABLE_THE_INTERRUPT = 0 +ENABLE_THE_INTERRUPT = 1 +DC_SMU_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'STATIC_SCREEN_SMU_INTR' +STATIC_SCREEN_SMU_INTR__enumvalues = { + 0: 'STATIC_SCREEN_SMU_INTR_NOOP', + 1: 'SET_STATIC_SCREEN_SMU_INTR', +} +STATIC_SCREEN_SMU_INTR_NOOP = 0 +SET_STATIC_SCREEN_SMU_INTR = 1 +STATIC_SCREEN_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE' +ENABLE__enumvalues = { + 0: 'DISABLE_THE_FEATURE', + 1: 'ENABLE_THE_FEATURE', +} +DISABLE_THE_FEATURE = 0 +ENABLE_THE_FEATURE = 1 +ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_HW_CAL_ENABLE' +DS_HW_CAL_ENABLE__enumvalues = { + 0: 'DS_HW_CAL_DIS', + 1: 'DS_HW_CAL_EN', +} +DS_HW_CAL_DIS = 0 +DS_HW_CAL_EN = 1 +DS_HW_CAL_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_CLOCK' +ENABLE_CLOCK__enumvalues = { + 0: 'DISABLE_THE_CLOCK', + 1: 'ENABLE_THE_CLOCK', +} +DISABLE_THE_CLOCK = 0 +ENABLE_THE_CLOCK = 1 +ENABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'CLEAR_SMU_INTR' +CLEAR_SMU_INTR__enumvalues = { + 0: 'SMU_INTR_STATUS_NOOP', + 1: 'SMU_INTR_STATUS_CLEAR', +} +SMU_INTR_STATUS_NOOP = 0 +SMU_INTR_STATUS_CLEAR = 1 +CLEAR_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'JITTER_REMOVE_DISABLE' +JITTER_REMOVE_DISABLE__enumvalues = { + 0: 'ENABLE_JITTER_REMOVAL', + 1: 'DISABLE_JITTER_REMOVAL', +} +ENABLE_JITTER_REMOVAL = 0 +DISABLE_JITTER_REMOVAL = 1 +JITTER_REMOVE_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_REF_SRC' +DS_REF_SRC__enumvalues = { + 0: 'DS_REF_IS_XTALIN', + 1: 'DS_REF_IS_EXT_GENLOCK', + 2: 'DS_REF_IS_PCIE', +} +DS_REF_IS_XTALIN = 0 +DS_REF_IS_EXT_GENLOCK = 1 +DS_REF_IS_PCIE = 2 +DS_REF_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING' +DISABLE_CLOCK_GATING__enumvalues = { + 0: 'CLOCK_GATING_ENABLED', + 1: 'CLOCK_GATING_DISABLED', +} +CLOCK_GATING_ENABLED = 0 +CLOCK_GATING_DISABLED = 1 +DISABLE_CLOCK_GATING = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING_IN_DCO' +DISABLE_CLOCK_GATING_IN_DCO__enumvalues = { + 0: 'CLOCK_GATING_ENABLED_IN_DCO', + 1: 'CLOCK_GATING_DISABLED_IN_DCO', +} +CLOCK_GATING_ENABLED_IN_DCO = 0 +CLOCK_GATING_DISABLED_IN_DCO = 1 +DISABLE_CLOCK_GATING_IN_DCO = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DEEP_COLOR_CNTL' +DCCG_DEEP_COLOR_CNTL__enumvalues = { + 0: 'DCCG_DEEP_COLOR_DTO_DISABLE', + 1: 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', + 2: 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 3: 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', +} +DCCG_DEEP_COLOR_DTO_DISABLE = 0 +DCCG_DEEP_COLOR_DTO_5_4_RATIO = 1 +DCCG_DEEP_COLOR_DTO_3_2_RATIO = 2 +DCCG_DEEP_COLOR_DTO_2_1_RATIO = 3 +DCCG_DEEP_COLOR_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'REFCLK_CLOCK_EN' +REFCLK_CLOCK_EN__enumvalues = { + 0: 'REFCLK_CLOCK_EN_XTALIN_CLK', + 1: 'REFCLK_CLOCK_EN_ALLOW_SRC_SEL', +} +REFCLK_CLOCK_EN_XTALIN_CLK = 0 +REFCLK_CLOCK_EN_ALLOW_SRC_SEL = 1 +REFCLK_CLOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'REFCLK_SRC_SEL' +REFCLK_SRC_SEL__enumvalues = { + 0: 'REFCLK_SRC_SEL_PCIE_REFCLK', + 1: 'REFCLK_SRC_SEL_CPL_REFCLK', +} +REFCLK_SRC_SEL_PCIE_REFCLK = 0 +REFCLK_SRC_SEL_CPL_REFCLK = 1 +REFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPREFCLK_SRC_SEL' +DPREFCLK_SRC_SEL__enumvalues = { + 0: 'DPREFCLK_SRC_SEL_CK', + 1: 'DPREFCLK_SRC_SEL_P0PLL', + 2: 'DPREFCLK_SRC_SEL_P1PLL', + 3: 'DPREFCLK_SRC_SEL_P2PLL', +} +DPREFCLK_SRC_SEL_CK = 0 +DPREFCLK_SRC_SEL_P0PLL = 1 +DPREFCLK_SRC_SEL_P1PLL = 2 +DPREFCLK_SRC_SEL_P2PLL = 3 +DPREFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_SEL' +XTAL_REF_SEL__enumvalues = { + 0: 'XTAL_REF_SEL_1X', + 1: 'XTAL_REF_SEL_2X', +} +XTAL_REF_SEL_1X = 0 +XTAL_REF_SEL_2X = 1 +XTAL_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_CLOCK_SOURCE_SEL' +XTAL_REF_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', + 1: 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', +} +XTAL_REF_CLOCK_SOURCE_SEL_XTALIN = 0 +XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK = 1 +XTAL_REF_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ALLOW_SR_ON_TRANS_REQ' +ALLOW_SR_ON_TRANS_REQ__enumvalues = { + 0: 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 1: 'ALLOW_SR_ON_TRANS_REQ_DISABLE', +} +ALLOW_SR_ON_TRANS_REQ_ENABLE = 0 +ALLOW_SR_ON_TRANS_REQ_DISABLE = 1 +ALLOW_SR_ON_TRANS_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_SOURCE' +PIPE_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_SOURCE_P0PLL', + 1: 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 2: 'PIPE_PIXEL_RATE_SOURCE_P2PLL', +} +PIPE_PIXEL_RATE_SOURCE_P0PLL = 0 +PIPE_PIXEL_RATE_SOURCE_P1PLL = 1 +PIPE_PIXEL_RATE_SOURCE_P2PLL = 2 +PIPE_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_DIV_SEL' +TEST_CLK_DIV_SEL__enumvalues = { + 0: 'NO_DIV', + 1: 'DIV_2', + 2: 'DIV_4', + 3: 'DIV_8', +} +NO_DIV = 0 +DIV_2 = 1 +DIV_4 = 2 +DIV_8 = 3 +TEST_CLK_DIV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PHYPLL_PIXEL_RATE_SOURCE' +PIPE_PHYPLL_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 1: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 2: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 3: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 4: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE', + 5: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF', + 6: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', +} +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA = 0 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB = 1 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC = 2 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD = 3 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE = 4 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF = 5 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED = 6 +PIPE_PHYPLL_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_PLL_SOURCE' +PIPE_PIXEL_RATE_PLL_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', + 1: 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', +} +PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL = 0 +PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL = 1 +PIPE_PIXEL_RATE_PLL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DTO_DS_DISABLE' +DP_DTO_DS_DISABLE__enumvalues = { + 0: 'DP_DTO_DESPREAD_DISABLE', + 1: 'DP_DTO_DESPREAD_ENABLE', +} +DP_DTO_DESPREAD_DISABLE = 0 +DP_DTO_DESPREAD_ENABLE = 1 +DP_DTO_DS_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_ADD_PIXEL' +OTG_ADD_PIXEL__enumvalues = { + 0: 'OTG_ADD_PIXEL_NOOP', + 1: 'OTG_ADD_PIXEL_FORCE', +} +OTG_ADD_PIXEL_NOOP = 0 +OTG_ADD_PIXEL_FORCE = 1 +OTG_ADD_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DROP_PIXEL' +OTG_DROP_PIXEL__enumvalues = { + 0: 'OTG_DROP_PIXEL_NOOP', + 1: 'OTG_DROP_PIXEL_FORCE', +} +OTG_DROP_PIXEL_NOOP = 0 +OTG_DROP_PIXEL_FORCE = 1 +OTG_DROP_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_EN' +SYMCLK_FE_FORCE_EN__enumvalues = { + 0: 'SYMCLK_FE_FORCE_EN_DISABLE', + 1: 'SYMCLK_FE_FORCE_EN_ENABLE', +} +SYMCLK_FE_FORCE_EN_DISABLE = 0 +SYMCLK_FE_FORCE_EN_ENABLE = 1 +SYMCLK_FE_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_SRC' +SYMCLK_FE_FORCE_SRC__enumvalues = { + 0: 'SYMCLK_FE_FORCE_SRC_UNIPHYA', + 1: 'SYMCLK_FE_FORCE_SRC_UNIPHYB', + 2: 'SYMCLK_FE_FORCE_SRC_UNIPHYC', + 3: 'SYMCLK_FE_FORCE_SRC_UNIPHYD', + 4: 'SYMCLK_FE_FORCE_SRC_UNIPHYE', + 5: 'SYMCLK_FE_FORCE_SRC_UNIPHYF', + 6: 'SYMCLK_FE_FORCE_SRC_RESERVED', +} +SYMCLK_FE_FORCE_SRC_UNIPHYA = 0 +SYMCLK_FE_FORCE_SRC_UNIPHYB = 1 +SYMCLK_FE_FORCE_SRC_UNIPHYC = 2 +SYMCLK_FE_FORCE_SRC_UNIPHYD = 3 +SYMCLK_FE_FORCE_SRC_UNIPHYE = 4 +SYMCLK_FE_FORCE_SRC_UNIPHYF = 5 +SYMCLK_FE_FORCE_SRC_RESERVED = 6 +SYMCLK_FE_FORCE_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_COARSE_SKEW_CNTL' +DVOACLK_COARSE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 5: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 6: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 7: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 8: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 9: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 10: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 11: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 12: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 13: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 14: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 15: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 16: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 17: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 18: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 19: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 20: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 21: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 22: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 23: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 24: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 25: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 26: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 27: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 28: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 29: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 30: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', +} +DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS = 4 +DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS = 5 +DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS = 6 +DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS = 7 +DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS = 8 +DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS = 9 +DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS = 10 +DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS = 11 +DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS = 12 +DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS = 13 +DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS = 14 +DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS = 15 +DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP = 16 +DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS = 17 +DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS = 18 +DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS = 19 +DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS = 20 +DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS = 21 +DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS = 22 +DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS = 23 +DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS = 24 +DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS = 25 +DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS = 26 +DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS = 27 +DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS = 28 +DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS = 29 +DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS = 30 +DVOACLK_COARSE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_FINE_SKEW_CNTL' +DVOACLK_FINE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 5: 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 6: 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 7: 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', +} +DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP = 4 +DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS = 5 +DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS = 6 +DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS = 7 +DVOACLK_FINE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKD_IN_PHASE' +DVOACLKD_IN_PHASE__enumvalues = { + 0: 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKD_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKD_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_IN_PHASE' +DVOACLKC_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_IN_PHASE' +DVOACLKC_MVP_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_MVP_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE' +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE__enumvalues = { + 0: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 1: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', +} +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE = 0 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE = 1 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO0_SOURCE_SEL' +DCCG_AUDIO_DTO0_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 1: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 2: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 3: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 4: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG4', + 5: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG5', + 6: 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', +} +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0 = 0 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1 = 1 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2 = 2 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3 = 3 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG4 = 4 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG5 = 5 +DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED = 6 +DCCG_AUDIO_DTO0_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_SEL' +DCCG_AUDIO_DTO_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', + 1: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 2: 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', +} +DCCG_AUDIO_DTO_SEL_AUDIO_DTO0 = 0 +DCCG_AUDIO_DTO_SEL_AUDIO_DTO1 = 1 +DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO = 2 +DCCG_AUDIO_DTO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO2_SOURCE_SEL' +DCCG_AUDIO_DTO2_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 1: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1', +} +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0 = 0 +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1 = 1 +DCCG_AUDIO_DTO2_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_USE_512FBR_DTO' +DCCG_AUDIO_DTO_USE_512FBR_DTO__enumvalues = { + 0: 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 1: 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', +} +DCCG_AUDIO_DTO_USE_128FBR_FOR_DP = 0 +DCCG_AUDIO_DTO_USE_512FBR_FOR_DP = 1 +DCCG_AUDIO_DTO_USE_512FBR_DTO = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_FREQ_RAMP_DONE' +DISPCLK_FREQ_RAMP_DONE__enumvalues = { + 0: 'DISPCLK_FREQ_RAMP_IN_PROGRESS', + 1: 'DISPCLK_FREQ_RAMP_COMPLETED', +} +DISPCLK_FREQ_RAMP_IN_PROGRESS = 0 +DISPCLK_FREQ_RAMP_COMPLETED = 1 +DISPCLK_FREQ_RAMP_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_RESET' +DCCG_FIFO_ERRDET_RESET__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_RESET_NOOP', + 1: 'DCCG_FIFO_ERRDET_RESET_FORCE', +} +DCCG_FIFO_ERRDET_RESET_NOOP = 0 +DCCG_FIFO_ERRDET_RESET_FORCE = 1 +DCCG_FIFO_ERRDET_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_STATE' +DCCG_FIFO_ERRDET_STATE__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 1: 'DCCG_FIFO_ERRDET_STATE_DETECTION', +} +DCCG_FIFO_ERRDET_STATE_CALIBRATION = 0 +DCCG_FIFO_ERRDET_STATE_DETECTION = 1 +DCCG_FIFO_ERRDET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_OVR_EN' +DCCG_FIFO_ERRDET_OVR_EN__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_OVR_DISABLE', + 1: 'DCCG_FIFO_ERRDET_OVR_ENABLE', +} +DCCG_FIFO_ERRDET_OVR_DISABLE = 0 +DCCG_FIFO_ERRDET_OVR_ENABLE = 1 +DCCG_FIFO_ERRDET_OVR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_CHG_FWD_CORR_DISABLE' +DISPCLK_CHG_FWD_CORR_DISABLE__enumvalues = { + 0: 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 1: 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', +} +DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING = 0 +DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING = 1 +DISPCLK_CHG_FWD_CORR_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DC_MEM_GLOBAL_PWR_REQ_DIS' +DC_MEM_GLOBAL_PWR_REQ_DIS__enumvalues = { + 0: 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 1: 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', +} +DC_MEM_GLOBAL_PWR_REQ_ENABLE = 0 +DC_MEM_GLOBAL_PWR_REQ_DISABLE = 1 +DC_MEM_GLOBAL_PWR_REQ_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_RUN' +DCCG_PERF_RUN__enumvalues = { + 0: 'DCCG_PERF_RUN_NOOP', + 1: 'DCCG_PERF_RUN_START', +} +DCCG_PERF_RUN_NOOP = 0 +DCCG_PERF_RUN_START = 1 +DCCG_PERF_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_VSYNC' +DCCG_PERF_MODE_VSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_VSYNC_NOOP', + 1: 'DCCG_PERF_MODE_VSYNC_START', +} +DCCG_PERF_MODE_VSYNC_NOOP = 0 +DCCG_PERF_MODE_VSYNC_START = 1 +DCCG_PERF_MODE_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_HSYNC' +DCCG_PERF_MODE_HSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_HSYNC_NOOP', + 1: 'DCCG_PERF_MODE_HSYNC_START', +} +DCCG_PERF_MODE_HSYNC_NOOP = 0 +DCCG_PERF_MODE_HSYNC_START = 1 +DCCG_PERF_MODE_HSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_OTG_SELECT' +DCCG_PERF_OTG_SELECT__enumvalues = { + 0: 'DCCG_PERF_SEL_OTG0', + 1: 'DCCG_PERF_SEL_OTG1', + 2: 'DCCG_PERF_SEL_OTG2', + 3: 'DCCG_PERF_SEL_OTG3', + 4: 'DCCG_PERF_SEL_OTG4', + 5: 'DCCG_PERF_SEL_OTG5', + 6: 'DCCG_PERF_SEL_RESERVED', +} +DCCG_PERF_SEL_OTG0 = 0 +DCCG_PERF_SEL_OTG1 = 1 +DCCG_PERF_SEL_OTG2 = 2 +DCCG_PERF_SEL_OTG3 = 3 +DCCG_PERF_SEL_OTG4 = 4 +DCCG_PERF_SEL_OTG5 = 5 +DCCG_PERF_SEL_RESERVED = 6 +DCCG_PERF_OTG_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_BRANCH_SOFT_RESET' +CLOCK_BRANCH_SOFT_RESET__enumvalues = { + 0: 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 1: 'CLOCK_BRANCH_SOFT_RESET_FORCE', +} +CLOCK_BRANCH_SOFT_RESET_NOOP = 0 +CLOCK_BRANCH_SOFT_RESET_FORCE = 1 +CLOCK_BRANCH_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'PLL_CFG_IF_SOFT_RESET' +PLL_CFG_IF_SOFT_RESET__enumvalues = { + 0: 'PLL_CFG_IF_SOFT_RESET_NOOP', + 1: 'PLL_CFG_IF_SOFT_RESET_FORCE', +} +PLL_CFG_IF_SOFT_RESET_NOOP = 0 +PLL_CFG_IF_SOFT_RESET_FORCE = 1 +PLL_CFG_IF_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DVO_ENABLE_RST' +DVO_ENABLE_RST__enumvalues = { + 0: 'DVO_ENABLE_RST_DISABLE', + 1: 'DVO_ENABLE_RST_ENABLE', +} +DVO_ENABLE_RST_DISABLE = 0 +DVO_ENABLE_RST_ENABLE = 1 +DVO_ENABLE_RST = ctypes.c_uint32 # enum + +# values for enumeration 'DS_JITTER_COUNT_SRC_SEL' +DS_JITTER_COUNT_SRC_SEL__enumvalues = { + 0: 'DS_JITTER_COUNT_SRC_SEL0', + 1: 'DS_JITTER_COUNT_SRC_SEL1', +} +DS_JITTER_COUNT_SRC_SEL0 = 0 +DS_JITTER_COUNT_SRC_SEL1 = 1 +DS_JITTER_COUNT_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_FIFO_ERROR' +DIO_FIFO_ERROR__enumvalues = { + 0: 'DIO_FIFO_ERROR_00', + 1: 'DIO_FIFO_ERROR_01', + 2: 'DIO_FIFO_ERROR_10', + 3: 'DIO_FIFO_ERROR_11', +} +DIO_FIFO_ERROR_00 = 0 +DIO_FIFO_ERROR_01 = 1 +DIO_FIFO_ERROR_10 = 2 +DIO_FIFO_ERROR_11 = 3 +DIO_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_REFCLK_SEL' +VSYNC_CNT_REFCLK_SEL__enumvalues = { + 0: 'VSYNC_CNT_REFCLK_SEL_0', + 1: 'VSYNC_CNT_REFCLK_SEL_1', +} +VSYNC_CNT_REFCLK_SEL_0 = 0 +VSYNC_CNT_REFCLK_SEL_1 = 1 +VSYNC_CNT_REFCLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_RESET_SEL' +VSYNC_CNT_RESET_SEL__enumvalues = { + 0: 'VSYNC_CNT_RESET_SEL_0', + 1: 'VSYNC_CNT_RESET_SEL_1', +} +VSYNC_CNT_RESET_SEL_0 = 0 +VSYNC_CNT_RESET_SEL_1 = 1 +VSYNC_CNT_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_LATCH_MASK' +VSYNC_CNT_LATCH_MASK__enumvalues = { + 0: 'VSYNC_CNT_LATCH_MASK_0', + 1: 'VSYNC_CNT_LATCH_MASK_1', +} +VSYNC_CNT_LATCH_MASK_0 = 0 +VSYNC_CNT_LATCH_MASK_1 = 1 +VSYNC_CNT_LATCH_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_ACK' +HPD_INT_CONTROL_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_ACK_0', + 1: 'HPD_INT_CONTROL_ACK_1', +} +HPD_INT_CONTROL_ACK_0 = 0 +HPD_INT_CONTROL_ACK_1 = 1 +HPD_INT_CONTROL_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_POLARITY' +HPD_INT_CONTROL_POLARITY__enumvalues = { + 0: 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', + 1: 'HPD_INT_CONTROL_GEN_INT_ON_CON', +} +HPD_INT_CONTROL_GEN_INT_ON_DISCON = 0 +HPD_INT_CONTROL_GEN_INT_ON_CON = 1 +HPD_INT_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_RX_INT_ACK' +HPD_INT_CONTROL_RX_INT_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_RX_INT_ACK_0', + 1: 'HPD_INT_CONTROL_RX_INT_ACK_1', +} +HPD_INT_CONTROL_RX_INT_ACK_0 = 0 +HPD_INT_CONTROL_RX_INT_ACK_1 = 1 +HPD_INT_CONTROL_RX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSO_NUM_OF_SST_LINKS' +DP_MSO_NUM_OF_SST_LINKS__enumvalues = { + 0: 'DP_MSO_ONE_SSTLINK', + 1: 'DP_MSO_TWO_SSTLINK', + 2: 'DP_MSO_FOUR_SSTLINK', +} +DP_MSO_ONE_SSTLINK = 0 +DP_MSO_TWO_SSTLINK = 1 +DP_MSO_FOUR_SSTLINK = 2 +DP_MSO_NUM_OF_SST_LINKS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SYNC_POLARITY' +DP_SYNC_POLARITY__enumvalues = { + 0: 'DP_SYNC_POLARITY_ACTIVE_HIGH', + 1: 'DP_SYNC_POLARITY_ACTIVE_LOW', +} +DP_SYNC_POLARITY_ACTIVE_HIGH = 0 +DP_SYNC_POLARITY_ACTIVE_LOW = 1 +DP_SYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMBINE_PIXEL_NUM' +DP_COMBINE_PIXEL_NUM__enumvalues = { + 0: 'DP_COMBINE_ONE_PIXEL', + 1: 'DP_COMBINE_TWO_PIXEL', + 2: 'DP_COMBINE_FOUR_PIXEL', +} +DP_COMBINE_ONE_PIXEL = 0 +DP_COMBINE_TWO_PIXEL = 1 +DP_COMBINE_FOUR_PIXEL = 2 +DP_COMBINE_PIXEL_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_COMPLETE' +DP_LINK_TRAINING_COMPLETE__enumvalues = { + 0: 'DP_LINK_TRAINING_NOT_COMPLETE', + 1: 'DP_LINK_TRAINING_ALREADY_COMPLETE', +} +DP_LINK_TRAINING_NOT_COMPLETE = 0 +DP_LINK_TRAINING_ALREADY_COMPLETE = 1 +DP_LINK_TRAINING_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_EMBEDDED_PANEL_MODE' +DP_EMBEDDED_PANEL_MODE__enumvalues = { + 0: 'DP_EXTERNAL_PANEL', + 1: 'DP_EMBEDDED_PANEL', +} +DP_EXTERNAL_PANEL = 0 +DP_EMBEDDED_PANEL = 1 +DP_EMBEDDED_PANEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_ENCODING' +DP_PIXEL_ENCODING__enumvalues = { + 0: 'DP_PIXEL_ENCODING_RGB444', + 1: 'DP_PIXEL_ENCODING_YCBCR422', + 2: 'DP_PIXEL_ENCODING_YCBCR444', + 3: 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', + 4: 'DP_PIXEL_ENCODING_Y_ONLY', + 5: 'DP_PIXEL_ENCODING_YCBCR420', + 6: 'DP_PIXEL_ENCODING_RESERVED', +} +DP_PIXEL_ENCODING_RGB444 = 0 +DP_PIXEL_ENCODING_YCBCR422 = 1 +DP_PIXEL_ENCODING_YCBCR444 = 2 +DP_PIXEL_ENCODING_RGB_WIDE_GAMUT = 3 +DP_PIXEL_ENCODING_Y_ONLY = 4 +DP_PIXEL_ENCODING_YCBCR420 = 5 +DP_PIXEL_ENCODING_RESERVED = 6 +DP_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMPONENT_DEPTH' +DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_COMPONENT_DEPTH_6BPC', + 1: 'DP_COMPONENT_DEPTH_8BPC', + 2: 'DP_COMPONENT_DEPTH_10BPC', + 3: 'DP_COMPONENT_DEPTH_12BPC', + 4: 'DP_COMPONENT_DEPTH_16BPC_RESERVED', + 5: 'DP_COMPONENT_DEPTH_RESERVED', +} +DP_COMPONENT_DEPTH_6BPC = 0 +DP_COMPONENT_DEPTH_8BPC = 1 +DP_COMPONENT_DEPTH_10BPC = 2 +DP_COMPONENT_DEPTH_12BPC = 3 +DP_COMPONENT_DEPTH_16BPC_RESERVED = 4 +DP_COMPONENT_DEPTH_RESERVED = 5 +DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DP_UDI_LANES' +DP_UDI_LANES__enumvalues = { + 0: 'DP_UDI_1_LANE', + 1: 'DP_UDI_2_LANES', + 2: 'DP_UDI_LANES_RESERVED', + 3: 'DP_UDI_4_LANES', +} +DP_UDI_1_LANE = 0 +DP_UDI_2_LANES = 1 +DP_UDI_LANES_RESERVED = 2 +DP_UDI_4_LANES = 3 +DP_UDI_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DIS_DEFER' +DP_VID_STREAM_DIS_DEFER__enumvalues = { + 0: 'DP_VID_STREAM_DIS_NO_DEFER', + 1: 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 2: 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', +} +DP_VID_STREAM_DIS_NO_DEFER = 0 +DP_VID_STREAM_DIS_DEFER_TO_HBLANK = 1 +DP_VID_STREAM_DIS_DEFER_TO_VBLANK = 2 +DP_VID_STREAM_DIS_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_ACK' +DP_STEER_OVERFLOW_ACK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_STEER_OVERFLOW_ACK_NO_EFFECT = 0 +DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_STEER_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_MASK' +DP_STEER_OVERFLOW_MASK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_MASKED', + 1: 'DP_STEER_OVERFLOW_UNMASK', +} +DP_STEER_OVERFLOW_MASKED = 0 +DP_STEER_OVERFLOW_UNMASK = 1 +DP_STEER_OVERFLOW_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_TU_OVERFLOW_ACK' +DP_TU_OVERFLOW_ACK__enumvalues = { + 0: 'DP_TU_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_TU_OVERFLOW_ACK_NO_EFFECT = 0 +DP_TU_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_TU_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_DOUBLE_BUFFER_MODE' +DP_VID_M_N_DOUBLE_BUFFER_MODE__enumvalues = { + 0: 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 1: 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', +} +DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE = 0 +DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START = 1 +DP_VID_M_N_DOUBLE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_GEN_EN' +DP_VID_M_N_GEN_EN__enumvalues = { + 0: 'DP_VID_M_N_PROGRAMMED_VIA_REG', + 1: 'DP_VID_M_N_CALC_AUTO', +} +DP_VID_M_N_PROGRAMMED_VIA_REG = 0 +DP_VID_M_N_CALC_AUTO = 1 +DP_VID_M_N_GEN_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_N_MUL' +DP_VID_N_MUL__enumvalues = { + 0: 'DP_VID_M_1X_INPUT_PIXEL_RATE', + 1: 'DP_VID_M_2X_INPUT_PIXEL_RATE', + 2: 'DP_VID_M_4X_INPUT_PIXEL_RATE', + 3: 'DP_VID_M_8X_INPUT_PIXEL_RATE', +} +DP_VID_M_1X_INPUT_PIXEL_RATE = 0 +DP_VID_M_2X_INPUT_PIXEL_RATE = 1 +DP_VID_M_4X_INPUT_PIXEL_RATE = 2 +DP_VID_M_8X_INPUT_PIXEL_RATE = 3 +DP_VID_N_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_ENHANCED_FRAME_MODE' +DP_VID_ENHANCED_FRAME_MODE__enumvalues = { + 0: 'VID_NORMAL_FRAME_MODE', + 1: 'VID_ENHANCED_MODE', +} +VID_NORMAL_FRAME_MODE = 0 +VID_ENHANCED_MODE = 1 +DP_VID_ENHANCED_FRAME_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_VBID_FIELD_POL' +DP_VID_VBID_FIELD_POL__enumvalues = { + 0: 'DP_VID_VBID_FIELD_POL_NORMAL', + 1: 'DP_VID_VBID_FIELD_POL_INV', +} +DP_VID_VBID_FIELD_POL_NORMAL = 0 +DP_VID_VBID_FIELD_POL_INV = 1 +DP_VID_VBID_FIELD_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_ACK' +DP_VID_STREAM_DISABLE_ACK__enumvalues = { + 0: 'ID_STREAM_DISABLE_NO_ACK', + 1: 'ID_STREAM_DISABLE_ACKED', +} +ID_STREAM_DISABLE_NO_ACK = 0 +ID_STREAM_DISABLE_ACKED = 1 +DP_VID_STREAM_DISABLE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_MASK' +DP_VID_STREAM_DISABLE_MASK__enumvalues = { + 0: 'VID_STREAM_DISABLE_MASKED', + 1: 'VID_STREAM_DISABLE_UNMASK', +} +VID_STREAM_DISABLE_MASKED = 0 +VID_STREAM_DISABLE_UNMASK = 1 +DP_VID_STREAM_DISABLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE0' +DPHY_ATEST_SEL_LANE0__enumvalues = { + 0: 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE0_REG_PATTERN', +} +DPHY_ATEST_LANE0_PRBS_PATTERN = 0 +DPHY_ATEST_LANE0_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE0 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE1' +DPHY_ATEST_SEL_LANE1__enumvalues = { + 0: 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE1_REG_PATTERN', +} +DPHY_ATEST_LANE1_PRBS_PATTERN = 0 +DPHY_ATEST_LANE1_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE1 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE2' +DPHY_ATEST_SEL_LANE2__enumvalues = { + 0: 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE2_REG_PATTERN', +} +DPHY_ATEST_LANE2_PRBS_PATTERN = 0 +DPHY_ATEST_LANE2_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE2 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE3' +DPHY_ATEST_SEL_LANE3__enumvalues = { + 0: 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE3_REG_PATTERN', +} +DPHY_ATEST_LANE3_PRBS_PATTERN = 0 +DPHY_ATEST_LANE3_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE3 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_BYPASS' +DPHY_BYPASS__enumvalues = { + 0: 'DPHY_8B10B_OUTPUT', + 1: 'DPHY_DBG_OUTPUT', +} +DPHY_8B10B_OUTPUT = 0 +DPHY_DBG_OUTPUT = 1 +DPHY_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SKEW_BYPASS' +DPHY_SKEW_BYPASS__enumvalues = { + 0: 'DPHY_WITH_SKEW', + 1: 'DPHY_NO_SKEW', +} +DPHY_WITH_SKEW = 0 +DPHY_NO_SKEW = 1 +DPHY_SKEW_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_TRAINING_PATTERN_SEL' +DPHY_TRAINING_PATTERN_SEL__enumvalues = { + 0: 'DPHY_TRAINING_PATTERN_1', + 1: 'DPHY_TRAINING_PATTERN_2', + 2: 'DPHY_TRAINING_PATTERN_3', + 3: 'DPHY_TRAINING_PATTERN_4', +} +DPHY_TRAINING_PATTERN_1 = 0 +DPHY_TRAINING_PATTERN_2 = 1 +DPHY_TRAINING_PATTERN_3 = 2 +DPHY_TRAINING_PATTERN_4 = 3 +DPHY_TRAINING_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_RESET' +DPHY_8B10B_RESET__enumvalues = { + 0: 'DPHY_8B10B_NOT_RESET', + 1: 'DPHY_8B10B_RESETET', +} +DPHY_8B10B_NOT_RESET = 0 +DPHY_8B10B_RESETET = 1 +DPHY_8B10B_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_8B10B_EXT_DISP' +DP_DPHY_8B10B_EXT_DISP__enumvalues = { + 0: 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 1: 'DP_DPHY_8B10B_EXT_DISP_ONE', +} +DP_DPHY_8B10B_EXT_DISP_ZERO = 0 +DP_DPHY_8B10B_EXT_DISP_ONE = 1 +DP_DPHY_8B10B_EXT_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_CUR_DISP' +DPHY_8B10B_CUR_DISP__enumvalues = { + 0: 'DPHY_8B10B_CUR_DISP_ZERO', + 1: 'DPHY_8B10B_CUR_DISP_ONE', +} +DPHY_8B10B_CUR_DISP_ZERO = 0 +DPHY_8B10B_CUR_DISP_ONE = 1 +DPHY_8B10B_CUR_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_EN' +DPHY_PRBS_EN__enumvalues = { + 0: 'DPHY_PRBS_DISABLE', + 1: 'DPHY_PRBS_ENABLE', +} +DPHY_PRBS_DISABLE = 0 +DPHY_PRBS_ENABLE = 1 +DPHY_PRBS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_SEL' +DPHY_PRBS_SEL__enumvalues = { + 0: 'DPHY_PRBS7_SELECTED', + 1: 'DPHY_PRBS23_SELECTED', + 2: 'DPHY_PRBS11_SELECTED', +} +DPHY_PRBS7_SELECTED = 0 +DPHY_PRBS23_SELECTED = 1 +DPHY_PRBS11_SELECTED = 2 +DPHY_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_ENABLE' +DPHY_FEC_ENABLE__enumvalues = { + 0: 'DPHY_FEC_DISABLED', + 1: 'DPHY_FEC_ENABLED', +} +DPHY_FEC_DISABLED = 0 +DPHY_FEC_ENABLED = 1 +DPHY_FEC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'FEC_ACTIVE_STATUS' +FEC_ACTIVE_STATUS__enumvalues = { + 0: 'DPHY_FEC_NOT_ACTIVE', + 1: 'DPHY_FEC_ACTIVE', +} +DPHY_FEC_NOT_ACTIVE = 0 +DPHY_FEC_ACTIVE = 1 +FEC_ACTIVE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_READY' +DPHY_FEC_READY__enumvalues = { + 0: 'DPHY_FEC_READY_EN', + 1: 'DPHY_FEC_READY_DIS', +} +DPHY_FEC_READY_EN = 0 +DPHY_FEC_READY_DIS = 1 +DPHY_FEC_READY = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_LOAD_BS_COUNT_START' +DPHY_LOAD_BS_COUNT_START__enumvalues = { + 0: 'DPHY_LOAD_BS_COUNT_STARTED', + 1: 'DPHY_LOAD_BS_COUNT_NOT_STARTED', +} +DPHY_LOAD_BS_COUNT_STARTED = 0 +DPHY_LOAD_BS_COUNT_NOT_STARTED = 1 +DPHY_LOAD_BS_COUNT_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_EN' +DPHY_CRC_EN__enumvalues = { + 0: 'DPHY_CRC_DISABLED', + 1: 'DPHY_CRC_ENABLED', +} +DPHY_CRC_DISABLED = 0 +DPHY_CRC_ENABLED = 1 +DPHY_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_CONT_EN' +DPHY_CRC_CONT_EN__enumvalues = { + 0: 'DPHY_CRC_ONE_SHOT', + 1: 'DPHY_CRC_CONTINUOUS', +} +DPHY_CRC_ONE_SHOT = 0 +DPHY_CRC_CONTINUOUS = 1 +DPHY_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_FIELD' +DPHY_CRC_FIELD__enumvalues = { + 0: 'DPHY_CRC_START_FROM_TOP_FIELD', + 1: 'DPHY_CRC_START_FROM_BOTTOM_FIELD', +} +DPHY_CRC_START_FROM_TOP_FIELD = 0 +DPHY_CRC_START_FROM_BOTTOM_FIELD = 1 +DPHY_CRC_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_SEL' +DPHY_CRC_SEL__enumvalues = { + 0: 'DPHY_CRC_LANE0_SELECTED', + 1: 'DPHY_CRC_LANE1_SELECTED', + 2: 'DPHY_CRC_LANE2_SELECTED', + 3: 'DPHY_CRC_LANE3_SELECTED', +} +DPHY_CRC_LANE0_SELECTED = 0 +DPHY_CRC_LANE1_SELECTED = 1 +DPHY_CRC_LANE2_SELECTED = 2 +DPHY_CRC_LANE3_SELECTED = 3 +DPHY_CRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_RX_FAST_TRAINING_CAPABLE' +DPHY_RX_FAST_TRAINING_CAPABLE__enumvalues = { + 0: 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 1: 'DPHY_FAST_TRAINING_CAPABLE', +} +DPHY_FAST_TRAINING_NOT_CAPABLE_0 = 0 +DPHY_FAST_TRAINING_CAPABLE = 1 +DPHY_RX_FAST_TRAINING_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_COLLISION_ACK' +DP_SEC_COLLISION_ACK__enumvalues = { + 0: 'DP_SEC_COLLISION_ACK_NO_EFFECT', + 1: 'DP_SEC_COLLISION_ACK_CLR_FLAG', +} +DP_SEC_COLLISION_ACK_NO_EFFECT = 0 +DP_SEC_COLLISION_ACK_CLR_FLAG = 1 +DP_SEC_COLLISION_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_AUDIO_MUTE' +DP_SEC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SEC_AUDIO_MUTE_HW_CTRL', + 1: 'DP_SEC_AUDIO_MUTE_SW_CTRL', +} +DP_SEC_AUDIO_MUTE_HW_CTRL = 0 +DP_SEC_AUDIO_MUTE_SW_CTRL = 1 +DP_SEC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_TIMESTAMP_MODE' +DP_SEC_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', + 1: 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', +} +DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE = 0 +DP_SEC_TIMESTAMP_AUTO_CALC_MODE = 1 +DP_SEC_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_PRIORITY' +DP_SEC_ASP_PRIORITY__enumvalues = { + 0: 'DP_SEC_ASP_LOW_PRIORITY', + 1: 'DP_SEC_ASP_HIGH_PRIORITY', +} +DP_SEC_ASP_LOW_PRIORITY = 0 +DP_SEC_ASP_HIGH_PRIORITY = 1 +DP_SEC_ASP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE' +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ = 0 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_UPDATE_ACT' +DP_MSE_SAT_UPDATE_ACT__enumvalues = { + 0: 'DP_MSE_SAT_UPDATE_NO_ACTION', + 1: 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 2: 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', +} +DP_MSE_SAT_UPDATE_NO_ACTION = 0 +DP_MSE_SAT_UPDATE_WITH_TRIGGER = 1 +DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER = 2 +DP_MSE_SAT_UPDATE_ACT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_LINK_LINE' +DP_MSE_LINK_LINE__enumvalues = { + 0: 'DP_MSE_LINK_LINE_32_MTP_LONG', + 1: 'DP_MSE_LINK_LINE_64_MTP_LONG', + 2: 'DP_MSE_LINK_LINE_128_MTP_LONG', + 3: 'DP_MSE_LINK_LINE_256_MTP_LONG', +} +DP_MSE_LINK_LINE_32_MTP_LONG = 0 +DP_MSE_LINK_LINE_64_MTP_LONG = 1 +DP_MSE_LINK_LINE_128_MTP_LONG = 2 +DP_MSE_LINK_LINE_256_MTP_LONG = 3 +DP_MSE_LINK_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_BLANK_CODE' +DP_MSE_BLANK_CODE__enumvalues = { + 0: 'DP_MSE_BLANK_CODE_SF_FILLED', + 1: 'DP_MSE_BLANK_CODE_ZERO_FILLED', +} +DP_MSE_BLANK_CODE_SF_FILLED = 0 +DP_MSE_BLANK_CODE_ZERO_FILLED = 1 +DP_MSE_BLANK_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_TIMESTAMP_MODE' +DP_MSE_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 1: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', +} +DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE = 0 +DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE = 1 +DP_MSE_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_ZERO_ENCODER' +DP_MSE_ZERO_ENCODER__enumvalues = { + 0: 'DP_MSE_NOT_ZERO_FE_ENCODER', + 1: 'DP_MSE_ZERO_FE_ENCODER', +} +DP_MSE_NOT_ZERO_FE_ENCODER = 0 +DP_MSE_ZERO_FE_ENCODER = 1 +DP_MSE_ZERO_ENCODER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE' +DP_DPHY_HBR2_PATTERN_CONTROL_MODE__enumvalues = { + 0: 'DP_DPHY_HBR2_PASS_THROUGH', + 1: 'DP_DPHY_HBR2_PATTERN_1', + 2: 'DP_DPHY_HBR2_PATTERN_2_NEG', + 3: 'DP_DPHY_HBR2_PATTERN_3', + 6: 'DP_DPHY_HBR2_PATTERN_2_POS', +} +DP_DPHY_HBR2_PASS_THROUGH = 0 +DP_DPHY_HBR2_PATTERN_1 = 1 +DP_DPHY_HBR2_PATTERN_2_NEG = 2 +DP_DPHY_HBR2_PATTERN_3 = 3 +DP_DPHY_HBR2_PATTERN_2_POS = 6 +DP_DPHY_HBR2_PATTERN_CONTROL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_MST_PHASE_ERROR_ACK' +DPHY_CRC_MST_PHASE_ERROR_ACK__enumvalues = { + 0: 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', + 1: 'DPHY_CRC_MST_PHASE_ERROR_ACKED', +} +DPHY_CRC_MST_PHASE_ERROR_NO_ACK = 0 +DPHY_CRC_MST_PHASE_ERROR_ACKED = 1 +DPHY_CRC_MST_PHASE_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SW_FAST_TRAINING_START' +DPHY_SW_FAST_TRAINING_START__enumvalues = { + 0: 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 1: 'DPHY_SW_FAST_TRAINING_STARTED', +} +DPHY_SW_FAST_TRAINING_NOT_STARTED = 0 +DPHY_SW_FAST_TRAINING_STARTED = 1 +DPHY_SW_FAST_TRAINING_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN' +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 1: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', +} +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED = 0 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED = 1 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK' +DP_DPHY_FAST_TRAINING_COMPLETE_MASK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_MASKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK' +DP_DPHY_FAST_TRAINING_COMPLETE_ACK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_ACKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_V_TIMING_OVERRIDE_EN' +DP_MSA_V_TIMING_OVERRIDE_EN__enumvalues = { + 0: 'MSA_V_TIMING_OVERRIDE_DISABLED', + 1: 'MSA_V_TIMING_OVERRIDE_ENABLED', +} +MSA_V_TIMING_OVERRIDE_DISABLED = 0 +MSA_V_TIMING_OVERRIDE_ENABLED = 1 +DP_MSA_V_TIMING_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP0_PRIORITY' +DP_SEC_GSP0_PRIORITY__enumvalues = { + 0: 'SEC_GSP0_PRIORITY_LOW', + 1: 'SEC_GSP0_PRIORITY_HIGH', +} +SEC_GSP0_PRIORITY_LOW = 0 +SEC_GSP0_PRIORITY_HIGH = 1 +DP_SEC_GSP0_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND' +DP_SEC_GSP_SEND__enumvalues = { + 0: 'NOT_SENT', + 1: 'FORCE_SENT', +} +NOT_SENT = 0 +FORCE_SENT = 1 +DP_SEC_GSP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_ANY_LINE' +DP_SEC_GSP_SEND_ANY_LINE__enumvalues = { + 0: 'SEND_AT_LINK_NUMBER', + 1: 'SEND_AT_EARLIEST_TIME', +} +SEND_AT_LINK_NUMBER = 0 +SEND_AT_EARLIEST_TIME = 1 +DP_SEC_GSP_SEND_ANY_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_LINE_REFERENCE' +DP_SEC_LINE_REFERENCE__enumvalues = { + 0: 'REFER_TO_DP_SOF', + 1: 'REFER_TO_OTG_SOF', +} +REFER_TO_DP_SOF = 0 +REFER_TO_OTG_SOF = 1 +DP_SEC_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_PPS' +DP_SEC_GSP_SEND_PPS__enumvalues = { + 0: 'SEND_NORMAL_PACKET', + 1: 'SEND_PPS_PACKET', +} +SEND_NORMAL_PACKET = 0 +SEND_PPS_PACKET = 1 +DP_SEC_GSP_SEND_PPS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_ML_PHY_SEQ_MODE' +DP_ML_PHY_SEQ_MODE__enumvalues = { + 0: 'DP_ML_PHY_SEQ_LINE_NUM', + 1: 'DP_ML_PHY_SEQ_IMMEDIATE', +} +DP_ML_PHY_SEQ_LINE_NUM = 0 +DP_ML_PHY_SEQ_IMMEDIATE = 1 +DP_ML_PHY_SEQ_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_SWITCH_MODE' +DP_LINK_TRAINING_SWITCH_MODE__enumvalues = { + 0: 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 1: 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', +} +DP_LINK_TRAINING_SWITCH_TO_IDLE = 0 +DP_LINK_TRAINING_SWITCH_TO_VIDEO = 1 +DP_LINK_TRAINING_SWITCH_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DSC_MODE' +DP_DSC_MODE__enumvalues = { + 0: 'DP_DSC_DISABLE', + 1: 'DP_DSC_444_SIMPLE_422', + 2: 'DP_DSC_NATIVE_422_420', +} +DP_DSC_DISABLE = 0 +DP_DSC_444_SIMPLE_422 = 1 +DP_DSC_NATIVE_422_420 = 2 +DP_DSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_KEEPOUT_MODE' +HDMI_KEEPOUT_MODE__enumvalues = { + 0: 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 1: 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', +} +HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC = 0 +HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC = 1 +HDMI_KEEPOUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_CLOCK_CHANNEL_RATE' +HDMI_CLOCK_CHANNEL_RATE__enumvalues = { + 0: 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 1: 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', +} +HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE = 0 +HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE = 1 +HDMI_CLOCK_CHANNEL_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NO_EXTRA_NULL_PACKET_FILLED' +HDMI_NO_EXTRA_NULL_PACKET_FILLED__enumvalues = { + 0: 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', + 1: 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', +} +HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE = 0 +HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE = 1 +HDMI_NO_EXTRA_NULL_PACKET_FILLED = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_GEN_VERSION' +HDMI_PACKET_GEN_VERSION__enumvalues = { + 0: 'HDMI_PACKET_GEN_VERSION_OLD', + 1: 'HDMI_PACKET_GEN_VERSION_NEW', +} +HDMI_PACKET_GEN_VERSION_OLD = 0 +HDMI_PACKET_GEN_VERSION_NEW = 1 +HDMI_PACKET_GEN_VERSION = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_ACK' +HDMI_ERROR_ACK__enumvalues = { + 0: 'HDMI_ERROR_ACK_INT', + 1: 'HDMI_ERROR_NOT_ACK', +} +HDMI_ERROR_ACK_INT = 0 +HDMI_ERROR_NOT_ACK = 1 +HDMI_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_MASK' +HDMI_ERROR_MASK__enumvalues = { + 0: 'HDMI_ERROR_MASK_INT', + 1: 'HDMI_ERROR_NOT_MASK', +} +HDMI_ERROR_MASK_INT = 0 +HDMI_ERROR_NOT_MASK = 1 +HDMI_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEEP_COLOR_DEPTH' +HDMI_DEEP_COLOR_DEPTH__enumvalues = { + 0: 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 1: 'HDMI_DEEP_COLOR_DEPTH_30BPP', + 2: 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 3: 'HDMI_DEEP_COLOR_DEPTH_48BPP', +} +HDMI_DEEP_COLOR_DEPTH_24BPP = 0 +HDMI_DEEP_COLOR_DEPTH_30BPP = 1 +HDMI_DEEP_COLOR_DEPTH_36BPP = 2 +HDMI_DEEP_COLOR_DEPTH_48BPP = 3 +HDMI_DEEP_COLOR_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_DELAY_EN' +HDMI_AUDIO_DELAY_EN__enumvalues = { + 0: 'HDMI_AUDIO_DELAY_DISABLE', + 1: 'HDMI_AUDIO_DELAY_58CLK', + 2: 'HDMI_AUDIO_DELAY_56CLK', + 3: 'HDMI_AUDIO_DELAY_RESERVED', +} +HDMI_AUDIO_DELAY_DISABLE = 0 +HDMI_AUDIO_DELAY_58CLK = 1 +HDMI_AUDIO_DELAY_56CLK = 2 +HDMI_AUDIO_DELAY_RESERVED = 3 +HDMI_AUDIO_DELAY_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_SEND_MAX_PACKETS' +HDMI_AUDIO_SEND_MAX_PACKETS__enumvalues = { + 0: 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 1: 'HDMI_SEND_MAX_AUDIO_PACKETS', +} +HDMI_NOT_SEND_MAX_AUDIO_PACKETS = 0 +HDMI_SEND_MAX_AUDIO_PACKETS = 1 +HDMI_AUDIO_SEND_MAX_PACKETS = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SEND' +HDMI_ACR_SEND__enumvalues = { + 0: 'HDMI_ACR_NOT_SEND', + 1: 'HDMI_ACR_PKT_SEND', +} +HDMI_ACR_NOT_SEND = 0 +HDMI_ACR_PKT_SEND = 1 +HDMI_ACR_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_CONT' +HDMI_ACR_CONT__enumvalues = { + 0: 'HDMI_ACR_CONT_DISABLE', + 1: 'HDMI_ACR_CONT_ENABLE', +} +HDMI_ACR_CONT_DISABLE = 0 +HDMI_ACR_CONT_ENABLE = 1 +HDMI_ACR_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SELECT' +HDMI_ACR_SELECT__enumvalues = { + 0: 'HDMI_ACR_SELECT_HW', + 1: 'HDMI_ACR_SELECT_32K', + 2: 'HDMI_ACR_SELECT_44K', + 3: 'HDMI_ACR_SELECT_48K', +} +HDMI_ACR_SELECT_HW = 0 +HDMI_ACR_SELECT_32K = 1 +HDMI_ACR_SELECT_44K = 2 +HDMI_ACR_SELECT_48K = 3 +HDMI_ACR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SOURCE' +HDMI_ACR_SOURCE__enumvalues = { + 0: 'HDMI_ACR_SOURCE_HW', + 1: 'HDMI_ACR_SOURCE_SW', +} +HDMI_ACR_SOURCE_HW = 0 +HDMI_ACR_SOURCE_SW = 1 +HDMI_ACR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_N_MULTIPLE' +HDMI_ACR_N_MULTIPLE__enumvalues = { + 0: 'HDMI_ACR_0_MULTIPLE_RESERVED', + 1: 'HDMI_ACR_1_MULTIPLE', + 2: 'HDMI_ACR_2_MULTIPLE', + 3: 'HDMI_ACR_3_MULTIPLE_RESERVED', + 4: 'HDMI_ACR_4_MULTIPLE', + 5: 'HDMI_ACR_5_MULTIPLE_RESERVED', + 6: 'HDMI_ACR_6_MULTIPLE_RESERVED', + 7: 'HDMI_ACR_7_MULTIPLE_RESERVED', +} +HDMI_ACR_0_MULTIPLE_RESERVED = 0 +HDMI_ACR_1_MULTIPLE = 1 +HDMI_ACR_2_MULTIPLE = 2 +HDMI_ACR_3_MULTIPLE_RESERVED = 3 +HDMI_ACR_4_MULTIPLE = 4 +HDMI_ACR_5_MULTIPLE_RESERVED = 5 +HDMI_ACR_6_MULTIPLE_RESERVED = 6 +HDMI_ACR_7_MULTIPLE_RESERVED = 7 +HDMI_ACR_N_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_AUDIO_PRIORITY' +HDMI_ACR_AUDIO_PRIORITY__enumvalues = { + 0: 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 1: 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', +} +HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE = 0 +HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT = 1 +HDMI_ACR_AUDIO_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NULL_SEND' +HDMI_NULL_SEND__enumvalues = { + 0: 'HDMI_NULL_NOT_SEND', + 1: 'HDMI_NULL_PKT_SEND', +} +HDMI_NULL_NOT_SEND = 0 +HDMI_NULL_PKT_SEND = 1 +HDMI_NULL_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_SEND' +HDMI_GC_SEND__enumvalues = { + 0: 'HDMI_GC_NOT_SEND', + 1: 'HDMI_GC_PKT_SEND', +} +HDMI_GC_NOT_SEND = 0 +HDMI_GC_PKT_SEND = 1 +HDMI_GC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_CONT' +HDMI_GC_CONT__enumvalues = { + 0: 'HDMI_GC_CONT_DISABLE', + 1: 'HDMI_GC_CONT_ENABLE', +} +HDMI_GC_CONT_DISABLE = 0 +HDMI_GC_CONT_ENABLE = 1 +HDMI_GC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_SEND' +HDMI_ISRC_SEND__enumvalues = { + 0: 'HDMI_ISRC_NOT_SEND', + 1: 'HDMI_ISRC_PKT_SEND', +} +HDMI_ISRC_NOT_SEND = 0 +HDMI_ISRC_PKT_SEND = 1 +HDMI_ISRC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_CONT' +HDMI_ISRC_CONT__enumvalues = { + 0: 'HDMI_ISRC_CONT_DISABLE', + 1: 'HDMI_ISRC_CONT_ENABLE', +} +HDMI_ISRC_CONT_DISABLE = 0 +HDMI_ISRC_CONT_ENABLE = 1 +HDMI_ISRC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_SEND' +HDMI_AUDIO_INFO_SEND__enumvalues = { + 0: 'HDMI_AUDIO_INFO_NOT_SEND', + 1: 'HDMI_AUDIO_INFO_PKT_SEND', +} +HDMI_AUDIO_INFO_NOT_SEND = 0 +HDMI_AUDIO_INFO_PKT_SEND = 1 +HDMI_AUDIO_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_CONT' +HDMI_AUDIO_INFO_CONT__enumvalues = { + 0: 'HDMI_AUDIO_INFO_CONT_DISABLE', + 1: 'HDMI_AUDIO_INFO_CONT_ENABLE', +} +HDMI_AUDIO_INFO_CONT_DISABLE = 0 +HDMI_AUDIO_INFO_CONT_ENABLE = 1 +HDMI_AUDIO_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_SEND' +HDMI_MPEG_INFO_SEND__enumvalues = { + 0: 'HDMI_MPEG_INFO_NOT_SEND', + 1: 'HDMI_MPEG_INFO_PKT_SEND', +} +HDMI_MPEG_INFO_NOT_SEND = 0 +HDMI_MPEG_INFO_PKT_SEND = 1 +HDMI_MPEG_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_CONT' +HDMI_MPEG_INFO_CONT__enumvalues = { + 0: 'HDMI_MPEG_INFO_CONT_DISABLE', + 1: 'HDMI_MPEG_INFO_CONT_ENABLE', +} +HDMI_MPEG_INFO_CONT_DISABLE = 0 +HDMI_MPEG_INFO_CONT_ENABLE = 1 +HDMI_MPEG_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_SEND' +HDMI_GENERIC_SEND__enumvalues = { + 0: 'HDMI_GENERIC_NOT_SEND', + 1: 'HDMI_GENERIC_PKT_SEND', +} +HDMI_GENERIC_NOT_SEND = 0 +HDMI_GENERIC_PKT_SEND = 1 +HDMI_GENERIC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_CONT' +HDMI_GENERIC_CONT__enumvalues = { + 0: 'HDMI_GENERIC_CONT_DISABLE', + 1: 'HDMI_GENERIC_CONT_ENABLE', +} +HDMI_GENERIC_CONT_DISABLE = 0 +HDMI_GENERIC_CONT_ENABLE = 1 +HDMI_GENERIC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE_CONT' +HDMI_GC_AVMUTE_CONT__enumvalues = { + 0: 'HDMI_GC_AVMUTE_CONT_DISABLE', + 1: 'HDMI_GC_AVMUTE_CONT_ENABLE', +} +HDMI_GC_AVMUTE_CONT_DISABLE = 0 +HDMI_GC_AVMUTE_CONT_ENABLE = 1 +HDMI_GC_AVMUTE_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKING_PHASE_OVERRIDE' +HDMI_PACKING_PHASE_OVERRIDE__enumvalues = { + 0: 'HDMI_PACKING_PHASE_SET_BY_HW', + 1: 'HDMI_PACKING_PHASE_SET_BY_SW', +} +HDMI_PACKING_PHASE_SET_BY_HW = 0 +HDMI_PACKING_PHASE_SET_BY_SW = 1 +HDMI_PACKING_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_PIXEL_ENCODING' +TMDS_PIXEL_ENCODING__enumvalues = { + 0: 'TMDS_PIXEL_ENCODING_444_OR_420', + 1: 'TMDS_PIXEL_ENCODING_422', +} +TMDS_PIXEL_ENCODING_444_OR_420 = 0 +TMDS_PIXEL_ENCODING_422 = 1 +TMDS_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_COLOR_FORMAT' +TMDS_COLOR_FORMAT__enumvalues = { + 0: 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 1: 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 2: 'TMDS_COLOR_FORMAT_DUAL30BPP', + 3: 'TMDS_COLOR_FORMAT_RESERVED', +} +TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP = 0 +TMDS_COLOR_FORMAT_TWIN30BPP_LSB = 1 +TMDS_COLOR_FORMAT_DUAL30BPP = 2 +TMDS_COLOR_FORMAT_RESERVED = 3 +TMDS_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_STEREOSYNC_CTL_SEL_REG' +TMDS_STEREOSYNC_CTL_SEL_REG__enumvalues = { + 0: 'TMDS_STEREOSYNC_CTL0', + 1: 'TMDS_STEREOSYNC_CTL1', + 2: 'TMDS_STEREOSYNC_CTL2', + 3: 'TMDS_STEREOSYNC_CTL3', +} +TMDS_STEREOSYNC_CTL0 = 0 +TMDS_STEREOSYNC_CTL1 = 1 +TMDS_STEREOSYNC_CTL2 = 2 +TMDS_STEREOSYNC_CTL3 = 3 +TMDS_STEREOSYNC_CTL_SEL_REG = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_SEL' +TMDS_CTL0_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL0_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL0_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL0_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL0_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 7: 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', +} +TMDS_CTL0_DATA_SEL0_RESERVED = 0 +TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL0_DATA_SEL2_VSYNC = 2 +TMDS_CTL0_DATA_SEL3_RESERVED = 3 +TMDS_CTL0_DATA_SEL4_HSYNC = 4 +TMDS_CTL0_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL0_DATA_SEL8_RANDOM_DATA = 6 +TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA = 7 +TMDS_CTL0_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_INVERT' +TMDS_CTL0_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL0_DATA_NORMAL', + 1: 'TMDS_CTL0_DATA_INVERT_EN', +} +TMDS_CTL0_DATA_NORMAL = 0 +TMDS_CTL0_DATA_INVERT_EN = 1 +TMDS_CTL0_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_MODULATION' +TMDS_CTL0_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL0_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL0_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL0_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL0_DATA_MODULATION_BIT2', +} +TMDS_CTL0_DATA_MODULATION_DISABLE = 0 +TMDS_CTL0_DATA_MODULATION_BIT0 = 1 +TMDS_CTL0_DATA_MODULATION_BIT1 = 2 +TMDS_CTL0_DATA_MODULATION_BIT2 = 3 +TMDS_CTL0_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_PATTERN_OUT_EN' +TMDS_CTL0_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL0_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL0_PATTERN_OUT_ENABLE', +} +TMDS_CTL0_PATTERN_OUT_DISABLE = 0 +TMDS_CTL0_PATTERN_OUT_ENABLE = 1 +TMDS_CTL0_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_SEL' +TMDS_CTL1_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL1_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL1_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL1_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL1_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL1_DATA_SEL0_RESERVED = 0 +TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL1_DATA_SEL2_VSYNC = 2 +TMDS_CTL1_DATA_SEL3_RESERVED = 3 +TMDS_CTL1_DATA_SEL4_HSYNC = 4 +TMDS_CTL1_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL1_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL1_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL1_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_INVERT' +TMDS_CTL1_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL1_DATA_NORMAL', + 1: 'TMDS_CTL1_DATA_INVERT_EN', +} +TMDS_CTL1_DATA_NORMAL = 0 +TMDS_CTL1_DATA_INVERT_EN = 1 +TMDS_CTL1_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_MODULATION' +TMDS_CTL1_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL1_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL1_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL1_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL1_DATA_MODULATION_BIT2', +} +TMDS_CTL1_DATA_MODULATION_DISABLE = 0 +TMDS_CTL1_DATA_MODULATION_BIT0 = 1 +TMDS_CTL1_DATA_MODULATION_BIT1 = 2 +TMDS_CTL1_DATA_MODULATION_BIT2 = 3 +TMDS_CTL1_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_PATTERN_OUT_EN' +TMDS_CTL1_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL1_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL1_PATTERN_OUT_ENABLE', +} +TMDS_CTL1_PATTERN_OUT_DISABLE = 0 +TMDS_CTL1_PATTERN_OUT_ENABLE = 1 +TMDS_CTL1_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_SEL' +TMDS_CTL2_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL2_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL2_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL2_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL2_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL2_DATA_SEL0_RESERVED = 0 +TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL2_DATA_SEL2_VSYNC = 2 +TMDS_CTL2_DATA_SEL3_RESERVED = 3 +TMDS_CTL2_DATA_SEL4_HSYNC = 4 +TMDS_CTL2_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL2_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL2_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL2_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_INVERT' +TMDS_CTL2_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL2_DATA_NORMAL', + 1: 'TMDS_CTL2_DATA_INVERT_EN', +} +TMDS_CTL2_DATA_NORMAL = 0 +TMDS_CTL2_DATA_INVERT_EN = 1 +TMDS_CTL2_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_MODULATION' +TMDS_CTL2_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL2_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL2_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL2_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL2_DATA_MODULATION_BIT2', +} +TMDS_CTL2_DATA_MODULATION_DISABLE = 0 +TMDS_CTL2_DATA_MODULATION_BIT0 = 1 +TMDS_CTL2_DATA_MODULATION_BIT1 = 2 +TMDS_CTL2_DATA_MODULATION_BIT2 = 3 +TMDS_CTL2_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_PATTERN_OUT_EN' +TMDS_CTL2_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL2_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL2_PATTERN_OUT_ENABLE', +} +TMDS_CTL2_PATTERN_OUT_DISABLE = 0 +TMDS_CTL2_PATTERN_OUT_ENABLE = 1 +TMDS_CTL2_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_INVERT' +TMDS_CTL3_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL3_DATA_NORMAL', + 1: 'TMDS_CTL3_DATA_INVERT_EN', +} +TMDS_CTL3_DATA_NORMAL = 0 +TMDS_CTL3_DATA_INVERT_EN = 1 +TMDS_CTL3_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_MODULATION' +TMDS_CTL3_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL3_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL3_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL3_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL3_DATA_MODULATION_BIT2', +} +TMDS_CTL3_DATA_MODULATION_DISABLE = 0 +TMDS_CTL3_DATA_MODULATION_BIT0 = 1 +TMDS_CTL3_DATA_MODULATION_BIT1 = 2 +TMDS_CTL3_DATA_MODULATION_BIT2 = 3 +TMDS_CTL3_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_PATTERN_OUT_EN' +TMDS_CTL3_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL3_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL3_PATTERN_OUT_ENABLE', +} +TMDS_CTL3_PATTERN_OUT_DISABLE = 0 +TMDS_CTL3_PATTERN_OUT_ENABLE = 1 +TMDS_CTL3_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_SEL' +TMDS_CTL3_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL3_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL3_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL3_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL3_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL3_DATA_SEL0_RESERVED = 0 +TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL3_DATA_SEL2_VSYNC = 2 +TMDS_CTL3_DATA_SEL3_RESERVED = 3 +TMDS_CTL3_DATA_SEL4_HSYNC = 4 +TMDS_CTL3_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL3_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL3_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL3_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_SOURCE_SELECT' +DIG_FE_CNTL_SOURCE_SELECT__enumvalues = { + 0: 'DIG_FE_SOURCE_FROM_OTG0', + 1: 'DIG_FE_SOURCE_FROM_OTG1', + 2: 'DIG_FE_SOURCE_FROM_OTG2', + 3: 'DIG_FE_SOURCE_FROM_OTG3', + 4: 'DIG_FE_SOURCE_FROM_OTG4', + 5: 'DIG_FE_SOURCE_FROM_OTG5', + 6: 'DIG_FE_SOURCE_RESERVED', +} +DIG_FE_SOURCE_FROM_OTG0 = 0 +DIG_FE_SOURCE_FROM_OTG1 = 1 +DIG_FE_SOURCE_FROM_OTG2 = 2 +DIG_FE_SOURCE_FROM_OTG3 = 3 +DIG_FE_SOURCE_FROM_OTG4 = 4 +DIG_FE_SOURCE_FROM_OTG5 = 5 +DIG_FE_SOURCE_RESERVED = 6 +DIG_FE_CNTL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_STEREOSYNC_SELECT' +DIG_FE_CNTL_STEREOSYNC_SELECT__enumvalues = { + 0: 'DIG_FE_STEREOSYNC_FROM_OTG0', + 1: 'DIG_FE_STEREOSYNC_FROM_OTG1', + 2: 'DIG_FE_STEREOSYNC_FROM_OTG2', + 3: 'DIG_FE_STEREOSYNC_FROM_OTG3', + 4: 'DIG_FE_STEREOSYNC_FROM_OTG4', + 5: 'DIG_FE_STEREOSYNC_FROM_OTG5', + 6: 'DIG_FE_STEREOSYNC_RESERVED', +} +DIG_FE_STEREOSYNC_FROM_OTG0 = 0 +DIG_FE_STEREOSYNC_FROM_OTG1 = 1 +DIG_FE_STEREOSYNC_FROM_OTG2 = 2 +DIG_FE_STEREOSYNC_FROM_OTG3 = 3 +DIG_FE_STEREOSYNC_FROM_OTG4 = 4 +DIG_FE_STEREOSYNC_FROM_OTG5 = 5 +DIG_FE_STEREOSYNC_RESERVED = 6 +DIG_FE_CNTL_STEREOSYNC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_READ_CLOCK_SRC' +DIG_FIFO_READ_CLOCK_SRC__enumvalues = { + 0: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 1: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', +} +DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG = 0 +DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE = 1 +DIG_FIFO_READ_CLOCK_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_CNTL_LINK_SEL' +DIG_OUTPUT_CRC_CNTL_LINK_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_ON_LINK0', + 1: 'DIG_OUTPUT_CRC_ON_LINK1', +} +DIG_OUTPUT_CRC_ON_LINK0 = 0 +DIG_OUTPUT_CRC_ON_LINK1 = 1 +DIG_OUTPUT_CRC_CNTL_LINK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_DATA_SEL' +DIG_OUTPUT_CRC_DATA_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_FOR_FULLFRAME', + 1: 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', + 2: 'DIG_OUTPUT_CRC_FOR_VBI', + 3: 'DIG_OUTPUT_CRC_FOR_AUDIO', +} +DIG_OUTPUT_CRC_FOR_FULLFRAME = 0 +DIG_OUTPUT_CRC_FOR_ACTIVEONLY = 1 +DIG_OUTPUT_CRC_FOR_VBI = 2 +DIG_OUTPUT_CRC_FOR_AUDIO = 3 +DIG_OUTPUT_CRC_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN' +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_IN_NORMAL_OPERATION', + 1: 'DIG_IN_DEBUG_MODE', +} +DIG_IN_NORMAL_OPERATION = 0 +DIG_IN_DEBUG_MODE = 1 +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL' +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL__enumvalues = { + 0: 'DIG_10BIT_TEST_PATTERN', + 1: 'DIG_ALTERNATING_TEST_PATTERN', +} +DIG_10BIT_TEST_PATTERN = 0 +DIG_ALTERNATING_TEST_PATTERN = 1 +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN' +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_NORMAL', + 1: 'DIG_TEST_PATTERN_RANDOM', +} +DIG_TEST_PATTERN_NORMAL = 0 +DIG_TEST_PATTERN_RANDOM = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET' +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_ENABLED', + 1: 'DIG_RANDOM_PATTERN_RESETED', +} +DIG_RANDOM_PATTERN_ENABLED = 0 +DIG_RANDOM_PATTERN_RESETED = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN' +DIG_TEST_PATTERN_EXTERNAL_RESET_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 1: 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', +} +DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE = 0 +DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG = 1 +DIG_TEST_PATTERN_EXTERNAL_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_RANDOM_PATTERN_SEED_RAN_PAT' +DIG_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 1: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', +} +DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS = 0 +DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH = 1 +DIG_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL' +DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL__enumvalues = { + 0: 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 1: 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', +} +DIG_FIFO_USE_OVERWRITE_LEVEL = 0 +DIG_FIFO_USE_CAL_AVERAGE_LEVEL = 1 +DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_ERROR_ACK' +DIG_FIFO_ERROR_ACK__enumvalues = { + 0: 'DIG_FIFO_ERROR_ACK_INT', + 1: 'DIG_FIFO_ERROR_NOT_ACK', +} +DIG_FIFO_ERROR_ACK_INT = 0 +DIG_FIFO_ERROR_NOT_ACK = 1 +DIG_FIFO_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE' +DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 1: 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', +} +DIG_FIFO_NOT_FORCE_RECAL_AVERAGE = 0 +DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL = 1 +DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX' +DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', + 1: 'DIG_FIFO_FORCE_RECOMP_MINMAX', +} +DIG_FIFO_NOT_FORCE_RECOMP_MINMAX = 0 +DIG_FIFO_FORCE_RECOMP_MINMAX = 1 +DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INTERRUPT_STATUS_CHG_MASK' +AFMT_INTERRUPT_STATUS_CHG_MASK__enumvalues = { + 0: 'AFMT_INTERRUPT_DISABLE', + 1: 'AFMT_INTERRUPT_ENABLE', +} +AFMT_INTERRUPT_DISABLE = 0 +AFMT_INTERRUPT_ENABLE = 1 +AFMT_INTERRUPT_STATUS_CHG_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE' +HDMI_GC_AVMUTE__enumvalues = { + 0: 'HDMI_GC_AVMUTE_SET', + 1: 'HDMI_GC_AVMUTE_UNSET', +} +HDMI_GC_AVMUTE_SET = 0 +HDMI_GC_AVMUTE_UNSET = 1 +HDMI_GC_AVMUTE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEFAULT_PAHSE' +HDMI_DEFAULT_PAHSE__enumvalues = { + 0: 'HDMI_DEFAULT_PHASE_IS_0', + 1: 'HDMI_DEFAULT_PHASE_IS_1', +} +HDMI_DEFAULT_PHASE_IS_0 = 0 +HDMI_DEFAULT_PHASE_IS_1 = 1 +HDMI_DEFAULT_PAHSE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD' +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD__enumvalues = { + 0: 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 1: 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', +} +AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS = 0 +AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER = 1 +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD = ctypes.c_uint32 # enum + +# values for enumeration 'AUDIO_LAYOUT_SELECT' +AUDIO_LAYOUT_SELECT__enumvalues = { + 0: 'AUDIO_LAYOUT_0', + 1: 'AUDIO_LAYOUT_1', +} +AUDIO_LAYOUT_0 = 0 +AUDIO_LAYOUT_1 = 1 +AUDIO_LAYOUT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CONT' +AFMT_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'AFMT_AUDIO_CRC_ONESHOT', + 1: 'AFMT_AUDIO_CRC_AUTO_RESTART', +} +AFMT_AUDIO_CRC_ONESHOT = 0 +AFMT_AUDIO_CRC_AUTO_RESTART = 1 +AFMT_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_SOURCE' +AFMT_AUDIO_CRC_CONTROL_SOURCE__enumvalues = { + 0: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 1: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', +} +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT = 0 +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT = 1 +AFMT_AUDIO_CRC_CONTROL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CH_SEL' +AFMT_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'AFMT_AUDIO_CRC_CH0_SIG', + 1: 'AFMT_AUDIO_CRC_CH1_SIG', + 2: 'AFMT_AUDIO_CRC_CH2_SIG', + 3: 'AFMT_AUDIO_CRC_CH3_SIG', + 4: 'AFMT_AUDIO_CRC_CH4_SIG', + 5: 'AFMT_AUDIO_CRC_CH5_SIG', + 6: 'AFMT_AUDIO_CRC_CH6_SIG', + 7: 'AFMT_AUDIO_CRC_CH7_SIG', + 8: 'AFMT_AUDIO_CRC_RESERVED_8', + 9: 'AFMT_AUDIO_CRC_RESERVED_9', + 10: 'AFMT_AUDIO_CRC_RESERVED_10', + 11: 'AFMT_AUDIO_CRC_RESERVED_11', + 12: 'AFMT_AUDIO_CRC_RESERVED_12', + 13: 'AFMT_AUDIO_CRC_RESERVED_13', + 14: 'AFMT_AUDIO_CRC_RESERVED_14', + 15: 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', +} +AFMT_AUDIO_CRC_CH0_SIG = 0 +AFMT_AUDIO_CRC_CH1_SIG = 1 +AFMT_AUDIO_CRC_CH2_SIG = 2 +AFMT_AUDIO_CRC_CH3_SIG = 3 +AFMT_AUDIO_CRC_CH4_SIG = 4 +AFMT_AUDIO_CRC_CH5_SIG = 5 +AFMT_AUDIO_CRC_CH6_SIG = 6 +AFMT_AUDIO_CRC_CH7_SIG = 7 +AFMT_AUDIO_CRC_RESERVED_8 = 8 +AFMT_AUDIO_CRC_RESERVED_9 = 9 +AFMT_AUDIO_CRC_RESERVED_10 = 10 +AFMT_AUDIO_CRC_RESERVED_11 = 11 +AFMT_AUDIO_CRC_RESERVED_12 = 12 +AFMT_AUDIO_CRC_RESERVED_13 = 13 +AFMT_AUDIO_CRC_RESERVED_14 = 14 +AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT = 15 +AFMT_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_RAMP_CONTROL0_SIGN' +AFMT_RAMP_CONTROL0_SIGN__enumvalues = { + 0: 'AFMT_RAMP_SIGNED', + 1: 'AFMT_RAMP_UNSIGNED', +} +AFMT_RAMP_SIGNED = 0 +AFMT_RAMP_UNSIGNED = 1 +AFMT_RAMP_CONTROL0_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND' +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND__enumvalues = { + 0: 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 1: 'AFMT_AUDIO_PACKET_SENT_ENABLED', +} +AFMT_AUDIO_PACKET_SENT_DISABLED = 0 +AFMT_AUDIO_PACKET_SENT_ENABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS' +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS__enumvalues = { + 0: 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 1: 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', +} +AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED = 0 +AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE' +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 1: 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK = 0 +AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_SRC_CONTROL_SELECT' +AFMT_AUDIO_SRC_CONTROL_SELECT__enumvalues = { + 0: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 1: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 2: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 3: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 4: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 5: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', + 6: 'AFMT_AUDIO_SRC_RESERVED', +} +AFMT_AUDIO_SRC_FROM_AZ_STREAM0 = 0 +AFMT_AUDIO_SRC_FROM_AZ_STREAM1 = 1 +AFMT_AUDIO_SRC_FROM_AZ_STREAM2 = 2 +AFMT_AUDIO_SRC_FROM_AZ_STREAM3 = 3 +AFMT_AUDIO_SRC_FROM_AZ_STREAM4 = 4 +AFMT_AUDIO_SRC_FROM_AZ_STREAM5 = 5 +AFMT_AUDIO_SRC_RESERVED = 6 +AFMT_AUDIO_SRC_CONTROL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_MODE' +DIG_BE_CNTL_MODE__enumvalues = { + 0: 'DIG_BE_DP_SST_MODE', + 1: 'DIG_BE_RESERVED1', + 2: 'DIG_BE_TMDS_DVI_MODE', + 3: 'DIG_BE_TMDS_HDMI_MODE', + 4: 'DIG_BE_RESERVED4', + 5: 'DIG_BE_DP_MST_MODE', + 6: 'DIG_BE_RESERVED2', + 7: 'DIG_BE_RESERVED3', +} +DIG_BE_DP_SST_MODE = 0 +DIG_BE_RESERVED1 = 1 +DIG_BE_TMDS_DVI_MODE = 2 +DIG_BE_TMDS_HDMI_MODE = 3 +DIG_BE_RESERVED4 = 4 +DIG_BE_DP_MST_MODE = 5 +DIG_BE_RESERVED2 = 6 +DIG_BE_RESERVED3 = 7 +DIG_BE_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_HPD_SELECT' +DIG_BE_CNTL_HPD_SELECT__enumvalues = { + 0: 'DIG_BE_CNTL_HPD1', + 1: 'DIG_BE_CNTL_HPD2', + 2: 'DIG_BE_CNTL_HPD3', + 3: 'DIG_BE_CNTL_HPD4', + 4: 'DIG_BE_CNTL_HPD5', + 5: 'DIG_BE_CNTL_HPD6', + 6: 'DIG_BE_CNTL_NO_HPD', +} +DIG_BE_CNTL_HPD1 = 0 +DIG_BE_CNTL_HPD2 = 1 +DIG_BE_CNTL_HPD3 = 2 +DIG_BE_CNTL_HPD4 = 3 +DIG_BE_CNTL_HPD5 = 4 +DIG_BE_CNTL_HPD6 = 5 +DIG_BE_CNTL_NO_HPD = 6 +DIG_BE_CNTL_HPD_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT' +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 1: 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', +} +LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS = 0 +LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH = 1 +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_SYNC_PHASE' +TMDS_SYNC_PHASE__enumvalues = { + 0: 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 1: 'TMDS_SYNC_PHASE_ON_FRAME_START', +} +TMDS_NOT_SYNC_PHASE_ON_FRAME_START = 0 +TMDS_SYNC_PHASE_ON_FRAME_START = 1 +TMDS_SYNC_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL' +TMDS_DATA_SYNCHRONIZATION_DSINTSEL__enumvalues = { + 0: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 1: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', +} +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS = 0 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL = 1 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 1: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 2: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 3: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', +} +TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE = 0 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON = 1 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON = 2 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE = 3 +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA' +TMDS_TRANSMITTER_CONTROL_IDSCKSELA__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB' +TMDS_TRANSMITTER_CONTROL_IDSCKSELB__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN' +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 1: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', +} +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE = 0 +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE = 1 +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 1: 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', +} +TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD = 0 +TMDS_TRANSMITTER_PLL_RST_ON_HPD = 1 +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 1: 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK = 0 +TMDS_TRANSMITTER_TMCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 1: 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK = 0 +TMDS_TRANSMITTER_TDCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN' +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 1: 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', +} +TMDS_TRANSMITTER_PLLSEL_BY_HW = 0 +TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW = 1 +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTA_CNTLA' +TMDS_REG_TEST_OUTPUTA_CNTLA__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 1: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 2: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 3: 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', +} +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0 = 0 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1 = 1 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2 = 2 +TMDS_REG_TEST_OUTPUTA_CNTLA_NA = 3 +TMDS_REG_TEST_OUTPUTA_CNTLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTB_CNTLB' +TMDS_REG_TEST_OUTPUTB_CNTLB__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 1: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 2: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', + 3: 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', +} +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0 = 0 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1 = 1 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2 = 2 +TMDS_REG_TEST_OUTPUTB_CNTLB_NA = 3 +TMDS_REG_TEST_OUTPUTB_CNTLB = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_VBI_GSP_INDEX' +AFMT_VBI_GSP_INDEX__enumvalues = { + 0: 'AFMT_VBI_GSP0_INDEX', + 1: 'AFMT_VBI_GSP1_INDEX', + 2: 'AFMT_VBI_GSP2_INDEX', + 3: 'AFMT_VBI_GSP3_INDEX', + 4: 'AFMT_VBI_GSP4_INDEX', + 5: 'AFMT_VBI_GSP5_INDEX', + 6: 'AFMT_VBI_GSP6_INDEX', + 7: 'AFMT_VBI_GSP7_INDEX', + 8: 'AFMT_VBI_GSP8_INDEX', + 9: 'AFMT_VBI_GSP9_INDEX', + 10: 'AFMT_VBI_GSP10_INDEX', +} +AFMT_VBI_GSP0_INDEX = 0 +AFMT_VBI_GSP1_INDEX = 1 +AFMT_VBI_GSP2_INDEX = 2 +AFMT_VBI_GSP3_INDEX = 3 +AFMT_VBI_GSP4_INDEX = 4 +AFMT_VBI_GSP5_INDEX = 5 +AFMT_VBI_GSP6_INDEX = 6 +AFMT_VBI_GSP7_INDEX = 7 +AFMT_VBI_GSP8_INDEX = 8 +AFMT_VBI_GSP9_INDEX = 9 +AFMT_VBI_GSP10_INDEX = 10 +AFMT_VBI_GSP_INDEX = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_DIGITAL_BYPASS_SEL' +DIG_DIGITAL_BYPASS_SEL__enumvalues = { + 0: 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 1: 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 2: 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 3: 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 4: 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 5: 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 6: 'DIG_DIGITAL_BYPASS_SEL_ALPHA', +} +DIG_DIGITAL_BYPASS_SEL_BYPASS = 0 +DIG_DIGITAL_BYPASS_SEL_36BPP = 1 +DIG_DIGITAL_BYPASS_SEL_48BPP_LSB = 2 +DIG_DIGITAL_BYPASS_SEL_48BPP_MSB = 3 +DIG_DIGITAL_BYPASS_SEL_10BPP_LSB = 4 +DIG_DIGITAL_BYPASS_SEL_12BPC_LSB = 5 +DIG_DIGITAL_BYPASS_SEL_ALPHA = 6 +DIG_DIGITAL_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_INPUT_PIXEL_SEL' +DIG_INPUT_PIXEL_SEL__enumvalues = { + 0: 'DIG_ALL_PIXEL', + 1: 'DIG_EVEN_PIXEL_ONLY', + 2: 'DIG_ODD_PIXEL_ONLY', +} +DIG_ALL_PIXEL = 0 +DIG_EVEN_PIXEL_ONLY = 1 +DIG_ODD_PIXEL_ONLY = 2 +DIG_INPUT_PIXEL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOLBY_VISION_ENABLE' +DOLBY_VISION_ENABLE__enumvalues = { + 0: 'DOLBY_VISION_ENABLED', + 1: 'DOLBY_VISION_DISABLED', +} +DOLBY_VISION_ENABLED = 0 +DOLBY_VISION_DISABLED = 1 +DOLBY_VISION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_HUBP_SEL' +METADATA_HUBP_SEL__enumvalues = { + 0: 'METADATA_HUBP_SEL_0', + 1: 'METADATA_HUBP_SEL_1', + 2: 'METADATA_HUBP_SEL_2', + 3: 'METADATA_HUBP_SEL_3', + 4: 'METADATA_HUBP_SEL_4', + 5: 'METADATA_HUBP_SEL_5', + 6: 'METADATA_HUBP_SEL_RESERVED', +} +METADATA_HUBP_SEL_0 = 0 +METADATA_HUBP_SEL_1 = 1 +METADATA_HUBP_SEL_2 = 2 +METADATA_HUBP_SEL_3 = 3 +METADATA_HUBP_SEL_4 = 4 +METADATA_HUBP_SEL_5 = 5 +METADATA_HUBP_SEL_RESERVED = 6 +METADATA_HUBP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_STREAM_TYPE_SEL' +METADATA_STREAM_TYPE_SEL__enumvalues = { + 0: 'METADATA_STREAM_DP', + 1: 'METADATA_STREAM_DVE', +} +METADATA_STREAM_DP = 0 +METADATA_STREAM_DVE = 1 +METADATA_STREAM_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_METADATA_ENABLE' +HDMI_METADATA_ENABLE__enumvalues = { + 0: 'HDMI_METADATA_NOT_SEND', + 1: 'HDMI_METADATA_PKT_SEND', +} +HDMI_METADATA_NOT_SEND = 0 +HDMI_METADATA_PKT_SEND = 1 +HDMI_METADATA_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_LINE_REFERENCE' +HDMI_PACKET_LINE_REFERENCE__enumvalues = { + 0: 'HDMI_PKT_LINE_REF_VSYNC', + 1: 'HDMI_PKT_LINE_REF_OTGSOF', +} +HDMI_PKT_LINE_REF_VSYNC = 0 +HDMI_PKT_LINE_REF_OTGSOF = 1 +HDMI_PACKET_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_HPD_SEL' +DP_AUX_CONTROL_HPD_SEL__enumvalues = { + 0: 'DP_AUX_CONTROL_HPD1_SELECTED', + 1: 'DP_AUX_CONTROL_HPD2_SELECTED', + 2: 'DP_AUX_CONTROL_HPD3_SELECTED', + 3: 'DP_AUX_CONTROL_HPD4_SELECTED', + 4: 'DP_AUX_CONTROL_HPD5_SELECTED', + 5: 'DP_AUX_CONTROL_HPD6_SELECTED', + 6: 'DP_AUX_CONTROL_NO_HPD_SELECTED', +} +DP_AUX_CONTROL_HPD1_SELECTED = 0 +DP_AUX_CONTROL_HPD2_SELECTED = 1 +DP_AUX_CONTROL_HPD3_SELECTED = 2 +DP_AUX_CONTROL_HPD4_SELECTED = 3 +DP_AUX_CONTROL_HPD5_SELECTED = 4 +DP_AUX_CONTROL_HPD6_SELECTED = 5 +DP_AUX_CONTROL_NO_HPD_SELECTED = 6 +DP_AUX_CONTROL_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_TEST_MODE' +DP_AUX_CONTROL_TEST_MODE__enumvalues = { + 0: 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 1: 'DP_AUX_CONTROL_TEST_MODE_ENABLE', +} +DP_AUX_CONTROL_TEST_MODE_DISABLE = 0 +DP_AUX_CONTROL_TEST_MODE_ENABLE = 1 +DP_AUX_CONTROL_TEST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_SW_GO' +DP_AUX_SW_CONTROL_SW_GO__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 1: 'DP_AUX_SW_CONTROL_SW__GO', +} +DP_AUX_SW_CONTROL_SW__NOT_GO = 0 +DP_AUX_SW_CONTROL_SW__GO = 1 +DP_AUX_SW_CONTROL_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_LS_READ_TRIG' +DP_AUX_SW_CONTROL_LS_READ_TRIG__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 1: 'DP_AUX_SW_CONTROL_LS_READ__TRIG', +} +DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG = 0 +DP_AUX_SW_CONTROL_LS_READ__TRIG = 1 +DP_AUX_SW_CONTROL_LS_READ_TRIG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_ARB_PRIORITY' +DP_AUX_ARB_CONTROL_ARB_PRIORITY__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 1: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 2: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 3: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', +} +DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW = 0 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW = 1 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC = 2 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS = 3 +DP_AUX_ARB_CONTROL_ARB_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ' +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 1: 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', +} +DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ = 0 +DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ = 1 +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG' +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 1: 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', +} +DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG = 0 +DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG = 1 +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_INT_ACK' +DP_AUX_INT_ACK__enumvalues = { + 0: 'DP_AUX_INT__NOT_ACK', + 1: 'DP_AUX_INT__ACK', +} +DP_AUX_INT__NOT_ACK = 0 +DP_AUX_INT__ACK = 1 +DP_AUX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_LS_UPDATE_ACK' +DP_AUX_LS_UPDATE_ACK__enumvalues = { + 0: 'DP_AUX_INT_LS_UPDATE_NOT_ACK', + 1: 'DP_AUX_INT_LS_UPDATE_ACK', +} +DP_AUX_INT_LS_UPDATE_NOT_ACK = 0 +DP_AUX_INT_LS_UPDATE_ACK = 1 +DP_AUX_LS_UPDATE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL' +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE' +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 2: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 3: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ = 2 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ = 3 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY' +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__enumvalues = { + 0: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 1: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 2: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 3: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 4: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 5: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', +} +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0 = 0 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US = 1 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US = 2 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US = 3 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US = 4 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US = 5 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW' +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW' +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 1: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 2: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 3: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', +} +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES = 0 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES = 1 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES = 2 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED = 3 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 1: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 2: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 3: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', +} +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS = 0 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS = 1 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS = 2 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS = 3 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RX_TIMEOUT_LEN_MUL' +DP_AUX_RX_TIMEOUT_LEN_MUL__enumvalues = { + 0: 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 1: 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', + 2: 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 3: 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', +} +DP_AUX_RX_TIMEOUT_LEN_NO_MUL = 0 +DP_AUX_RX_TIMEOUT_LEN_MUL_2 = 1 +DP_AUX_RX_TIMEOUT_LEN_MUL_4 = 2 +DP_AUX_RX_TIMEOUT_LEN_MUL_8 = 3 +DP_AUX_RX_TIMEOUT_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_TX_PRECHARGE_LEN_MUL' +DP_AUX_TX_PRECHARGE_LEN_MUL__enumvalues = { + 0: 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', + 1: 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 2: 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', + 3: 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', +} +DP_AUX_TX_PRECHARGE_LEN_NO_MUL = 0 +DP_AUX_TX_PRECHARGE_LEN_MUL_2 = 1 +DP_AUX_TX_PRECHARGE_LEN_MUL_4 = 2 +DP_AUX_TX_PRECHARGE_LEN_MUL_8 = 3 +DP_AUX_TX_PRECHARGE_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD' +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__enumvalues = { + 0: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 1: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 2: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 3: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 4: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 5: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 6: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 7: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', +} +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2 = 0 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4 = 1 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8 = 2 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16 = 3 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32 = 4 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64 = 5 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128 = 6 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256 = 7 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ' +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 1: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', +} +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX = 0 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX = 1 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW' +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 1: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 2: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 3: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', +} +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US = 0 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US = 1 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US = 2 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US = 3 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT' +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 1: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 2: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 3: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', +} +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS = 0 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS = 1 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS = 2 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED = 3 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN' +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 1: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 2: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 3: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', +} +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0 = 0 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64 = 1 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128 = 2 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256 = 3 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ERR_OCCURRED_ACK' +DP_AUX_ERR_OCCURRED_ACK__enumvalues = { + 0: 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 1: 'DP_AUX_ERR_OCCURRED__ACK', +} +DP_AUX_ERR_OCCURRED__NOT_ACK = 0 +DP_AUX_ERR_OCCURRED__ACK = 1 +DP_AUX_ERR_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_POTENTIAL_ERR_REACHED_ACK' +DP_AUX_POTENTIAL_ERR_REACHED_ACK__enumvalues = { + 0: 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', + 1: 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', +} +DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK = 0 +DP_AUX_POTENTIAL_ERR_REACHED__ACK = 1 +DP_AUX_POTENTIAL_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DEFINITE_ERR_REACHED_ACK' +DP_AUX_DEFINITE_ERR_REACHED_ACK__enumvalues = { + 0: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', + 1: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', +} +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK = 0 +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK = 1 +DP_AUX_DEFINITE_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET' +DP_AUX_RESET__enumvalues = { + 0: 'DP_AUX_RESET_DEASSERTED', + 1: 'DP_AUX_RESET_ASSERTED', +} +DP_AUX_RESET_DEASSERTED = 0 +DP_AUX_RESET_ASSERTED = 1 +DP_AUX_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET_DONE' +DP_AUX_RESET_DONE__enumvalues = { + 0: 'DP_AUX_RESET_SEQUENCE_NOT_DONE', + 1: 'DP_AUX_RESET_SEQUENCE_DONE', +} +DP_AUX_RESET_SEQUENCE_NOT_DONE = 0 +DP_AUX_RESET_SEQUENCE_DONE = 1 +DP_AUX_RESET_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_PHY_WAKE_PRIORITY' +DP_AUX_PHY_WAKE_PRIORITY__enumvalues = { + 0: 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', + 1: 'DP_AUX_PHY_WAKE_LOW_PRIORITY', +} +DP_AUX_PHY_WAKE_HIGH_PRIORITY = 0 +DP_AUX_PHY_WAKE_LOW_PRIORITY = 1 +DP_AUX_PHY_WAKE_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_GO' +DOUT_I2C_CONTROL_GO__enumvalues = { + 0: 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 1: 'DOUT_I2C_CONTROL_START_TRANSFER', +} +DOUT_I2C_CONTROL_STOP_TRANSFER = 0 +DOUT_I2C_CONTROL_START_TRANSFER = 1 +DOUT_I2C_CONTROL_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SOFT_RESET' +DOUT_I2C_CONTROL_SOFT_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 1: 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', +} +DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER = 0 +DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER = 1 +DOUT_I2C_CONTROL_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET' +DOUT_I2C_CONTROL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 1: 'DOUT_I2C_CONTROL__SEND_RESET', +} +DOUT_I2C_CONTROL__NOT_SEND_RESET = 0 +DOUT_I2C_CONTROL__SEND_RESET = 1 +DOUT_I2C_CONTROL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH' +DOUT_I2C_CONTROL_SEND_RESET_LENGTH__enumvalues = { + 0: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 1: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', +} +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9 = 0 +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10 = 1 +DOUT_I2C_CONTROL_SEND_RESET_LENGTH = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SW_STATUS_RESET' +DOUT_I2C_CONTROL_SW_STATUS_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 1: 'DOUT_I2C_CONTROL_RESET_SW_STATUS', +} +DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS = 0 +DOUT_I2C_CONTROL_RESET_SW_STATUS = 1 +DOUT_I2C_CONTROL_SW_STATUS_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DDC_SELECT' +DOUT_I2C_CONTROL_DDC_SELECT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_SELECT_DDC1', + 1: 'DOUT_I2C_CONTROL_SELECT_DDC2', + 2: 'DOUT_I2C_CONTROL_SELECT_DDC3', + 3: 'DOUT_I2C_CONTROL_SELECT_DDC4', + 4: 'DOUT_I2C_CONTROL_SELECT_DDC5', + 5: 'DOUT_I2C_CONTROL_SELECT_DDC6', + 6: 'DOUT_I2C_CONTROL_SELECT_DDCVGA', +} +DOUT_I2C_CONTROL_SELECT_DDC1 = 0 +DOUT_I2C_CONTROL_SELECT_DDC2 = 1 +DOUT_I2C_CONTROL_SELECT_DDC3 = 2 +DOUT_I2C_CONTROL_SELECT_DDC4 = 3 +DOUT_I2C_CONTROL_SELECT_DDC5 = 4 +DOUT_I2C_CONTROL_SELECT_DDC6 = 5 +DOUT_I2C_CONTROL_SELECT_DDCVGA = 6 +DOUT_I2C_CONTROL_DDC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_TRANSACTION_COUNT' +DOUT_I2C_CONTROL_TRANSACTION_COUNT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_TRANS0', + 1: 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 2: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 3: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', +} +DOUT_I2C_CONTROL_TRANS0 = 0 +DOUT_I2C_CONTROL_TRANS0_TRANS1 = 1 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2 = 2 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3 = 3 +DOUT_I2C_CONTROL_TRANSACTION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_SW_PRIORITY' +DOUT_I2C_ARBITRATION_SW_PRIORITY__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 1: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 2: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 3: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', +} +DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL = 0 +DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH = 1 +DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED = 2 +DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED = 3 +DOUT_I2C_ARBITRATION_SW_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO' +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 1: 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', +} +DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED = 0 +DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED = 1 +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_ABORT_XFER' +DOUT_I2C_ARBITRATION_ABORT_XFER__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 1: 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', +} +DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER = 0 +DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER = 1 +DOUT_I2C_ARBITRATION_ABORT_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ' +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 1: 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', +} +DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ = 0 +DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ = 1 +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG' +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 1: 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', +} +DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG = 0 +DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG = 1 +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ACK' +DOUT_I2C_ACK__enumvalues = { + 0: 'DOUT_I2C_NO_ACK', + 1: 'DOUT_I2C_ACK_TO_CLEAN', +} +DOUT_I2C_NO_ACK = 0 +DOUT_I2C_ACK_TO_CLEAN = 1 +DOUT_I2C_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SPEED_THRESHOLD' +DOUT_I2C_DDC_SPEED_THRESHOLD__enumvalues = { + 0: 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 1: 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 2: 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 3: 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', +} +DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO = 0 +DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE = 1 +DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE = 2 +DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE = 3 +DOUT_I2C_DDC_SPEED_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 1: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS = 0 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE' +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 1: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', +} +DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT = 0 +DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT = 1 +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_EDID_DETECT_STATUS' +DOUT_I2C_DDC_EDID_DETECT_STATUS__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_EDID_CONNECT_DETECTED', + 1: 'DOUT_I2C_DDC_SETUP_EDID_DISCONNECT_DETECTED', +} +DOUT_I2C_DDC_SETUP_EDID_CONNECT_DETECTED = 0 +DOUT_I2C_DDC_SETUP_EDID_DISCONNECT_DETECTED = 1 +DOUT_I2C_DDC_EDID_DETECT_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN' +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', +} +DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL = 1 +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_TRANSACTION_STOP_ON_NACK' +DOUT_I2C_TRANSACTION_STOP_ON_NACK__enumvalues = { + 0: 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 1: 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', +} +DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS = 0 +DOUT_I2C_TRANSACTION_STOP_ALL_TRANS = 1 +DOUT_I2C_TRANSACTION_STOP_ON_NACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DATA_INDEX_WRITE' +DOUT_I2C_DATA_INDEX_WRITE__enumvalues = { + 0: 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 1: 'DOUT_I2C_DATA__INDEX_WRITE', +} +DOUT_I2C_DATA__NOT_INDEX_WRITE = 0 +DOUT_I2C_DATA__INDEX_WRITE = 1 +DOUT_I2C_DATA_INDEX_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET' +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 1: 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', +} +DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION = 0 +DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION = 1 +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE' +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__enumvalues = { + 0: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 1: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', +} +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL = 0 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE = 1 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL' +DIOMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQUEST', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', +} +DIOMEM_NO_FORCE_REQUEST = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DIOMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +DIOMEM_FORCE_SHUT_DOWN_REQUEST = 3 +DIOMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL2' +DIOMEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQ', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', +} +DIOMEM_NO_FORCE_REQ = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQ = 1 +DIOMEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_DIS_CTRL' +DIOMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 1: 'DIOMEM_DISABLE_MEM_PWR_CTRL', +} +DIOMEM_ENABLE_MEM_PWR_CTRL = 0 +DIOMEM_DISABLE_MEM_PWR_CTRL = 1 +DIOMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_EN' +CLOCK_GATING_EN__enumvalues = { + 0: 'CLOCK_GATING_ENABLE', + 1: 'CLOCK_GATING_DISABLE', +} +CLOCK_GATING_ENABLE = 0 +CLOCK_GATING_DISABLE = 1 +CLOCK_GATING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL' +DIOMEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE = 0 +DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +DIOMEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL2' +DIOMEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 1: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', +} +DIOMEM_DYNAMIC_DEEP_SLEEP_EN = 0 +DIOMEM_DYNAMIC_LIGHT_SLEEP_EN = 1 +DIOMEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'PM_ASSERT_RESET' +PM_ASSERT_RESET__enumvalues = { + 0: 'PM_ASSERT_RESET_0', + 1: 'PM_ASSERT_RESET_1', +} +PM_ASSERT_RESET_0 = 0 +PM_ASSERT_RESET_1 = 1 +PM_ASSERT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DAC_MUX_SELECT' +DAC_MUX_SELECT__enumvalues = { + 0: 'DAC_MUX_SELECT_DACA', + 1: 'DAC_MUX_SELECT_DACB', +} +DAC_MUX_SELECT_DACA = 0 +DAC_MUX_SELECT_DACB = 1 +DAC_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_MUX_SELECT' +TMDS_MUX_SELECT__enumvalues = { + 0: 'TMDS_MUX_SELECT_B', + 1: 'TMDS_MUX_SELECT_G', + 2: 'TMDS_MUX_SELECT_R', + 3: 'TMDS_MUX_SELECT_RESERVED', +} +TMDS_MUX_SELECT_B = 0 +TMDS_MUX_SELECT_G = 1 +TMDS_MUX_SELECT_R = 2 +TMDS_MUX_SELECT_RESERVED = 3 +TMDS_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SOFT_RESET' +SOFT_RESET__enumvalues = { + 0: 'SOFT_RESET_0', + 1: 'SOFT_RESET_1', +} +SOFT_RESET_0 = 0 +SOFT_RESET_1 = 1 +SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_STEREOSYNC_SEL' +GENERIC_STEREOSYNC_SEL__enumvalues = { + 0: 'GENERIC_STEREOSYNC_SEL_D1', + 1: 'GENERIC_STEREOSYNC_SEL_D2', + 2: 'GENERIC_STEREOSYNC_SEL_D3', + 3: 'GENERIC_STEREOSYNC_SEL_D4', + 4: 'GENERIC_STEREOSYNC_SEL_D5', + 5: 'GENERIC_STEREOSYNC_SEL_D6', + 6: 'GENERIC_STEREOSYNC_SEL_RESERVED', +} +GENERIC_STEREOSYNC_SEL_D1 = 0 +GENERIC_STEREOSYNC_SEL_D2 = 1 +GENERIC_STEREOSYNC_SEL_D3 = 2 +GENERIC_STEREOSYNC_SEL_D4 = 3 +GENERIC_STEREOSYNC_SEL_D5 = 4 +GENERIC_STEREOSYNC_SEL_D6 = 5 +GENERIC_STEREOSYNC_SEL_RESERVED = 6 +GENERIC_STEREOSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE' +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE__enumvalues = { + 0: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 1: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', +} +DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL = 0 +DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE = 1 +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE' +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE__enumvalues = { + 0: 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0', + 1: 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1', +} +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0 = 0 +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1 = 1 +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICA_SEL' +DCIO_DC_GENERICA_SEL__enumvalues = { + 0: 'DCIO_GENERICA_SEL_DACA_STEREOSYNC', + 1: 'DCIO_GENERICA_SEL_STEREOSYNC', + 2: 'DCIO_GENERICA_SEL_DACA_PIXCLK', + 3: 'DCIO_GENERICA_SEL_DACB_PIXCLK', + 4: 'DCIO_GENERICA_SEL_DVOA_CTL3', + 5: 'DCIO_GENERICA_SEL_P1_PLLCLK', + 6: 'DCIO_GENERICA_SEL_P2_PLLCLK', + 7: 'DCIO_GENERICA_SEL_DVOA_STEREOSYNC', + 8: 'DCIO_GENERICA_SEL_DACA_FIELD_NUMBER', + 9: 'DCIO_GENERICA_SEL_DACB_FIELD_NUMBER', + 10: 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 11: 'DCIO_GENERICA_SEL_SYNCEN', + 12: 'DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK', + 13: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK', + 14: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK', + 15: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2', + 16: 'DCIO_GENERICA_SEL_GENERICA_DPRX', + 17: 'DCIO_GENERICA_SEL_GENERICB_DPRX', +} +DCIO_GENERICA_SEL_DACA_STEREOSYNC = 0 +DCIO_GENERICA_SEL_STEREOSYNC = 1 +DCIO_GENERICA_SEL_DACA_PIXCLK = 2 +DCIO_GENERICA_SEL_DACB_PIXCLK = 3 +DCIO_GENERICA_SEL_DVOA_CTL3 = 4 +DCIO_GENERICA_SEL_P1_PLLCLK = 5 +DCIO_GENERICA_SEL_P2_PLLCLK = 6 +DCIO_GENERICA_SEL_DVOA_STEREOSYNC = 7 +DCIO_GENERICA_SEL_DACA_FIELD_NUMBER = 8 +DCIO_GENERICA_SEL_DACB_FIELD_NUMBER = 9 +DCIO_GENERICA_SEL_GENERICA_DCCG = 10 +DCIO_GENERICA_SEL_SYNCEN = 11 +DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK = 12 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK = 13 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK = 14 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2 = 15 +DCIO_GENERICA_SEL_GENERICA_DPRX = 16 +DCIO_GENERICA_SEL_GENERICB_DPRX = 17 +DCIO_DC_GENERICA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_REFDIV_CLK', + 1: 'DCIO_UNIPHYB_TEST_REFDIV_CLK', + 2: 'DCIO_UNIPHYC_TEST_REFDIV_CLK', + 3: 'DCIO_UNIPHYD_TEST_REFDIV_CLK', + 4: 'DCIO_UNIPHYE_TEST_REFDIV_CLK', + 5: 'DCIO_UNIPHYF_TEST_REFDIV_CLK', + 6: 'DCIO_UNIPHYG_TEST_REFDIV_CLK', +} +DCIO_UNIPHYA_TEST_REFDIV_CLK = 0 +DCIO_UNIPHYB_TEST_REFDIV_CLK = 1 +DCIO_UNIPHYC_TEST_REFDIV_CLK = 2 +DCIO_UNIPHYD_TEST_REFDIV_CLK = 3 +DCIO_UNIPHYE_TEST_REFDIV_CLK = 4 +DCIO_UNIPHYF_TEST_REFDIV_CLK = 5 +DCIO_UNIPHYG_TEST_REFDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_CLK', +} +DCIO_UNIPHYA_FBDIV_CLK = 0 +DCIO_UNIPHYB_FBDIV_CLK = 1 +DCIO_UNIPHYC_FBDIV_CLK = 2 +DCIO_UNIPHYD_FBDIV_CLK = 3 +DCIO_UNIPHYE_FBDIV_CLK = 4 +DCIO_UNIPHYF_FBDIV_CLK = 5 +DCIO_UNIPHYG_FBDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_SSC_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_SSC_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_SSC_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_SSC_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_SSC_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_SSC_CLK', +} +DCIO_UNIPHYA_FBDIV_SSC_CLK = 0 +DCIO_UNIPHYB_FBDIV_SSC_CLK = 1 +DCIO_UNIPHYC_FBDIV_SSC_CLK = 2 +DCIO_UNIPHYD_FBDIV_SSC_CLK = 3 +DCIO_UNIPHYE_FBDIV_SSC_CLK = 4 +DCIO_UNIPHYF_FBDIV_SSC_CLK = 5 +DCIO_UNIPHYG_FBDIV_SSC_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 1: 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 2: 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 3: 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 4: 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 5: 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 6: 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', +} +DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2 = 0 +DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2 = 1 +DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2 = 2 +DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2 = 3 +DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2 = 4 +DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2 = 5 +DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2 = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICB_SEL' +DCIO_DC_GENERICB_SEL__enumvalues = { + 0: 'DCIO_GENERICB_SEL_DACA_STEREOSYNC', + 1: 'DCIO_GENERICB_SEL_STEREOSYNC', + 2: 'DCIO_GENERICB_SEL_DACA_PIXCLK', + 3: 'DCIO_GENERICB_SEL_DACB_PIXCLK', + 4: 'DCIO_GENERICB_SEL_DVOA_CTL3', + 5: 'DCIO_GENERICB_SEL_P1_PLLCLK', + 6: 'DCIO_GENERICB_SEL_P2_PLLCLK', + 7: 'DCIO_GENERICB_SEL_DVOA_STEREOSYNC', + 8: 'DCIO_GENERICB_SEL_DACA_FIELD_NUMBER', + 9: 'DCIO_GENERICB_SEL_DACB_FIELD_NUMBER', + 10: 'DCIO_GENERICB_SEL_GENERICB_DCCG', + 11: 'DCIO_GENERICB_SEL_SYNCEN', + 12: 'DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK', + 13: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK', + 14: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK', + 15: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2', +} +DCIO_GENERICB_SEL_DACA_STEREOSYNC = 0 +DCIO_GENERICB_SEL_STEREOSYNC = 1 +DCIO_GENERICB_SEL_DACA_PIXCLK = 2 +DCIO_GENERICB_SEL_DACB_PIXCLK = 3 +DCIO_GENERICB_SEL_DVOA_CTL3 = 4 +DCIO_GENERICB_SEL_P1_PLLCLK = 5 +DCIO_GENERICB_SEL_P2_PLLCLK = 6 +DCIO_GENERICB_SEL_DVOA_STEREOSYNC = 7 +DCIO_GENERICB_SEL_DACA_FIELD_NUMBER = 8 +DCIO_GENERICB_SEL_DACB_FIELD_NUMBER = 9 +DCIO_GENERICB_SEL_GENERICB_DCCG = 10 +DCIO_GENERICB_SEL_SYNCEN = 11 +DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK = 12 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK = 13 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK = 14 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2 = 15 +DCIO_DC_GENERICB_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', + 1: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', + 2: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', + 3: 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', +} +DCIO_HSYNCA_OUTPUT_SEL_DISABLE = 0 +DCIO_HSYNCA_OUTPUT_SEL_PPLL1 = 1 +DCIO_HSYNCA_OUTPUT_SEL_PPLL2 = 2 +DCIO_HSYNCA_OUTPUT_SEL_RESERVED = 3 +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 1: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 2: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 3: 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', +} +DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE = 0 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1 = 1 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2 = 2 +DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3 = 3 +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION' +DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION__enumvalues = { + 0: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS', + 1: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS', + 2: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS', + 3: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS', + 4: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS', + 5: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS', + 6: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS', + 7: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS', +} +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS = 0 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS = 1 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS = 2 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS = 3 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS = 4 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS = 5 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS = 6 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS = 7 +DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT' +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 1: 'DCIO_UNIPHY_CHANNEL_INVERTED', +} +DCIO_UNIPHY_CHANNEL_NO_INVERSION = 0 +DCIO_UNIPHY_CHANNEL_INVERTED = 1 +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK' +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK__enumvalues = { + 0: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 1: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 2: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 3: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', +} +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW = 0 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW = 1 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED = 2 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED = 3 +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE' +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 1: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 2: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 3: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', +} +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0 = 0 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1 = 1 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2 = 2 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3 = 3 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN' +DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN__enumvalues = { + 0: 'DCIO_VIP_MUX_EN_DVO', + 1: 'DCIO_VIP_MUX_EN_VIP', +} +DCIO_VIP_MUX_EN_DVO = 0 +DCIO_VIP_MUX_EN_VIP = 1 +DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN' +DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN__enumvalues = { + 0: 'DCIO_VIP_ALTER_MAPPING_EN_DEFAULT', + 1: 'DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE', +} +DCIO_VIP_ALTER_MAPPING_EN_DEFAULT = 0 +DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE = 1 +DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN' +DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN__enumvalues = { + 0: 'DCIO_DVO_ALTER_MAPPING_EN_DEFAULT', + 1: 'DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE', +} +DCIO_DVO_ALTER_MAPPING_EN_DEFAULT = 0 +DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE = 1 +DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN' +DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN__enumvalues = { + 0: 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE', + 1: 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE', +} +DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE = 0 +DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE = 1 +DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE' +DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE__enumvalues = { + 0: 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF', + 1: 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON', +} +DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF = 0 +DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL__enumvalues = { + 0: 'DCIO_LVTMA_SYNCEN_POL_NON_INVERT', + 1: 'DCIO_LVTMA_SYNCEN_POL_INVERT', +} +DCIO_LVTMA_SYNCEN_POL_NON_INVERT = 0 +DCIO_LVTMA_SYNCEN_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON__enumvalues = { + 0: 'DCIO_LVTMA_DIGON_OFF', + 1: 'DCIO_LVTMA_DIGON_ON', +} +DCIO_LVTMA_DIGON_OFF = 0 +DCIO_LVTMA_DIGON_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL__enumvalues = { + 0: 'DCIO_LVTMA_DIGON_POL_NON_INVERT', + 1: 'DCIO_LVTMA_DIGON_POL_INVERT', +} +DCIO_LVTMA_DIGON_POL_NON_INVERT = 0 +DCIO_LVTMA_DIGON_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON__enumvalues = { + 0: 'DCIO_LVTMA_BLON_OFF', + 1: 'DCIO_LVTMA_BLON_ON', +} +DCIO_LVTMA_BLON_OFF = 0 +DCIO_LVTMA_BLON_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL__enumvalues = { + 0: 'DCIO_LVTMA_BLON_POL_NON_INVERT', + 1: 'DCIO_LVTMA_BLON_POL_INVERT', +} +DCIO_LVTMA_BLON_POL_NON_INVERT = 0 +DCIO_LVTMA_BLON_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN' +DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN__enumvalues = { + 0: 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON', + 1: 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE', +} +DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON = 0 +DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE = 1 +DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN' +DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN__enumvalues = { + 0: 'DCIO_BL_PWM_FRACTIONAL_DISABLE', + 1: 'DCIO_BL_PWM_FRACTIONAL_ENABLE', +} +DCIO_BL_PWM_FRACTIONAL_DISABLE = 0 +DCIO_BL_PWM_FRACTIONAL_ENABLE = 1 +DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL_BL_PWM_EN' +DCIO_BL_PWM_CNTL_BL_PWM_EN__enumvalues = { + 0: 'DCIO_BL_PWM_DISABLE', + 1: 'DCIO_BL_PWM_ENABLE', +} +DCIO_BL_PWM_DISABLE = 0 +DCIO_BL_PWM_ENABLE = 1 +DCIO_BL_PWM_CNTL_BL_PWM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE' +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE__enumvalues = { + 0: 'DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 1: 'DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE', +} +DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE = 0 +DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE = 1 +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN' +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN__enumvalues = { + 0: 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL', + 1: 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM', +} +DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL = 0 +DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM = 1 +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_REG_LOCK' +DCIO_BL_PWM_GRP1_REG_LOCK__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE', + 1: 'DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE', +} +DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE = 0 +DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE = 1 +DCIO_BL_PWM_GRP1_REG_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START' +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 1: 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', +} +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE = 0 +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE = 1 +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL' +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 1: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 2: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 3: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 4: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 5: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', +} +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1 = 0 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2 = 1 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3 = 2 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4 = 3 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5 = 4 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6 = 5 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN' +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 1: 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', +} +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM = 0 +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM = 1 +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN' +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 1: 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', +} +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE = 0 +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE = 1 +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL_SEL' +DCIO_GSL_SEL__enumvalues = { + 0: 'DCIO_GSL_SEL_GROUP_0', + 1: 'DCIO_GSL_SEL_GROUP_1', + 2: 'DCIO_GSL_SEL_GROUP_2', +} +DCIO_GSL_SEL_GROUP_0 = 0 +DCIO_GSL_SEL_GROUP_1 = 1 +DCIO_GSL_SEL_GROUP_2 = 2 +DCIO_GSL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_CLK_GSL_MASK' +DCIO_GENLK_CLK_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_CLK_GSL_MASK_NO', + 1: 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_CLK_GSL_MASK_STEREO', +} +DCIO_GENLK_CLK_GSL_MASK_NO = 0 +DCIO_GENLK_CLK_GSL_MASK_TIMING = 1 +DCIO_GENLK_CLK_GSL_MASK_STEREO = 2 +DCIO_GENLK_CLK_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_VSYNC_GSL_MASK' +DCIO_GENLK_VSYNC_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 1: 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', +} +DCIO_GENLK_VSYNC_GSL_MASK_NO = 0 +DCIO_GENLK_VSYNC_GSL_MASK_TIMING = 1 +DCIO_GENLK_VSYNC_GSL_MASK_STEREO = 2 +DCIO_GENLK_VSYNC_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_A_GSL_MASK' +DCIO_SWAPLOCK_A_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_A_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_A_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_A_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_A_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_B_GSL_MASK' +DCIO_SWAPLOCK_B_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_B_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_B_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_B_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_B_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_B_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_START_POSITION' +DCIO_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DCIO_GPU_TIMER_START_0_END_27', + 1: 'DCIO_GPU_TIMER_START_1_END_28', + 2: 'DCIO_GPU_TIMER_START_2_END_29', + 3: 'DCIO_GPU_TIMER_START_3_END_30', + 4: 'DCIO_GPU_TIMER_START_4_END_31', + 5: 'DCIO_GPU_TIMER_START_6_END_33', + 6: 'DCIO_GPU_TIMER_START_8_END_35', + 7: 'DCIO_GPU_TIMER_START_10_END_37', +} +DCIO_GPU_TIMER_START_0_END_27 = 0 +DCIO_GPU_TIMER_START_1_END_28 = 1 +DCIO_GPU_TIMER_START_2_END_29 = 2 +DCIO_GPU_TIMER_START_3_END_30 = 3 +DCIO_GPU_TIMER_START_4_END_31 = 4 +DCIO_GPU_TIMER_START_6_END_33 = 5 +DCIO_GPU_TIMER_START_8_END_35 = 6 +DCIO_GPU_TIMER_START_10_END_37 = 7 +DCIO_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL' +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL__enumvalues = { + 0: 'DCIO_TEST_CLK_SEL_DISPCLK', + 1: 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', + 2: 'DCIO_TEST_CLK_SEL_SOCCLK', +} +DCIO_TEST_CLK_SEL_DISPCLK = 0 +DCIO_TEST_CLK_SEL_GATED_DISPCLK = 1 +DCIO_TEST_CLK_SEL_SOCCLK = 2 +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS' +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS__enumvalues = { + 0: 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 1: 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', +} +DCIO_DISPCLK_R_DCIO_GATE_DISABLE = 0 +DCIO_DISPCLK_R_DCIO_GATE_ENABLE = 1 +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_OTG_EXT_VSYNC_MUX' +DCIO_DIO_OTG_EXT_VSYNC_MUX__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 1: 'DCIO_EXT_VSYNC_MUX_OTG0', + 2: 'DCIO_EXT_VSYNC_MUX_OTG1', + 3: 'DCIO_EXT_VSYNC_MUX_OTG2', + 4: 'DCIO_EXT_VSYNC_MUX_OTG3', + 5: 'DCIO_EXT_VSYNC_MUX_OTG4', + 6: 'DCIO_EXT_VSYNC_MUX_OTG5', + 7: 'DCIO_EXT_VSYNC_MUX_GENERICB', +} +DCIO_EXT_VSYNC_MUX_SWAPLOCKB = 0 +DCIO_EXT_VSYNC_MUX_OTG0 = 1 +DCIO_EXT_VSYNC_MUX_OTG1 = 2 +DCIO_EXT_VSYNC_MUX_OTG2 = 3 +DCIO_EXT_VSYNC_MUX_OTG3 = 4 +DCIO_EXT_VSYNC_MUX_OTG4 = 5 +DCIO_EXT_VSYNC_MUX_OTG5 = 6 +DCIO_EXT_VSYNC_MUX_GENERICB = 7 +DCIO_DIO_OTG_EXT_VSYNC_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_EXT_VSYNC_MASK' +DCIO_DIO_EXT_VSYNC_MASK__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MASK_NONE', + 1: 'DCIO_EXT_VSYNC_MASK_PIPE0', + 2: 'DCIO_EXT_VSYNC_MASK_PIPE1', + 3: 'DCIO_EXT_VSYNC_MASK_PIPE2', + 4: 'DCIO_EXT_VSYNC_MASK_PIPE3', + 5: 'DCIO_EXT_VSYNC_MASK_PIPE4', + 6: 'DCIO_EXT_VSYNC_MASK_PIPE5', + 7: 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', +} +DCIO_EXT_VSYNC_MASK_NONE = 0 +DCIO_EXT_VSYNC_MASK_PIPE0 = 1 +DCIO_EXT_VSYNC_MASK_PIPE1 = 2 +DCIO_EXT_VSYNC_MASK_PIPE2 = 3 +DCIO_EXT_VSYNC_MASK_PIPE3 = 4 +DCIO_EXT_VSYNC_MASK_PIPE4 = 5 +DCIO_EXT_VSYNC_MASK_PIPE5 = 6 +DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE = 7 +DCIO_DIO_EXT_VSYNC_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DSYNC_SOFT_RESET' +DCIO_DSYNC_SOFT_RESET__enumvalues = { + 0: 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 1: 'DCIO_DSYNC_SOFT_RESET_ASSERT', +} +DCIO_DSYNC_SOFT_RESET_DEASSERT = 0 +DCIO_DSYNC_SOFT_RESET_ASSERT = 1 +DCIO_DSYNC_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DACA_SOFT_RESET' +DCIO_DACA_SOFT_RESET__enumvalues = { + 0: 'DCIO_DACA_SOFT_RESET_DEASSERT', + 1: 'DCIO_DACA_SOFT_RESET_ASSERT', +} +DCIO_DACA_SOFT_RESET_DEASSERT = 0 +DCIO_DACA_SOFT_RESET_ASSERT = 1 +DCIO_DACA_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCRXPHY_SOFT_RESET' +DCIO_DCRXPHY_SOFT_RESET__enumvalues = { + 0: 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 1: 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', +} +DCIO_DCRXPHY_SOFT_RESET_DEASSERT = 0 +DCIO_DCRXPHY_SOFT_RESET_ASSERT = 1 +DCIO_DCRXPHY_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPHY_LANE_SEL' +DCIO_DPHY_LANE_SEL__enumvalues = { + 0: 'DCIO_DPHY_LANE_SEL_LANE0', + 1: 'DCIO_DPHY_LANE_SEL_LANE1', + 2: 'DCIO_DPHY_LANE_SEL_LANE2', + 3: 'DCIO_DPHY_LANE_SEL_LANE3', +} +DCIO_DPHY_LANE_SEL_LANE0 = 0 +DCIO_DPHY_LANE_SEL_LANE1 = 1 +DCIO_DPHY_LANE_SEL_LANE2 = 2 +DCIO_DPHY_LANE_SEL_LANE3 = 3 +DCIO_DPHY_LANE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_TYPE' +DCIO_DPCS_INTERRUPT_TYPE__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', +} +DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED = 0 +DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED = 1 +DCIO_DPCS_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_MASK' +DCIO_DPCS_INTERRUPT_MASK__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_DISABLE', + 1: 'DCIO_DPCS_INTERRUPT_ENABLE', +} +DCIO_DPCS_INTERRUPT_DISABLE = 0 +DCIO_DPCS_INTERRUPT_ENABLE = 1 +DCIO_DPCS_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_READ_SELECT' +DCIO_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 1: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 2: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 3: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 4: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 5: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', +} +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE = 0 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE = 1 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP = 2 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP = 3 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM = 4 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM = 5 +DCIO_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_IMPCAL_STEP_DELAY' +DCIO_IMPCAL_STEP_DELAY__enumvalues = { + 0: 'DCIO_IMPCAL_STEP_DELAY_1us', + 1: 'DCIO_IMPCAL_STEP_DELAY_2us', + 2: 'DCIO_IMPCAL_STEP_DELAY_3us', + 3: 'DCIO_IMPCAL_STEP_DELAY_4us', + 4: 'DCIO_IMPCAL_STEP_DELAY_5us', + 5: 'DCIO_IMPCAL_STEP_DELAY_6us', + 6: 'DCIO_IMPCAL_STEP_DELAY_7us', + 7: 'DCIO_IMPCAL_STEP_DELAY_8us', + 8: 'DCIO_IMPCAL_STEP_DELAY_9us', + 9: 'DCIO_IMPCAL_STEP_DELAY_10us', + 10: 'DCIO_IMPCAL_STEP_DELAY_11us', + 11: 'DCIO_IMPCAL_STEP_DELAY_12us', + 12: 'DCIO_IMPCAL_STEP_DELAY_13us', + 13: 'DCIO_IMPCAL_STEP_DELAY_14us', + 14: 'DCIO_IMPCAL_STEP_DELAY_15us', + 15: 'DCIO_IMPCAL_STEP_DELAY_16us', +} +DCIO_IMPCAL_STEP_DELAY_1us = 0 +DCIO_IMPCAL_STEP_DELAY_2us = 1 +DCIO_IMPCAL_STEP_DELAY_3us = 2 +DCIO_IMPCAL_STEP_DELAY_4us = 3 +DCIO_IMPCAL_STEP_DELAY_5us = 4 +DCIO_IMPCAL_STEP_DELAY_6us = 5 +DCIO_IMPCAL_STEP_DELAY_7us = 6 +DCIO_IMPCAL_STEP_DELAY_8us = 7 +DCIO_IMPCAL_STEP_DELAY_9us = 8 +DCIO_IMPCAL_STEP_DELAY_10us = 9 +DCIO_IMPCAL_STEP_DELAY_11us = 10 +DCIO_IMPCAL_STEP_DELAY_12us = 11 +DCIO_IMPCAL_STEP_DELAY_13us = 12 +DCIO_IMPCAL_STEP_DELAY_14us = 13 +DCIO_IMPCAL_STEP_DELAY_15us = 14 +DCIO_IMPCAL_STEP_DELAY_16us = 15 +DCIO_IMPCAL_STEP_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_IMPCAL_SEL' +DCIO_UNIPHY_IMPCAL_SEL__enumvalues = { + 0: 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 1: 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', +} +DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE = 0 +DCIO_UNIPHY_IMPCAL_SEL_BINARY = 1 +DCIO_UNIPHY_IMPCAL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_HPD_SEL' +DCIOCHIP_HPD_SEL__enumvalues = { + 0: 'DCIOCHIP_HPD_SEL_ASYNC', + 1: 'DCIOCHIP_HPD_SEL_CLOCKED', +} +DCIOCHIP_HPD_SEL_ASYNC = 0 +DCIOCHIP_HPD_SEL_CLOCKED = 1 +DCIOCHIP_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PAD_MODE' +DCIOCHIP_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_PAD_MODE_DDC', + 1: 'DCIOCHIP_PAD_MODE_DP', +} +DCIOCHIP_PAD_MODE_DDC = 0 +DCIOCHIP_PAD_MODE_DP = 1 +DCIOCHIP_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUXSLAVE_PAD_MODE' +DCIOCHIP_AUXSLAVE_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_AUXSLAVE_PAD_MODE_I2C', + 1: 'DCIOCHIP_AUXSLAVE_PAD_MODE_AUX', +} +DCIOCHIP_AUXSLAVE_PAD_MODE_I2C = 0 +DCIOCHIP_AUXSLAVE_PAD_MODE_AUX = 1 +DCIOCHIP_AUXSLAVE_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_INVERT' +DCIOCHIP_INVERT__enumvalues = { + 0: 'DCIOCHIP_POL_NON_INVERT', + 1: 'DCIOCHIP_POL_INVERT', +} +DCIOCHIP_POL_NON_INVERT = 0 +DCIOCHIP_POL_INVERT = 1 +DCIOCHIP_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PD_EN' +DCIOCHIP_PD_EN__enumvalues = { + 0: 'DCIOCHIP_PD_EN_NOTALLOW', + 1: 'DCIOCHIP_PD_EN_ALLOW', +} +DCIOCHIP_PD_EN_NOTALLOW = 0 +DCIOCHIP_PD_EN_ALLOW = 1 +DCIOCHIP_PD_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_MASK_EN' +DCIOCHIP_GPIO_MASK_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 1: 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', +} +DCIOCHIP_GPIO_MASK_EN_HARDWARE = 0 +DCIOCHIP_GPIO_MASK_EN_SOFTWARE = 1 +DCIOCHIP_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK' +DCIOCHIP_MASK__enumvalues = { + 0: 'DCIOCHIP_MASK_DISABLE', + 1: 'DCIOCHIP_MASK_ENABLE', +} +DCIOCHIP_MASK_DISABLE = 0 +DCIOCHIP_MASK_ENABLE = 1 +DCIOCHIP_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_MASK' +DCIOCHIP_GPIO_I2C_MASK__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_MASK_DISABLE', + 1: 'DCIOCHIP_GPIO_I2C_MASK_ENABLE', +} +DCIOCHIP_GPIO_I2C_MASK_DISABLE = 0 +DCIOCHIP_GPIO_I2C_MASK_ENABLE = 1 +DCIOCHIP_GPIO_I2C_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_DRIVE' +DCIOCHIP_GPIO_I2C_DRIVE__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_DRIVE_LOW', + 1: 'DCIOCHIP_GPIO_I2C_DRIVE_HIGH', +} +DCIOCHIP_GPIO_I2C_DRIVE_LOW = 0 +DCIOCHIP_GPIO_I2C_DRIVE_HIGH = 1 +DCIOCHIP_GPIO_I2C_DRIVE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_EN' +DCIOCHIP_GPIO_I2C_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_DISABLE', + 1: 'DCIOCHIP_GPIO_I2C_ENABLE', +} +DCIOCHIP_GPIO_I2C_DISABLE = 0 +DCIOCHIP_GPIO_I2C_ENABLE = 1 +DCIOCHIP_GPIO_I2C_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_4BIT' +DCIOCHIP_MASK_4BIT__enumvalues = { + 0: 'DCIOCHIP_MASK_4BIT_DISABLE', + 15: 'DCIOCHIP_MASK_4BIT_ENABLE', +} +DCIOCHIP_MASK_4BIT_DISABLE = 0 +DCIOCHIP_MASK_4BIT_ENABLE = 15 +DCIOCHIP_MASK_4BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_4BIT' +DCIOCHIP_ENABLE_4BIT__enumvalues = { + 0: 'DCIOCHIP_4BIT_DISABLE', + 15: 'DCIOCHIP_4BIT_ENABLE', +} +DCIOCHIP_4BIT_DISABLE = 0 +DCIOCHIP_4BIT_ENABLE = 15 +DCIOCHIP_ENABLE_4BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_5BIT' +DCIOCHIP_MASK_5BIT__enumvalues = { + 0: 'DCIOCHIP_MASIK_5BIT_DISABLE', + 31: 'DCIOCHIP_MASIK_5BIT_ENABLE', +} +DCIOCHIP_MASIK_5BIT_DISABLE = 0 +DCIOCHIP_MASIK_5BIT_ENABLE = 31 +DCIOCHIP_MASK_5BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_5BIT' +DCIOCHIP_ENABLE_5BIT__enumvalues = { + 0: 'DCIOCHIP_5BIT_DISABLE', + 31: 'DCIOCHIP_5BIT_ENABLE', +} +DCIOCHIP_5BIT_DISABLE = 0 +DCIOCHIP_5BIT_ENABLE = 31 +DCIOCHIP_ENABLE_5BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_2BIT' +DCIOCHIP_MASK_2BIT__enumvalues = { + 0: 'DCIOCHIP_MASK_2BIT_DISABLE', + 3: 'DCIOCHIP_MASK_2BIT_ENABLE', +} +DCIOCHIP_MASK_2BIT_DISABLE = 0 +DCIOCHIP_MASK_2BIT_ENABLE = 3 +DCIOCHIP_MASK_2BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_2BIT' +DCIOCHIP_ENABLE_2BIT__enumvalues = { + 0: 'DCIOCHIP_2BIT_DISABLE', + 3: 'DCIOCHIP_2BIT_ENABLE', +} +DCIOCHIP_2BIT_DISABLE = 0 +DCIOCHIP_2BIT_ENABLE = 3 +DCIOCHIP_ENABLE_2BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_REF_27_SRC_SEL' +DCIOCHIP_REF_27_SRC_SEL__enumvalues = { + 0: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 1: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 2: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 3: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', +} +DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER = 0 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER = 1 +DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS = 2 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS = 3 +DCIOCHIP_REF_27_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_DVO_VREFPON' +DCIOCHIP_DVO_VREFPON__enumvalues = { + 0: 'DCIOCHIP_DVO_VREFPON_DISABLE', + 1: 'DCIOCHIP_DVO_VREFPON_ENABLE', +} +DCIOCHIP_DVO_VREFPON_DISABLE = 0 +DCIOCHIP_DVO_VREFPON_ENABLE = 1 +DCIOCHIP_DVO_VREFPON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_DVO_VREFSEL' +DCIOCHIP_DVO_VREFSEL__enumvalues = { + 0: 'DCIOCHIP_DVO_VREFSEL_ONCHIP', + 1: 'DCIOCHIP_DVO_VREFSEL_EXTERNAL', +} +DCIOCHIP_DVO_VREFSEL_ONCHIP = 0 +DCIOCHIP_DVO_VREFSEL_EXTERNAL = 1 +DCIOCHIP_DVO_VREFSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_SPDIF1_IMODE' +DCIOCHIP_SPDIF1_IMODE__enumvalues = { + 0: 'DCIOCHIP_SPDIF1_IMODE_OE_A', + 1: 'DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO', +} +DCIOCHIP_SPDIF1_IMODE_OE_A = 0 +DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO = 1 +DCIOCHIP_SPDIF1_IMODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_FALLSLEWSEL' +DCIOCHIP_AUX_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 1: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 2: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', + 3: 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', +} +DCIOCHIP_AUX_FALLSLEWSEL_LOW = 0 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH0 = 1 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH1 = 2 +DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH = 3 +DCIOCHIP_AUX_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_FALLSLEWSEL' +DCIOCHIP_I2C_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_FALLSLEWSEL_00', + 1: 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 2: 'DCIOCHIP_I2C_FALLSLEWSEL_10', + 3: 'DCIOCHIP_I2C_FALLSLEWSEL_11', +} +DCIOCHIP_I2C_FALLSLEWSEL_00 = 0 +DCIOCHIP_I2C_FALLSLEWSEL_01 = 1 +DCIOCHIP_I2C_FALLSLEWSEL_10 = 2 +DCIOCHIP_I2C_FALLSLEWSEL_11 = 3 +DCIOCHIP_I2C_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_SPIKESEL' +DCIOCHIP_AUX_SPIKESEL__enumvalues = { + 0: 'DCIOCHIP_AUX_SPIKESEL_50NS', + 1: 'DCIOCHIP_AUX_SPIKESEL_10NS', +} +DCIOCHIP_AUX_SPIKESEL_50NS = 0 +DCIOCHIP_AUX_SPIKESEL_10NS = 1 +DCIOCHIP_AUX_SPIKESEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL0P9' +DCIOCHIP_AUX_CSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_CSEL_DEC0P9', +} +DCIOCHIP_AUX_CSEL_DEC1P0 = 0 +DCIOCHIP_AUX_CSEL_DEC0P9 = 1 +DCIOCHIP_AUX_CSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL1P1' +DCIOCHIP_AUX_CSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_INC1P0', + 1: 'DCIOCHIP_AUX_CSEL_INC1P1', +} +DCIOCHIP_AUX_CSEL_INC1P0 = 0 +DCIOCHIP_AUX_CSEL_INC1P1 = 1 +DCIOCHIP_AUX_CSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL0P9' +DCIOCHIP_AUX_RSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_RSEL_DEC0P9', +} +DCIOCHIP_AUX_RSEL_DEC1P0 = 0 +DCIOCHIP_AUX_RSEL_DEC0P9 = 1 +DCIOCHIP_AUX_RSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL1P1' +DCIOCHIP_AUX_RSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_INC1P0', + 1: 'DCIOCHIP_AUX_RSEL_INC1P1', +} +DCIOCHIP_AUX_RSEL_INC1P0 = 0 +DCIOCHIP_AUX_RSEL_INC1P1 = 1 +DCIOCHIP_AUX_RSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_HYS_TUNE' +DCIOCHIP_AUX_HYS_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_HYS_TUNE_0', + 1: 'DCIOCHIP_AUX_HYS_TUNE_1', + 2: 'DCIOCHIP_AUX_HYS_TUNE_2', + 3: 'DCIOCHIP_AUX_HYS_TUNE_3', +} +DCIOCHIP_AUX_HYS_TUNE_0 = 0 +DCIOCHIP_AUX_HYS_TUNE_1 = 1 +DCIOCHIP_AUX_HYS_TUNE_2 = 2 +DCIOCHIP_AUX_HYS_TUNE_3 = 3 +DCIOCHIP_AUX_HYS_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_VOD_TUNE' +DCIOCHIP_AUX_VOD_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_VOD_TUNE_0', + 1: 'DCIOCHIP_AUX_VOD_TUNE_1', + 2: 'DCIOCHIP_AUX_VOD_TUNE_2', + 3: 'DCIOCHIP_AUX_VOD_TUNE_3', +} +DCIOCHIP_AUX_VOD_TUNE_0 = 0 +DCIOCHIP_AUX_VOD_TUNE_1 = 1 +DCIOCHIP_AUX_VOD_TUNE_2 = 2 +DCIOCHIP_AUX_VOD_TUNE_3 = 3 +DCIOCHIP_AUX_VOD_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_VPH_1V2_EN' +DCIOCHIP_I2C_VPH_1V2_EN__enumvalues = { + 0: 'DCIOCHIP_I2C_VPH_1V2_EN_0', + 1: 'DCIOCHIP_I2C_VPH_1V2_EN_1', +} +DCIOCHIP_I2C_VPH_1V2_EN_0 = 0 +DCIOCHIP_I2C_VPH_1V2_EN_1 = 1 +DCIOCHIP_I2C_VPH_1V2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_COMPSEL' +DCIOCHIP_I2C_COMPSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_REC_SCHMIT', + 1: 'DCIOCHIP_I2C_REC_COMPARATOR', +} +DCIOCHIP_I2C_REC_SCHMIT = 0 +DCIOCHIP_I2C_REC_COMPARATOR = 1 +DCIOCHIP_I2C_COMPSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_ALL_PWR_OK' +DCIOCHIP_AUX_ALL_PWR_OK__enumvalues = { + 0: 'DCIOCHIP_AUX_ALL_PWR_OK_0', + 1: 'DCIOCHIP_AUX_ALL_PWR_OK_1', +} +DCIOCHIP_AUX_ALL_PWR_OK_0 = 0 +DCIOCHIP_AUX_ALL_PWR_OK_1 = 1 +DCIOCHIP_AUX_ALL_PWR_OK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_RECEIVER_SEL' +DCIOCHIP_I2C_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 1: 'DCIOCHIP_I2C_RECEIVER_SEL_1', + 2: 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 3: 'DCIOCHIP_I2C_RECEIVER_SEL_3', +} +DCIOCHIP_I2C_RECEIVER_SEL_0 = 0 +DCIOCHIP_I2C_RECEIVER_SEL_1 = 1 +DCIOCHIP_I2C_RECEIVER_SEL_2 = 2 +DCIOCHIP_I2C_RECEIVER_SEL_3 = 3 +DCIOCHIP_I2C_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RECEIVER_SEL' +DCIOCHIP_AUX_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 1: 'DCIOCHIP_AUX_RECEIVER_SEL_1', + 2: 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 3: 'DCIOCHIP_AUX_RECEIVER_SEL_3', +} +DCIOCHIP_AUX_RECEIVER_SEL_0 = 0 +DCIOCHIP_AUX_RECEIVER_SEL_1 = 1 +DCIOCHIP_AUX_RECEIVER_SEL_2 = 2 +DCIOCHIP_AUX_RECEIVER_SEL_3 = 3 +DCIOCHIP_AUX_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_GLOBAL_CAPABILITIES' +AZ_GLOBAL_CAPABILITIES__enumvalues = { + 0: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 1: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', +} +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED = 0 +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED = 1 +AZ_GLOBAL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE' +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE__enumvalues = { + 0: 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', + 1: 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', +} +ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE = 0 +ACCEPT_UNSOLICITED_RESPONSE_ENABLE = 1 +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_FLUSH_CONTROL' +GLOBAL_CONTROL_FLUSH_CONTROL__enumvalues = { + 0: 'FLUSH_CONTROL_FLUSH_NOT_STARTED', + 1: 'FLUSH_CONTROL_FLUSH_STARTED', +} +FLUSH_CONTROL_FLUSH_NOT_STARTED = 0 +FLUSH_CONTROL_FLUSH_STARTED = 1 +GLOBAL_CONTROL_FLUSH_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_CONTROLLER_RESET' +GLOBAL_CONTROL_CONTROLLER_RESET__enumvalues = { + 0: 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 1: 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', +} +CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET = 0 +CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET = 1 +GLOBAL_CONTROL_CONTROLLER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_STATE_CHANGE_STATUS' +AZ_STATE_CHANGE_STATUS__enumvalues = { + 0: 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 1: 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', +} +AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT = 0 +AZ_STATE_CHANGE_STATUS_CODEC_PRESENT = 1 +AZ_STATE_CHANGE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_STATUS_FLUSH_STATUS' +GLOBAL_STATUS_FLUSH_STATUS__enumvalues = { + 0: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 1: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', +} +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED = 0 +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED = 1 +GLOBAL_STATUS_FLUSH_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_0_SYNCHRONIZATION' +STREAM_0_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_0_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_0_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_1_SYNCHRONIZATION' +STREAM_1_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_1_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_1_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_2_SYNCHRONIZATION' +STREAM_2_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_2_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_2_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_3_SYNCHRONIZATION' +STREAM_3_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_3_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_3_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_4_SYNCHRONIZATION' +STREAM_4_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_4_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_4_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_5_SYNCHRONIZATION' +STREAM_5_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_5_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_5_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_6_SYNCHRONIZATION' +STREAM_6_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_6_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_7_SYNCHRONIZATION' +STREAM_7_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_7_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_8_SYNCHRONIZATION' +STREAM_8_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_8_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_9_SYNCHRONIZATION' +STREAM_9_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_9_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_10_SYNCHRONIZATION' +STREAM_10_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_10_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_11_SYNCHRONIZATION' +STREAM_11_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_11_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_12_SYNCHRONIZATION' +STREAM_12_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_12_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_13_SYNCHRONIZATION' +STREAM_13_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_13_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_14_SYNCHRONIZATION' +STREAM_14_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_14_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_15_SYNCHRONIZATION' +STREAM_15_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_15_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'CORB_READ_POINTER_RESET' +CORB_READ_POINTER_RESET__enumvalues = { + 0: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 1: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', +} +CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET = 0 +CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET = 1 +CORB_READ_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_CORB_SIZE' +AZ_CORB_SIZE__enumvalues = { + 0: 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_CORB_SIZE_256ENTRIES', + 3: 'AZ_CORB_SIZE_RESERVED', +} +AZ_CORB_SIZE_2ENTRIES_RESERVED = 0 +AZ_CORB_SIZE_16ENTRIES_RESERVED = 1 +AZ_CORB_SIZE_256ENTRIES = 2 +AZ_CORB_SIZE_RESERVED = 3 +AZ_CORB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_WRITE_POINTER_RESET' +AZ_RIRB_WRITE_POINTER_RESET__enumvalues = { + 0: 'AZ_RIRB_WRITE_POINTER_NOT_RESET', + 1: 'AZ_RIRB_WRITE_POINTER_DO_RESET', +} +AZ_RIRB_WRITE_POINTER_NOT_RESET = 0 +AZ_RIRB_WRITE_POINTER_DO_RESET = 1 +AZ_RIRB_WRITE_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_SIZE' +AZ_RIRB_SIZE__enumvalues = { + 0: 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_RIRB_SIZE_256ENTRIES', + 3: 'AZ_RIRB_SIZE_UNDEFINED', +} +AZ_RIRB_SIZE_2ENTRIES_RESERVED = 0 +AZ_RIRB_SIZE_16ENTRIES_RESERVED = 1 +AZ_RIRB_SIZE_256ENTRIES = 2 +AZ_RIRB_SIZE_UNDEFINED = 3 +AZ_RIRB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY = ctypes.c_uint32 # enum + +# values for enumeration 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE' +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE__enumvalues = { + 0: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 1: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', +} +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE = 0 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE = 1 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT' +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE' +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 2: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 3: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 4: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 5: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 6: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 7: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 8: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 9: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 10: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 11: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 12: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 13: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 14: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 15: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', +} +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0 = 0 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1 = 1 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2 = 2 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3 = 3 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4 = 4 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5 = 5 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6 = 6 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7 = 7 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8 = 8 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9 = 9 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10 = 10 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11 = 11 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12 = 12 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13 = 13 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14 = 14 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15 = 15 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL' +MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'NO_FORCE_REQUEST', + 1: 'FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FORCE_DEEP_SLEEP_REQUEST', + 3: 'FORCE_SHUT_DOWN_REQUEST', +} +NO_FORCE_REQUEST = 0 +FORCE_LIGHT_SLEEP_REQUEST = 1 +FORCE_DEEP_SLEEP_REQUEST = 2 +FORCE_SHUT_DOWN_REQUEST = 3 +MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL2' +MEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'NO_FORCE_REQ', + 1: 'FORCE_LIGHT_SLEEP_REQ', +} +NO_FORCE_REQ = 0 +FORCE_LIGHT_SLEEP_REQ = 1 +MEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_CTRL' +MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'ENABLE_MEM_PWR_CTRL', + 1: 'DISABLE_MEM_PWR_CTRL', +} +ENABLE_MEM_PWR_CTRL = 0 +DISABLE_MEM_PWR_CTRL = 1 +MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL' +MEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DYNAMIC_SHUT_DOWN_ENABLE = 0 +DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +MEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL2' +MEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DYNAMIC_DEEP_SLEEP_EN', + 1: 'DYNAMIC_LIGHT_SLEEP_EN', +} +DYNAMIC_DEEP_SLEEP_EN = 0 +DYNAMIC_LIGHT_SLEEP_EN = 1 +MEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET' +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET__enumvalues = { + 0: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 1: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', +} +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET = 0 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC = 1 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET' +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET__enumvalues = { + 0: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 1: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', +} +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET = 0 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET = 1 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_LATENCY_COUNTER_CONTROL' +AZ_LATENCY_COUNTER_CONTROL__enumvalues = { + 0: 'AZ_LATENCY_COUNTER_NO_RESET', + 1: 'AZ_LATENCY_COUNTER_RESET_DONE', +} +AZ_LATENCY_COUNTER_NO_RESET = 0 +AZ_LATENCY_COUNTER_RESET_DONE = 1 +AZ_LATENCY_COUNTER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 9: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 10: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 11: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 12: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 13: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 14: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 15: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED = 8 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED = 9 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED = 10 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED = 11 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED = 12 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED = 13 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED = 14 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED = 15 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', +} +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY = 0 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY = 1 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ICH_RESET_ENUM' +DSCC_ICH_RESET_ENUM__enumvalues = { + 1: 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 2: 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 4: 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 8: 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', +} +DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET = 1 +DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET = 2 +DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET = 4 +DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET = 8 +DSCC_ICH_RESET_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MINOR_ENUM' +DSCC_DSC_VERSION_MINOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 2: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', +} +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION = 1 +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION = 2 +DSCC_DSC_VERSION_MINOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MAJOR_ENUM' +DSCC_DSC_VERSION_MAJOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', +} +DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION = 1 +DSCC_DSC_VERSION_MAJOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_LINEBUF_DEPTH_ENUM' +DSCC_LINEBUF_DEPTH_ENUM__enumvalues = { + 8: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 9: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 10: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 11: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 12: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 13: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', +} +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT = 8 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT = 9 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT = 10 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT = 11 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT = 12 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT = 13 +DSCC_LINEBUF_DEPTH_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_BITS_PER_COMPONENT_ENUM' +DSCC_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCC_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ENABLE_ENUM' +DSCC_ENABLE_ENUM__enumvalues = { + 0: 'DSCC_ENABLE_ENUM_DISABLED', + 1: 'DSCC_ENABLE_ENUM_ENABLED', +} +DSCC_ENABLE_ENUM_DISABLED = 0 +DSCC_ENABLE_ENUM_ENABLED = 1 +DSCC_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_FORCE_ENUM' +DSCC_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 1: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', +} +DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST = 0 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST = 2 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST = 3 +DSCC_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'POWER_STATE_ENUM' +POWER_STATE_ENUM__enumvalues = { + 0: 'POWER_STATE_ENUM_ON', + 1: 'POWER_STATE_ENUM_LS', + 2: 'POWER_STATE_ENUM_DS', + 3: 'POWER_STATE_ENUM_SD', +} +POWER_STATE_ENUM_ON = 0 +POWER_STATE_ENUM_LS = 1 +POWER_STATE_ENUM_DS = 2 +POWER_STATE_ENUM_SD = 3 +POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_DIS_ENUM' +DSCC_MEM_PWR_DIS_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', + 1: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', +} +DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN = 0 +DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS = 1 +DSCC_MEM_PWR_DIS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_ENABLE_ENUM' +DSCCIF_ENABLE_ENUM__enumvalues = { + 0: 'DSCCIF_ENABLE_ENUM_DISABLED', + 1: 'DSCCIF_ENABLE_ENUM_ENABLED', +} +DSCCIF_ENABLE_ENUM_DISABLED = 0 +DSCCIF_ENABLE_ENUM_ENABLED = 1 +DSCCIF_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM' +DSCCIF_INPUT_PIXEL_FORMAT_ENUM__enumvalues = { + 0: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 1: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 2: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 3: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 4: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', +} +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB = 0 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444 = 1 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422 = 2 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422 = 3 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420 = 4 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_BITS_PER_COMPONENT_ENUM' +DSCCIF_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCCIF_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_ENUM' +ENABLE_ENUM__enumvalues = { + 0: 'ENABLE_ENUM_DISABLED', + 1: 'ENABLE_ENUM_ENABLED', +} +ENABLE_ENUM_DISABLED = 0 +ENABLE_ENUM_ENABLED = 1 +ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_DISABLE_ENUM' +CLOCK_GATING_DISABLE_ENUM__enumvalues = { + 0: 'CLOCK_GATING_DISABLE_ENUM_ENABLED', + 1: 'CLOCK_GATING_DISABLE_ENUM_DISABLED', +} +CLOCK_GATING_DISABLE_ENUM_ENABLED = 0 +CLOCK_GATING_DISABLE_ENUM_DISABLED = 1 +CLOCK_GATING_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLOCK_MUX_SELECT_ENUM' +TEST_CLOCK_MUX_SELECT_ENUM__enumvalues = { + 0: 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 1: 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 2: 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 3: 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 4: 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 5: 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', +} +TEST_CLOCK_MUX_SELECT_DISPCLK_P = 0 +TEST_CLOCK_MUX_SELECT_DISPCLK_G = 1 +TEST_CLOCK_MUX_SELECT_DISPCLK_R = 2 +TEST_CLOCK_MUX_SELECT_DSCCLK_P = 3 +TEST_CLOCK_MUX_SELECT_DSCCLK_G = 4 +TEST_CLOCK_MUX_SELECT_DSCCLK_R = 5 +TEST_CLOCK_MUX_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_ENABLE_ENUM' +WB_ENABLE_ENUM__enumvalues = { + 0: 'WB_EN_DISABLE', + 1: 'WB_EN_ENABLE', +} +WB_EN_DISABLE = 0 +WB_EN_ENABLE = 1 +WB_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_CLK_GATE_DIS_ENUM' +WB_CLK_GATE_DIS_ENUM__enumvalues = { + 0: 'WB_CLK_GATE_ENABLE', + 1: 'WB_CLK_GATE_DISABLE', +} +WB_CLK_GATE_ENABLE = 0 +WB_CLK_GATE_DISABLE = 1 +WB_CLK_GATE_DIS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_MEM_PWR_DIS_ENUM' +WB_MEM_PWR_DIS_ENUM__enumvalues = { + 0: 'WB_MEM_PWR_ENABLE', + 1: 'WB_MEM_PWR_DISABLE', +} +WB_MEM_PWR_ENABLE = 0 +WB_MEM_PWR_DISABLE = 1 +WB_MEM_PWR_DIS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_TEST_CLK_SEL_ENUM' +WB_TEST_CLK_SEL_ENUM__enumvalues = { + 0: 'WB_TEST_CLK_SEL_REG', + 1: 'WB_TEST_CLK_SEL_WB', + 2: 'WB_TEST_CLK_SEL_WBSCL', + 3: 'WB_TEST_CLK_SEL_PERM', +} +WB_TEST_CLK_SEL_REG = 0 +WB_TEST_CLK_SEL_WB = 1 +WB_TEST_CLK_SEL_WBSCL = 2 +WB_TEST_CLK_SEL_PERM = 3 +WB_TEST_CLK_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_LB_MEM_PWR_MODE_SEL_ENUM' +WBSCL_LB_MEM_PWR_MODE_SEL_ENUM__enumvalues = { + 0: 'WBSCL_LB_MEM_PWR_MODE_SEL_SD', + 1: 'WBSCL_LB_MEM_PWR_MODE_SEL_DS', + 2: 'WBSCL_LB_MEM_PWR_MODE_SEL_LS', + 3: 'WBSCL_LB_MEM_PWR_MODE_SEL_ON', +} +WBSCL_LB_MEM_PWR_MODE_SEL_SD = 0 +WBSCL_LB_MEM_PWR_MODE_SEL_DS = 1 +WBSCL_LB_MEM_PWR_MODE_SEL_LS = 2 +WBSCL_LB_MEM_PWR_MODE_SEL_ON = 3 +WBSCL_LB_MEM_PWR_MODE_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_LB_MEM_PWR_FORCE_ENUM' +WBSCL_LB_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'WBSCL_LB_MEM_PWR_FORCE_NO', + 1: 'WBSCL_LB_MEM_PWR_FORCE_LS', + 2: 'WBSCL_LB_MEM_PWR_FORCE_DS', + 3: 'WBSCL_LB_MEM_PWR_FORCE_SD', +} +WBSCL_LB_MEM_PWR_FORCE_NO = 0 +WBSCL_LB_MEM_PWR_FORCE_LS = 1 +WBSCL_LB_MEM_PWR_FORCE_DS = 2 +WBSCL_LB_MEM_PWR_FORCE_SD = 3 +WBSCL_LB_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_MEM_PWR_STATE_ENUM' +WBSCL_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'WBSCL_MEM_PWR_STATE_ON', + 1: 'WBSCL_MEM_PWR_STATE_LS', + 2: 'WBSCL_MEM_PWR_STATE_DS', + 3: 'WBSCL_MEM_PWR_STATE_SD', +} +WBSCL_MEM_PWR_STATE_ON = 0 +WBSCL_MEM_PWR_STATE_LS = 1 +WBSCL_MEM_PWR_STATE_DS = 2 +WBSCL_MEM_PWR_STATE_SD = 3 +WBSCL_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_LUT_MEM_PWR_STATE_ENUM' +WBSCL_LUT_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'WBSCL_LUT_MEM_PWR_STATE_ON', + 1: 'WBSCL_LUT_MEM_PWR_STATE_LS', + 2: 'WBSCL_LUT_MEM_PWR_STATE_RESERVED2', + 3: 'WBSCL_LUT_MEM_PWR_STATE_RESERVED3', +} +WBSCL_LUT_MEM_PWR_STATE_ON = 0 +WBSCL_LUT_MEM_PWR_STATE_LS = 1 +WBSCL_LUT_MEM_PWR_STATE_RESERVED2 = 2 +WBSCL_LUT_MEM_PWR_STATE_RESERVED3 = 3 +WBSCL_LUT_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_RAM_PW_SAVE_MODE_ENUM' +WB_RAM_PW_SAVE_MODE_ENUM__enumvalues = { + 0: 'WB_RAM_PW_SAVE_MODE_LS', + 1: 'WB_RAM_PW_SAVE_MODE_SD', +} +WB_RAM_PW_SAVE_MODE_LS = 0 +WB_RAM_PW_SAVE_MODE_SD = 1 +WB_RAM_PW_SAVE_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_OUT_BPC_ENUM' +CNV_OUT_BPC_ENUM__enumvalues = { + 0: 'CNV_OUT_BPC_8BPC', + 1: 'CNV_OUT_BPC_10BPC', +} +CNV_OUT_BPC_8BPC = 0 +CNV_OUT_BPC_10BPC = 1 +CNV_OUT_BPC_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_FRAME_CAPTURE_RATE_ENUM' +CNV_FRAME_CAPTURE_RATE_ENUM__enumvalues = { + 0: 'CNV_FRAME_CAPTURE_RATE_0', + 1: 'CNV_FRAME_CAPTURE_RATE_1', + 2: 'CNV_FRAME_CAPTURE_RATE_2', + 3: 'CNV_FRAME_CAPTURE_RATE_3', +} +CNV_FRAME_CAPTURE_RATE_0 = 0 +CNV_FRAME_CAPTURE_RATE_1 = 1 +CNV_FRAME_CAPTURE_RATE_2 = 2 +CNV_FRAME_CAPTURE_RATE_3 = 3 +CNV_FRAME_CAPTURE_RATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_WINDOW_CROP_EN_ENUM' +CNV_WINDOW_CROP_EN_ENUM__enumvalues = { + 0: 'CNV_WINDOW_CROP_DISABLE', + 1: 'CNV_WINDOW_CROP_ENABLE', +} +CNV_WINDOW_CROP_DISABLE = 0 +CNV_WINDOW_CROP_ENABLE = 1 +CNV_WINDOW_CROP_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_INTERLACED_MODE_ENUM' +CNV_INTERLACED_MODE_ENUM__enumvalues = { + 0: 'CNV_INTERLACED_MODE_PROGRESSIVE', + 1: 'CNV_INTERLACED_MODE_INTERLACED', +} +CNV_INTERLACED_MODE_PROGRESSIVE = 0 +CNV_INTERLACED_MODE_INTERLACED = 1 +CNV_INTERLACED_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_EYE_SELECT' +CNV_EYE_SELECT__enumvalues = { + 0: 'STEREO_DISABLED', + 1: 'LEFT_EYE', + 2: 'RIGHT_EYE', + 3: 'BOTH_EYE', +} +STEREO_DISABLED = 0 +LEFT_EYE = 1 +RIGHT_EYE = 2 +BOTH_EYE = 3 +CNV_EYE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_STEREO_TYPE_ENUM' +CNV_STEREO_TYPE_ENUM__enumvalues = { + 0: 'CNV_STEREO_TYPE_RESERVED0', + 1: 'CNV_STEREO_TYPE_RESERVED1', + 2: 'CNV_STEREO_TYPE_RESERVED2', + 3: 'CNV_STEREO_TYPE_FRAME_SEQUENTIAL', +} +CNV_STEREO_TYPE_RESERVED0 = 0 +CNV_STEREO_TYPE_RESERVED1 = 1 +CNV_STEREO_TYPE_RESERVED2 = 2 +CNV_STEREO_TYPE_FRAME_SEQUENTIAL = 3 +CNV_STEREO_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_STEREO_POLARITY_ENUM' +CNV_STEREO_POLARITY_ENUM__enumvalues = { + 0: 'CNV_STEREO_POLARITY_LEFT', + 1: 'CNV_STEREO_POLARITY_RIGHT', +} +CNV_STEREO_POLARITY_LEFT = 0 +CNV_STEREO_POLARITY_RIGHT = 1 +CNV_STEREO_POLARITY_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_INTERLACED_FIELD_ORDER_ENUM' +CNV_INTERLACED_FIELD_ORDER_ENUM__enumvalues = { + 0: 'CNV_INTERLACED_FIELD_ORDER_TOP', + 1: 'CNV_INTERLACED_FIELD_ORDER_BOT', +} +CNV_INTERLACED_FIELD_ORDER_TOP = 0 +CNV_INTERLACED_FIELD_ORDER_BOT = 1 +CNV_INTERLACED_FIELD_ORDER_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_STEREO_SPLIT_ENUM' +CNV_STEREO_SPLIT_ENUM__enumvalues = { + 0: 'CNV_STEREO_SPLIT_DISABLE', + 1: 'CNV_STEREO_SPLIT_ENABLE', +} +CNV_STEREO_SPLIT_DISABLE = 0 +CNV_STEREO_SPLIT_ENABLE = 1 +CNV_STEREO_SPLIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_NEW_CONTENT_ENUM' +CNV_NEW_CONTENT_ENUM__enumvalues = { + 0: 'CNV_NEW_CONTENT_NEG', + 1: 'CNV_NEW_CONTENT_POS', +} +CNV_NEW_CONTENT_NEG = 0 +CNV_NEW_CONTENT_POS = 1 +CNV_NEW_CONTENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_FRAME_CAPTURE_EN_ENUM' +CNV_FRAME_CAPTURE_EN_ENUM__enumvalues = { + 0: 'CNV_FRAME_CAPTURE_DISABLE', + 1: 'CNV_FRAME_CAPTURE_ENABLE', +} +CNV_FRAME_CAPTURE_DISABLE = 0 +CNV_FRAME_CAPTURE_ENABLE = 1 +CNV_FRAME_CAPTURE_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_UPDATE_PENDING_ENUM' +CNV_UPDATE_PENDING_ENUM__enumvalues = { + 0: 'CNV_UPDATE_PENDING_NEG', + 1: 'CNV_UPDATE_PENDING_POS', +} +CNV_UPDATE_PENDING_NEG = 0 +CNV_UPDATE_PENDING_POS = 1 +CNV_UPDATE_PENDING_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_UPDATE_LOCK_ENUM' +CNV_UPDATE_LOCK_ENUM__enumvalues = { + 0: 'CNV_UPDATE_UNLOCK', + 1: 'CNV_UPDATE_LOCK', +} +CNV_UPDATE_UNLOCK = 0 +CNV_UPDATE_LOCK = 1 +CNV_UPDATE_LOCK_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_CSC_BYPASS_ENUM' +CNV_CSC_BYPASS_ENUM__enumvalues = { + 0: 'CNV_CSC_BYPASS_NEG', + 1: 'CNV_CSC_BYPASS_POS', +} +CNV_CSC_BYPASS_NEG = 0 +CNV_CSC_BYPASS_POS = 1 +CNV_CSC_BYPASS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_TEST_CRC_EN_ENUM' +CNV_TEST_CRC_EN_ENUM__enumvalues = { + 0: 'CNV_TEST_CRC_DISABLE', + 1: 'CNV_TEST_CRC_ENABLE', +} +CNV_TEST_CRC_DISABLE = 0 +CNV_TEST_CRC_ENABLE = 1 +CNV_TEST_CRC_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNV_TEST_CRC_CONT_EN_ENUM' +CNV_TEST_CRC_CONT_EN_ENUM__enumvalues = { + 0: 'CNV_TEST_CRC_CONT_DISABLE', + 1: 'CNV_TEST_CRC_CONT_ENABLE', +} +CNV_TEST_CRC_CONT_DISABLE = 0 +CNV_TEST_CRC_CONT_ENABLE = 1 +CNV_TEST_CRC_CONT_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WB_SOFT_RESET_ENUM' +WB_SOFT_RESET_ENUM__enumvalues = { + 0: 'WB_SOFT_RESET_NEG', + 1: 'WB_SOFT_RESET_POS', +} +WB_SOFT_RESET_NEG = 0 +WB_SOFT_RESET_POS = 1 +WB_SOFT_RESET_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_GMC_WARM_UP_ENABLE_ENUM' +DWB_GMC_WARM_UP_ENABLE_ENUM__enumvalues = { + 0: 'DWB_GMC_WARM_UP_DISABLE', + 1: 'DWB_GMC_WARM_UP_ENABLE', +} +DWB_GMC_WARM_UP_DISABLE = 0 +DWB_GMC_WARM_UP_ENABLE = 1 +DWB_GMC_WARM_UP_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_MODE_WARMUP_ENUM' +DWB_MODE_WARMUP_ENUM__enumvalues = { + 0: 'DWB_MODE_WARMUP_420', + 1: 'DWB_MODE_WARMUP_444', +} +DWB_MODE_WARMUP_420 = 0 +DWB_MODE_WARMUP_444 = 1 +DWB_MODE_WARMUP_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DATA_DEPTH_WARMUP_ENUM' +DWB_DATA_DEPTH_WARMUP_ENUM__enumvalues = { + 0: 'DWB_DATA_DEPTH_WARMUP_8BPC', + 1: 'DWB_DATA_DEPTH_WARMUP_10BPC', +} +DWB_DATA_DEPTH_WARMUP_8BPC = 0 +DWB_DATA_DEPTH_WARMUP_10BPC = 1 +DWB_DATA_DEPTH_WARMUP_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_TAP_PAIR_IDX_ENUM' +WBSCL_COEF_RAM_TAP_PAIR_IDX_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_TAP_PAIR_IDX0', + 1: 'WBSCL_COEF_RAM_TAP_PAIR_IDX1', + 2: 'WBSCL_COEF_RAM_TAP_PAIR_IDX2', + 3: 'WBSCL_COEF_RAM_TAP_PAIR_IDX3', + 4: 'WBSCL_COEF_RAM_TAP_PAIR_IDX4', + 5: 'WBSCL_COEF_RAM_TAP_PAIR_IDX5', +} +WBSCL_COEF_RAM_TAP_PAIR_IDX0 = 0 +WBSCL_COEF_RAM_TAP_PAIR_IDX1 = 1 +WBSCL_COEF_RAM_TAP_PAIR_IDX2 = 2 +WBSCL_COEF_RAM_TAP_PAIR_IDX3 = 3 +WBSCL_COEF_RAM_TAP_PAIR_IDX4 = 4 +WBSCL_COEF_RAM_TAP_PAIR_IDX5 = 5 +WBSCL_COEF_RAM_TAP_PAIR_IDX_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_PHASE_ENUM' +WBSCL_COEF_RAM_PHASE_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_PHASE0', + 1: 'WBSCL_COEF_RAM_PHASE1', + 2: 'WBSCL_COEF_RAM_PHASE2', + 3: 'WBSCL_COEF_RAM_PHASE3', + 4: 'WBSCL_COEF_RAM_PHASE4', + 5: 'WBSCL_COEF_RAM_PHASE5', + 6: 'WBSCL_COEF_RAM_PHASE6', + 7: 'WBSCL_COEF_RAM_PHASE7', + 8: 'WBSCL_COEF_RAM_PHASE8', +} +WBSCL_COEF_RAM_PHASE0 = 0 +WBSCL_COEF_RAM_PHASE1 = 1 +WBSCL_COEF_RAM_PHASE2 = 2 +WBSCL_COEF_RAM_PHASE3 = 3 +WBSCL_COEF_RAM_PHASE4 = 4 +WBSCL_COEF_RAM_PHASE5 = 5 +WBSCL_COEF_RAM_PHASE6 = 6 +WBSCL_COEF_RAM_PHASE7 = 7 +WBSCL_COEF_RAM_PHASE8 = 8 +WBSCL_COEF_RAM_PHASE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_FILTER_TYPE_ENUM' +WBSCL_COEF_RAM_FILTER_TYPE_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_FILTER_TYPE_VL', + 1: 'WBSCL_COEF_RAM_FILTER_TYPE_VC', + 2: 'WBSCL_COEF_RAM_FILTER_TYPE_HL', + 3: 'WBSCL_COEF_RAM_FILTER_TYPE_HC', +} +WBSCL_COEF_RAM_FILTER_TYPE_VL = 0 +WBSCL_COEF_RAM_FILTER_TYPE_VC = 1 +WBSCL_COEF_RAM_FILTER_TYPE_HL = 2 +WBSCL_COEF_RAM_FILTER_TYPE_HC = 3 +WBSCL_COEF_RAM_FILTER_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_FILTER_TYPE_SEL' +WBSCL_COEF_FILTER_TYPE_SEL__enumvalues = { + 0: 'WBSCL_COEF_LUMA_VERT_FILTER', + 1: 'WBSCL_COEF_CHROMA_VERT_FILTER', + 2: 'WBSCL_COEF_LUMA_HORZ_FILTER', + 3: 'WBSCL_COEF_CHROMA_HORZ_FILTER', +} +WBSCL_COEF_LUMA_VERT_FILTER = 0 +WBSCL_COEF_CHROMA_VERT_FILTER = 1 +WBSCL_COEF_LUMA_HORZ_FILTER = 2 +WBSCL_COEF_CHROMA_HORZ_FILTER = 3 +WBSCL_COEF_FILTER_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_MODE_SEL' +WBSCL_MODE_SEL__enumvalues = { + 0: 'WBSCL_MODE_SCALING_444_BYPASS', + 1: 'WBSCL_MODE_SCALING_444_RGB_ENABLE', + 2: 'WBSCL_MODE_SCALING_444_YCBCR_ENABLE', + 3: 'WBSCL_MODE_SCALING_YCBCR_ENABLE', +} +WBSCL_MODE_SCALING_444_BYPASS = 0 +WBSCL_MODE_SCALING_444_RGB_ENABLE = 1 +WBSCL_MODE_SCALING_444_YCBCR_ENABLE = 2 +WBSCL_MODE_SCALING_YCBCR_ENABLE = 3 +WBSCL_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_PIXEL_DEPTH' +WBSCL_PIXEL_DEPTH__enumvalues = { + 0: 'PIXEL_DEPTH_8BPC', + 1: 'PIXEL_DEPTH_10BPC', +} +PIXEL_DEPTH_8BPC = 0 +PIXEL_DEPTH_10BPC = 1 +WBSCL_PIXEL_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_SEL_ENUM' +WBSCL_COEF_RAM_SEL_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_SEL_0', + 1: 'WBSCL_COEF_RAM_SEL_1', +} +WBSCL_COEF_RAM_SEL_0 = 0 +WBSCL_COEF_RAM_SEL_1 = 1 +WBSCL_COEF_RAM_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_RD_SEL_ENUM' +WBSCL_COEF_RAM_RD_SEL_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_RD_SEL_0', + 1: 'WBSCL_COEF_RAM_RD_SEL_1', +} +WBSCL_COEF_RAM_RD_SEL_0 = 0 +WBSCL_COEF_RAM_RD_SEL_1 = 1 +WBSCL_COEF_RAM_RD_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_COEF_RAM_TAP_COEF_EN_ENUM' +WBSCL_COEF_RAM_TAP_COEF_EN_ENUM__enumvalues = { + 0: 'WBSCL_COEF_RAM_TAP_COEF_DISABLE', + 1: 'WBSCL_COEF_RAM_TAP_COEF_ENABLE', +} +WBSCL_COEF_RAM_TAP_COEF_DISABLE = 0 +WBSCL_COEF_RAM_TAP_COEF_ENABLE = 1 +WBSCL_COEF_RAM_TAP_COEF_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_NUM_OF_TAPS_ENUM' +WBSCL_NUM_OF_TAPS_ENUM__enumvalues = { + 0: 'WBSCL_NUM_OF_TAPS0', + 1: 'WBSCL_NUM_OF_TAPS1', + 2: 'WBSCL_NUM_OF_TAPS2', + 3: 'WBSCL_NUM_OF_TAPS3', + 4: 'WBSCL_NUM_OF_TAPS4', + 5: 'WBSCL_NUM_OF_TAPS5', + 6: 'WBSCL_NUM_OF_TAPS6', + 7: 'WBSCL_NUM_OF_TAPS7', + 8: 'WBSCL_NUM_OF_TAPS8', + 9: 'WBSCL_NUM_OF_TAPS9', + 10: 'WBSCL_NUM_OF_TAPS10', + 11: 'WBSCL_NUM_OF_TAPS11', +} +WBSCL_NUM_OF_TAPS0 = 0 +WBSCL_NUM_OF_TAPS1 = 1 +WBSCL_NUM_OF_TAPS2 = 2 +WBSCL_NUM_OF_TAPS3 = 3 +WBSCL_NUM_OF_TAPS4 = 4 +WBSCL_NUM_OF_TAPS5 = 5 +WBSCL_NUM_OF_TAPS6 = 6 +WBSCL_NUM_OF_TAPS7 = 7 +WBSCL_NUM_OF_TAPS8 = 8 +WBSCL_NUM_OF_TAPS9 = 9 +WBSCL_NUM_OF_TAPS10 = 10 +WBSCL_NUM_OF_TAPS11 = 11 +WBSCL_NUM_OF_TAPS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_STATUS_ACK_ENUM' +WBSCL_STATUS_ACK_ENUM__enumvalues = { + 0: 'WBSCL_STATUS_ACK_NCLR', + 1: 'WBSCL_STATUS_ACK_CLR', +} +WBSCL_STATUS_ACK_NCLR = 0 +WBSCL_STATUS_ACK_CLR = 1 +WBSCL_STATUS_ACK_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_STATUS_MASK_ENUM' +WBSCL_STATUS_MASK_ENUM__enumvalues = { + 0: 'WBSCL_STATUS_MASK_DISABLE', + 1: 'WBSCL_STATUS_MASK_ENABLE', +} +WBSCL_STATUS_MASK_DISABLE = 0 +WBSCL_STATUS_MASK_ENABLE = 1 +WBSCL_STATUS_MASK_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_DATA_OVERFLOW_INT_TYPE_ENUM' +WBSCL_DATA_OVERFLOW_INT_TYPE_ENUM__enumvalues = { + 0: 'WBSCL_DATA_OVERFLOW_INT_TYPE_REG', + 1: 'WBSCL_DATA_OVERFLOW_INT_TYPE_HW', +} +WBSCL_DATA_OVERFLOW_INT_TYPE_REG = 0 +WBSCL_DATA_OVERFLOW_INT_TYPE_HW = 1 +WBSCL_DATA_OVERFLOW_INT_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_HOST_CONFLICT_INT_TYPE_ENUM' +WBSCL_HOST_CONFLICT_INT_TYPE_ENUM__enumvalues = { + 0: 'WBSCL_HOST_CONFLICT_INT_TYPE_REG', + 1: 'WBSCL_HOST_CONFLICT_INT_TYPE_HW', +} +WBSCL_HOST_CONFLICT_INT_TYPE_REG = 0 +WBSCL_HOST_CONFLICT_INT_TYPE_HW = 1 +WBSCL_HOST_CONFLICT_INT_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_TEST_CRC_EN_ENUM' +WBSCL_TEST_CRC_EN_ENUM__enumvalues = { + 0: 'WBSCL_TEST_CRC_DISABLE', + 1: 'WBSCL_TEST_CRC_ENABLE', +} +WBSCL_TEST_CRC_DISABLE = 0 +WBSCL_TEST_CRC_ENABLE = 1 +WBSCL_TEST_CRC_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_TEST_CRC_CONT_EN_ENUM' +WBSCL_TEST_CRC_CONT_EN_ENUM__enumvalues = { + 0: 'WBSCL_TEST_CRC_CONT_DISABLE', + 1: 'WBSCL_TEST_CRC_CONT_ENABLE', +} +WBSCL_TEST_CRC_CONT_DISABLE = 0 +WBSCL_TEST_CRC_CONT_ENABLE = 1 +WBSCL_TEST_CRC_CONT_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_TEST_CRC_MASK_ENUM' +WBSCL_TEST_CRC_MASK_ENUM__enumvalues = { + 0: 'WBSCL_TEST_CRC_MASKED', + 1: 'WBSCL_TEST_CRC_UNMASKED', +} +WBSCL_TEST_CRC_MASKED = 0 +WBSCL_TEST_CRC_UNMASKED = 1 +WBSCL_TEST_CRC_MASK_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_BACKPRESSURE_CNT_EN_ENUM' +WBSCL_BACKPRESSURE_CNT_EN_ENUM__enumvalues = { + 0: 'WBSCL_BACKPRESSURE_CNT_DISABLE', + 1: 'WBSCL_BACKPRESSURE_CNT_ENABLE', +} +WBSCL_BACKPRESSURE_CNT_DISABLE = 0 +WBSCL_BACKPRESSURE_CNT_ENABLE = 1 +WBSCL_BACKPRESSURE_CNT_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'WBSCL_OUTSIDE_PIX_STRATEGY_ENUM' +WBSCL_OUTSIDE_PIX_STRATEGY_ENUM__enumvalues = { + 0: 'WBSCL_OUTSIDE_PIX_STRATEGY_BLACK', + 1: 'WBSCL_OUTSIDE_PIX_STRATEGY_EDGE', +} +WBSCL_OUTSIDE_PIX_STRATEGY_BLACK = 0 +WBSCL_OUTSIDE_PIX_STRATEGY_EDGE = 1 +WBSCL_OUTSIDE_PIX_STRATEGY_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL' +DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL__enumvalues = { + 0: 'DPCSRX_BPHY_PCS_RX0_CLK', + 1: 'DPCSRX_BPHY_PCS_RX1_CLK', + 2: 'DPCSRX_BPHY_PCS_RX2_CLK', + 3: 'DPCSRX_BPHY_PCS_RX3_CLK', +} +DPCSRX_BPHY_PCS_RX0_CLK = 0 +DPCSRX_BPHY_PCS_RX1_CLK = 1 +DPCSRX_BPHY_PCS_RX2_CLK = 2 +DPCSRX_BPHY_PCS_RX3_CLK = 3 +DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSTX_DVI_LINK_MODE' +DPCSTX_DVI_LINK_MODE__enumvalues = { + 0: 'DPCSTX_DVI_LINK_MODE_NORMAL', + 1: 'DPCSTX_DVI_LINK_MODE_DUAL_LINK_MASTER', + 2: 'DPCSTX_DVI_LINK_MODE_DUAL_LINK_SLAVER', +} +DPCSTX_DVI_LINK_MODE_NORMAL = 0 +DPCSTX_DVI_LINK_MODE_DUAL_LINK_MASTER = 1 +DPCSTX_DVI_LINK_MODE_DUAL_LINK_SLAVER = 2 +DPCSTX_DVI_LINK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET__enumvalues = { + 0: 'RDPCS_CBUS_SOFT_RESET_DISABLE', + 1: 'RDPCS_CBUS_SOFT_RESET_ENABLE', +} +RDPCS_CBUS_SOFT_RESET_DISABLE = 0 +RDPCS_CBUS_SOFT_RESET_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET__enumvalues = { + 0: 'RDPCS_SRAM_SRAM_RESET_DISABLE', +} +RDPCS_SRAM_SRAM_RESET_DISABLE = 0 +RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN' +RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN__enumvalues = { + 0: 'RDPCS_TX_FIFO_LANE_DISABLE', + 1: 'RDPCS_TX_FIFO_LANE_ENABLE', +} +RDPCS_TX_FIFO_LANE_DISABLE = 0 +RDPCS_TX_FIFO_LANE_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_FIFO_EN' +RDPCSTX_CNTL_RDPCS_TX_FIFO_EN__enumvalues = { + 0: 'RDPCS_TX_FIFO_DISABLE', + 1: 'RDPCS_TX_FIFO_ENABLE', +} +RDPCS_TX_FIFO_DISABLE = 0 +RDPCS_TX_FIFO_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_FIFO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET__enumvalues = { + 0: 'RDPCS_TX_SOFT_RESET_DISABLE', + 1: 'RDPCS_TX_SOFT_RESET_ENABLE', +} +RDPCS_TX_SOFT_RESET_DISABLE = 0 +RDPCS_TX_SOFT_RESET_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN__enumvalues = { + 0: 'RDPCS_EXT_REFCLK_DISABLE', + 1: 'RDPCS_EXT_REFCLK_ENABLE', +} +RDPCS_EXT_REFCLK_DISABLE = 0 +RDPCS_EXT_REFCLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_TX_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_TX_EN__enumvalues = { + 0: 'RDPCS_EXT_REFCLK_EN_DISABLE', + 1: 'RDPCS_EXT_REFCLK_EN_ENABLE', +} +RDPCS_EXT_REFCLK_EN_DISABLE = 0 +RDPCS_EXT_REFCLK_EN_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_TX_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_GATE_DIS' +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_GATE_DIS__enumvalues = { + 0: 'RDPCS_SYMCLK_DIV2_GATE_ENABLE', + 1: 'RDPCS_SYMCLK_DIV2_GATE_DISABLE', +} +RDPCS_SYMCLK_DIV2_GATE_ENABLE = 0 +RDPCS_SYMCLK_DIV2_GATE_DISABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_EN__enumvalues = { + 0: 'RDPCS_SYMCLK_DIV2_DISABLE', + 1: 'RDPCS_SYMCLK_DIV2_ENABLE', +} +RDPCS_SYMCLK_DIV2_DISABLE = 0 +RDPCS_SYMCLK_DIV2_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_CLOCK_ON' +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_CLOCK_ON__enumvalues = { + 0: 'RDPCS_SYMCLK_DIV2_CLOCK_OFF', + 1: 'RDPCS_SYMCLK_DIV2_CLOCK_ON', +} +RDPCS_SYMCLK_DIV2_CLOCK_OFF = 0 +RDPCS_SYMCLK_DIV2_CLOCK_ON = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS__enumvalues = { + 0: 'RDPCS_SRAMCLK_GATE_ENABLE', + 1: 'RDPCS_SRAMCLK_GATE_DISABLE', +} +RDPCS_SRAMCLK_GATE_ENABLE = 0 +RDPCS_SRAMCLK_GATE_DISABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN__enumvalues = { + 0: 'RDPCS_SRAMCLK_DISABLE', + 1: 'RDPCS_SRAMCLK_ENABLE', +} +RDPCS_SRAMCLK_DISABLE = 0 +RDPCS_SRAMCLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_BYPASS' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_BYPASS__enumvalues = { + 0: 'RDPCS_SRAMCLK_NOT_BYPASS', + 1: 'RDPCS_SRAMCLK_BYPASS', +} +RDPCS_SRAMCLK_NOT_BYPASS = 0 +RDPCS_SRAMCLK_BYPASS = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF', + 1: 'RDPCS_SYMCLK_SRAMCLK_CLOCK_ON', +} +RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF = 0 +RDPCS_SYMCLK_SRAMCLK_CLOCK_ON = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE__enumvalues = { + 0: 'RDPCS_DPALT_DISABLE_TOGGLE_ENABLE', + 1: 'RDPCS_DPALT_DISABLE_TOGGLE_DISABLE', +} +RDPCS_DPALT_DISABLE_TOGGLE_ENABLE = 0 +RDPCS_DPALT_DISABLE_TOGGLE_DISABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE__enumvalues = { + 0: 'RDPCS_DPALT_4LANE_TOGGLE_2LANE', + 1: 'RDPCS_DPALT_4LANE_TOGGLE_4LANE', +} +RDPCS_DPALT_4LANE_TOGGLE_2LANE = 0 +RDPCS_DPALT_4LANE_TOGGLE_4LANE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCS_REG_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCS_REG_FIFO_ERROR_MASK_ENABLE', +} +RDPCS_REG_FIFO_ERROR_MASK_DISABLE = 0 +RDPCS_REG_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 1: 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE', +} +RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE = 0 +RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 1: 'RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE', +} +RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE = 0 +RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCS_TX_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCS_TX_FIFO_ERROR_MASK_ENABLE', +} +RDPCS_TX_FIFO_ERROR_MASK_DISABLE = 0 +RDPCS_TX_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE' +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE__enumvalues = { + 0: 'RDPCS_MEM_PWR_NO_FORCE', + 1: 'RDPCS_MEM_PWR_LIGHT_SLEEP', + 2: 'RDPCS_MEM_PWR_DEEP_SLEEP', + 3: 'RDPCS_MEM_PWR_SHUT_DOWN', +} +RDPCS_MEM_PWR_NO_FORCE = 0 +RDPCS_MEM_PWR_LIGHT_SLEEP = 1 +RDPCS_MEM_PWR_DEEP_SLEEP = 2 +RDPCS_MEM_PWR_SHUT_DOWN = 3 +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE' +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE__enumvalues = { + 0: 'RDPCS_MEM_PWR_PWR_STATE_ON', + 1: 'RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 2: 'RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 3: 'RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN', +} +RDPCS_MEM_PWR_PWR_STATE_ON = 0 +RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP = 1 +RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP = 2 +RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN = 3 +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_MEM_POWER_CTRL2_RDPCS_MEM_POWER_CTRL_POFF' +RDPCSTX_MEM_POWER_CTRL2_RDPCS_MEM_POWER_CTRL_POFF__enumvalues = { + 0: 'RDPCS_MEM_POWER_CTRL_POFF_FOR_NO_PERIPHERY', + 1: 'RDPCS_MEM_POWER_CTRL_POFF_FOR_STANDARD', + 2: 'RDPCS_MEM_POWER_CTRL_POFF_FOR_RM3', + 3: 'RDPCS_MEM_POWER_CTRL_POFF_FOR_SD', +} +RDPCS_MEM_POWER_CTRL_POFF_FOR_NO_PERIPHERY = 0 +RDPCS_MEM_POWER_CTRL_POFF_FOR_STANDARD = 1 +RDPCS_MEM_POWER_CTRL_POFF_FOR_RM3 = 2 +RDPCS_MEM_POWER_CTRL_POFF_FOR_SD = 3 +RDPCSTX_MEM_POWER_CTRL2_RDPCS_MEM_POWER_CTRL_POFF = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE__enumvalues = { + 0: 'RDPCS_PHY_REF_RANGE_0', + 1: 'RDPCS_PHY_REF_RANGE_1', + 2: 'RDPCS_PHY_REF_RANGE_2', + 3: 'RDPCS_PHY_REF_RANGE_3', + 4: 'RDPCS_PHY_REF_RANGE_4', + 5: 'RDPCS_PHY_REF_RANGE_5', + 6: 'RDPCS_PHY_REF_RANGE_6', + 7: 'RDPCS_PHY_REF_RANGE_7', +} +RDPCS_PHY_REF_RANGE_0 = 0 +RDPCS_PHY_REF_RANGE_1 = 1 +RDPCS_PHY_REF_RANGE_2 = 2 +RDPCS_PHY_REF_RANGE_3 = 3 +RDPCS_PHY_REF_RANGE_4 = 4 +RDPCS_PHY_REF_RANGE_5 = 5 +RDPCS_PHY_REF_RANGE_6 = 6 +RDPCS_PHY_REF_RANGE_7 = 7 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL__enumvalues = { + 0: 'RDPCS_PHY_CR_PARA_SEL_JTAG', + 1: 'RDPCS_PHY_CR_PARA_SEL_CR', +} +RDPCS_PHY_CR_PARA_SEL_JTAG = 0 +RDPCS_PHY_CR_PARA_SEL_CR = 1 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL__enumvalues = { + 0: 'RDPCS_PHY_CR_MUX_SEL_FOR_USB', + 1: 'RDPCS_PHY_CR_MUX_SEL_FOR_DC', +} +RDPCS_PHY_CR_MUX_SEL_FOR_USB = 0 +RDPCS_PHY_CR_MUX_SEL_FOR_DC = 1 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE' +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE__enumvalues = { + 0: 'RDPCS_SRAM_INIT_NOT_DONE', + 1: 'RDPCS_SRAM_INIT_DONE', +} +RDPCS_SRAM_INIT_NOT_DONE = 0 +RDPCS_SRAM_INIT_DONE = 1 +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE' +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE__enumvalues = { + 0: 'RDPCS_SRAM_EXT_LD_NOT_DONE', + 1: 'RDPCS_SRAM_EXT_LD_DONE', +} +RDPCS_SRAM_EXT_LD_NOT_DONE = 0 +RDPCS_SRAM_EXT_LD_DONE = 1 +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL' +RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_TERM_CTRL_54', + 1: 'RDPCS_PHY_DP_TX_TERM_CTRL_52', + 2: 'RDPCS_PHY_DP_TX_TERM_CTRL_50', + 3: 'RDPCS_PHY_DP_TX_TERM_CTRL_48', + 4: 'RDPCS_PHY_DP_TX_TERM_CTRL_46', + 5: 'RDPCS_PHY_DP_TX_TERM_CTRL_44', + 6: 'RDPCS_PHY_DP_TX_TERM_CTRL_42', + 7: 'RDPCS_PHY_DP_TX_TERM_CTRL_40', +} +RDPCS_PHY_DP_TX_TERM_CTRL_54 = 0 +RDPCS_PHY_DP_TX_TERM_CTRL_52 = 1 +RDPCS_PHY_DP_TX_TERM_CTRL_50 = 2 +RDPCS_PHY_DP_TX_TERM_CTRL_48 = 3 +RDPCS_PHY_DP_TX_TERM_CTRL_46 = 4 +RDPCS_PHY_DP_TX_TERM_CTRL_44 = 5 +RDPCS_PHY_DP_TX_TERM_CTRL_42 = 6 +RDPCS_PHY_DP_TX_TERM_CTRL_40 = 7 +RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE' +RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE__enumvalues = { + 0: 'RRDPCS_PHY_DP_TX_PSTATE_POWER_UP', + 1: 'RRDPCS_PHY_DP_TX_PSTATE_HOLD', + 2: 'RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF', + 3: 'RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN', +} +RRDPCS_PHY_DP_TX_PSTATE_POWER_UP = 0 +RRDPCS_PHY_DP_TX_PSTATE_HOLD = 1 +RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF = 2 +RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN = 3 +RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_RATE', + 1: 'RDPCS_PHY_DP_TX_RATE_DIV2', + 2: 'RDPCS_PHY_DP_TX_RATE_DIV4', +} +RDPCS_PHY_DP_TX_RATE = 0 +RDPCS_PHY_DP_TX_RATE_DIV2 = 1 +RDPCS_PHY_DP_TX_RATE_DIV4 = 2 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_WIDTH_8', + 1: 'RDPCS_PHY_DP_TX_WIDTH_10', + 2: 'RDPCS_PHY_DP_TX_WIDTH_16', + 3: 'RDPCS_PHY_DP_TX_WIDTH_20', +} +RDPCS_PHY_DP_TX_WIDTH_8 = 0 +RDPCS_PHY_DP_TX_WIDTH_10 = 1 +RDPCS_PHY_DP_TX_WIDTH_16 = 2 +RDPCS_PHY_DP_TX_WIDTH_20 = 3 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT', + 1: 'RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT', +} +RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT = 0 +RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT = 1 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV' +RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV__enumvalues = { + 0: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1', + 1: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2', + 2: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3', + 3: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8', + 4: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16', +} +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1 = 0 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2 = 1 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3 = 2 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8 = 3 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16 = 4 +RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV' +RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV__enumvalues = { + 0: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 1: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 2: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 3: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', +} +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0 = 0 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1 = 1 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2 = 2 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3 = 3 +RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV' +RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV__enumvalues = { + 0: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 1: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2', + 2: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4', + 3: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8', + 4: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3', + 5: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5', + 6: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6', + 7: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10', +} +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV = 0 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2 = 1 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4 = 2 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8 = 3 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3 = 4 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5 = 5 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6 = 6 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10 = 7 +RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TEST_CLK_SEL' +RDPCS_TEST_CLK_SEL__enumvalues = { + 0: 'RDPCS_TEST_CLK_SEL_NONE', + 1: 'RDPCS_TEST_CLK_SEL_CFGCLK', + 2: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 3: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 4: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 5: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 6: 'RDPCS_TEST_CLK_SEL_SRAMCLK', + 7: 'RDPCS_TEST_CLK_SEL_EXT_CR_CLK', + 8: 'RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 9: 'RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 10: 'RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 11: 'RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 12: 'RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 13: 'RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 14: 'RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 15: 'RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk', + 16: 'RDPCS_TEST_CLK_SEL_dtb_out0', + 17: 'RDPCS_TEST_CLK_SEL_dtb_out1', +} +RDPCS_TEST_CLK_SEL_NONE = 0 +RDPCS_TEST_CLK_SEL_CFGCLK = 1 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS = 2 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS = 3 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4 = 4 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4 = 5 +RDPCS_TEST_CLK_SEL_SRAMCLK = 6 +RDPCS_TEST_CLK_SEL_EXT_CR_CLK = 7 +RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK = 8 +RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK = 9 +RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK = 10 +RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK = 11 +RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK = 12 +RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK = 13 +RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK = 14 +RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk = 15 +RDPCS_TEST_CLK_SEL_dtb_out0 = 16 +RDPCS_TEST_CLK_SEL_dtb_out1 = 17 +RDPCS_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CBMode' +CBMode__enumvalues = { + 0: 'CB_DISABLE', + 1: 'CB_NORMAL', + 2: 'CB_ELIMINATE_FAST_CLEAR', + 3: 'CB_RESOLVE', + 4: 'CB_DECOMPRESS', + 5: 'CB_FMASK_DECOMPRESS', + 6: 'CB_DCC_DECOMPRESS', + 7: 'CB_RESERVED', +} +CB_DISABLE = 0 +CB_NORMAL = 1 +CB_ELIMINATE_FAST_CLEAR = 2 +CB_RESOLVE = 3 +CB_DECOMPRESS = 4 +CB_FMASK_DECOMPRESS = 5 +CB_DCC_DECOMPRESS = 6 +CB_RESERVED = 7 +CBMode = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOp' +BlendOp__enumvalues = { + 0: 'BLEND_ZERO', + 1: 'BLEND_ONE', + 2: 'BLEND_SRC_COLOR', + 3: 'BLEND_ONE_MINUS_SRC_COLOR', + 4: 'BLEND_SRC_ALPHA', + 5: 'BLEND_ONE_MINUS_SRC_ALPHA', + 6: 'BLEND_DST_ALPHA', + 7: 'BLEND_ONE_MINUS_DST_ALPHA', + 8: 'BLEND_DST_COLOR', + 9: 'BLEND_ONE_MINUS_DST_COLOR', + 10: 'BLEND_SRC_ALPHA_SATURATE', + 11: 'BLEND_BOTH_SRC_ALPHA', + 12: 'BLEND_BOTH_INV_SRC_ALPHA', + 13: 'BLEND_CONSTANT_COLOR', + 14: 'BLEND_ONE_MINUS_CONSTANT_COLOR', + 15: 'BLEND_SRC1_COLOR', + 16: 'BLEND_INV_SRC1_COLOR', + 17: 'BLEND_SRC1_ALPHA', + 18: 'BLEND_INV_SRC1_ALPHA', + 19: 'BLEND_CONSTANT_ALPHA', + 20: 'BLEND_ONE_MINUS_CONSTANT_ALPHA', +} +BLEND_ZERO = 0 +BLEND_ONE = 1 +BLEND_SRC_COLOR = 2 +BLEND_ONE_MINUS_SRC_COLOR = 3 +BLEND_SRC_ALPHA = 4 +BLEND_ONE_MINUS_SRC_ALPHA = 5 +BLEND_DST_ALPHA = 6 +BLEND_ONE_MINUS_DST_ALPHA = 7 +BLEND_DST_COLOR = 8 +BLEND_ONE_MINUS_DST_COLOR = 9 +BLEND_SRC_ALPHA_SATURATE = 10 +BLEND_BOTH_SRC_ALPHA = 11 +BLEND_BOTH_INV_SRC_ALPHA = 12 +BLEND_CONSTANT_COLOR = 13 +BLEND_ONE_MINUS_CONSTANT_COLOR = 14 +BLEND_SRC1_COLOR = 15 +BLEND_INV_SRC1_COLOR = 16 +BLEND_SRC1_ALPHA = 17 +BLEND_INV_SRC1_ALPHA = 18 +BLEND_CONSTANT_ALPHA = 19 +BLEND_ONE_MINUS_CONSTANT_ALPHA = 20 +BlendOp = ctypes.c_uint32 # enum +GL__ZERO = BLEND_ZERO # macro +GL__ONE = BLEND_ONE # macro +GL__SRC_COLOR = BLEND_SRC_COLOR # macro +GL__ONE_MINUS_SRC_COLOR = BLEND_ONE_MINUS_SRC_COLOR # macro +GL__DST_COLOR = BLEND_DST_COLOR # macro +GL__ONE_MINUS_DST_COLOR = BLEND_ONE_MINUS_DST_COLOR # macro +GL__SRC_ALPHA = BLEND_SRC_ALPHA # macro +GL__ONE_MINUS_SRC_ALPHA = BLEND_ONE_MINUS_SRC_ALPHA # macro +GL__DST_ALPHA = BLEND_DST_ALPHA # macro +GL__ONE_MINUS_DST_ALPHA = BLEND_ONE_MINUS_DST_ALPHA # macro +GL__SRC_ALPHA_SATURATE = BLEND_SRC_ALPHA_SATURATE # macro +GL__CONSTANT_COLOR = BLEND_CONSTANT_COLOR # macro +GL__ONE_MINUS_CONSTANT_COLOR = BLEND_ONE_MINUS_CONSTANT_COLOR # macro +GL__CONSTANT_ALPHA = BLEND_CONSTANT_ALPHA # macro +GL__ONE_MINUS_CONSTANT_ALPHA = BLEND_ONE_MINUS_CONSTANT_ALPHA # macro + +# values for enumeration 'CombFunc' +CombFunc__enumvalues = { + 0: 'COMB_DST_PLUS_SRC', + 1: 'COMB_SRC_MINUS_DST', + 2: 'COMB_MIN_DST_SRC', + 3: 'COMB_MAX_DST_SRC', + 4: 'COMB_DST_MINUS_SRC', +} +COMB_DST_PLUS_SRC = 0 +COMB_SRC_MINUS_DST = 1 +COMB_MIN_DST_SRC = 2 +COMB_MAX_DST_SRC = 3 +COMB_DST_MINUS_SRC = 4 +CombFunc = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOpt' +BlendOpt__enumvalues = { + 0: 'FORCE_OPT_AUTO', + 1: 'FORCE_OPT_DISABLE', + 2: 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 3: 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 4: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 5: 'FORCE_OPT_ENABLE_IF_SRC_A_1', + 6: 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', + 7: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', +} +FORCE_OPT_AUTO = 0 +FORCE_OPT_DISABLE = 1 +FORCE_OPT_ENABLE_IF_SRC_A_0 = 2 +FORCE_OPT_ENABLE_IF_SRC_RGB_0 = 3 +FORCE_OPT_ENABLE_IF_SRC_ARGB_0 = 4 +FORCE_OPT_ENABLE_IF_SRC_A_1 = 5 +FORCE_OPT_ENABLE_IF_SRC_RGB_1 = 6 +FORCE_OPT_ENABLE_IF_SRC_ARGB_1 = 7 +BlendOpt = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskCode' +CmaskCode__enumvalues = { + 0: 'CMASK_CLR00_F0', + 1: 'CMASK_CLR00_F1', + 2: 'CMASK_CLR00_F2', + 3: 'CMASK_CLR00_FX', + 4: 'CMASK_CLR01_F0', + 5: 'CMASK_CLR01_F1', + 6: 'CMASK_CLR01_F2', + 7: 'CMASK_CLR01_FX', + 8: 'CMASK_CLR10_F0', + 9: 'CMASK_CLR10_F1', + 10: 'CMASK_CLR10_F2', + 11: 'CMASK_CLR10_FX', + 12: 'CMASK_CLR11_F0', + 13: 'CMASK_CLR11_F1', + 14: 'CMASK_CLR11_F2', + 15: 'CMASK_CLR11_FX', +} +CMASK_CLR00_F0 = 0 +CMASK_CLR00_F1 = 1 +CMASK_CLR00_F2 = 2 +CMASK_CLR00_FX = 3 +CMASK_CLR01_F0 = 4 +CMASK_CLR01_F1 = 5 +CMASK_CLR01_F2 = 6 +CMASK_CLR01_FX = 7 +CMASK_CLR10_F0 = 8 +CMASK_CLR10_F1 = 9 +CMASK_CLR10_F2 = 10 +CMASK_CLR10_FX = 11 +CMASK_CLR11_F0 = 12 +CMASK_CLR11_F1 = 13 +CMASK_CLR11_F2 = 14 +CMASK_CLR11_FX = 15 +CmaskCode = ctypes.c_uint32 # enum + +# values for enumeration 'MemArbMode' +MemArbMode__enumvalues = { + 0: 'MEM_ARB_MODE_FIXED', + 1: 'MEM_ARB_MODE_AGE', + 2: 'MEM_ARB_MODE_WEIGHT', + 3: 'MEM_ARB_MODE_BOTH', +} +MEM_ARB_MODE_FIXED = 0 +MEM_ARB_MODE_AGE = 1 +MEM_ARB_MODE_WEIGHT = 2 +MEM_ARB_MODE_BOTH = 3 +MemArbMode = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfOpFilterSel' +CBPerfOpFilterSel__enumvalues = { + 0: 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 1: 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 2: 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 3: 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 4: 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 5: 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', +} +CB_PERF_OP_FILTER_SEL_WRITE_ONLY = 0 +CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION = 1 +CB_PERF_OP_FILTER_SEL_RESOLVE = 2 +CB_PERF_OP_FILTER_SEL_DECOMPRESS = 3 +CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS = 4 +CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR = 5 +CBPerfOpFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfClearFilterSel' +CBPerfClearFilterSel__enumvalues = { + 0: 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 1: 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', +} +CB_PERF_CLEAR_FILTER_SEL_NONCLEAR = 0 +CB_PERF_CLEAR_FILTER_SEL_CLEAR = 1 +CBPerfClearFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfSel' +CBPerfSel__enumvalues = { + 0: 'CB_PERF_SEL_NONE', + 1: 'CB_PERF_SEL_BUSY', + 2: 'CB_PERF_SEL_CORE_SCLK_VLD', + 3: 'CB_PERF_SEL_REG_SCLK0_VLD', + 4: 'CB_PERF_SEL_REG_SCLK1_VLD', + 5: 'CB_PERF_SEL_DRAWN_QUAD', + 6: 'CB_PERF_SEL_DRAWN_PIXEL', + 7: 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', + 8: 'CB_PERF_SEL_DRAWN_TILE', + 9: 'CB_PERF_SEL_DB_CB_TILE_VALID_READY', + 10: 'CB_PERF_SEL_DB_CB_TILE_VALID_READYB', + 11: 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READY', + 12: 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB', + 13: 'CB_PERF_SEL_CM_FC_TILE_VALID_READY', + 14: 'CB_PERF_SEL_CM_FC_TILE_VALID_READYB', + 15: 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READY', + 16: 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB', + 17: 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY', + 18: 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB', + 19: 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READY', + 20: 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB', + 21: 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY', + 22: 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB', + 23: 'CB_PERF_SEL_LQUAD_NO_TILE', + 24: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R', + 25: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR', + 26: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR', + 27: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR', + 28: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR', + 29: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR', + 30: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR', + 31: 'CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT', + 32: 'CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID', + 33: 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK', + 34: 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK', + 35: 'CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL', + 36: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY', + 37: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB', + 38: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY', + 39: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB', + 40: 'CB_PERF_SEL_FOP_IN_VALID_READY', + 41: 'CB_PERF_SEL_FOP_IN_VALID_READYB', + 42: 'CB_PERF_SEL_FOP_IN_VALIDB_READY', + 43: 'CB_PERF_SEL_FOP_IN_VALIDB_READYB', + 44: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY', + 45: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB', + 46: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY', + 47: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB', + 48: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY', + 49: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB', + 50: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY', + 51: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB', + 52: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY', + 53: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB', + 54: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY', + 55: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB', + 56: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY', + 57: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB', + 58: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY', + 59: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB', + 60: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY', + 61: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB', + 62: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY', + 63: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB', + 64: 'CB_PERF_SEL_CC_BC_CS_FRAG_VALID', + 65: 'CB_PERF_SEL_CM_CACHE_HIT', + 66: 'CB_PERF_SEL_CM_CACHE_TAG_MISS', + 67: 'CB_PERF_SEL_CM_CACHE_SECTOR_MISS', + 68: 'CB_PERF_SEL_CM_CACHE_REEVICTION_STALL', + 69: 'CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 70: 'CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL', + 71: 'CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 72: 'CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL', + 73: 'CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL', + 74: 'CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL', + 75: 'CB_PERF_SEL_CM_CACHE_STALL', + 76: 'CB_PERF_SEL_CM_CACHE_FLUSH', + 77: 'CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED', + 78: 'CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED', + 79: 'CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED', + 80: 'CB_PERF_SEL_FC_CACHE_HIT', + 81: 'CB_PERF_SEL_FC_CACHE_TAG_MISS', + 82: 'CB_PERF_SEL_FC_CACHE_SECTOR_MISS', + 83: 'CB_PERF_SEL_FC_CACHE_REEVICTION_STALL', + 84: 'CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 85: 'CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL', + 86: 'CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 87: 'CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL', + 88: 'CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL', + 89: 'CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL', + 90: 'CB_PERF_SEL_FC_CACHE_STALL', + 91: 'CB_PERF_SEL_FC_CACHE_FLUSH', + 92: 'CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED', + 93: 'CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED', + 94: 'CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED', + 95: 'CB_PERF_SEL_CC_CACHE_HIT', + 96: 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 97: 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', + 98: 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 99: 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 100: 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 101: 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 102: 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 103: 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 104: 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 105: 'CB_PERF_SEL_CC_CACHE_STALL', + 106: 'CB_PERF_SEL_CC_CACHE_FLUSH', + 107: 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 108: 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 109: 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 110: 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 111: 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY', + 112: 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB', + 113: 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY', + 114: 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB', + 115: 'CB_PERF_SEL_CM_MC_WRITE_REQUEST', + 116: 'CB_PERF_SEL_FC_MC_WRITE_REQUEST', + 117: 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 118: 'CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT', + 119: 'CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT', + 120: 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 121: 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY', + 122: 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB', + 123: 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY', + 124: 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB', + 125: 'CB_PERF_SEL_CM_MC_READ_REQUEST', + 126: 'CB_PERF_SEL_FC_MC_READ_REQUEST', + 127: 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 128: 'CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT', + 129: 'CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT', + 130: 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 131: 'CB_PERF_SEL_CM_TQ_FULL', + 132: 'CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL', + 133: 'CB_PERF_SEL_CM_TQ_FIFO_STUTTER_STALL', + 134: 'CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL', + 135: 'CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL', + 136: 'CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 137: 'CB_PERF_SEL_FC_TILE_STUTTER_STALL', + 138: 'CB_PERF_SEL_FC_QUAD_STUTTER_STALL', + 139: 'CB_PERF_SEL_FC_KEYID_STUTTER_STALL', + 140: 'CB_PERF_SEL_FOP_FMASK_RAW_STALL', + 141: 'CB_PERF_SEL_FOP_FMASK_BYPASS_STALL', + 142: 'CB_PERF_SEL_CC_SF_FULL', + 143: 'CB_PERF_SEL_CC_RB_FULL', + 144: 'CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL', + 145: 'CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL', + 146: 'CB_PERF_SEL_CC_EVENFIFO_STUTTER_STALL', + 147: 'CB_PERF_SEL_CC_ODDFIFO_STUTTER_STALL', + 148: 'CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL', + 149: 'CB_PERF_SEL_EVENT', + 150: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 151: 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 152: 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 153: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 154: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 155: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 156: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 157: 'CB_PERF_SEL_CC_SURFACE_SYNC', + 158: 'CB_PERF_SEL_CMASK_READ_DATA_0xC', + 159: 'CB_PERF_SEL_CMASK_READ_DATA_0xD', + 160: 'CB_PERF_SEL_CMASK_READ_DATA_0xE', + 161: 'CB_PERF_SEL_CMASK_READ_DATA_0xF', + 162: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xC', + 163: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xD', + 164: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xE', + 165: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xF', + 166: 'CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT', + 167: 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 168: 'CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT', + 169: 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE', + 170: 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 171: 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 172: 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 173: 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 174: 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 175: 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 176: 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 177: 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE', + 178: 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE', + 179: 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE', + 180: 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE', + 181: 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE', + 182: 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE', + 183: 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE', + 184: 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE', + 185: 'CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT', + 186: 'CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS', + 187: 'CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS', + 188: 'CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS', + 189: 'CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS', + 190: 'CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS', + 191: 'CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS', + 192: 'CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT', + 193: 'CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS', + 194: 'CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS', + 195: 'CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS', + 196: 'CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS', + 197: 'CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS', + 198: 'CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS', + 199: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_0', + 200: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_1', + 201: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_2', + 202: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_3', + 203: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_4', + 204: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_5', + 205: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_6', + 206: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_7', + 207: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0', + 208: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1', + 209: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2', + 210: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3', + 211: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4', + 212: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5', + 213: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6', + 214: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7', + 215: 'CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST', + 216: 'CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS', + 217: 'CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS', + 218: 'CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 219: 'CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 220: 'CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED', + 221: 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 222: 'CB_PERF_SEL_DRAWN_BUSY', + 223: 'CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY', + 224: 'CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY', + 225: 'CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY', + 226: 'CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY', + 227: 'CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED', + 228: 'CB_PERF_SEL_FC_SEQUENCER_CLEAR', + 229: 'CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR', + 230: 'CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS', + 231: 'CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE', + 232: 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 233: 'CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL', + 234: 'CB_PERF_SEL_FC_DOC_IS_STALLED', + 235: 'CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED', + 236: 'CB_PERF_SEL_FC_DOC_MRTS_COMBINED', + 237: 'CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS', + 238: 'CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT', + 239: 'CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS', + 240: 'CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT', + 241: 'CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL', + 242: 'CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR', + 243: 'CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS', + 244: 'CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS', + 245: 'CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS', + 246: 'CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS', + 247: 'CB_PERF_SEL_FC_DCC_CACHE_HIT', + 248: 'CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS', + 249: 'CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS', + 250: 'CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL', + 251: 'CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 252: 'CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 253: 'CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 254: 'CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL', + 255: 'CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL', + 256: 'CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL', + 257: 'CB_PERF_SEL_FC_DCC_CACHE_STALL', + 258: 'CB_PERF_SEL_FC_DCC_CACHE_FLUSH', + 259: 'CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED', + 260: 'CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED', + 261: 'CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 262: 'CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT', + 263: 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST', + 264: 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT', + 265: 'CB_PERF_SEL_FC_MC_DCC_READ_REQUEST', + 266: 'CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT', + 267: 'CB_PERF_SEL_CC_DCC_RDREQ_STALL', + 268: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN', + 269: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT', + 270: 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN', + 271: 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT', + 272: 'CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR', + 273: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1', + 274: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2', + 275: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 276: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1', + 277: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1', + 278: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2', + 279: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1', + 280: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 281: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 282: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1', + 283: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2', + 284: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2', + 285: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2', + 286: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 287: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1', + 288: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1', + 289: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2', + 290: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3', + 291: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4', + 292: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1', + 293: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2', + 294: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3', + 295: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4', + 296: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1', + 297: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2', + 298: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3', + 299: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4', + 300: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1', + 301: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2', + 302: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3', + 303: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1', + 304: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2', + 305: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3', + 306: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4', + 307: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1', + 308: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2', + 309: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3', + 310: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4', + 311: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1', + 312: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2', + 313: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3', + 314: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4', + 315: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1', + 316: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2', + 317: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3', + 318: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1', + 319: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1', + 320: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1', + 321: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1', + 322: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1', + 323: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1', + 324: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1', + 325: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1', + 326: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2', + 327: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2', + 328: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2', + 329: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2', + 330: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2', + 331: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2', + 332: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2', + 333: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1', + 334: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1', + 335: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1', + 336: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1', + 337: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2', + 338: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2', + 339: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2', + 340: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2', + 341: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 342: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2', + 343: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2', + 344: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 345: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1', + 346: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1', + 347: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1', + 348: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1', + 349: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2', + 350: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3', + 351: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4', + 352: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5', + 353: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6', + 354: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0', + 355: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1', + 356: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1', + 357: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2', + 358: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3', + 359: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4', + 360: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5', + 361: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0', + 362: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1', + 363: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1', + 364: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1', + 365: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1', + 366: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1', + 367: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1', + 368: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1', + 369: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1', + 370: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1', + 371: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2', + 372: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2', + 373: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2', + 374: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2', + 375: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2', + 376: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2', + 377: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2', + 378: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1', + 379: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2', + 380: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3', + 381: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4', + 382: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5', + 383: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6', + 384: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7', + 385: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED', + 386: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1', + 387: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1', + 388: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2', + 389: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3', + 390: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1', + 391: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2', + 392: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3', + 393: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4', + 394: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5', + 395: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1', + 396: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2', + 397: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3', + 398: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4', + 399: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5', + 400: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6', + 401: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7', + 402: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 403: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 404: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 405: 'CB_PERF_SEL_RBP_SPLIT_MICROTILE', + 406: 'CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK', + 407: 'CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK', + 408: 'CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING', + 409: 'CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS', + 410: 'CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD', + 411: 'CB_PERF_SEL_NACK_CM_READ', + 412: 'CB_PERF_SEL_NACK_CM_WRITE', + 413: 'CB_PERF_SEL_NACK_FC_READ', + 414: 'CB_PERF_SEL_NACK_FC_WRITE', + 415: 'CB_PERF_SEL_NACK_DC_READ', + 416: 'CB_PERF_SEL_NACK_DC_WRITE', + 417: 'CB_PERF_SEL_NACK_CC_READ', + 418: 'CB_PERF_SEL_NACK_CC_WRITE', + 419: 'CB_PERF_SEL_CM_MC_EARLY_WRITE_RETURN', + 420: 'CB_PERF_SEL_FC_MC_EARLY_WRITE_RETURN', + 421: 'CB_PERF_SEL_DC_MC_EARLY_WRITE_RETURN', + 422: 'CB_PERF_SEL_CC_MC_EARLY_WRITE_RETURN', + 423: 'CB_PERF_SEL_CM_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 424: 'CB_PERF_SEL_FC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 425: 'CB_PERF_SEL_DC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 426: 'CB_PERF_SEL_CC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 427: 'CB_PERF_SEL_CM_MC_WRITE_ACK64B', + 428: 'CB_PERF_SEL_FC_MC_WRITE_ACK64B', + 429: 'CB_PERF_SEL_DC_MC_WRITE_ACK64B', + 430: 'CB_PERF_SEL_CC_MC_WRITE_ACK64B', + 431: 'CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS', + 432: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_DB_DATA_TS', + 433: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_PIXEL_DATA', + 434: 'CB_PERF_SEL_DB_CB_TILE_TILENOTEVENT', + 435: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32BPP_8PIX', + 436: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_UNSIGNED_8PIX', + 437: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_SIGNED_8PIX', + 438: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_FLOAT_8PIX', + 439: 'CB_PERF_SEL_MERGE_PIXELS_WITH_BLEND_ENABLED', + 440: 'CB_PERF_SEL_DB_CB_CONTEXT_DONE', + 441: 'CB_PERF_SEL_DB_CB_EOP_DONE', + 442: 'CB_PERF_SEL_CC_MC_WRITE_REQUEST_PARTIAL', + 443: 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VLD', +} +CB_PERF_SEL_NONE = 0 +CB_PERF_SEL_BUSY = 1 +CB_PERF_SEL_CORE_SCLK_VLD = 2 +CB_PERF_SEL_REG_SCLK0_VLD = 3 +CB_PERF_SEL_REG_SCLK1_VLD = 4 +CB_PERF_SEL_DRAWN_QUAD = 5 +CB_PERF_SEL_DRAWN_PIXEL = 6 +CB_PERF_SEL_DRAWN_QUAD_FRAGMENT = 7 +CB_PERF_SEL_DRAWN_TILE = 8 +CB_PERF_SEL_DB_CB_TILE_VALID_READY = 9 +CB_PERF_SEL_DB_CB_TILE_VALID_READYB = 10 +CB_PERF_SEL_DB_CB_TILE_VALIDB_READY = 11 +CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB = 12 +CB_PERF_SEL_CM_FC_TILE_VALID_READY = 13 +CB_PERF_SEL_CM_FC_TILE_VALID_READYB = 14 +CB_PERF_SEL_CM_FC_TILE_VALIDB_READY = 15 +CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB = 16 +CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY = 17 +CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB = 18 +CB_PERF_SEL_DB_CB_LQUAD_VALID_READY = 19 +CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB = 20 +CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY = 21 +CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB = 22 +CB_PERF_SEL_LQUAD_NO_TILE = 23 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R = 24 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR = 25 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR = 26 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR = 27 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR = 28 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR = 29 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR = 30 +CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT = 31 +CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID = 32 +CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK = 33 +CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK = 34 +CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL = 35 +CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY = 36 +CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB = 37 +CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY = 38 +CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB = 39 +CB_PERF_SEL_FOP_IN_VALID_READY = 40 +CB_PERF_SEL_FOP_IN_VALID_READYB = 41 +CB_PERF_SEL_FOP_IN_VALIDB_READY = 42 +CB_PERF_SEL_FOP_IN_VALIDB_READYB = 43 +CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY = 44 +CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB = 45 +CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY = 46 +CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB = 47 +CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY = 48 +CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB = 49 +CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY = 50 +CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB = 51 +CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY = 52 +CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB = 53 +CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY = 54 +CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB = 55 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY = 56 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB = 57 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY = 58 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB = 59 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY = 60 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB = 61 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY = 62 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB = 63 +CB_PERF_SEL_CC_BC_CS_FRAG_VALID = 64 +CB_PERF_SEL_CM_CACHE_HIT = 65 +CB_PERF_SEL_CM_CACHE_TAG_MISS = 66 +CB_PERF_SEL_CM_CACHE_SECTOR_MISS = 67 +CB_PERF_SEL_CM_CACHE_REEVICTION_STALL = 68 +CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 69 +CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL = 70 +CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 71 +CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL = 72 +CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL = 73 +CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL = 74 +CB_PERF_SEL_CM_CACHE_STALL = 75 +CB_PERF_SEL_CM_CACHE_FLUSH = 76 +CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED = 77 +CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED = 78 +CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED = 79 +CB_PERF_SEL_FC_CACHE_HIT = 80 +CB_PERF_SEL_FC_CACHE_TAG_MISS = 81 +CB_PERF_SEL_FC_CACHE_SECTOR_MISS = 82 +CB_PERF_SEL_FC_CACHE_REEVICTION_STALL = 83 +CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 84 +CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL = 85 +CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 86 +CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL = 87 +CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL = 88 +CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL = 89 +CB_PERF_SEL_FC_CACHE_STALL = 90 +CB_PERF_SEL_FC_CACHE_FLUSH = 91 +CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED = 92 +CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED = 93 +CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED = 94 +CB_PERF_SEL_CC_CACHE_HIT = 95 +CB_PERF_SEL_CC_CACHE_TAG_MISS = 96 +CB_PERF_SEL_CC_CACHE_SECTOR_MISS = 97 +CB_PERF_SEL_CC_CACHE_REEVICTION_STALL = 98 +CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 99 +CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL = 100 +CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 101 +CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL = 102 +CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL = 103 +CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL = 104 +CB_PERF_SEL_CC_CACHE_STALL = 105 +CB_PERF_SEL_CC_CACHE_FLUSH = 106 +CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED = 107 +CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED = 108 +CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED = 109 +CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION = 110 +CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY = 111 +CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB = 112 +CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY = 113 +CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB = 114 +CB_PERF_SEL_CM_MC_WRITE_REQUEST = 115 +CB_PERF_SEL_FC_MC_WRITE_REQUEST = 116 +CB_PERF_SEL_CC_MC_WRITE_REQUEST = 117 +CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT = 118 +CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT = 119 +CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT = 120 +CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY = 121 +CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB = 122 +CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY = 123 +CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB = 124 +CB_PERF_SEL_CM_MC_READ_REQUEST = 125 +CB_PERF_SEL_FC_MC_READ_REQUEST = 126 +CB_PERF_SEL_CC_MC_READ_REQUEST = 127 +CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT = 128 +CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT = 129 +CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT = 130 +CB_PERF_SEL_CM_TQ_FULL = 131 +CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL = 132 +CB_PERF_SEL_CM_TQ_FIFO_STUTTER_STALL = 133 +CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL = 134 +CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL = 135 +CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL = 136 +CB_PERF_SEL_FC_TILE_STUTTER_STALL = 137 +CB_PERF_SEL_FC_QUAD_STUTTER_STALL = 138 +CB_PERF_SEL_FC_KEYID_STUTTER_STALL = 139 +CB_PERF_SEL_FOP_FMASK_RAW_STALL = 140 +CB_PERF_SEL_FOP_FMASK_BYPASS_STALL = 141 +CB_PERF_SEL_CC_SF_FULL = 142 +CB_PERF_SEL_CC_RB_FULL = 143 +CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL = 144 +CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL = 145 +CB_PERF_SEL_CC_EVENFIFO_STUTTER_STALL = 146 +CB_PERF_SEL_CC_ODDFIFO_STUTTER_STALL = 147 +CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL = 148 +CB_PERF_SEL_EVENT = 149 +CB_PERF_SEL_EVENT_CACHE_FLUSH_TS = 150 +CB_PERF_SEL_EVENT_CONTEXT_DONE = 151 +CB_PERF_SEL_EVENT_CACHE_FLUSH = 152 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT = 153 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT = 154 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS = 155 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META = 156 +CB_PERF_SEL_CC_SURFACE_SYNC = 157 +CB_PERF_SEL_CMASK_READ_DATA_0xC = 158 +CB_PERF_SEL_CMASK_READ_DATA_0xD = 159 +CB_PERF_SEL_CMASK_READ_DATA_0xE = 160 +CB_PERF_SEL_CMASK_READ_DATA_0xF = 161 +CB_PERF_SEL_CMASK_WRITE_DATA_0xC = 162 +CB_PERF_SEL_CMASK_WRITE_DATA_0xD = 163 +CB_PERF_SEL_CMASK_WRITE_DATA_0xE = 164 +CB_PERF_SEL_CMASK_WRITE_DATA_0xF = 165 +CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT = 166 +CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT = 167 +CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT = 168 +CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE = 169 +CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE = 170 +CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE = 171 +CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE = 172 +CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE = 173 +CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE = 174 +CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE = 175 +CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE = 176 +CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE = 177 +CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE = 178 +CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE = 179 +CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE = 180 +CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE = 181 +CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE = 182 +CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE = 183 +CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE = 184 +CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT = 185 +CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS = 186 +CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS = 187 +CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS = 188 +CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS = 189 +CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS = 190 +CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS = 191 +CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT = 192 +CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS = 193 +CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS = 194 +CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS = 195 +CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS = 196 +CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS = 197 +CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS = 198 +CB_PERF_SEL_QUAD_READS_FRAGMENT_0 = 199 +CB_PERF_SEL_QUAD_READS_FRAGMENT_1 = 200 +CB_PERF_SEL_QUAD_READS_FRAGMENT_2 = 201 +CB_PERF_SEL_QUAD_READS_FRAGMENT_3 = 202 +CB_PERF_SEL_QUAD_READS_FRAGMENT_4 = 203 +CB_PERF_SEL_QUAD_READS_FRAGMENT_5 = 204 +CB_PERF_SEL_QUAD_READS_FRAGMENT_6 = 205 +CB_PERF_SEL_QUAD_READS_FRAGMENT_7 = 206 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0 = 207 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1 = 208 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2 = 209 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3 = 210 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4 = 211 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5 = 212 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6 = 213 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7 = 214 +CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST = 215 +CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS = 216 +CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS = 217 +CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED = 218 +CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED = 219 +CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED = 220 +CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST = 221 +CB_PERF_SEL_DRAWN_BUSY = 222 +CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY = 223 +CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY = 224 +CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY = 225 +CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY = 226 +CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED = 227 +CB_PERF_SEL_FC_SEQUENCER_CLEAR = 228 +CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR = 229 +CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS = 230 +CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE = 231 +CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC = 232 +CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL = 233 +CB_PERF_SEL_FC_DOC_IS_STALLED = 234 +CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED = 235 +CB_PERF_SEL_FC_DOC_MRTS_COMBINED = 236 +CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS = 237 +CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT = 238 +CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS = 239 +CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT = 240 +CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL = 241 +CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR = 242 +CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS = 243 +CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS = 244 +CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS = 245 +CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS = 246 +CB_PERF_SEL_FC_DCC_CACHE_HIT = 247 +CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS = 248 +CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS = 249 +CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL = 250 +CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 251 +CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL = 252 +CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 253 +CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL = 254 +CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL = 255 +CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL = 256 +CB_PERF_SEL_FC_DCC_CACHE_STALL = 257 +CB_PERF_SEL_FC_DCC_CACHE_FLUSH = 258 +CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED = 259 +CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED = 260 +CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED = 261 +CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT = 262 +CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST = 263 +CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT = 264 +CB_PERF_SEL_FC_MC_DCC_READ_REQUEST = 265 +CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT = 266 +CB_PERF_SEL_CC_DCC_RDREQ_STALL = 267 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN = 268 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT = 269 +CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN = 270 +CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT = 271 +CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR = 272 +CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1 = 273 +CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2 = 274 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 275 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1 = 276 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1 = 277 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2 = 278 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1 = 279 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 280 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 281 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1 = 282 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2 = 283 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2 = 284 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2 = 285 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 286 +CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1 = 287 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1 = 288 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2 = 289 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3 = 290 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4 = 291 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1 = 292 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2 = 293 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3 = 294 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4 = 295 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1 = 296 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2 = 297 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3 = 298 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4 = 299 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1 = 300 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2 = 301 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3 = 302 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1 = 303 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2 = 304 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3 = 305 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4 = 306 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1 = 307 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2 = 308 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3 = 309 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4 = 310 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1 = 311 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2 = 312 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3 = 313 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4 = 314 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1 = 315 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2 = 316 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3 = 317 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1 = 318 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1 = 319 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1 = 320 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1 = 321 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1 = 322 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1 = 323 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1 = 324 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1 = 325 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2 = 326 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2 = 327 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2 = 328 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2 = 329 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2 = 330 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2 = 331 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2 = 332 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1 = 333 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1 = 334 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1 = 335 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1 = 336 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2 = 337 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2 = 338 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2 = 339 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2 = 340 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 341 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2 = 342 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2 = 343 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 344 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1 = 345 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1 = 346 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1 = 347 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1 = 348 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2 = 349 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3 = 350 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4 = 351 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5 = 352 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6 = 353 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0 = 354 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1 = 355 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1 = 356 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2 = 357 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3 = 358 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4 = 359 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5 = 360 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0 = 361 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1 = 362 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1 = 363 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1 = 364 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1 = 365 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1 = 366 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1 = 367 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1 = 368 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1 = 369 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1 = 370 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2 = 371 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2 = 372 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2 = 373 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2 = 374 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2 = 375 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2 = 376 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2 = 377 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1 = 378 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2 = 379 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3 = 380 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4 = 381 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5 = 382 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6 = 383 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7 = 384 +CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED = 385 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1 = 386 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1 = 387 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2 = 388 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3 = 389 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1 = 390 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2 = 391 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3 = 392 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4 = 393 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5 = 394 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1 = 395 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2 = 396 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3 = 397 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4 = 398 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5 = 399 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6 = 400 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7 = 401 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH = 402 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT = 403 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT = 404 +CB_PERF_SEL_RBP_SPLIT_MICROTILE = 405 +CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK = 406 +CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK = 407 +CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING = 408 +CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS = 409 +CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD = 410 +CB_PERF_SEL_NACK_CM_READ = 411 +CB_PERF_SEL_NACK_CM_WRITE = 412 +CB_PERF_SEL_NACK_FC_READ = 413 +CB_PERF_SEL_NACK_FC_WRITE = 414 +CB_PERF_SEL_NACK_DC_READ = 415 +CB_PERF_SEL_NACK_DC_WRITE = 416 +CB_PERF_SEL_NACK_CC_READ = 417 +CB_PERF_SEL_NACK_CC_WRITE = 418 +CB_PERF_SEL_CM_MC_EARLY_WRITE_RETURN = 419 +CB_PERF_SEL_FC_MC_EARLY_WRITE_RETURN = 420 +CB_PERF_SEL_DC_MC_EARLY_WRITE_RETURN = 421 +CB_PERF_SEL_CC_MC_EARLY_WRITE_RETURN = 422 +CB_PERF_SEL_CM_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT = 423 +CB_PERF_SEL_FC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT = 424 +CB_PERF_SEL_DC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT = 425 +CB_PERF_SEL_CC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT = 426 +CB_PERF_SEL_CM_MC_WRITE_ACK64B = 427 +CB_PERF_SEL_FC_MC_WRITE_ACK64B = 428 +CB_PERF_SEL_DC_MC_WRITE_ACK64B = 429 +CB_PERF_SEL_CC_MC_WRITE_ACK64B = 430 +CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS = 431 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_DB_DATA_TS = 432 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_PIXEL_DATA = 433 +CB_PERF_SEL_DB_CB_TILE_TILENOTEVENT = 434 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32BPP_8PIX = 435 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_UNSIGNED_8PIX = 436 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_SIGNED_8PIX = 437 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_FLOAT_8PIX = 438 +CB_PERF_SEL_MERGE_PIXELS_WITH_BLEND_ENABLED = 439 +CB_PERF_SEL_DB_CB_CONTEXT_DONE = 440 +CB_PERF_SEL_DB_CB_EOP_DONE = 441 +CB_PERF_SEL_CC_MC_WRITE_REQUEST_PARTIAL = 442 +CB_PERF_SEL_CC_BB_BLEND_PIXEL_VLD = 443 +CBPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskAddr' +CmaskAddr__enumvalues = { + 0: 'CMASK_ADDR_TILED', + 1: 'CMASK_ADDR_LINEAR', + 2: 'CMASK_ADDR_COMPATIBLE', +} +CMASK_ADDR_TILED = 0 +CMASK_ADDR_LINEAR = 1 +CMASK_ADDR_COMPATIBLE = 2 +CmaskAddr = ctypes.c_uint32 # enum + +# values for enumeration 'SourceFormat' +SourceFormat__enumvalues = { + 0: 'EXPORT_4C_32BPC', + 1: 'EXPORT_4C_16BPC', + 2: 'EXPORT_2C_32BPC_GR', + 3: 'EXPORT_2C_32BPC_AR', +} +EXPORT_4C_32BPC = 0 +EXPORT_4C_16BPC = 1 +EXPORT_2C_32BPC_GR = 2 +EXPORT_2C_32BPC_AR = 3 +SourceFormat = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP_MASKS' +TC_OP_MASKS__enumvalues = { + 8: 'TC_OP_MASK_FLUSH_DENROM', + 32: 'TC_OP_MASK_64', + 64: 'TC_OP_MASK_NO_RTN', +} +TC_OP_MASK_FLUSH_DENROM = 8 +TC_OP_MASK_64 = 32 +TC_OP_MASK_NO_RTN = 64 +TC_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP' +TC_OP__enumvalues = { + 0: 'TC_OP_READ', + 1: 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'TC_OP_ATOMIC_FMIN_RTN_32', + 3: 'TC_OP_ATOMIC_FMAX_RTN_32', + 4: 'TC_OP_RESERVED_FOP_RTN_32_0', + 5: 'TC_OP_RESERVED_FOP_RTN_32_1', + 6: 'TC_OP_RESERVED_FOP_RTN_32_2', + 7: 'TC_OP_ATOMIC_SWAP_RTN_32', + 8: 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'TC_OP_PROBE_FILTER', + 13: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 14: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'TC_OP_ATOMIC_ADD_RTN_32', + 16: 'TC_OP_ATOMIC_SUB_RTN_32', + 17: 'TC_OP_ATOMIC_SMIN_RTN_32', + 18: 'TC_OP_ATOMIC_UMIN_RTN_32', + 19: 'TC_OP_ATOMIC_SMAX_RTN_32', + 20: 'TC_OP_ATOMIC_UMAX_RTN_32', + 21: 'TC_OP_ATOMIC_AND_RTN_32', + 22: 'TC_OP_ATOMIC_OR_RTN_32', + 23: 'TC_OP_ATOMIC_XOR_RTN_32', + 24: 'TC_OP_ATOMIC_INC_RTN_32', + 25: 'TC_OP_ATOMIC_DEC_RTN_32', + 26: 'TC_OP_WBINVL1_VOL', + 27: 'TC_OP_WBINVL1_SD', + 28: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 29: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 30: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 31: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 32: 'TC_OP_WRITE', + 33: 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'TC_OP_ATOMIC_FMIN_RTN_64', + 35: 'TC_OP_ATOMIC_FMAX_RTN_64', + 36: 'TC_OP_RESERVED_FOP_RTN_64_0', + 37: 'TC_OP_RESERVED_FOP_RTN_64_1', + 38: 'TC_OP_RESERVED_FOP_RTN_64_2', + 39: 'TC_OP_ATOMIC_SWAP_RTN_64', + 40: 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 44: 'TC_OP_WBINVL2_SD', + 45: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 46: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 47: 'TC_OP_ATOMIC_ADD_RTN_64', + 48: 'TC_OP_ATOMIC_SUB_RTN_64', + 49: 'TC_OP_ATOMIC_SMIN_RTN_64', + 50: 'TC_OP_ATOMIC_UMIN_RTN_64', + 51: 'TC_OP_ATOMIC_SMAX_RTN_64', + 52: 'TC_OP_ATOMIC_UMAX_RTN_64', + 53: 'TC_OP_ATOMIC_AND_RTN_64', + 54: 'TC_OP_ATOMIC_OR_RTN_64', + 55: 'TC_OP_ATOMIC_XOR_RTN_64', + 56: 'TC_OP_ATOMIC_INC_RTN_64', + 57: 'TC_OP_ATOMIC_DEC_RTN_64', + 58: 'TC_OP_WBL2_NC', + 59: 'TC_OP_WBL2_WC', + 60: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 61: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 62: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 63: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', + 64: 'TC_OP_WBINVL1', + 65: 'TC_OP_ATOMIC_FCMPSWAP_32', + 66: 'TC_OP_ATOMIC_FMIN_32', + 67: 'TC_OP_ATOMIC_FMAX_32', + 68: 'TC_OP_RESERVED_FOP_32_0', + 69: 'TC_OP_RESERVED_FOP_32_1', + 70: 'TC_OP_RESERVED_FOP_32_2', + 71: 'TC_OP_ATOMIC_SWAP_32', + 72: 'TC_OP_ATOMIC_CMPSWAP_32', + 73: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'TC_OP_INV_METADATA', + 77: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1', + 78: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 79: 'TC_OP_ATOMIC_ADD_32', + 80: 'TC_OP_ATOMIC_SUB_32', + 81: 'TC_OP_ATOMIC_SMIN_32', + 82: 'TC_OP_ATOMIC_UMIN_32', + 83: 'TC_OP_ATOMIC_SMAX_32', + 84: 'TC_OP_ATOMIC_UMAX_32', + 85: 'TC_OP_ATOMIC_AND_32', + 86: 'TC_OP_ATOMIC_OR_32', + 87: 'TC_OP_ATOMIC_XOR_32', + 88: 'TC_OP_ATOMIC_INC_32', + 89: 'TC_OP_ATOMIC_DEC_32', + 90: 'TC_OP_INVL2_NC', + 91: 'TC_OP_NOP_RTN0', + 92: 'TC_OP_RESERVED_NON_FLOAT_32_1', + 93: 'TC_OP_RESERVED_NON_FLOAT_32_2', + 94: 'TC_OP_RESERVED_NON_FLOAT_32_3', + 95: 'TC_OP_RESERVED_NON_FLOAT_32_4', + 96: 'TC_OP_WBINVL2', + 97: 'TC_OP_ATOMIC_FCMPSWAP_64', + 98: 'TC_OP_ATOMIC_FMIN_64', + 99: 'TC_OP_ATOMIC_FMAX_64', + 100: 'TC_OP_RESERVED_FOP_64_0', + 101: 'TC_OP_RESERVED_FOP_64_1', + 102: 'TC_OP_RESERVED_FOP_64_2', + 103: 'TC_OP_ATOMIC_SWAP_64', + 104: 'TC_OP_ATOMIC_CMPSWAP_64', + 105: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 108: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 109: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 110: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 111: 'TC_OP_ATOMIC_ADD_64', + 112: 'TC_OP_ATOMIC_SUB_64', + 113: 'TC_OP_ATOMIC_SMIN_64', + 114: 'TC_OP_ATOMIC_UMIN_64', + 115: 'TC_OP_ATOMIC_SMAX_64', + 116: 'TC_OP_ATOMIC_UMAX_64', + 117: 'TC_OP_ATOMIC_AND_64', + 118: 'TC_OP_ATOMIC_OR_64', + 119: 'TC_OP_ATOMIC_XOR_64', + 120: 'TC_OP_ATOMIC_INC_64', + 121: 'TC_OP_ATOMIC_DEC_64', + 122: 'TC_OP_WBINVL2_NC', + 123: 'TC_OP_NOP_ACK', + 124: 'TC_OP_RESERVED_NON_FLOAT_64_1', + 125: 'TC_OP_RESERVED_NON_FLOAT_64_2', + 126: 'TC_OP_RESERVED_NON_FLOAT_64_3', + 127: 'TC_OP_RESERVED_NON_FLOAT_64_4', +} +TC_OP_READ = 0 +TC_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +TC_OP_ATOMIC_FMIN_RTN_32 = 2 +TC_OP_ATOMIC_FMAX_RTN_32 = 3 +TC_OP_RESERVED_FOP_RTN_32_0 = 4 +TC_OP_RESERVED_FOP_RTN_32_1 = 5 +TC_OP_RESERVED_FOP_RTN_32_2 = 6 +TC_OP_ATOMIC_SWAP_RTN_32 = 7 +TC_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +TC_OP_PROBE_FILTER = 12 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1 = 13 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +TC_OP_ATOMIC_ADD_RTN_32 = 15 +TC_OP_ATOMIC_SUB_RTN_32 = 16 +TC_OP_ATOMIC_SMIN_RTN_32 = 17 +TC_OP_ATOMIC_UMIN_RTN_32 = 18 +TC_OP_ATOMIC_SMAX_RTN_32 = 19 +TC_OP_ATOMIC_UMAX_RTN_32 = 20 +TC_OP_ATOMIC_AND_RTN_32 = 21 +TC_OP_ATOMIC_OR_RTN_32 = 22 +TC_OP_ATOMIC_XOR_RTN_32 = 23 +TC_OP_ATOMIC_INC_RTN_32 = 24 +TC_OP_ATOMIC_DEC_RTN_32 = 25 +TC_OP_WBINVL1_VOL = 26 +TC_OP_WBINVL1_SD = 27 +TC_OP_RESERVED_NON_FLOAT_RTN_32_0 = 28 +TC_OP_RESERVED_NON_FLOAT_RTN_32_1 = 29 +TC_OP_RESERVED_NON_FLOAT_RTN_32_2 = 30 +TC_OP_RESERVED_NON_FLOAT_RTN_32_3 = 31 +TC_OP_WRITE = 32 +TC_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +TC_OP_ATOMIC_FMIN_RTN_64 = 34 +TC_OP_ATOMIC_FMAX_RTN_64 = 35 +TC_OP_RESERVED_FOP_RTN_64_0 = 36 +TC_OP_RESERVED_FOP_RTN_64_1 = 37 +TC_OP_RESERVED_FOP_RTN_64_2 = 38 +TC_OP_ATOMIC_SWAP_RTN_64 = 39 +TC_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +TC_OP_WBINVL2_SD = 44 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0 = 45 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1 = 46 +TC_OP_ATOMIC_ADD_RTN_64 = 47 +TC_OP_ATOMIC_SUB_RTN_64 = 48 +TC_OP_ATOMIC_SMIN_RTN_64 = 49 +TC_OP_ATOMIC_UMIN_RTN_64 = 50 +TC_OP_ATOMIC_SMAX_RTN_64 = 51 +TC_OP_ATOMIC_UMAX_RTN_64 = 52 +TC_OP_ATOMIC_AND_RTN_64 = 53 +TC_OP_ATOMIC_OR_RTN_64 = 54 +TC_OP_ATOMIC_XOR_RTN_64 = 55 +TC_OP_ATOMIC_INC_RTN_64 = 56 +TC_OP_ATOMIC_DEC_RTN_64 = 57 +TC_OP_WBL2_NC = 58 +TC_OP_WBL2_WC = 59 +TC_OP_RESERVED_NON_FLOAT_RTN_64_1 = 60 +TC_OP_RESERVED_NON_FLOAT_RTN_64_2 = 61 +TC_OP_RESERVED_NON_FLOAT_RTN_64_3 = 62 +TC_OP_RESERVED_NON_FLOAT_RTN_64_4 = 63 +TC_OP_WBINVL1 = 64 +TC_OP_ATOMIC_FCMPSWAP_32 = 65 +TC_OP_ATOMIC_FMIN_32 = 66 +TC_OP_ATOMIC_FMAX_32 = 67 +TC_OP_RESERVED_FOP_32_0 = 68 +TC_OP_RESERVED_FOP_32_1 = 69 +TC_OP_RESERVED_FOP_32_2 = 70 +TC_OP_ATOMIC_SWAP_32 = 71 +TC_OP_ATOMIC_CMPSWAP_32 = 72 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +TC_OP_INV_METADATA = 76 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1 = 77 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2 = 78 +TC_OP_ATOMIC_ADD_32 = 79 +TC_OP_ATOMIC_SUB_32 = 80 +TC_OP_ATOMIC_SMIN_32 = 81 +TC_OP_ATOMIC_UMIN_32 = 82 +TC_OP_ATOMIC_SMAX_32 = 83 +TC_OP_ATOMIC_UMAX_32 = 84 +TC_OP_ATOMIC_AND_32 = 85 +TC_OP_ATOMIC_OR_32 = 86 +TC_OP_ATOMIC_XOR_32 = 87 +TC_OP_ATOMIC_INC_32 = 88 +TC_OP_ATOMIC_DEC_32 = 89 +TC_OP_INVL2_NC = 90 +TC_OP_NOP_RTN0 = 91 +TC_OP_RESERVED_NON_FLOAT_32_1 = 92 +TC_OP_RESERVED_NON_FLOAT_32_2 = 93 +TC_OP_RESERVED_NON_FLOAT_32_3 = 94 +TC_OP_RESERVED_NON_FLOAT_32_4 = 95 +TC_OP_WBINVL2 = 96 +TC_OP_ATOMIC_FCMPSWAP_64 = 97 +TC_OP_ATOMIC_FMIN_64 = 98 +TC_OP_ATOMIC_FMAX_64 = 99 +TC_OP_RESERVED_FOP_64_0 = 100 +TC_OP_RESERVED_FOP_64_1 = 101 +TC_OP_RESERVED_FOP_64_2 = 102 +TC_OP_ATOMIC_SWAP_64 = 103 +TC_OP_ATOMIC_CMPSWAP_64 = 104 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0 = 108 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1 = 109 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2 = 110 +TC_OP_ATOMIC_ADD_64 = 111 +TC_OP_ATOMIC_SUB_64 = 112 +TC_OP_ATOMIC_SMIN_64 = 113 +TC_OP_ATOMIC_UMIN_64 = 114 +TC_OP_ATOMIC_SMAX_64 = 115 +TC_OP_ATOMIC_UMAX_64 = 116 +TC_OP_ATOMIC_AND_64 = 117 +TC_OP_ATOMIC_OR_64 = 118 +TC_OP_ATOMIC_XOR_64 = 119 +TC_OP_ATOMIC_INC_64 = 120 +TC_OP_ATOMIC_DEC_64 = 121 +TC_OP_WBINVL2_NC = 122 +TC_OP_NOP_ACK = 123 +TC_OP_RESERVED_NON_FLOAT_64_1 = 124 +TC_OP_RESERVED_NON_FLOAT_64_2 = 125 +TC_OP_RESERVED_NON_FLOAT_64_3 = 126 +TC_OP_RESERVED_NON_FLOAT_64_4 = 127 +TC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'TC_NACKS' +TC_NACKS__enumvalues = { + 0: 'TC_NACK_NO_FAULT', + 1: 'TC_NACK_PAGE_FAULT', + 2: 'TC_NACK_PROTECTION_FAULT', + 3: 'TC_NACK_DATA_ERROR', +} +TC_NACK_NO_FAULT = 0 +TC_NACK_PAGE_FAULT = 1 +TC_NACK_PROTECTION_FAULT = 2 +TC_NACK_DATA_ERROR = 3 +TC_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_EA_CID' +TC_EA_CID__enumvalues = { + 0: 'TC_EA_CID_RT', + 1: 'TC_EA_CID_FMASK', + 2: 'TC_EA_CID_DCC', + 3: 'TC_EA_CID_TCPMETA', + 4: 'TC_EA_CID_Z', + 5: 'TC_EA_CID_STENCIL', + 6: 'TC_EA_CID_HTILE', + 7: 'TC_EA_CID_MISC', + 8: 'TC_EA_CID_TCP', + 9: 'TC_EA_CID_SQC', + 10: 'TC_EA_CID_CPF', + 11: 'TC_EA_CID_CPG', + 12: 'TC_EA_CID_IA', + 13: 'TC_EA_CID_WD', + 14: 'TC_EA_CID_PA', + 15: 'TC_EA_CID_UTCL2_TPI', +} +TC_EA_CID_RT = 0 +TC_EA_CID_FMASK = 1 +TC_EA_CID_DCC = 2 +TC_EA_CID_TCPMETA = 3 +TC_EA_CID_Z = 4 +TC_EA_CID_STENCIL = 5 +TC_EA_CID_HTILE = 6 +TC_EA_CID_MISC = 7 +TC_EA_CID_TCP = 8 +TC_EA_CID_SQC = 9 +TC_EA_CID_CPF = 10 +TC_EA_CID_CPG = 11 +TC_EA_CID_IA = 12 +TC_EA_CID_WD = 13 +TC_EA_CID_PA = 14 +TC_EA_CID_UTCL2_TPI = 15 +TC_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP_MASKS' +GL2_OP_MASKS__enumvalues = { + 8: 'GL2_OP_MASK_FLUSH_DENROM', + 32: 'GL2_OP_MASK_64', + 64: 'GL2_OP_MASK_NO_RTN', +} +GL2_OP_MASK_FLUSH_DENROM = 8 +GL2_OP_MASK_64 = 32 +GL2_OP_MASK_NO_RTN = 64 +GL2_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP' +GL2_OP__enumvalues = { + 0: 'GL2_OP_READ', + 1: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'GL2_OP_ATOMIC_FMIN_RTN_32', + 3: 'GL2_OP_ATOMIC_FMAX_RTN_32', + 7: 'GL2_OP_ATOMIC_SWAP_RTN_32', + 8: 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'GL2_OP_PROBE_FILTER', + 13: 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 14: 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'GL2_OP_ATOMIC_ADD_RTN_32', + 16: 'GL2_OP_ATOMIC_SUB_RTN_32', + 17: 'GL2_OP_ATOMIC_SMIN_RTN_32', + 18: 'GL2_OP_ATOMIC_UMIN_RTN_32', + 19: 'GL2_OP_ATOMIC_SMAX_RTN_32', + 20: 'GL2_OP_ATOMIC_UMAX_RTN_32', + 21: 'GL2_OP_ATOMIC_AND_RTN_32', + 22: 'GL2_OP_ATOMIC_OR_RTN_32', + 23: 'GL2_OP_ATOMIC_XOR_RTN_32', + 24: 'GL2_OP_ATOMIC_INC_RTN_32', + 25: 'GL2_OP_ATOMIC_DEC_RTN_32', + 32: 'GL2_OP_WRITE', + 33: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'GL2_OP_ATOMIC_FMIN_RTN_64', + 35: 'GL2_OP_ATOMIC_FMAX_RTN_64', + 39: 'GL2_OP_ATOMIC_SWAP_RTN_64', + 40: 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 47: 'GL2_OP_ATOMIC_ADD_RTN_64', + 48: 'GL2_OP_ATOMIC_SUB_RTN_64', + 49: 'GL2_OP_ATOMIC_SMIN_RTN_64', + 50: 'GL2_OP_ATOMIC_UMIN_RTN_64', + 51: 'GL2_OP_ATOMIC_SMAX_RTN_64', + 52: 'GL2_OP_ATOMIC_UMAX_RTN_64', + 53: 'GL2_OP_ATOMIC_AND_RTN_64', + 54: 'GL2_OP_ATOMIC_OR_RTN_64', + 55: 'GL2_OP_ATOMIC_XOR_RTN_64', + 56: 'GL2_OP_ATOMIC_INC_RTN_64', + 57: 'GL2_OP_ATOMIC_DEC_RTN_64', + 64: 'GL2_OP_GL1_INV', + 65: 'GL2_OP_ATOMIC_FCMPSWAP_32', + 66: 'GL2_OP_ATOMIC_FMIN_32', + 67: 'GL2_OP_ATOMIC_FMAX_32', + 71: 'GL2_OP_ATOMIC_SWAP_32', + 72: 'GL2_OP_ATOMIC_CMPSWAP_32', + 73: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 79: 'GL2_OP_ATOMIC_ADD_32', + 80: 'GL2_OP_ATOMIC_SUB_32', + 81: 'GL2_OP_ATOMIC_SMIN_32', + 82: 'GL2_OP_ATOMIC_UMIN_32', + 83: 'GL2_OP_ATOMIC_SMAX_32', + 84: 'GL2_OP_ATOMIC_UMAX_32', + 85: 'GL2_OP_ATOMIC_AND_32', + 86: 'GL2_OP_ATOMIC_OR_32', + 87: 'GL2_OP_ATOMIC_XOR_32', + 88: 'GL2_OP_ATOMIC_INC_32', + 89: 'GL2_OP_ATOMIC_DEC_32', + 91: 'GL2_OP_NOP_RTN0', + 97: 'GL2_OP_ATOMIC_FCMPSWAP_64', + 98: 'GL2_OP_ATOMIC_FMIN_64', + 99: 'GL2_OP_ATOMIC_FMAX_64', + 103: 'GL2_OP_ATOMIC_SWAP_64', + 104: 'GL2_OP_ATOMIC_CMPSWAP_64', + 105: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 111: 'GL2_OP_ATOMIC_ADD_64', + 112: 'GL2_OP_ATOMIC_SUB_64', + 113: 'GL2_OP_ATOMIC_SMIN_64', + 114: 'GL2_OP_ATOMIC_UMIN_64', + 115: 'GL2_OP_ATOMIC_SMAX_64', + 116: 'GL2_OP_ATOMIC_UMAX_64', + 117: 'GL2_OP_ATOMIC_AND_64', + 118: 'GL2_OP_ATOMIC_OR_64', + 119: 'GL2_OP_ATOMIC_XOR_64', + 120: 'GL2_OP_ATOMIC_INC_64', + 121: 'GL2_OP_ATOMIC_DEC_64', + 123: 'GL2_OP_NOP_ACK', +} +GL2_OP_READ = 0 +GL2_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +GL2_OP_ATOMIC_FMIN_RTN_32 = 2 +GL2_OP_ATOMIC_FMAX_RTN_32 = 3 +GL2_OP_ATOMIC_SWAP_RTN_32 = 7 +GL2_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +GL2_OP_PROBE_FILTER = 12 +GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1 = 13 +GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +GL2_OP_ATOMIC_ADD_RTN_32 = 15 +GL2_OP_ATOMIC_SUB_RTN_32 = 16 +GL2_OP_ATOMIC_SMIN_RTN_32 = 17 +GL2_OP_ATOMIC_UMIN_RTN_32 = 18 +GL2_OP_ATOMIC_SMAX_RTN_32 = 19 +GL2_OP_ATOMIC_UMAX_RTN_32 = 20 +GL2_OP_ATOMIC_AND_RTN_32 = 21 +GL2_OP_ATOMIC_OR_RTN_32 = 22 +GL2_OP_ATOMIC_XOR_RTN_32 = 23 +GL2_OP_ATOMIC_INC_RTN_32 = 24 +GL2_OP_ATOMIC_DEC_RTN_32 = 25 +GL2_OP_WRITE = 32 +GL2_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +GL2_OP_ATOMIC_FMIN_RTN_64 = 34 +GL2_OP_ATOMIC_FMAX_RTN_64 = 35 +GL2_OP_ATOMIC_SWAP_RTN_64 = 39 +GL2_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +GL2_OP_ATOMIC_ADD_RTN_64 = 47 +GL2_OP_ATOMIC_SUB_RTN_64 = 48 +GL2_OP_ATOMIC_SMIN_RTN_64 = 49 +GL2_OP_ATOMIC_UMIN_RTN_64 = 50 +GL2_OP_ATOMIC_SMAX_RTN_64 = 51 +GL2_OP_ATOMIC_UMAX_RTN_64 = 52 +GL2_OP_ATOMIC_AND_RTN_64 = 53 +GL2_OP_ATOMIC_OR_RTN_64 = 54 +GL2_OP_ATOMIC_XOR_RTN_64 = 55 +GL2_OP_ATOMIC_INC_RTN_64 = 56 +GL2_OP_ATOMIC_DEC_RTN_64 = 57 +GL2_OP_GL1_INV = 64 +GL2_OP_ATOMIC_FCMPSWAP_32 = 65 +GL2_OP_ATOMIC_FMIN_32 = 66 +GL2_OP_ATOMIC_FMAX_32 = 67 +GL2_OP_ATOMIC_SWAP_32 = 71 +GL2_OP_ATOMIC_CMPSWAP_32 = 72 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +GL2_OP_ATOMIC_ADD_32 = 79 +GL2_OP_ATOMIC_SUB_32 = 80 +GL2_OP_ATOMIC_SMIN_32 = 81 +GL2_OP_ATOMIC_UMIN_32 = 82 +GL2_OP_ATOMIC_SMAX_32 = 83 +GL2_OP_ATOMIC_UMAX_32 = 84 +GL2_OP_ATOMIC_AND_32 = 85 +GL2_OP_ATOMIC_OR_32 = 86 +GL2_OP_ATOMIC_XOR_32 = 87 +GL2_OP_ATOMIC_INC_32 = 88 +GL2_OP_ATOMIC_DEC_32 = 89 +GL2_OP_NOP_RTN0 = 91 +GL2_OP_ATOMIC_FCMPSWAP_64 = 97 +GL2_OP_ATOMIC_FMIN_64 = 98 +GL2_OP_ATOMIC_FMAX_64 = 99 +GL2_OP_ATOMIC_SWAP_64 = 103 +GL2_OP_ATOMIC_CMPSWAP_64 = 104 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +GL2_OP_ATOMIC_ADD_64 = 111 +GL2_OP_ATOMIC_SUB_64 = 112 +GL2_OP_ATOMIC_SMIN_64 = 113 +GL2_OP_ATOMIC_UMIN_64 = 114 +GL2_OP_ATOMIC_SMAX_64 = 115 +GL2_OP_ATOMIC_UMAX_64 = 116 +GL2_OP_ATOMIC_AND_64 = 117 +GL2_OP_ATOMIC_OR_64 = 118 +GL2_OP_ATOMIC_XOR_64 = 119 +GL2_OP_ATOMIC_INC_64 = 120 +GL2_OP_ATOMIC_DEC_64 = 121 +GL2_OP_NOP_ACK = 123 +GL2_OP = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_NACKS' +GL2_NACKS__enumvalues = { + 0: 'GL2_NACK_NO_FAULT', + 1: 'GL2_NACK_PAGE_FAULT', + 2: 'GL2_NACK_PROTECTION_FAULT', + 3: 'GL2_NACK_DATA_ERROR', +} +GL2_NACK_NO_FAULT = 0 +GL2_NACK_PAGE_FAULT = 1 +GL2_NACK_PROTECTION_FAULT = 2 +GL2_NACK_DATA_ERROR = 3 +GL2_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_EA_CID' +GL2_EA_CID__enumvalues = { + 0: 'GL2_EA_CID_CLIENT', + 1: 'GL2_EA_CID_SDMA', + 2: 'GL2_EA_CID_RLC', + 4: 'GL2_EA_CID_CP', + 5: 'GL2_EA_CID_CPDMA', + 6: 'GL2_EA_CID_UTCL2', + 7: 'GL2_EA_CID_RT', + 8: 'GL2_EA_CID_FMASK', + 9: 'GL2_EA_CID_DCC', + 10: 'GL2_EA_CID_Z_STENCIL', + 11: 'GL2_EA_CID_ZPCPSD', + 12: 'GL2_EA_CID_HTILE', + 15: 'GL2_EA_CID_TCPMETA', +} +GL2_EA_CID_CLIENT = 0 +GL2_EA_CID_SDMA = 1 +GL2_EA_CID_RLC = 2 +GL2_EA_CID_CP = 4 +GL2_EA_CID_CPDMA = 5 +GL2_EA_CID_UTCL2 = 6 +GL2_EA_CID_RT = 7 +GL2_EA_CID_FMASK = 8 +GL2_EA_CID_DCC = 9 +GL2_EA_CID_Z_STENCIL = 10 +GL2_EA_CID_ZPCPSD = 11 +GL2_EA_CID_HTILE = 12 +GL2_EA_CID_TCPMETA = 15 +GL2_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SAMPLE_CNTL' +SPI_SAMPLE_CNTL__enumvalues = { + 0: 'CENTROIDS_ONLY', + 1: 'CENTERS_ONLY', + 2: 'CENTROIDS_AND_CENTERS', + 3: 'UNDEF', +} +CENTROIDS_ONLY = 0 +CENTERS_ONLY = 1 +CENTROIDS_AND_CENTERS = 2 +UNDEF = 3 +SPI_SAMPLE_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_FOG_MODE' +SPI_FOG_MODE__enumvalues = { + 0: 'SPI_FOG_NONE', + 1: 'SPI_FOG_EXP', + 2: 'SPI_FOG_EXP2', + 3: 'SPI_FOG_LINEAR', +} +SPI_FOG_NONE = 0 +SPI_FOG_EXP = 1 +SPI_FOG_EXP2 = 2 +SPI_FOG_LINEAR = 3 +SPI_FOG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PNT_SPRITE_OVERRIDE' +SPI_PNT_SPRITE_OVERRIDE__enumvalues = { + 0: 'SPI_PNT_SPRITE_SEL_0', + 1: 'SPI_PNT_SPRITE_SEL_1', + 2: 'SPI_PNT_SPRITE_SEL_S', + 3: 'SPI_PNT_SPRITE_SEL_T', + 4: 'SPI_PNT_SPRITE_SEL_NONE', +} +SPI_PNT_SPRITE_SEL_0 = 0 +SPI_PNT_SPRITE_SEL_1 = 1 +SPI_PNT_SPRITE_SEL_S = 2 +SPI_PNT_SPRITE_SEL_T = 3 +SPI_PNT_SPRITE_SEL_NONE = 4 +SPI_PNT_SPRITE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PERFCNT_SEL' +SPI_PERFCNT_SEL__enumvalues = { + 0: 'SPI_PERF_VS_WINDOW_VALID', + 1: 'SPI_PERF_VS_BUSY', + 2: 'SPI_PERF_VS_FIRST_WAVE', + 3: 'SPI_PERF_VS_LAST_WAVE', + 4: 'SPI_PERF_VS_LSHS_DEALLOC', + 5: 'SPI_PERF_VS_PC_STALL', + 6: 'SPI_PERF_VS_POS0_STALL', + 7: 'SPI_PERF_VS_POS1_STALL', + 8: 'SPI_PERF_VS_CRAWLER_STALL', + 9: 'SPI_PERF_VS_EVENT_WAVE', + 10: 'SPI_PERF_VS_WAVE', + 11: 'SPI_PERF_VS_PERS_UPD_FULL0', + 12: 'SPI_PERF_VS_PERS_UPD_FULL1', + 13: 'SPI_PERF_VS_LATE_ALLOC_FULL', + 14: 'SPI_PERF_VS_FIRST_SUBGRP', + 15: 'SPI_PERF_VS_LAST_SUBGRP', + 16: 'SPI_PERF_VS_ALLOC_CNT', + 17: 'SPI_PERF_VS_PC_ALLOC_CNT', + 18: 'SPI_PERF_VS_LATE_ALLOC_ACCUM', + 19: 'SPI_PERF_GS_WINDOW_VALID', + 20: 'SPI_PERF_GS_BUSY', + 21: 'SPI_PERF_GS_CRAWLER_STALL', + 22: 'SPI_PERF_GS_EVENT_WAVE', + 23: 'SPI_PERF_GS_WAVE', + 24: 'SPI_PERF_GS_PERS_UPD_FULL0', + 25: 'SPI_PERF_GS_PERS_UPD_FULL1', + 26: 'SPI_PERF_GS_FIRST_SUBGRP', + 27: 'SPI_PERF_GS_LAST_SUBGRP', + 28: 'SPI_PERF_GS_HS_DEALLOC', + 29: 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 30: 'SPI_PERF_GS_GRP_FIFO_FULL', + 31: 'SPI_PERF_HS_WINDOW_VALID', + 32: 'SPI_PERF_HS_BUSY', + 33: 'SPI_PERF_HS_CRAWLER_STALL', + 34: 'SPI_PERF_HS_FIRST_WAVE', + 35: 'SPI_PERF_HS_LAST_WAVE', + 36: 'SPI_PERF_HS_OFFCHIP_LDS_STALL', + 37: 'SPI_PERF_HS_EVENT_WAVE', + 38: 'SPI_PERF_HS_WAVE', + 39: 'SPI_PERF_HS_PERS_UPD_FULL0', + 40: 'SPI_PERF_HS_PERS_UPD_FULL1', + 41: 'SPI_PERF_CSG_WINDOW_VALID', + 42: 'SPI_PERF_CSG_BUSY', + 43: 'SPI_PERF_CSG_NUM_THREADGROUPS', + 44: 'SPI_PERF_CSG_CRAWLER_STALL', + 45: 'SPI_PERF_CSG_EVENT_WAVE', + 46: 'SPI_PERF_CSG_WAVE', + 47: 'SPI_PERF_CSN_WINDOW_VALID', + 48: 'SPI_PERF_CSN_BUSY', + 49: 'SPI_PERF_CSN_NUM_THREADGROUPS', + 50: 'SPI_PERF_CSN_CRAWLER_STALL', + 51: 'SPI_PERF_CSN_EVENT_WAVE', + 52: 'SPI_PERF_CSN_WAVE', + 53: 'SPI_PERF_PS0_WINDOW_VALID', + 54: 'SPI_PERF_PS1_WINDOW_VALID', + 55: 'SPI_PERF_PS2_WINDOW_VALID', + 56: 'SPI_PERF_PS3_WINDOW_VALID', + 57: 'SPI_PERF_PS0_BUSY', + 58: 'SPI_PERF_PS1_BUSY', + 59: 'SPI_PERF_PS2_BUSY', + 60: 'SPI_PERF_PS3_BUSY', + 61: 'SPI_PERF_PS0_ACTIVE', + 62: 'SPI_PERF_PS1_ACTIVE', + 63: 'SPI_PERF_PS2_ACTIVE', + 64: 'SPI_PERF_PS3_ACTIVE', + 65: 'SPI_PERF_PS0_DEALLOC_BIN0', + 66: 'SPI_PERF_PS1_DEALLOC_BIN0', + 67: 'SPI_PERF_PS2_DEALLOC_BIN0', + 68: 'SPI_PERF_PS3_DEALLOC_BIN0', + 69: 'SPI_PERF_PS0_FPOS_BIN1_STALL', + 70: 'SPI_PERF_PS1_FPOS_BIN1_STALL', + 71: 'SPI_PERF_PS2_FPOS_BIN1_STALL', + 72: 'SPI_PERF_PS3_FPOS_BIN1_STALL', + 73: 'SPI_PERF_PS0_EVENT_WAVE', + 74: 'SPI_PERF_PS1_EVENT_WAVE', + 75: 'SPI_PERF_PS2_EVENT_WAVE', + 76: 'SPI_PERF_PS3_EVENT_WAVE', + 77: 'SPI_PERF_PS0_WAVE', + 78: 'SPI_PERF_PS1_WAVE', + 79: 'SPI_PERF_PS2_WAVE', + 80: 'SPI_PERF_PS3_WAVE', + 81: 'SPI_PERF_PS0_OPT_WAVE', + 82: 'SPI_PERF_PS1_OPT_WAVE', + 83: 'SPI_PERF_PS2_OPT_WAVE', + 84: 'SPI_PERF_PS3_OPT_WAVE', + 85: 'SPI_PERF_PS0_PASS_BIN0', + 86: 'SPI_PERF_PS1_PASS_BIN0', + 87: 'SPI_PERF_PS2_PASS_BIN0', + 88: 'SPI_PERF_PS3_PASS_BIN0', + 89: 'SPI_PERF_PS0_PASS_BIN1', + 90: 'SPI_PERF_PS1_PASS_BIN1', + 91: 'SPI_PERF_PS2_PASS_BIN1', + 92: 'SPI_PERF_PS3_PASS_BIN1', + 93: 'SPI_PERF_PS0_FPOS_BIN2', + 94: 'SPI_PERF_PS1_FPOS_BIN2', + 95: 'SPI_PERF_PS2_FPOS_BIN2', + 96: 'SPI_PERF_PS3_FPOS_BIN2', + 97: 'SPI_PERF_PS0_PRIM_BIN0', + 98: 'SPI_PERF_PS1_PRIM_BIN0', + 99: 'SPI_PERF_PS2_PRIM_BIN0', + 100: 'SPI_PERF_PS3_PRIM_BIN0', + 101: 'SPI_PERF_PS0_PRIM_BIN1', + 102: 'SPI_PERF_PS1_PRIM_BIN1', + 103: 'SPI_PERF_PS2_PRIM_BIN1', + 104: 'SPI_PERF_PS3_PRIM_BIN1', + 105: 'SPI_PERF_PS0_CNF_BIN2', + 106: 'SPI_PERF_PS1_CNF_BIN2', + 107: 'SPI_PERF_PS2_CNF_BIN2', + 108: 'SPI_PERF_PS3_CNF_BIN2', + 109: 'SPI_PERF_PS0_CNF_BIN3', + 110: 'SPI_PERF_PS1_CNF_BIN3', + 111: 'SPI_PERF_PS2_CNF_BIN3', + 112: 'SPI_PERF_PS3_CNF_BIN3', + 113: 'SPI_PERF_PS0_CRAWLER_STALL', + 114: 'SPI_PERF_PS1_CRAWLER_STALL', + 115: 'SPI_PERF_PS2_CRAWLER_STALL', + 116: 'SPI_PERF_PS3_CRAWLER_STALL', + 117: 'SPI_PERF_PS0_LDS_RES_FULL', + 118: 'SPI_PERF_PS1_LDS_RES_FULL', + 119: 'SPI_PERF_PS2_LDS_RES_FULL', + 120: 'SPI_PERF_PS3_LDS_RES_FULL', + 121: 'SPI_PERF_PS_PERS_UPD_FULL0', + 122: 'SPI_PERF_PS_PERS_UPD_FULL1', + 123: 'SPI_PERF_PS0_POPS_WAVE_SENT', + 124: 'SPI_PERF_PS1_POPS_WAVE_SENT', + 125: 'SPI_PERF_PS2_POPS_WAVE_SENT', + 126: 'SPI_PERF_PS3_POPS_WAVE_SENT', + 127: 'SPI_PERF_PS0_POPS_WAVE_EXIT', + 128: 'SPI_PERF_PS1_POPS_WAVE_EXIT', + 129: 'SPI_PERF_PS2_POPS_WAVE_EXIT', + 130: 'SPI_PERF_PS3_POPS_WAVE_EXIT', + 131: 'SPI_PERF_LDS0_PC_VALID', + 132: 'SPI_PERF_LDS1_PC_VALID', + 133: 'SPI_PERF_RA_PIPE_REQ_BIN2', + 134: 'SPI_PERF_RA_TASK_REQ_BIN3', + 135: 'SPI_PERF_RA_WR_CTL_FULL', + 136: 'SPI_PERF_RA_REQ_NO_ALLOC', + 137: 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 138: 'SPI_PERF_RA_REQ_NO_ALLOC_VS', + 139: 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 140: 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 141: 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 142: 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', + 143: 'SPI_PERF_RA_RES_STALL_PS', + 144: 'SPI_PERF_RA_RES_STALL_VS', + 145: 'SPI_PERF_RA_RES_STALL_GS', + 146: 'SPI_PERF_RA_RES_STALL_HS', + 147: 'SPI_PERF_RA_RES_STALL_CSG', + 148: 'SPI_PERF_RA_RES_STALL_CSN', + 149: 'SPI_PERF_RA_TMP_STALL_PS', + 150: 'SPI_PERF_RA_TMP_STALL_VS', + 151: 'SPI_PERF_RA_TMP_STALL_GS', + 152: 'SPI_PERF_RA_TMP_STALL_HS', + 153: 'SPI_PERF_RA_TMP_STALL_CSG', + 154: 'SPI_PERF_RA_TMP_STALL_CSN', + 155: 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 156: 'SPI_PERF_RA_WAVE_SIMD_FULL_VS', + 157: 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 158: 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', + 159: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 160: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', + 161: 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 162: 'SPI_PERF_RA_VGPR_SIMD_FULL_VS', + 163: 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 164: 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', + 165: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 166: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', + 167: 'SPI_PERF_RA_SGPR_SIMD_FULL_PS', + 168: 'SPI_PERF_RA_SGPR_SIMD_FULL_VS', + 169: 'SPI_PERF_RA_SGPR_SIMD_FULL_GS', + 170: 'SPI_PERF_RA_SGPR_SIMD_FULL_HS', + 171: 'SPI_PERF_RA_SGPR_SIMD_FULL_CSG', + 172: 'SPI_PERF_RA_SGPR_SIMD_FULL_CSN', + 173: 'SPI_PERF_RA_LDS_CU_FULL_PS', + 174: 'SPI_PERF_RA_LDS_CU_FULL_LS', + 175: 'SPI_PERF_RA_LDS_CU_FULL_ES', + 176: 'SPI_PERF_RA_LDS_CU_FULL_CSG', + 177: 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 178: 'SPI_PERF_RA_BAR_CU_FULL_HS', + 179: 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 180: 'SPI_PERF_RA_BAR_CU_FULL_CSN', + 181: 'SPI_PERF_RA_BULKY_CU_FULL_CSG', + 182: 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 183: 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', + 184: 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 185: 'SPI_PERF_RA_WVLIM_STALL_PS', + 186: 'SPI_PERF_RA_WVLIM_STALL_VS', + 187: 'SPI_PERF_RA_WVLIM_STALL_GS', + 188: 'SPI_PERF_RA_WVLIM_STALL_HS', + 189: 'SPI_PERF_RA_WVLIM_STALL_CSG', + 190: 'SPI_PERF_RA_WVLIM_STALL_CSN', + 191: 'SPI_PERF_RA_VS_LOCK', + 192: 'SPI_PERF_RA_GS_LOCK', + 193: 'SPI_PERF_RA_HS_LOCK', + 194: 'SPI_PERF_RA_CSG_LOCK', + 195: 'SPI_PERF_RA_CSN_LOCK', + 196: 'SPI_PERF_RA_RSV_UPD', + 197: 'SPI_PERF_EXP_ARB_COL_CNT', + 198: 'SPI_PERF_EXP_ARB_PAR_CNT', + 199: 'SPI_PERF_EXP_ARB_POS_CNT', + 200: 'SPI_PERF_EXP_ARB_GDS_CNT', + 201: 'SPI_PERF_NUM_PS_COL_R0_EXPORTS', + 202: 'SPI_PERF_NUM_PS_COL_R1_EXPORTS', + 203: 'SPI_PERF_NUM_VS_POS_R0_EXPORTS', + 204: 'SPI_PERF_NUM_VS_POS_R1_EXPORTS', + 205: 'SPI_PERF_NUM_VS_PARAM_R0_EXPORTS', + 206: 'SPI_PERF_NUM_VS_PARAM_R1_EXPORTS', + 207: 'SPI_PERF_NUM_VS_GDS_R0_EXPORTS', + 208: 'SPI_PERF_NUM_VS_GDS_R1_EXPORTS', + 209: 'SPI_PERF_NUM_EXPGRANT_EXPORTS', + 210: 'SPI_PERF_CLKGATE_BUSY_STALL', + 211: 'SPI_PERF_CLKGATE_ACTIVE_STALL', + 212: 'SPI_PERF_CLKGATE_ALL_CLOCKS_ON', + 213: 'SPI_PERF_CLKGATE_CGTT_DYN_ON', + 214: 'SPI_PERF_CLKGATE_CGTT_REG_ON', + 215: 'SPI_PERF_PIX_ALLOC_PEND_CNT', + 216: 'SPI_PERF_PIX_ALLOC_SCB0_STALL', + 217: 'SPI_PERF_PIX_ALLOC_SCB1_STALL', + 218: 'SPI_PERF_PIX_ALLOC_SCB2_STALL', + 219: 'SPI_PERF_PIX_ALLOC_SCB3_STALL', + 220: 'SPI_PERF_PIX_ALLOC_DB0_STALL', + 221: 'SPI_PERF_PIX_ALLOC_DB1_STALL', + 222: 'SPI_PERF_PIX_ALLOC_DB2_STALL', + 223: 'SPI_PERF_PIX_ALLOC_DB3_STALL', + 224: 'SPI_PERF_PIX_ALLOC_DB4_STALL', + 225: 'SPI_PERF_PIX_ALLOC_DB5_STALL', + 226: 'SPI_PERF_PIX_ALLOC_DB6_STALL', + 227: 'SPI_PERF_PIX_ALLOC_DB7_STALL', + 228: 'SPI_PERF_PC_ALLOC_ACCUM', + 229: 'SPI_PERF_GS_NGG_SE_HAS_BATON', + 230: 'SPI_PERF_GS_NGG_SE_DOES_NOT_HAVE_BATON', + 231: 'SPI_PERF_GS_NGG_SE_FORWARDED_BATON', + 232: 'SPI_PERF_GS_NGG_SE_AT_SYNC_EVENT', + 233: 'SPI_PERF_GS_NGG_SE_SG_ALLOC_PC_SPACE_CNT', + 234: 'SPI_PERF_GS_NGG_SE_DEALLOC_PC_SPACE_CNT', + 235: 'SPI_PERF_GS_NGG_PC_FULL', + 236: 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 237: 'SPI_PERF_GS_NGG_GS_ALLOC_FIFO_EMPTY', + 238: 'SPI_PERF_GSC_VTX_BUSY', + 239: 'SPI_PERF_GSC_VTX_INPUT_STARVED', + 240: 'SPI_PERF_GSC_VTX_VSR_STALL', + 241: 'SPI_PERF_GSC_VTX_VSR_FULL', + 242: 'SPI_PERF_GSC_VTX_CAC_BUSY', + 243: 'SPI_PERF_ESC_VTX_BUSY', + 244: 'SPI_PERF_ESC_VTX_INPUT_STARVED', + 245: 'SPI_PERF_ESC_VTX_VSR_STALL', + 246: 'SPI_PERF_ESC_VTX_VSR_FULL', + 247: 'SPI_PERF_ESC_VTX_CAC_BUSY', + 248: 'SPI_PERF_SWC_PS_WR', + 249: 'SPI_PERF_SWC_VS_WR', + 250: 'SPI_PERF_SWC_GS_WR', + 251: 'SPI_PERF_SWC_HS_WR', + 252: 'SPI_PERF_SWC_CSG_WR', + 253: 'SPI_PERF_SWC_CSC_WR', + 254: 'SPI_PERF_VWC_PS_WR', + 255: 'SPI_PERF_VWC_VS_WR', + 256: 'SPI_PERF_VWC_GS_WR', + 257: 'SPI_PERF_VWC_HS_WR', + 258: 'SPI_PERF_VWC_CSG_WR', + 259: 'SPI_PERF_VWC_CSC_WR', + 260: 'SPI_PERF_ES_WINDOW_VALID', + 261: 'SPI_PERF_ES_BUSY', + 262: 'SPI_PERF_ES_CRAWLER_STALL', + 263: 'SPI_PERF_ES_FIRST_WAVE', + 264: 'SPI_PERF_ES_LAST_WAVE', + 265: 'SPI_PERF_ES_LSHS_DEALLOC', + 266: 'SPI_PERF_ES_EVENT_WAVE', + 267: 'SPI_PERF_ES_WAVE', + 268: 'SPI_PERF_ES_PERS_UPD_FULL0', + 269: 'SPI_PERF_ES_PERS_UPD_FULL1', + 270: 'SPI_PERF_ES_FIRST_SUBGRP', + 271: 'SPI_PERF_ES_LAST_SUBGRP', + 272: 'SPI_PERF_LS_WINDOW_VALID', + 273: 'SPI_PERF_LS_BUSY', + 274: 'SPI_PERF_LS_CRAWLER_STALL', + 275: 'SPI_PERF_LS_FIRST_WAVE', + 276: 'SPI_PERF_LS_LAST_WAVE', + 277: 'SPI_PERF_LS_OFFCHIP_LDS_STALL', + 278: 'SPI_PERF_LS_EVENT_WAVE', + 279: 'SPI_PERF_LS_WAVE', + 280: 'SPI_PERF_LS_PERS_UPD_FULL0', + 281: 'SPI_PERF_LS_PERS_UPD_FULL1', +} +SPI_PERF_VS_WINDOW_VALID = 0 +SPI_PERF_VS_BUSY = 1 +SPI_PERF_VS_FIRST_WAVE = 2 +SPI_PERF_VS_LAST_WAVE = 3 +SPI_PERF_VS_LSHS_DEALLOC = 4 +SPI_PERF_VS_PC_STALL = 5 +SPI_PERF_VS_POS0_STALL = 6 +SPI_PERF_VS_POS1_STALL = 7 +SPI_PERF_VS_CRAWLER_STALL = 8 +SPI_PERF_VS_EVENT_WAVE = 9 +SPI_PERF_VS_WAVE = 10 +SPI_PERF_VS_PERS_UPD_FULL0 = 11 +SPI_PERF_VS_PERS_UPD_FULL1 = 12 +SPI_PERF_VS_LATE_ALLOC_FULL = 13 +SPI_PERF_VS_FIRST_SUBGRP = 14 +SPI_PERF_VS_LAST_SUBGRP = 15 +SPI_PERF_VS_ALLOC_CNT = 16 +SPI_PERF_VS_PC_ALLOC_CNT = 17 +SPI_PERF_VS_LATE_ALLOC_ACCUM = 18 +SPI_PERF_GS_WINDOW_VALID = 19 +SPI_PERF_GS_BUSY = 20 +SPI_PERF_GS_CRAWLER_STALL = 21 +SPI_PERF_GS_EVENT_WAVE = 22 +SPI_PERF_GS_WAVE = 23 +SPI_PERF_GS_PERS_UPD_FULL0 = 24 +SPI_PERF_GS_PERS_UPD_FULL1 = 25 +SPI_PERF_GS_FIRST_SUBGRP = 26 +SPI_PERF_GS_LAST_SUBGRP = 27 +SPI_PERF_GS_HS_DEALLOC = 28 +SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT = 29 +SPI_PERF_GS_GRP_FIFO_FULL = 30 +SPI_PERF_HS_WINDOW_VALID = 31 +SPI_PERF_HS_BUSY = 32 +SPI_PERF_HS_CRAWLER_STALL = 33 +SPI_PERF_HS_FIRST_WAVE = 34 +SPI_PERF_HS_LAST_WAVE = 35 +SPI_PERF_HS_OFFCHIP_LDS_STALL = 36 +SPI_PERF_HS_EVENT_WAVE = 37 +SPI_PERF_HS_WAVE = 38 +SPI_PERF_HS_PERS_UPD_FULL0 = 39 +SPI_PERF_HS_PERS_UPD_FULL1 = 40 +SPI_PERF_CSG_WINDOW_VALID = 41 +SPI_PERF_CSG_BUSY = 42 +SPI_PERF_CSG_NUM_THREADGROUPS = 43 +SPI_PERF_CSG_CRAWLER_STALL = 44 +SPI_PERF_CSG_EVENT_WAVE = 45 +SPI_PERF_CSG_WAVE = 46 +SPI_PERF_CSN_WINDOW_VALID = 47 +SPI_PERF_CSN_BUSY = 48 +SPI_PERF_CSN_NUM_THREADGROUPS = 49 +SPI_PERF_CSN_CRAWLER_STALL = 50 +SPI_PERF_CSN_EVENT_WAVE = 51 +SPI_PERF_CSN_WAVE = 52 +SPI_PERF_PS0_WINDOW_VALID = 53 +SPI_PERF_PS1_WINDOW_VALID = 54 +SPI_PERF_PS2_WINDOW_VALID = 55 +SPI_PERF_PS3_WINDOW_VALID = 56 +SPI_PERF_PS0_BUSY = 57 +SPI_PERF_PS1_BUSY = 58 +SPI_PERF_PS2_BUSY = 59 +SPI_PERF_PS3_BUSY = 60 +SPI_PERF_PS0_ACTIVE = 61 +SPI_PERF_PS1_ACTIVE = 62 +SPI_PERF_PS2_ACTIVE = 63 +SPI_PERF_PS3_ACTIVE = 64 +SPI_PERF_PS0_DEALLOC_BIN0 = 65 +SPI_PERF_PS1_DEALLOC_BIN0 = 66 +SPI_PERF_PS2_DEALLOC_BIN0 = 67 +SPI_PERF_PS3_DEALLOC_BIN0 = 68 +SPI_PERF_PS0_FPOS_BIN1_STALL = 69 +SPI_PERF_PS1_FPOS_BIN1_STALL = 70 +SPI_PERF_PS2_FPOS_BIN1_STALL = 71 +SPI_PERF_PS3_FPOS_BIN1_STALL = 72 +SPI_PERF_PS0_EVENT_WAVE = 73 +SPI_PERF_PS1_EVENT_WAVE = 74 +SPI_PERF_PS2_EVENT_WAVE = 75 +SPI_PERF_PS3_EVENT_WAVE = 76 +SPI_PERF_PS0_WAVE = 77 +SPI_PERF_PS1_WAVE = 78 +SPI_PERF_PS2_WAVE = 79 +SPI_PERF_PS3_WAVE = 80 +SPI_PERF_PS0_OPT_WAVE = 81 +SPI_PERF_PS1_OPT_WAVE = 82 +SPI_PERF_PS2_OPT_WAVE = 83 +SPI_PERF_PS3_OPT_WAVE = 84 +SPI_PERF_PS0_PASS_BIN0 = 85 +SPI_PERF_PS1_PASS_BIN0 = 86 +SPI_PERF_PS2_PASS_BIN0 = 87 +SPI_PERF_PS3_PASS_BIN0 = 88 +SPI_PERF_PS0_PASS_BIN1 = 89 +SPI_PERF_PS1_PASS_BIN1 = 90 +SPI_PERF_PS2_PASS_BIN1 = 91 +SPI_PERF_PS3_PASS_BIN1 = 92 +SPI_PERF_PS0_FPOS_BIN2 = 93 +SPI_PERF_PS1_FPOS_BIN2 = 94 +SPI_PERF_PS2_FPOS_BIN2 = 95 +SPI_PERF_PS3_FPOS_BIN2 = 96 +SPI_PERF_PS0_PRIM_BIN0 = 97 +SPI_PERF_PS1_PRIM_BIN0 = 98 +SPI_PERF_PS2_PRIM_BIN0 = 99 +SPI_PERF_PS3_PRIM_BIN0 = 100 +SPI_PERF_PS0_PRIM_BIN1 = 101 +SPI_PERF_PS1_PRIM_BIN1 = 102 +SPI_PERF_PS2_PRIM_BIN1 = 103 +SPI_PERF_PS3_PRIM_BIN1 = 104 +SPI_PERF_PS0_CNF_BIN2 = 105 +SPI_PERF_PS1_CNF_BIN2 = 106 +SPI_PERF_PS2_CNF_BIN2 = 107 +SPI_PERF_PS3_CNF_BIN2 = 108 +SPI_PERF_PS0_CNF_BIN3 = 109 +SPI_PERF_PS1_CNF_BIN3 = 110 +SPI_PERF_PS2_CNF_BIN3 = 111 +SPI_PERF_PS3_CNF_BIN3 = 112 +SPI_PERF_PS0_CRAWLER_STALL = 113 +SPI_PERF_PS1_CRAWLER_STALL = 114 +SPI_PERF_PS2_CRAWLER_STALL = 115 +SPI_PERF_PS3_CRAWLER_STALL = 116 +SPI_PERF_PS0_LDS_RES_FULL = 117 +SPI_PERF_PS1_LDS_RES_FULL = 118 +SPI_PERF_PS2_LDS_RES_FULL = 119 +SPI_PERF_PS3_LDS_RES_FULL = 120 +SPI_PERF_PS_PERS_UPD_FULL0 = 121 +SPI_PERF_PS_PERS_UPD_FULL1 = 122 +SPI_PERF_PS0_POPS_WAVE_SENT = 123 +SPI_PERF_PS1_POPS_WAVE_SENT = 124 +SPI_PERF_PS2_POPS_WAVE_SENT = 125 +SPI_PERF_PS3_POPS_WAVE_SENT = 126 +SPI_PERF_PS0_POPS_WAVE_EXIT = 127 +SPI_PERF_PS1_POPS_WAVE_EXIT = 128 +SPI_PERF_PS2_POPS_WAVE_EXIT = 129 +SPI_PERF_PS3_POPS_WAVE_EXIT = 130 +SPI_PERF_LDS0_PC_VALID = 131 +SPI_PERF_LDS1_PC_VALID = 132 +SPI_PERF_RA_PIPE_REQ_BIN2 = 133 +SPI_PERF_RA_TASK_REQ_BIN3 = 134 +SPI_PERF_RA_WR_CTL_FULL = 135 +SPI_PERF_RA_REQ_NO_ALLOC = 136 +SPI_PERF_RA_REQ_NO_ALLOC_PS = 137 +SPI_PERF_RA_REQ_NO_ALLOC_VS = 138 +SPI_PERF_RA_REQ_NO_ALLOC_GS = 139 +SPI_PERF_RA_REQ_NO_ALLOC_HS = 140 +SPI_PERF_RA_REQ_NO_ALLOC_CSG = 141 +SPI_PERF_RA_REQ_NO_ALLOC_CSN = 142 +SPI_PERF_RA_RES_STALL_PS = 143 +SPI_PERF_RA_RES_STALL_VS = 144 +SPI_PERF_RA_RES_STALL_GS = 145 +SPI_PERF_RA_RES_STALL_HS = 146 +SPI_PERF_RA_RES_STALL_CSG = 147 +SPI_PERF_RA_RES_STALL_CSN = 148 +SPI_PERF_RA_TMP_STALL_PS = 149 +SPI_PERF_RA_TMP_STALL_VS = 150 +SPI_PERF_RA_TMP_STALL_GS = 151 +SPI_PERF_RA_TMP_STALL_HS = 152 +SPI_PERF_RA_TMP_STALL_CSG = 153 +SPI_PERF_RA_TMP_STALL_CSN = 154 +SPI_PERF_RA_WAVE_SIMD_FULL_PS = 155 +SPI_PERF_RA_WAVE_SIMD_FULL_VS = 156 +SPI_PERF_RA_WAVE_SIMD_FULL_GS = 157 +SPI_PERF_RA_WAVE_SIMD_FULL_HS = 158 +SPI_PERF_RA_WAVE_SIMD_FULL_CSG = 159 +SPI_PERF_RA_WAVE_SIMD_FULL_CSN = 160 +SPI_PERF_RA_VGPR_SIMD_FULL_PS = 161 +SPI_PERF_RA_VGPR_SIMD_FULL_VS = 162 +SPI_PERF_RA_VGPR_SIMD_FULL_GS = 163 +SPI_PERF_RA_VGPR_SIMD_FULL_HS = 164 +SPI_PERF_RA_VGPR_SIMD_FULL_CSG = 165 +SPI_PERF_RA_VGPR_SIMD_FULL_CSN = 166 +SPI_PERF_RA_SGPR_SIMD_FULL_PS = 167 +SPI_PERF_RA_SGPR_SIMD_FULL_VS = 168 +SPI_PERF_RA_SGPR_SIMD_FULL_GS = 169 +SPI_PERF_RA_SGPR_SIMD_FULL_HS = 170 +SPI_PERF_RA_SGPR_SIMD_FULL_CSG = 171 +SPI_PERF_RA_SGPR_SIMD_FULL_CSN = 172 +SPI_PERF_RA_LDS_CU_FULL_PS = 173 +SPI_PERF_RA_LDS_CU_FULL_LS = 174 +SPI_PERF_RA_LDS_CU_FULL_ES = 175 +SPI_PERF_RA_LDS_CU_FULL_CSG = 176 +SPI_PERF_RA_LDS_CU_FULL_CSN = 177 +SPI_PERF_RA_BAR_CU_FULL_HS = 178 +SPI_PERF_RA_BAR_CU_FULL_CSG = 179 +SPI_PERF_RA_BAR_CU_FULL_CSN = 180 +SPI_PERF_RA_BULKY_CU_FULL_CSG = 181 +SPI_PERF_RA_BULKY_CU_FULL_CSN = 182 +SPI_PERF_RA_TGLIM_CU_FULL_CSG = 183 +SPI_PERF_RA_TGLIM_CU_FULL_CSN = 184 +SPI_PERF_RA_WVLIM_STALL_PS = 185 +SPI_PERF_RA_WVLIM_STALL_VS = 186 +SPI_PERF_RA_WVLIM_STALL_GS = 187 +SPI_PERF_RA_WVLIM_STALL_HS = 188 +SPI_PERF_RA_WVLIM_STALL_CSG = 189 +SPI_PERF_RA_WVLIM_STALL_CSN = 190 +SPI_PERF_RA_VS_LOCK = 191 +SPI_PERF_RA_GS_LOCK = 192 +SPI_PERF_RA_HS_LOCK = 193 +SPI_PERF_RA_CSG_LOCK = 194 +SPI_PERF_RA_CSN_LOCK = 195 +SPI_PERF_RA_RSV_UPD = 196 +SPI_PERF_EXP_ARB_COL_CNT = 197 +SPI_PERF_EXP_ARB_PAR_CNT = 198 +SPI_PERF_EXP_ARB_POS_CNT = 199 +SPI_PERF_EXP_ARB_GDS_CNT = 200 +SPI_PERF_NUM_PS_COL_R0_EXPORTS = 201 +SPI_PERF_NUM_PS_COL_R1_EXPORTS = 202 +SPI_PERF_NUM_VS_POS_R0_EXPORTS = 203 +SPI_PERF_NUM_VS_POS_R1_EXPORTS = 204 +SPI_PERF_NUM_VS_PARAM_R0_EXPORTS = 205 +SPI_PERF_NUM_VS_PARAM_R1_EXPORTS = 206 +SPI_PERF_NUM_VS_GDS_R0_EXPORTS = 207 +SPI_PERF_NUM_VS_GDS_R1_EXPORTS = 208 +SPI_PERF_NUM_EXPGRANT_EXPORTS = 209 +SPI_PERF_CLKGATE_BUSY_STALL = 210 +SPI_PERF_CLKGATE_ACTIVE_STALL = 211 +SPI_PERF_CLKGATE_ALL_CLOCKS_ON = 212 +SPI_PERF_CLKGATE_CGTT_DYN_ON = 213 +SPI_PERF_CLKGATE_CGTT_REG_ON = 214 +SPI_PERF_PIX_ALLOC_PEND_CNT = 215 +SPI_PERF_PIX_ALLOC_SCB0_STALL = 216 +SPI_PERF_PIX_ALLOC_SCB1_STALL = 217 +SPI_PERF_PIX_ALLOC_SCB2_STALL = 218 +SPI_PERF_PIX_ALLOC_SCB3_STALL = 219 +SPI_PERF_PIX_ALLOC_DB0_STALL = 220 +SPI_PERF_PIX_ALLOC_DB1_STALL = 221 +SPI_PERF_PIX_ALLOC_DB2_STALL = 222 +SPI_PERF_PIX_ALLOC_DB3_STALL = 223 +SPI_PERF_PIX_ALLOC_DB4_STALL = 224 +SPI_PERF_PIX_ALLOC_DB5_STALL = 225 +SPI_PERF_PIX_ALLOC_DB6_STALL = 226 +SPI_PERF_PIX_ALLOC_DB7_STALL = 227 +SPI_PERF_PC_ALLOC_ACCUM = 228 +SPI_PERF_GS_NGG_SE_HAS_BATON = 229 +SPI_PERF_GS_NGG_SE_DOES_NOT_HAVE_BATON = 230 +SPI_PERF_GS_NGG_SE_FORWARDED_BATON = 231 +SPI_PERF_GS_NGG_SE_AT_SYNC_EVENT = 232 +SPI_PERF_GS_NGG_SE_SG_ALLOC_PC_SPACE_CNT = 233 +SPI_PERF_GS_NGG_SE_DEALLOC_PC_SPACE_CNT = 234 +SPI_PERF_GS_NGG_PC_FULL = 235 +SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC = 236 +SPI_PERF_GS_NGG_GS_ALLOC_FIFO_EMPTY = 237 +SPI_PERF_GSC_VTX_BUSY = 238 +SPI_PERF_GSC_VTX_INPUT_STARVED = 239 +SPI_PERF_GSC_VTX_VSR_STALL = 240 +SPI_PERF_GSC_VTX_VSR_FULL = 241 +SPI_PERF_GSC_VTX_CAC_BUSY = 242 +SPI_PERF_ESC_VTX_BUSY = 243 +SPI_PERF_ESC_VTX_INPUT_STARVED = 244 +SPI_PERF_ESC_VTX_VSR_STALL = 245 +SPI_PERF_ESC_VTX_VSR_FULL = 246 +SPI_PERF_ESC_VTX_CAC_BUSY = 247 +SPI_PERF_SWC_PS_WR = 248 +SPI_PERF_SWC_VS_WR = 249 +SPI_PERF_SWC_GS_WR = 250 +SPI_PERF_SWC_HS_WR = 251 +SPI_PERF_SWC_CSG_WR = 252 +SPI_PERF_SWC_CSC_WR = 253 +SPI_PERF_VWC_PS_WR = 254 +SPI_PERF_VWC_VS_WR = 255 +SPI_PERF_VWC_GS_WR = 256 +SPI_PERF_VWC_HS_WR = 257 +SPI_PERF_VWC_CSG_WR = 258 +SPI_PERF_VWC_CSC_WR = 259 +SPI_PERF_ES_WINDOW_VALID = 260 +SPI_PERF_ES_BUSY = 261 +SPI_PERF_ES_CRAWLER_STALL = 262 +SPI_PERF_ES_FIRST_WAVE = 263 +SPI_PERF_ES_LAST_WAVE = 264 +SPI_PERF_ES_LSHS_DEALLOC = 265 +SPI_PERF_ES_EVENT_WAVE = 266 +SPI_PERF_ES_WAVE = 267 +SPI_PERF_ES_PERS_UPD_FULL0 = 268 +SPI_PERF_ES_PERS_UPD_FULL1 = 269 +SPI_PERF_ES_FIRST_SUBGRP = 270 +SPI_PERF_ES_LAST_SUBGRP = 271 +SPI_PERF_LS_WINDOW_VALID = 272 +SPI_PERF_LS_BUSY = 273 +SPI_PERF_LS_CRAWLER_STALL = 274 +SPI_PERF_LS_FIRST_WAVE = 275 +SPI_PERF_LS_LAST_WAVE = 276 +SPI_PERF_LS_OFFCHIP_LDS_STALL = 277 +SPI_PERF_LS_EVENT_WAVE = 278 +SPI_PERF_LS_WAVE = 279 +SPI_PERF_LS_PERS_UPD_FULL0 = 280 +SPI_PERF_LS_PERS_UPD_FULL1 = 281 +SPI_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_FORMAT' +SPI_SHADER_FORMAT__enumvalues = { + 0: 'SPI_SHADER_NONE', + 1: 'SPI_SHADER_1COMP', + 2: 'SPI_SHADER_2COMP', + 3: 'SPI_SHADER_4COMPRESS', + 4: 'SPI_SHADER_4COMP', +} +SPI_SHADER_NONE = 0 +SPI_SHADER_1COMP = 1 +SPI_SHADER_2COMP = 2 +SPI_SHADER_4COMPRESS = 3 +SPI_SHADER_4COMP = 4 +SPI_SHADER_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_EX_FORMAT' +SPI_SHADER_EX_FORMAT__enumvalues = { + 0: 'SPI_SHADER_ZERO', + 1: 'SPI_SHADER_32_R', + 2: 'SPI_SHADER_32_GR', + 3: 'SPI_SHADER_32_AR', + 4: 'SPI_SHADER_FP16_ABGR', + 5: 'SPI_SHADER_UNORM16_ABGR', + 6: 'SPI_SHADER_SNORM16_ABGR', + 7: 'SPI_SHADER_UINT16_ABGR', + 8: 'SPI_SHADER_SINT16_ABGR', + 9: 'SPI_SHADER_32_ABGR', +} +SPI_SHADER_ZERO = 0 +SPI_SHADER_32_R = 1 +SPI_SHADER_32_GR = 2 +SPI_SHADER_32_AR = 3 +SPI_SHADER_FP16_ABGR = 4 +SPI_SHADER_UNORM16_ABGR = 5 +SPI_SHADER_SNORM16_ABGR = 6 +SPI_SHADER_UINT16_ABGR = 7 +SPI_SHADER_SINT16_ABGR = 8 +SPI_SHADER_32_ABGR = 9 +SPI_SHADER_EX_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_SM_MODE' +CLKGATE_SM_MODE__enumvalues = { + 0: 'ON_SEQ', + 1: 'OFF_SEQ', + 2: 'PROG_SEQ', + 3: 'READ_SEQ', + 4: 'SM_MODE_RESERVED', +} +ON_SEQ = 0 +OFF_SEQ = 1 +PROG_SEQ = 2 +READ_SEQ = 3 +SM_MODE_RESERVED = 4 +CLKGATE_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_BASE_MODE' +CLKGATE_BASE_MODE__enumvalues = { + 0: 'MULT_8', + 1: 'MULT_16', +} +MULT_8 = 0 +MULT_16 = 1 +CLKGATE_BASE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_LB_WAVES_SELECT' +SPI_LB_WAVES_SELECT__enumvalues = { + 0: 'HS_GS', + 1: 'VS_PS', + 2: 'CS_NA', + 3: 'SPI_LB_WAVES_RSVD', +} +HS_GS = 0 +VS_PS = 1 +CS_NA = 2 +SPI_LB_WAVES_RSVD = 3 +SPI_LB_WAVES_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_CLAMP' +SQ_TEX_CLAMP__enumvalues = { + 0: 'SQ_TEX_WRAP', + 1: 'SQ_TEX_MIRROR', + 2: 'SQ_TEX_CLAMP_LAST_TEXEL', + 3: 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 4: 'SQ_TEX_CLAMP_HALF_BORDER', + 5: 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', + 6: 'SQ_TEX_CLAMP_BORDER', + 7: 'SQ_TEX_MIRROR_ONCE_BORDER', +} +SQ_TEX_WRAP = 0 +SQ_TEX_MIRROR = 1 +SQ_TEX_CLAMP_LAST_TEXEL = 2 +SQ_TEX_MIRROR_ONCE_LAST_TEXEL = 3 +SQ_TEX_CLAMP_HALF_BORDER = 4 +SQ_TEX_MIRROR_ONCE_HALF_BORDER = 5 +SQ_TEX_CLAMP_BORDER = 6 +SQ_TEX_MIRROR_ONCE_BORDER = 7 +SQ_TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_XY_FILTER' +SQ_TEX_XY_FILTER__enumvalues = { + 0: 'SQ_TEX_XY_FILTER_POINT', + 1: 'SQ_TEX_XY_FILTER_BILINEAR', + 2: 'SQ_TEX_XY_FILTER_ANISO_POINT', + 3: 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', +} +SQ_TEX_XY_FILTER_POINT = 0 +SQ_TEX_XY_FILTER_BILINEAR = 1 +SQ_TEX_XY_FILTER_ANISO_POINT = 2 +SQ_TEX_XY_FILTER_ANISO_BILINEAR = 3 +SQ_TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_Z_FILTER' +SQ_TEX_Z_FILTER__enumvalues = { + 0: 'SQ_TEX_Z_FILTER_NONE', + 1: 'SQ_TEX_Z_FILTER_POINT', + 2: 'SQ_TEX_Z_FILTER_LINEAR', +} +SQ_TEX_Z_FILTER_NONE = 0 +SQ_TEX_Z_FILTER_POINT = 1 +SQ_TEX_Z_FILTER_LINEAR = 2 +SQ_TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_MIP_FILTER' +SQ_TEX_MIP_FILTER__enumvalues = { + 0: 'SQ_TEX_MIP_FILTER_NONE', + 1: 'SQ_TEX_MIP_FILTER_POINT', + 2: 'SQ_TEX_MIP_FILTER_LINEAR', + 3: 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', +} +SQ_TEX_MIP_FILTER_NONE = 0 +SQ_TEX_MIP_FILTER_POINT = 1 +SQ_TEX_MIP_FILTER_LINEAR = 2 +SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ = 3 +SQ_TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_ANISO_RATIO' +SQ_TEX_ANISO_RATIO__enumvalues = { + 0: 'SQ_TEX_ANISO_RATIO_1', + 1: 'SQ_TEX_ANISO_RATIO_2', + 2: 'SQ_TEX_ANISO_RATIO_4', + 3: 'SQ_TEX_ANISO_RATIO_8', + 4: 'SQ_TEX_ANISO_RATIO_16', +} +SQ_TEX_ANISO_RATIO_1 = 0 +SQ_TEX_ANISO_RATIO_2 = 1 +SQ_TEX_ANISO_RATIO_4 = 2 +SQ_TEX_ANISO_RATIO_8 = 3 +SQ_TEX_ANISO_RATIO_16 = 4 +SQ_TEX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_DEPTH_COMPARE' +SQ_TEX_DEPTH_COMPARE__enumvalues = { + 0: 'SQ_TEX_DEPTH_COMPARE_NEVER', + 1: 'SQ_TEX_DEPTH_COMPARE_LESS', + 2: 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 3: 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', + 4: 'SQ_TEX_DEPTH_COMPARE_GREATER', + 5: 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', + 6: 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', + 7: 'SQ_TEX_DEPTH_COMPARE_ALWAYS', +} +SQ_TEX_DEPTH_COMPARE_NEVER = 0 +SQ_TEX_DEPTH_COMPARE_LESS = 1 +SQ_TEX_DEPTH_COMPARE_EQUAL = 2 +SQ_TEX_DEPTH_COMPARE_LESSEQUAL = 3 +SQ_TEX_DEPTH_COMPARE_GREATER = 4 +SQ_TEX_DEPTH_COMPARE_NOTEQUAL = 5 +SQ_TEX_DEPTH_COMPARE_GREATEREQUAL = 6 +SQ_TEX_DEPTH_COMPARE_ALWAYS = 7 +SQ_TEX_DEPTH_COMPARE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_BORDER_COLOR' +SQ_TEX_BORDER_COLOR__enumvalues = { + 0: 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 1: 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 2: 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 3: 'SQ_TEX_BORDER_COLOR_REGISTER', +} +SQ_TEX_BORDER_COLOR_TRANS_BLACK = 0 +SQ_TEX_BORDER_COLOR_OPAQUE_BLACK = 1 +SQ_TEX_BORDER_COLOR_OPAQUE_WHITE = 2 +SQ_TEX_BORDER_COLOR_REGISTER = 3 +SQ_TEX_BORDER_COLOR = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_BUF_TYPE' +SQ_RSRC_BUF_TYPE__enumvalues = { + 0: 'SQ_RSRC_BUF', + 1: 'SQ_RSRC_BUF_RSVD_1', + 2: 'SQ_RSRC_BUF_RSVD_2', + 3: 'SQ_RSRC_BUF_RSVD_3', +} +SQ_RSRC_BUF = 0 +SQ_RSRC_BUF_RSVD_1 = 1 +SQ_RSRC_BUF_RSVD_2 = 2 +SQ_RSRC_BUF_RSVD_3 = 3 +SQ_RSRC_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_IMG_TYPE' +SQ_RSRC_IMG_TYPE__enumvalues = { + 0: 'SQ_RSRC_IMG_RSVD_0', + 1: 'SQ_RSRC_IMG_RSVD_1', + 2: 'SQ_RSRC_IMG_RSVD_2', + 3: 'SQ_RSRC_IMG_RSVD_3', + 4: 'SQ_RSRC_IMG_RSVD_4', + 5: 'SQ_RSRC_IMG_RSVD_5', + 6: 'SQ_RSRC_IMG_RSVD_6', + 7: 'SQ_RSRC_IMG_RSVD_7', + 8: 'SQ_RSRC_IMG_1D', + 9: 'SQ_RSRC_IMG_2D', + 10: 'SQ_RSRC_IMG_3D', + 11: 'SQ_RSRC_IMG_CUBE', + 12: 'SQ_RSRC_IMG_1D_ARRAY', + 13: 'SQ_RSRC_IMG_2D_ARRAY', + 14: 'SQ_RSRC_IMG_2D_MSAA', + 15: 'SQ_RSRC_IMG_2D_MSAA_ARRAY', +} +SQ_RSRC_IMG_RSVD_0 = 0 +SQ_RSRC_IMG_RSVD_1 = 1 +SQ_RSRC_IMG_RSVD_2 = 2 +SQ_RSRC_IMG_RSVD_3 = 3 +SQ_RSRC_IMG_RSVD_4 = 4 +SQ_RSRC_IMG_RSVD_5 = 5 +SQ_RSRC_IMG_RSVD_6 = 6 +SQ_RSRC_IMG_RSVD_7 = 7 +SQ_RSRC_IMG_1D = 8 +SQ_RSRC_IMG_2D = 9 +SQ_RSRC_IMG_3D = 10 +SQ_RSRC_IMG_CUBE = 11 +SQ_RSRC_IMG_1D_ARRAY = 12 +SQ_RSRC_IMG_2D_ARRAY = 13 +SQ_RSRC_IMG_2D_MSAA = 14 +SQ_RSRC_IMG_2D_MSAA_ARRAY = 15 +SQ_RSRC_IMG_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_FLAT_TYPE' +SQ_RSRC_FLAT_TYPE__enumvalues = { + 0: 'SQ_RSRC_FLAT_RSVD_0', + 1: 'SQ_RSRC_FLAT', + 2: 'SQ_RSRC_FLAT_RSVD_2', + 3: 'SQ_RSRC_FLAT_RSVD_3', +} +SQ_RSRC_FLAT_RSVD_0 = 0 +SQ_RSRC_FLAT = 1 +SQ_RSRC_FLAT_RSVD_2 = 2 +SQ_RSRC_FLAT_RSVD_3 = 3 +SQ_RSRC_FLAT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IMG_FILTER_TYPE' +SQ_IMG_FILTER_TYPE__enumvalues = { + 0: 'SQ_IMG_FILTER_MODE_BLEND', + 1: 'SQ_IMG_FILTER_MODE_MIN', + 2: 'SQ_IMG_FILTER_MODE_MAX', +} +SQ_IMG_FILTER_MODE_BLEND = 0 +SQ_IMG_FILTER_MODE_MIN = 1 +SQ_IMG_FILTER_MODE_MAX = 2 +SQ_IMG_FILTER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_SEL_XYZW01' +SQ_SEL_XYZW01__enumvalues = { + 0: 'SQ_SEL_0', + 1: 'SQ_SEL_1', + 2: 'SQ_SEL_N_BC_1', + 3: 'SQ_SEL_RESERVED_1', + 4: 'SQ_SEL_X', + 5: 'SQ_SEL_Y', + 6: 'SQ_SEL_Z', + 7: 'SQ_SEL_W', +} +SQ_SEL_0 = 0 +SQ_SEL_1 = 1 +SQ_SEL_N_BC_1 = 2 +SQ_SEL_RESERVED_1 = 3 +SQ_SEL_X = 4 +SQ_SEL_Y = 5 +SQ_SEL_Z = 6 +SQ_SEL_W = 7 +SQ_SEL_XYZW01 = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_OOB_SELECT' +SQ_OOB_SELECT__enumvalues = { + 0: 'SQ_OOB_INDEX_AND_OFFSET', + 1: 'SQ_OOB_INDEX_ONLY', + 2: 'SQ_OOB_NUM_RECORDS_0', + 3: 'SQ_OOB_COMPLETE', +} +SQ_OOB_INDEX_AND_OFFSET = 0 +SQ_OOB_INDEX_ONLY = 1 +SQ_OOB_NUM_RECORDS_0 = 2 +SQ_OOB_COMPLETE = 3 +SQ_OOB_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_TYPE' +SQ_WAVE_TYPE__enumvalues = { + 0: 'SQ_WAVE_TYPE_PS', + 1: 'SQ_WAVE_TYPE_VS', + 2: 'SQ_WAVE_TYPE_GS', + 3: 'SQ_WAVE_TYPE_ES', + 4: 'SQ_WAVE_TYPE_HS', + 5: 'SQ_WAVE_TYPE_LS', + 6: 'SQ_WAVE_TYPE_CS', + 7: 'SQ_WAVE_TYPE_PS1', + 8: 'SQ_WAVE_TYPE_PS2', + 9: 'SQ_WAVE_TYPE_PS3', +} +SQ_WAVE_TYPE_PS = 0 +SQ_WAVE_TYPE_VS = 1 +SQ_WAVE_TYPE_GS = 2 +SQ_WAVE_TYPE_ES = 3 +SQ_WAVE_TYPE_HS = 4 +SQ_WAVE_TYPE_LS = 5 +SQ_WAVE_TYPE_CS = 6 +SQ_WAVE_TYPE_PS1 = 7 +SQ_WAVE_TYPE_PS2 = 8 +SQ_WAVE_TYPE_PS3 = 9 +SQ_WAVE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_PERF_SEL' +SQ_PERF_SEL__enumvalues = { + 0: 'SQ_PERF_SEL_NONE', + 1: 'SQ_PERF_SEL_ACCUM_PREV', + 2: 'SQ_PERF_SEL_CYCLES', + 3: 'SQ_PERF_SEL_BUSY_CYCLES', + 4: 'SQ_PERF_SEL_WAVES', + 5: 'SQ_PERF_SEL_WAVES_32', + 6: 'SQ_PERF_SEL_WAVES_64', + 7: 'SQ_PERF_SEL_LEVEL_WAVES', + 8: 'SQ_PERF_SEL_ITEMS', + 9: 'SQ_PERF_SEL_WAVE32_ITEMS', + 10: 'SQ_PERF_SEL_WAVE64_ITEMS', + 11: 'SQ_PERF_SEL_QUADS', + 12: 'SQ_PERF_SEL_EVENTS', + 13: 'SQ_PERF_SEL_WAVES_EQ_64', + 14: 'SQ_PERF_SEL_WAVES_LT_64', + 15: 'SQ_PERF_SEL_WAVES_LT_48', + 16: 'SQ_PERF_SEL_WAVES_LT_32', + 17: 'SQ_PERF_SEL_WAVES_LT_16', + 18: 'SQ_PERF_SEL_WAVES_RESTORED', + 19: 'SQ_PERF_SEL_WAVES_SAVED', + 20: 'SQ_PERF_SEL_MSG', + 21: 'SQ_PERF_SEL_MSG_GSCNT', + 22: 'SQ_PERF_SEL_MSG_INTERRUPT', + 23: 'SQ_PERF_SEL_Reserved_1', + 24: 'SQ_PERF_SEL_Reserved_2', + 25: 'SQ_PERF_SEL_Reserved_3', + 26: 'SQ_PERF_SEL_WAVE_CYCLES', + 27: 'SQ_PERF_SEL_WAVE_READY', + 28: 'SQ_PERF_SEL_WAIT_INST_ANY', + 29: 'SQ_PERF_SEL_WAIT_INST_VALU', + 30: 'SQ_PERF_SEL_WAIT_INST_SCA', + 31: 'SQ_PERF_SEL_WAIT_INST_LDS', + 32: 'SQ_PERF_SEL_WAIT_INST_TEX', + 33: 'SQ_PERF_SEL_WAIT_INST_FLAT', + 34: 'SQ_PERF_SEL_WAIT_INST_VMEM', + 35: 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', + 36: 'SQ_PERF_SEL_WAIT_INST_BR_MSG', + 37: 'SQ_PERF_SEL_WAIT_ANY', + 38: 'SQ_PERF_SEL_WAIT_CNT_ANY', + 39: 'SQ_PERF_SEL_WAIT_CNT_VMVS', + 40: 'SQ_PERF_SEL_WAIT_CNT_LGKM', + 41: 'SQ_PERF_SEL_WAIT_CNT_EXP', + 42: 'SQ_PERF_SEL_WAIT_TTRACE', + 43: 'SQ_PERF_SEL_WAIT_IFETCH', + 44: 'SQ_PERF_SEL_WAIT_BARRIER', + 45: 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 46: 'SQ_PERF_SEL_WAIT_SLEEP', + 47: 'SQ_PERF_SEL_WAIT_SLEEP_XNACK', + 48: 'SQ_PERF_SEL_WAIT_OTHER', + 49: 'SQ_PERF_SEL_INSTS_ALL', + 50: 'SQ_PERF_SEL_INSTS_BRANCH', + 51: 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 52: 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', + 53: 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS', + 54: 'SQ_PERF_SEL_INSTS_EXP_GDS', + 55: 'SQ_PERF_SEL_INSTS_GDS', + 56: 'SQ_PERF_SEL_INSTS_EXP', + 57: 'SQ_PERF_SEL_INSTS_FLAT', + 58: 'SQ_PERF_SEL_Reserved_4', + 59: 'SQ_PERF_SEL_INSTS_LDS', + 60: 'SQ_PERF_SEL_INSTS_SALU', + 61: 'SQ_PERF_SEL_INSTS_SMEM', + 62: 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 63: 'SQ_PERF_SEL_INSTS_SENDMSG', + 64: 'SQ_PERF_SEL_INSTS_VALU', + 65: 'SQ_PERF_SEL_Reserved_17', + 66: 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 67: 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 68: 'SQ_PERF_SEL_INSTS_TEX', + 69: 'SQ_PERF_SEL_INSTS_TEX_LOAD', + 70: 'SQ_PERF_SEL_INSTS_TEX_STORE', + 71: 'SQ_PERF_SEL_INSTS_WAVE32', + 72: 'SQ_PERF_SEL_INSTS_WAVE32_FLAT', + 73: 'SQ_PERF_SEL_Reserved_5', + 74: 'SQ_PERF_SEL_INSTS_WAVE32_LDS', + 75: 'SQ_PERF_SEL_INSTS_WAVE32_VALU', + 76: 'SQ_PERF_SEL_Reserved_16', + 77: 'SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32', + 78: 'SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC', + 79: 'SQ_PERF_SEL_INSTS_WAVE32_TEX', + 80: 'SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD', + 81: 'SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE', + 82: 'SQ_PERF_SEL_ITEM_CYCLES_VALU', + 83: 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 84: 'SQ_PERF_SEL_WAVE32_INSTS', + 85: 'SQ_PERF_SEL_WAVE64_INSTS', + 86: 'SQ_PERF_SEL_Reserved_18', + 87: 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 88: 'SQ_PERF_SEL_WAVE64_HALF_SKIP', + 89: 'SQ_PERF_SEL_INSTS_TEX_REPLAY', + 90: 'SQ_PERF_SEL_INSTS_SMEM_REPLAY', + 91: 'SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY', + 92: 'SQ_PERF_SEL_INSTS_FLAT_REPLAY', + 93: 'SQ_PERF_SEL_XNACK_ALL', + 94: 'SQ_PERF_SEL_XNACK_FIRST', + 95: 'SQ_PERF_SEL_INSTS_VALU_LDS_DIRECT_RD', + 96: 'SQ_PERF_SEL_INSTS_VALU_VINTRP_OP', + 97: 'SQ_PERF_SEL_INST_LEVEL_EXP', + 98: 'SQ_PERF_SEL_INST_LEVEL_GDS', + 99: 'SQ_PERF_SEL_INST_LEVEL_LDS', + 100: 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 101: 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 102: 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', + 103: 'SQ_PERF_SEL_IFETCH_REQS', + 104: 'SQ_PERF_SEL_IFETCH_LEVEL', + 105: 'SQ_PERF_SEL_IFETCH_XNACK', + 106: 'SQ_PERF_SEL_Reserved_6', + 107: 'SQ_PERF_SEL_Reserved_7', + 108: 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 109: 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 110: 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 111: 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 112: 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 113: 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 114: 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 115: 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 116: 'SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL', + 117: 'SQ_PERF_SEL_INST_CYCLES_VALU', + 118: 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 119: 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 120: 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 121: 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 122: 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 123: 'SQ_PERF_SEL_INST_CYCLES_LDS', + 124: 'SQ_PERF_SEL_INST_CYCLES_TEX', + 125: 'SQ_PERF_SEL_INST_CYCLES_FLAT', + 126: 'SQ_PERF_SEL_INST_CYCLES_EXP_GDS', + 127: 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', + 128: 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 129: 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 130: 'SQ_PERF_SEL_Reserved_8', + 131: 'SQ_PERF_SEL_Reserved_9', + 132: 'SQ_PERF_SEL_Reserved_10', + 133: 'SQ_PERF_SEL_Reserved_11', + 134: 'SQ_PERF_SEL_Reserved_12', + 135: 'SQ_PERF_SEL_Reserved_13', + 136: 'SQ_PERF_SEL_Reserved_14', + 137: 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', + 138: 'SQ_PERF_SEL_VMEM_BUS_STALL', + 139: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 140: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 141: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 142: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 143: 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', + 144: 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 145: 'SQ_PERF_SEL_Reserved_15', + 146: 'SQ_PERF_SEL_SALU_PIPE_STALL', + 147: 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 148: 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_STALL', + 149: 'SQ_PERF_SEL_MSG_BUS_BUSY', + 150: 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', + 151: 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', + 152: 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 153: 'SQ_PERF_SEL_EXP_BUS0_BUSY', + 154: 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 155: 'SQ_PERF_SEL_INST_CACHE_REQS', + 156: 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', + 157: 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VALU', + 158: 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_SALU', + 159: 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VMEM', + 160: 'SQ_PERF_SEL_USER0', + 161: 'SQ_PERF_SEL_USER1', + 162: 'SQ_PERF_SEL_USER2', + 163: 'SQ_PERF_SEL_USER3', + 164: 'SQ_PERF_SEL_USER4', + 165: 'SQ_PERF_SEL_USER5', + 166: 'SQ_PERF_SEL_USER6', + 167: 'SQ_PERF_SEL_USER7', + 168: 'SQ_PERF_SEL_USER8', + 169: 'SQ_PERF_SEL_USER9', + 170: 'SQ_PERF_SEL_USER10', + 171: 'SQ_PERF_SEL_USER11', + 172: 'SQ_PERF_SEL_USER12', + 173: 'SQ_PERF_SEL_USER13', + 174: 'SQ_PERF_SEL_USER14', + 175: 'SQ_PERF_SEL_USER15', + 176: 'SQ_PERF_SEL_USER_LEVEL0', + 177: 'SQ_PERF_SEL_USER_LEVEL1', + 178: 'SQ_PERF_SEL_USER_LEVEL2', + 179: 'SQ_PERF_SEL_USER_LEVEL3', + 180: 'SQ_PERF_SEL_USER_LEVEL4', + 181: 'SQ_PERF_SEL_USER_LEVEL5', + 182: 'SQ_PERF_SEL_USER_LEVEL6', + 183: 'SQ_PERF_SEL_USER_LEVEL7', + 184: 'SQ_PERF_SEL_USER_LEVEL8', + 185: 'SQ_PERF_SEL_USER_LEVEL9', + 186: 'SQ_PERF_SEL_USER_LEVEL10', + 187: 'SQ_PERF_SEL_USER_LEVEL11', + 188: 'SQ_PERF_SEL_USER_LEVEL12', + 189: 'SQ_PERF_SEL_USER_LEVEL13', + 190: 'SQ_PERF_SEL_USER_LEVEL14', + 191: 'SQ_PERF_SEL_USER_LEVEL15', + 192: 'SQ_PERF_SEL_VALU_RETURN_SDST', + 193: 'SQ_PERF_SEL_VMEM_SECOND_TRY_USED', + 194: 'SQ_PERF_SEL_VMEM_SECOND_TRY_STALL', + 195: 'SQ_PERF_SEL_DUMMY_END', + 255: 'SQ_PERF_SEL_DUMMY_LAST', + 256: 'SQG_PERF_SEL_UTCL0_TRANSLATION_MISS', + 257: 'SQG_PERF_SEL_UTCL0_PERMISSION_MISS', + 258: 'SQG_PERF_SEL_UTCL0_TRANSLATION_HIT', + 259: 'SQG_PERF_SEL_UTCL0_REQUEST', + 260: 'SQG_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 261: 'SQG_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 262: 'SQG_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 263: 'SQG_PERF_SEL_UTCL0_LFIFO_FULL', + 264: 'SQG_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 265: 'SQG_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 266: 'SQG_PERF_SEL_UTCL0_HIT_FIFO_FULL', + 267: 'SQG_PERF_SEL_UTCL0_UTCL1_REQ', + 268: 'SQG_PERF_SEL_TLB_SHOOTDOWN', + 269: 'SQG_PERF_SEL_TLB_SHOOTDOWN_CYCLES', + 270: 'SQG_PERF_SEL_TTRACE_REQS', + 271: 'SQG_PERF_SEL_TTRACE_INFLIGHT_REQS', + 272: 'SQG_PERF_SEL_TTRACE_STALL', + 273: 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', + 274: 'SQG_PERF_SEL_DUMMY_LAST', + 275: 'SQC_PERF_SEL_POWER_VALU', + 276: 'SQC_PERF_SEL_POWER_VALU0', + 277: 'SQC_PERF_SEL_POWER_VALU1', + 278: 'SQC_PERF_SEL_POWER_VALU2', + 279: 'SQC_PERF_SEL_POWER_GPR_RD', + 280: 'SQC_PERF_SEL_POWER_GPR_WR', + 281: 'SQC_PERF_SEL_POWER_LDS_BUSY', + 282: 'SQC_PERF_SEL_POWER_ALU_BUSY', + 283: 'SQC_PERF_SEL_POWER_TEX_BUSY', + 284: 'SQC_PERF_SEL_PT_POWER_STALL', + 285: 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 286: 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 287: 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', + 288: 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 289: 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 290: 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 291: 'SQC_PERF_SEL_LDS_DATA_FIFO_FULL', + 292: 'SQC_PERF_SEL_LDS_CMD_FIFO_FULL', + 293: 'SQC_PERF_SEL_LDS_ADDR_STALL', + 294: 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', + 295: 'SQC_PERF_SEL_LDS_DIRECT_FIFO_FULL_STALL', + 296: 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 297: 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 298: 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 299: 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', + 300: 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 301: 'SQC_PERF_SEL_ICACHE_REQ', + 302: 'SQC_PERF_SEL_ICACHE_HITS', + 303: 'SQC_PERF_SEL_ICACHE_MISSES', + 304: 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 305: 'SQC_PERF_SEL_ICACHE_INVAL_INST', + 306: 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 307: 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 308: 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 309: 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', + 310: 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 311: 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 312: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READY', + 313: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 314: 'SQC_PERF_SEL_ICACHE_INPUT_VALIDB', + 315: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READY', + 316: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 317: 'SQC_PERF_SEL_DCACHE_INPUT_VALIDB', + 318: 'SQC_PERF_SEL_TC_REQ', + 319: 'SQC_PERF_SEL_TC_INST_REQ', + 320: 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 321: 'SQC_PERF_SEL_TC_DATA_WRITE_REQ', + 322: 'SQC_PERF_SEL_TC_DATA_ATOMIC_REQ', + 323: 'SQC_PERF_SEL_TC_STALL', + 324: 'SQC_PERF_SEL_TC_STARVE', + 325: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 326: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 327: 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 328: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO', + 329: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 330: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT', + 331: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 332: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 333: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF', + 334: 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 335: 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 336: 'SQC_PERF_SEL_DCACHE_REQ', + 337: 'SQC_PERF_SEL_DCACHE_HITS', + 338: 'SQC_PERF_SEL_DCACHE_MISSES', + 339: 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 340: 'SQC_PERF_SEL_DCACHE_INVAL_INST', + 341: 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 342: 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 343: 'SQC_PERF_SEL_DCACHE_WC_LRU_WRITE', + 344: 'SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE', + 345: 'SQC_PERF_SEL_DCACHE_ATOMIC', + 346: 'SQC_PERF_SEL_DCACHE_WB_INST', + 347: 'SQC_PERF_SEL_DCACHE_WB_ASYNC', + 348: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 349: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 350: 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 351: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_NONZERO', + 352: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 353: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 354: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT', + 355: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED', + 356: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE', + 357: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT', + 358: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH', + 359: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE', + 360: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 361: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 362: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF', + 363: 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 364: 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 365: 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 366: 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 367: 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 368: 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 369: 'SQC_PERF_SEL_DCACHE_REQ_TIME', + 370: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_1', + 371: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_2', + 372: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_4', + 373: 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 374: 'SQC_PERF_SEL_SQ_DCACHE_REQS', + 375: 'SQC_PERF_SEL_DCACHE_FLAT_REQ', + 376: 'SQC_PERF_SEL_DCACHE_NONFLAT_REQ', + 377: 'SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_MISS', + 378: 'SQC_PERF_SEL_ICACHE_UTCL0_PERMISSION_MISS', + 379: 'SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_HIT', + 380: 'SQC_PERF_SEL_ICACHE_UTCL0_REQUEST', + 381: 'SQC_PERF_SEL_ICACHE_UTCL0_XNACK', + 382: 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_INFLIGHT_MAX', + 383: 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_LRU_INFLIGHT', + 384: 'SQC_PERF_SEL_ICACHE_UTCL0_LFIFO_FULL', + 385: 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_LFIFO_NOT_RES', + 386: 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 387: 'SQC_PERF_SEL_ICACHE_UTCL0_UTCL1_INFLIGHT', + 388: 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_MISSFIFO_FULL', + 389: 'SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_MISS', + 390: 'SQC_PERF_SEL_DCACHE_UTCL0_PERMISSION_MISS', + 391: 'SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_HIT', + 392: 'SQC_PERF_SEL_DCACHE_UTCL0_REQUEST', + 393: 'SQC_PERF_SEL_DCACHE_UTCL0_XNACK', + 394: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_INFLIGHT_MAX', + 395: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_LRU_INFLIGHT', + 396: 'SQC_PERF_SEL_DCACHE_UTCL0_LFIFO_FULL', + 397: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_LFIFO_NOT_RES', + 398: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 399: 'SQC_PERF_SEL_DCACHE_UTCL0_UTCL1_INFLIGHT', + 400: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_MISSFIFO_FULL', + 401: 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_MULTI_MISS', + 402: 'SQC_PERF_SEL_DCACHE_UTCL0_HIT_FIFO_FULL', + 403: 'SQC_PERF_SEL_ICACHE_UTCL0_INFLIGHT_LEVEL', + 404: 'SQC_PERF_SEL_ICACHE_UTCL0_ALL_REQ', + 405: 'SQC_PERF_SEL_ICACHE_UTCL1_INFLIGHT_LEVEL', + 406: 'SQC_PERF_SEL_ICACHE_UTCL1_ALL_REQ', + 407: 'SQC_PERF_SEL_DCACHE_UTCL0_INFLIGHT_LEVEL', + 408: 'SQC_PERF_SEL_DCACHE_UTCL0_ALL_REQ', + 409: 'SQC_PERF_SEL_DCACHE_UTCL1_INFLIGHT_LEVEL', + 410: 'SQC_PERF_SEL_DCACHE_UTCL1_ALL_REQ', + 411: 'SQC_PERF_SEL_ICACHE_GCR', + 412: 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 413: 'SQC_PERF_SEL_DCACHE_GCR', + 414: 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 415: 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', + 416: 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', + 417: 'SQC_PERF_SEL_DCACHE_GCR_WRITEBACK', + 418: 'SQC_PERF_SEL_DUMMY_LAST', + 448: 'SP_PERF_SEL_DUMMY_BEGIN', + 511: 'SP_PERF_SEL_DUMMY_LAST', +} +SQ_PERF_SEL_NONE = 0 +SQ_PERF_SEL_ACCUM_PREV = 1 +SQ_PERF_SEL_CYCLES = 2 +SQ_PERF_SEL_BUSY_CYCLES = 3 +SQ_PERF_SEL_WAVES = 4 +SQ_PERF_SEL_WAVES_32 = 5 +SQ_PERF_SEL_WAVES_64 = 6 +SQ_PERF_SEL_LEVEL_WAVES = 7 +SQ_PERF_SEL_ITEMS = 8 +SQ_PERF_SEL_WAVE32_ITEMS = 9 +SQ_PERF_SEL_WAVE64_ITEMS = 10 +SQ_PERF_SEL_QUADS = 11 +SQ_PERF_SEL_EVENTS = 12 +SQ_PERF_SEL_WAVES_EQ_64 = 13 +SQ_PERF_SEL_WAVES_LT_64 = 14 +SQ_PERF_SEL_WAVES_LT_48 = 15 +SQ_PERF_SEL_WAVES_LT_32 = 16 +SQ_PERF_SEL_WAVES_LT_16 = 17 +SQ_PERF_SEL_WAVES_RESTORED = 18 +SQ_PERF_SEL_WAVES_SAVED = 19 +SQ_PERF_SEL_MSG = 20 +SQ_PERF_SEL_MSG_GSCNT = 21 +SQ_PERF_SEL_MSG_INTERRUPT = 22 +SQ_PERF_SEL_Reserved_1 = 23 +SQ_PERF_SEL_Reserved_2 = 24 +SQ_PERF_SEL_Reserved_3 = 25 +SQ_PERF_SEL_WAVE_CYCLES = 26 +SQ_PERF_SEL_WAVE_READY = 27 +SQ_PERF_SEL_WAIT_INST_ANY = 28 +SQ_PERF_SEL_WAIT_INST_VALU = 29 +SQ_PERF_SEL_WAIT_INST_SCA = 30 +SQ_PERF_SEL_WAIT_INST_LDS = 31 +SQ_PERF_SEL_WAIT_INST_TEX = 32 +SQ_PERF_SEL_WAIT_INST_FLAT = 33 +SQ_PERF_SEL_WAIT_INST_VMEM = 34 +SQ_PERF_SEL_WAIT_INST_EXP_GDS = 35 +SQ_PERF_SEL_WAIT_INST_BR_MSG = 36 +SQ_PERF_SEL_WAIT_ANY = 37 +SQ_PERF_SEL_WAIT_CNT_ANY = 38 +SQ_PERF_SEL_WAIT_CNT_VMVS = 39 +SQ_PERF_SEL_WAIT_CNT_LGKM = 40 +SQ_PERF_SEL_WAIT_CNT_EXP = 41 +SQ_PERF_SEL_WAIT_TTRACE = 42 +SQ_PERF_SEL_WAIT_IFETCH = 43 +SQ_PERF_SEL_WAIT_BARRIER = 44 +SQ_PERF_SEL_WAIT_EXP_ALLOC = 45 +SQ_PERF_SEL_WAIT_SLEEP = 46 +SQ_PERF_SEL_WAIT_SLEEP_XNACK = 47 +SQ_PERF_SEL_WAIT_OTHER = 48 +SQ_PERF_SEL_INSTS_ALL = 49 +SQ_PERF_SEL_INSTS_BRANCH = 50 +SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN = 51 +SQ_PERF_SEL_INSTS_CBRANCH_TAKEN = 52 +SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS = 53 +SQ_PERF_SEL_INSTS_EXP_GDS = 54 +SQ_PERF_SEL_INSTS_GDS = 55 +SQ_PERF_SEL_INSTS_EXP = 56 +SQ_PERF_SEL_INSTS_FLAT = 57 +SQ_PERF_SEL_Reserved_4 = 58 +SQ_PERF_SEL_INSTS_LDS = 59 +SQ_PERF_SEL_INSTS_SALU = 60 +SQ_PERF_SEL_INSTS_SMEM = 61 +SQ_PERF_SEL_INSTS_SMEM_NORM = 62 +SQ_PERF_SEL_INSTS_SENDMSG = 63 +SQ_PERF_SEL_INSTS_VALU = 64 +SQ_PERF_SEL_Reserved_17 = 65 +SQ_PERF_SEL_INSTS_VALU_TRANS32 = 66 +SQ_PERF_SEL_INSTS_VALU_NO_COEXEC = 67 +SQ_PERF_SEL_INSTS_TEX = 68 +SQ_PERF_SEL_INSTS_TEX_LOAD = 69 +SQ_PERF_SEL_INSTS_TEX_STORE = 70 +SQ_PERF_SEL_INSTS_WAVE32 = 71 +SQ_PERF_SEL_INSTS_WAVE32_FLAT = 72 +SQ_PERF_SEL_Reserved_5 = 73 +SQ_PERF_SEL_INSTS_WAVE32_LDS = 74 +SQ_PERF_SEL_INSTS_WAVE32_VALU = 75 +SQ_PERF_SEL_Reserved_16 = 76 +SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32 = 77 +SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC = 78 +SQ_PERF_SEL_INSTS_WAVE32_TEX = 79 +SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD = 80 +SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE = 81 +SQ_PERF_SEL_ITEM_CYCLES_VALU = 82 +SQ_PERF_SEL_VALU_READWRITELANE_CYCLES = 83 +SQ_PERF_SEL_WAVE32_INSTS = 84 +SQ_PERF_SEL_WAVE64_INSTS = 85 +SQ_PERF_SEL_Reserved_18 = 86 +SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED = 87 +SQ_PERF_SEL_WAVE64_HALF_SKIP = 88 +SQ_PERF_SEL_INSTS_TEX_REPLAY = 89 +SQ_PERF_SEL_INSTS_SMEM_REPLAY = 90 +SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY = 91 +SQ_PERF_SEL_INSTS_FLAT_REPLAY = 92 +SQ_PERF_SEL_XNACK_ALL = 93 +SQ_PERF_SEL_XNACK_FIRST = 94 +SQ_PERF_SEL_INSTS_VALU_LDS_DIRECT_RD = 95 +SQ_PERF_SEL_INSTS_VALU_VINTRP_OP = 96 +SQ_PERF_SEL_INST_LEVEL_EXP = 97 +SQ_PERF_SEL_INST_LEVEL_GDS = 98 +SQ_PERF_SEL_INST_LEVEL_LDS = 99 +SQ_PERF_SEL_INST_LEVEL_SMEM = 100 +SQ_PERF_SEL_INST_LEVEL_TEX_LOAD = 101 +SQ_PERF_SEL_INST_LEVEL_TEX_STORE = 102 +SQ_PERF_SEL_IFETCH_REQS = 103 +SQ_PERF_SEL_IFETCH_LEVEL = 104 +SQ_PERF_SEL_IFETCH_XNACK = 105 +SQ_PERF_SEL_Reserved_6 = 106 +SQ_PERF_SEL_Reserved_7 = 107 +SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL = 108 +SQ_PERF_SEL_VALU_SGATHER_STALL = 109 +SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL = 110 +SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL = 111 +SQ_PERF_SEL_VALU_SGATHER_FULL_STALL = 112 +SQ_PERF_SEL_SALU_SGATHER_STALL = 113 +SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL = 114 +SQ_PERF_SEL_SALU_GATHER_FULL_STALL = 115 +SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL = 116 +SQ_PERF_SEL_INST_CYCLES_VALU = 117 +SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32 = 118 +SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC = 119 +SQ_PERF_SEL_INST_CYCLES_VMEM = 120 +SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD = 121 +SQ_PERF_SEL_INST_CYCLES_VMEM_STORE = 122 +SQ_PERF_SEL_INST_CYCLES_LDS = 123 +SQ_PERF_SEL_INST_CYCLES_TEX = 124 +SQ_PERF_SEL_INST_CYCLES_FLAT = 125 +SQ_PERF_SEL_INST_CYCLES_EXP_GDS = 126 +SQ_PERF_SEL_VMEM_ARB_FIFO_FULL = 127 +SQ_PERF_SEL_MSG_FIFO_FULL_STALL = 128 +SQ_PERF_SEL_EXP_REQ_FIFO_FULL = 129 +SQ_PERF_SEL_Reserved_8 = 130 +SQ_PERF_SEL_Reserved_9 = 131 +SQ_PERF_SEL_Reserved_10 = 132 +SQ_PERF_SEL_Reserved_11 = 133 +SQ_PERF_SEL_Reserved_12 = 134 +SQ_PERF_SEL_Reserved_13 = 135 +SQ_PERF_SEL_Reserved_14 = 136 +SQ_PERF_SEL_VMEM_BUS_ACTIVE = 137 +SQ_PERF_SEL_VMEM_BUS_STALL = 138 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL = 139 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL = 140 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL = 141 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL = 142 +SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY = 143 +SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY = 144 +SQ_PERF_SEL_Reserved_15 = 145 +SQ_PERF_SEL_SALU_PIPE_STALL = 146 +SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES = 147 +SQ_PERF_SEL_SMEM_DCACHE_RETURN_STALL = 148 +SQ_PERF_SEL_MSG_BUS_BUSY = 149 +SQ_PERF_SEL_EXP_REQ_BUS_STALL = 150 +SQ_PERF_SEL_EXP_REQ0_BUS_BUSY = 151 +SQ_PERF_SEL_EXP_REQ1_BUS_BUSY = 152 +SQ_PERF_SEL_EXP_BUS0_BUSY = 153 +SQ_PERF_SEL_EXP_BUS1_BUSY = 154 +SQ_PERF_SEL_INST_CACHE_REQS = 155 +SQ_PERF_SEL_INST_CACHE_REQ_STALL = 156 +SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VALU = 157 +SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_SALU = 158 +SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VMEM = 159 +SQ_PERF_SEL_USER0 = 160 +SQ_PERF_SEL_USER1 = 161 +SQ_PERF_SEL_USER2 = 162 +SQ_PERF_SEL_USER3 = 163 +SQ_PERF_SEL_USER4 = 164 +SQ_PERF_SEL_USER5 = 165 +SQ_PERF_SEL_USER6 = 166 +SQ_PERF_SEL_USER7 = 167 +SQ_PERF_SEL_USER8 = 168 +SQ_PERF_SEL_USER9 = 169 +SQ_PERF_SEL_USER10 = 170 +SQ_PERF_SEL_USER11 = 171 +SQ_PERF_SEL_USER12 = 172 +SQ_PERF_SEL_USER13 = 173 +SQ_PERF_SEL_USER14 = 174 +SQ_PERF_SEL_USER15 = 175 +SQ_PERF_SEL_USER_LEVEL0 = 176 +SQ_PERF_SEL_USER_LEVEL1 = 177 +SQ_PERF_SEL_USER_LEVEL2 = 178 +SQ_PERF_SEL_USER_LEVEL3 = 179 +SQ_PERF_SEL_USER_LEVEL4 = 180 +SQ_PERF_SEL_USER_LEVEL5 = 181 +SQ_PERF_SEL_USER_LEVEL6 = 182 +SQ_PERF_SEL_USER_LEVEL7 = 183 +SQ_PERF_SEL_USER_LEVEL8 = 184 +SQ_PERF_SEL_USER_LEVEL9 = 185 +SQ_PERF_SEL_USER_LEVEL10 = 186 +SQ_PERF_SEL_USER_LEVEL11 = 187 +SQ_PERF_SEL_USER_LEVEL12 = 188 +SQ_PERF_SEL_USER_LEVEL13 = 189 +SQ_PERF_SEL_USER_LEVEL14 = 190 +SQ_PERF_SEL_USER_LEVEL15 = 191 +SQ_PERF_SEL_VALU_RETURN_SDST = 192 +SQ_PERF_SEL_VMEM_SECOND_TRY_USED = 193 +SQ_PERF_SEL_VMEM_SECOND_TRY_STALL = 194 +SQ_PERF_SEL_DUMMY_END = 195 +SQ_PERF_SEL_DUMMY_LAST = 255 +SQG_PERF_SEL_UTCL0_TRANSLATION_MISS = 256 +SQG_PERF_SEL_UTCL0_PERMISSION_MISS = 257 +SQG_PERF_SEL_UTCL0_TRANSLATION_HIT = 258 +SQG_PERF_SEL_UTCL0_REQUEST = 259 +SQG_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL = 260 +SQG_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX = 261 +SQG_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT = 262 +SQG_PERF_SEL_UTCL0_LFIFO_FULL = 263 +SQG_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES = 264 +SQG_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 265 +SQG_PERF_SEL_UTCL0_HIT_FIFO_FULL = 266 +SQG_PERF_SEL_UTCL0_UTCL1_REQ = 267 +SQG_PERF_SEL_TLB_SHOOTDOWN = 268 +SQG_PERF_SEL_TLB_SHOOTDOWN_CYCLES = 269 +SQG_PERF_SEL_TTRACE_REQS = 270 +SQG_PERF_SEL_TTRACE_INFLIGHT_REQS = 271 +SQG_PERF_SEL_TTRACE_STALL = 272 +SQG_PERF_SEL_TTRACE_LOST_PACKETS = 273 +SQG_PERF_SEL_DUMMY_LAST = 274 +SQC_PERF_SEL_POWER_VALU = 275 +SQC_PERF_SEL_POWER_VALU0 = 276 +SQC_PERF_SEL_POWER_VALU1 = 277 +SQC_PERF_SEL_POWER_VALU2 = 278 +SQC_PERF_SEL_POWER_GPR_RD = 279 +SQC_PERF_SEL_POWER_GPR_WR = 280 +SQC_PERF_SEL_POWER_LDS_BUSY = 281 +SQC_PERF_SEL_POWER_ALU_BUSY = 282 +SQC_PERF_SEL_POWER_TEX_BUSY = 283 +SQC_PERF_SEL_PT_POWER_STALL = 284 +SQC_PERF_SEL_LDS_BANK_CONFLICT = 285 +SQC_PERF_SEL_LDS_ADDR_CONFLICT = 286 +SQC_PERF_SEL_LDS_UNALIGNED_STALL = 287 +SQC_PERF_SEL_LDS_MEM_VIOLATIONS = 288 +SQC_PERF_SEL_LDS_ATOMIC_RETURN = 289 +SQC_PERF_SEL_LDS_IDX_ACTIVE = 290 +SQC_PERF_SEL_LDS_DATA_FIFO_FULL = 291 +SQC_PERF_SEL_LDS_CMD_FIFO_FULL = 292 +SQC_PERF_SEL_LDS_ADDR_STALL = 293 +SQC_PERF_SEL_LDS_ADDR_ACTIVE = 294 +SQC_PERF_SEL_LDS_DIRECT_FIFO_FULL_STALL = 295 +SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD = 296 +SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD = 297 +SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL = 298 +SQC_PERF_SEL_LDS_FP_ADD_CYCLES = 299 +SQC_PERF_SEL_ICACHE_BUSY_CYCLES = 300 +SQC_PERF_SEL_ICACHE_REQ = 301 +SQC_PERF_SEL_ICACHE_HITS = 302 +SQC_PERF_SEL_ICACHE_MISSES = 303 +SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE = 304 +SQC_PERF_SEL_ICACHE_INVAL_INST = 305 +SQC_PERF_SEL_ICACHE_INVAL_ASYNC = 306 +SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL = 307 +SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL = 308 +SQC_PERF_SEL_TC_INFLIGHT_LEVEL = 309 +SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL = 310 +SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL = 311 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READY = 312 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB = 313 +SQC_PERF_SEL_ICACHE_INPUT_VALIDB = 314 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READY = 315 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB = 316 +SQC_PERF_SEL_DCACHE_INPUT_VALIDB = 317 +SQC_PERF_SEL_TC_REQ = 318 +SQC_PERF_SEL_TC_INST_REQ = 319 +SQC_PERF_SEL_TC_DATA_READ_REQ = 320 +SQC_PERF_SEL_TC_DATA_WRITE_REQ = 321 +SQC_PERF_SEL_TC_DATA_ATOMIC_REQ = 322 +SQC_PERF_SEL_TC_STALL = 323 +SQC_PERF_SEL_TC_STARVE = 324 +SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT = 325 +SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB = 326 +SQC_PERF_SEL_ICACHE_CACHE_STALLED = 327 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO = 328 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX = 329 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT = 330 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO = 331 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO = 332 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF = 333 +SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT = 334 +SQC_PERF_SEL_DCACHE_BUSY_CYCLES = 335 +SQC_PERF_SEL_DCACHE_REQ = 336 +SQC_PERF_SEL_DCACHE_HITS = 337 +SQC_PERF_SEL_DCACHE_MISSES = 338 +SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE = 339 +SQC_PERF_SEL_DCACHE_INVAL_INST = 340 +SQC_PERF_SEL_DCACHE_INVAL_ASYNC = 341 +SQC_PERF_SEL_DCACHE_HIT_LRU_READ = 342 +SQC_PERF_SEL_DCACHE_WC_LRU_WRITE = 343 +SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE = 344 +SQC_PERF_SEL_DCACHE_ATOMIC = 345 +SQC_PERF_SEL_DCACHE_WB_INST = 346 +SQC_PERF_SEL_DCACHE_WB_ASYNC = 347 +SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT = 348 +SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB = 349 +SQC_PERF_SEL_DCACHE_CACHE_STALLED = 350 +SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_NONZERO = 351 +SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX = 352 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT = 353 +SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT = 354 +SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED = 355 +SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE = 356 +SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT = 357 +SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH = 358 +SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE = 359 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO = 360 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO = 361 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF = 362 +SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT = 363 +SQC_PERF_SEL_DCACHE_REQ_READ_1 = 364 +SQC_PERF_SEL_DCACHE_REQ_READ_2 = 365 +SQC_PERF_SEL_DCACHE_REQ_READ_4 = 366 +SQC_PERF_SEL_DCACHE_REQ_READ_8 = 367 +SQC_PERF_SEL_DCACHE_REQ_READ_16 = 368 +SQC_PERF_SEL_DCACHE_REQ_TIME = 369 +SQC_PERF_SEL_DCACHE_REQ_WRITE_1 = 370 +SQC_PERF_SEL_DCACHE_REQ_WRITE_2 = 371 +SQC_PERF_SEL_DCACHE_REQ_WRITE_4 = 372 +SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE = 373 +SQC_PERF_SEL_SQ_DCACHE_REQS = 374 +SQC_PERF_SEL_DCACHE_FLAT_REQ = 375 +SQC_PERF_SEL_DCACHE_NONFLAT_REQ = 376 +SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_MISS = 377 +SQC_PERF_SEL_ICACHE_UTCL0_PERMISSION_MISS = 378 +SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_HIT = 379 +SQC_PERF_SEL_ICACHE_UTCL0_REQUEST = 380 +SQC_PERF_SEL_ICACHE_UTCL0_XNACK = 381 +SQC_PERF_SEL_ICACHE_UTCL0_STALL_INFLIGHT_MAX = 382 +SQC_PERF_SEL_ICACHE_UTCL0_STALL_LRU_INFLIGHT = 383 +SQC_PERF_SEL_ICACHE_UTCL0_LFIFO_FULL = 384 +SQC_PERF_SEL_ICACHE_UTCL0_STALL_LFIFO_NOT_RES = 385 +SQC_PERF_SEL_ICACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 386 +SQC_PERF_SEL_ICACHE_UTCL0_UTCL1_INFLIGHT = 387 +SQC_PERF_SEL_ICACHE_UTCL0_STALL_MISSFIFO_FULL = 388 +SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_MISS = 389 +SQC_PERF_SEL_DCACHE_UTCL0_PERMISSION_MISS = 390 +SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_HIT = 391 +SQC_PERF_SEL_DCACHE_UTCL0_REQUEST = 392 +SQC_PERF_SEL_DCACHE_UTCL0_XNACK = 393 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_INFLIGHT_MAX = 394 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_LRU_INFLIGHT = 395 +SQC_PERF_SEL_DCACHE_UTCL0_LFIFO_FULL = 396 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_LFIFO_NOT_RES = 397 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 398 +SQC_PERF_SEL_DCACHE_UTCL0_UTCL1_INFLIGHT = 399 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_MISSFIFO_FULL = 400 +SQC_PERF_SEL_DCACHE_UTCL0_STALL_MULTI_MISS = 401 +SQC_PERF_SEL_DCACHE_UTCL0_HIT_FIFO_FULL = 402 +SQC_PERF_SEL_ICACHE_UTCL0_INFLIGHT_LEVEL = 403 +SQC_PERF_SEL_ICACHE_UTCL0_ALL_REQ = 404 +SQC_PERF_SEL_ICACHE_UTCL1_INFLIGHT_LEVEL = 405 +SQC_PERF_SEL_ICACHE_UTCL1_ALL_REQ = 406 +SQC_PERF_SEL_DCACHE_UTCL0_INFLIGHT_LEVEL = 407 +SQC_PERF_SEL_DCACHE_UTCL0_ALL_REQ = 408 +SQC_PERF_SEL_DCACHE_UTCL1_INFLIGHT_LEVEL = 409 +SQC_PERF_SEL_DCACHE_UTCL1_ALL_REQ = 410 +SQC_PERF_SEL_ICACHE_GCR = 411 +SQC_PERF_SEL_ICACHE_GCR_HITS = 412 +SQC_PERF_SEL_DCACHE_GCR = 413 +SQC_PERF_SEL_DCACHE_GCR_HITS = 414 +SQC_PERF_SEL_ICACHE_GCR_INVALIDATE = 415 +SQC_PERF_SEL_DCACHE_GCR_INVALIDATE = 416 +SQC_PERF_SEL_DCACHE_GCR_WRITEBACK = 417 +SQC_PERF_SEL_DUMMY_LAST = 418 +SP_PERF_SEL_DUMMY_BEGIN = 448 +SP_PERF_SEL_DUMMY_LAST = 511 +SQ_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_CAC_POWER_SEL' +SQ_CAC_POWER_SEL__enumvalues = { + 0: 'SQ_CAC_POWER_VALU', + 1: 'SQ_CAC_POWER_VALU0', + 2: 'SQ_CAC_POWER_VALU1', + 3: 'SQ_CAC_POWER_VALU2', + 4: 'SQ_CAC_POWER_GPR_RD', + 5: 'SQ_CAC_POWER_GPR_WR', + 6: 'SQ_CAC_POWER_LDS_BUSY', + 7: 'SQ_CAC_POWER_ALU_BUSY', + 8: 'SQ_CAC_POWER_TEX_BUSY', +} +SQ_CAC_POWER_VALU = 0 +SQ_CAC_POWER_VALU0 = 1 +SQ_CAC_POWER_VALU1 = 2 +SQ_CAC_POWER_VALU2 = 3 +SQ_CAC_POWER_GPR_RD = 4 +SQ_CAC_POWER_GPR_WR = 5 +SQ_CAC_POWER_LDS_BUSY = 6 +SQ_CAC_POWER_ALU_BUSY = 7 +SQ_CAC_POWER_TEX_BUSY = 8 +SQ_CAC_POWER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_CMD' +SQ_IND_CMD_CMD__enumvalues = { + 0: 'SQ_IND_CMD_CMD_NULL', + 1: 'SQ_IND_CMD_CMD_SETHALT', + 2: 'SQ_IND_CMD_CMD_SAVECTX', + 3: 'SQ_IND_CMD_CMD_KILL', + 4: 'SQ_IND_CMD_CMD_DEBUG', + 5: 'SQ_IND_CMD_CMD_TRAP', + 6: 'SQ_IND_CMD_CMD_SET_SPI_PRIO', + 7: 'SQ_IND_CMD_CMD_SETFATALHALT', + 8: 'SQ_IND_CMD_CMD_SINGLE_STEP', +} +SQ_IND_CMD_CMD_NULL = 0 +SQ_IND_CMD_CMD_SETHALT = 1 +SQ_IND_CMD_CMD_SAVECTX = 2 +SQ_IND_CMD_CMD_KILL = 3 +SQ_IND_CMD_CMD_DEBUG = 4 +SQ_IND_CMD_CMD_TRAP = 5 +SQ_IND_CMD_CMD_SET_SPI_PRIO = 6 +SQ_IND_CMD_CMD_SETFATALHALT = 7 +SQ_IND_CMD_CMD_SINGLE_STEP = 8 +SQ_IND_CMD_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_MODE' +SQ_IND_CMD_MODE__enumvalues = { + 0: 'SQ_IND_CMD_MODE_SINGLE', + 1: 'SQ_IND_CMD_MODE_BROADCAST', + 2: 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', + 3: 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 4: 'SQ_IND_CMD_MODE_BROADCAST_ME', +} +SQ_IND_CMD_MODE_SINGLE = 0 +SQ_IND_CMD_MODE_BROADCAST = 1 +SQ_IND_CMD_MODE_BROADCAST_QUEUE = 2 +SQ_IND_CMD_MODE_BROADCAST_PIPE = 3 +SQ_IND_CMD_MODE_BROADCAST_ME = 4 +SQ_IND_CMD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_EDC_INFO_SOURCE' +SQ_EDC_INFO_SOURCE__enumvalues = { + 0: 'SQ_EDC_INFO_SOURCE_INVALID', + 1: 'SQ_EDC_INFO_SOURCE_INST', + 2: 'SQ_EDC_INFO_SOURCE_SGPR', + 3: 'SQ_EDC_INFO_SOURCE_VGPR', + 4: 'SQ_EDC_INFO_SOURCE_LDS', + 5: 'SQ_EDC_INFO_SOURCE_GDS', + 6: 'SQ_EDC_INFO_SOURCE_TA', +} +SQ_EDC_INFO_SOURCE_INVALID = 0 +SQ_EDC_INFO_SOURCE_INST = 1 +SQ_EDC_INFO_SOURCE_SGPR = 2 +SQ_EDC_INFO_SOURCE_VGPR = 3 +SQ_EDC_INFO_SOURCE_LDS = 4 +SQ_EDC_INFO_SOURCE_GDS = 5 +SQ_EDC_INFO_SOURCE_TA = 6 +SQ_EDC_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_ROUND_MODE' +SQ_ROUND_MODE__enumvalues = { + 0: 'SQ_ROUND_NEAREST_EVEN', + 1: 'SQ_ROUND_PLUS_INFINITY', + 2: 'SQ_ROUND_MINUS_INFINITY', + 3: 'SQ_ROUND_TO_ZERO', +} +SQ_ROUND_NEAREST_EVEN = 0 +SQ_ROUND_PLUS_INFINITY = 1 +SQ_ROUND_MINUS_INFINITY = 2 +SQ_ROUND_TO_ZERO = 3 +SQ_ROUND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INTERRUPT_WORD_ENCODING' +SQ_INTERRUPT_WORD_ENCODING__enumvalues = { + 0: 'SQ_INTERRUPT_WORD_ENCODING_AUTO', + 1: 'SQ_INTERRUPT_WORD_ENCODING_INST', + 2: 'SQ_INTERRUPT_WORD_ENCODING_ERROR', +} +SQ_INTERRUPT_WORD_ENCODING_AUTO = 0 +SQ_INTERRUPT_WORD_ENCODING_INST = 1 +SQ_INTERRUPT_WORD_ENCODING_ERROR = 2 +SQ_INTERRUPT_WORD_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IBUF_ST' +SQ_IBUF_ST__enumvalues = { + 0: 'SQ_IBUF_IB_IDLE', + 1: 'SQ_IBUF_IB_INI_WAIT_GNT', + 2: 'SQ_IBUF_IB_INI_WAIT_DRET', + 3: 'SQ_IBUF_IB_LE_4DW', + 4: 'SQ_IBUF_IB_WAIT_DRET', + 5: 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 6: 'SQ_IBUF_IB_DRET', + 7: 'SQ_IBUF_IB_EMPTY_WAIT_GNT', +} +SQ_IBUF_IB_IDLE = 0 +SQ_IBUF_IB_INI_WAIT_GNT = 1 +SQ_IBUF_IB_INI_WAIT_DRET = 2 +SQ_IBUF_IB_LE_4DW = 3 +SQ_IBUF_IB_WAIT_DRET = 4 +SQ_IBUF_IB_EMPTY_WAIT_DRET = 5 +SQ_IBUF_IB_DRET = 6 +SQ_IBUF_IB_EMPTY_WAIT_GNT = 7 +SQ_IBUF_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_STR_ST' +SQ_INST_STR_ST__enumvalues = { + 0: 'SQ_INST_STR_IB_WAVE_NORML', + 1: 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 2: 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 3: 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 4: 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST0', + 5: 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST1', + 6: 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', + 7: 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', +} +SQ_INST_STR_IB_WAVE_NORML = 0 +SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV = 1 +SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV = 2 +SQ_INST_STR_IB_WAVE_INST_SKIP_AV = 3 +SQ_INST_STR_IB_WAVE_SETVSKIP_ST0 = 4 +SQ_INST_STR_IB_WAVE_SETVSKIP_ST1 = 5 +SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT = 6 +SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT = 7 +SQ_INST_STR_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_IB_ECC_ST' +SQ_WAVE_IB_ECC_ST__enumvalues = { + 0: 'SQ_WAVE_IB_ECC_CLEAN', + 1: 'SQ_WAVE_IB_ECC_ERR_CONTINUE', + 2: 'SQ_WAVE_IB_ECC_ERR_HALT', + 3: 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', +} +SQ_WAVE_IB_ECC_CLEAN = 0 +SQ_WAVE_IB_ECC_ERR_CONTINUE = 1 +SQ_WAVE_IB_ECC_ERR_HALT = 2 +SQ_WAVE_IB_ECC_WITH_ERR_MSG = 3 +SQ_WAVE_IB_ECC_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ADDRESS_MODE' +SH_MEM_ADDRESS_MODE__enumvalues = { + 0: 'SH_MEM_ADDRESS_MODE_64', + 1: 'SH_MEM_ADDRESS_MODE_32', +} +SH_MEM_ADDRESS_MODE_64 = 0 +SH_MEM_ADDRESS_MODE_32 = 1 +SH_MEM_ADDRESS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_RETRY_MODE' +SH_MEM_RETRY_MODE__enumvalues = { + 0: 'SH_MEM_RETRY_MODE_ALL', + 1: 'SH_MEM_RETRY_MODE_WRITEATOMIC', + 2: 'SH_MEM_RETRY_MODE_NONE', +} +SH_MEM_RETRY_MODE_ALL = 0 +SH_MEM_RETRY_MODE_WRITEATOMIC = 1 +SH_MEM_RETRY_MODE_NONE = 2 +SH_MEM_RETRY_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ALIGNMENT_MODE' +SH_MEM_ALIGNMENT_MODE__enumvalues = { + 0: 'SH_MEM_ALIGNMENT_MODE_DWORD', + 1: 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 2: 'SH_MEM_ALIGNMENT_MODE_STRICT', + 3: 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', +} +SH_MEM_ALIGNMENT_MODE_DWORD = 0 +SH_MEM_ALIGNMENT_MODE_DWORD_STRICT = 1 +SH_MEM_ALIGNMENT_MODE_STRICT = 2 +SH_MEM_ALIGNMENT_MODE_UNALIGNED = 3 +SH_MEM_ALIGNMENT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_TOKEN_MASK_SQDEC_SHIFT', + 1: 'SQ_TT_TOKEN_MASK_SHDEC_SHIFT', + 2: 'SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT', + 3: 'SQ_TT_TOKEN_MASK_COMP_SHIFT', + 4: 'SQ_TT_TOKEN_MASK_CONTEXT_SHIFT', + 5: 'SQ_TT_TOKEN_MASK_CONFIG_SHIFT', + 6: 'SQ_TT_TOKEN_MASK_OTHER_SHIFT', + 7: 'SQ_TT_TOKEN_MASK_READS_SHIFT', +} +SQ_TT_TOKEN_MASK_SQDEC_SHIFT = 0 +SQ_TT_TOKEN_MASK_SHDEC_SHIFT = 1 +SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT = 2 +SQ_TT_TOKEN_MASK_COMP_SHIFT = 3 +SQ_TT_TOKEN_MASK_CONTEXT_SHIFT = 4 +SQ_TT_TOKEN_MASK_CONFIG_SHIFT = 5 +SQ_TT_TOKEN_MASK_OTHER_SHIFT = 6 +SQ_TT_TOKEN_MASK_READS_SHIFT = 7 +SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_INCLUDE' +SQ_TT_TOKEN_MASK_REG_INCLUDE__enumvalues = { + 1: 'SQ_TT_TOKEN_MASK_SQDEC_BIT', + 2: 'SQ_TT_TOKEN_MASK_SHDEC_BIT', + 4: 'SQ_TT_TOKEN_MASK_GFXUDEC_BIT', + 8: 'SQ_TT_TOKEN_MASK_COMP_BIT', + 16: 'SQ_TT_TOKEN_MASK_CONTEXT_BIT', + 32: 'SQ_TT_TOKEN_MASK_CONFIG_BIT', + 64: 'SQ_TT_TOKEN_MASK_OTHER_BIT', + 128: 'SQ_TT_TOKEN_MASK_READS_BIT', +} +SQ_TT_TOKEN_MASK_SQDEC_BIT = 1 +SQ_TT_TOKEN_MASK_SHDEC_BIT = 2 +SQ_TT_TOKEN_MASK_GFXUDEC_BIT = 4 +SQ_TT_TOKEN_MASK_COMP_BIT = 8 +SQ_TT_TOKEN_MASK_CONTEXT_BIT = 16 +SQ_TT_TOKEN_MASK_CONFIG_BIT = 32 +SQ_TT_TOKEN_MASK_OTHER_BIT = 64 +SQ_TT_TOKEN_MASK_READS_BIT = 128 +SQ_TT_TOKEN_MASK_REG_INCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT', + 1: 'SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT', + 2: 'SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT', + 3: 'SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT', + 4: 'SQ_TT_TOKEN_EXCLUDE_IMMED1_SHIFT', + 5: 'SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT', + 6: 'SQ_TT_TOKEN_EXCLUDE_REG_SHIFT', + 7: 'SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT', + 8: 'SQ_TT_TOKEN_EXCLUDE_INST_SHIFT', + 9: 'SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT', + 10: 'SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT', + 11: 'SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT', +} +SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT = 0 +SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT = 1 +SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT = 2 +SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT = 3 +SQ_TT_TOKEN_EXCLUDE_IMMED1_SHIFT = 4 +SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT = 5 +SQ_TT_TOKEN_EXCLUDE_REG_SHIFT = 6 +SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT = 7 +SQ_TT_TOKEN_EXCLUDE_INST_SHIFT = 8 +SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT = 9 +SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT = 10 +SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT = 11 +SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_INST_EXCLUDE' +SQ_TT_TOKEN_MASK_INST_EXCLUDE__enumvalues = { + 0: 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD', + 1: 'SQ_TT_INST_EXCLUDE_EXPGNT234', +} +SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD = 0 +SQ_TT_INST_EXCLUDE_EXPGNT234 = 1 +SQ_TT_TOKEN_MASK_INST_EXCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_MODE' +SQ_TT_MODE__enumvalues = { + 0: 'SQ_TT_MODE_OFF', + 1: 'SQ_TT_MODE_ON', + 2: 'SQ_TT_MODE_GLOBAL', + 3: 'SQ_TT_MODE_DETAIL', +} +SQ_TT_MODE_OFF = 0 +SQ_TT_MODE_ON = 1 +SQ_TT_MODE_GLOBAL = 2 +SQ_TT_MODE_DETAIL = 3 +SQ_TT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WTYPE_INCLUDE_SHIFT' +SQ_TT_WTYPE_INCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_WTYPE_INCLUDE_PS_SHIFT', + 1: 'SQ_TT_WTYPE_INCLUDE_VS_SHIFT', + 2: 'SQ_TT_WTYPE_INCLUDE_GS_SHIFT', + 3: 'SQ_TT_WTYPE_INCLUDE_ES_SHIFT', + 4: 'SQ_TT_WTYPE_INCLUDE_HS_SHIFT', + 5: 'SQ_TT_WTYPE_INCLUDE_LS_SHIFT', + 6: 'SQ_TT_WTYPE_INCLUDE_CS_SHIFT', +} +SQ_TT_WTYPE_INCLUDE_PS_SHIFT = 0 +SQ_TT_WTYPE_INCLUDE_VS_SHIFT = 1 +SQ_TT_WTYPE_INCLUDE_GS_SHIFT = 2 +SQ_TT_WTYPE_INCLUDE_ES_SHIFT = 3 +SQ_TT_WTYPE_INCLUDE_HS_SHIFT = 4 +SQ_TT_WTYPE_INCLUDE_LS_SHIFT = 5 +SQ_TT_WTYPE_INCLUDE_CS_SHIFT = 6 +SQ_TT_WTYPE_INCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WTYPE_INCLUDE' +SQ_TT_WTYPE_INCLUDE__enumvalues = { + 1: 'SQ_TT_WTYPE_INCLUDE_PS_BIT', + 2: 'SQ_TT_WTYPE_INCLUDE_VS_BIT', + 4: 'SQ_TT_WTYPE_INCLUDE_GS_BIT', + 8: 'SQ_TT_WTYPE_INCLUDE_ES_BIT', + 16: 'SQ_TT_WTYPE_INCLUDE_HS_BIT', + 32: 'SQ_TT_WTYPE_INCLUDE_LS_BIT', + 64: 'SQ_TT_WTYPE_INCLUDE_CS_BIT', +} +SQ_TT_WTYPE_INCLUDE_PS_BIT = 1 +SQ_TT_WTYPE_INCLUDE_VS_BIT = 2 +SQ_TT_WTYPE_INCLUDE_GS_BIT = 4 +SQ_TT_WTYPE_INCLUDE_ES_BIT = 8 +SQ_TT_WTYPE_INCLUDE_HS_BIT = 16 +SQ_TT_WTYPE_INCLUDE_LS_BIT = 32 +SQ_TT_WTYPE_INCLUDE_CS_BIT = 64 +SQ_TT_WTYPE_INCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_UTIL_TIMER' +SQ_TT_UTIL_TIMER__enumvalues = { + 0: 'SQ_TT_UTIL_TIMER_100_CLK', + 1: 'SQ_TT_UTIL_TIMER_250_CLK', +} +SQ_TT_UTIL_TIMER_100_CLK = 0 +SQ_TT_UTIL_TIMER_250_CLK = 1 +SQ_TT_UTIL_TIMER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WAVESTART_MODE' +SQ_TT_WAVESTART_MODE__enumvalues = { + 0: 'SQ_TT_WAVESTART_MODE_SHORT', + 1: 'SQ_TT_WAVESTART_MODE_ALLOC', + 2: 'SQ_TT_WAVESTART_MODE_PBB_ID', +} +SQ_TT_WAVESTART_MODE_SHORT = 0 +SQ_TT_WAVESTART_MODE_ALLOC = 1 +SQ_TT_WAVESTART_MODE_PBB_ID = 2 +SQ_TT_WAVESTART_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_RT_FREQ' +SQ_TT_RT_FREQ__enumvalues = { + 0: 'SQ_TT_RT_FREQ_NEVER', + 1: 'SQ_TT_RT_FREQ_1024_CLK', + 2: 'SQ_TT_RT_FREQ_4096_CLK', +} +SQ_TT_RT_FREQ_NEVER = 0 +SQ_TT_RT_FREQ_1024_CLK = 1 +SQ_TT_RT_FREQ_4096_CLK = 2 +SQ_TT_RT_FREQ = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WATCH_MODES' +SQ_WATCH_MODES__enumvalues = { + 0: 'SQ_WATCH_MODE_READ', + 1: 'SQ_WATCH_MODE_NONREAD', + 2: 'SQ_WATCH_MODE_ATOMIC', + 3: 'SQ_WATCH_MODE_ALL', +} +SQ_WATCH_MODE_READ = 0 +SQ_WATCH_MODE_NONREAD = 1 +SQ_WATCH_MODE_ATOMIC = 2 +SQ_WATCH_MODE_ALL = 3 +SQ_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_SCHED_MODES' +SQ_WAVE_SCHED_MODES__enumvalues = { + 0: 'SQ_WAVE_SCHED_MODE_NORMAL', + 1: 'SQ_WAVE_SCHED_MODE_EXPERT', + 2: 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST', +} +SQ_WAVE_SCHED_MODE_NORMAL = 0 +SQ_WAVE_SCHED_MODE_EXPERT = 1 +SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST = 2 +SQ_WAVE_SCHED_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'CSDATA_TYPE' +CSDATA_TYPE__enumvalues = { + 0: 'CSDATA_TYPE_TG', + 1: 'CSDATA_TYPE_STATE', + 2: 'CSDATA_TYPE_EVENT', + 3: 'CSDATA_TYPE_PRIVATE', +} +CSDATA_TYPE_TG = 0 +CSDATA_TYPE_STATE = 1 +CSDATA_TYPE_EVENT = 2 +CSDATA_TYPE_PRIVATE = 3 +CSDATA_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CSCNTL_TYPE' +CSCNTL_TYPE__enumvalues = { + 0: 'CSCNTL_TYPE_TG', + 1: 'CSCNTL_TYPE_STATE', + 2: 'CSCNTL_TYPE_EVENT', + 3: 'CSCNTL_TYPE_PRIVATE', +} +CSCNTL_TYPE_TG = 0 +CSCNTL_TYPE_STATE = 1 +CSCNTL_TYPE_EVENT = 2 +CSCNTL_TYPE_PRIVATE = 3 +CSCNTL_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUT_PRIM_TYPE' +VGT_OUT_PRIM_TYPE__enumvalues = { + 0: 'VGT_OUT_POINT', + 1: 'VGT_OUT_LINE', + 2: 'VGT_OUT_TRI', + 3: 'VGT_OUT_RECT_V0', + 4: 'VGT_OUT_RECT_V1', + 5: 'VGT_OUT_RECT_V2', + 6: 'VGT_OUT_RECT_V3', + 7: 'VGT_OUT_2D_RECT', + 8: 'VGT_TE_QUAD', + 9: 'VGT_TE_PRIM_INDEX_LINE', + 10: 'VGT_TE_PRIM_INDEX_TRI', + 11: 'VGT_TE_PRIM_INDEX_QUAD', + 12: 'VGT_OUT_LINE_ADJ', + 13: 'VGT_OUT_TRI_ADJ', + 14: 'VGT_OUT_PATCH', +} +VGT_OUT_POINT = 0 +VGT_OUT_LINE = 1 +VGT_OUT_TRI = 2 +VGT_OUT_RECT_V0 = 3 +VGT_OUT_RECT_V1 = 4 +VGT_OUT_RECT_V2 = 5 +VGT_OUT_RECT_V3 = 6 +VGT_OUT_2D_RECT = 7 +VGT_TE_QUAD = 8 +VGT_TE_PRIM_INDEX_LINE = 9 +VGT_TE_PRIM_INDEX_TRI = 10 +VGT_TE_PRIM_INDEX_QUAD = 11 +VGT_OUT_LINE_ADJ = 12 +VGT_OUT_TRI_ADJ = 13 +VGT_OUT_PATCH = 14 +VGT_OUT_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_PRIM_TYPE' +VGT_DI_PRIM_TYPE__enumvalues = { + 0: 'DI_PT_NONE', + 1: 'DI_PT_POINTLIST', + 2: 'DI_PT_LINELIST', + 3: 'DI_PT_LINESTRIP', + 4: 'DI_PT_TRILIST', + 5: 'DI_PT_TRIFAN', + 6: 'DI_PT_TRISTRIP', + 7: 'DI_PT_2D_RECTANGLE', + 8: 'DI_PT_UNUSED_1', + 9: 'DI_PT_PATCH', + 10: 'DI_PT_LINELIST_ADJ', + 11: 'DI_PT_LINESTRIP_ADJ', + 12: 'DI_PT_TRILIST_ADJ', + 13: 'DI_PT_TRISTRIP_ADJ', + 14: 'DI_PT_UNUSED_3', + 15: 'DI_PT_UNUSED_4', + 16: 'DI_PT_TRI_WITH_WFLAGS', + 17: 'DI_PT_RECTLIST', + 18: 'DI_PT_LINELOOP', + 19: 'DI_PT_QUADLIST', + 20: 'DI_PT_QUADSTRIP', + 21: 'DI_PT_POLYGON', +} +DI_PT_NONE = 0 +DI_PT_POINTLIST = 1 +DI_PT_LINELIST = 2 +DI_PT_LINESTRIP = 3 +DI_PT_TRILIST = 4 +DI_PT_TRIFAN = 5 +DI_PT_TRISTRIP = 6 +DI_PT_2D_RECTANGLE = 7 +DI_PT_UNUSED_1 = 8 +DI_PT_PATCH = 9 +DI_PT_LINELIST_ADJ = 10 +DI_PT_LINESTRIP_ADJ = 11 +DI_PT_TRILIST_ADJ = 12 +DI_PT_TRISTRIP_ADJ = 13 +DI_PT_UNUSED_3 = 14 +DI_PT_UNUSED_4 = 15 +DI_PT_TRI_WITH_WFLAGS = 16 +DI_PT_RECTLIST = 17 +DI_PT_LINELOOP = 18 +DI_PT_QUADLIST = 19 +DI_PT_QUADSTRIP = 20 +DI_PT_POLYGON = 21 +VGT_DI_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_SOURCE_SELECT' +VGT_DI_SOURCE_SELECT__enumvalues = { + 0: 'DI_SRC_SEL_DMA', + 1: 'DI_SRC_SEL_IMMEDIATE', + 2: 'DI_SRC_SEL_AUTO_INDEX', + 3: 'DI_SRC_SEL_RESERVED', +} +DI_SRC_SEL_DMA = 0 +DI_SRC_SEL_IMMEDIATE = 1 +DI_SRC_SEL_AUTO_INDEX = 2 +DI_SRC_SEL_RESERVED = 3 +VGT_DI_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_MAJOR_MODE_SELECT' +VGT_DI_MAJOR_MODE_SELECT__enumvalues = { + 0: 'DI_MAJOR_MODE_0', + 1: 'DI_MAJOR_MODE_1', +} +DI_MAJOR_MODE_0 = 0 +DI_MAJOR_MODE_1 = 1 +VGT_DI_MAJOR_MODE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_INDEX_SIZE' +VGT_DI_INDEX_SIZE__enumvalues = { + 0: 'DI_INDEX_SIZE_16_BIT', + 1: 'DI_INDEX_SIZE_32_BIT', + 2: 'DI_INDEX_SIZE_8_BIT', +} +DI_INDEX_SIZE_16_BIT = 0 +DI_INDEX_SIZE_32_BIT = 1 +DI_INDEX_SIZE_8_BIT = 2 +VGT_DI_INDEX_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_EVENT_TYPE' +VGT_EVENT_TYPE__enumvalues = { + 0: 'Reserved_0x00', + 1: 'SAMPLE_STREAMOUTSTATS1', + 2: 'SAMPLE_STREAMOUTSTATS2', + 3: 'SAMPLE_STREAMOUTSTATS3', + 4: 'CACHE_FLUSH_TS', + 5: 'CONTEXT_DONE', + 6: 'CACHE_FLUSH', + 7: 'CS_PARTIAL_FLUSH', + 8: 'VGT_STREAMOUT_SYNC', + 9: 'SET_FE_ID', + 10: 'VGT_STREAMOUT_RESET', + 11: 'END_OF_PIPE_INCR_DE', + 12: 'END_OF_PIPE_IB_END', + 13: 'RST_PIX_CNT', + 14: 'BREAK_BATCH', + 15: 'VS_PARTIAL_FLUSH', + 16: 'PS_PARTIAL_FLUSH', + 17: 'FLUSH_HS_OUTPUT', + 18: 'FLUSH_DFSM', + 19: 'RESET_TO_LOWEST_VGT', + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', + 21: 'ZPASS_DONE', + 22: 'CACHE_FLUSH_AND_INV_EVENT', + 23: 'PERFCOUNTER_START', + 24: 'PERFCOUNTER_STOP', + 25: 'PIPELINESTAT_START', + 26: 'PIPELINESTAT_STOP', + 27: 'PERFCOUNTER_SAMPLE', + 28: 'FLUSH_ES_OUTPUT', + 29: 'BIN_CONF_OVERRIDE_CHECK', + 30: 'SAMPLE_PIPELINESTAT', + 31: 'SO_VGTSTREAMOUT_FLUSH', + 32: 'SAMPLE_STREAMOUTSTATS', + 33: 'RESET_VTX_CNT', + 34: 'BLOCK_CONTEXT_DONE', + 35: 'CS_CONTEXT_DONE', + 36: 'VGT_FLUSH', + 37: 'TGID_ROLLOVER', + 38: 'SQ_NON_EVENT', + 39: 'SC_SEND_DB_VPZ', + 40: 'BOTTOM_OF_PIPE_TS', + 41: 'FLUSH_SX_TS', + 42: 'DB_CACHE_FLUSH_AND_INV', + 43: 'FLUSH_AND_INV_DB_DATA_TS', + 44: 'FLUSH_AND_INV_DB_META', + 45: 'FLUSH_AND_INV_CB_DATA_TS', + 46: 'FLUSH_AND_INV_CB_META', + 47: 'CS_DONE', + 48: 'PS_DONE', + 49: 'FLUSH_AND_INV_CB_PIXEL_DATA', + 50: 'SX_CB_RAT_ACK_REQUEST', + 51: 'THREAD_TRACE_START', + 52: 'THREAD_TRACE_STOP', + 53: 'THREAD_TRACE_MARKER', + 54: 'THREAD_TRACE_DRAW', + 55: 'THREAD_TRACE_FINISH', + 56: 'PIXEL_PIPE_STAT_CONTROL', + 57: 'PIXEL_PIPE_STAT_DUMP', + 58: 'PIXEL_PIPE_STAT_RESET', + 59: 'CONTEXT_SUSPEND', + 60: 'OFFCHIP_HS_DEALLOC', + 61: 'ENABLE_NGG_PIPELINE', + 62: 'ENABLE_LEGACY_PIPELINE', + 63: 'DRAW_DONE', +} +Reserved_0x00 = 0 +SAMPLE_STREAMOUTSTATS1 = 1 +SAMPLE_STREAMOUTSTATS2 = 2 +SAMPLE_STREAMOUTSTATS3 = 3 +CACHE_FLUSH_TS = 4 +CONTEXT_DONE = 5 +CACHE_FLUSH = 6 +CS_PARTIAL_FLUSH = 7 +VGT_STREAMOUT_SYNC = 8 +SET_FE_ID = 9 +VGT_STREAMOUT_RESET = 10 +END_OF_PIPE_INCR_DE = 11 +END_OF_PIPE_IB_END = 12 +RST_PIX_CNT = 13 +BREAK_BATCH = 14 +VS_PARTIAL_FLUSH = 15 +PS_PARTIAL_FLUSH = 16 +FLUSH_HS_OUTPUT = 17 +FLUSH_DFSM = 18 +RESET_TO_LOWEST_VGT = 19 +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +ZPASS_DONE = 21 +CACHE_FLUSH_AND_INV_EVENT = 22 +PERFCOUNTER_START = 23 +PERFCOUNTER_STOP = 24 +PIPELINESTAT_START = 25 +PIPELINESTAT_STOP = 26 +PERFCOUNTER_SAMPLE = 27 +FLUSH_ES_OUTPUT = 28 +BIN_CONF_OVERRIDE_CHECK = 29 +SAMPLE_PIPELINESTAT = 30 +SO_VGTSTREAMOUT_FLUSH = 31 +SAMPLE_STREAMOUTSTATS = 32 +RESET_VTX_CNT = 33 +BLOCK_CONTEXT_DONE = 34 +CS_CONTEXT_DONE = 35 +VGT_FLUSH = 36 +TGID_ROLLOVER = 37 +SQ_NON_EVENT = 38 +SC_SEND_DB_VPZ = 39 +BOTTOM_OF_PIPE_TS = 40 +FLUSH_SX_TS = 41 +DB_CACHE_FLUSH_AND_INV = 42 +FLUSH_AND_INV_DB_DATA_TS = 43 +FLUSH_AND_INV_DB_META = 44 +FLUSH_AND_INV_CB_DATA_TS = 45 +FLUSH_AND_INV_CB_META = 46 +CS_DONE = 47 +PS_DONE = 48 +FLUSH_AND_INV_CB_PIXEL_DATA = 49 +SX_CB_RAT_ACK_REQUEST = 50 +THREAD_TRACE_START = 51 +THREAD_TRACE_STOP = 52 +THREAD_TRACE_MARKER = 53 +THREAD_TRACE_DRAW = 54 +THREAD_TRACE_FINISH = 55 +PIXEL_PIPE_STAT_CONTROL = 56 +PIXEL_PIPE_STAT_DUMP = 57 +PIXEL_PIPE_STAT_RESET = 58 +CONTEXT_SUSPEND = 59 +OFFCHIP_HS_DEALLOC = 60 +ENABLE_NGG_PIPELINE = 61 +ENABLE_LEGACY_PIPELINE = 62 +DRAW_DONE = 63 +VGT_EVENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_SWAP_MODE' +VGT_DMA_SWAP_MODE__enumvalues = { + 0: 'VGT_DMA_SWAP_NONE', + 1: 'VGT_DMA_SWAP_16_BIT', + 2: 'VGT_DMA_SWAP_32_BIT', + 3: 'VGT_DMA_SWAP_WORD', +} +VGT_DMA_SWAP_NONE = 0 +VGT_DMA_SWAP_16_BIT = 1 +VGT_DMA_SWAP_32_BIT = 2 +VGT_DMA_SWAP_WORD = 3 +VGT_DMA_SWAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_INDEX_TYPE_MODE' +VGT_INDEX_TYPE_MODE__enumvalues = { + 0: 'VGT_INDEX_16', + 1: 'VGT_INDEX_32', + 2: 'VGT_INDEX_8', +} +VGT_INDEX_16 = 0 +VGT_INDEX_32 = 1 +VGT_INDEX_8 = 2 +VGT_INDEX_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_BUF_TYPE' +VGT_DMA_BUF_TYPE__enumvalues = { + 0: 'VGT_DMA_BUF_MEM', + 1: 'VGT_DMA_BUF_RING', + 2: 'VGT_DMA_BUF_SETUP', + 3: 'VGT_DMA_PTR_UPDATE', +} +VGT_DMA_BUF_MEM = 0 +VGT_DMA_BUF_RING = 1 +VGT_DMA_BUF_SETUP = 2 +VGT_DMA_PTR_UPDATE = 3 +VGT_DMA_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUTPATH_SELECT' +VGT_OUTPATH_SELECT__enumvalues = { + 0: 'VGT_OUTPATH_VTX_REUSE', + 1: 'VGT_OUTPATH_GS_BLOCK', + 2: 'VGT_OUTPATH_HS_BLOCK', + 3: 'VGT_OUTPATH_PRIM_GEN', + 4: 'VGT_OUTPATH_TE_PRIM_GEN', + 5: 'VGT_OUTPATH_TE_GS_BLOCK', + 6: 'VGT_OUTPATH_TE_OUTPUT', +} +VGT_OUTPATH_VTX_REUSE = 0 +VGT_OUTPATH_GS_BLOCK = 1 +VGT_OUTPATH_HS_BLOCK = 2 +VGT_OUTPATH_PRIM_GEN = 3 +VGT_OUTPATH_TE_PRIM_GEN = 4 +VGT_OUTPATH_TE_GS_BLOCK = 5 +VGT_OUTPATH_TE_OUTPUT = 6 +VGT_OUTPATH_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GRP_PRIM_TYPE' +VGT_GRP_PRIM_TYPE__enumvalues = { + 0: 'VGT_GRP_3D_POINT', + 1: 'VGT_GRP_3D_LINE', + 2: 'VGT_GRP_3D_TRI', + 3: 'VGT_GRP_3D_RECT', + 4: 'VGT_GRP_3D_QUAD', + 5: 'VGT_GRP_2D_COPY_RECT_V0', + 6: 'VGT_GRP_2D_COPY_RECT_V1', + 7: 'VGT_GRP_2D_COPY_RECT_V2', + 8: 'VGT_GRP_2D_COPY_RECT_V3', + 9: 'VGT_GRP_2D_FILL_RECT', + 10: 'VGT_GRP_2D_LINE', + 11: 'VGT_GRP_2D_TRI', + 12: 'VGT_GRP_PRIM_INDEX_LINE', + 13: 'VGT_GRP_PRIM_INDEX_TRI', + 14: 'VGT_GRP_PRIM_INDEX_QUAD', + 15: 'VGT_GRP_3D_LINE_ADJ', + 16: 'VGT_GRP_3D_TRI_ADJ', + 17: 'VGT_GRP_3D_PATCH', + 18: 'VGT_GRP_2D_RECT', +} +VGT_GRP_3D_POINT = 0 +VGT_GRP_3D_LINE = 1 +VGT_GRP_3D_TRI = 2 +VGT_GRP_3D_RECT = 3 +VGT_GRP_3D_QUAD = 4 +VGT_GRP_2D_COPY_RECT_V0 = 5 +VGT_GRP_2D_COPY_RECT_V1 = 6 +VGT_GRP_2D_COPY_RECT_V2 = 7 +VGT_GRP_2D_COPY_RECT_V3 = 8 +VGT_GRP_2D_FILL_RECT = 9 +VGT_GRP_2D_LINE = 10 +VGT_GRP_2D_TRI = 11 +VGT_GRP_PRIM_INDEX_LINE = 12 +VGT_GRP_PRIM_INDEX_TRI = 13 +VGT_GRP_PRIM_INDEX_QUAD = 14 +VGT_GRP_3D_LINE_ADJ = 15 +VGT_GRP_3D_TRI_ADJ = 16 +VGT_GRP_3D_PATCH = 17 +VGT_GRP_2D_RECT = 18 +VGT_GRP_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GRP_PRIM_ORDER' +VGT_GRP_PRIM_ORDER__enumvalues = { + 0: 'VGT_GRP_LIST', + 1: 'VGT_GRP_STRIP', + 2: 'VGT_GRP_FAN', + 3: 'VGT_GRP_LOOP', + 4: 'VGT_GRP_POLYGON', +} +VGT_GRP_LIST = 0 +VGT_GRP_STRIP = 1 +VGT_GRP_FAN = 2 +VGT_GRP_LOOP = 3 +VGT_GRP_POLYGON = 4 +VGT_GRP_PRIM_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GROUP_CONV_SEL' +VGT_GROUP_CONV_SEL__enumvalues = { + 0: 'VGT_GRP_INDEX_16', + 1: 'VGT_GRP_INDEX_32', + 2: 'VGT_GRP_UINT_16', + 3: 'VGT_GRP_UINT_32', + 4: 'VGT_GRP_SINT_16', + 5: 'VGT_GRP_SINT_32', + 6: 'VGT_GRP_FLOAT_32', + 7: 'VGT_GRP_AUTO_PRIM', + 8: 'VGT_GRP_FIX_1_23_TO_FLOAT', +} +VGT_GRP_INDEX_16 = 0 +VGT_GRP_INDEX_32 = 1 +VGT_GRP_UINT_16 = 2 +VGT_GRP_UINT_32 = 3 +VGT_GRP_SINT_16 = 4 +VGT_GRP_SINT_32 = 5 +VGT_GRP_FLOAT_32 = 6 +VGT_GRP_AUTO_PRIM = 7 +VGT_GRP_FIX_1_23_TO_FLOAT = 8 +VGT_GROUP_CONV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_MODE_TYPE' +VGT_GS_MODE_TYPE__enumvalues = { + 0: 'GS_OFF', + 1: 'GS_SCENARIO_A', + 2: 'GS_SCENARIO_B', + 3: 'GS_SCENARIO_G', + 4: 'GS_SCENARIO_C', + 5: 'SPRITE_EN', +} +GS_OFF = 0 +GS_SCENARIO_A = 1 +GS_SCENARIO_B = 2 +GS_SCENARIO_G = 3 +GS_SCENARIO_C = 4 +SPRITE_EN = 5 +VGT_GS_MODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_CUT_MODE' +VGT_GS_CUT_MODE__enumvalues = { + 0: 'GS_CUT_1024', + 1: 'GS_CUT_512', + 2: 'GS_CUT_256', + 3: 'GS_CUT_128', +} +GS_CUT_1024 = 0 +GS_CUT_512 = 1 +GS_CUT_256 = 2 +GS_CUT_128 = 3 +VGT_GS_CUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_OUTPRIM_TYPE' +VGT_GS_OUTPRIM_TYPE__enumvalues = { + 0: 'POINTLIST', + 1: 'LINESTRIP', + 2: 'TRISTRIP', + 3: 'RECTLIST', +} +POINTLIST = 0 +LINESTRIP = 1 +TRISTRIP = 2 +RECTLIST = 3 +VGT_GS_OUTPRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_CACHE_INVALID_MODE' +VGT_CACHE_INVALID_MODE__enumvalues = { + 0: 'VC_ONLY', + 1: 'TC_ONLY', + 2: 'VC_AND_TC', +} +VC_ONLY = 0 +TC_ONLY = 1 +VC_AND_TC = 2 +VGT_CACHE_INVALID_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TYPE' +VGT_TESS_TYPE__enumvalues = { + 0: 'TESS_ISOLINE', + 1: 'TESS_TRIANGLE', + 2: 'TESS_QUAD', +} +TESS_ISOLINE = 0 +TESS_TRIANGLE = 1 +TESS_QUAD = 2 +VGT_TESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_PARTITION' +VGT_TESS_PARTITION__enumvalues = { + 0: 'PART_INTEGER', + 1: 'PART_POW2', + 2: 'PART_FRAC_ODD', + 3: 'PART_FRAC_EVEN', +} +PART_INTEGER = 0 +PART_POW2 = 1 +PART_FRAC_ODD = 2 +PART_FRAC_EVEN = 3 +VGT_TESS_PARTITION = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TOPOLOGY' +VGT_TESS_TOPOLOGY__enumvalues = { + 0: 'OUTPUT_POINT', + 1: 'OUTPUT_LINE', + 2: 'OUTPUT_TRIANGLE_CW', + 3: 'OUTPUT_TRIANGLE_CCW', +} +OUTPUT_POINT = 0 +OUTPUT_LINE = 1 +OUTPUT_TRIANGLE_CW = 2 +OUTPUT_TRIANGLE_CCW = 3 +VGT_TESS_TOPOLOGY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_RDREQ_POLICY' +VGT_RDREQ_POLICY__enumvalues = { + 0: 'VGT_POLICY_LRU', + 1: 'VGT_POLICY_STREAM', + 2: 'VGT_POLICY_BYPASS', +} +VGT_POLICY_LRU = 0 +VGT_POLICY_STREAM = 1 +VGT_POLICY_BYPASS = 2 +VGT_RDREQ_POLICY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DIST_MODE' +VGT_DIST_MODE__enumvalues = { + 0: 'NO_DIST', + 1: 'PATCHES', + 2: 'DONUTS', + 3: 'TRAPEZOIDS', +} +NO_DIST = 0 +PATCHES = 1 +DONUTS = 2 +TRAPEZOIDS = 3 +VGT_DIST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ONE' +VGT_DETECT_ONE__enumvalues = { + 0: 'PRE_CLAMP_TF1', + 1: 'POST_CLAMP_TF1', + 2: 'DISABLE_TF1', +} +PRE_CLAMP_TF1 = 0 +POST_CLAMP_TF1 = 1 +DISABLE_TF1 = 2 +VGT_DETECT_ONE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ZERO' +VGT_DETECT_ZERO__enumvalues = { + 0: 'PRE_CLAMP_TF0', + 1: 'POST_CLAMP_TF0', + 2: 'DISABLE_TF0', +} +PRE_CLAMP_TF0 = 0 +POST_CLAMP_TF0 = 1 +DISABLE_TF0 = 2 +VGT_DETECT_ZERO = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_LS_EN' +VGT_STAGES_LS_EN__enumvalues = { + 0: 'LS_STAGE_OFF', + 1: 'LS_STAGE_ON', + 2: 'CS_STAGE_ON', + 3: 'RESERVED_LS', +} +LS_STAGE_OFF = 0 +LS_STAGE_ON = 1 +CS_STAGE_ON = 2 +RESERVED_LS = 3 +VGT_STAGES_LS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_HS_EN' +VGT_STAGES_HS_EN__enumvalues = { + 0: 'HS_STAGE_OFF', + 1: 'HS_STAGE_ON', +} +HS_STAGE_OFF = 0 +HS_STAGE_ON = 1 +VGT_STAGES_HS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_ES_EN' +VGT_STAGES_ES_EN__enumvalues = { + 0: 'ES_STAGE_OFF', + 1: 'ES_STAGE_DS', + 2: 'ES_STAGE_REAL', + 3: 'RESERVED_ES', +} +ES_STAGE_OFF = 0 +ES_STAGE_DS = 1 +ES_STAGE_REAL = 2 +RESERVED_ES = 3 +VGT_STAGES_ES_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_GS_EN' +VGT_STAGES_GS_EN__enumvalues = { + 0: 'GS_STAGE_OFF', + 1: 'GS_STAGE_ON', +} +GS_STAGE_OFF = 0 +GS_STAGE_ON = 1 +VGT_STAGES_GS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_VS_EN' +VGT_STAGES_VS_EN__enumvalues = { + 0: 'VS_STAGE_REAL', + 1: 'VS_STAGE_DS', + 2: 'VS_STAGE_COPY_SHADER', + 3: 'RESERVED_VS', +} +VS_STAGE_REAL = 0 +VS_STAGE_DS = 1 +VS_STAGE_COPY_SHADER = 2 +RESERVED_VS = 3 +VGT_STAGES_VS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'GE_PERFCOUNT_SELECT' +GE_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge_assembler_busy', + 1: 'ge_assembler_stalled', + 2: 'ge_cm_reading_stalled', + 3: 'ge_cm_stalled_by_gog', + 4: 'ge_cm_stalled_by_gsfetch_done', + 5: 'ge_dma_busy', + 6: 'ge_dma_lat_bin_0', + 7: 'ge_dma_lat_bin_1', + 8: 'ge_dma_lat_bin_2', + 9: 'ge_dma_lat_bin_3', + 10: 'ge_dma_lat_bin_4', + 11: 'ge_dma_lat_bin_5', + 12: 'ge_dma_lat_bin_6', + 13: 'ge_dma_lat_bin_7', + 14: 'ge_dma_return', + 15: 'ge_dma_utcl1_consecutive_retry_event', + 16: 'ge_dma_utcl1_request_event', + 17: 'ge_dma_utcl1_retry_event', + 18: 'ge_dma_utcl1_stall_event', + 19: 'ge_dma_utcl1_stall_utcl2_event', + 20: 'ge_dma_utcl1_translation_hit_event', + 21: 'ge_dma_utcl1_translation_miss_event', + 22: 'ge_dma_utcl2_stall_on_trans', + 23: 'ge_dma_utcl2_trans_ack', + 24: 'ge_dma_utcl2_trans_xnack', + 25: 'ge_ds_cache_hits', + 26: 'ge_ds_prims', + 27: 'ge_es_done', + 28: 'ge_es_done_latency', + 29: 'ge_es_flush', + 30: 'ge_es_ring_high_water_mark', + 31: 'ge_es_thread_groups', + 32: 'ge_esthread_stalled_es_rb_full', + 33: 'ge_esthread_stalled_spi_bp', + 34: 'ge_esvert_stalled_es_tbl', + 35: 'ge_esvert_stalled_gs_event', + 36: 'ge_esvert_stalled_gs_tbl', + 37: 'ge_esvert_stalled_gsprim', + 38: 'ge_gea_dma_starved', + 39: 'ge_gog_busy', + 40: 'ge_gog_out_indx_stalled', + 41: 'ge_gog_out_prim_stalled', + 42: 'ge_gog_vs_tbl_stalled', + 43: 'ge_gs_cache_hits', + 44: 'ge_gs_counters_avail_stalled', + 45: 'ge_gs_done', + 46: 'ge_gs_done_latency', + 47: 'ge_gs_event_stall', + 48: 'ge_gs_issue_rtr_stalled', + 49: 'ge_gs_rb_space_avail_stalled', + 50: 'ge_gs_ring_high_water_mark', + 51: 'ge_gsprim_stalled_es_tbl', + 52: 'ge_gsprim_stalled_esvert', + 53: 'ge_gsprim_stalled_gs_event', + 54: 'ge_gsprim_stalled_gs_tbl', + 55: 'ge_gsthread_stalled', + 56: 'ge_hs_done', + 57: 'ge_hs_done_latency', + 58: 'ge_hs_done_se0', + 59: 'ge_hs_done_se1', + 60: 'ge_hs_done_se2_reserved', + 61: 'ge_hs_done_se3_reserved', + 62: 'ge_hs_tfm_stall', + 63: 'ge_hs_tgs_active_high_water_mark', + 64: 'ge_hs_thread_groups', + 65: 'ge_inside_tf_bin_0', + 66: 'ge_inside_tf_bin_1', + 67: 'ge_inside_tf_bin_2', + 68: 'ge_inside_tf_bin_3', + 69: 'ge_inside_tf_bin_4', + 70: 'ge_inside_tf_bin_5', + 71: 'ge_inside_tf_bin_6', + 72: 'ge_inside_tf_bin_7', + 73: 'ge_inside_tf_bin_8', + 74: 'ge_ls_done', + 75: 'ge_ls_done_latency', + 76: 'ge_null_patch', + 77: 'ge_pa_clipp_eop', + 78: 'ge_pa_clipp_is_event', + 79: 'ge_pa_clipp_new_vtx_vect', + 80: 'ge_pa_clipp_null_prim', + 81: 'ge_pa_clipp_send', + 82: 'ge_pa_clipp_send_not_event', + 83: 'ge_pa_clipp_stalled', + 84: 'ge_pa_clipp_starved_busy', + 85: 'ge_pa_clipp_starved_idle', + 86: 'ge_pa_clipp_valid_prim', + 87: 'ge_pa_clips_send', + 88: 'ge_pa_clips_stalled', + 89: 'ge_pa_clipv_send', + 90: 'ge_pa_clipv_stalled', + 91: 'ge_rbiu_di_fifo_stalled', + 92: 'ge_rbiu_di_fifo_starved', + 93: 'ge_rbiu_dr_fifo_stalled', + 94: 'ge_rbiu_dr_fifo_starved', + 95: 'ge_reused_es_indices', + 96: 'ge_reused_vs_indices', + 97: 'ge_sclk_core_vld', + 98: 'ge_sclk_gs_vld', + 99: 'ge_sclk_input_vld', + 100: 'ge_sclk_leg_gs_arb_vld', + 101: 'ge_sclk_ngg_vld', + 102: 'ge_sclk_reg_vld', + 103: 'ge_sclk_te11_vld', + 104: 'ge_sclk_vr_vld', + 105: 'ge_sclk_wd_te11_vld', + 106: 'ge_spi_esvert_eov', + 107: 'ge_spi_esvert_stalled', + 108: 'ge_spi_esvert_starved_busy', + 109: 'ge_spi_esvert_valid', + 110: 'ge_spi_eswave_is_event', + 111: 'ge_spi_eswave_send', + 112: 'ge_spi_gsprim_cont', + 113: 'ge_spi_gsprim_eov', + 114: 'ge_spi_gsprim_stalled', + 115: 'ge_spi_gsprim_starved_busy', + 116: 'ge_spi_gsprim_starved_idle', + 117: 'ge_spi_gsprim_valid', + 118: 'ge_spi_gssubgrp_is_event', + 119: 'ge_spi_gssubgrp_send', + 120: 'ge_spi_gswave_is_event', + 121: 'ge_spi_gswave_send', + 122: 'ge_spi_hsvert_eov', + 123: 'ge_spi_hsvert_stalled', + 124: 'ge_spi_hsvert_starved_busy', + 125: 'ge_spi_hsvert_valid', + 126: 'ge_spi_hswave_is_event', + 127: 'ge_spi_hswave_send', + 128: 'ge_spi_lsvert_eov', + 129: 'ge_spi_lsvert_stalled', + 130: 'ge_spi_lsvert_starved_busy', + 131: 'ge_spi_lsvert_starved_idle', + 132: 'ge_spi_lsvert_valid', + 133: 'ge_spi_lswave_is_event', + 134: 'ge_spi_lswave_send', + 135: 'ge_spi_vsvert_eov', + 136: 'ge_spi_vsvert_send', + 137: 'ge_spi_vsvert_stalled', + 138: 'ge_spi_vsvert_starved_busy', + 139: 'ge_spi_vsvert_starved_idle', + 140: 'ge_spi_vswave_is_event', + 141: 'ge_spi_vswave_send', + 142: 'ge_starved_on_hs_done', + 143: 'ge_stat_busy', + 144: 'ge_stat_combined_busy', + 145: 'ge_stat_no_dma_busy', + 146: 'ge_strmout_stalled', + 147: 'ge_te11_busy', + 148: 'ge_te11_starved', + 149: 'ge_tfreq_lat_bin_0', + 150: 'ge_tfreq_lat_bin_1', + 151: 'ge_tfreq_lat_bin_2', + 152: 'ge_tfreq_lat_bin_3', + 153: 'ge_tfreq_lat_bin_4', + 154: 'ge_tfreq_lat_bin_5', + 155: 'ge_tfreq_lat_bin_6', + 156: 'ge_tfreq_lat_bin_7', + 157: 'ge_tfreq_utcl1_consecutive_retry_event', + 158: 'ge_tfreq_utcl1_request_event', + 159: 'ge_tfreq_utcl1_retry_event', + 160: 'ge_tfreq_utcl1_stall_event', + 161: 'ge_tfreq_utcl1_stall_utcl2_event', + 162: 'ge_tfreq_utcl1_translation_hit_event', + 163: 'ge_tfreq_utcl1_translation_miss_event', + 164: 'ge_tfreq_utcl2_stall_on_trans', + 165: 'ge_tfreq_utcl2_trans_ack', + 166: 'ge_tfreq_utcl2_trans_xnack', + 167: 'ge_vs_cache_hits', + 168: 'ge_vs_done', + 169: 'ge_vs_pc_stall', + 170: 'ge_vs_table_high_water_mark', + 171: 'ge_vs_thread_groups', + 172: 'ge_vsvert_api_send', + 173: 'ge_vsvert_ds_send', + 174: 'ge_wait_for_es_done_stalled', + 175: 'ge_waveid_stalled', +} +ge_assembler_busy = 0 +ge_assembler_stalled = 1 +ge_cm_reading_stalled = 2 +ge_cm_stalled_by_gog = 3 +ge_cm_stalled_by_gsfetch_done = 4 +ge_dma_busy = 5 +ge_dma_lat_bin_0 = 6 +ge_dma_lat_bin_1 = 7 +ge_dma_lat_bin_2 = 8 +ge_dma_lat_bin_3 = 9 +ge_dma_lat_bin_4 = 10 +ge_dma_lat_bin_5 = 11 +ge_dma_lat_bin_6 = 12 +ge_dma_lat_bin_7 = 13 +ge_dma_return = 14 +ge_dma_utcl1_consecutive_retry_event = 15 +ge_dma_utcl1_request_event = 16 +ge_dma_utcl1_retry_event = 17 +ge_dma_utcl1_stall_event = 18 +ge_dma_utcl1_stall_utcl2_event = 19 +ge_dma_utcl1_translation_hit_event = 20 +ge_dma_utcl1_translation_miss_event = 21 +ge_dma_utcl2_stall_on_trans = 22 +ge_dma_utcl2_trans_ack = 23 +ge_dma_utcl2_trans_xnack = 24 +ge_ds_cache_hits = 25 +ge_ds_prims = 26 +ge_es_done = 27 +ge_es_done_latency = 28 +ge_es_flush = 29 +ge_es_ring_high_water_mark = 30 +ge_es_thread_groups = 31 +ge_esthread_stalled_es_rb_full = 32 +ge_esthread_stalled_spi_bp = 33 +ge_esvert_stalled_es_tbl = 34 +ge_esvert_stalled_gs_event = 35 +ge_esvert_stalled_gs_tbl = 36 +ge_esvert_stalled_gsprim = 37 +ge_gea_dma_starved = 38 +ge_gog_busy = 39 +ge_gog_out_indx_stalled = 40 +ge_gog_out_prim_stalled = 41 +ge_gog_vs_tbl_stalled = 42 +ge_gs_cache_hits = 43 +ge_gs_counters_avail_stalled = 44 +ge_gs_done = 45 +ge_gs_done_latency = 46 +ge_gs_event_stall = 47 +ge_gs_issue_rtr_stalled = 48 +ge_gs_rb_space_avail_stalled = 49 +ge_gs_ring_high_water_mark = 50 +ge_gsprim_stalled_es_tbl = 51 +ge_gsprim_stalled_esvert = 52 +ge_gsprim_stalled_gs_event = 53 +ge_gsprim_stalled_gs_tbl = 54 +ge_gsthread_stalled = 55 +ge_hs_done = 56 +ge_hs_done_latency = 57 +ge_hs_done_se0 = 58 +ge_hs_done_se1 = 59 +ge_hs_done_se2_reserved = 60 +ge_hs_done_se3_reserved = 61 +ge_hs_tfm_stall = 62 +ge_hs_tgs_active_high_water_mark = 63 +ge_hs_thread_groups = 64 +ge_inside_tf_bin_0 = 65 +ge_inside_tf_bin_1 = 66 +ge_inside_tf_bin_2 = 67 +ge_inside_tf_bin_3 = 68 +ge_inside_tf_bin_4 = 69 +ge_inside_tf_bin_5 = 70 +ge_inside_tf_bin_6 = 71 +ge_inside_tf_bin_7 = 72 +ge_inside_tf_bin_8 = 73 +ge_ls_done = 74 +ge_ls_done_latency = 75 +ge_null_patch = 76 +ge_pa_clipp_eop = 77 +ge_pa_clipp_is_event = 78 +ge_pa_clipp_new_vtx_vect = 79 +ge_pa_clipp_null_prim = 80 +ge_pa_clipp_send = 81 +ge_pa_clipp_send_not_event = 82 +ge_pa_clipp_stalled = 83 +ge_pa_clipp_starved_busy = 84 +ge_pa_clipp_starved_idle = 85 +ge_pa_clipp_valid_prim = 86 +ge_pa_clips_send = 87 +ge_pa_clips_stalled = 88 +ge_pa_clipv_send = 89 +ge_pa_clipv_stalled = 90 +ge_rbiu_di_fifo_stalled = 91 +ge_rbiu_di_fifo_starved = 92 +ge_rbiu_dr_fifo_stalled = 93 +ge_rbiu_dr_fifo_starved = 94 +ge_reused_es_indices = 95 +ge_reused_vs_indices = 96 +ge_sclk_core_vld = 97 +ge_sclk_gs_vld = 98 +ge_sclk_input_vld = 99 +ge_sclk_leg_gs_arb_vld = 100 +ge_sclk_ngg_vld = 101 +ge_sclk_reg_vld = 102 +ge_sclk_te11_vld = 103 +ge_sclk_vr_vld = 104 +ge_sclk_wd_te11_vld = 105 +ge_spi_esvert_eov = 106 +ge_spi_esvert_stalled = 107 +ge_spi_esvert_starved_busy = 108 +ge_spi_esvert_valid = 109 +ge_spi_eswave_is_event = 110 +ge_spi_eswave_send = 111 +ge_spi_gsprim_cont = 112 +ge_spi_gsprim_eov = 113 +ge_spi_gsprim_stalled = 114 +ge_spi_gsprim_starved_busy = 115 +ge_spi_gsprim_starved_idle = 116 +ge_spi_gsprim_valid = 117 +ge_spi_gssubgrp_is_event = 118 +ge_spi_gssubgrp_send = 119 +ge_spi_gswave_is_event = 120 +ge_spi_gswave_send = 121 +ge_spi_hsvert_eov = 122 +ge_spi_hsvert_stalled = 123 +ge_spi_hsvert_starved_busy = 124 +ge_spi_hsvert_valid = 125 +ge_spi_hswave_is_event = 126 +ge_spi_hswave_send = 127 +ge_spi_lsvert_eov = 128 +ge_spi_lsvert_stalled = 129 +ge_spi_lsvert_starved_busy = 130 +ge_spi_lsvert_starved_idle = 131 +ge_spi_lsvert_valid = 132 +ge_spi_lswave_is_event = 133 +ge_spi_lswave_send = 134 +ge_spi_vsvert_eov = 135 +ge_spi_vsvert_send = 136 +ge_spi_vsvert_stalled = 137 +ge_spi_vsvert_starved_busy = 138 +ge_spi_vsvert_starved_idle = 139 +ge_spi_vswave_is_event = 140 +ge_spi_vswave_send = 141 +ge_starved_on_hs_done = 142 +ge_stat_busy = 143 +ge_stat_combined_busy = 144 +ge_stat_no_dma_busy = 145 +ge_strmout_stalled = 146 +ge_te11_busy = 147 +ge_te11_starved = 148 +ge_tfreq_lat_bin_0 = 149 +ge_tfreq_lat_bin_1 = 150 +ge_tfreq_lat_bin_2 = 151 +ge_tfreq_lat_bin_3 = 152 +ge_tfreq_lat_bin_4 = 153 +ge_tfreq_lat_bin_5 = 154 +ge_tfreq_lat_bin_6 = 155 +ge_tfreq_lat_bin_7 = 156 +ge_tfreq_utcl1_consecutive_retry_event = 157 +ge_tfreq_utcl1_request_event = 158 +ge_tfreq_utcl1_retry_event = 159 +ge_tfreq_utcl1_stall_event = 160 +ge_tfreq_utcl1_stall_utcl2_event = 161 +ge_tfreq_utcl1_translation_hit_event = 162 +ge_tfreq_utcl1_translation_miss_event = 163 +ge_tfreq_utcl2_stall_on_trans = 164 +ge_tfreq_utcl2_trans_ack = 165 +ge_tfreq_utcl2_trans_xnack = 166 +ge_vs_cache_hits = 167 +ge_vs_done = 168 +ge_vs_pc_stall = 169 +ge_vs_table_high_water_mark = 170 +ge_vs_thread_groups = 171 +ge_vsvert_api_send = 172 +ge_vsvert_ds_send = 173 +ge_wait_for_es_done_stalled = 174 +ge_waveid_stalled = 175 +GE_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_TYPE' +WD_IA_DRAW_TYPE__enumvalues = { + 0: 'WD_IA_DRAW_TYPE_DI_MM0', + 1: 'WD_IA_DRAW_TYPE_REG_XFER', + 2: 'WD_IA_DRAW_TYPE_EVENT_INIT', + 3: 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 4: 'WD_IA_DRAW_TYPE_MIN_INDX', + 5: 'WD_IA_DRAW_TYPE_MAX_INDX', + 6: 'WD_IA_DRAW_TYPE_INDX_OFF', + 7: 'WD_IA_DRAW_TYPE_IMM_DATA', +} +WD_IA_DRAW_TYPE_DI_MM0 = 0 +WD_IA_DRAW_TYPE_REG_XFER = 1 +WD_IA_DRAW_TYPE_EVENT_INIT = 2 +WD_IA_DRAW_TYPE_EVENT_ADDR = 3 +WD_IA_DRAW_TYPE_MIN_INDX = 4 +WD_IA_DRAW_TYPE_MAX_INDX = 5 +WD_IA_DRAW_TYPE_INDX_OFF = 6 +WD_IA_DRAW_TYPE_IMM_DATA = 7 +WD_IA_DRAW_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_REG_XFER' +WD_IA_DRAW_REG_XFER__enumvalues = { + 0: 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 1: 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 2: 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 3: 'WD_IA_DRAW_REG_XFER_GE_CNTL', +} +WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM = 0 +WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN = 1 +WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID = 2 +WD_IA_DRAW_REG_XFER_GE_CNTL = 3 +WD_IA_DRAW_REG_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_SOURCE' +WD_IA_DRAW_SOURCE__enumvalues = { + 0: 'WD_IA_DRAW_SOURCE_DMA', + 1: 'WD_IA_DRAW_SOURCE_IMMD', + 2: 'WD_IA_DRAW_SOURCE_AUTO', + 3: 'WD_IA_DRAW_SOURCE_OPAQ', +} +WD_IA_DRAW_SOURCE_DMA = 0 +WD_IA_DRAW_SOURCE_IMMD = 1 +WD_IA_DRAW_SOURCE_AUTO = 2 +WD_IA_DRAW_SOURCE_OPAQ = 3 +WD_IA_DRAW_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'GB_EDC_DED_MODE' +GB_EDC_DED_MODE__enumvalues = { + 0: 'GB_EDC_DED_MODE_LOG', + 1: 'GB_EDC_DED_MODE_HALT', + 2: 'GB_EDC_DED_MODE_INT_HALT', +} +GB_EDC_DED_MODE_LOG = 0 +GB_EDC_DED_MODE_HALT = 1 +GB_EDC_DED_MODE_INT_HALT = 2 +GB_EDC_DED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CHA_PERF_SEL' +CHA_PERF_SEL__enumvalues = { + 0: 'CHA_PERF_SEL_BUSY', + 1: 'CHA_PERF_SEL_STALL_CHC0', + 2: 'CHA_PERF_SEL_STALL_CHC1', + 3: 'CHA_PERF_SEL_STALL_CHC2', + 4: 'CHA_PERF_SEL_STALL_CHC3', + 5: 'CHA_PERF_SEL_STALL_CHC4', + 6: 'CHA_PERF_SEL_REQUEST_CHC0', + 7: 'CHA_PERF_SEL_REQUEST_CHC1', + 8: 'CHA_PERF_SEL_REQUEST_CHC2', + 9: 'CHA_PERF_SEL_REQUEST_CHC3', + 10: 'CHA_PERF_SEL_REQUEST_CHC4', + 11: 'CHA_PERF_SEL_REQUEST_CHC5', + 12: 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', + 13: 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 14: 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', + 15: 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 16: 'CHA_PERF_SEL_MEM_32B_WDS_CHC4', + 17: 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 18: 'CHA_PERF_SEL_IO_32B_WDS_CHC1', + 19: 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 20: 'CHA_PERF_SEL_IO_32B_WDS_CHC3', + 21: 'CHA_PERF_SEL_IO_32B_WDS_CHC4', + 22: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 23: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 24: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 25: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', + 26: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC4', + 27: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 28: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 29: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 30: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 31: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC4', + 32: 'CHA_PERF_SEL_ARB_REQUESTS', + 33: 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 34: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 35: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 36: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 37: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', + 38: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4', + 39: 'CHA_PERF_SEL_CYCLE', +} +CHA_PERF_SEL_BUSY = 0 +CHA_PERF_SEL_STALL_CHC0 = 1 +CHA_PERF_SEL_STALL_CHC1 = 2 +CHA_PERF_SEL_STALL_CHC2 = 3 +CHA_PERF_SEL_STALL_CHC3 = 4 +CHA_PERF_SEL_STALL_CHC4 = 5 +CHA_PERF_SEL_REQUEST_CHC0 = 6 +CHA_PERF_SEL_REQUEST_CHC1 = 7 +CHA_PERF_SEL_REQUEST_CHC2 = 8 +CHA_PERF_SEL_REQUEST_CHC3 = 9 +CHA_PERF_SEL_REQUEST_CHC4 = 10 +CHA_PERF_SEL_REQUEST_CHC5 = 11 +CHA_PERF_SEL_MEM_32B_WDS_CHC0 = 12 +CHA_PERF_SEL_MEM_32B_WDS_CHC1 = 13 +CHA_PERF_SEL_MEM_32B_WDS_CHC2 = 14 +CHA_PERF_SEL_MEM_32B_WDS_CHC3 = 15 +CHA_PERF_SEL_MEM_32B_WDS_CHC4 = 16 +CHA_PERF_SEL_IO_32B_WDS_CHC0 = 17 +CHA_PERF_SEL_IO_32B_WDS_CHC1 = 18 +CHA_PERF_SEL_IO_32B_WDS_CHC2 = 19 +CHA_PERF_SEL_IO_32B_WDS_CHC3 = 20 +CHA_PERF_SEL_IO_32B_WDS_CHC4 = 21 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC0 = 22 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC1 = 23 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC2 = 24 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC3 = 25 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC4 = 26 +CHA_PERF_SEL_IO_BURST_COUNT_CHC0 = 27 +CHA_PERF_SEL_IO_BURST_COUNT_CHC1 = 28 +CHA_PERF_SEL_IO_BURST_COUNT_CHC2 = 29 +CHA_PERF_SEL_IO_BURST_COUNT_CHC3 = 30 +CHA_PERF_SEL_IO_BURST_COUNT_CHC4 = 31 +CHA_PERF_SEL_ARB_REQUESTS = 32 +CHA_PERF_SEL_REQ_INFLIGHT_LEVEL = 33 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0 = 34 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1 = 35 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2 = 36 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3 = 37 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4 = 38 +CHA_PERF_SEL_CYCLE = 39 +CHA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CHC_PERF_SEL' +CHC_PERF_SEL__enumvalues = { + 0: 'CHC_PERF_SEL_GATE_EN1', + 1: 'CHC_PERF_SEL_GATE_EN2', + 2: 'CHC_PERF_SEL_CORE_REG_SCLK_VLD', + 3: 'CHC_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES', + 4: 'CHC_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES', + 5: 'CHC_PERF_SEL_CYCLE', + 6: 'CHC_PERF_SEL_REQ', +} +CHC_PERF_SEL_GATE_EN1 = 0 +CHC_PERF_SEL_GATE_EN2 = 1 +CHC_PERF_SEL_CORE_REG_SCLK_VLD = 2 +CHC_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES = 3 +CHC_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES = 4 +CHC_PERF_SEL_CYCLE = 5 +CHC_PERF_SEL_REQ = 6 +CHC_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CHCG_PERF_SEL' +CHCG_PERF_SEL__enumvalues = { + 0: 'CHCG_PERF_SEL_GATE_EN1', + 1: 'CHCG_PERF_SEL_GATE_EN2', + 2: 'CHCG_PERF_SEL_CORE_REG_SCLK_VLD', + 3: 'CHCG_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES', + 4: 'CHCG_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES', + 5: 'CHCG_PERF_SEL_CYCLE', + 6: 'CHCG_PERF_SEL_REQ', +} +CHCG_PERF_SEL_GATE_EN1 = 0 +CHCG_PERF_SEL_GATE_EN2 = 1 +CHCG_PERF_SEL_CORE_REG_SCLK_VLD = 2 +CHCG_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES = 3 +CHCG_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES = 4 +CHCG_PERF_SEL_CYCLE = 5 +CHCG_PERF_SEL_REQ = 6 +CHCG_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1A_PERF_SEL' +GL1A_PERF_SEL__enumvalues = { + 0: 'GL1A_PERF_SEL_BUSY', + 1: 'GL1A_PERF_SEL_STALL_GL1C0', + 2: 'GL1A_PERF_SEL_STALL_GL1C1', + 3: 'GL1A_PERF_SEL_STALL_GL1C2', + 4: 'GL1A_PERF_SEL_STALL_GL1C3', + 5: 'GL1A_PERF_SEL_STALL_GL1C4', + 6: 'GL1A_PERF_SEL_REQUEST_GL1C0', + 7: 'GL1A_PERF_SEL_REQUEST_GL1C1', + 8: 'GL1A_PERF_SEL_REQUEST_GL1C2', + 9: 'GL1A_PERF_SEL_REQUEST_GL1C3', + 10: 'GL1A_PERF_SEL_REQUEST_GL1C4', + 11: 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C0', + 12: 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C1', + 13: 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C2', + 14: 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C3', + 15: 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C4', + 16: 'GL1A_PERF_SEL_IO_32B_WDS_GL1C0', + 17: 'GL1A_PERF_SEL_IO_32B_WDS_GL1C1', + 18: 'GL1A_PERF_SEL_IO_32B_WDS_GL1C2', + 19: 'GL1A_PERF_SEL_IO_32B_WDS_GL1C3', + 20: 'GL1A_PERF_SEL_IO_32B_WDS_GL1C4', + 21: 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C0', + 22: 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C1', + 23: 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C2', + 24: 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C3', + 25: 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C4', + 26: 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C0', + 27: 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C1', + 28: 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C2', + 29: 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C3', + 30: 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C4', + 31: 'GL1A_PERF_SEL_ARB_REQUESTS', + 32: 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 33: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 34: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 35: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 36: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 37: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C4', + 38: 'GL1A_PERF_SEL_CYCLE', +} +GL1A_PERF_SEL_BUSY = 0 +GL1A_PERF_SEL_STALL_GL1C0 = 1 +GL1A_PERF_SEL_STALL_GL1C1 = 2 +GL1A_PERF_SEL_STALL_GL1C2 = 3 +GL1A_PERF_SEL_STALL_GL1C3 = 4 +GL1A_PERF_SEL_STALL_GL1C4 = 5 +GL1A_PERF_SEL_REQUEST_GL1C0 = 6 +GL1A_PERF_SEL_REQUEST_GL1C1 = 7 +GL1A_PERF_SEL_REQUEST_GL1C2 = 8 +GL1A_PERF_SEL_REQUEST_GL1C3 = 9 +GL1A_PERF_SEL_REQUEST_GL1C4 = 10 +GL1A_PERF_SEL_MEM_32B_WDS_GL1C0 = 11 +GL1A_PERF_SEL_MEM_32B_WDS_GL1C1 = 12 +GL1A_PERF_SEL_MEM_32B_WDS_GL1C2 = 13 +GL1A_PERF_SEL_MEM_32B_WDS_GL1C3 = 14 +GL1A_PERF_SEL_MEM_32B_WDS_GL1C4 = 15 +GL1A_PERF_SEL_IO_32B_WDS_GL1C0 = 16 +GL1A_PERF_SEL_IO_32B_WDS_GL1C1 = 17 +GL1A_PERF_SEL_IO_32B_WDS_GL1C2 = 18 +GL1A_PERF_SEL_IO_32B_WDS_GL1C3 = 19 +GL1A_PERF_SEL_IO_32B_WDS_GL1C4 = 20 +GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C0 = 21 +GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C1 = 22 +GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C2 = 23 +GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C3 = 24 +GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C4 = 25 +GL1A_PERF_SEL_IO_BURST_COUNT_GL1C0 = 26 +GL1A_PERF_SEL_IO_BURST_COUNT_GL1C1 = 27 +GL1A_PERF_SEL_IO_BURST_COUNT_GL1C2 = 28 +GL1A_PERF_SEL_IO_BURST_COUNT_GL1C3 = 29 +GL1A_PERF_SEL_IO_BURST_COUNT_GL1C4 = 30 +GL1A_PERF_SEL_ARB_REQUESTS = 31 +GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL = 32 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0 = 33 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1 = 34 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2 = 35 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3 = 36 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C4 = 37 +GL1A_PERF_SEL_CYCLE = 38 +GL1A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1C_PERF_SEL' +GL1C_PERF_SEL__enumvalues = { + 0: 'GL1C_PERF_SEL_GATE_EN1', + 1: 'GL1C_PERF_SEL_GATE_EN2', + 2: 'GL1C_PERF_SEL_CORE_REG_SCLK_VLD', + 3: 'GL1C_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES', + 4: 'GL1C_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES', + 5: 'GL1C_PERF_SEL_CYCLE', + 6: 'GL1C_PERF_SEL_REQ', +} +GL1C_PERF_SEL_GATE_EN1 = 0 +GL1C_PERF_SEL_GATE_EN2 = 1 +GL1C_PERF_SEL_CORE_REG_SCLK_VLD = 2 +GL1C_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES = 3 +GL1C_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES = 4 +GL1C_PERF_SEL_CYCLE = 5 +GL1C_PERF_SEL_REQ = 6 +GL1C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1CG_PERF_SEL' +GL1CG_PERF_SEL__enumvalues = { + 0: 'GL1CG_PERF_SEL_GATE_EN1', + 1: 'GL1CG_PERF_SEL_GATE_EN2', + 2: 'GL1CG_PERF_SEL_CORE_REG_SCLK_VLD', + 3: 'GL1CG_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES', + 4: 'GL1CG_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES', + 5: 'GL1CG_PERF_SEL_CYCLE', + 6: 'GL1CG_PERF_SEL_REQ', +} +GL1CG_PERF_SEL_GATE_EN1 = 0 +GL1CG_PERF_SEL_GATE_EN2 = 1 +GL1CG_PERF_SEL_CORE_REG_SCLK_VLD = 2 +GL1CG_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES = 3 +GL1CG_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES = 4 +GL1CG_PERF_SEL_CYCLE = 5 +GL1CG_PERF_SEL_REQ = 6 +GL1CG_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_REQ_MODES' +TA_TC_REQ_MODES__enumvalues = { + 0: 'TA_TC_REQ_MODE_BORDER', + 1: 'TA_TC_REQ_MODE_TEX2', + 2: 'TA_TC_REQ_MODE_TEX1', + 3: 'TA_TC_REQ_MODE_TEX0', + 4: 'TA_TC_REQ_MODE_NORMAL', + 5: 'TA_TC_REQ_MODE_DWORD', + 6: 'TA_TC_REQ_MODE_BYTE', + 7: 'TA_TC_REQ_MODE_BYTE_NV', +} +TA_TC_REQ_MODE_BORDER = 0 +TA_TC_REQ_MODE_TEX2 = 1 +TA_TC_REQ_MODE_TEX1 = 2 +TA_TC_REQ_MODE_TEX0 = 3 +TA_TC_REQ_MODE_NORMAL = 4 +TA_TC_REQ_MODE_DWORD = 5 +TA_TC_REQ_MODE_BYTE = 6 +TA_TC_REQ_MODE_BYTE_NV = 7 +TA_TC_REQ_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_ADDR_MODES' +TA_TC_ADDR_MODES__enumvalues = { + 0: 'TA_TC_ADDR_MODE_DEFAULT', + 1: 'TA_TC_ADDR_MODE_COMP0', + 2: 'TA_TC_ADDR_MODE_COMP1', + 3: 'TA_TC_ADDR_MODE_COMP2', + 4: 'TA_TC_ADDR_MODE_COMP3', + 5: 'TA_TC_ADDR_MODE_UNALIGNED', + 6: 'TA_TC_ADDR_MODE_BORDER_COLOR', +} +TA_TC_ADDR_MODE_DEFAULT = 0 +TA_TC_ADDR_MODE_COMP0 = 1 +TA_TC_ADDR_MODE_COMP1 = 2 +TA_TC_ADDR_MODE_COMP2 = 3 +TA_TC_ADDR_MODE_COMP3 = 4 +TA_TC_ADDR_MODE_UNALIGNED = 5 +TA_TC_ADDR_MODE_BORDER_COLOR = 6 +TA_TC_ADDR_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TA_PERFCOUNT_SEL' +TA_PERFCOUNT_SEL__enumvalues = { + 0: 'TA_PERF_SEL_NULL', + 1: 'TA_PERF_SEL_sh_fifo_busy', + 2: 'TA_PERF_SEL_sh_fifo_cmd_busy', + 3: 'TA_PERF_SEL_sh_fifo_addr_busy', + 4: 'TA_PERF_SEL_sh_fifo_data_busy', + 5: 'TA_PERF_SEL_sh_fifo_data_sfifo_busy', + 6: 'TA_PERF_SEL_sh_fifo_data_tfifo_busy', + 7: 'TA_PERF_SEL_gradient_busy', + 8: 'TA_PERF_SEL_gradient_fifo_busy', + 9: 'TA_PERF_SEL_lod_busy', + 10: 'TA_PERF_SEL_lod_fifo_busy', + 11: 'TA_PERF_SEL_addresser_busy', + 12: 'TA_PERF_SEL_addresser_fifo_busy', + 13: 'TA_PERF_SEL_aligner_busy', + 14: 'TA_PERF_SEL_write_path_busy', + 15: 'TA_PERF_SEL_ta_busy', + 16: 'TA_PERF_SEL_sq_ta_cmd_cycles', + 17: 'TA_PERF_SEL_sp_ta_addr_cycles', + 18: 'TA_PERF_SEL_sp_ta_data_cycles', + 19: 'TA_PERF_SEL_ta_fa_data_state_cycles', + 20: 'TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles', + 21: 'TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles', + 22: 'TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles', + 23: 'TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles', + 24: 'TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles', + 25: 'TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles', + 26: 'TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles', + 27: 'TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles', + 28: 'TA_PERF_SEL_ta_sh_fifo_starved', + 29: 'TA_PERF_SEL_RESERVED_29', + 30: 'TA_PERF_SEL_sh_fifo_addr_cycles', + 31: 'TA_PERF_SEL_sh_fifo_data_cycles', + 32: 'TA_PERF_SEL_total_wavefronts', + 33: 'TA_PERF_SEL_gradient_cycles', + 34: 'TA_PERF_SEL_walker_cycles', + 35: 'TA_PERF_SEL_aligner_cycles', + 36: 'TA_PERF_SEL_image_wavefronts', + 37: 'TA_PERF_SEL_image_read_wavefronts', + 38: 'TA_PERF_SEL_image_write_wavefronts', + 39: 'TA_PERF_SEL_image_atomic_wavefronts', + 40: 'TA_PERF_SEL_image_total_cycles', + 41: 'TA_PERF_SEL_RESERVED_41', + 42: 'TA_PERF_SEL_RESERVED_42', + 43: 'TA_PERF_SEL_RESERVED_43', + 44: 'TA_PERF_SEL_buffer_wavefronts', + 45: 'TA_PERF_SEL_buffer_read_wavefronts', + 46: 'TA_PERF_SEL_buffer_write_wavefronts', + 47: 'TA_PERF_SEL_buffer_atomic_wavefronts', + 48: 'TA_PERF_SEL_buffer_coalescable_wavefronts', + 49: 'TA_PERF_SEL_buffer_total_cycles', + 50: 'TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles', + 51: 'TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles', + 52: 'TA_PERF_SEL_buffer_coalesced_read_cycles', + 53: 'TA_PERF_SEL_buffer_coalesced_write_cycles', + 54: 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 55: 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 56: 'TA_PERF_SEL_data_stalled_by_tc_cycles', + 57: 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 58: 'TA_PERF_SEL_addresser_stalled_cycles', + 59: 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 60: 'TA_PERF_SEL_aniso_stalled_cycles', + 61: 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 62: 'TA_PERF_SEL_deriv_stalled_cycles', + 63: 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 64: 'TA_PERF_SEL_color_1_cycle_pixels', + 65: 'TA_PERF_SEL_color_2_cycle_pixels', + 66: 'TA_PERF_SEL_color_3_cycle_pixels', + 67: 'TA_PERF_SEL_color_4_cycle_pixels', + 68: 'TA_PERF_SEL_mip_1_cycle_pixels', + 69: 'TA_PERF_SEL_mip_2_cycle_pixels', + 70: 'TA_PERF_SEL_vol_1_cycle_pixels', + 71: 'TA_PERF_SEL_vol_2_cycle_pixels', + 72: 'TA_PERF_SEL_bilin_point_1_cycle_pixels', + 73: 'TA_PERF_SEL_mipmap_lod_0_samples', + 74: 'TA_PERF_SEL_mipmap_lod_1_samples', + 75: 'TA_PERF_SEL_mipmap_lod_2_samples', + 76: 'TA_PERF_SEL_mipmap_lod_3_samples', + 77: 'TA_PERF_SEL_mipmap_lod_4_samples', + 78: 'TA_PERF_SEL_mipmap_lod_5_samples', + 79: 'TA_PERF_SEL_mipmap_lod_6_samples', + 80: 'TA_PERF_SEL_mipmap_lod_7_samples', + 81: 'TA_PERF_SEL_mipmap_lod_8_samples', + 82: 'TA_PERF_SEL_mipmap_lod_9_samples', + 83: 'TA_PERF_SEL_mipmap_lod_10_samples', + 84: 'TA_PERF_SEL_mipmap_lod_11_samples', + 85: 'TA_PERF_SEL_mipmap_lod_12_samples', + 86: 'TA_PERF_SEL_mipmap_lod_13_samples', + 87: 'TA_PERF_SEL_mipmap_lod_14_samples', + 88: 'TA_PERF_SEL_mipmap_invalid_samples', + 89: 'TA_PERF_SEL_aniso_1_cycle_quads', + 90: 'TA_PERF_SEL_aniso_2_cycle_quads', + 91: 'TA_PERF_SEL_aniso_4_cycle_quads', + 92: 'TA_PERF_SEL_aniso_6_cycle_quads', + 93: 'TA_PERF_SEL_aniso_8_cycle_quads', + 94: 'TA_PERF_SEL_aniso_10_cycle_quads', + 95: 'TA_PERF_SEL_aniso_12_cycle_quads', + 96: 'TA_PERF_SEL_aniso_14_cycle_quads', + 97: 'TA_PERF_SEL_aniso_16_cycle_quads', + 98: 'TA_PERF_SEL_write_path_input_cycles', + 99: 'TA_PERF_SEL_write_path_output_cycles', + 100: 'TA_PERF_SEL_flat_wavefronts', + 101: 'TA_PERF_SEL_flat_read_wavefronts', + 102: 'TA_PERF_SEL_flat_write_wavefronts', + 103: 'TA_PERF_SEL_flat_atomic_wavefronts', + 104: 'TA_PERF_SEL_flat_coalesceable_wavefronts', + 105: 'TA_PERF_SEL_reg_sclk_vld', + 106: 'TA_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 107: 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 108: 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en', + 109: 'TA_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 110: 'TA_PERF_SEL_local_cg_dyn_sclk_grp5_en', + 111: 'TA_PERF_SEL_xnack_on_phase0', + 112: 'TA_PERF_SEL_xnack_on_phase1', + 113: 'TA_PERF_SEL_xnack_on_phase2', + 114: 'TA_PERF_SEL_xnack_on_phase3', + 115: 'TA_PERF_SEL_first_xnack_on_phase0', + 116: 'TA_PERF_SEL_first_xnack_on_phase1', + 117: 'TA_PERF_SEL_first_xnack_on_phase2', + 118: 'TA_PERF_SEL_first_xnack_on_phase3', +} +TA_PERF_SEL_NULL = 0 +TA_PERF_SEL_sh_fifo_busy = 1 +TA_PERF_SEL_sh_fifo_cmd_busy = 2 +TA_PERF_SEL_sh_fifo_addr_busy = 3 +TA_PERF_SEL_sh_fifo_data_busy = 4 +TA_PERF_SEL_sh_fifo_data_sfifo_busy = 5 +TA_PERF_SEL_sh_fifo_data_tfifo_busy = 6 +TA_PERF_SEL_gradient_busy = 7 +TA_PERF_SEL_gradient_fifo_busy = 8 +TA_PERF_SEL_lod_busy = 9 +TA_PERF_SEL_lod_fifo_busy = 10 +TA_PERF_SEL_addresser_busy = 11 +TA_PERF_SEL_addresser_fifo_busy = 12 +TA_PERF_SEL_aligner_busy = 13 +TA_PERF_SEL_write_path_busy = 14 +TA_PERF_SEL_ta_busy = 15 +TA_PERF_SEL_sq_ta_cmd_cycles = 16 +TA_PERF_SEL_sp_ta_addr_cycles = 17 +TA_PERF_SEL_sp_ta_data_cycles = 18 +TA_PERF_SEL_ta_fa_data_state_cycles = 19 +TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles = 20 +TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles = 21 +TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles = 22 +TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles = 23 +TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles = 24 +TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles = 25 +TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles = 26 +TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles = 27 +TA_PERF_SEL_ta_sh_fifo_starved = 28 +TA_PERF_SEL_RESERVED_29 = 29 +TA_PERF_SEL_sh_fifo_addr_cycles = 30 +TA_PERF_SEL_sh_fifo_data_cycles = 31 +TA_PERF_SEL_total_wavefronts = 32 +TA_PERF_SEL_gradient_cycles = 33 +TA_PERF_SEL_walker_cycles = 34 +TA_PERF_SEL_aligner_cycles = 35 +TA_PERF_SEL_image_wavefronts = 36 +TA_PERF_SEL_image_read_wavefronts = 37 +TA_PERF_SEL_image_write_wavefronts = 38 +TA_PERF_SEL_image_atomic_wavefronts = 39 +TA_PERF_SEL_image_total_cycles = 40 +TA_PERF_SEL_RESERVED_41 = 41 +TA_PERF_SEL_RESERVED_42 = 42 +TA_PERF_SEL_RESERVED_43 = 43 +TA_PERF_SEL_buffer_wavefronts = 44 +TA_PERF_SEL_buffer_read_wavefronts = 45 +TA_PERF_SEL_buffer_write_wavefronts = 46 +TA_PERF_SEL_buffer_atomic_wavefronts = 47 +TA_PERF_SEL_buffer_coalescable_wavefronts = 48 +TA_PERF_SEL_buffer_total_cycles = 49 +TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles = 50 +TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles = 51 +TA_PERF_SEL_buffer_coalesced_read_cycles = 52 +TA_PERF_SEL_buffer_coalesced_write_cycles = 53 +TA_PERF_SEL_addr_stalled_by_tc_cycles = 54 +TA_PERF_SEL_addr_stalled_by_td_cycles = 55 +TA_PERF_SEL_data_stalled_by_tc_cycles = 56 +TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles = 57 +TA_PERF_SEL_addresser_stalled_cycles = 58 +TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles = 59 +TA_PERF_SEL_aniso_stalled_cycles = 60 +TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles = 61 +TA_PERF_SEL_deriv_stalled_cycles = 62 +TA_PERF_SEL_aniso_gt1_cycle_quads = 63 +TA_PERF_SEL_color_1_cycle_pixels = 64 +TA_PERF_SEL_color_2_cycle_pixels = 65 +TA_PERF_SEL_color_3_cycle_pixels = 66 +TA_PERF_SEL_color_4_cycle_pixels = 67 +TA_PERF_SEL_mip_1_cycle_pixels = 68 +TA_PERF_SEL_mip_2_cycle_pixels = 69 +TA_PERF_SEL_vol_1_cycle_pixels = 70 +TA_PERF_SEL_vol_2_cycle_pixels = 71 +TA_PERF_SEL_bilin_point_1_cycle_pixels = 72 +TA_PERF_SEL_mipmap_lod_0_samples = 73 +TA_PERF_SEL_mipmap_lod_1_samples = 74 +TA_PERF_SEL_mipmap_lod_2_samples = 75 +TA_PERF_SEL_mipmap_lod_3_samples = 76 +TA_PERF_SEL_mipmap_lod_4_samples = 77 +TA_PERF_SEL_mipmap_lod_5_samples = 78 +TA_PERF_SEL_mipmap_lod_6_samples = 79 +TA_PERF_SEL_mipmap_lod_7_samples = 80 +TA_PERF_SEL_mipmap_lod_8_samples = 81 +TA_PERF_SEL_mipmap_lod_9_samples = 82 +TA_PERF_SEL_mipmap_lod_10_samples = 83 +TA_PERF_SEL_mipmap_lod_11_samples = 84 +TA_PERF_SEL_mipmap_lod_12_samples = 85 +TA_PERF_SEL_mipmap_lod_13_samples = 86 +TA_PERF_SEL_mipmap_lod_14_samples = 87 +TA_PERF_SEL_mipmap_invalid_samples = 88 +TA_PERF_SEL_aniso_1_cycle_quads = 89 +TA_PERF_SEL_aniso_2_cycle_quads = 90 +TA_PERF_SEL_aniso_4_cycle_quads = 91 +TA_PERF_SEL_aniso_6_cycle_quads = 92 +TA_PERF_SEL_aniso_8_cycle_quads = 93 +TA_PERF_SEL_aniso_10_cycle_quads = 94 +TA_PERF_SEL_aniso_12_cycle_quads = 95 +TA_PERF_SEL_aniso_14_cycle_quads = 96 +TA_PERF_SEL_aniso_16_cycle_quads = 97 +TA_PERF_SEL_write_path_input_cycles = 98 +TA_PERF_SEL_write_path_output_cycles = 99 +TA_PERF_SEL_flat_wavefronts = 100 +TA_PERF_SEL_flat_read_wavefronts = 101 +TA_PERF_SEL_flat_write_wavefronts = 102 +TA_PERF_SEL_flat_atomic_wavefronts = 103 +TA_PERF_SEL_flat_coalesceable_wavefronts = 104 +TA_PERF_SEL_reg_sclk_vld = 105 +TA_PERF_SEL_local_cg_dyn_sclk_grp0_en = 106 +TA_PERF_SEL_local_cg_dyn_sclk_grp1_en = 107 +TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en = 108 +TA_PERF_SEL_local_cg_dyn_sclk_grp4_en = 109 +TA_PERF_SEL_local_cg_dyn_sclk_grp5_en = 110 +TA_PERF_SEL_xnack_on_phase0 = 111 +TA_PERF_SEL_xnack_on_phase1 = 112 +TA_PERF_SEL_xnack_on_phase2 = 113 +TA_PERF_SEL_xnack_on_phase3 = 114 +TA_PERF_SEL_first_xnack_on_phase0 = 115 +TA_PERF_SEL_first_xnack_on_phase1 = 116 +TA_PERF_SEL_first_xnack_on_phase2 = 117 +TA_PERF_SEL_first_xnack_on_phase3 = 118 +TA_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TD_PERFCOUNT_SEL' +TD_PERFCOUNT_SEL__enumvalues = { + 0: 'TD_PERF_SEL_none', + 1: 'TD_PERF_SEL_td_busy', + 2: 'TD_PERF_SEL_input_busy', + 3: 'TD_PERF_SEL_sampler_lerp_busy', + 4: 'TD_PERF_SEL_sampler_out_busy', + 5: 'TD_PERF_SEL_nofilter_busy', + 6: 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 7: 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 8: 'TD_PERF_SEL_RESERVED_8', + 9: 'TD_PERF_SEL_core_state_rams_read', + 10: 'TD_PERF_SEL_weight_data_rams_read', + 11: 'TD_PERF_SEL_reference_data_rams_read', + 12: 'TD_PERF_SEL_tc_td_data_fifo_full', + 13: 'TD_PERF_SEL_tc_td_ram_fifo_full', + 14: 'TD_PERF_SEL_input_state_fifo_full', + 15: 'TD_PERF_SEL_ta_data_stall', + 16: 'TD_PERF_SEL_tc_data_stall', + 17: 'TD_PERF_SEL_tc_ram_stall', + 18: 'TD_PERF_SEL_lds_stall', + 19: 'TD_PERF_SEL_sampler_pkr_full', + 20: 'TD_PERF_SEL_nofilter_pkr_full', + 21: 'TD_PERF_SEL_RESERVED_21', + 22: 'TD_PERF_SEL_gather4_wavefront', + 23: 'TD_PERF_SEL_gather4h_wavefront', + 24: 'TD_PERF_SEL_gather4h_packed_wavefront', + 25: 'TD_PERF_SEL_gather8h_packed_wavefront', + 26: 'TD_PERF_SEL_sample_c_wavefront', + 27: 'TD_PERF_SEL_load_wavefront', + 28: 'TD_PERF_SEL_store_wavefront', + 29: 'TD_PERF_SEL_ldfptr_wavefront', + 30: 'TD_PERF_SEL_write_ack_wavefront', + 31: 'TD_PERF_SEL_d16_en_wavefront', + 32: 'TD_PERF_SEL_bypassLerp_wavefront', + 33: 'TD_PERF_SEL_min_max_filter_wavefront', + 34: 'TD_PERF_SEL_one_comp_wavefront', + 35: 'TD_PERF_SEL_two_comp_wavefront', + 36: 'TD_PERF_SEL_three_comp_wavefront', + 37: 'TD_PERF_SEL_four_comp_wavefront', + 38: 'TD_PERF_SEL_user_defined_border', + 39: 'TD_PERF_SEL_white_border', + 40: 'TD_PERF_SEL_opaque_black_border', + 41: 'TD_PERF_SEL_lod_warn_from_ta', + 42: 'TD_PERF_SEL_wavefront_dest_is_lds', + 43: 'TD_PERF_SEL_td_cycling_of_nofilter_instr', + 44: 'TD_PERF_SEL_tc_cycling_of_nofilter_instr', + 45: 'TD_PERF_SEL_out_of_order_instr', + 46: 'TD_PERF_SEL_total_num_instr', + 47: 'TD_PERF_SEL_mixmode_instruction', + 48: 'TD_PERF_SEL_mixmode_resource', + 49: 'TD_PERF_SEL_status_packet', + 50: 'TD_PERF_SEL_address_cmd_poison', + 51: 'TD_PERF_SEL_data_poison', + 52: 'TD_PERF_SEL_done_scoreboard_not_empty', + 53: 'TD_PERF_SEL_done_scoreboard_is_full', + 54: 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 55: 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 56: 'TD_PERF_SEL_nofilter_formatters_turned_off', + 57: 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 58: 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', +} +TD_PERF_SEL_none = 0 +TD_PERF_SEL_td_busy = 1 +TD_PERF_SEL_input_busy = 2 +TD_PERF_SEL_sampler_lerp_busy = 3 +TD_PERF_SEL_sampler_out_busy = 4 +TD_PERF_SEL_nofilter_busy = 5 +TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off = 6 +TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off = 7 +TD_PERF_SEL_RESERVED_8 = 8 +TD_PERF_SEL_core_state_rams_read = 9 +TD_PERF_SEL_weight_data_rams_read = 10 +TD_PERF_SEL_reference_data_rams_read = 11 +TD_PERF_SEL_tc_td_data_fifo_full = 12 +TD_PERF_SEL_tc_td_ram_fifo_full = 13 +TD_PERF_SEL_input_state_fifo_full = 14 +TD_PERF_SEL_ta_data_stall = 15 +TD_PERF_SEL_tc_data_stall = 16 +TD_PERF_SEL_tc_ram_stall = 17 +TD_PERF_SEL_lds_stall = 18 +TD_PERF_SEL_sampler_pkr_full = 19 +TD_PERF_SEL_nofilter_pkr_full = 20 +TD_PERF_SEL_RESERVED_21 = 21 +TD_PERF_SEL_gather4_wavefront = 22 +TD_PERF_SEL_gather4h_wavefront = 23 +TD_PERF_SEL_gather4h_packed_wavefront = 24 +TD_PERF_SEL_gather8h_packed_wavefront = 25 +TD_PERF_SEL_sample_c_wavefront = 26 +TD_PERF_SEL_load_wavefront = 27 +TD_PERF_SEL_store_wavefront = 28 +TD_PERF_SEL_ldfptr_wavefront = 29 +TD_PERF_SEL_write_ack_wavefront = 30 +TD_PERF_SEL_d16_en_wavefront = 31 +TD_PERF_SEL_bypassLerp_wavefront = 32 +TD_PERF_SEL_min_max_filter_wavefront = 33 +TD_PERF_SEL_one_comp_wavefront = 34 +TD_PERF_SEL_two_comp_wavefront = 35 +TD_PERF_SEL_three_comp_wavefront = 36 +TD_PERF_SEL_four_comp_wavefront = 37 +TD_PERF_SEL_user_defined_border = 38 +TD_PERF_SEL_white_border = 39 +TD_PERF_SEL_opaque_black_border = 40 +TD_PERF_SEL_lod_warn_from_ta = 41 +TD_PERF_SEL_wavefront_dest_is_lds = 42 +TD_PERF_SEL_td_cycling_of_nofilter_instr = 43 +TD_PERF_SEL_tc_cycling_of_nofilter_instr = 44 +TD_PERF_SEL_out_of_order_instr = 45 +TD_PERF_SEL_total_num_instr = 46 +TD_PERF_SEL_mixmode_instruction = 47 +TD_PERF_SEL_mixmode_resource = 48 +TD_PERF_SEL_status_packet = 49 +TD_PERF_SEL_address_cmd_poison = 50 +TD_PERF_SEL_data_poison = 51 +TD_PERF_SEL_done_scoreboard_not_empty = 52 +TD_PERF_SEL_done_scoreboard_is_full = 53 +TD_PERF_SEL_done_scoreboard_bp_due_to_ooo = 54 +TD_PERF_SEL_done_scoreboard_bp_due_to_lds = 55 +TD_PERF_SEL_nofilter_formatters_turned_off = 56 +TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt = 57 +TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt = 58 +TD_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_PERFCOUNT_SELECT' +TCP_PERFCOUNT_SELECT__enumvalues = { + 0: 'TCP_PERF_SEL_GATE_EN1', + 1: 'TCP_PERF_SEL_GATE_EN2', + 2: 'TCP_PERF_SEL_CORE_REG_SCLK_VLD', + 3: 'TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES', + 4: 'TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES', + 5: 'TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES', + 6: 'TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES', + 7: 'TCP_PERF_SEL_TD_TCP_STALL_CYCLES', + 8: 'TCP_PERF_SEL_TCR_TCP_STALL_CYCLES', + 9: 'TCP_PERF_SEL_TCP_TCR_STARVE_CYCLES', + 10: 'TCP_PERF_SEL_LOD_STALL_CYCLES', + 11: 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES', + 12: 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES', + 13: 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES', + 14: 'TCP_PERF_SEL_ALLOC_STALL_CYCLES', + 15: 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 16: 'TCP_PERF_SEL_LFIFO_STALL_CYCLES', + 17: 'TCP_PERF_SEL_RFIFO_STALL_CYCLES', + 18: 'TCP_PERF_SEL_TCR_RDRET_STALL', + 19: 'TCP_PERF_SEL_WRITE_CONFLICT_STALL', + 20: 'TCP_PERF_SEL_HOLE_READ_STALL', + 21: 'TCP_PERF_SEL_READCONFLICT_STALL_CYCLES', + 22: 'TCP_PERF_SEL_PENDING_STALL_CYCLES', + 23: 'TCP_PERF_SEL_READFIFO_STALL_CYCLES', + 24: 'TCP_PERF_SEL_POWER_STALL', + 25: 'TCP_PERF_SEL_UTCL0_SERIALIZATION_STALL', + 26: 'TCP_PERF_SEL_TC_TA_XNACK_STALL', + 27: 'TCP_PERF_SEL_TA_TCP_STATE_READ', + 28: 'TCP_PERF_SEL_TOTAL_ACCESSES', + 29: 'TCP_PERF_SEL_TOTAL_READ', + 30: 'TCP_PERF_SEL_TOTAL_NON_READ', + 31: 'TCP_PERF_SEL_TOTAL_WRITE', + 32: 'TCP_PERF_SEL_TOTAL_HIT_LRU_READ', + 33: 'TCP_PERF_SEL_TOTAL_MISS_LRU_READ', + 34: 'TCP_PERF_SEL_TOTAL_MISS_EVICT_READ', + 35: 'TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE', + 36: 'TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE', + 37: 'TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET', + 38: 'TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET', + 39: 'TCP_PERF_SEL_TOTAL_WBINVL1', + 40: 'TCP_PERF_SEL_CP_TCP_INVALIDATE', + 41: 'TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES', + 42: 'TCP_PERF_SEL_SHOOTDOWN', + 43: 'TCP_PERF_SEL_UTCL0_REQUEST', + 44: 'TCP_PERF_SEL_UTCL0_TRANSLATION_MISS', + 45: 'TCP_PERF_SEL_UTCL0_TRANSLATION_HIT', + 46: 'TCP_PERF_SEL_UTCL0_PERMISSION_MISS', + 47: 'TCP_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 48: 'TCP_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 49: 'TCP_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 50: 'TCP_PERF_SEL_UTCL0_LFIFO_FULL', + 51: 'TCP_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 52: 'TCP_PERF_SEL_UTCL0_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 53: 'TCP_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 54: 'TCP_PERF_SEL_UTCL0_UTCL2_INFLIGHT', + 55: 'TCP_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 56: 'TCP_PERF_SEL_TOTAL_CACHE_ACCESSES', + 57: 'TCP_PERF_SEL_TAGRAM0_REQ', + 58: 'TCP_PERF_SEL_TAGRAM1_REQ', + 59: 'TCP_PERF_SEL_TAGRAM2_REQ', + 60: 'TCP_PERF_SEL_TAGRAM3_REQ', + 61: 'TCP_PERF_SEL_TCP_LATENCY', + 62: 'TCP_PERF_SEL_TCC_READ_REQ_LATENCY', + 63: 'TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY', + 64: 'TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY', + 65: 'TCP_PERF_SEL_TCC_READ_REQ', + 66: 'TCP_PERF_SEL_TCC_WRITE_REQ', + 67: 'TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ', + 68: 'TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ', + 69: 'TCP_PERF_SEL_TCC_LRU_REQ', + 70: 'TCP_PERF_SEL_TCC_STREAM_REQ', + 71: 'TCP_PERF_SEL_TCC_NC_READ_REQ', + 72: 'TCP_PERF_SEL_TCC_NC_WRITE_REQ', + 73: 'TCP_PERF_SEL_TCC_NC_ATOMIC_REQ', + 74: 'TCP_PERF_SEL_TCC_UC_READ_REQ', + 75: 'TCP_PERF_SEL_TCC_UC_WRITE_REQ', + 76: 'TCP_PERF_SEL_TCC_UC_ATOMIC_REQ', + 77: 'TCP_PERF_SEL_TCC_CC_READ_REQ', + 78: 'TCP_PERF_SEL_TCC_CC_WRITE_REQ', + 79: 'TCP_PERF_SEL_TCC_CC_ATOMIC_REQ', + 80: 'TCP_PERF_SEL_TCC_DCC_REQ', + 81: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', + 82: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 83: 'TCP_PERF_SEL_GL1_REQ_READ', + 84: 'TCP_PERF_SEL_GL1_REQ_READ_LATENCY', + 85: 'TCP_PERF_SEL_GL1_REQ_WRITE', + 86: 'TCP_PERF_SEL_GL1_REQ_WRITE_LATENCY', + 87: 'TCP_PERF_SEL_REQ_MISS_TAGRAM0', + 88: 'TCP_PERF_SEL_REQ_MISS_TAGRAM1', + 89: 'TCP_PERF_SEL_REQ_MISS_TAGRAM2', + 90: 'TCP_PERF_SEL_REQ_MISS_TAGRAM3', + 91: 'TCP_PERF_SEL_TA_REQ', + 92: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', + 93: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 94: 'TCP_PERF_SEL_TA_REQ_READ', + 95: 'TCP_PERF_SEL_TA_REQ_WRITE', + 96: 'TCP_PERF_SEL_TA_REQ_STATE_READ', +} +TCP_PERF_SEL_GATE_EN1 = 0 +TCP_PERF_SEL_GATE_EN2 = 1 +TCP_PERF_SEL_CORE_REG_SCLK_VLD = 2 +TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES = 3 +TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES = 4 +TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES = 5 +TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES = 6 +TCP_PERF_SEL_TD_TCP_STALL_CYCLES = 7 +TCP_PERF_SEL_TCR_TCP_STALL_CYCLES = 8 +TCP_PERF_SEL_TCP_TCR_STARVE_CYCLES = 9 +TCP_PERF_SEL_LOD_STALL_CYCLES = 10 +TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES = 11 +TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES = 12 +TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES = 13 +TCP_PERF_SEL_ALLOC_STALL_CYCLES = 14 +TCP_PERF_SEL_UNORDERED_MTYPE_STALL = 15 +TCP_PERF_SEL_LFIFO_STALL_CYCLES = 16 +TCP_PERF_SEL_RFIFO_STALL_CYCLES = 17 +TCP_PERF_SEL_TCR_RDRET_STALL = 18 +TCP_PERF_SEL_WRITE_CONFLICT_STALL = 19 +TCP_PERF_SEL_HOLE_READ_STALL = 20 +TCP_PERF_SEL_READCONFLICT_STALL_CYCLES = 21 +TCP_PERF_SEL_PENDING_STALL_CYCLES = 22 +TCP_PERF_SEL_READFIFO_STALL_CYCLES = 23 +TCP_PERF_SEL_POWER_STALL = 24 +TCP_PERF_SEL_UTCL0_SERIALIZATION_STALL = 25 +TCP_PERF_SEL_TC_TA_XNACK_STALL = 26 +TCP_PERF_SEL_TA_TCP_STATE_READ = 27 +TCP_PERF_SEL_TOTAL_ACCESSES = 28 +TCP_PERF_SEL_TOTAL_READ = 29 +TCP_PERF_SEL_TOTAL_NON_READ = 30 +TCP_PERF_SEL_TOTAL_WRITE = 31 +TCP_PERF_SEL_TOTAL_HIT_LRU_READ = 32 +TCP_PERF_SEL_TOTAL_MISS_LRU_READ = 33 +TCP_PERF_SEL_TOTAL_MISS_EVICT_READ = 34 +TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE = 35 +TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE = 36 +TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET = 37 +TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET = 38 +TCP_PERF_SEL_TOTAL_WBINVL1 = 39 +TCP_PERF_SEL_CP_TCP_INVALIDATE = 40 +TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES = 41 +TCP_PERF_SEL_SHOOTDOWN = 42 +TCP_PERF_SEL_UTCL0_REQUEST = 43 +TCP_PERF_SEL_UTCL0_TRANSLATION_MISS = 44 +TCP_PERF_SEL_UTCL0_TRANSLATION_HIT = 45 +TCP_PERF_SEL_UTCL0_PERMISSION_MISS = 46 +TCP_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX = 47 +TCP_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT = 48 +TCP_PERF_SEL_UTCL0_STALL_MULTI_MISS = 49 +TCP_PERF_SEL_UTCL0_LFIFO_FULL = 50 +TCP_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES = 51 +TCP_PERF_SEL_UTCL0_STALL_UTCL2_REQ_OUT_OF_CREDITS = 52 +TCP_PERF_SEL_CLIENT_UTCL0_INFLIGHT = 53 +TCP_PERF_SEL_UTCL0_UTCL2_INFLIGHT = 54 +TCP_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL = 55 +TCP_PERF_SEL_TOTAL_CACHE_ACCESSES = 56 +TCP_PERF_SEL_TAGRAM0_REQ = 57 +TCP_PERF_SEL_TAGRAM1_REQ = 58 +TCP_PERF_SEL_TAGRAM2_REQ = 59 +TCP_PERF_SEL_TAGRAM3_REQ = 60 +TCP_PERF_SEL_TCP_LATENCY = 61 +TCP_PERF_SEL_TCC_READ_REQ_LATENCY = 62 +TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY = 63 +TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY = 64 +TCP_PERF_SEL_TCC_READ_REQ = 65 +TCP_PERF_SEL_TCC_WRITE_REQ = 66 +TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ = 67 +TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ = 68 +TCP_PERF_SEL_TCC_LRU_REQ = 69 +TCP_PERF_SEL_TCC_STREAM_REQ = 70 +TCP_PERF_SEL_TCC_NC_READ_REQ = 71 +TCP_PERF_SEL_TCC_NC_WRITE_REQ = 72 +TCP_PERF_SEL_TCC_NC_ATOMIC_REQ = 73 +TCP_PERF_SEL_TCC_UC_READ_REQ = 74 +TCP_PERF_SEL_TCC_UC_WRITE_REQ = 75 +TCP_PERF_SEL_TCC_UC_ATOMIC_REQ = 76 +TCP_PERF_SEL_TCC_CC_READ_REQ = 77 +TCP_PERF_SEL_TCC_CC_WRITE_REQ = 78 +TCP_PERF_SEL_TCC_CC_ATOMIC_REQ = 79 +TCP_PERF_SEL_TCC_DCC_REQ = 80 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET = 81 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET = 82 +TCP_PERF_SEL_GL1_REQ_READ = 83 +TCP_PERF_SEL_GL1_REQ_READ_LATENCY = 84 +TCP_PERF_SEL_GL1_REQ_WRITE = 85 +TCP_PERF_SEL_GL1_REQ_WRITE_LATENCY = 86 +TCP_PERF_SEL_REQ_MISS_TAGRAM0 = 87 +TCP_PERF_SEL_REQ_MISS_TAGRAM1 = 88 +TCP_PERF_SEL_REQ_MISS_TAGRAM2 = 89 +TCP_PERF_SEL_REQ_MISS_TAGRAM3 = 90 +TCP_PERF_SEL_TA_REQ = 91 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET = 92 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET = 93 +TCP_PERF_SEL_TA_REQ_READ = 94 +TCP_PERF_SEL_TA_REQ_WRITE = 95 +TCP_PERF_SEL_TA_REQ_STATE_READ = 96 +TCP_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_POLICIES' +TCP_CACHE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_POLICY_MISS_LRU', + 1: 'TCP_CACHE_POLICY_MISS_EVICT', + 2: 'TCP_CACHE_POLICY_HIT_LRU', + 3: 'TCP_CACHE_POLICY_HIT_EVICT', +} +TCP_CACHE_POLICY_MISS_LRU = 0 +TCP_CACHE_POLICY_MISS_EVICT = 1 +TCP_CACHE_POLICY_HIT_LRU = 2 +TCP_CACHE_POLICY_HIT_EVICT = 3 +TCP_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_STORE_POLICIES' +TCP_CACHE_STORE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_STORE_POLICY_WT_LRU', + 1: 'TCP_CACHE_STORE_POLICY_WT_EVICT', +} +TCP_CACHE_STORE_POLICY_WT_LRU = 0 +TCP_CACHE_STORE_POLICY_WT_EVICT = 1 +TCP_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_WATCH_MODES' +TCP_WATCH_MODES__enumvalues = { + 0: 'TCP_WATCH_MODE_READ', + 1: 'TCP_WATCH_MODE_NONREAD', + 2: 'TCP_WATCH_MODE_ATOMIC', + 3: 'TCP_WATCH_MODE_ALL', +} +TCP_WATCH_MODE_READ = 0 +TCP_WATCH_MODE_NONREAD = 1 +TCP_WATCH_MODE_ATOMIC = 2 +TCP_WATCH_MODE_ALL = 3 +TCP_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_DATA_SEL' +TCP_DSM_DATA_SEL__enumvalues = { + 0: 'TCP_DSM_DISABLE', + 1: 'TCP_DSM_SEL0', + 2: 'TCP_DSM_SEL1', + 3: 'TCP_DSM_SEL_BOTH', +} +TCP_DSM_DISABLE = 0 +TCP_DSM_SEL0 = 1 +TCP_DSM_SEL1 = 2 +TCP_DSM_SEL_BOTH = 3 +TCP_DSM_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_SINGLE_WRITE' +TCP_DSM_SINGLE_WRITE__enumvalues = { + 0: 'TCP_DSM_SINGLE_WRITE_DIS', + 1: 'TCP_DSM_SINGLE_WRITE_EN', +} +TCP_DSM_SINGLE_WRITE_DIS = 0 +TCP_DSM_SINGLE_WRITE_EN = 1 +TCP_DSM_SINGLE_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_INJECT_SEL' +TCP_DSM_INJECT_SEL__enumvalues = { + 0: 'TCP_DSM_INJECT_SEL0', + 1: 'TCP_DSM_INJECT_SEL1', + 2: 'TCP_DSM_INJECT_SEL2', + 3: 'TCP_DSM_INJECT_SEL3', +} +TCP_DSM_INJECT_SEL0 = 0 +TCP_DSM_INJECT_SEL1 = 1 +TCP_DSM_INJECT_SEL2 = 2 +TCP_DSM_INJECT_SEL3 = 3 +TCP_DSM_INJECT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_OPCODE_TYPE' +TCP_OPCODE_TYPE__enumvalues = { + 0: 'TCP_OPCODE_READ', + 1: 'TCP_OPCODE_WRITE', + 2: 'TCP_OPCODE_ATOMIC', + 3: 'TCP_OPCODE_WBINVL1', + 4: 'TCP_OPCODE_ATOMIC_CMPSWAP', + 5: 'TCP_OPCODE_GATHERH', +} +TCP_OPCODE_READ = 0 +TCP_OPCODE_WRITE = 1 +TCP_OPCODE_ATOMIC = 2 +TCP_OPCODE_WBINVL1 = 3 +TCP_OPCODE_ATOMIC_CMPSWAP = 4 +TCP_OPCODE_GATHERH = 5 +TCP_OPCODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GL2C_PERF_SEL' +GL2C_PERF_SEL__enumvalues = { + 0: 'GL2C_PERF_SEL_NONE', + 1: 'GL2C_PERF_SEL_CYCLE', + 2: 'GL2C_PERF_SEL_BUSY', + 3: 'GL2C_PERF_SEL_REQ', + 4: 'GL2C_PERF_SEL_VOL_REQ', + 5: 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', + 6: 'GL2C_PERF_SEL_READ', + 7: 'GL2C_PERF_SEL_WRITE', + 8: 'GL2C_PERF_SEL_ATOMIC', + 9: 'GL2C_PERF_SEL_NOP_ACK', + 10: 'GL2C_PERF_SEL_NOP_RTN0', + 11: 'GL2C_PERF_SEL_PROBE', + 12: 'GL2C_PERF_SEL_PROBE_ALL', + 13: 'GL2C_PERF_SEL_INTERNAL_PROBE', + 14: 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', + 15: 'GL2C_PERF_SEL_METADATA_READ_REQ', + 16: 'GL2C_PERF_SEL_CLIENT0_REQ', + 17: 'GL2C_PERF_SEL_CLIENT1_REQ', + 18: 'GL2C_PERF_SEL_CLIENT2_REQ', + 19: 'GL2C_PERF_SEL_CLIENT3_REQ', + 20: 'GL2C_PERF_SEL_CLIENT4_REQ', + 21: 'GL2C_PERF_SEL_CLIENT5_REQ', + 22: 'GL2C_PERF_SEL_CLIENT6_REQ', + 23: 'GL2C_PERF_SEL_CLIENT7_REQ', + 24: 'GL2C_PERF_SEL_C_RW_S_REQ', + 25: 'GL2C_PERF_SEL_C_RW_US_REQ', + 26: 'GL2C_PERF_SEL_C_RO_S_REQ', + 27: 'GL2C_PERF_SEL_C_RO_US_REQ', + 28: 'GL2C_PERF_SEL_UC_REQ', + 29: 'GL2C_PERF_SEL_LRU_REQ', + 30: 'GL2C_PERF_SEL_STREAM_REQ', + 31: 'GL2C_PERF_SEL_BYPASS_REQ', + 32: 'GL2C_PERF_SEL_NOA_REQ', + 33: 'GL2C_PERF_SEL_SHARED_REQ', + 34: 'GL2C_PERF_SEL_HIT', + 35: 'GL2C_PERF_SEL_MISS', + 36: 'GL2C_PERF_SEL_FULL_HIT', + 37: 'GL2C_PERF_SEL_PARTIAL_32B_HIT', + 38: 'GL2C_PERF_SEL_PARTIAL_64B_HIT', + 39: 'GL2C_PERF_SEL_PARTIAL_96B_HIT', + 40: 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', + 41: 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', + 42: 'GL2C_PERF_SEL_UNCACHED_WRITE', + 43: 'GL2C_PERF_SEL_WRITEBACK', + 44: 'GL2C_PERF_SEL_NORMAL_WRITEBACK', + 45: 'GL2C_PERF_SEL_EVICT', + 46: 'GL2C_PERF_SEL_NORMAL_EVICT', + 47: 'GL2C_PERF_SEL_PROBE_EVICT', + 48: 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', + 49: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_HI_PRIO', + 50: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_COMP', + 51: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 52: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 53: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 54: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 55: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 56: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 57: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 58: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 59: 'GL2C_PERF_SEL_READ_32_REQ', + 60: 'GL2C_PERF_SEL_READ_64_REQ', + 61: 'GL2C_PERF_SEL_READ_128_REQ', + 62: 'GL2C_PERF_SEL_WRITE_32_REQ', + 63: 'GL2C_PERF_SEL_WRITE_64_REQ', + 64: 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 65: 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 66: 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 67: 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 68: 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 69: 'GL2C_PERF_SEL_MC_WRREQ', + 70: 'GL2C_PERF_SEL_EA_WRREQ_64B', + 71: 'GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 72: 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', + 73: 'GL2C_PERF_SEL_MC_WRREQ_STALL', + 74: 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 75: 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 76: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 77: 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', + 78: 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', + 79: 'GL2C_PERF_SEL_EA_ATOMIC', + 80: 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', + 81: 'GL2C_PERF_SEL_MC_RDREQ', + 82: 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', + 83: 'GL2C_PERF_SEL_EA_RDREQ_32B', + 84: 'GL2C_PERF_SEL_EA_RDREQ_64B', + 85: 'GL2C_PERF_SEL_EA_RDREQ_96B', + 86: 'GL2C_PERF_SEL_EA_RDREQ_128B', + 87: 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', + 88: 'GL2C_PERF_SEL_EA_RD_MDC_32B', + 89: 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 90: 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 91: 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 92: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 93: 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', + 94: 'GL2C_PERF_SEL_EA_RDREQ_DRAM', + 95: 'GL2C_PERF_SEL_EA_WRREQ_DRAM', + 96: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 97: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 98: 'GL2C_PERF_SEL_ONION_READ', + 99: 'GL2C_PERF_SEL_ONION_WRITE', + 100: 'GL2C_PERF_SEL_IO_READ', + 101: 'GL2C_PERF_SEL_IO_WRITE', + 102: 'GL2C_PERF_SEL_GARLIC_READ', + 103: 'GL2C_PERF_SEL_GARLIC_WRITE', + 104: 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', + 105: 'GL2C_PERF_SEL_SRC_FIFO_FULL', + 106: 'GL2C_PERF_SEL_TAG_STALL', + 107: 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 108: 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 109: 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 110: 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 111: 'GL2C_PERF_SEL_TAG_PROBE_STALL', + 112: 'GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL', + 113: 'GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL', + 114: 'GL2C_PERF_SEL_TAG_READ_DST_STALL', + 115: 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', + 116: 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 117: 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 118: 'GL2C_PERF_SEL_BUBBLE', + 119: 'GL2C_PERF_SEL_IB_REQ', + 120: 'GL2C_PERF_SEL_IB_STALL', + 121: 'GL2C_PERF_SEL_IB_TAG_STALL', + 122: 'GL2C_PERF_SEL_IB_CM_STALL', + 123: 'GL2C_PERF_SEL_RETURN_ACK', + 124: 'GL2C_PERF_SEL_RETURN_DATA', + 125: 'GL2C_PERF_SEL_EA_RDRET_NACK', + 126: 'GL2C_PERF_SEL_EA_WRRET_NACK', + 127: 'GL2C_PERF_SEL_GL2A_LEVEL', + 128: 'GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 129: 'GL2C_PERF_SEL_PROBE_FILTER_DISABLED', + 130: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 131: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 132: 'GL2C_PERF_SEL_GCR_INV', + 133: 'GL2C_PERF_SEL_GCR_WB', + 134: 'GL2C_PERF_SEL_GCR_DISCARD', + 135: 'GL2C_PERF_SEL_GCR_RANGE', + 136: 'GL2C_PERF_SEL_GCR_ALL', + 137: 'GL2C_PERF_SEL_GCR_VOL', + 138: 'GL2C_PERF_SEL_GCR_UNSHARED', + 139: 'GL2C_PERF_SEL_GCR_MDC_INV', + 140: 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 141: 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 142: 'GL2C_PERF_SEL_GCR_MDC_INV_ALL', + 143: 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', + 144: 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', + 145: 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 146: 'GL2C_PERF_SEL_GCR_MDC_INV_RANGE', + 147: 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 148: 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 149: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 150: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 151: 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 152: 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 153: 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 154: 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', + 155: 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 156: 'GL2C_PERF_SEL_GCR_WBL2_VOL_EVICT', + 157: 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', + 158: 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 159: 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 160: 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 161: 'GL2C_PERF_SEL_MDC_INV_METADATA', + 162: 'GL2C_PERF_SEL_MDC_REQ', + 163: 'GL2C_PERF_SEL_MDC_LEVEL', + 164: 'GL2C_PERF_SEL_MDC_TAG_HIT', + 165: 'GL2C_PERF_SEL_MDC_SECTOR_HIT', + 166: 'GL2C_PERF_SEL_MDC_SECTOR_MISS', + 167: 'GL2C_PERF_SEL_MDC_TAG_STALL', + 168: 'GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 169: 'GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 170: 'GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 171: 'GL2C_PERF_SEL_CM_CHANNEL0_REQ', + 172: 'GL2C_PERF_SEL_CM_CHANNEL1_REQ', + 173: 'GL2C_PERF_SEL_CM_CHANNEL2_REQ', + 174: 'GL2C_PERF_SEL_CM_CHANNEL3_REQ', + 175: 'GL2C_PERF_SEL_CM_CHANNEL4_REQ', + 176: 'GL2C_PERF_SEL_CM_CHANNEL5_REQ', + 177: 'GL2C_PERF_SEL_CM_CHANNEL6_REQ', + 178: 'GL2C_PERF_SEL_CM_CHANNEL7_REQ', + 179: 'GL2C_PERF_SEL_CM_CHANNEL8_REQ', + 180: 'GL2C_PERF_SEL_CM_CHANNEL9_REQ', + 181: 'GL2C_PERF_SEL_CM_CHANNEL10_REQ', + 182: 'GL2C_PERF_SEL_CM_CHANNEL11_REQ', + 183: 'GL2C_PERF_SEL_CM_CHANNEL12_REQ', + 184: 'GL2C_PERF_SEL_CM_CHANNEL13_REQ', + 185: 'GL2C_PERF_SEL_CM_CHANNEL14_REQ', + 186: 'GL2C_PERF_SEL_CM_CHANNEL15_REQ', + 187: 'GL2C_PERF_SEL_CM_CHANNEL16_REQ', + 188: 'GL2C_PERF_SEL_CM_CHANNEL17_REQ', + 189: 'GL2C_PERF_SEL_CM_CHANNEL18_REQ', + 190: 'GL2C_PERF_SEL_CM_CHANNEL19_REQ', + 191: 'GL2C_PERF_SEL_CM_CHANNEL20_REQ', + 192: 'GL2C_PERF_SEL_CM_CHANNEL21_REQ', + 193: 'GL2C_PERF_SEL_CM_CHANNEL22_REQ', + 194: 'GL2C_PERF_SEL_CM_CHANNEL23_REQ', + 195: 'GL2C_PERF_SEL_CM_CHANNEL24_REQ', + 196: 'GL2C_PERF_SEL_CM_CHANNEL25_REQ', + 197: 'GL2C_PERF_SEL_CM_CHANNEL26_REQ', + 198: 'GL2C_PERF_SEL_CM_CHANNEL27_REQ', + 199: 'GL2C_PERF_SEL_CM_CHANNEL28_REQ', + 200: 'GL2C_PERF_SEL_CM_CHANNEL29_REQ', + 201: 'GL2C_PERF_SEL_CM_CHANNEL30_REQ', + 202: 'GL2C_PERF_SEL_CM_CHANNEL31_REQ', + 203: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ', + 204: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ', + 205: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ', + 206: 'GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ', + 207: 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ', + 208: 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ', + 209: 'GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ', + 210: 'GL2C_PERF_SEL_CM_COMP_READ_REQ', + 211: 'GL2C_PERF_SEL_CM_READ_BACK_REQ', + 212: 'GL2C_PERF_SEL_CM_METADATA_WR_REQ', + 213: 'GL2C_PERF_SEL_CM_WR_ACK_REQ', + 214: 'GL2C_PERF_SEL_CM_NO_ACK_REQ', + 215: 'GL2C_PERF_SEL_CM_NOOP_REQ', + 216: 'GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ', + 217: 'GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ', + 218: 'GL2C_PERF_SEL_CM_COMP_STENCIL_REQ', + 219: 'GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ', + 220: 'GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ', + 221: 'GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ', + 222: 'GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ', + 223: 'GL2C_PERF_SEL_CM_FULL_WRITE_REQ', + 224: 'GL2C_PERF_SEL_CM_RVF_FULL', + 225: 'GL2C_PERF_SEL_CM_SDR_FULL', + 226: 'GL2C_PERF_SEL_CM_MERGE_BUF_FULL', + 227: 'GL2C_PERF_SEL_CM_DCC_STALL', +} +GL2C_PERF_SEL_NONE = 0 +GL2C_PERF_SEL_CYCLE = 1 +GL2C_PERF_SEL_BUSY = 2 +GL2C_PERF_SEL_REQ = 3 +GL2C_PERF_SEL_VOL_REQ = 4 +GL2C_PERF_SEL_HIGH_PRIORITY_REQ = 5 +GL2C_PERF_SEL_READ = 6 +GL2C_PERF_SEL_WRITE = 7 +GL2C_PERF_SEL_ATOMIC = 8 +GL2C_PERF_SEL_NOP_ACK = 9 +GL2C_PERF_SEL_NOP_RTN0 = 10 +GL2C_PERF_SEL_PROBE = 11 +GL2C_PERF_SEL_PROBE_ALL = 12 +GL2C_PERF_SEL_INTERNAL_PROBE = 13 +GL2C_PERF_SEL_COMPRESSED_READ_REQ = 14 +GL2C_PERF_SEL_METADATA_READ_REQ = 15 +GL2C_PERF_SEL_CLIENT0_REQ = 16 +GL2C_PERF_SEL_CLIENT1_REQ = 17 +GL2C_PERF_SEL_CLIENT2_REQ = 18 +GL2C_PERF_SEL_CLIENT3_REQ = 19 +GL2C_PERF_SEL_CLIENT4_REQ = 20 +GL2C_PERF_SEL_CLIENT5_REQ = 21 +GL2C_PERF_SEL_CLIENT6_REQ = 22 +GL2C_PERF_SEL_CLIENT7_REQ = 23 +GL2C_PERF_SEL_C_RW_S_REQ = 24 +GL2C_PERF_SEL_C_RW_US_REQ = 25 +GL2C_PERF_SEL_C_RO_S_REQ = 26 +GL2C_PERF_SEL_C_RO_US_REQ = 27 +GL2C_PERF_SEL_UC_REQ = 28 +GL2C_PERF_SEL_LRU_REQ = 29 +GL2C_PERF_SEL_STREAM_REQ = 30 +GL2C_PERF_SEL_BYPASS_REQ = 31 +GL2C_PERF_SEL_NOA_REQ = 32 +GL2C_PERF_SEL_SHARED_REQ = 33 +GL2C_PERF_SEL_HIT = 34 +GL2C_PERF_SEL_MISS = 35 +GL2C_PERF_SEL_FULL_HIT = 36 +GL2C_PERF_SEL_PARTIAL_32B_HIT = 37 +GL2C_PERF_SEL_PARTIAL_64B_HIT = 38 +GL2C_PERF_SEL_PARTIAL_96B_HIT = 39 +GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT = 40 +GL2C_PERF_SEL_FULLY_WRITTEN_HIT = 41 +GL2C_PERF_SEL_UNCACHED_WRITE = 42 +GL2C_PERF_SEL_WRITEBACK = 43 +GL2C_PERF_SEL_NORMAL_WRITEBACK = 44 +GL2C_PERF_SEL_EVICT = 45 +GL2C_PERF_SEL_NORMAL_EVICT = 46 +GL2C_PERF_SEL_PROBE_EVICT = 47 +GL2C_PERF_SEL_REQ_TO_MISS_QUEUE = 48 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_HI_PRIO = 49 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_COMP = 50 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0 = 51 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1 = 52 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2 = 53 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3 = 54 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4 = 55 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5 = 56 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6 = 57 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7 = 58 +GL2C_PERF_SEL_READ_32_REQ = 59 +GL2C_PERF_SEL_READ_64_REQ = 60 +GL2C_PERF_SEL_READ_128_REQ = 61 +GL2C_PERF_SEL_WRITE_32_REQ = 62 +GL2C_PERF_SEL_WRITE_64_REQ = 63 +GL2C_PERF_SEL_COMPRESSED_READ_0_REQ = 64 +GL2C_PERF_SEL_COMPRESSED_READ_32_REQ = 65 +GL2C_PERF_SEL_COMPRESSED_READ_64_REQ = 66 +GL2C_PERF_SEL_COMPRESSED_READ_96_REQ = 67 +GL2C_PERF_SEL_COMPRESSED_READ_128_REQ = 68 +GL2C_PERF_SEL_MC_WRREQ = 69 +GL2C_PERF_SEL_EA_WRREQ_64B = 70 +GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND = 71 +GL2C_PERF_SEL_EA_WR_UNCACHED_32B = 72 +GL2C_PERF_SEL_MC_WRREQ_STALL = 73 +GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL = 74 +GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL = 75 +GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL = 76 +GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL = 77 +GL2C_PERF_SEL_MC_WRREQ_LEVEL = 78 +GL2C_PERF_SEL_EA_ATOMIC = 79 +GL2C_PERF_SEL_EA_ATOMIC_LEVEL = 80 +GL2C_PERF_SEL_MC_RDREQ = 81 +GL2C_PERF_SEL_EA_RDREQ_SPLIT = 82 +GL2C_PERF_SEL_EA_RDREQ_32B = 83 +GL2C_PERF_SEL_EA_RDREQ_64B = 84 +GL2C_PERF_SEL_EA_RDREQ_96B = 85 +GL2C_PERF_SEL_EA_RDREQ_128B = 86 +GL2C_PERF_SEL_EA_RD_UNCACHED_32B = 87 +GL2C_PERF_SEL_EA_RD_MDC_32B = 88 +GL2C_PERF_SEL_EA_RD_COMPRESSED_32B = 89 +GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL = 90 +GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL = 91 +GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL = 92 +GL2C_PERF_SEL_MC_RDREQ_LEVEL = 93 +GL2C_PERF_SEL_EA_RDREQ_DRAM = 94 +GL2C_PERF_SEL_EA_WRREQ_DRAM = 95 +GL2C_PERF_SEL_EA_RDREQ_DRAM_32B = 96 +GL2C_PERF_SEL_EA_WRREQ_DRAM_32B = 97 +GL2C_PERF_SEL_ONION_READ = 98 +GL2C_PERF_SEL_ONION_WRITE = 99 +GL2C_PERF_SEL_IO_READ = 100 +GL2C_PERF_SEL_IO_WRITE = 101 +GL2C_PERF_SEL_GARLIC_READ = 102 +GL2C_PERF_SEL_GARLIC_WRITE = 103 +GL2C_PERF_SEL_LATENCY_FIFO_FULL = 104 +GL2C_PERF_SEL_SRC_FIFO_FULL = 105 +GL2C_PERF_SEL_TAG_STALL = 106 +GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL = 107 +GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL = 108 +GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL = 109 +GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL = 110 +GL2C_PERF_SEL_TAG_PROBE_STALL = 111 +GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL = 112 +GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL = 113 +GL2C_PERF_SEL_TAG_READ_DST_STALL = 114 +GL2C_PERF_SEL_READ_RETURN_TIMEOUT = 115 +GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT = 116 +GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE = 117 +GL2C_PERF_SEL_BUBBLE = 118 +GL2C_PERF_SEL_IB_REQ = 119 +GL2C_PERF_SEL_IB_STALL = 120 +GL2C_PERF_SEL_IB_TAG_STALL = 121 +GL2C_PERF_SEL_IB_CM_STALL = 122 +GL2C_PERF_SEL_RETURN_ACK = 123 +GL2C_PERF_SEL_RETURN_DATA = 124 +GL2C_PERF_SEL_EA_RDRET_NACK = 125 +GL2C_PERF_SEL_EA_WRRET_NACK = 126 +GL2C_PERF_SEL_GL2A_LEVEL = 127 +GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION = 128 +GL2C_PERF_SEL_PROBE_FILTER_DISABLED = 129 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START = 130 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START = 131 +GL2C_PERF_SEL_GCR_INV = 132 +GL2C_PERF_SEL_GCR_WB = 133 +GL2C_PERF_SEL_GCR_DISCARD = 134 +GL2C_PERF_SEL_GCR_RANGE = 135 +GL2C_PERF_SEL_GCR_ALL = 136 +GL2C_PERF_SEL_GCR_VOL = 137 +GL2C_PERF_SEL_GCR_UNSHARED = 138 +GL2C_PERF_SEL_GCR_MDC_INV = 139 +GL2C_PERF_SEL_GCR_GL2_INV_ALL = 140 +GL2C_PERF_SEL_GCR_GL2_WB_ALL = 141 +GL2C_PERF_SEL_GCR_MDC_INV_ALL = 142 +GL2C_PERF_SEL_GCR_GL2_INV_RANGE = 143 +GL2C_PERF_SEL_GCR_GL2_WB_RANGE = 144 +GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE = 145 +GL2C_PERF_SEL_GCR_MDC_INV_RANGE = 146 +GL2C_PERF_SEL_ALL_GCR_INV_EVICT = 147 +GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT = 148 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE = 149 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE = 150 +GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK = 151 +GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE = 152 +GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT = 153 +GL2C_PERF_SEL_GCR_INVL2_VOL_START = 154 +GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE = 155 +GL2C_PERF_SEL_GCR_WBL2_VOL_EVICT = 156 +GL2C_PERF_SEL_GCR_WBL2_VOL_START = 157 +GL2C_PERF_SEL_GCR_WBINVL2_CYCLE = 158 +GL2C_PERF_SEL_GCR_WBINVL2_EVICT = 159 +GL2C_PERF_SEL_GCR_WBINVL2_START = 160 +GL2C_PERF_SEL_MDC_INV_METADATA = 161 +GL2C_PERF_SEL_MDC_REQ = 162 +GL2C_PERF_SEL_MDC_LEVEL = 163 +GL2C_PERF_SEL_MDC_TAG_HIT = 164 +GL2C_PERF_SEL_MDC_SECTOR_HIT = 165 +GL2C_PERF_SEL_MDC_SECTOR_MISS = 166 +GL2C_PERF_SEL_MDC_TAG_STALL = 167 +GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL = 168 +GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL = 169 +GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL = 170 +GL2C_PERF_SEL_CM_CHANNEL0_REQ = 171 +GL2C_PERF_SEL_CM_CHANNEL1_REQ = 172 +GL2C_PERF_SEL_CM_CHANNEL2_REQ = 173 +GL2C_PERF_SEL_CM_CHANNEL3_REQ = 174 +GL2C_PERF_SEL_CM_CHANNEL4_REQ = 175 +GL2C_PERF_SEL_CM_CHANNEL5_REQ = 176 +GL2C_PERF_SEL_CM_CHANNEL6_REQ = 177 +GL2C_PERF_SEL_CM_CHANNEL7_REQ = 178 +GL2C_PERF_SEL_CM_CHANNEL8_REQ = 179 +GL2C_PERF_SEL_CM_CHANNEL9_REQ = 180 +GL2C_PERF_SEL_CM_CHANNEL10_REQ = 181 +GL2C_PERF_SEL_CM_CHANNEL11_REQ = 182 +GL2C_PERF_SEL_CM_CHANNEL12_REQ = 183 +GL2C_PERF_SEL_CM_CHANNEL13_REQ = 184 +GL2C_PERF_SEL_CM_CHANNEL14_REQ = 185 +GL2C_PERF_SEL_CM_CHANNEL15_REQ = 186 +GL2C_PERF_SEL_CM_CHANNEL16_REQ = 187 +GL2C_PERF_SEL_CM_CHANNEL17_REQ = 188 +GL2C_PERF_SEL_CM_CHANNEL18_REQ = 189 +GL2C_PERF_SEL_CM_CHANNEL19_REQ = 190 +GL2C_PERF_SEL_CM_CHANNEL20_REQ = 191 +GL2C_PERF_SEL_CM_CHANNEL21_REQ = 192 +GL2C_PERF_SEL_CM_CHANNEL22_REQ = 193 +GL2C_PERF_SEL_CM_CHANNEL23_REQ = 194 +GL2C_PERF_SEL_CM_CHANNEL24_REQ = 195 +GL2C_PERF_SEL_CM_CHANNEL25_REQ = 196 +GL2C_PERF_SEL_CM_CHANNEL26_REQ = 197 +GL2C_PERF_SEL_CM_CHANNEL27_REQ = 198 +GL2C_PERF_SEL_CM_CHANNEL28_REQ = 199 +GL2C_PERF_SEL_CM_CHANNEL29_REQ = 200 +GL2C_PERF_SEL_CM_CHANNEL30_REQ = 201 +GL2C_PERF_SEL_CM_CHANNEL31_REQ = 202 +GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ = 203 +GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ = 204 +GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ = 205 +GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ = 206 +GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ = 207 +GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ = 208 +GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ = 209 +GL2C_PERF_SEL_CM_COMP_READ_REQ = 210 +GL2C_PERF_SEL_CM_READ_BACK_REQ = 211 +GL2C_PERF_SEL_CM_METADATA_WR_REQ = 212 +GL2C_PERF_SEL_CM_WR_ACK_REQ = 213 +GL2C_PERF_SEL_CM_NO_ACK_REQ = 214 +GL2C_PERF_SEL_CM_NOOP_REQ = 215 +GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ = 216 +GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ = 217 +GL2C_PERF_SEL_CM_COMP_STENCIL_REQ = 218 +GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ = 219 +GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ = 220 +GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ = 221 +GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ = 222 +GL2C_PERF_SEL_CM_FULL_WRITE_REQ = 223 +GL2C_PERF_SEL_CM_RVF_FULL = 224 +GL2C_PERF_SEL_CM_SDR_FULL = 225 +GL2C_PERF_SEL_CM_MERGE_BUF_FULL = 226 +GL2C_PERF_SEL_CM_DCC_STALL = 227 +GL2C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL2A_PERF_SEL' +GL2A_PERF_SEL__enumvalues = { + 0: 'GL2A_PERF_SEL_NONE', + 1: 'GL2A_PERF_SEL_CYCLE', + 2: 'GL2A_PERF_SEL_BUSY', + 3: 'GL2A_PERF_SEL_REQ_GL2C0', + 4: 'GL2A_PERF_SEL_REQ_GL2C1', + 5: 'GL2A_PERF_SEL_REQ_GL2C2', + 6: 'GL2A_PERF_SEL_REQ_GL2C3', + 7: 'GL2A_PERF_SEL_REQ_GL2C4', + 8: 'GL2A_PERF_SEL_REQ_GL2C5', + 9: 'GL2A_PERF_SEL_REQ_GL2C6', + 10: 'GL2A_PERF_SEL_REQ_GL2C7', + 11: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0', + 12: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1', + 13: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2', + 14: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3', + 15: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4', + 16: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5', + 17: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6', + 18: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7', + 19: 'GL2A_PERF_SEL_REQ_BURST_GL2C0', + 20: 'GL2A_PERF_SEL_REQ_BURST_GL2C1', + 21: 'GL2A_PERF_SEL_REQ_BURST_GL2C2', + 22: 'GL2A_PERF_SEL_REQ_BURST_GL2C3', + 23: 'GL2A_PERF_SEL_REQ_BURST_GL2C4', + 24: 'GL2A_PERF_SEL_REQ_BURST_GL2C5', + 25: 'GL2A_PERF_SEL_REQ_BURST_GL2C6', + 26: 'GL2A_PERF_SEL_REQ_BURST_GL2C7', + 27: 'GL2A_PERF_SEL_REQ_STALL_GL2C0', + 28: 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 29: 'GL2A_PERF_SEL_REQ_STALL_GL2C2', + 30: 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 31: 'GL2A_PERF_SEL_REQ_STALL_GL2C4', + 32: 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 33: 'GL2A_PERF_SEL_REQ_STALL_GL2C6', + 34: 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 35: 'GL2A_PERF_SEL_RTN_STALL_GL2C0', + 36: 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 37: 'GL2A_PERF_SEL_RTN_STALL_GL2C2', + 38: 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 39: 'GL2A_PERF_SEL_RTN_STALL_GL2C4', + 40: 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 41: 'GL2A_PERF_SEL_RTN_STALL_GL2C6', + 42: 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 43: 'GL2A_PERF_SEL_RTN_CLIENT0', + 44: 'GL2A_PERF_SEL_RTN_CLIENT1', + 45: 'GL2A_PERF_SEL_RTN_CLIENT2', + 46: 'GL2A_PERF_SEL_RTN_CLIENT3', + 47: 'GL2A_PERF_SEL_RTN_CLIENT4', + 48: 'GL2A_PERF_SEL_RTN_CLIENT5', + 49: 'GL2A_PERF_SEL_RTN_CLIENT6', + 50: 'GL2A_PERF_SEL_RTN_CLIENT7', + 51: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 52: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 53: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 54: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 55: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 56: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 57: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 58: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', +} +GL2A_PERF_SEL_NONE = 0 +GL2A_PERF_SEL_CYCLE = 1 +GL2A_PERF_SEL_BUSY = 2 +GL2A_PERF_SEL_REQ_GL2C0 = 3 +GL2A_PERF_SEL_REQ_GL2C1 = 4 +GL2A_PERF_SEL_REQ_GL2C2 = 5 +GL2A_PERF_SEL_REQ_GL2C3 = 6 +GL2A_PERF_SEL_REQ_GL2C4 = 7 +GL2A_PERF_SEL_REQ_GL2C5 = 8 +GL2A_PERF_SEL_REQ_GL2C6 = 9 +GL2A_PERF_SEL_REQ_GL2C7 = 10 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0 = 11 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1 = 12 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2 = 13 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3 = 14 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4 = 15 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5 = 16 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6 = 17 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7 = 18 +GL2A_PERF_SEL_REQ_BURST_GL2C0 = 19 +GL2A_PERF_SEL_REQ_BURST_GL2C1 = 20 +GL2A_PERF_SEL_REQ_BURST_GL2C2 = 21 +GL2A_PERF_SEL_REQ_BURST_GL2C3 = 22 +GL2A_PERF_SEL_REQ_BURST_GL2C4 = 23 +GL2A_PERF_SEL_REQ_BURST_GL2C5 = 24 +GL2A_PERF_SEL_REQ_BURST_GL2C6 = 25 +GL2A_PERF_SEL_REQ_BURST_GL2C7 = 26 +GL2A_PERF_SEL_REQ_STALL_GL2C0 = 27 +GL2A_PERF_SEL_REQ_STALL_GL2C1 = 28 +GL2A_PERF_SEL_REQ_STALL_GL2C2 = 29 +GL2A_PERF_SEL_REQ_STALL_GL2C3 = 30 +GL2A_PERF_SEL_REQ_STALL_GL2C4 = 31 +GL2A_PERF_SEL_REQ_STALL_GL2C5 = 32 +GL2A_PERF_SEL_REQ_STALL_GL2C6 = 33 +GL2A_PERF_SEL_REQ_STALL_GL2C7 = 34 +GL2A_PERF_SEL_RTN_STALL_GL2C0 = 35 +GL2A_PERF_SEL_RTN_STALL_GL2C1 = 36 +GL2A_PERF_SEL_RTN_STALL_GL2C2 = 37 +GL2A_PERF_SEL_RTN_STALL_GL2C3 = 38 +GL2A_PERF_SEL_RTN_STALL_GL2C4 = 39 +GL2A_PERF_SEL_RTN_STALL_GL2C5 = 40 +GL2A_PERF_SEL_RTN_STALL_GL2C6 = 41 +GL2A_PERF_SEL_RTN_STALL_GL2C7 = 42 +GL2A_PERF_SEL_RTN_CLIENT0 = 43 +GL2A_PERF_SEL_RTN_CLIENT1 = 44 +GL2A_PERF_SEL_RTN_CLIENT2 = 45 +GL2A_PERF_SEL_RTN_CLIENT3 = 46 +GL2A_PERF_SEL_RTN_CLIENT4 = 47 +GL2A_PERF_SEL_RTN_CLIENT5 = 48 +GL2A_PERF_SEL_RTN_CLIENT6 = 49 +GL2A_PERF_SEL_RTN_CLIENT7 = 50 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0 = 51 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1 = 52 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2 = 53 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3 = 54 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4 = 55 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5 = 56 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6 = 57 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7 = 58 +GL2A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_PERF_SEL' +GRBM_PERF_SEL__enumvalues = { + 0: 'GRBM_PERF_SEL_COUNT', + 1: 'GRBM_PERF_SEL_USER_DEFINED', + 2: 'GRBM_PERF_SEL_GUI_ACTIVE', + 3: 'GRBM_PERF_SEL_CP_BUSY', + 4: 'GRBM_PERF_SEL_CP_COHER_BUSY', + 5: 'GRBM_PERF_SEL_CP_DMA_BUSY', + 6: 'GRBM_PERF_SEL_CB_BUSY', + 7: 'GRBM_PERF_SEL_DB_BUSY', + 8: 'GRBM_PERF_SEL_PA_BUSY', + 9: 'GRBM_PERF_SEL_SC_BUSY', + 10: 'GRBM_PERF_SEL_RESERVED_6', + 11: 'GRBM_PERF_SEL_SPI_BUSY', + 12: 'GRBM_PERF_SEL_SX_BUSY', + 13: 'GRBM_PERF_SEL_TA_BUSY', + 14: 'GRBM_PERF_SEL_CB_CLEAN', + 15: 'GRBM_PERF_SEL_DB_CLEAN', + 16: 'GRBM_PERF_SEL_RESERVED_5', + 17: 'GRBM_PERF_SEL_RESERVED_9', + 18: 'GRBM_PERF_SEL_RESERVED_4', + 19: 'GRBM_PERF_SEL_RESERVED_3', + 20: 'GRBM_PERF_SEL_RESERVED_2', + 21: 'GRBM_PERF_SEL_RESERVED_1', + 22: 'GRBM_PERF_SEL_RESERVED_0', + 23: 'GRBM_PERF_SEL_RESERVED_8', + 24: 'GRBM_PERF_SEL_RESERVED_7', + 25: 'GRBM_PERF_SEL_GDS_BUSY', + 26: 'GRBM_PERF_SEL_BCI_BUSY', + 27: 'GRBM_PERF_SEL_RLC_BUSY', + 28: 'GRBM_PERF_SEL_TCP_BUSY', + 29: 'GRBM_PERF_SEL_CPG_BUSY', + 30: 'GRBM_PERF_SEL_CPC_BUSY', + 31: 'GRBM_PERF_SEL_CPF_BUSY', + 32: 'GRBM_PERF_SEL_GE_BUSY', + 33: 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', + 34: 'GRBM_PERF_SEL_UTCL2_BUSY', + 35: 'GRBM_PERF_SEL_EA_BUSY', + 36: 'GRBM_PERF_SEL_RMI_BUSY', + 37: 'GRBM_PERF_SEL_CPAXI_BUSY', + 39: 'GRBM_PERF_SEL_UTCL1_BUSY', + 40: 'GRBM_PERF_SEL_GL2CC_BUSY', + 41: 'GRBM_PERF_SEL_SDMA_BUSY', + 42: 'GRBM_PERF_SEL_CH_BUSY', + 43: 'GRBM_PERF_SEL_PH_BUSY', + 44: 'GRBM_PERF_SEL_PMM_BUSY', + 45: 'GRBM_PERF_SEL_GUS_BUSY', + 46: 'GRBM_PERF_SEL_GL1CC_BUSY', +} +GRBM_PERF_SEL_COUNT = 0 +GRBM_PERF_SEL_USER_DEFINED = 1 +GRBM_PERF_SEL_GUI_ACTIVE = 2 +GRBM_PERF_SEL_CP_BUSY = 3 +GRBM_PERF_SEL_CP_COHER_BUSY = 4 +GRBM_PERF_SEL_CP_DMA_BUSY = 5 +GRBM_PERF_SEL_CB_BUSY = 6 +GRBM_PERF_SEL_DB_BUSY = 7 +GRBM_PERF_SEL_PA_BUSY = 8 +GRBM_PERF_SEL_SC_BUSY = 9 +GRBM_PERF_SEL_RESERVED_6 = 10 +GRBM_PERF_SEL_SPI_BUSY = 11 +GRBM_PERF_SEL_SX_BUSY = 12 +GRBM_PERF_SEL_TA_BUSY = 13 +GRBM_PERF_SEL_CB_CLEAN = 14 +GRBM_PERF_SEL_DB_CLEAN = 15 +GRBM_PERF_SEL_RESERVED_5 = 16 +GRBM_PERF_SEL_RESERVED_9 = 17 +GRBM_PERF_SEL_RESERVED_4 = 18 +GRBM_PERF_SEL_RESERVED_3 = 19 +GRBM_PERF_SEL_RESERVED_2 = 20 +GRBM_PERF_SEL_RESERVED_1 = 21 +GRBM_PERF_SEL_RESERVED_0 = 22 +GRBM_PERF_SEL_RESERVED_8 = 23 +GRBM_PERF_SEL_RESERVED_7 = 24 +GRBM_PERF_SEL_GDS_BUSY = 25 +GRBM_PERF_SEL_BCI_BUSY = 26 +GRBM_PERF_SEL_RLC_BUSY = 27 +GRBM_PERF_SEL_TCP_BUSY = 28 +GRBM_PERF_SEL_CPG_BUSY = 29 +GRBM_PERF_SEL_CPC_BUSY = 30 +GRBM_PERF_SEL_CPF_BUSY = 31 +GRBM_PERF_SEL_GE_BUSY = 32 +GRBM_PERF_SEL_GE_NO_DMA_BUSY = 33 +GRBM_PERF_SEL_UTCL2_BUSY = 34 +GRBM_PERF_SEL_EA_BUSY = 35 +GRBM_PERF_SEL_RMI_BUSY = 36 +GRBM_PERF_SEL_CPAXI_BUSY = 37 +GRBM_PERF_SEL_UTCL1_BUSY = 39 +GRBM_PERF_SEL_GL2CC_BUSY = 40 +GRBM_PERF_SEL_SDMA_BUSY = 41 +GRBM_PERF_SEL_CH_BUSY = 42 +GRBM_PERF_SEL_PH_BUSY = 43 +GRBM_PERF_SEL_PMM_BUSY = 44 +GRBM_PERF_SEL_GUS_BUSY = 45 +GRBM_PERF_SEL_GL1CC_BUSY = 46 +GRBM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE0_PERF_SEL' +GRBM_SE0_PERF_SEL__enumvalues = { + 0: 'GRBM_SE0_PERF_SEL_COUNT', + 1: 'GRBM_SE0_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE0_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE0_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE0_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE0_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE0_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE0_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE0_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE0_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE0_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE0_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE0_PERF_SEL_RESERVED_2', + 14: 'GRBM_SE0_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE0_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE0_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE0_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE0_PERF_SEL_GL1CC_BUSY', +} +GRBM_SE0_PERF_SEL_COUNT = 0 +GRBM_SE0_PERF_SEL_USER_DEFINED = 1 +GRBM_SE0_PERF_SEL_CB_BUSY = 2 +GRBM_SE0_PERF_SEL_DB_BUSY = 3 +GRBM_SE0_PERF_SEL_SC_BUSY = 4 +GRBM_SE0_PERF_SEL_RESERVED_1 = 5 +GRBM_SE0_PERF_SEL_SPI_BUSY = 6 +GRBM_SE0_PERF_SEL_SX_BUSY = 7 +GRBM_SE0_PERF_SEL_TA_BUSY = 8 +GRBM_SE0_PERF_SEL_CB_CLEAN = 9 +GRBM_SE0_PERF_SEL_DB_CLEAN = 10 +GRBM_SE0_PERF_SEL_RESERVED_0 = 11 +GRBM_SE0_PERF_SEL_PA_BUSY = 12 +GRBM_SE0_PERF_SEL_RESERVED_2 = 13 +GRBM_SE0_PERF_SEL_BCI_BUSY = 14 +GRBM_SE0_PERF_SEL_RMI_BUSY = 15 +GRBM_SE0_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE0_PERF_SEL_TCP_BUSY = 17 +GRBM_SE0_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE0_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE1_PERF_SEL' +GRBM_SE1_PERF_SEL__enumvalues = { + 0: 'GRBM_SE1_PERF_SEL_COUNT', + 1: 'GRBM_SE1_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE1_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE1_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE1_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE1_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE1_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE1_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE1_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE1_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE1_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE1_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE1_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE1_PERF_SEL_RESERVED_2', + 14: 'GRBM_SE1_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE1_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE1_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE1_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE1_PERF_SEL_GL1CC_BUSY', +} +GRBM_SE1_PERF_SEL_COUNT = 0 +GRBM_SE1_PERF_SEL_USER_DEFINED = 1 +GRBM_SE1_PERF_SEL_CB_BUSY = 2 +GRBM_SE1_PERF_SEL_DB_BUSY = 3 +GRBM_SE1_PERF_SEL_SC_BUSY = 4 +GRBM_SE1_PERF_SEL_RESERVED_1 = 5 +GRBM_SE1_PERF_SEL_SPI_BUSY = 6 +GRBM_SE1_PERF_SEL_SX_BUSY = 7 +GRBM_SE1_PERF_SEL_TA_BUSY = 8 +GRBM_SE1_PERF_SEL_CB_CLEAN = 9 +GRBM_SE1_PERF_SEL_DB_CLEAN = 10 +GRBM_SE1_PERF_SEL_RESERVED_0 = 11 +GRBM_SE1_PERF_SEL_PA_BUSY = 12 +GRBM_SE1_PERF_SEL_RESERVED_2 = 13 +GRBM_SE1_PERF_SEL_BCI_BUSY = 14 +GRBM_SE1_PERF_SEL_RMI_BUSY = 15 +GRBM_SE1_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE1_PERF_SEL_TCP_BUSY = 17 +GRBM_SE1_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE1_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE2_PERF_SEL' +GRBM_SE2_PERF_SEL__enumvalues = { + 0: 'GRBM_SE2_PERF_SEL_COUNT', + 1: 'GRBM_SE2_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE2_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE2_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE2_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE2_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE2_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE2_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE2_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE2_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE2_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE2_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE2_PERF_SEL_RESERVED_2', + 14: 'GRBM_SE2_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE2_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE2_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE2_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE2_PERF_SEL_GL1CC_BUSY', +} +GRBM_SE2_PERF_SEL_COUNT = 0 +GRBM_SE2_PERF_SEL_USER_DEFINED = 1 +GRBM_SE2_PERF_SEL_CB_BUSY = 2 +GRBM_SE2_PERF_SEL_DB_BUSY = 3 +GRBM_SE2_PERF_SEL_SC_BUSY = 4 +GRBM_SE2_PERF_SEL_RESERVED_1 = 5 +GRBM_SE2_PERF_SEL_SPI_BUSY = 6 +GRBM_SE2_PERF_SEL_SX_BUSY = 7 +GRBM_SE2_PERF_SEL_TA_BUSY = 8 +GRBM_SE2_PERF_SEL_CB_CLEAN = 9 +GRBM_SE2_PERF_SEL_DB_CLEAN = 10 +GRBM_SE2_PERF_SEL_RESERVED_0 = 11 +GRBM_SE2_PERF_SEL_PA_BUSY = 12 +GRBM_SE2_PERF_SEL_RESERVED_2 = 13 +GRBM_SE2_PERF_SEL_BCI_BUSY = 14 +GRBM_SE2_PERF_SEL_RMI_BUSY = 15 +GRBM_SE2_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE2_PERF_SEL_TCP_BUSY = 17 +GRBM_SE2_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE2_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE3_PERF_SEL' +GRBM_SE3_PERF_SEL__enumvalues = { + 0: 'GRBM_SE3_PERF_SEL_COUNT', + 1: 'GRBM_SE3_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE3_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE3_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE3_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE3_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE3_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE3_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE3_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE3_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE3_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE3_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE3_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE3_PERF_SEL_RESERVED_2', + 14: 'GRBM_SE3_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE3_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE3_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE3_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE3_PERF_SEL_GL1CC_BUSY', +} +GRBM_SE3_PERF_SEL_COUNT = 0 +GRBM_SE3_PERF_SEL_USER_DEFINED = 1 +GRBM_SE3_PERF_SEL_CB_BUSY = 2 +GRBM_SE3_PERF_SEL_DB_BUSY = 3 +GRBM_SE3_PERF_SEL_SC_BUSY = 4 +GRBM_SE3_PERF_SEL_RESERVED_1 = 5 +GRBM_SE3_PERF_SEL_SPI_BUSY = 6 +GRBM_SE3_PERF_SEL_SX_BUSY = 7 +GRBM_SE3_PERF_SEL_TA_BUSY = 8 +GRBM_SE3_PERF_SEL_CB_CLEAN = 9 +GRBM_SE3_PERF_SEL_DB_CLEAN = 10 +GRBM_SE3_PERF_SEL_RESERVED_0 = 11 +GRBM_SE3_PERF_SEL_PA_BUSY = 12 +GRBM_SE3_PERF_SEL_RESERVED_2 = 13 +GRBM_SE3_PERF_SEL_BCI_BUSY = 14 +GRBM_SE3_PERF_SEL_RMI_BUSY = 15 +GRBM_SE3_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE3_PERF_SEL_TCP_BUSY = 17 +GRBM_SE3_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE3_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_RING_ID' +CP_RING_ID__enumvalues = { + 0: 'RINGID0', + 1: 'RINGID1', + 2: 'RINGID2', + 3: 'RINGID3', +} +RINGID0 = 0 +RINGID1 = 1 +RINGID2 = 2 +RINGID3 = 3 +CP_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PIPE_ID' +CP_PIPE_ID__enumvalues = { + 0: 'PIPE_ID0', + 1: 'PIPE_ID1', + 2: 'PIPE_ID2', + 3: 'PIPE_ID3', +} +PIPE_ID0 = 0 +PIPE_ID1 = 1 +PIPE_ID2 = 2 +PIPE_ID3 = 3 +CP_PIPE_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ME_ID' +CP_ME_ID__enumvalues = { + 0: 'ME_ID0', + 1: 'ME_ID1', + 2: 'ME_ID2', + 3: 'ME_ID3', +} +ME_ID0 = 0 +ME_ID1 = 1 +ME_ID2 = 2 +ME_ID3 = 3 +CP_ME_ID = ctypes.c_uint32 # enum + +# values for enumeration 'SPM_PERFMON_STATE' +SPM_PERFMON_STATE__enumvalues = { + 0: 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'STRM_PERFMON_STATE_START_COUNTING', + 2: 'STRM_PERFMON_STATE_STOP_COUNTING', + 3: 'STRM_PERFMON_STATE_RESERVED_3', + 4: 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +STRM_PERFMON_STATE_DISABLE_AND_RESET = 0 +STRM_PERFMON_STATE_START_COUNTING = 1 +STRM_PERFMON_STATE_STOP_COUNTING = 2 +STRM_PERFMON_STATE_RESERVED_3 = 3 +STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +SPM_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_STATE' +CP_PERFMON_STATE__enumvalues = { + 0: 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'CP_PERFMON_STATE_START_COUNTING', + 2: 'CP_PERFMON_STATE_STOP_COUNTING', + 3: 'CP_PERFMON_STATE_RESERVED_3', + 4: 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +CP_PERFMON_STATE_DISABLE_AND_RESET = 0 +CP_PERFMON_STATE_START_COUNTING = 1 +CP_PERFMON_STATE_STOP_COUNTING = 2 +CP_PERFMON_STATE_RESERVED_3 = 3 +CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +CP_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_ENABLE_MODE' +CP_PERFMON_ENABLE_MODE__enumvalues = { + 0: 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 1: 'CP_PERFMON_ENABLE_MODE_RESERVED_1', + 2: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 3: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', +} +CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT = 0 +CP_PERFMON_ENABLE_MODE_RESERVED_1 = 1 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE = 2 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE = 3 +CP_PERFMON_ENABLE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNT_SEL' +CPG_PERFCOUNT_SEL__enumvalues = { + 0: 'CPG_PERF_SEL_ALWAYS_COUNT', + 1: 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 2: 'CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR', + 3: 'CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL', + 4: 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 5: 'CPG_PERF_SEL_ME_PARSER_BUSY', + 6: 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 7: 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', + 8: 'CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 9: 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 10: 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 11: 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 12: 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 13: 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 14: 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 15: 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 16: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 17: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 18: 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 19: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 20: 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 21: 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 22: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 23: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 24: 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 25: 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 26: 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 27: 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 28: 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 29: 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 30: 'CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS', + 31: 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 32: 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 33: 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 34: 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 35: 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 36: 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 37: 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 38: 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 39: 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 40: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU', + 41: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 42: 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 43: 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 44: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 45: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 46: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 47: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 48: 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 49: 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 50: 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 51: 'CPG_PERF_SEL_CPG_STAT_BUSY', + 52: 'CPG_PERF_SEL_CPG_STAT_IDLE', + 53: 'CPG_PERF_SEL_CPG_STAT_STALL', + 54: 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 55: 'CPG_PERF_SEL_CPG_TCIU_IDLE', + 56: 'CPF_PERF_SEL_CPG_TCIU_STALL', + 57: 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', + 58: 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', + 59: 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', + 60: 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 61: 'CPG_PERF_SEL_CPG_GCRIU_IDLE', + 62: 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 63: 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 64: 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', + 65: 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', + 66: 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 67: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 68: 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 69: 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 70: 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 71: 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 72: 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 73: 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', + 74: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 75: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 76: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 77: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', +} +CPG_PERF_SEL_ALWAYS_COUNT = 0 +CPG_PERF_SEL_RBIU_FIFO_FULL = 1 +CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR = 2 +CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL = 3 +CPG_PERF_SEL_CP_GRBM_DWORDS_SENT = 4 +CPG_PERF_SEL_ME_PARSER_BUSY = 5 +CPG_PERF_SEL_COUNT_TYPE0_PACKETS = 6 +CPG_PERF_SEL_COUNT_TYPE3_PACKETS = 7 +CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 8 +CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS = 9 +CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS = 10 +CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS = 11 +CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ = 12 +CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ = 13 +CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX = 14 +CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS = 15 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE = 16 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM = 17 +CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY = 18 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY = 19 +CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY = 20 +CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ = 21 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP = 22 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ = 23 +CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX = 24 +CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU = 25 +CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS = 26 +CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH = 27 +CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER = 28 +CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER = 29 +CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS = 30 +CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY = 31 +CPG_PERF_SEL_DYNAMIC_CLK_VALID = 32 +CPG_PERF_SEL_REGISTER_CLK_VALID = 33 +CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT = 34 +CPG_PERF_SEL_GUS_READ_REQUEST_SENT = 35 +CPG_PERF_SEL_CE_STALL_RAM_DUMP = 36 +CPG_PERF_SEL_CE_STALL_RAM_WRITE = 37 +CPG_PERF_SEL_CE_STALL_ON_INC_FIFO = 38 +CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO = 39 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU = 40 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ = 41 +CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG = 42 +CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER = 43 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 44 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS = 45 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 46 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 47 +CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 48 +CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 49 +CPG_PERF_SEL_TCIU_READ_REQUEST_SENT = 50 +CPG_PERF_SEL_CPG_STAT_BUSY = 51 +CPG_PERF_SEL_CPG_STAT_IDLE = 52 +CPG_PERF_SEL_CPG_STAT_STALL = 53 +CPG_PERF_SEL_CPG_TCIU_BUSY = 54 +CPG_PERF_SEL_CPG_TCIU_IDLE = 55 +CPF_PERF_SEL_CPG_TCIU_STALL = 56 +CPG_PERF_SEL_CPG_UTCL2IU_BUSY = 57 +CPG_PERF_SEL_CPG_UTCL2IU_IDLE = 58 +CPG_PERF_SEL_CPG_UTCL2IU_STALL = 59 +CPG_PERF_SEL_CPG_GCRIU_BUSY = 60 +CPG_PERF_SEL_CPG_GCRIU_IDLE = 61 +CPG_PERF_SEL_CPG_GCRIU_STALL = 62 +CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 63 +CPG_PERF_SEL_ALL_GFX_PIPES_BUSY = 64 +CPG_PERF_SEL_CPG_UTCL2IU_XACK = 65 +CPG_PERF_SEL_CPG_UTCL2IU_XNACK = 66 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY = 67 +CPG_PERF_SEL_PFP_INSTR_CACHE_HIT = 68 +CPG_PERF_SEL_PFP_INSTR_CACHE_MISS = 69 +CPG_PERF_SEL_CE_INSTR_CACHE_HIT = 70 +CPG_PERF_SEL_CE_INSTR_CACHE_MISS = 71 +CPG_PERF_SEL_ME_INSTR_CACHE_HIT = 72 +CPG_PERF_SEL_ME_INSTR_CACHE_MISS = 73 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1 = 74 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1 = 75 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2 = 76 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2 = 77 +CPG_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNT_SEL' +CPF_PERFCOUNT_SEL__enumvalues = { + 0: 'CPF_PERF_SEL_ALWAYS_COUNT', + 1: 'CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE', + 2: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 3: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 4: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 5: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 6: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 7: 'CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE', + 8: 'CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS', + 9: 'CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR', + 10: 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 11: 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 12: 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 13: 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 14: 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 15: 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SEND', + 16: 'CPF_PERF_SEL_GUS_READ_REQUEST_SEND', + 17: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 18: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 19: 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 20: 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 21: 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 22: 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 23: 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 24: 'CPF_PERF_SEL_CPF_STAT_BUSY', + 25: 'CPF_PERF_SEL_CPF_STAT_IDLE', + 26: 'CPF_PERF_SEL_CPF_STAT_STALL', + 27: 'CPF_PERF_SEL_CPF_TCIU_BUSY', + 28: 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 29: 'CPF_PERF_SEL_CPF_TCIU_STALL', + 30: 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 31: 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', + 32: 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 33: 'CPF_PERF_SEL_CPF_GCRIU_BUSY', + 34: 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 35: 'CPF_PERF_SEL_CPF_GCRIU_STALL', + 36: 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 37: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 38: 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', + 39: 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', +} +CPF_PERF_SEL_ALWAYS_COUNT = 0 +CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE = 1 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE = 2 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS = 3 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING = 4 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1 = 5 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2 = 6 +CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE = 7 +CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS = 8 +CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR = 9 +CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR = 10 +CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 11 +CPF_PERF_SEL_GRBM_DWORDS_SENT = 12 +CPF_PERF_SEL_DYNAMIC_CLOCK_VALID = 13 +CPF_PERF_SEL_REGISTER_CLOCK_VALID = 14 +CPF_PERF_SEL_GUS_WRITE_REQUEST_SEND = 15 +CPF_PERF_SEL_GUS_READ_REQUEST_SEND = 16 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 17 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 18 +CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION = 19 +CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION = 20 +CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 21 +CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 22 +CPF_PERF_SEL_TCIU_READ_REQUEST_SENT = 23 +CPF_PERF_SEL_CPF_STAT_BUSY = 24 +CPF_PERF_SEL_CPF_STAT_IDLE = 25 +CPF_PERF_SEL_CPF_STAT_STALL = 26 +CPF_PERF_SEL_CPF_TCIU_BUSY = 27 +CPF_PERF_SEL_CPF_TCIU_IDLE = 28 +CPF_PERF_SEL_CPF_TCIU_STALL = 29 +CPF_PERF_SEL_CPF_UTCL2IU_BUSY = 30 +CPF_PERF_SEL_CPF_UTCL2IU_IDLE = 31 +CPF_PERF_SEL_CPF_UTCL2IU_STALL = 32 +CPF_PERF_SEL_CPF_GCRIU_BUSY = 33 +CPF_PERF_SEL_CPF_GCRIU_IDLE = 34 +CPF_PERF_SEL_CPF_GCRIU_STALL = 35 +CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 36 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB = 37 +CPF_PERF_SEL_CPF_UTCL2IU_XACK = 38 +CPF_PERF_SEL_CPF_UTCL2IU_XNACK = 39 +CPF_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_PERFCOUNT_SEL' +CPC_PERFCOUNT_SEL__enumvalues = { + 0: 'CPC_PERF_SEL_ALWAYS_COUNT', + 1: 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 2: 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 3: 'CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE', + 4: 'CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE', + 5: 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 6: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 7: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 8: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 9: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ', + 10: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE', + 11: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 12: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 13: 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 14: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 15: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 16: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 17: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ', + 18: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE', + 19: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 20: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 21: 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 22: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 23: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 24: 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 25: 'CPC_PERF_SEL_CPC_STAT_BUSY', + 26: 'CPC_PERF_SEL_CPC_STAT_IDLE', + 27: 'CPC_PERF_SEL_CPC_STAT_STALL', + 28: 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 29: 'CPC_PERF_SEL_CPC_TCIU_IDLE', + 30: 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 31: 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', + 32: 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 33: 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 34: 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 35: 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 36: 'CPC_PERF_SEL_CPC_GCRIU_IDLE', + 37: 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 38: 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 39: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 40: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 41: 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', + 42: 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 43: 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 44: 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', +} +CPC_PERF_SEL_ALWAYS_COUNT = 0 +CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 1 +CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION = 2 +CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE = 3 +CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE = 4 +CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 5 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY = 6 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF = 7 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ = 8 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ = 9 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE = 10 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ = 11 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF = 12 +CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE = 13 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY = 14 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF = 15 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ = 16 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ = 17 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE = 18 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ = 19 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF = 20 +CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE = 21 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 22 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 23 +CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 24 +CPC_PERF_SEL_CPC_STAT_BUSY = 25 +CPC_PERF_SEL_CPC_STAT_IDLE = 26 +CPC_PERF_SEL_CPC_STAT_STALL = 27 +CPC_PERF_SEL_CPC_TCIU_BUSY = 28 +CPC_PERF_SEL_CPC_TCIU_IDLE = 29 +CPC_PERF_SEL_CPC_UTCL2IU_BUSY = 30 +CPC_PERF_SEL_CPC_UTCL2IU_IDLE = 31 +CPC_PERF_SEL_CPC_UTCL2IU_STALL = 32 +CPC_PERF_SEL_ME1_DC0_SPI_BUSY = 33 +CPC_PERF_SEL_ME2_DC1_SPI_BUSY = 34 +CPC_PERF_SEL_CPC_GCRIU_BUSY = 35 +CPC_PERF_SEL_CPC_GCRIU_IDLE = 36 +CPC_PERF_SEL_CPC_GCRIU_STALL = 37 +CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 38 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ = 39 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ = 40 +CPC_PERF_SEL_CPC_UTCL2IU_XACK = 41 +CPC_PERF_SEL_CPC_UTCL2IU_XNACK = 42 +CPC_PERF_SEL_MEC_INSTR_CACHE_HIT = 43 +CPC_PERF_SEL_MEC_INSTR_CACHE_MISS = 44 +CPC_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ALPHA_TAG_RAM_SEL' +CP_ALPHA_TAG_RAM_SEL__enumvalues = { + 0: 'CPG_TAG_RAM', + 1: 'CPC_TAG_RAM', + 2: 'CPF_TAG_RAM', + 3: 'RSV_TAG_RAM', +} +CPG_TAG_RAM = 0 +CPC_TAG_RAM = 1 +CPF_TAG_RAM = 2 +RSV_TAG_RAM = 3 +CP_ALPHA_TAG_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNTWINDOW_SEL' +CPF_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPF_PERFWINDOW_SEL_CSF', + 1: 'CPF_PERFWINDOW_SEL_HQD1', + 2: 'CPF_PERFWINDOW_SEL_HQD2', + 3: 'CPF_PERFWINDOW_SEL_RDMA', + 4: 'CPF_PERFWINDOW_SEL_RWPP', +} +CPF_PERFWINDOW_SEL_CSF = 0 +CPF_PERFWINDOW_SEL_HQD1 = 1 +CPF_PERFWINDOW_SEL_HQD2 = 2 +CPF_PERFWINDOW_SEL_RDMA = 3 +CPF_PERFWINDOW_SEL_RWPP = 4 +CPF_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNTWINDOW_SEL' +CPG_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPG_PERFWINDOW_SEL_PFP', + 1: 'CPG_PERFWINDOW_SEL_ME', + 2: 'CPG_PERFWINDOW_SEL_CE', + 3: 'CPG_PERFWINDOW_SEL_MES', + 4: 'CPG_PERFWINDOW_SEL_MEC1', + 5: 'CPG_PERFWINDOW_SEL_MEC2', + 6: 'CPG_PERFWINDOW_SEL_DFY', + 7: 'CPG_PERFWINDOW_SEL_DMA', + 8: 'CPG_PERFWINDOW_SEL_SHADOW', + 9: 'CPG_PERFWINDOW_SEL_RB', + 10: 'CPG_PERFWINDOW_SEL_CEDMA', + 11: 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 12: 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', + 13: 'CPG_PERFWINDOW_SEL_PQ1', + 14: 'CPG_PERFWINDOW_SEL_PQ2', + 15: 'CPG_PERFWINDOW_SEL_PQ3', + 16: 'CPG_PERFWINDOW_SEL_MEMWR', + 17: 'CPG_PERFWINDOW_SEL_MEMRD', + 18: 'CPG_PERFWINDOW_SEL_VGT0', + 19: 'CPG_PERFWINDOW_SEL_VGT1', + 20: 'CPG_PERFWINDOW_SEL_APPEND', + 21: 'CPG_PERFWINDOW_SEL_QURD', + 22: 'CPG_PERFWINDOW_SEL_DDID', + 23: 'CPG_PERFWINDOW_SEL_SR', + 24: 'CPG_PERFWINDOW_SEL_QU_EOP', + 25: 'CPG_PERFWINDOW_SEL_QU_STRM', + 26: 'CPG_PERFWINDOW_SEL_QU_PIPE', + 27: 'CPG_PERFWINDOW_SEL_RESERVED1', + 28: 'CPG_PERFWINDOW_SEL_CPC_IC', + 29: 'CPG_PERFWINDOW_SEL_RESERVED2', + 30: 'CPG_PERFWINDOW_SEL_CPG_IC', +} +CPG_PERFWINDOW_SEL_PFP = 0 +CPG_PERFWINDOW_SEL_ME = 1 +CPG_PERFWINDOW_SEL_CE = 2 +CPG_PERFWINDOW_SEL_MES = 3 +CPG_PERFWINDOW_SEL_MEC1 = 4 +CPG_PERFWINDOW_SEL_MEC2 = 5 +CPG_PERFWINDOW_SEL_DFY = 6 +CPG_PERFWINDOW_SEL_DMA = 7 +CPG_PERFWINDOW_SEL_SHADOW = 8 +CPG_PERFWINDOW_SEL_RB = 9 +CPG_PERFWINDOW_SEL_CEDMA = 10 +CPG_PERFWINDOW_SEL_PRT_HDR_RPTR = 11 +CPG_PERFWINDOW_SEL_PRT_SMP_RPTR = 12 +CPG_PERFWINDOW_SEL_PQ1 = 13 +CPG_PERFWINDOW_SEL_PQ2 = 14 +CPG_PERFWINDOW_SEL_PQ3 = 15 +CPG_PERFWINDOW_SEL_MEMWR = 16 +CPG_PERFWINDOW_SEL_MEMRD = 17 +CPG_PERFWINDOW_SEL_VGT0 = 18 +CPG_PERFWINDOW_SEL_VGT1 = 19 +CPG_PERFWINDOW_SEL_APPEND = 20 +CPG_PERFWINDOW_SEL_QURD = 21 +CPG_PERFWINDOW_SEL_DDID = 22 +CPG_PERFWINDOW_SEL_SR = 23 +CPG_PERFWINDOW_SEL_QU_EOP = 24 +CPG_PERFWINDOW_SEL_QU_STRM = 25 +CPG_PERFWINDOW_SEL_QU_PIPE = 26 +CPG_PERFWINDOW_SEL_RESERVED1 = 27 +CPG_PERFWINDOW_SEL_CPC_IC = 28 +CPG_PERFWINDOW_SEL_RESERVED2 = 29 +CPG_PERFWINDOW_SEL_CPG_IC = 30 +CPG_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_LATENCY_STATS_SEL' +CPF_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPF_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPF_LATENCY_STATS_SEL_READ_MAX', + 7: 'CPF_LATENCY_STATS_SEL_READ_MIN', + 8: 'CPF_LATENCY_STATS_SEL_READ_LAST', + 9: 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 10: 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 11: 'CPF_LATENCY_STATS_SEL_INVAL_LAST', +} +CPF_LATENCY_STATS_SEL_XACK_MAX = 0 +CPF_LATENCY_STATS_SEL_XACK_MIN = 1 +CPF_LATENCY_STATS_SEL_XACK_LAST = 2 +CPF_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPF_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPF_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPF_LATENCY_STATS_SEL_READ_MAX = 6 +CPF_LATENCY_STATS_SEL_READ_MIN = 7 +CPF_LATENCY_STATS_SEL_READ_LAST = 8 +CPF_LATENCY_STATS_SEL_INVAL_MAX = 9 +CPF_LATENCY_STATS_SEL_INVAL_MIN = 10 +CPF_LATENCY_STATS_SEL_INVAL_LAST = 11 +CPF_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_LATENCY_STATS_SEL' +CPG_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPG_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 7: 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 8: 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 9: 'CPG_LATENCY_STATS_SEL_READ_MAX', + 10: 'CPG_LATENCY_STATS_SEL_READ_MIN', + 11: 'CPG_LATENCY_STATS_SEL_READ_LAST', + 12: 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 13: 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 14: 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 15: 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 16: 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 17: 'CPG_LATENCY_STATS_SEL_INVAL_LAST', +} +CPG_LATENCY_STATS_SEL_XACK_MAX = 0 +CPG_LATENCY_STATS_SEL_XACK_MIN = 1 +CPG_LATENCY_STATS_SEL_XACK_LAST = 2 +CPG_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPG_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPG_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPG_LATENCY_STATS_SEL_WRITE_MAX = 6 +CPG_LATENCY_STATS_SEL_WRITE_MIN = 7 +CPG_LATENCY_STATS_SEL_WRITE_LAST = 8 +CPG_LATENCY_STATS_SEL_READ_MAX = 9 +CPG_LATENCY_STATS_SEL_READ_MIN = 10 +CPG_LATENCY_STATS_SEL_READ_LAST = 11 +CPG_LATENCY_STATS_SEL_ATOMIC_MAX = 12 +CPG_LATENCY_STATS_SEL_ATOMIC_MIN = 13 +CPG_LATENCY_STATS_SEL_ATOMIC_LAST = 14 +CPG_LATENCY_STATS_SEL_INVAL_MAX = 15 +CPG_LATENCY_STATS_SEL_INVAL_MIN = 16 +CPG_LATENCY_STATS_SEL_INVAL_LAST = 17 +CPG_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_LATENCY_STATS_SEL' +CPC_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPC_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 7: 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 8: 'CPC_LATENCY_STATS_SEL_INVAL_LAST', +} +CPC_LATENCY_STATS_SEL_XACK_MAX = 0 +CPC_LATENCY_STATS_SEL_XACK_MIN = 1 +CPC_LATENCY_STATS_SEL_XACK_LAST = 2 +CPC_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPC_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPC_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPC_LATENCY_STATS_SEL_INVAL_MAX = 6 +CPC_LATENCY_STATS_SEL_INVAL_MIN = 7 +CPC_LATENCY_STATS_SEL_INVAL_LAST = 8 +CPC_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_MODE' +CP_DDID_CNTL_MODE__enumvalues = { + 0: 'STALL', + 1: 'OVERRUN', +} +STALL = 0 +OVERRUN = 1 +CP_DDID_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_SIZE' +CP_DDID_CNTL_SIZE__enumvalues = { + 0: 'SIZE_8K', + 1: 'SIZE_16K', +} +SIZE_8K = 0 +SIZE_16K = 1 +CP_DDID_CNTL_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_VMID_SEL' +CP_DDID_CNTL_VMID_SEL__enumvalues = { + 0: 'DDID_VMID_PIPE', + 1: 'DDID_VMID_CNTL', +} +DDID_VMID_PIPE = 0 +DDID_VMID_CNTL = 1 +CP_DDID_CNTL_VMID_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SX_BLEND_OPT' +SX_BLEND_OPT__enumvalues = { + 0: 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 1: 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 2: 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 3: 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 4: 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 5: 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 6: 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 7: 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', +} +BLEND_OPT_PRESERVE_NONE_IGNORE_ALL = 0 +BLEND_OPT_PRESERVE_ALL_IGNORE_NONE = 1 +BLEND_OPT_PRESERVE_C1_IGNORE_C0 = 2 +BLEND_OPT_PRESERVE_C0_IGNORE_C1 = 3 +BLEND_OPT_PRESERVE_A1_IGNORE_A0 = 4 +BLEND_OPT_PRESERVE_A0_IGNORE_A1 = 5 +BLEND_OPT_PRESERVE_NONE_IGNORE_A0 = 6 +BLEND_OPT_PRESERVE_NONE_IGNORE_NONE = 7 +SX_BLEND_OPT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_OPT_COMB_FCN' +SX_OPT_COMB_FCN__enumvalues = { + 0: 'OPT_COMB_NONE', + 1: 'OPT_COMB_ADD', + 2: 'OPT_COMB_SUBTRACT', + 3: 'OPT_COMB_MIN', + 4: 'OPT_COMB_MAX', + 5: 'OPT_COMB_REVSUBTRACT', + 6: 'OPT_COMB_BLEND_DISABLED', + 7: 'OPT_COMB_SAFE_ADD', +} +OPT_COMB_NONE = 0 +OPT_COMB_ADD = 1 +OPT_COMB_SUBTRACT = 2 +OPT_COMB_MIN = 3 +OPT_COMB_MAX = 4 +OPT_COMB_REVSUBTRACT = 5 +OPT_COMB_BLEND_DISABLED = 6 +OPT_COMB_SAFE_ADD = 7 +SX_OPT_COMB_FCN = ctypes.c_uint32 # enum + +# values for enumeration 'SX_DOWNCONVERT_FORMAT' +SX_DOWNCONVERT_FORMAT__enumvalues = { + 0: 'SX_RT_EXPORT_NO_CONVERSION', + 1: 'SX_RT_EXPORT_32_R', + 2: 'SX_RT_EXPORT_32_A', + 3: 'SX_RT_EXPORT_10_11_11', + 4: 'SX_RT_EXPORT_2_10_10_10', + 5: 'SX_RT_EXPORT_8_8_8_8', + 6: 'SX_RT_EXPORT_5_6_5', + 7: 'SX_RT_EXPORT_1_5_5_5', + 8: 'SX_RT_EXPORT_4_4_4_4', + 9: 'SX_RT_EXPORT_16_16_GR', + 10: 'SX_RT_EXPORT_16_16_AR', +} +SX_RT_EXPORT_NO_CONVERSION = 0 +SX_RT_EXPORT_32_R = 1 +SX_RT_EXPORT_32_A = 2 +SX_RT_EXPORT_10_11_11 = 3 +SX_RT_EXPORT_2_10_10_10 = 4 +SX_RT_EXPORT_8_8_8_8 = 5 +SX_RT_EXPORT_5_6_5 = 6 +SX_RT_EXPORT_1_5_5_5 = 7 +SX_RT_EXPORT_4_4_4_4 = 8 +SX_RT_EXPORT_16_16_GR = 9 +SX_RT_EXPORT_16_16_AR = 10 +SX_DOWNCONVERT_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_PERFCOUNTER_VALS' +SX_PERFCOUNTER_VALS__enumvalues = { + 0: 'SX_PERF_SEL_PA_IDLE_CYCLES', + 1: 'SX_PERF_SEL_PA_REQ', + 2: 'SX_PERF_SEL_PA_POS', + 3: 'SX_PERF_SEL_CLOCK', + 4: 'SX_PERF_SEL_GATE_EN1', + 5: 'SX_PERF_SEL_GATE_EN2', + 6: 'SX_PERF_SEL_GATE_EN3', + 7: 'SX_PERF_SEL_GATE_EN4', + 8: 'SX_PERF_SEL_SH_POS_STARVE', + 9: 'SX_PERF_SEL_SH_COLOR_STARVE', + 10: 'SX_PERF_SEL_SH_POS_STALL', + 11: 'SX_PERF_SEL_SH_COLOR_STALL', + 12: 'SX_PERF_SEL_DB0_PIXELS', + 13: 'SX_PERF_SEL_DB0_HALF_QUADS', + 14: 'SX_PERF_SEL_DB0_PIXEL_STALL', + 15: 'SX_PERF_SEL_DB0_PIXEL_IDLE', + 16: 'SX_PERF_SEL_DB0_PRED_PIXELS', + 17: 'SX_PERF_SEL_DB1_PIXELS', + 18: 'SX_PERF_SEL_DB1_HALF_QUADS', + 19: 'SX_PERF_SEL_DB1_PIXEL_STALL', + 20: 'SX_PERF_SEL_DB1_PIXEL_IDLE', + 21: 'SX_PERF_SEL_DB1_PRED_PIXELS', + 22: 'SX_PERF_SEL_DB2_PIXELS', + 23: 'SX_PERF_SEL_DB2_HALF_QUADS', + 24: 'SX_PERF_SEL_DB2_PIXEL_STALL', + 25: 'SX_PERF_SEL_DB2_PIXEL_IDLE', + 26: 'SX_PERF_SEL_DB2_PRED_PIXELS', + 27: 'SX_PERF_SEL_DB3_PIXELS', + 28: 'SX_PERF_SEL_DB3_HALF_QUADS', + 29: 'SX_PERF_SEL_DB3_PIXEL_STALL', + 30: 'SX_PERF_SEL_DB3_PIXEL_IDLE', + 31: 'SX_PERF_SEL_DB3_PRED_PIXELS', + 32: 'SX_PERF_SEL_COL_BUSY', + 33: 'SX_PERF_SEL_POS_BUSY', + 34: 'SX_PERF_SEL_DB0_A2M_DISCARD_QUADS', + 35: 'SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS', + 36: 'SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST', + 37: 'SX_PERF_SEL_DB0_MRT0_DISCARD_SRC', + 38: 'SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS', + 39: 'SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS', + 40: 'SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS', + 41: 'SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST', + 42: 'SX_PERF_SEL_DB0_MRT1_DISCARD_SRC', + 43: 'SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS', + 44: 'SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS', + 45: 'SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS', + 46: 'SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST', + 47: 'SX_PERF_SEL_DB0_MRT2_DISCARD_SRC', + 48: 'SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS', + 49: 'SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS', + 50: 'SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS', + 51: 'SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST', + 52: 'SX_PERF_SEL_DB0_MRT3_DISCARD_SRC', + 53: 'SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS', + 54: 'SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS', + 55: 'SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS', + 56: 'SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST', + 57: 'SX_PERF_SEL_DB0_MRT4_DISCARD_SRC', + 58: 'SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS', + 59: 'SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS', + 60: 'SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS', + 61: 'SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST', + 62: 'SX_PERF_SEL_DB0_MRT5_DISCARD_SRC', + 63: 'SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS', + 64: 'SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS', + 65: 'SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS', + 66: 'SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST', + 67: 'SX_PERF_SEL_DB0_MRT6_DISCARD_SRC', + 68: 'SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS', + 69: 'SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS', + 70: 'SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS', + 71: 'SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST', + 72: 'SX_PERF_SEL_DB0_MRT7_DISCARD_SRC', + 73: 'SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS', + 74: 'SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS', + 75: 'SX_PERF_SEL_DB1_A2M_DISCARD_QUADS', + 76: 'SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS', + 77: 'SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST', + 78: 'SX_PERF_SEL_DB1_MRT0_DISCARD_SRC', + 79: 'SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS', + 80: 'SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS', + 81: 'SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS', + 82: 'SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST', + 83: 'SX_PERF_SEL_DB1_MRT1_DISCARD_SRC', + 84: 'SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS', + 85: 'SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS', + 86: 'SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS', + 87: 'SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST', + 88: 'SX_PERF_SEL_DB1_MRT2_DISCARD_SRC', + 89: 'SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS', + 90: 'SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS', + 91: 'SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS', + 92: 'SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST', + 93: 'SX_PERF_SEL_DB1_MRT3_DISCARD_SRC', + 94: 'SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS', + 95: 'SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS', + 96: 'SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS', + 97: 'SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST', + 98: 'SX_PERF_SEL_DB1_MRT4_DISCARD_SRC', + 99: 'SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS', + 100: 'SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS', + 101: 'SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS', + 102: 'SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST', + 103: 'SX_PERF_SEL_DB1_MRT5_DISCARD_SRC', + 104: 'SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS', + 105: 'SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS', + 106: 'SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS', + 107: 'SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST', + 108: 'SX_PERF_SEL_DB1_MRT6_DISCARD_SRC', + 109: 'SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS', + 110: 'SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS', + 111: 'SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS', + 112: 'SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST', + 113: 'SX_PERF_SEL_DB1_MRT7_DISCARD_SRC', + 114: 'SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS', + 115: 'SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS', + 116: 'SX_PERF_SEL_DB2_A2M_DISCARD_QUADS', + 117: 'SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS', + 118: 'SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST', + 119: 'SX_PERF_SEL_DB2_MRT0_DISCARD_SRC', + 120: 'SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS', + 121: 'SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS', + 122: 'SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS', + 123: 'SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST', + 124: 'SX_PERF_SEL_DB2_MRT1_DISCARD_SRC', + 125: 'SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS', + 126: 'SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS', + 127: 'SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS', + 128: 'SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST', + 129: 'SX_PERF_SEL_DB2_MRT2_DISCARD_SRC', + 130: 'SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS', + 131: 'SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS', + 132: 'SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS', + 133: 'SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST', + 134: 'SX_PERF_SEL_DB2_MRT3_DISCARD_SRC', + 135: 'SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS', + 136: 'SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS', + 137: 'SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS', + 138: 'SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST', + 139: 'SX_PERF_SEL_DB2_MRT4_DISCARD_SRC', + 140: 'SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS', + 141: 'SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS', + 142: 'SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS', + 143: 'SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST', + 144: 'SX_PERF_SEL_DB2_MRT5_DISCARD_SRC', + 145: 'SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS', + 146: 'SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS', + 147: 'SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS', + 148: 'SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST', + 149: 'SX_PERF_SEL_DB2_MRT6_DISCARD_SRC', + 150: 'SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS', + 151: 'SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS', + 152: 'SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS', + 153: 'SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST', + 154: 'SX_PERF_SEL_DB2_MRT7_DISCARD_SRC', + 155: 'SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS', + 156: 'SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS', + 157: 'SX_PERF_SEL_DB3_A2M_DISCARD_QUADS', + 158: 'SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS', + 159: 'SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST', + 160: 'SX_PERF_SEL_DB3_MRT0_DISCARD_SRC', + 161: 'SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS', + 162: 'SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS', + 163: 'SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS', + 164: 'SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST', + 165: 'SX_PERF_SEL_DB3_MRT1_DISCARD_SRC', + 166: 'SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS', + 167: 'SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS', + 168: 'SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS', + 169: 'SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST', + 170: 'SX_PERF_SEL_DB3_MRT2_DISCARD_SRC', + 171: 'SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS', + 172: 'SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS', + 173: 'SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS', + 174: 'SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST', + 175: 'SX_PERF_SEL_DB3_MRT3_DISCARD_SRC', + 176: 'SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS', + 177: 'SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS', + 178: 'SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS', + 179: 'SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST', + 180: 'SX_PERF_SEL_DB3_MRT4_DISCARD_SRC', + 181: 'SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS', + 182: 'SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS', + 183: 'SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS', + 184: 'SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST', + 185: 'SX_PERF_SEL_DB3_MRT5_DISCARD_SRC', + 186: 'SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS', + 187: 'SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS', + 188: 'SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS', + 189: 'SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST', + 190: 'SX_PERF_SEL_DB3_MRT6_DISCARD_SRC', + 191: 'SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS', + 192: 'SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS', + 193: 'SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS', + 194: 'SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST', + 195: 'SX_PERF_SEL_DB3_MRT7_DISCARD_SRC', + 196: 'SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS', + 197: 'SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS', + 198: 'SX_PERF_SEL_PA_REQ_LATENCY', + 199: 'SX_PERF_SEL_POS_SCBD_STALL', + 200: 'SX_PERF_SEL_COL_SCBD_STALL', + 201: 'SX_PERF_SEL_CLOCK_DROP_STALL', + 202: 'SX_PERF_SEL_GATE_EN5', + 203: 'SX_PERF_SEL_GATE_EN6', + 204: 'SX_PERF_SEL_DB0_SIZE', + 205: 'SX_PERF_SEL_DB1_SIZE', + 206: 'SX_PERF_SEL_DB2_SIZE', + 207: 'SX_PERF_SEL_DB3_SIZE', + 208: 'SX_PERF_SEL_SPLITMODE', + 209: 'SX_PERF_SEL_COL_SCBD0_STALL', + 210: 'SX_PERF_SEL_COL_SCBD1_STALL', + 211: 'SX_PERF_SEL_IDX_STALL_CYCLES', + 212: 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 213: 'SX_PERF_SEL_IDX_REQ', + 214: 'SX_PERF_SEL_IDX_RET', + 215: 'SX_PERF_SEL_IDX_REQ_LATENCY', + 216: 'SX_PERF_SEL_IDX_SCBD_STALL', + 217: 'SX_PERF_SEL_GATE_EN7', + 218: 'SX_PERF_SEL_GATE_EN8', + 219: 'SX_PERF_SEL_SH_IDX_STARVE', + 220: 'SX_PERF_SEL_IDX_BUSY', +} +SX_PERF_SEL_PA_IDLE_CYCLES = 0 +SX_PERF_SEL_PA_REQ = 1 +SX_PERF_SEL_PA_POS = 2 +SX_PERF_SEL_CLOCK = 3 +SX_PERF_SEL_GATE_EN1 = 4 +SX_PERF_SEL_GATE_EN2 = 5 +SX_PERF_SEL_GATE_EN3 = 6 +SX_PERF_SEL_GATE_EN4 = 7 +SX_PERF_SEL_SH_POS_STARVE = 8 +SX_PERF_SEL_SH_COLOR_STARVE = 9 +SX_PERF_SEL_SH_POS_STALL = 10 +SX_PERF_SEL_SH_COLOR_STALL = 11 +SX_PERF_SEL_DB0_PIXELS = 12 +SX_PERF_SEL_DB0_HALF_QUADS = 13 +SX_PERF_SEL_DB0_PIXEL_STALL = 14 +SX_PERF_SEL_DB0_PIXEL_IDLE = 15 +SX_PERF_SEL_DB0_PRED_PIXELS = 16 +SX_PERF_SEL_DB1_PIXELS = 17 +SX_PERF_SEL_DB1_HALF_QUADS = 18 +SX_PERF_SEL_DB1_PIXEL_STALL = 19 +SX_PERF_SEL_DB1_PIXEL_IDLE = 20 +SX_PERF_SEL_DB1_PRED_PIXELS = 21 +SX_PERF_SEL_DB2_PIXELS = 22 +SX_PERF_SEL_DB2_HALF_QUADS = 23 +SX_PERF_SEL_DB2_PIXEL_STALL = 24 +SX_PERF_SEL_DB2_PIXEL_IDLE = 25 +SX_PERF_SEL_DB2_PRED_PIXELS = 26 +SX_PERF_SEL_DB3_PIXELS = 27 +SX_PERF_SEL_DB3_HALF_QUADS = 28 +SX_PERF_SEL_DB3_PIXEL_STALL = 29 +SX_PERF_SEL_DB3_PIXEL_IDLE = 30 +SX_PERF_SEL_DB3_PRED_PIXELS = 31 +SX_PERF_SEL_COL_BUSY = 32 +SX_PERF_SEL_POS_BUSY = 33 +SX_PERF_SEL_DB0_A2M_DISCARD_QUADS = 34 +SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS = 35 +SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST = 36 +SX_PERF_SEL_DB0_MRT0_DISCARD_SRC = 37 +SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS = 38 +SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS = 39 +SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS = 40 +SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST = 41 +SX_PERF_SEL_DB0_MRT1_DISCARD_SRC = 42 +SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS = 43 +SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS = 44 +SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS = 45 +SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST = 46 +SX_PERF_SEL_DB0_MRT2_DISCARD_SRC = 47 +SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS = 48 +SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS = 49 +SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS = 50 +SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST = 51 +SX_PERF_SEL_DB0_MRT3_DISCARD_SRC = 52 +SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS = 53 +SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS = 54 +SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS = 55 +SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST = 56 +SX_PERF_SEL_DB0_MRT4_DISCARD_SRC = 57 +SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS = 58 +SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS = 59 +SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS = 60 +SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST = 61 +SX_PERF_SEL_DB0_MRT5_DISCARD_SRC = 62 +SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS = 63 +SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS = 64 +SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS = 65 +SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST = 66 +SX_PERF_SEL_DB0_MRT6_DISCARD_SRC = 67 +SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS = 68 +SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS = 69 +SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS = 70 +SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST = 71 +SX_PERF_SEL_DB0_MRT7_DISCARD_SRC = 72 +SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS = 73 +SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS = 74 +SX_PERF_SEL_DB1_A2M_DISCARD_QUADS = 75 +SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS = 76 +SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST = 77 +SX_PERF_SEL_DB1_MRT0_DISCARD_SRC = 78 +SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS = 79 +SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS = 80 +SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS = 81 +SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST = 82 +SX_PERF_SEL_DB1_MRT1_DISCARD_SRC = 83 +SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS = 84 +SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS = 85 +SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS = 86 +SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST = 87 +SX_PERF_SEL_DB1_MRT2_DISCARD_SRC = 88 +SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS = 89 +SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS = 90 +SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS = 91 +SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST = 92 +SX_PERF_SEL_DB1_MRT3_DISCARD_SRC = 93 +SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS = 94 +SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS = 95 +SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS = 96 +SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST = 97 +SX_PERF_SEL_DB1_MRT4_DISCARD_SRC = 98 +SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS = 99 +SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS = 100 +SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS = 101 +SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST = 102 +SX_PERF_SEL_DB1_MRT5_DISCARD_SRC = 103 +SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS = 104 +SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS = 105 +SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS = 106 +SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST = 107 +SX_PERF_SEL_DB1_MRT6_DISCARD_SRC = 108 +SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS = 109 +SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS = 110 +SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS = 111 +SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST = 112 +SX_PERF_SEL_DB1_MRT7_DISCARD_SRC = 113 +SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS = 114 +SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS = 115 +SX_PERF_SEL_DB2_A2M_DISCARD_QUADS = 116 +SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS = 117 +SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST = 118 +SX_PERF_SEL_DB2_MRT0_DISCARD_SRC = 119 +SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS = 120 +SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS = 121 +SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS = 122 +SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST = 123 +SX_PERF_SEL_DB2_MRT1_DISCARD_SRC = 124 +SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS = 125 +SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS = 126 +SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS = 127 +SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST = 128 +SX_PERF_SEL_DB2_MRT2_DISCARD_SRC = 129 +SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS = 130 +SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS = 131 +SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS = 132 +SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST = 133 +SX_PERF_SEL_DB2_MRT3_DISCARD_SRC = 134 +SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS = 135 +SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS = 136 +SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS = 137 +SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST = 138 +SX_PERF_SEL_DB2_MRT4_DISCARD_SRC = 139 +SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS = 140 +SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS = 141 +SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS = 142 +SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST = 143 +SX_PERF_SEL_DB2_MRT5_DISCARD_SRC = 144 +SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS = 145 +SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS = 146 +SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS = 147 +SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST = 148 +SX_PERF_SEL_DB2_MRT6_DISCARD_SRC = 149 +SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS = 150 +SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS = 151 +SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS = 152 +SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST = 153 +SX_PERF_SEL_DB2_MRT7_DISCARD_SRC = 154 +SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS = 155 +SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS = 156 +SX_PERF_SEL_DB3_A2M_DISCARD_QUADS = 157 +SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS = 158 +SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST = 159 +SX_PERF_SEL_DB3_MRT0_DISCARD_SRC = 160 +SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS = 161 +SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS = 162 +SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS = 163 +SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST = 164 +SX_PERF_SEL_DB3_MRT1_DISCARD_SRC = 165 +SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS = 166 +SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS = 167 +SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS = 168 +SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST = 169 +SX_PERF_SEL_DB3_MRT2_DISCARD_SRC = 170 +SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS = 171 +SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS = 172 +SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS = 173 +SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST = 174 +SX_PERF_SEL_DB3_MRT3_DISCARD_SRC = 175 +SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS = 176 +SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS = 177 +SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS = 178 +SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST = 179 +SX_PERF_SEL_DB3_MRT4_DISCARD_SRC = 180 +SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS = 181 +SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS = 182 +SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS = 183 +SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST = 184 +SX_PERF_SEL_DB3_MRT5_DISCARD_SRC = 185 +SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS = 186 +SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS = 187 +SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS = 188 +SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST = 189 +SX_PERF_SEL_DB3_MRT6_DISCARD_SRC = 190 +SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS = 191 +SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS = 192 +SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS = 193 +SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST = 194 +SX_PERF_SEL_DB3_MRT7_DISCARD_SRC = 195 +SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS = 196 +SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS = 197 +SX_PERF_SEL_PA_REQ_LATENCY = 198 +SX_PERF_SEL_POS_SCBD_STALL = 199 +SX_PERF_SEL_COL_SCBD_STALL = 200 +SX_PERF_SEL_CLOCK_DROP_STALL = 201 +SX_PERF_SEL_GATE_EN5 = 202 +SX_PERF_SEL_GATE_EN6 = 203 +SX_PERF_SEL_DB0_SIZE = 204 +SX_PERF_SEL_DB1_SIZE = 205 +SX_PERF_SEL_DB2_SIZE = 206 +SX_PERF_SEL_DB3_SIZE = 207 +SX_PERF_SEL_SPLITMODE = 208 +SX_PERF_SEL_COL_SCBD0_STALL = 209 +SX_PERF_SEL_COL_SCBD1_STALL = 210 +SX_PERF_SEL_IDX_STALL_CYCLES = 211 +SX_PERF_SEL_IDX_IDLE_CYCLES = 212 +SX_PERF_SEL_IDX_REQ = 213 +SX_PERF_SEL_IDX_RET = 214 +SX_PERF_SEL_IDX_REQ_LATENCY = 215 +SX_PERF_SEL_IDX_SCBD_STALL = 216 +SX_PERF_SEL_GATE_EN7 = 217 +SX_PERF_SEL_GATE_EN8 = 218 +SX_PERF_SEL_SH_IDX_STARVE = 219 +SX_PERF_SEL_IDX_BUSY = 220 +SX_PERFCOUNTER_VALS = ctypes.c_uint32 # enum + +# values for enumeration 'ForceControl' +ForceControl__enumvalues = { + 0: 'FORCE_OFF', + 1: 'FORCE_ENABLE', + 2: 'FORCE_DISABLE', + 3: 'FORCE_RESERVED', +} +FORCE_OFF = 0 +FORCE_ENABLE = 1 +FORCE_DISABLE = 2 +FORCE_RESERVED = 3 +ForceControl = ctypes.c_uint32 # enum + +# values for enumeration 'ZSamplePosition' +ZSamplePosition__enumvalues = { + 0: 'Z_SAMPLE_CENTER', + 1: 'Z_SAMPLE_CENTROID', +} +Z_SAMPLE_CENTER = 0 +Z_SAMPLE_CENTROID = 1 +ZSamplePosition = ctypes.c_uint32 # enum + +# values for enumeration 'ZOrder' +ZOrder__enumvalues = { + 0: 'LATE_Z', + 1: 'EARLY_Z_THEN_LATE_Z', + 2: 'RE_Z', + 3: 'EARLY_Z_THEN_RE_Z', +} +LATE_Z = 0 +EARLY_Z_THEN_LATE_Z = 1 +RE_Z = 2 +EARLY_Z_THEN_RE_Z = 3 +ZOrder = ctypes.c_uint32 # enum + +# values for enumeration 'ZpassControl' +ZpassControl__enumvalues = { + 0: 'ZPASS_DISABLE', + 1: 'ZPASS_SAMPLES', + 2: 'ZPASS_PIXELS', +} +ZPASS_DISABLE = 0 +ZPASS_SAMPLES = 1 +ZPASS_PIXELS = 2 +ZpassControl = ctypes.c_uint32 # enum + +# values for enumeration 'ZModeForce' +ZModeForce__enumvalues = { + 0: 'NO_FORCE', + 1: 'FORCE_EARLY_Z', + 2: 'FORCE_LATE_Z', + 3: 'FORCE_RE_Z', +} +NO_FORCE = 0 +FORCE_EARLY_Z = 1 +FORCE_LATE_Z = 2 +FORCE_RE_Z = 3 +ZModeForce = ctypes.c_uint32 # enum + +# values for enumeration 'ZLimitSumm' +ZLimitSumm__enumvalues = { + 0: 'FORCE_SUMM_OFF', + 1: 'FORCE_SUMM_MINZ', + 2: 'FORCE_SUMM_MAXZ', + 3: 'FORCE_SUMM_BOTH', +} +FORCE_SUMM_OFF = 0 +FORCE_SUMM_MINZ = 1 +FORCE_SUMM_MAXZ = 2 +FORCE_SUMM_BOTH = 3 +ZLimitSumm = ctypes.c_uint32 # enum + +# values for enumeration 'CompareFrag' +CompareFrag__enumvalues = { + 0: 'FRAG_NEVER', + 1: 'FRAG_LESS', + 2: 'FRAG_EQUAL', + 3: 'FRAG_LEQUAL', + 4: 'FRAG_GREATER', + 5: 'FRAG_NOTEQUAL', + 6: 'FRAG_GEQUAL', + 7: 'FRAG_ALWAYS', +} +FRAG_NEVER = 0 +FRAG_LESS = 1 +FRAG_EQUAL = 2 +FRAG_LEQUAL = 3 +FRAG_GREATER = 4 +FRAG_NOTEQUAL = 5 +FRAG_GEQUAL = 6 +FRAG_ALWAYS = 7 +CompareFrag = ctypes.c_uint32 # enum + +# values for enumeration 'StencilOp' +StencilOp__enumvalues = { + 0: 'STENCIL_KEEP', + 1: 'STENCIL_ZERO', + 2: 'STENCIL_ONES', + 3: 'STENCIL_REPLACE_TEST', + 4: 'STENCIL_REPLACE_OP', + 5: 'STENCIL_ADD_CLAMP', + 6: 'STENCIL_SUB_CLAMP', + 7: 'STENCIL_INVERT', + 8: 'STENCIL_ADD_WRAP', + 9: 'STENCIL_SUB_WRAP', + 10: 'STENCIL_AND', + 11: 'STENCIL_OR', + 12: 'STENCIL_XOR', + 13: 'STENCIL_NAND', + 14: 'STENCIL_NOR', + 15: 'STENCIL_XNOR', +} +STENCIL_KEEP = 0 +STENCIL_ZERO = 1 +STENCIL_ONES = 2 +STENCIL_REPLACE_TEST = 3 +STENCIL_REPLACE_OP = 4 +STENCIL_ADD_CLAMP = 5 +STENCIL_SUB_CLAMP = 6 +STENCIL_INVERT = 7 +STENCIL_ADD_WRAP = 8 +STENCIL_SUB_WRAP = 9 +STENCIL_AND = 10 +STENCIL_OR = 11 +STENCIL_XOR = 12 +STENCIL_NAND = 13 +STENCIL_NOR = 14 +STENCIL_XNOR = 15 +StencilOp = ctypes.c_uint32 # enum + +# values for enumeration 'ConservativeZExport' +ConservativeZExport__enumvalues = { + 0: 'EXPORT_ANY_Z', + 1: 'EXPORT_LESS_THAN_Z', + 2: 'EXPORT_GREATER_THAN_Z', + 3: 'EXPORT_RESERVED', +} +EXPORT_ANY_Z = 0 +EXPORT_LESS_THAN_Z = 1 +EXPORT_GREATER_THAN_Z = 2 +EXPORT_RESERVED = 3 +ConservativeZExport = ctypes.c_uint32 # enum + +# values for enumeration 'DbPSLControl' +DbPSLControl__enumvalues = { + 0: 'PSLC_AUTO', + 1: 'PSLC_ON_HANG_ONLY', + 2: 'PSLC_ASAP', + 3: 'PSLC_COUNTDOWN', +} +PSLC_AUTO = 0 +PSLC_ON_HANG_ONLY = 1 +PSLC_ASAP = 2 +PSLC_COUNTDOWN = 3 +DbPSLControl = ctypes.c_uint32 # enum + +# values for enumeration 'DbPRTFaultBehavior' +DbPRTFaultBehavior__enumvalues = { + 0: 'FAULT_ZERO', + 1: 'FAULT_ONE', + 2: 'FAULT_FAIL', + 3: 'FAULT_PASS', +} +FAULT_ZERO = 0 +FAULT_ONE = 1 +FAULT_FAIL = 2 +FAULT_PASS = 3 +DbPRTFaultBehavior = ctypes.c_uint32 # enum + +# values for enumeration 'PerfCounter_Vals' +PerfCounter_Vals__enumvalues = { + 0: 'DB_PERF_SEL_SC_DB_tile_sends', + 1: 'DB_PERF_SEL_SC_DB_tile_busy', + 2: 'DB_PERF_SEL_SC_DB_tile_stalls', + 3: 'DB_PERF_SEL_SC_DB_tile_events', + 4: 'DB_PERF_SEL_SC_DB_tile_tiles', + 5: 'DB_PERF_SEL_SC_DB_tile_covered', + 6: 'DB_PERF_SEL_hiz_tc_read_starved', + 7: 'DB_PERF_SEL_hiz_tc_write_stall', + 8: 'DB_PERF_SEL_hiz_tile_culled', + 9: 'DB_PERF_SEL_his_tile_culled', + 10: 'DB_PERF_SEL_DB_SC_tile_sends', + 11: 'DB_PERF_SEL_DB_SC_tile_busy', + 12: 'DB_PERF_SEL_DB_SC_tile_stalls', + 13: 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 14: 'DB_PERF_SEL_DB_SC_tile_tiles', + 15: 'DB_PERF_SEL_DB_SC_tile_culled', + 16: 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 17: 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 18: 'DB_PERF_SEL_DB_SC_tile_no_ops', + 19: 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 20: 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 21: 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 22: 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 23: 'DB_PERF_SEL_SC_DB_quad_sends', + 24: 'DB_PERF_SEL_SC_DB_quad_busy', + 25: 'DB_PERF_SEL_SC_DB_quad_squads', + 26: 'DB_PERF_SEL_SC_DB_quad_tiles', + 27: 'DB_PERF_SEL_SC_DB_quad_pixels', + 28: 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 29: 'DB_PERF_SEL_DB_SC_quad_sends', + 30: 'DB_PERF_SEL_DB_SC_quad_busy', + 31: 'DB_PERF_SEL_DB_SC_quad_stalls', + 32: 'DB_PERF_SEL_DB_SC_quad_tiles', + 33: 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 34: 'DB_PERF_SEL_DB_CB_tile_sends', + 35: 'DB_PERF_SEL_DB_CB_tile_busy', + 36: 'DB_PERF_SEL_DB_CB_tile_stalls', + 37: 'DB_PERF_SEL_SX_DB_quad_sends', + 38: 'DB_PERF_SEL_SX_DB_quad_busy', + 39: 'DB_PERF_SEL_SX_DB_quad_stalls', + 40: 'DB_PERF_SEL_SX_DB_quad_quads', + 41: 'DB_PERF_SEL_SX_DB_quad_pixels', + 42: 'DB_PERF_SEL_SX_DB_quad_exports', + 43: 'DB_PERF_SEL_SH_quads_outstanding_sum', + 44: 'DB_PERF_SEL_DB_CB_lquad_sends', + 45: 'DB_PERF_SEL_DB_CB_lquad_busy', + 46: 'DB_PERF_SEL_DB_CB_lquad_stalls', + 47: 'DB_PERF_SEL_DB_CB_lquad_quads', + 48: 'DB_PERF_SEL_tile_rd_sends', + 49: 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 50: 'DB_PERF_SEL_quad_rd_sends', + 51: 'DB_PERF_SEL_quad_rd_busy', + 52: 'DB_PERF_SEL_quad_rd_mi_stall', + 53: 'DB_PERF_SEL_quad_rd_rw_collision', + 54: 'DB_PERF_SEL_quad_rd_tag_stall', + 55: 'DB_PERF_SEL_quad_rd_32byte_reqs', + 56: 'DB_PERF_SEL_quad_rd_panic', + 57: 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 58: 'DB_PERF_SEL_quad_rdret_sends', + 59: 'DB_PERF_SEL_quad_rdret_busy', + 60: 'DB_PERF_SEL_tile_wr_sends', + 61: 'DB_PERF_SEL_tile_wr_acks', + 62: 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 63: 'DB_PERF_SEL_quad_wr_sends', + 64: 'DB_PERF_SEL_quad_wr_busy', + 65: 'DB_PERF_SEL_quad_wr_mi_stall', + 66: 'DB_PERF_SEL_quad_wr_coherency_stall', + 67: 'DB_PERF_SEL_quad_wr_acks', + 68: 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 69: 'DB_PERF_SEL_Tile_Cache_misses', + 70: 'DB_PERF_SEL_Tile_Cache_hits', + 71: 'DB_PERF_SEL_Tile_Cache_flushes', + 72: 'DB_PERF_SEL_Tile_Cache_surface_stall', + 73: 'DB_PERF_SEL_Tile_Cache_starves', + 74: 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 75: 'DB_PERF_SEL_tcp_dispatcher_reads', + 76: 'DB_PERF_SEL_tcp_prefetcher_reads', + 77: 'DB_PERF_SEL_tcp_preloader_reads', + 78: 'DB_PERF_SEL_tcp_dispatcher_flushes', + 79: 'DB_PERF_SEL_tcp_prefetcher_flushes', + 80: 'DB_PERF_SEL_tcp_preloader_flushes', + 81: 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 82: 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 83: 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 84: 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 85: 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 86: 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 87: 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 88: 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 89: 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 90: 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 91: 'DB_PERF_SEL_Depth_Tile_Cache_event', + 92: 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 93: 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 94: 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 95: 'DB_PERF_SEL_Stencil_Cache_misses', + 96: 'DB_PERF_SEL_Stencil_Cache_hits', + 97: 'DB_PERF_SEL_Stencil_Cache_flushes', + 98: 'DB_PERF_SEL_Stencil_Cache_starves', + 99: 'DB_PERF_SEL_Stencil_Cache_frees', + 100: 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 101: 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 102: 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 103: 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 104: 'DB_PERF_SEL_Z_Cache_pmask_misses', + 105: 'DB_PERF_SEL_Z_Cache_pmask_hits', + 106: 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 107: 'DB_PERF_SEL_Z_Cache_pmask_starves', + 108: 'DB_PERF_SEL_Z_Cache_frees', + 109: 'DB_PERF_SEL_Plane_Cache_misses', + 110: 'DB_PERF_SEL_Plane_Cache_hits', + 111: 'DB_PERF_SEL_Plane_Cache_flushes', + 112: 'DB_PERF_SEL_Plane_Cache_starves', + 113: 'DB_PERF_SEL_Plane_Cache_frees', + 114: 'DB_PERF_SEL_flush_expanded_stencil', + 115: 'DB_PERF_SEL_flush_compressed_stencil', + 116: 'DB_PERF_SEL_flush_single_stencil', + 117: 'DB_PERF_SEL_planes_flushed', + 118: 'DB_PERF_SEL_flush_1plane', + 119: 'DB_PERF_SEL_flush_2plane', + 120: 'DB_PERF_SEL_flush_3plane', + 121: 'DB_PERF_SEL_flush_4plane', + 122: 'DB_PERF_SEL_flush_5plane', + 123: 'DB_PERF_SEL_flush_6plane', + 124: 'DB_PERF_SEL_flush_7plane', + 125: 'DB_PERF_SEL_flush_8plane', + 126: 'DB_PERF_SEL_flush_9plane', + 127: 'DB_PERF_SEL_flush_10plane', + 128: 'DB_PERF_SEL_flush_11plane', + 129: 'DB_PERF_SEL_flush_12plane', + 130: 'DB_PERF_SEL_flush_13plane', + 131: 'DB_PERF_SEL_flush_14plane', + 132: 'DB_PERF_SEL_flush_15plane', + 133: 'DB_PERF_SEL_flush_16plane', + 134: 'DB_PERF_SEL_flush_expanded_z', + 135: 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 136: 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 137: 'DB_PERF_SEL_dk_tile_sends', + 138: 'DB_PERF_SEL_dk_tile_busy', + 139: 'DB_PERF_SEL_dk_tile_quad_starves', + 140: 'DB_PERF_SEL_dk_tile_stalls', + 141: 'DB_PERF_SEL_dk_squad_sends', + 142: 'DB_PERF_SEL_dk_squad_busy', + 143: 'DB_PERF_SEL_dk_squad_stalls', + 144: 'DB_PERF_SEL_Op_Pipe_Busy', + 145: 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 146: 'DB_PERF_SEL_qc_busy', + 147: 'DB_PERF_SEL_qc_xfc', + 148: 'DB_PERF_SEL_qc_conflicts', + 149: 'DB_PERF_SEL_qc_full_stall', + 150: 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', + 151: 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 152: 'DB_PERF_SEL_tsc_insert_summarize_stall', + 153: 'DB_PERF_SEL_tl_busy', + 154: 'DB_PERF_SEL_tl_dtc_read_starved', + 155: 'DB_PERF_SEL_tl_z_fetch_stall', + 156: 'DB_PERF_SEL_tl_stencil_stall', + 157: 'DB_PERF_SEL_tl_z_decompress_stall', + 158: 'DB_PERF_SEL_tl_stencil_locked_stall', + 159: 'DB_PERF_SEL_tl_events', + 160: 'DB_PERF_SEL_tl_summarize_squads', + 161: 'DB_PERF_SEL_tl_flush_expand_squads', + 162: 'DB_PERF_SEL_tl_expand_squads', + 163: 'DB_PERF_SEL_tl_preZ_squads', + 164: 'DB_PERF_SEL_tl_postZ_squads', + 165: 'DB_PERF_SEL_tl_preZ_noop_squads', + 166: 'DB_PERF_SEL_tl_postZ_noop_squads', + 167: 'DB_PERF_SEL_tl_tile_ops', + 168: 'DB_PERF_SEL_tl_in_xfc', + 169: 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 170: 'DB_PERF_SEL_tl_in_fast_z_stall', + 171: 'DB_PERF_SEL_tl_out_xfc', + 172: 'DB_PERF_SEL_tl_out_squads', + 173: 'DB_PERF_SEL_zf_plane_multicycle', + 174: 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 175: 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 176: 'DB_PERF_SEL_PostZ_Samples_failing_S', + 177: 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 178: 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 179: 'DB_PERF_SEL_PreZ_Samples_failing_S', + 180: 'DB_PERF_SEL_ts_tc_update_stall', + 181: 'DB_PERF_SEL_sc_kick_start', + 182: 'DB_PERF_SEL_sc_kick_end', + 183: 'DB_PERF_SEL_clock_reg_active', + 184: 'DB_PERF_SEL_clock_main_active', + 185: 'DB_PERF_SEL_clock_mem_export_active', + 186: 'DB_PERF_SEL_esr_ps_out_busy', + 187: 'DB_PERF_SEL_esr_ps_lqf_busy', + 188: 'DB_PERF_SEL_esr_ps_lqf_stall', + 189: 'DB_PERF_SEL_etr_out_send', + 190: 'DB_PERF_SEL_etr_out_busy', + 191: 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 192: 'DB_PERF_SEL_etr_out_cb_tile_stall', + 193: 'DB_PERF_SEL_etr_out_esr_stall', + 194: 'DB_PERF_SEL_esr_ps_sqq_busy', + 195: 'DB_PERF_SEL_esr_ps_sqq_stall', + 196: 'DB_PERF_SEL_esr_eot_fwd_busy', + 197: 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 198: 'DB_PERF_SEL_esr_eot_fwd_forward', + 199: 'DB_PERF_SEL_esr_sqq_zi_busy', + 200: 'DB_PERF_SEL_esr_sqq_zi_stall', + 201: 'DB_PERF_SEL_postzl_sq_pt_busy', + 202: 'DB_PERF_SEL_postzl_sq_pt_stall', + 203: 'DB_PERF_SEL_postzl_se_busy', + 204: 'DB_PERF_SEL_postzl_se_stall', + 205: 'DB_PERF_SEL_postzl_partial_launch', + 206: 'DB_PERF_SEL_postzl_full_launch', + 207: 'DB_PERF_SEL_postzl_partial_waiting', + 208: 'DB_PERF_SEL_postzl_tile_mem_stall', + 209: 'DB_PERF_SEL_postzl_tile_init_stall', + 210: 'DB_PERF_SEL_prezl_tile_mem_stall', + 211: 'DB_PERF_SEL_prezl_tile_init_stall', + 212: 'DB_PERF_SEL_dtt_sm_clash_stall', + 213: 'DB_PERF_SEL_dtt_sm_slot_stall', + 214: 'DB_PERF_SEL_dtt_sm_miss_stall', + 215: 'DB_PERF_SEL_mi_rdreq_busy', + 216: 'DB_PERF_SEL_mi_rdreq_stall', + 217: 'DB_PERF_SEL_mi_wrreq_busy', + 218: 'DB_PERF_SEL_mi_wrreq_stall', + 219: 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 220: 'DB_PERF_SEL_dkg_tile_rate_tile', + 221: 'DB_PERF_SEL_prezl_src_in_sends', + 222: 'DB_PERF_SEL_prezl_src_in_stall', + 223: 'DB_PERF_SEL_prezl_src_in_squads', + 224: 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 225: 'DB_PERF_SEL_prezl_src_in_tile_rate', + 226: 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 227: 'DB_PERF_SEL_prezl_src_out_stall', + 228: 'DB_PERF_SEL_postzl_src_in_sends', + 229: 'DB_PERF_SEL_postzl_src_in_stall', + 230: 'DB_PERF_SEL_postzl_src_in_squads', + 231: 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 232: 'DB_PERF_SEL_postzl_src_in_tile_rate', + 233: 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 234: 'DB_PERF_SEL_postzl_src_out_stall', + 235: 'DB_PERF_SEL_esr_ps_src_in_sends', + 236: 'DB_PERF_SEL_esr_ps_src_in_stall', + 237: 'DB_PERF_SEL_esr_ps_src_in_squads', + 238: 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 239: 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 240: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 241: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 242: 'DB_PERF_SEL_esr_ps_src_out_stall', + 243: 'DB_PERF_SEL_depth_bounds_tile_culled', + 244: 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 245: 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 246: 'DB_PERF_SEL_flush_compressed', + 247: 'DB_PERF_SEL_flush_plane_le4', + 248: 'DB_PERF_SEL_tiles_z_fully_summarized', + 249: 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 250: 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 251: 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 252: 'DB_PERF_SEL_tiles_decomp_on_expclear', + 253: 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 254: 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 255: 'DB_PERF_SEL_Op_Pipe_Postz_Busy', + 256: 'DB_PERF_SEL_di_dt_stall', + 257: 'DB_PERF_SEL_DB_SC_quad_lit_quad_pre_invoke', + 258: 'DB_PERF_SEL_DB_SC_s_tile_rate', + 259: 'DB_PERF_SEL_DB_SC_c_tile_rate', + 260: 'DB_PERF_SEL_DB_SC_z_tile_rate', + 261: 'Spare_261', + 262: 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 263: 'DB_PERF_SEL_DB_CB_lquad_double_format', + 264: 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 265: 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 266: 'DB_PERF_SEL_CB_DB_rdreq_sends', + 267: 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 268: 'DB_PERF_SEL_CB_DB_wrreq_sends', + 269: 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 270: 'DB_PERF_SEL_DB_CB_rdret_ack', + 271: 'DB_PERF_SEL_DB_CB_rdret_nack', + 272: 'DB_PERF_SEL_DB_CB_wrret_ack', + 273: 'DB_PERF_SEL_DB_CB_wrret_nack', + 274: 'DB_PERF_SEL_DFSM_Stall_opmode_change', + 275: 'DB_PERF_SEL_DFSM_Stall_cam_fifo', + 276: 'DB_PERF_SEL_DFSM_Stall_bypass_fifo', + 277: 'DB_PERF_SEL_DFSM_Stall_retained_tile_fifo', + 278: 'DB_PERF_SEL_DFSM_Stall_control_fifo', + 279: 'DB_PERF_SEL_DFSM_Stall_overflow_counter', + 280: 'DB_PERF_SEL_DFSM_Stall_pops_stall_overflow', + 281: 'DB_PERF_SEL_DFSM_Stall_pops_stall_self_flush', + 282: 'DB_PERF_SEL_DFSM_Stall_middle_output', + 283: 'DB_PERF_SEL_DFSM_Stall_stalling_general', + 284: 'Spare_285', + 285: 'Spare_286', + 286: 'DB_PERF_SEL_DFSM_prez_killed_squad', + 287: 'DB_PERF_SEL_DFSM_squads_in', + 288: 'DB_PERF_SEL_DFSM_full_cleared_squads_out', + 289: 'DB_PERF_SEL_DFSM_quads_in', + 290: 'DB_PERF_SEL_DFSM_fully_cleared_quads_out', + 291: 'DB_PERF_SEL_DFSM_lit_pixels_in', + 292: 'DB_PERF_SEL_DFSM_fully_cleared_pixels_out', + 293: 'DB_PERF_SEL_DFSM_lit_samples_in', + 294: 'DB_PERF_SEL_DFSM_lit_samples_out', + 295: 'DB_PERF_SEL_DFSM_evicted_tiles_above_watermark', + 296: 'DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream', + 297: 'DB_PERF_SEL_DFSM_stalled_by_downstream', + 298: 'DB_PERF_SEL_DFSM_evicted_squads_above_watermark', + 299: 'DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow', + 300: 'DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO', + 301: 'DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark', + 302: 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 303: 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 304: 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 305: 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 306: 'DB_PERF_SEL_unmapped_z_tile_culled', + 307: 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS', + 308: 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 309: 'DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS', + 310: 'DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event', + 311: 'DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix', + 312: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix', + 313: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix', + 314: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix', + 315: 'DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending', + 316: 'DB_PERF_SEL_DB_CB_context_dones', + 317: 'DB_PERF_SEL_DB_CB_eop_dones', + 318: 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 319: 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 320: 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 321: 'DB_PERF_SEL_SC_DB_tile_backface', + 322: 'DB_PERF_SEL_SC_DB_quad_quads', + 323: 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 324: 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 325: 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 326: 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 327: 'DB_PERF_SEL_DFSM_Flush_flushabit', + 328: 'DB_PERF_SEL_DFSM_Flush_flushabit_camcoord_fifo', + 329: 'DB_PERF_SEL_DFSM_Flush_flushabit_passthrough', + 330: 'DB_PERF_SEL_DFSM_Flush_flushabit_forceflush', + 331: 'DB_PERF_SEL_DFSM_Flush_flushabit_nearlyfull', + 332: 'DB_PERF_SEL_DFSM_Flush_flushabit_primitivesinflightwatermark', + 333: 'DB_PERF_SEL_DFSM_Flush_flushabit_punch_stalling', + 334: 'DB_PERF_SEL_DFSM_Flush_flushabit_retainedtilefifo_watermark', + 335: 'DB_PERF_SEL_DFSM_Flush_flushabit_tilesinflightwatermark', + 336: 'DB_PERF_SEL_DFSM_Flush_flushall', + 337: 'DB_PERF_SEL_DFSM_Flush_flushall_dfsmflush', + 338: 'DB_PERF_SEL_DFSM_Flush_flushall_opmodechange', + 339: 'DB_PERF_SEL_DFSM_Flush_flushall_sampleratechange', + 340: 'DB_PERF_SEL_DFSM_Flush_flushall_watchdog', + 341: 'DB_PERF_SEL_DB_SC_quad_double_quad', + 342: 'DB_PERF_SEL_SX_DB_quad_export_quads', + 343: 'DB_PERF_SEL_SX_DB_quad_double_format', + 344: 'DB_PERF_SEL_SX_DB_quad_fast_format', + 345: 'DB_PERF_SEL_SX_DB_quad_slow_format', +} +DB_PERF_SEL_SC_DB_tile_sends = 0 +DB_PERF_SEL_SC_DB_tile_busy = 1 +DB_PERF_SEL_SC_DB_tile_stalls = 2 +DB_PERF_SEL_SC_DB_tile_events = 3 +DB_PERF_SEL_SC_DB_tile_tiles = 4 +DB_PERF_SEL_SC_DB_tile_covered = 5 +DB_PERF_SEL_hiz_tc_read_starved = 6 +DB_PERF_SEL_hiz_tc_write_stall = 7 +DB_PERF_SEL_hiz_tile_culled = 8 +DB_PERF_SEL_his_tile_culled = 9 +DB_PERF_SEL_DB_SC_tile_sends = 10 +DB_PERF_SEL_DB_SC_tile_busy = 11 +DB_PERF_SEL_DB_SC_tile_stalls = 12 +DB_PERF_SEL_DB_SC_tile_df_stalls = 13 +DB_PERF_SEL_DB_SC_tile_tiles = 14 +DB_PERF_SEL_DB_SC_tile_culled = 15 +DB_PERF_SEL_DB_SC_tile_hier_kill = 16 +DB_PERF_SEL_DB_SC_tile_fast_ops = 17 +DB_PERF_SEL_DB_SC_tile_no_ops = 18 +DB_PERF_SEL_DB_SC_tile_tile_rate = 19 +DB_PERF_SEL_DB_SC_tile_ssaa_kill = 20 +DB_PERF_SEL_DB_SC_tile_fast_z_ops = 21 +DB_PERF_SEL_DB_SC_tile_fast_stencil_ops = 22 +DB_PERF_SEL_SC_DB_quad_sends = 23 +DB_PERF_SEL_SC_DB_quad_busy = 24 +DB_PERF_SEL_SC_DB_quad_squads = 25 +DB_PERF_SEL_SC_DB_quad_tiles = 26 +DB_PERF_SEL_SC_DB_quad_pixels = 27 +DB_PERF_SEL_SC_DB_quad_killed_tiles = 28 +DB_PERF_SEL_DB_SC_quad_sends = 29 +DB_PERF_SEL_DB_SC_quad_busy = 30 +DB_PERF_SEL_DB_SC_quad_stalls = 31 +DB_PERF_SEL_DB_SC_quad_tiles = 32 +DB_PERF_SEL_DB_SC_quad_lit_quad = 33 +DB_PERF_SEL_DB_CB_tile_sends = 34 +DB_PERF_SEL_DB_CB_tile_busy = 35 +DB_PERF_SEL_DB_CB_tile_stalls = 36 +DB_PERF_SEL_SX_DB_quad_sends = 37 +DB_PERF_SEL_SX_DB_quad_busy = 38 +DB_PERF_SEL_SX_DB_quad_stalls = 39 +DB_PERF_SEL_SX_DB_quad_quads = 40 +DB_PERF_SEL_SX_DB_quad_pixels = 41 +DB_PERF_SEL_SX_DB_quad_exports = 42 +DB_PERF_SEL_SH_quads_outstanding_sum = 43 +DB_PERF_SEL_DB_CB_lquad_sends = 44 +DB_PERF_SEL_DB_CB_lquad_busy = 45 +DB_PERF_SEL_DB_CB_lquad_stalls = 46 +DB_PERF_SEL_DB_CB_lquad_quads = 47 +DB_PERF_SEL_tile_rd_sends = 48 +DB_PERF_SEL_mi_tile_rd_outstanding_sum = 49 +DB_PERF_SEL_quad_rd_sends = 50 +DB_PERF_SEL_quad_rd_busy = 51 +DB_PERF_SEL_quad_rd_mi_stall = 52 +DB_PERF_SEL_quad_rd_rw_collision = 53 +DB_PERF_SEL_quad_rd_tag_stall = 54 +DB_PERF_SEL_quad_rd_32byte_reqs = 55 +DB_PERF_SEL_quad_rd_panic = 56 +DB_PERF_SEL_mi_quad_rd_outstanding_sum = 57 +DB_PERF_SEL_quad_rdret_sends = 58 +DB_PERF_SEL_quad_rdret_busy = 59 +DB_PERF_SEL_tile_wr_sends = 60 +DB_PERF_SEL_tile_wr_acks = 61 +DB_PERF_SEL_mi_tile_wr_outstanding_sum = 62 +DB_PERF_SEL_quad_wr_sends = 63 +DB_PERF_SEL_quad_wr_busy = 64 +DB_PERF_SEL_quad_wr_mi_stall = 65 +DB_PERF_SEL_quad_wr_coherency_stall = 66 +DB_PERF_SEL_quad_wr_acks = 67 +DB_PERF_SEL_mi_quad_wr_outstanding_sum = 68 +DB_PERF_SEL_Tile_Cache_misses = 69 +DB_PERF_SEL_Tile_Cache_hits = 70 +DB_PERF_SEL_Tile_Cache_flushes = 71 +DB_PERF_SEL_Tile_Cache_surface_stall = 72 +DB_PERF_SEL_Tile_Cache_starves = 73 +DB_PERF_SEL_Tile_Cache_mem_return_starve = 74 +DB_PERF_SEL_tcp_dispatcher_reads = 75 +DB_PERF_SEL_tcp_prefetcher_reads = 76 +DB_PERF_SEL_tcp_preloader_reads = 77 +DB_PERF_SEL_tcp_dispatcher_flushes = 78 +DB_PERF_SEL_tcp_prefetcher_flushes = 79 +DB_PERF_SEL_tcp_preloader_flushes = 80 +DB_PERF_SEL_Depth_Tile_Cache_sends = 81 +DB_PERF_SEL_Depth_Tile_Cache_busy = 82 +DB_PERF_SEL_Depth_Tile_Cache_starves = 83 +DB_PERF_SEL_Depth_Tile_Cache_dtile_locked = 84 +DB_PERF_SEL_Depth_Tile_Cache_alloc_stall = 85 +DB_PERF_SEL_Depth_Tile_Cache_misses = 86 +DB_PERF_SEL_Depth_Tile_Cache_hits = 87 +DB_PERF_SEL_Depth_Tile_Cache_flushes = 88 +DB_PERF_SEL_Depth_Tile_Cache_noop_tile = 89 +DB_PERF_SEL_Depth_Tile_Cache_detailed_noop = 90 +DB_PERF_SEL_Depth_Tile_Cache_event = 91 +DB_PERF_SEL_Depth_Tile_Cache_tile_frees = 92 +DB_PERF_SEL_Depth_Tile_Cache_data_frees = 93 +DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve = 94 +DB_PERF_SEL_Stencil_Cache_misses = 95 +DB_PERF_SEL_Stencil_Cache_hits = 96 +DB_PERF_SEL_Stencil_Cache_flushes = 97 +DB_PERF_SEL_Stencil_Cache_starves = 98 +DB_PERF_SEL_Stencil_Cache_frees = 99 +DB_PERF_SEL_Z_Cache_separate_Z_misses = 100 +DB_PERF_SEL_Z_Cache_separate_Z_hits = 101 +DB_PERF_SEL_Z_Cache_separate_Z_flushes = 102 +DB_PERF_SEL_Z_Cache_separate_Z_starves = 103 +DB_PERF_SEL_Z_Cache_pmask_misses = 104 +DB_PERF_SEL_Z_Cache_pmask_hits = 105 +DB_PERF_SEL_Z_Cache_pmask_flushes = 106 +DB_PERF_SEL_Z_Cache_pmask_starves = 107 +DB_PERF_SEL_Z_Cache_frees = 108 +DB_PERF_SEL_Plane_Cache_misses = 109 +DB_PERF_SEL_Plane_Cache_hits = 110 +DB_PERF_SEL_Plane_Cache_flushes = 111 +DB_PERF_SEL_Plane_Cache_starves = 112 +DB_PERF_SEL_Plane_Cache_frees = 113 +DB_PERF_SEL_flush_expanded_stencil = 114 +DB_PERF_SEL_flush_compressed_stencil = 115 +DB_PERF_SEL_flush_single_stencil = 116 +DB_PERF_SEL_planes_flushed = 117 +DB_PERF_SEL_flush_1plane = 118 +DB_PERF_SEL_flush_2plane = 119 +DB_PERF_SEL_flush_3plane = 120 +DB_PERF_SEL_flush_4plane = 121 +DB_PERF_SEL_flush_5plane = 122 +DB_PERF_SEL_flush_6plane = 123 +DB_PERF_SEL_flush_7plane = 124 +DB_PERF_SEL_flush_8plane = 125 +DB_PERF_SEL_flush_9plane = 126 +DB_PERF_SEL_flush_10plane = 127 +DB_PERF_SEL_flush_11plane = 128 +DB_PERF_SEL_flush_12plane = 129 +DB_PERF_SEL_flush_13plane = 130 +DB_PERF_SEL_flush_14plane = 131 +DB_PERF_SEL_flush_15plane = 132 +DB_PERF_SEL_flush_16plane = 133 +DB_PERF_SEL_flush_expanded_z = 134 +DB_PERF_SEL_earlyZ_waiting_for_postZ_done = 135 +DB_PERF_SEL_reZ_waiting_for_postZ_done = 136 +DB_PERF_SEL_dk_tile_sends = 137 +DB_PERF_SEL_dk_tile_busy = 138 +DB_PERF_SEL_dk_tile_quad_starves = 139 +DB_PERF_SEL_dk_tile_stalls = 140 +DB_PERF_SEL_dk_squad_sends = 141 +DB_PERF_SEL_dk_squad_busy = 142 +DB_PERF_SEL_dk_squad_stalls = 143 +DB_PERF_SEL_Op_Pipe_Busy = 144 +DB_PERF_SEL_Op_Pipe_MC_Read_stall = 145 +DB_PERF_SEL_qc_busy = 146 +DB_PERF_SEL_qc_xfc = 147 +DB_PERF_SEL_qc_conflicts = 148 +DB_PERF_SEL_qc_full_stall = 149 +DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ = 150 +DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ = 151 +DB_PERF_SEL_tsc_insert_summarize_stall = 152 +DB_PERF_SEL_tl_busy = 153 +DB_PERF_SEL_tl_dtc_read_starved = 154 +DB_PERF_SEL_tl_z_fetch_stall = 155 +DB_PERF_SEL_tl_stencil_stall = 156 +DB_PERF_SEL_tl_z_decompress_stall = 157 +DB_PERF_SEL_tl_stencil_locked_stall = 158 +DB_PERF_SEL_tl_events = 159 +DB_PERF_SEL_tl_summarize_squads = 160 +DB_PERF_SEL_tl_flush_expand_squads = 161 +DB_PERF_SEL_tl_expand_squads = 162 +DB_PERF_SEL_tl_preZ_squads = 163 +DB_PERF_SEL_tl_postZ_squads = 164 +DB_PERF_SEL_tl_preZ_noop_squads = 165 +DB_PERF_SEL_tl_postZ_noop_squads = 166 +DB_PERF_SEL_tl_tile_ops = 167 +DB_PERF_SEL_tl_in_xfc = 168 +DB_PERF_SEL_tl_in_single_stencil_expand_stall = 169 +DB_PERF_SEL_tl_in_fast_z_stall = 170 +DB_PERF_SEL_tl_out_xfc = 171 +DB_PERF_SEL_tl_out_squads = 172 +DB_PERF_SEL_zf_plane_multicycle = 173 +DB_PERF_SEL_PostZ_Samples_passing_Z = 174 +DB_PERF_SEL_PostZ_Samples_failing_Z = 175 +DB_PERF_SEL_PostZ_Samples_failing_S = 176 +DB_PERF_SEL_PreZ_Samples_passing_Z = 177 +DB_PERF_SEL_PreZ_Samples_failing_Z = 178 +DB_PERF_SEL_PreZ_Samples_failing_S = 179 +DB_PERF_SEL_ts_tc_update_stall = 180 +DB_PERF_SEL_sc_kick_start = 181 +DB_PERF_SEL_sc_kick_end = 182 +DB_PERF_SEL_clock_reg_active = 183 +DB_PERF_SEL_clock_main_active = 184 +DB_PERF_SEL_clock_mem_export_active = 185 +DB_PERF_SEL_esr_ps_out_busy = 186 +DB_PERF_SEL_esr_ps_lqf_busy = 187 +DB_PERF_SEL_esr_ps_lqf_stall = 188 +DB_PERF_SEL_etr_out_send = 189 +DB_PERF_SEL_etr_out_busy = 190 +DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall = 191 +DB_PERF_SEL_etr_out_cb_tile_stall = 192 +DB_PERF_SEL_etr_out_esr_stall = 193 +DB_PERF_SEL_esr_ps_sqq_busy = 194 +DB_PERF_SEL_esr_ps_sqq_stall = 195 +DB_PERF_SEL_esr_eot_fwd_busy = 196 +DB_PERF_SEL_esr_eot_fwd_holding_squad = 197 +DB_PERF_SEL_esr_eot_fwd_forward = 198 +DB_PERF_SEL_esr_sqq_zi_busy = 199 +DB_PERF_SEL_esr_sqq_zi_stall = 200 +DB_PERF_SEL_postzl_sq_pt_busy = 201 +DB_PERF_SEL_postzl_sq_pt_stall = 202 +DB_PERF_SEL_postzl_se_busy = 203 +DB_PERF_SEL_postzl_se_stall = 204 +DB_PERF_SEL_postzl_partial_launch = 205 +DB_PERF_SEL_postzl_full_launch = 206 +DB_PERF_SEL_postzl_partial_waiting = 207 +DB_PERF_SEL_postzl_tile_mem_stall = 208 +DB_PERF_SEL_postzl_tile_init_stall = 209 +DB_PERF_SEL_prezl_tile_mem_stall = 210 +DB_PERF_SEL_prezl_tile_init_stall = 211 +DB_PERF_SEL_dtt_sm_clash_stall = 212 +DB_PERF_SEL_dtt_sm_slot_stall = 213 +DB_PERF_SEL_dtt_sm_miss_stall = 214 +DB_PERF_SEL_mi_rdreq_busy = 215 +DB_PERF_SEL_mi_rdreq_stall = 216 +DB_PERF_SEL_mi_wrreq_busy = 217 +DB_PERF_SEL_mi_wrreq_stall = 218 +DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop = 219 +DB_PERF_SEL_dkg_tile_rate_tile = 220 +DB_PERF_SEL_prezl_src_in_sends = 221 +DB_PERF_SEL_prezl_src_in_stall = 222 +DB_PERF_SEL_prezl_src_in_squads = 223 +DB_PERF_SEL_prezl_src_in_squads_unrolled = 224 +DB_PERF_SEL_prezl_src_in_tile_rate = 225 +DB_PERF_SEL_prezl_src_in_tile_rate_unrolled = 226 +DB_PERF_SEL_prezl_src_out_stall = 227 +DB_PERF_SEL_postzl_src_in_sends = 228 +DB_PERF_SEL_postzl_src_in_stall = 229 +DB_PERF_SEL_postzl_src_in_squads = 230 +DB_PERF_SEL_postzl_src_in_squads_unrolled = 231 +DB_PERF_SEL_postzl_src_in_tile_rate = 232 +DB_PERF_SEL_postzl_src_in_tile_rate_unrolled = 233 +DB_PERF_SEL_postzl_src_out_stall = 234 +DB_PERF_SEL_esr_ps_src_in_sends = 235 +DB_PERF_SEL_esr_ps_src_in_stall = 236 +DB_PERF_SEL_esr_ps_src_in_squads = 237 +DB_PERF_SEL_esr_ps_src_in_squads_unrolled = 238 +DB_PERF_SEL_esr_ps_src_in_tile_rate = 239 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled = 240 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate = 241 +DB_PERF_SEL_esr_ps_src_out_stall = 242 +DB_PERF_SEL_depth_bounds_tile_culled = 243 +DB_PERF_SEL_PreZ_Samples_failing_DB = 244 +DB_PERF_SEL_PostZ_Samples_failing_DB = 245 +DB_PERF_SEL_flush_compressed = 246 +DB_PERF_SEL_flush_plane_le4 = 247 +DB_PERF_SEL_tiles_z_fully_summarized = 248 +DB_PERF_SEL_tiles_stencil_fully_summarized = 249 +DB_PERF_SEL_tiles_z_clear_on_expclear = 250 +DB_PERF_SEL_tiles_s_clear_on_expclear = 251 +DB_PERF_SEL_tiles_decomp_on_expclear = 252 +DB_PERF_SEL_tiles_compressed_to_decompressed = 253 +DB_PERF_SEL_Op_Pipe_Prez_Busy = 254 +DB_PERF_SEL_Op_Pipe_Postz_Busy = 255 +DB_PERF_SEL_di_dt_stall = 256 +DB_PERF_SEL_DB_SC_quad_lit_quad_pre_invoke = 257 +DB_PERF_SEL_DB_SC_s_tile_rate = 258 +DB_PERF_SEL_DB_SC_c_tile_rate = 259 +DB_PERF_SEL_DB_SC_z_tile_rate = 260 +Spare_261 = 261 +DB_PERF_SEL_DB_CB_lquad_export_quads = 262 +DB_PERF_SEL_DB_CB_lquad_double_format = 263 +DB_PERF_SEL_DB_CB_lquad_fast_format = 264 +DB_PERF_SEL_DB_CB_lquad_slow_format = 265 +DB_PERF_SEL_CB_DB_rdreq_sends = 266 +DB_PERF_SEL_CB_DB_rdreq_prt_sends = 267 +DB_PERF_SEL_CB_DB_wrreq_sends = 268 +DB_PERF_SEL_CB_DB_wrreq_prt_sends = 269 +DB_PERF_SEL_DB_CB_rdret_ack = 270 +DB_PERF_SEL_DB_CB_rdret_nack = 271 +DB_PERF_SEL_DB_CB_wrret_ack = 272 +DB_PERF_SEL_DB_CB_wrret_nack = 273 +DB_PERF_SEL_DFSM_Stall_opmode_change = 274 +DB_PERF_SEL_DFSM_Stall_cam_fifo = 275 +DB_PERF_SEL_DFSM_Stall_bypass_fifo = 276 +DB_PERF_SEL_DFSM_Stall_retained_tile_fifo = 277 +DB_PERF_SEL_DFSM_Stall_control_fifo = 278 +DB_PERF_SEL_DFSM_Stall_overflow_counter = 279 +DB_PERF_SEL_DFSM_Stall_pops_stall_overflow = 280 +DB_PERF_SEL_DFSM_Stall_pops_stall_self_flush = 281 +DB_PERF_SEL_DFSM_Stall_middle_output = 282 +DB_PERF_SEL_DFSM_Stall_stalling_general = 283 +Spare_285 = 284 +Spare_286 = 285 +DB_PERF_SEL_DFSM_prez_killed_squad = 286 +DB_PERF_SEL_DFSM_squads_in = 287 +DB_PERF_SEL_DFSM_full_cleared_squads_out = 288 +DB_PERF_SEL_DFSM_quads_in = 289 +DB_PERF_SEL_DFSM_fully_cleared_quads_out = 290 +DB_PERF_SEL_DFSM_lit_pixels_in = 291 +DB_PERF_SEL_DFSM_fully_cleared_pixels_out = 292 +DB_PERF_SEL_DFSM_lit_samples_in = 293 +DB_PERF_SEL_DFSM_lit_samples_out = 294 +DB_PERF_SEL_DFSM_evicted_tiles_above_watermark = 295 +DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream = 296 +DB_PERF_SEL_DFSM_stalled_by_downstream = 297 +DB_PERF_SEL_DFSM_evicted_squads_above_watermark = 298 +DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow = 299 +DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO = 300 +DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark = 301 +DB_PERF_SEL_MI_tile_req_wrack_counter_stall = 302 +DB_PERF_SEL_MI_quad_req_wrack_counter_stall = 303 +DB_PERF_SEL_MI_zpc_req_wrack_counter_stall = 304 +DB_PERF_SEL_MI_psd_req_wrack_counter_stall = 305 +DB_PERF_SEL_unmapped_z_tile_culled = 306 +DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS = 307 +DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA = 308 +DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS = 309 +DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event = 310 +DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix = 311 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix = 312 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix = 313 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix = 314 +DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending = 315 +DB_PERF_SEL_DB_CB_context_dones = 316 +DB_PERF_SEL_DB_CB_eop_dones = 317 +DB_PERF_SEL_SX_DB_quad_all_pixels_killed = 318 +DB_PERF_SEL_SX_DB_quad_all_pixels_enabled = 319 +DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read = 320 +DB_PERF_SEL_SC_DB_tile_backface = 321 +DB_PERF_SEL_SC_DB_quad_quads = 322 +DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel = 323 +DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels = 324 +DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels = 325 +DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels = 326 +DB_PERF_SEL_DFSM_Flush_flushabit = 327 +DB_PERF_SEL_DFSM_Flush_flushabit_camcoord_fifo = 328 +DB_PERF_SEL_DFSM_Flush_flushabit_passthrough = 329 +DB_PERF_SEL_DFSM_Flush_flushabit_forceflush = 330 +DB_PERF_SEL_DFSM_Flush_flushabit_nearlyfull = 331 +DB_PERF_SEL_DFSM_Flush_flushabit_primitivesinflightwatermark = 332 +DB_PERF_SEL_DFSM_Flush_flushabit_punch_stalling = 333 +DB_PERF_SEL_DFSM_Flush_flushabit_retainedtilefifo_watermark = 334 +DB_PERF_SEL_DFSM_Flush_flushabit_tilesinflightwatermark = 335 +DB_PERF_SEL_DFSM_Flush_flushall = 336 +DB_PERF_SEL_DFSM_Flush_flushall_dfsmflush = 337 +DB_PERF_SEL_DFSM_Flush_flushall_opmodechange = 338 +DB_PERF_SEL_DFSM_Flush_flushall_sampleratechange = 339 +DB_PERF_SEL_DFSM_Flush_flushall_watchdog = 340 +DB_PERF_SEL_DB_SC_quad_double_quad = 341 +DB_PERF_SEL_SX_DB_quad_export_quads = 342 +DB_PERF_SEL_SX_DB_quad_double_format = 343 +DB_PERF_SEL_SX_DB_quad_fast_format = 344 +DB_PERF_SEL_SX_DB_quad_slow_format = 345 +PerfCounter_Vals = ctypes.c_uint32 # enum + +# values for enumeration 'RingCounterControl' +RingCounterControl__enumvalues = { + 0: 'COUNTER_RING_SPLIT', + 1: 'COUNTER_RING_0', + 2: 'COUNTER_RING_1', +} +COUNTER_RING_SPLIT = 0 +COUNTER_RING_0 = 1 +COUNTER_RING_1 = 2 +RingCounterControl = ctypes.c_uint32 # enum + +# values for enumeration 'DbMemArbWatermarks' +DbMemArbWatermarks__enumvalues = { + 0: 'TRANSFERRED_64_BYTES', + 1: 'TRANSFERRED_128_BYTES', + 2: 'TRANSFERRED_256_BYTES', + 3: 'TRANSFERRED_512_BYTES', + 4: 'TRANSFERRED_1024_BYTES', + 5: 'TRANSFERRED_2048_BYTES', + 6: 'TRANSFERRED_4096_BYTES', + 7: 'TRANSFERRED_8192_BYTES', +} +TRANSFERRED_64_BYTES = 0 +TRANSFERRED_128_BYTES = 1 +TRANSFERRED_256_BYTES = 2 +TRANSFERRED_512_BYTES = 3 +TRANSFERRED_1024_BYTES = 4 +TRANSFERRED_2048_BYTES = 5 +TRANSFERRED_4096_BYTES = 6 +TRANSFERRED_8192_BYTES = 7 +DbMemArbWatermarks = ctypes.c_uint32 # enum + +# values for enumeration 'DFSMFlushEvents' +DFSMFlushEvents__enumvalues = { + 0: 'DB_FLUSH_AND_INV_DB_DATA_TS', + 1: 'DB_FLUSH_AND_INV_DB_META', + 2: 'DB_CACHE_FLUSH', + 3: 'DB_CACHE_FLUSH_TS', + 4: 'DB_CACHE_FLUSH_AND_INV_EVENT', + 5: 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', + 6: 'DB_VPORT_CHANGED_EVENT', + 7: 'DB_CONTEXT_DONE_EVENT', + 8: 'DB_BREAK_BATCH_EVENT', + 9: 'DB_PSINVOKE_CHANGE_EVENT', + 10: 'DB_CONTEXT_SUSPEND_EVENT', +} +DB_FLUSH_AND_INV_DB_DATA_TS = 0 +DB_FLUSH_AND_INV_DB_META = 1 +DB_CACHE_FLUSH = 2 +DB_CACHE_FLUSH_TS = 3 +DB_CACHE_FLUSH_AND_INV_EVENT = 4 +DB_CACHE_FLUSH_AND_INV_TS_EVENT = 5 +DB_VPORT_CHANGED_EVENT = 6 +DB_CONTEXT_DONE_EVENT = 7 +DB_BREAK_BATCH_EVENT = 8 +DB_PSINVOKE_CHANGE_EVENT = 9 +DB_CONTEXT_SUSPEND_EVENT = 10 +DFSMFlushEvents = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeCounterId' +PixelPipeCounterId__enumvalues = { + 0: 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 1: 'PIXEL_PIPE_OCCLUSION_COUNT_1', + 2: 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 3: 'PIXEL_PIPE_OCCLUSION_COUNT_3', + 4: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 5: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 6: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', + 7: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', +} +PIXEL_PIPE_OCCLUSION_COUNT_0 = 0 +PIXEL_PIPE_OCCLUSION_COUNT_1 = 1 +PIXEL_PIPE_OCCLUSION_COUNT_2 = 2 +PIXEL_PIPE_OCCLUSION_COUNT_3 = 3 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_0 = 4 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_0 = 5 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_1 = 6 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_1 = 7 +PixelPipeCounterId = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeStride' +PixelPipeStride__enumvalues = { + 0: 'PIXEL_PIPE_STRIDE_32_BITS', + 1: 'PIXEL_PIPE_STRIDE_64_BITS', + 2: 'PIXEL_PIPE_STRIDE_128_BITS', + 3: 'PIXEL_PIPE_STRIDE_256_BITS', +} +PIXEL_PIPE_STRIDE_32_BITS = 0 +PIXEL_PIPE_STRIDE_64_BITS = 1 +PIXEL_PIPE_STRIDE_128_BITS = 2 +PIXEL_PIPE_STRIDE_256_BITS = 3 +PixelPipeStride = ctypes.c_uint32 # enum + +# values for enumeration 'FullTileWaveBreak' +FullTileWaveBreak__enumvalues = { + 0: 'FULL_TILE_WAVE_BREAK_NBC_ONLY', + 1: 'FULL_TILE_WAVE_BREAK_BOTH', + 2: 'FULL_TILE_WAVE_BREAK_NONE', + 3: 'FULL_TILE_WAVE_BREAK_BC_ONLY', +} +FULL_TILE_WAVE_BREAK_NBC_ONLY = 0 +FULL_TILE_WAVE_BREAK_BOTH = 1 +FULL_TILE_WAVE_BREAK_NONE = 2 +FULL_TILE_WAVE_BREAK_BC_ONLY = 3 +FullTileWaveBreak = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BORDER_COLOR_TYPE' +TEX_BORDER_COLOR_TYPE__enumvalues = { + 0: 'TEX_BorderColor_TransparentBlack', + 1: 'TEX_BorderColor_OpaqueBlack', + 2: 'TEX_BorderColor_OpaqueWhite', + 3: 'TEX_BorderColor_Register', +} +TEX_BorderColor_TransparentBlack = 0 +TEX_BorderColor_OpaqueBlack = 1 +TEX_BorderColor_OpaqueWhite = 2 +TEX_BorderColor_Register = 3 +TEX_BORDER_COLOR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BC_SWIZZLE' +TEX_BC_SWIZZLE__enumvalues = { + 0: 'TEX_BC_Swizzle_XYZW', + 1: 'TEX_BC_Swizzle_XWYZ', + 2: 'TEX_BC_Swizzle_WZYX', + 3: 'TEX_BC_Swizzle_WXYZ', + 4: 'TEX_BC_Swizzle_ZYXW', + 5: 'TEX_BC_Swizzle_YXWZ', +} +TEX_BC_Swizzle_XYZW = 0 +TEX_BC_Swizzle_XWYZ = 1 +TEX_BC_Swizzle_WZYX = 2 +TEX_BC_Swizzle_WXYZ = 3 +TEX_BC_Swizzle_ZYXW = 4 +TEX_BC_Swizzle_YXWZ = 5 +TEX_BC_SWIZZLE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CHROMA_KEY' +TEX_CHROMA_KEY__enumvalues = { + 0: 'TEX_ChromaKey_Disabled', + 1: 'TEX_ChromaKey_Kill', + 2: 'TEX_ChromaKey_Blend', + 3: 'TEX_ChromaKey_RESERVED_3', +} +TEX_ChromaKey_Disabled = 0 +TEX_ChromaKey_Kill = 1 +TEX_ChromaKey_Blend = 2 +TEX_ChromaKey_RESERVED_3 = 3 +TEX_CHROMA_KEY = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CLAMP' +TEX_CLAMP__enumvalues = { + 0: 'TEX_Clamp_Repeat', + 1: 'TEX_Clamp_Mirror', + 2: 'TEX_Clamp_ClampToLast', + 3: 'TEX_Clamp_MirrorOnceToLast', + 4: 'TEX_Clamp_ClampHalfToBorder', + 5: 'TEX_Clamp_MirrorOnceHalfToBorder', + 6: 'TEX_Clamp_ClampToBorder', + 7: 'TEX_Clamp_MirrorOnceToBorder', +} +TEX_Clamp_Repeat = 0 +TEX_Clamp_Mirror = 1 +TEX_Clamp_ClampToLast = 2 +TEX_Clamp_MirrorOnceToLast = 3 +TEX_Clamp_ClampHalfToBorder = 4 +TEX_Clamp_MirrorOnceHalfToBorder = 5 +TEX_Clamp_ClampToBorder = 6 +TEX_Clamp_MirrorOnceToBorder = 7 +TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_COORD_TYPE' +TEX_COORD_TYPE__enumvalues = { + 0: 'TEX_CoordType_Unnormalized', + 1: 'TEX_CoordType_Normalized', +} +TEX_CoordType_Unnormalized = 0 +TEX_CoordType_Normalized = 1 +TEX_COORD_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DEPTH_COMPARE_FUNCTION' +TEX_DEPTH_COMPARE_FUNCTION__enumvalues = { + 0: 'TEX_DepthCompareFunction_Never', + 1: 'TEX_DepthCompareFunction_Less', + 2: 'TEX_DepthCompareFunction_Equal', + 3: 'TEX_DepthCompareFunction_LessEqual', + 4: 'TEX_DepthCompareFunction_Greater', + 5: 'TEX_DepthCompareFunction_NotEqual', + 6: 'TEX_DepthCompareFunction_GreaterEqual', + 7: 'TEX_DepthCompareFunction_Always', +} +TEX_DepthCompareFunction_Never = 0 +TEX_DepthCompareFunction_Less = 1 +TEX_DepthCompareFunction_Equal = 2 +TEX_DepthCompareFunction_LessEqual = 3 +TEX_DepthCompareFunction_Greater = 4 +TEX_DepthCompareFunction_NotEqual = 5 +TEX_DepthCompareFunction_GreaterEqual = 6 +TEX_DepthCompareFunction_Always = 7 +TEX_DEPTH_COMPARE_FUNCTION = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DIM' +TEX_DIM__enumvalues = { + 0: 'TEX_Dim_1D', + 1: 'TEX_Dim_2D', + 2: 'TEX_Dim_3D', + 3: 'TEX_Dim_CubeMap', + 4: 'TEX_Dim_1DArray', + 5: 'TEX_Dim_2DArray', + 6: 'TEX_Dim_2D_MSAA', + 7: 'TEX_Dim_2DArray_MSAA', +} +TEX_Dim_1D = 0 +TEX_Dim_2D = 1 +TEX_Dim_3D = 2 +TEX_Dim_CubeMap = 3 +TEX_Dim_1DArray = 4 +TEX_Dim_2DArray = 5 +TEX_Dim_2D_MSAA = 6 +TEX_Dim_2DArray_MSAA = 7 +TEX_DIM = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_FORMAT_COMP' +TEX_FORMAT_COMP__enumvalues = { + 0: 'TEX_FormatComp_Unsigned', + 1: 'TEX_FormatComp_Signed', + 2: 'TEX_FormatComp_UnsignedBiased', + 3: 'TEX_FormatComp_RESERVED_3', +} +TEX_FormatComp_Unsigned = 0 +TEX_FormatComp_Signed = 1 +TEX_FormatComp_UnsignedBiased = 2 +TEX_FormatComp_RESERVED_3 = 3 +TEX_FORMAT_COMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MAX_ANISO_RATIO' +TEX_MAX_ANISO_RATIO__enumvalues = { + 0: 'TEX_MaxAnisoRatio_1to1', + 1: 'TEX_MaxAnisoRatio_2to1', + 2: 'TEX_MaxAnisoRatio_4to1', + 3: 'TEX_MaxAnisoRatio_8to1', + 4: 'TEX_MaxAnisoRatio_16to1', + 5: 'TEX_MaxAnisoRatio_RESERVED_5', + 6: 'TEX_MaxAnisoRatio_RESERVED_6', + 7: 'TEX_MaxAnisoRatio_RESERVED_7', +} +TEX_MaxAnisoRatio_1to1 = 0 +TEX_MaxAnisoRatio_2to1 = 1 +TEX_MaxAnisoRatio_4to1 = 2 +TEX_MaxAnisoRatio_8to1 = 3 +TEX_MaxAnisoRatio_16to1 = 4 +TEX_MaxAnisoRatio_RESERVED_5 = 5 +TEX_MaxAnisoRatio_RESERVED_6 = 6 +TEX_MaxAnisoRatio_RESERVED_7 = 7 +TEX_MAX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MIP_FILTER' +TEX_MIP_FILTER__enumvalues = { + 0: 'TEX_MipFilter_None', + 1: 'TEX_MipFilter_Point', + 2: 'TEX_MipFilter_Linear', + 3: 'TEX_MipFilter_Point_Aniso_Adj', +} +TEX_MipFilter_None = 0 +TEX_MipFilter_Point = 1 +TEX_MipFilter_Linear = 2 +TEX_MipFilter_Point_Aniso_Adj = 3 +TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_REQUEST_SIZE' +TEX_REQUEST_SIZE__enumvalues = { + 0: 'TEX_RequestSize_32B', + 1: 'TEX_RequestSize_64B', + 2: 'TEX_RequestSize_128B', + 3: 'TEX_RequestSize_2X64B', +} +TEX_RequestSize_32B = 0 +TEX_RequestSize_64B = 1 +TEX_RequestSize_128B = 2 +TEX_RequestSize_2X64B = 3 +TEX_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_SAMPLER_TYPE' +TEX_SAMPLER_TYPE__enumvalues = { + 0: 'TEX_SamplerType_Invalid', + 1: 'TEX_SamplerType_Valid', +} +TEX_SamplerType_Invalid = 0 +TEX_SamplerType_Valid = 1 +TEX_SAMPLER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_XY_FILTER' +TEX_XY_FILTER__enumvalues = { + 0: 'TEX_XYFilter_Point', + 1: 'TEX_XYFilter_Linear', + 2: 'TEX_XYFilter_AnisoPoint', + 3: 'TEX_XYFilter_AnisoLinear', +} +TEX_XYFilter_Point = 0 +TEX_XYFilter_Linear = 1 +TEX_XYFilter_AnisoPoint = 2 +TEX_XYFilter_AnisoLinear = 3 +TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_Z_FILTER' +TEX_Z_FILTER__enumvalues = { + 0: 'TEX_ZFilter_None', + 1: 'TEX_ZFilter_Point', + 2: 'TEX_ZFilter_Linear', + 3: 'TEX_ZFilter_RESERVED_3', +} +TEX_ZFilter_None = 0 +TEX_ZFilter_Point = 1 +TEX_ZFilter_Linear = 2 +TEX_ZFilter_RESERVED_3 = 3 +TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_CLAMP' +VTX_CLAMP__enumvalues = { + 0: 'VTX_Clamp_ClampToZero', + 1: 'VTX_Clamp_ClampToNAN', +} +VTX_Clamp_ClampToZero = 0 +VTX_Clamp_ClampToNAN = 1 +VTX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_FETCH_TYPE' +VTX_FETCH_TYPE__enumvalues = { + 0: 'VTX_FetchType_VertexData', + 1: 'VTX_FetchType_InstanceData', + 2: 'VTX_FetchType_NoIndexOffset', + 3: 'VTX_FetchType_RESERVED_3', +} +VTX_FetchType_VertexData = 0 +VTX_FetchType_InstanceData = 1 +VTX_FetchType_NoIndexOffset = 2 +VTX_FetchType_RESERVED_3 = 3 +VTX_FETCH_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_FORMAT_COMP_ALL' +VTX_FORMAT_COMP_ALL__enumvalues = { + 0: 'VTX_FormatCompAll_Unsigned', + 1: 'VTX_FormatCompAll_Signed', +} +VTX_FormatCompAll_Unsigned = 0 +VTX_FormatCompAll_Signed = 1 +VTX_FORMAT_COMP_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_MEM_REQUEST_SIZE' +VTX_MEM_REQUEST_SIZE__enumvalues = { + 0: 'VTX_MemRequestSize_32B', + 1: 'VTX_MemRequestSize_64B', +} +VTX_MemRequestSize_32B = 0 +VTX_MemRequestSize_64B = 1 +VTX_MEM_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_DATA_FORMAT' +TVX_DATA_FORMAT__enumvalues = { + 0: 'TVX_FMT_INVALID', + 1: 'TVX_FMT_8', + 2: 'TVX_FMT_4_4', + 3: 'TVX_FMT_3_3_2', + 4: 'TVX_FMT_RESERVED_4', + 5: 'TVX_FMT_16', + 6: 'TVX_FMT_16_FLOAT', + 7: 'TVX_FMT_8_8', + 8: 'TVX_FMT_5_6_5', + 9: 'TVX_FMT_6_5_5', + 10: 'TVX_FMT_1_5_5_5', + 11: 'TVX_FMT_4_4_4_4', + 12: 'TVX_FMT_5_5_5_1', + 13: 'TVX_FMT_32', + 14: 'TVX_FMT_32_FLOAT', + 15: 'TVX_FMT_16_16', + 16: 'TVX_FMT_16_16_FLOAT', + 17: 'TVX_FMT_8_24', + 18: 'TVX_FMT_8_24_FLOAT', + 19: 'TVX_FMT_24_8', + 20: 'TVX_FMT_24_8_FLOAT', + 21: 'TVX_FMT_10_11_11', + 22: 'TVX_FMT_10_11_11_FLOAT', + 23: 'TVX_FMT_11_11_10', + 24: 'TVX_FMT_11_11_10_FLOAT', + 25: 'TVX_FMT_2_10_10_10', + 26: 'TVX_FMT_8_8_8_8', + 27: 'TVX_FMT_10_10_10_2', + 28: 'TVX_FMT_X24_8_32_FLOAT', + 29: 'TVX_FMT_32_32', + 30: 'TVX_FMT_32_32_FLOAT', + 31: 'TVX_FMT_16_16_16_16', + 32: 'TVX_FMT_16_16_16_16_FLOAT', + 33: 'TVX_FMT_RESERVED_33', + 34: 'TVX_FMT_32_32_32_32', + 35: 'TVX_FMT_32_32_32_32_FLOAT', + 36: 'TVX_FMT_RESERVED_36', + 37: 'TVX_FMT_1', + 38: 'TVX_FMT_1_REVERSED', + 39: 'TVX_FMT_GB_GR', + 40: 'TVX_FMT_BG_RG', + 41: 'TVX_FMT_32_AS_8', + 42: 'TVX_FMT_32_AS_8_8', + 43: 'TVX_FMT_5_9_9_9_SHAREDEXP', + 44: 'TVX_FMT_8_8_8', + 45: 'TVX_FMT_16_16_16', + 46: 'TVX_FMT_16_16_16_FLOAT', + 47: 'TVX_FMT_32_32_32', + 48: 'TVX_FMT_32_32_32_FLOAT', + 49: 'TVX_FMT_BC1', + 50: 'TVX_FMT_BC2', + 51: 'TVX_FMT_BC3', + 52: 'TVX_FMT_BC4', + 53: 'TVX_FMT_BC5', + 54: 'TVX_FMT_APC0', + 55: 'TVX_FMT_APC1', + 56: 'TVX_FMT_APC2', + 57: 'TVX_FMT_APC3', + 58: 'TVX_FMT_APC4', + 59: 'TVX_FMT_APC5', + 60: 'TVX_FMT_APC6', + 61: 'TVX_FMT_APC7', + 62: 'TVX_FMT_CTX1', + 63: 'TVX_FMT_RESERVED_63', +} +TVX_FMT_INVALID = 0 +TVX_FMT_8 = 1 +TVX_FMT_4_4 = 2 +TVX_FMT_3_3_2 = 3 +TVX_FMT_RESERVED_4 = 4 +TVX_FMT_16 = 5 +TVX_FMT_16_FLOAT = 6 +TVX_FMT_8_8 = 7 +TVX_FMT_5_6_5 = 8 +TVX_FMT_6_5_5 = 9 +TVX_FMT_1_5_5_5 = 10 +TVX_FMT_4_4_4_4 = 11 +TVX_FMT_5_5_5_1 = 12 +TVX_FMT_32 = 13 +TVX_FMT_32_FLOAT = 14 +TVX_FMT_16_16 = 15 +TVX_FMT_16_16_FLOAT = 16 +TVX_FMT_8_24 = 17 +TVX_FMT_8_24_FLOAT = 18 +TVX_FMT_24_8 = 19 +TVX_FMT_24_8_FLOAT = 20 +TVX_FMT_10_11_11 = 21 +TVX_FMT_10_11_11_FLOAT = 22 +TVX_FMT_11_11_10 = 23 +TVX_FMT_11_11_10_FLOAT = 24 +TVX_FMT_2_10_10_10 = 25 +TVX_FMT_8_8_8_8 = 26 +TVX_FMT_10_10_10_2 = 27 +TVX_FMT_X24_8_32_FLOAT = 28 +TVX_FMT_32_32 = 29 +TVX_FMT_32_32_FLOAT = 30 +TVX_FMT_16_16_16_16 = 31 +TVX_FMT_16_16_16_16_FLOAT = 32 +TVX_FMT_RESERVED_33 = 33 +TVX_FMT_32_32_32_32 = 34 +TVX_FMT_32_32_32_32_FLOAT = 35 +TVX_FMT_RESERVED_36 = 36 +TVX_FMT_1 = 37 +TVX_FMT_1_REVERSED = 38 +TVX_FMT_GB_GR = 39 +TVX_FMT_BG_RG = 40 +TVX_FMT_32_AS_8 = 41 +TVX_FMT_32_AS_8_8 = 42 +TVX_FMT_5_9_9_9_SHAREDEXP = 43 +TVX_FMT_8_8_8 = 44 +TVX_FMT_16_16_16 = 45 +TVX_FMT_16_16_16_FLOAT = 46 +TVX_FMT_32_32_32 = 47 +TVX_FMT_32_32_32_FLOAT = 48 +TVX_FMT_BC1 = 49 +TVX_FMT_BC2 = 50 +TVX_FMT_BC3 = 51 +TVX_FMT_BC4 = 52 +TVX_FMT_BC5 = 53 +TVX_FMT_APC0 = 54 +TVX_FMT_APC1 = 55 +TVX_FMT_APC2 = 56 +TVX_FMT_APC3 = 57 +TVX_FMT_APC4 = 58 +TVX_FMT_APC5 = 59 +TVX_FMT_APC6 = 60 +TVX_FMT_APC7 = 61 +TVX_FMT_CTX1 = 62 +TVX_FMT_RESERVED_63 = 63 +TVX_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_DST_SEL' +TVX_DST_SEL__enumvalues = { + 0: 'TVX_DstSel_X', + 1: 'TVX_DstSel_Y', + 2: 'TVX_DstSel_Z', + 3: 'TVX_DstSel_W', + 4: 'TVX_DstSel_0f', + 5: 'TVX_DstSel_1f', + 6: 'TVX_DstSel_RESERVED_6', + 7: 'TVX_DstSel_Mask', +} +TVX_DstSel_X = 0 +TVX_DstSel_Y = 1 +TVX_DstSel_Z = 2 +TVX_DstSel_W = 3 +TVX_DstSel_0f = 4 +TVX_DstSel_1f = 5 +TVX_DstSel_RESERVED_6 = 6 +TVX_DstSel_Mask = 7 +TVX_DST_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_ENDIAN_SWAP' +TVX_ENDIAN_SWAP__enumvalues = { + 0: 'TVX_EndianSwap_None', + 1: 'TVX_EndianSwap_8in16', + 2: 'TVX_EndianSwap_8in32', + 3: 'TVX_EndianSwap_8in64', +} +TVX_EndianSwap_None = 0 +TVX_EndianSwap_8in16 = 1 +TVX_EndianSwap_8in32 = 2 +TVX_EndianSwap_8in64 = 3 +TVX_ENDIAN_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_INST' +TVX_INST__enumvalues = { + 0: 'TVX_Inst_NormalVertexFetch', + 1: 'TVX_Inst_SemanticVertexFetch', + 2: 'TVX_Inst_RESERVED_2', + 3: 'TVX_Inst_LD', + 4: 'TVX_Inst_GetTextureResInfo', + 5: 'TVX_Inst_GetNumberOfSamples', + 6: 'TVX_Inst_GetLOD', + 7: 'TVX_Inst_GetGradientsH', + 8: 'TVX_Inst_GetGradientsV', + 9: 'TVX_Inst_SetTextureOffsets', + 10: 'TVX_Inst_KeepGradients', + 11: 'TVX_Inst_SetGradientsH', + 12: 'TVX_Inst_SetGradientsV', + 13: 'TVX_Inst_Pass', + 14: 'TVX_Inst_GetBufferResInfo', + 15: 'TVX_Inst_RESERVED_15', + 16: 'TVX_Inst_Sample', + 17: 'TVX_Inst_Sample_L', + 18: 'TVX_Inst_Sample_LB', + 19: 'TVX_Inst_Sample_LZ', + 20: 'TVX_Inst_Sample_G', + 21: 'TVX_Inst_Gather4', + 22: 'TVX_Inst_Sample_G_LB', + 23: 'TVX_Inst_Gather4_O', + 24: 'TVX_Inst_Sample_C', + 25: 'TVX_Inst_Sample_C_L', + 26: 'TVX_Inst_Sample_C_LB', + 27: 'TVX_Inst_Sample_C_LZ', + 28: 'TVX_Inst_Sample_C_G', + 29: 'TVX_Inst_Gather4_C', + 30: 'TVX_Inst_Sample_C_G_LB', + 31: 'TVX_Inst_Gather4_C_O', +} +TVX_Inst_NormalVertexFetch = 0 +TVX_Inst_SemanticVertexFetch = 1 +TVX_Inst_RESERVED_2 = 2 +TVX_Inst_LD = 3 +TVX_Inst_GetTextureResInfo = 4 +TVX_Inst_GetNumberOfSamples = 5 +TVX_Inst_GetLOD = 6 +TVX_Inst_GetGradientsH = 7 +TVX_Inst_GetGradientsV = 8 +TVX_Inst_SetTextureOffsets = 9 +TVX_Inst_KeepGradients = 10 +TVX_Inst_SetGradientsH = 11 +TVX_Inst_SetGradientsV = 12 +TVX_Inst_Pass = 13 +TVX_Inst_GetBufferResInfo = 14 +TVX_Inst_RESERVED_15 = 15 +TVX_Inst_Sample = 16 +TVX_Inst_Sample_L = 17 +TVX_Inst_Sample_LB = 18 +TVX_Inst_Sample_LZ = 19 +TVX_Inst_Sample_G = 20 +TVX_Inst_Gather4 = 21 +TVX_Inst_Sample_G_LB = 22 +TVX_Inst_Gather4_O = 23 +TVX_Inst_Sample_C = 24 +TVX_Inst_Sample_C_L = 25 +TVX_Inst_Sample_C_LB = 26 +TVX_Inst_Sample_C_LZ = 27 +TVX_Inst_Sample_C_G = 28 +TVX_Inst_Gather4_C = 29 +TVX_Inst_Sample_C_G_LB = 30 +TVX_Inst_Gather4_C_O = 31 +TVX_INST = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_NUM_FORMAT_ALL' +TVX_NUM_FORMAT_ALL__enumvalues = { + 0: 'TVX_NumFormatAll_Norm', + 1: 'TVX_NumFormatAll_Int', + 2: 'TVX_NumFormatAll_Scaled', + 3: 'TVX_NumFormatAll_RESERVED_3', +} +TVX_NumFormatAll_Norm = 0 +TVX_NumFormatAll_Int = 1 +TVX_NumFormatAll_Scaled = 2 +TVX_NumFormatAll_RESERVED_3 = 3 +TVX_NUM_FORMAT_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_SRC_SEL' +TVX_SRC_SEL__enumvalues = { + 0: 'TVX_SrcSel_X', + 1: 'TVX_SrcSel_Y', + 2: 'TVX_SrcSel_Z', + 3: 'TVX_SrcSel_W', + 4: 'TVX_SrcSel_0f', + 5: 'TVX_SrcSel_1f', +} +TVX_SrcSel_X = 0 +TVX_SrcSel_Y = 1 +TVX_SrcSel_Z = 2 +TVX_SrcSel_W = 3 +TVX_SrcSel_0f = 4 +TVX_SrcSel_1f = 5 +TVX_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_SRF_MODE_ALL' +TVX_SRF_MODE_ALL__enumvalues = { + 0: 'TVX_SRFModeAll_ZCMO', + 1: 'TVX_SRFModeAll_NZ', +} +TVX_SRFModeAll_ZCMO = 0 +TVX_SRFModeAll_NZ = 1 +TVX_SRF_MODE_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_TYPE' +TVX_TYPE__enumvalues = { + 0: 'TVX_Type_InvalidTextureResource', + 1: 'TVX_Type_InvalidVertexBuffer', + 2: 'TVX_Type_ValidTextureResource', + 3: 'TVX_Type_ValidVertexBuffer', +} +TVX_Type_InvalidTextureResource = 0 +TVX_Type_InvalidVertexBuffer = 1 +TVX_Type_ValidTextureResource = 2 +TVX_Type_ValidVertexBuffer = 3 +TVX_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PH_PERFCNT_SEL' +PH_PERFCNT_SEL__enumvalues = { + 0: 'PH_SC0_SRPS_WINDOW_VALID', + 1: 'PH_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 2: 'PH_SC0_ARB_XFC_ONLY_PRIM_CYCLES', + 3: 'PH_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 4: 'PH_SC0_ARB_STALLED_FROM_BELOW', + 5: 'PH_SC0_ARB_STARVED_FROM_ABOVE', + 6: 'PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 7: 'PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 8: 'PH_SC0_ARB_BUSY', + 9: 'PH_SC0_ARB_PA_BUSY_SOP', + 10: 'PH_SC0_ARB_EOP_POP_SYNC_POP', + 11: 'PH_SC0_ARB_EVENT_SYNC_POP', + 12: 'PH_SC0_PS_ENG_MULTICYCLE_BUBBLE', + 13: 'PH_SC0_EOP_SYNC_WINDOW', + 14: 'PH_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', + 15: 'PH_SC0_BUSY_CNT_NOT_ZERO', + 16: 'PH_SC0_SEND', + 17: 'PH_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 18: 'PH_SC0_CREDIT_AT_MAX', + 19: 'PH_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 20: 'PH_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 21: 'PH_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 22: 'PH_SC0_GFX_PIPE0_TO_1_TRANSITION', + 23: 'PH_SC0_GFX_PIPE1_TO_0_TRANSITION', + 24: 'PH_SC0_PA0_DATA_FIFO_RD', + 25: 'PH_SC0_PA0_DATA_FIFO_WE', + 26: 'PH_SC0_PA0_FIFO_EMPTY', + 27: 'PH_SC0_PA0_FIFO_FULL', + 28: 'PH_SC0_PA0_NULL_WE', + 29: 'PH_SC0_PA0_EVENT_WE', + 30: 'PH_SC0_PA0_FPOV_WE', + 31: 'PH_SC0_PA0_LPOV_WE', + 32: 'PH_SC0_PA0_EOP_WE', + 33: 'PH_SC0_PA0_DATA_FIFO_EOP_RD', + 34: 'PH_SC0_PA0_EOPG_WE', + 35: 'PH_SC0_PA0_DEALLOC_4_0_RD', + 36: 'PH_SC0_PA1_DATA_FIFO_RD', + 37: 'PH_SC0_PA1_DATA_FIFO_WE', + 38: 'PH_SC0_PA1_FIFO_EMPTY', + 39: 'PH_SC0_PA1_FIFO_FULL', + 40: 'PH_SC0_PA1_NULL_WE', + 41: 'PH_SC0_PA1_EVENT_WE', + 42: 'PH_SC0_PA1_FPOV_WE', + 43: 'PH_SC0_PA1_LPOV_WE', + 44: 'PH_SC0_PA1_EOP_WE', + 45: 'PH_SC0_PA1_DATA_FIFO_EOP_RD', + 46: 'PH_SC0_PA1_EOPG_WE', + 47: 'PH_SC0_PA1_DEALLOC_4_0_RD', + 48: 'PH_SC0_PA2_DATA_FIFO_RD', + 49: 'PH_SC0_PA2_DATA_FIFO_WE', + 50: 'PH_SC0_PA2_FIFO_EMPTY', + 51: 'PH_SC0_PA2_FIFO_FULL', + 52: 'PH_SC0_PA2_NULL_WE', + 53: 'PH_SC0_PA2_EVENT_WE', + 54: 'PH_SC0_PA2_FPOV_WE', + 55: 'PH_SC0_PA2_LPOV_WE', + 56: 'PH_SC0_PA2_EOP_WE', + 57: 'PH_SC0_PA2_DATA_FIFO_EOP_RD', + 58: 'PH_SC0_PA2_EOPG_WE', + 59: 'PH_SC0_PA2_DEALLOC_4_0_RD', + 60: 'PH_SC0_PA3_DATA_FIFO_RD', + 61: 'PH_SC0_PA3_DATA_FIFO_WE', + 62: 'PH_SC0_PA3_FIFO_EMPTY', + 63: 'PH_SC0_PA3_FIFO_FULL', + 64: 'PH_SC0_PA3_NULL_WE', + 65: 'PH_SC0_PA3_EVENT_WE', + 66: 'PH_SC0_PA3_FPOV_WE', + 67: 'PH_SC0_PA3_LPOV_WE', + 68: 'PH_SC0_PA3_EOP_WE', + 69: 'PH_SC0_PA3_DATA_FIFO_EOP_RD', + 70: 'PH_SC0_PA3_EOPG_WE', + 71: 'PH_SC0_PA3_DEALLOC_4_0_RD', + 72: 'PH_SC0_PA4_DATA_FIFO_RD', + 73: 'PH_SC0_PA4_DATA_FIFO_WE', + 74: 'PH_SC0_PA4_FIFO_EMPTY', + 75: 'PH_SC0_PA4_FIFO_FULL', + 76: 'PH_SC0_PA4_NULL_WE', + 77: 'PH_SC0_PA4_EVENT_WE', + 78: 'PH_SC0_PA4_FPOV_WE', + 79: 'PH_SC0_PA4_LPOV_WE', + 80: 'PH_SC0_PA4_EOP_WE', + 81: 'PH_SC0_PA4_DATA_FIFO_EOP_RD', + 82: 'PH_SC0_PA4_EOPG_WE', + 83: 'PH_SC0_PA4_DEALLOC_4_0_RD', + 84: 'PH_SC0_PA5_DATA_FIFO_RD', + 85: 'PH_SC0_PA5_DATA_FIFO_WE', + 86: 'PH_SC0_PA5_FIFO_EMPTY', + 87: 'PH_SC0_PA5_FIFO_FULL', + 88: 'PH_SC0_PA5_NULL_WE', + 89: 'PH_SC0_PA5_EVENT_WE', + 90: 'PH_SC0_PA5_FPOV_WE', + 91: 'PH_SC0_PA5_LPOV_WE', + 92: 'PH_SC0_PA5_EOP_WE', + 93: 'PH_SC0_PA5_DATA_FIFO_EOP_RD', + 94: 'PH_SC0_PA5_EOPG_WE', + 95: 'PH_SC0_PA5_DEALLOC_4_0_RD', + 96: 'PH_SC0_PA6_DATA_FIFO_RD', + 97: 'PH_SC0_PA6_DATA_FIFO_WE', + 98: 'PH_SC0_PA6_FIFO_EMPTY', + 99: 'PH_SC0_PA6_FIFO_FULL', + 100: 'PH_SC0_PA6_NULL_WE', + 101: 'PH_SC0_PA6_EVENT_WE', + 102: 'PH_SC0_PA6_FPOV_WE', + 103: 'PH_SC0_PA6_LPOV_WE', + 104: 'PH_SC0_PA6_EOP_WE', + 105: 'PH_SC0_PA6_DATA_FIFO_EOP_RD', + 106: 'PH_SC0_PA6_EOPG_WE', + 107: 'PH_SC0_PA6_DEALLOC_4_0_RD', + 108: 'PH_SC0_PA7_DATA_FIFO_RD', + 109: 'PH_SC0_PA7_DATA_FIFO_WE', + 110: 'PH_SC0_PA7_FIFO_EMPTY', + 111: 'PH_SC0_PA7_FIFO_FULL', + 112: 'PH_SC0_PA7_NULL_WE', + 113: 'PH_SC0_PA7_EVENT_WE', + 114: 'PH_SC0_PA7_FPOV_WE', + 115: 'PH_SC0_PA7_LPOV_WE', + 116: 'PH_SC0_PA7_EOP_WE', + 117: 'PH_SC0_PA7_DATA_FIFO_EOP_RD', + 118: 'PH_SC0_PA7_EOPG_WE', + 119: 'PH_SC0_PA7_DEALLOC_4_0_RD', + 120: 'PH_SC1_SRPS_WINDOW_VALID', + 121: 'PH_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 122: 'PH_SC1_ARB_XFC_ONLY_PRIM_CYCLES', + 123: 'PH_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 124: 'PH_SC1_ARB_STALLED_FROM_BELOW', + 125: 'PH_SC1_ARB_STARVED_FROM_ABOVE', + 126: 'PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 127: 'PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 128: 'PH_SC1_ARB_BUSY', + 129: 'PH_SC1_ARB_PA_BUSY_SOP', + 130: 'PH_SC1_ARB_EOP_POP_SYNC_POP', + 131: 'PH_SC1_ARB_EVENT_SYNC_POP', + 132: 'PH_SC1_PS_ENG_MULTICYCLE_BUBBLE', + 133: 'PH_SC1_EOP_SYNC_WINDOW', + 134: 'PH_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', + 135: 'PH_SC1_BUSY_CNT_NOT_ZERO', + 136: 'PH_SC1_SEND', + 137: 'PH_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 138: 'PH_SC1_CREDIT_AT_MAX', + 139: 'PH_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 140: 'PH_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 141: 'PH_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 142: 'PH_SC1_GFX_PIPE0_TO_1_TRANSITION', + 143: 'PH_SC1_GFX_PIPE1_TO_0_TRANSITION', + 144: 'PH_SC1_PA0_DATA_FIFO_RD', + 145: 'PH_SC1_PA0_DATA_FIFO_WE', + 146: 'PH_SC1_PA0_FIFO_EMPTY', + 147: 'PH_SC1_PA0_FIFO_FULL', + 148: 'PH_SC1_PA0_NULL_WE', + 149: 'PH_SC1_PA0_EVENT_WE', + 150: 'PH_SC1_PA0_FPOV_WE', + 151: 'PH_SC1_PA0_LPOV_WE', + 152: 'PH_SC1_PA0_EOP_WE', + 153: 'PH_SC1_PA0_DATA_FIFO_EOP_RD', + 154: 'PH_SC1_PA0_EOPG_WE', + 155: 'PH_SC1_PA0_DEALLOC_4_0_RD', + 156: 'PH_SC1_PA1_DATA_FIFO_RD', + 157: 'PH_SC1_PA1_DATA_FIFO_WE', + 158: 'PH_SC1_PA1_FIFO_EMPTY', + 159: 'PH_SC1_PA1_FIFO_FULL', + 160: 'PH_SC1_PA1_NULL_WE', + 161: 'PH_SC1_PA1_EVENT_WE', + 162: 'PH_SC1_PA1_FPOV_WE', + 163: 'PH_SC1_PA1_LPOV_WE', + 164: 'PH_SC1_PA1_EOP_WE', + 165: 'PH_SC1_PA1_DATA_FIFO_EOP_RD', + 166: 'PH_SC1_PA1_EOPG_WE', + 167: 'PH_SC1_PA1_DEALLOC_4_0_RD', + 168: 'PH_SC1_PA2_DATA_FIFO_RD', + 169: 'PH_SC1_PA2_DATA_FIFO_WE', + 170: 'PH_SC1_PA2_FIFO_EMPTY', + 171: 'PH_SC1_PA2_FIFO_FULL', + 172: 'PH_SC1_PA2_NULL_WE', + 173: 'PH_SC1_PA2_EVENT_WE', + 174: 'PH_SC1_PA2_FPOV_WE', + 175: 'PH_SC1_PA2_LPOV_WE', + 176: 'PH_SC1_PA2_EOP_WE', + 177: 'PH_SC1_PA2_DATA_FIFO_EOP_RD', + 178: 'PH_SC1_PA2_EOPG_WE', + 179: 'PH_SC1_PA2_DEALLOC_4_0_RD', + 180: 'PH_SC1_PA3_DATA_FIFO_RD', + 181: 'PH_SC1_PA3_DATA_FIFO_WE', + 182: 'PH_SC1_PA3_FIFO_EMPTY', + 183: 'PH_SC1_PA3_FIFO_FULL', + 184: 'PH_SC1_PA3_NULL_WE', + 185: 'PH_SC1_PA3_EVENT_WE', + 186: 'PH_SC1_PA3_FPOV_WE', + 187: 'PH_SC1_PA3_LPOV_WE', + 188: 'PH_SC1_PA3_EOP_WE', + 189: 'PH_SC1_PA3_DATA_FIFO_EOP_RD', + 190: 'PH_SC1_PA3_EOPG_WE', + 191: 'PH_SC1_PA3_DEALLOC_4_0_RD', + 192: 'PH_SC1_PA4_DATA_FIFO_RD', + 193: 'PH_SC1_PA4_DATA_FIFO_WE', + 194: 'PH_SC1_PA4_FIFO_EMPTY', + 195: 'PH_SC1_PA4_FIFO_FULL', + 196: 'PH_SC1_PA4_NULL_WE', + 197: 'PH_SC1_PA4_EVENT_WE', + 198: 'PH_SC1_PA4_FPOV_WE', + 199: 'PH_SC1_PA4_LPOV_WE', + 200: 'PH_SC1_PA4_EOP_WE', + 201: 'PH_SC1_PA4_DATA_FIFO_EOP_RD', + 202: 'PH_SC1_PA4_EOPG_WE', + 203: 'PH_SC1_PA4_DEALLOC_4_0_RD', + 204: 'PH_SC1_PA5_DATA_FIFO_RD', + 205: 'PH_SC1_PA5_DATA_FIFO_WE', + 206: 'PH_SC1_PA5_FIFO_EMPTY', + 207: 'PH_SC1_PA5_FIFO_FULL', + 208: 'PH_SC1_PA5_NULL_WE', + 209: 'PH_SC1_PA5_EVENT_WE', + 210: 'PH_SC1_PA5_FPOV_WE', + 211: 'PH_SC1_PA5_LPOV_WE', + 212: 'PH_SC1_PA5_EOP_WE', + 213: 'PH_SC1_PA5_DATA_FIFO_EOP_RD', + 214: 'PH_SC1_PA5_EOPG_WE', + 215: 'PH_SC1_PA5_DEALLOC_4_0_RD', + 216: 'PH_SC1_PA6_DATA_FIFO_RD', + 217: 'PH_SC1_PA6_DATA_FIFO_WE', + 218: 'PH_SC1_PA6_FIFO_EMPTY', + 219: 'PH_SC1_PA6_FIFO_FULL', + 220: 'PH_SC1_PA6_NULL_WE', + 221: 'PH_SC1_PA6_EVENT_WE', + 222: 'PH_SC1_PA6_FPOV_WE', + 223: 'PH_SC1_PA6_LPOV_WE', + 224: 'PH_SC1_PA6_EOP_WE', + 225: 'PH_SC1_PA6_DATA_FIFO_EOP_RD', + 226: 'PH_SC1_PA6_EOPG_WE', + 227: 'PH_SC1_PA6_DEALLOC_4_0_RD', + 228: 'PH_SC1_PA7_DATA_FIFO_RD', + 229: 'PH_SC1_PA7_DATA_FIFO_WE', + 230: 'PH_SC1_PA7_FIFO_EMPTY', + 231: 'PH_SC1_PA7_FIFO_FULL', + 232: 'PH_SC1_PA7_NULL_WE', + 233: 'PH_SC1_PA7_EVENT_WE', + 234: 'PH_SC1_PA7_FPOV_WE', + 235: 'PH_SC1_PA7_LPOV_WE', + 236: 'PH_SC1_PA7_EOP_WE', + 237: 'PH_SC1_PA7_DATA_FIFO_EOP_RD', + 238: 'PH_SC1_PA7_EOPG_WE', + 239: 'PH_SC1_PA7_DEALLOC_4_0_RD', + 240: 'PH_SC2_SRPS_WINDOW_VALID', + 241: 'PH_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 242: 'PH_SC2_ARB_XFC_ONLY_PRIM_CYCLES', + 243: 'PH_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 244: 'PH_SC2_ARB_STALLED_FROM_BELOW', + 245: 'PH_SC2_ARB_STARVED_FROM_ABOVE', + 246: 'PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 247: 'PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 248: 'PH_SC2_ARB_BUSY', + 249: 'PH_SC2_ARB_PA_BUSY_SOP', + 250: 'PH_SC2_ARB_EOP_POP_SYNC_POP', + 251: 'PH_SC2_ARB_EVENT_SYNC_POP', + 252: 'PH_SC2_PS_ENG_MULTICYCLE_BUBBLE', + 253: 'PH_SC2_EOP_SYNC_WINDOW', + 254: 'PH_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', + 255: 'PH_SC2_BUSY_CNT_NOT_ZERO', + 256: 'PH_SC2_SEND', + 257: 'PH_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 258: 'PH_SC2_CREDIT_AT_MAX', + 259: 'PH_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 260: 'PH_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 261: 'PH_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 262: 'PH_SC2_GFX_PIPE0_TO_1_TRANSITION', + 263: 'PH_SC2_GFX_PIPE1_TO_0_TRANSITION', + 264: 'PH_SC2_PA0_DATA_FIFO_RD', + 265: 'PH_SC2_PA0_DATA_FIFO_WE', + 266: 'PH_SC2_PA0_FIFO_EMPTY', + 267: 'PH_SC2_PA0_FIFO_FULL', + 268: 'PH_SC2_PA0_NULL_WE', + 269: 'PH_SC2_PA0_EVENT_WE', + 270: 'PH_SC2_PA0_FPOV_WE', + 271: 'PH_SC2_PA0_LPOV_WE', + 272: 'PH_SC2_PA0_EOP_WE', + 273: 'PH_SC2_PA0_DATA_FIFO_EOP_RD', + 274: 'PH_SC2_PA0_EOPG_WE', + 275: 'PH_SC2_PA0_DEALLOC_4_0_RD', + 276: 'PH_SC2_PA1_DATA_FIFO_RD', + 277: 'PH_SC2_PA1_DATA_FIFO_WE', + 278: 'PH_SC2_PA1_FIFO_EMPTY', + 279: 'PH_SC2_PA1_FIFO_FULL', + 280: 'PH_SC2_PA1_NULL_WE', + 281: 'PH_SC2_PA1_EVENT_WE', + 282: 'PH_SC2_PA1_FPOV_WE', + 283: 'PH_SC2_PA1_LPOV_WE', + 284: 'PH_SC2_PA1_EOP_WE', + 285: 'PH_SC2_PA1_DATA_FIFO_EOP_RD', + 286: 'PH_SC2_PA1_EOPG_WE', + 287: 'PH_SC2_PA1_DEALLOC_4_0_RD', + 288: 'PH_SC2_PA2_DATA_FIFO_RD', + 289: 'PH_SC2_PA2_DATA_FIFO_WE', + 290: 'PH_SC2_PA2_FIFO_EMPTY', + 291: 'PH_SC2_PA2_FIFO_FULL', + 292: 'PH_SC2_PA2_NULL_WE', + 293: 'PH_SC2_PA2_EVENT_WE', + 294: 'PH_SC2_PA2_FPOV_WE', + 295: 'PH_SC2_PA2_LPOV_WE', + 296: 'PH_SC2_PA2_EOP_WE', + 297: 'PH_SC2_PA2_DATA_FIFO_EOP_RD', + 298: 'PH_SC2_PA2_EOPG_WE', + 299: 'PH_SC2_PA2_DEALLOC_4_0_RD', + 300: 'PH_SC2_PA3_DATA_FIFO_RD', + 301: 'PH_SC2_PA3_DATA_FIFO_WE', + 302: 'PH_SC2_PA3_FIFO_EMPTY', + 303: 'PH_SC2_PA3_FIFO_FULL', + 304: 'PH_SC2_PA3_NULL_WE', + 305: 'PH_SC2_PA3_EVENT_WE', + 306: 'PH_SC2_PA3_FPOV_WE', + 307: 'PH_SC2_PA3_LPOV_WE', + 308: 'PH_SC2_PA3_EOP_WE', + 309: 'PH_SC2_PA3_DATA_FIFO_EOP_RD', + 310: 'PH_SC2_PA3_EOPG_WE', + 311: 'PH_SC2_PA3_DEALLOC_4_0_RD', + 312: 'PH_SC2_PA4_DATA_FIFO_RD', + 313: 'PH_SC2_PA4_DATA_FIFO_WE', + 314: 'PH_SC2_PA4_FIFO_EMPTY', + 315: 'PH_SC2_PA4_FIFO_FULL', + 316: 'PH_SC2_PA4_NULL_WE', + 317: 'PH_SC2_PA4_EVENT_WE', + 318: 'PH_SC2_PA4_FPOV_WE', + 319: 'PH_SC2_PA4_LPOV_WE', + 320: 'PH_SC2_PA4_EOP_WE', + 321: 'PH_SC2_PA4_DATA_FIFO_EOP_RD', + 322: 'PH_SC2_PA4_EOPG_WE', + 323: 'PH_SC2_PA4_DEALLOC_4_0_RD', + 324: 'PH_SC2_PA5_DATA_FIFO_RD', + 325: 'PH_SC2_PA5_DATA_FIFO_WE', + 326: 'PH_SC2_PA5_FIFO_EMPTY', + 327: 'PH_SC2_PA5_FIFO_FULL', + 328: 'PH_SC2_PA5_NULL_WE', + 329: 'PH_SC2_PA5_EVENT_WE', + 330: 'PH_SC2_PA5_FPOV_WE', + 331: 'PH_SC2_PA5_LPOV_WE', + 332: 'PH_SC2_PA5_EOP_WE', + 333: 'PH_SC2_PA5_DATA_FIFO_EOP_RD', + 334: 'PH_SC2_PA5_EOPG_WE', + 335: 'PH_SC2_PA5_DEALLOC_4_0_RD', + 336: 'PH_SC2_PA6_DATA_FIFO_RD', + 337: 'PH_SC2_PA6_DATA_FIFO_WE', + 338: 'PH_SC2_PA6_FIFO_EMPTY', + 339: 'PH_SC2_PA6_FIFO_FULL', + 340: 'PH_SC2_PA6_NULL_WE', + 341: 'PH_SC2_PA6_EVENT_WE', + 342: 'PH_SC2_PA6_FPOV_WE', + 343: 'PH_SC2_PA6_LPOV_WE', + 344: 'PH_SC2_PA6_EOP_WE', + 345: 'PH_SC2_PA6_DATA_FIFO_EOP_RD', + 346: 'PH_SC2_PA6_EOPG_WE', + 347: 'PH_SC2_PA6_DEALLOC_4_0_RD', + 348: 'PH_SC2_PA7_DATA_FIFO_RD', + 349: 'PH_SC2_PA7_DATA_FIFO_WE', + 350: 'PH_SC2_PA7_FIFO_EMPTY', + 351: 'PH_SC2_PA7_FIFO_FULL', + 352: 'PH_SC2_PA7_NULL_WE', + 353: 'PH_SC2_PA7_EVENT_WE', + 354: 'PH_SC2_PA7_FPOV_WE', + 355: 'PH_SC2_PA7_LPOV_WE', + 356: 'PH_SC2_PA7_EOP_WE', + 357: 'PH_SC2_PA7_DATA_FIFO_EOP_RD', + 358: 'PH_SC2_PA7_EOPG_WE', + 359: 'PH_SC2_PA7_DEALLOC_4_0_RD', + 360: 'PH_SC3_SRPS_WINDOW_VALID', + 361: 'PH_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 362: 'PH_SC3_ARB_XFC_ONLY_PRIM_CYCLES', + 363: 'PH_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 364: 'PH_SC3_ARB_STALLED_FROM_BELOW', + 365: 'PH_SC3_ARB_STARVED_FROM_ABOVE', + 366: 'PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 367: 'PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 368: 'PH_SC3_ARB_BUSY', + 369: 'PH_SC3_ARB_PA_BUSY_SOP', + 370: 'PH_SC3_ARB_EOP_POP_SYNC_POP', + 371: 'PH_SC3_ARB_EVENT_SYNC_POP', + 372: 'PH_SC3_PS_ENG_MULTICYCLE_BUBBLE', + 373: 'PH_SC3_EOP_SYNC_WINDOW', + 374: 'PH_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', + 375: 'PH_SC3_BUSY_CNT_NOT_ZERO', + 376: 'PH_SC3_SEND', + 377: 'PH_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 378: 'PH_SC3_CREDIT_AT_MAX', + 379: 'PH_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 380: 'PH_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 381: 'PH_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 382: 'PH_SC3_GFX_PIPE0_TO_1_TRANSITION', + 383: 'PH_SC3_GFX_PIPE1_TO_0_TRANSITION', + 384: 'PH_SC3_PA0_DATA_FIFO_RD', + 385: 'PH_SC3_PA0_DATA_FIFO_WE', + 386: 'PH_SC3_PA0_FIFO_EMPTY', + 387: 'PH_SC3_PA0_FIFO_FULL', + 388: 'PH_SC3_PA0_NULL_WE', + 389: 'PH_SC3_PA0_EVENT_WE', + 390: 'PH_SC3_PA0_FPOV_WE', + 391: 'PH_SC3_PA0_LPOV_WE', + 392: 'PH_SC3_PA0_EOP_WE', + 393: 'PH_SC3_PA0_DATA_FIFO_EOP_RD', + 394: 'PH_SC3_PA0_EOPG_WE', + 395: 'PH_SC3_PA0_DEALLOC_4_0_RD', + 396: 'PH_SC3_PA1_DATA_FIFO_RD', + 397: 'PH_SC3_PA1_DATA_FIFO_WE', + 398: 'PH_SC3_PA1_FIFO_EMPTY', + 399: 'PH_SC3_PA1_FIFO_FULL', + 400: 'PH_SC3_PA1_NULL_WE', + 401: 'PH_SC3_PA1_EVENT_WE', + 402: 'PH_SC3_PA1_FPOV_WE', + 403: 'PH_SC3_PA1_LPOV_WE', + 404: 'PH_SC3_PA1_EOP_WE', + 405: 'PH_SC3_PA1_DATA_FIFO_EOP_RD', + 406: 'PH_SC3_PA1_EOPG_WE', + 407: 'PH_SC3_PA1_DEALLOC_4_0_RD', + 408: 'PH_SC3_PA2_DATA_FIFO_RD', + 409: 'PH_SC3_PA2_DATA_FIFO_WE', + 410: 'PH_SC3_PA2_FIFO_EMPTY', + 411: 'PH_SC3_PA2_FIFO_FULL', + 412: 'PH_SC3_PA2_NULL_WE', + 413: 'PH_SC3_PA2_EVENT_WE', + 414: 'PH_SC3_PA2_FPOV_WE', + 415: 'PH_SC3_PA2_LPOV_WE', + 416: 'PH_SC3_PA2_EOP_WE', + 417: 'PH_SC3_PA2_DATA_FIFO_EOP_RD', + 418: 'PH_SC3_PA2_EOPG_WE', + 419: 'PH_SC3_PA2_DEALLOC_4_0_RD', + 420: 'PH_SC3_PA3_DATA_FIFO_RD', + 421: 'PH_SC3_PA3_DATA_FIFO_WE', + 422: 'PH_SC3_PA3_FIFO_EMPTY', + 423: 'PH_SC3_PA3_FIFO_FULL', + 424: 'PH_SC3_PA3_NULL_WE', + 425: 'PH_SC3_PA3_EVENT_WE', + 426: 'PH_SC3_PA3_FPOV_WE', + 427: 'PH_SC3_PA3_LPOV_WE', + 428: 'PH_SC3_PA3_EOP_WE', + 429: 'PH_SC3_PA3_DATA_FIFO_EOP_RD', + 430: 'PH_SC3_PA3_EOPG_WE', + 431: 'PH_SC3_PA3_DEALLOC_4_0_RD', + 432: 'PH_SC3_PA4_DATA_FIFO_RD', + 433: 'PH_SC3_PA4_DATA_FIFO_WE', + 434: 'PH_SC3_PA4_FIFO_EMPTY', + 435: 'PH_SC3_PA4_FIFO_FULL', + 436: 'PH_SC3_PA4_NULL_WE', + 437: 'PH_SC3_PA4_EVENT_WE', + 438: 'PH_SC3_PA4_FPOV_WE', + 439: 'PH_SC3_PA4_LPOV_WE', + 440: 'PH_SC3_PA4_EOP_WE', + 441: 'PH_SC3_PA4_DATA_FIFO_EOP_RD', + 442: 'PH_SC3_PA4_EOPG_WE', + 443: 'PH_SC3_PA4_DEALLOC_4_0_RD', + 444: 'PH_SC3_PA5_DATA_FIFO_RD', + 445: 'PH_SC3_PA5_DATA_FIFO_WE', + 446: 'PH_SC3_PA5_FIFO_EMPTY', + 447: 'PH_SC3_PA5_FIFO_FULL', + 448: 'PH_SC3_PA5_NULL_WE', + 449: 'PH_SC3_PA5_EVENT_WE', + 450: 'PH_SC3_PA5_FPOV_WE', + 451: 'PH_SC3_PA5_LPOV_WE', + 452: 'PH_SC3_PA5_EOP_WE', + 453: 'PH_SC3_PA5_DATA_FIFO_EOP_RD', + 454: 'PH_SC3_PA5_EOPG_WE', + 455: 'PH_SC3_PA5_DEALLOC_4_0_RD', + 456: 'PH_SC3_PA6_DATA_FIFO_RD', + 457: 'PH_SC3_PA6_DATA_FIFO_WE', + 458: 'PH_SC3_PA6_FIFO_EMPTY', + 459: 'PH_SC3_PA6_FIFO_FULL', + 460: 'PH_SC3_PA6_NULL_WE', + 461: 'PH_SC3_PA6_EVENT_WE', + 462: 'PH_SC3_PA6_FPOV_WE', + 463: 'PH_SC3_PA6_LPOV_WE', + 464: 'PH_SC3_PA6_EOP_WE', + 465: 'PH_SC3_PA6_DATA_FIFO_EOP_RD', + 466: 'PH_SC3_PA6_EOPG_WE', + 467: 'PH_SC3_PA6_DEALLOC_4_0_RD', + 468: 'PH_SC3_PA7_DATA_FIFO_RD', + 469: 'PH_SC3_PA7_DATA_FIFO_WE', + 470: 'PH_SC3_PA7_FIFO_EMPTY', + 471: 'PH_SC3_PA7_FIFO_FULL', + 472: 'PH_SC3_PA7_NULL_WE', + 473: 'PH_SC3_PA7_EVENT_WE', + 474: 'PH_SC3_PA7_FPOV_WE', + 475: 'PH_SC3_PA7_LPOV_WE', + 476: 'PH_SC3_PA7_EOP_WE', + 477: 'PH_SC3_PA7_DATA_FIFO_EOP_RD', + 478: 'PH_SC3_PA7_EOPG_WE', + 479: 'PH_SC3_PA7_DEALLOC_4_0_RD', + 480: 'PH_SC4_SRPS_WINDOW_VALID', + 481: 'PH_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 482: 'PH_SC4_ARB_XFC_ONLY_PRIM_CYCLES', + 483: 'PH_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 484: 'PH_SC4_ARB_STALLED_FROM_BELOW', + 485: 'PH_SC4_ARB_STARVED_FROM_ABOVE', + 486: 'PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 487: 'PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 488: 'PH_SC4_ARB_BUSY', + 489: 'PH_SC4_ARB_PA_BUSY_SOP', + 490: 'PH_SC4_ARB_EOP_POP_SYNC_POP', + 491: 'PH_SC4_ARB_EVENT_SYNC_POP', + 492: 'PH_SC4_PS_ENG_MULTICYCLE_BUBBLE', + 493: 'PH_SC4_EOP_SYNC_WINDOW', + 494: 'PH_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', + 495: 'PH_SC4_BUSY_CNT_NOT_ZERO', + 496: 'PH_SC4_SEND', + 497: 'PH_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 498: 'PH_SC4_CREDIT_AT_MAX', + 499: 'PH_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 500: 'PH_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 501: 'PH_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 502: 'PH_SC4_GFX_PIPE0_TO_1_TRANSITION', + 503: 'PH_SC4_GFX_PIPE1_TO_0_TRANSITION', + 504: 'PH_SC4_PA0_DATA_FIFO_RD', + 505: 'PH_SC4_PA0_DATA_FIFO_WE', + 506: 'PH_SC4_PA0_FIFO_EMPTY', + 507: 'PH_SC4_PA0_FIFO_FULL', + 508: 'PH_SC4_PA0_NULL_WE', + 509: 'PH_SC4_PA0_EVENT_WE', + 510: 'PH_SC4_PA0_FPOV_WE', + 511: 'PH_SC4_PA0_LPOV_WE', + 512: 'PH_SC4_PA0_EOP_WE', + 513: 'PH_SC4_PA0_DATA_FIFO_EOP_RD', + 514: 'PH_SC4_PA0_EOPG_WE', + 515: 'PH_SC4_PA0_DEALLOC_4_0_RD', + 516: 'PH_SC4_PA1_DATA_FIFO_RD', + 517: 'PH_SC4_PA1_DATA_FIFO_WE', + 518: 'PH_SC4_PA1_FIFO_EMPTY', + 519: 'PH_SC4_PA1_FIFO_FULL', + 520: 'PH_SC4_PA1_NULL_WE', + 521: 'PH_SC4_PA1_EVENT_WE', + 522: 'PH_SC4_PA1_FPOV_WE', + 523: 'PH_SC4_PA1_LPOV_WE', + 524: 'PH_SC4_PA1_EOP_WE', + 525: 'PH_SC4_PA1_DATA_FIFO_EOP_RD', + 526: 'PH_SC4_PA1_EOPG_WE', + 527: 'PH_SC4_PA1_DEALLOC_4_0_RD', + 528: 'PH_SC4_PA2_DATA_FIFO_RD', + 529: 'PH_SC4_PA2_DATA_FIFO_WE', + 530: 'PH_SC4_PA2_FIFO_EMPTY', + 531: 'PH_SC4_PA2_FIFO_FULL', + 532: 'PH_SC4_PA2_NULL_WE', + 533: 'PH_SC4_PA2_EVENT_WE', + 534: 'PH_SC4_PA2_FPOV_WE', + 535: 'PH_SC4_PA2_LPOV_WE', + 536: 'PH_SC4_PA2_EOP_WE', + 537: 'PH_SC4_PA2_DATA_FIFO_EOP_RD', + 538: 'PH_SC4_PA2_EOPG_WE', + 539: 'PH_SC4_PA2_DEALLOC_4_0_RD', + 540: 'PH_SC4_PA3_DATA_FIFO_RD', + 541: 'PH_SC4_PA3_DATA_FIFO_WE', + 542: 'PH_SC4_PA3_FIFO_EMPTY', + 543: 'PH_SC4_PA3_FIFO_FULL', + 544: 'PH_SC4_PA3_NULL_WE', + 545: 'PH_SC4_PA3_EVENT_WE', + 546: 'PH_SC4_PA3_FPOV_WE', + 547: 'PH_SC4_PA3_LPOV_WE', + 548: 'PH_SC4_PA3_EOP_WE', + 549: 'PH_SC4_PA3_DATA_FIFO_EOP_RD', + 550: 'PH_SC4_PA3_EOPG_WE', + 551: 'PH_SC4_PA3_DEALLOC_4_0_RD', + 552: 'PH_SC4_PA4_DATA_FIFO_RD', + 553: 'PH_SC4_PA4_DATA_FIFO_WE', + 554: 'PH_SC4_PA4_FIFO_EMPTY', + 555: 'PH_SC4_PA4_FIFO_FULL', + 556: 'PH_SC4_PA4_NULL_WE', + 557: 'PH_SC4_PA4_EVENT_WE', + 558: 'PH_SC4_PA4_FPOV_WE', + 559: 'PH_SC4_PA4_LPOV_WE', + 560: 'PH_SC4_PA4_EOP_WE', + 561: 'PH_SC4_PA4_DATA_FIFO_EOP_RD', + 562: 'PH_SC4_PA4_EOPG_WE', + 563: 'PH_SC4_PA4_DEALLOC_4_0_RD', + 564: 'PH_SC4_PA5_DATA_FIFO_RD', + 565: 'PH_SC4_PA5_DATA_FIFO_WE', + 566: 'PH_SC4_PA5_FIFO_EMPTY', + 567: 'PH_SC4_PA5_FIFO_FULL', + 568: 'PH_SC4_PA5_NULL_WE', + 569: 'PH_SC4_PA5_EVENT_WE', + 570: 'PH_SC4_PA5_FPOV_WE', + 571: 'PH_SC4_PA5_LPOV_WE', + 572: 'PH_SC4_PA5_EOP_WE', + 573: 'PH_SC4_PA5_DATA_FIFO_EOP_RD', + 574: 'PH_SC4_PA5_EOPG_WE', + 575: 'PH_SC4_PA5_DEALLOC_4_0_RD', + 576: 'PH_SC4_PA6_DATA_FIFO_RD', + 577: 'PH_SC4_PA6_DATA_FIFO_WE', + 578: 'PH_SC4_PA6_FIFO_EMPTY', + 579: 'PH_SC4_PA6_FIFO_FULL', + 580: 'PH_SC4_PA6_NULL_WE', + 581: 'PH_SC4_PA6_EVENT_WE', + 582: 'PH_SC4_PA6_FPOV_WE', + 583: 'PH_SC4_PA6_LPOV_WE', + 584: 'PH_SC4_PA6_EOP_WE', + 585: 'PH_SC4_PA6_DATA_FIFO_EOP_RD', + 586: 'PH_SC4_PA6_EOPG_WE', + 587: 'PH_SC4_PA6_DEALLOC_4_0_RD', + 588: 'PH_SC4_PA7_DATA_FIFO_RD', + 589: 'PH_SC4_PA7_DATA_FIFO_WE', + 590: 'PH_SC4_PA7_FIFO_EMPTY', + 591: 'PH_SC4_PA7_FIFO_FULL', + 592: 'PH_SC4_PA7_NULL_WE', + 593: 'PH_SC4_PA7_EVENT_WE', + 594: 'PH_SC4_PA7_FPOV_WE', + 595: 'PH_SC4_PA7_LPOV_WE', + 596: 'PH_SC4_PA7_EOP_WE', + 597: 'PH_SC4_PA7_DATA_FIFO_EOP_RD', + 598: 'PH_SC4_PA7_EOPG_WE', + 599: 'PH_SC4_PA7_DEALLOC_4_0_RD', + 600: 'PH_SC5_SRPS_WINDOW_VALID', + 601: 'PH_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 602: 'PH_SC5_ARB_XFC_ONLY_PRIM_CYCLES', + 603: 'PH_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 604: 'PH_SC5_ARB_STALLED_FROM_BELOW', + 605: 'PH_SC5_ARB_STARVED_FROM_ABOVE', + 606: 'PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 607: 'PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 608: 'PH_SC5_ARB_BUSY', + 609: 'PH_SC5_ARB_PA_BUSY_SOP', + 610: 'PH_SC5_ARB_EOP_POP_SYNC_POP', + 611: 'PH_SC5_ARB_EVENT_SYNC_POP', + 612: 'PH_SC5_PS_ENG_MULTICYCLE_BUBBLE', + 613: 'PH_SC5_EOP_SYNC_WINDOW', + 614: 'PH_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', + 615: 'PH_SC5_BUSY_CNT_NOT_ZERO', + 616: 'PH_SC5_SEND', + 617: 'PH_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 618: 'PH_SC5_CREDIT_AT_MAX', + 619: 'PH_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 620: 'PH_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 621: 'PH_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 622: 'PH_SC5_GFX_PIPE0_TO_1_TRANSITION', + 623: 'PH_SC5_GFX_PIPE1_TO_0_TRANSITION', + 624: 'PH_SC5_PA0_DATA_FIFO_RD', + 625: 'PH_SC5_PA0_DATA_FIFO_WE', + 626: 'PH_SC5_PA0_FIFO_EMPTY', + 627: 'PH_SC5_PA0_FIFO_FULL', + 628: 'PH_SC5_PA0_NULL_WE', + 629: 'PH_SC5_PA0_EVENT_WE', + 630: 'PH_SC5_PA0_FPOV_WE', + 631: 'PH_SC5_PA0_LPOV_WE', + 632: 'PH_SC5_PA0_EOP_WE', + 633: 'PH_SC5_PA0_DATA_FIFO_EOP_RD', + 634: 'PH_SC5_PA0_EOPG_WE', + 635: 'PH_SC5_PA0_DEALLOC_4_0_RD', + 636: 'PH_SC5_PA1_DATA_FIFO_RD', + 637: 'PH_SC5_PA1_DATA_FIFO_WE', + 638: 'PH_SC5_PA1_FIFO_EMPTY', + 639: 'PH_SC5_PA1_FIFO_FULL', + 640: 'PH_SC5_PA1_NULL_WE', + 641: 'PH_SC5_PA1_EVENT_WE', + 642: 'PH_SC5_PA1_FPOV_WE', + 643: 'PH_SC5_PA1_LPOV_WE', + 644: 'PH_SC5_PA1_EOP_WE', + 645: 'PH_SC5_PA1_DATA_FIFO_EOP_RD', + 646: 'PH_SC5_PA1_EOPG_WE', + 647: 'PH_SC5_PA1_DEALLOC_4_0_RD', + 648: 'PH_SC5_PA2_DATA_FIFO_RD', + 649: 'PH_SC5_PA2_DATA_FIFO_WE', + 650: 'PH_SC5_PA2_FIFO_EMPTY', + 651: 'PH_SC5_PA2_FIFO_FULL', + 652: 'PH_SC5_PA2_NULL_WE', + 653: 'PH_SC5_PA2_EVENT_WE', + 654: 'PH_SC5_PA2_FPOV_WE', + 655: 'PH_SC5_PA2_LPOV_WE', + 656: 'PH_SC5_PA2_EOP_WE', + 657: 'PH_SC5_PA2_DATA_FIFO_EOP_RD', + 658: 'PH_SC5_PA2_EOPG_WE', + 659: 'PH_SC5_PA2_DEALLOC_4_0_RD', + 660: 'PH_SC5_PA3_DATA_FIFO_RD', + 661: 'PH_SC5_PA3_DATA_FIFO_WE', + 662: 'PH_SC5_PA3_FIFO_EMPTY', + 663: 'PH_SC5_PA3_FIFO_FULL', + 664: 'PH_SC5_PA3_NULL_WE', + 665: 'PH_SC5_PA3_EVENT_WE', + 666: 'PH_SC5_PA3_FPOV_WE', + 667: 'PH_SC5_PA3_LPOV_WE', + 668: 'PH_SC5_PA3_EOP_WE', + 669: 'PH_SC5_PA3_DATA_FIFO_EOP_RD', + 670: 'PH_SC5_PA3_EOPG_WE', + 671: 'PH_SC5_PA3_DEALLOC_4_0_RD', + 672: 'PH_SC5_PA4_DATA_FIFO_RD', + 673: 'PH_SC5_PA4_DATA_FIFO_WE', + 674: 'PH_SC5_PA4_FIFO_EMPTY', + 675: 'PH_SC5_PA4_FIFO_FULL', + 676: 'PH_SC5_PA4_NULL_WE', + 677: 'PH_SC5_PA4_EVENT_WE', + 678: 'PH_SC5_PA4_FPOV_WE', + 679: 'PH_SC5_PA4_LPOV_WE', + 680: 'PH_SC5_PA4_EOP_WE', + 681: 'PH_SC5_PA4_DATA_FIFO_EOP_RD', + 682: 'PH_SC5_PA4_EOPG_WE', + 683: 'PH_SC5_PA4_DEALLOC_4_0_RD', + 684: 'PH_SC5_PA5_DATA_FIFO_RD', + 685: 'PH_SC5_PA5_DATA_FIFO_WE', + 686: 'PH_SC5_PA5_FIFO_EMPTY', + 687: 'PH_SC5_PA5_FIFO_FULL', + 688: 'PH_SC5_PA5_NULL_WE', + 689: 'PH_SC5_PA5_EVENT_WE', + 690: 'PH_SC5_PA5_FPOV_WE', + 691: 'PH_SC5_PA5_LPOV_WE', + 692: 'PH_SC5_PA5_EOP_WE', + 693: 'PH_SC5_PA5_DATA_FIFO_EOP_RD', + 694: 'PH_SC5_PA5_EOPG_WE', + 695: 'PH_SC5_PA5_DEALLOC_4_0_RD', + 696: 'PH_SC5_PA6_DATA_FIFO_RD', + 697: 'PH_SC5_PA6_DATA_FIFO_WE', + 698: 'PH_SC5_PA6_FIFO_EMPTY', + 699: 'PH_SC5_PA6_FIFO_FULL', + 700: 'PH_SC5_PA6_NULL_WE', + 701: 'PH_SC5_PA6_EVENT_WE', + 702: 'PH_SC5_PA6_FPOV_WE', + 703: 'PH_SC5_PA6_LPOV_WE', + 704: 'PH_SC5_PA6_EOP_WE', + 705: 'PH_SC5_PA6_DATA_FIFO_EOP_RD', + 706: 'PH_SC5_PA6_EOPG_WE', + 707: 'PH_SC5_PA6_DEALLOC_4_0_RD', + 708: 'PH_SC5_PA7_DATA_FIFO_RD', + 709: 'PH_SC5_PA7_DATA_FIFO_WE', + 710: 'PH_SC5_PA7_FIFO_EMPTY', + 711: 'PH_SC5_PA7_FIFO_FULL', + 712: 'PH_SC5_PA7_NULL_WE', + 713: 'PH_SC5_PA7_EVENT_WE', + 714: 'PH_SC5_PA7_FPOV_WE', + 715: 'PH_SC5_PA7_LPOV_WE', + 716: 'PH_SC5_PA7_EOP_WE', + 717: 'PH_SC5_PA7_DATA_FIFO_EOP_RD', + 718: 'PH_SC5_PA7_EOPG_WE', + 719: 'PH_SC5_PA7_DEALLOC_4_0_RD', + 720: 'PH_SC6_SRPS_WINDOW_VALID', + 721: 'PH_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 722: 'PH_SC6_ARB_XFC_ONLY_PRIM_CYCLES', + 723: 'PH_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 724: 'PH_SC6_ARB_STALLED_FROM_BELOW', + 725: 'PH_SC6_ARB_STARVED_FROM_ABOVE', + 726: 'PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 727: 'PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 728: 'PH_SC6_ARB_BUSY', + 729: 'PH_SC6_ARB_PA_BUSY_SOP', + 730: 'PH_SC6_ARB_EOP_POP_SYNC_POP', + 731: 'PH_SC6_ARB_EVENT_SYNC_POP', + 732: 'PH_SC6_PS_ENG_MULTICYCLE_BUBBLE', + 733: 'PH_SC6_EOP_SYNC_WINDOW', + 734: 'PH_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', + 735: 'PH_SC6_BUSY_CNT_NOT_ZERO', + 736: 'PH_SC6_SEND', + 737: 'PH_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 738: 'PH_SC6_CREDIT_AT_MAX', + 739: 'PH_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 740: 'PH_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 741: 'PH_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 742: 'PH_SC6_GFX_PIPE0_TO_1_TRANSITION', + 743: 'PH_SC6_GFX_PIPE1_TO_0_TRANSITION', + 744: 'PH_SC6_PA0_DATA_FIFO_RD', + 745: 'PH_SC6_PA0_DATA_FIFO_WE', + 746: 'PH_SC6_PA0_FIFO_EMPTY', + 747: 'PH_SC6_PA0_FIFO_FULL', + 748: 'PH_SC6_PA0_NULL_WE', + 749: 'PH_SC6_PA0_EVENT_WE', + 750: 'PH_SC6_PA0_FPOV_WE', + 751: 'PH_SC6_PA0_LPOV_WE', + 752: 'PH_SC6_PA0_EOP_WE', + 753: 'PH_SC6_PA0_DATA_FIFO_EOP_RD', + 754: 'PH_SC6_PA0_EOPG_WE', + 755: 'PH_SC6_PA0_DEALLOC_4_0_RD', + 756: 'PH_SC6_PA1_DATA_FIFO_RD', + 757: 'PH_SC6_PA1_DATA_FIFO_WE', + 758: 'PH_SC6_PA1_FIFO_EMPTY', + 759: 'PH_SC6_PA1_FIFO_FULL', + 760: 'PH_SC6_PA1_NULL_WE', + 761: 'PH_SC6_PA1_EVENT_WE', + 762: 'PH_SC6_PA1_FPOV_WE', + 763: 'PH_SC6_PA1_LPOV_WE', + 764: 'PH_SC6_PA1_EOP_WE', + 765: 'PH_SC6_PA1_DATA_FIFO_EOP_RD', + 766: 'PH_SC6_PA1_EOPG_WE', + 767: 'PH_SC6_PA1_DEALLOC_4_0_RD', + 768: 'PH_SC6_PA2_DATA_FIFO_RD', + 769: 'PH_SC6_PA2_DATA_FIFO_WE', + 770: 'PH_SC6_PA2_FIFO_EMPTY', + 771: 'PH_SC6_PA2_FIFO_FULL', + 772: 'PH_SC6_PA2_NULL_WE', + 773: 'PH_SC6_PA2_EVENT_WE', + 774: 'PH_SC6_PA2_FPOV_WE', + 775: 'PH_SC6_PA2_LPOV_WE', + 776: 'PH_SC6_PA2_EOP_WE', + 777: 'PH_SC6_PA2_DATA_FIFO_EOP_RD', + 778: 'PH_SC6_PA2_EOPG_WE', + 779: 'PH_SC6_PA2_DEALLOC_4_0_RD', + 780: 'PH_SC6_PA3_DATA_FIFO_RD', + 781: 'PH_SC6_PA3_DATA_FIFO_WE', + 782: 'PH_SC6_PA3_FIFO_EMPTY', + 783: 'PH_SC6_PA3_FIFO_FULL', + 784: 'PH_SC6_PA3_NULL_WE', + 785: 'PH_SC6_PA3_EVENT_WE', + 786: 'PH_SC6_PA3_FPOV_WE', + 787: 'PH_SC6_PA3_LPOV_WE', + 788: 'PH_SC6_PA3_EOP_WE', + 789: 'PH_SC6_PA3_DATA_FIFO_EOP_RD', + 790: 'PH_SC6_PA3_EOPG_WE', + 791: 'PH_SC6_PA3_DEALLOC_4_0_RD', + 792: 'PH_SC6_PA4_DATA_FIFO_RD', + 793: 'PH_SC6_PA4_DATA_FIFO_WE', + 794: 'PH_SC6_PA4_FIFO_EMPTY', + 795: 'PH_SC6_PA4_FIFO_FULL', + 796: 'PH_SC6_PA4_NULL_WE', + 797: 'PH_SC6_PA4_EVENT_WE', + 798: 'PH_SC6_PA4_FPOV_WE', + 799: 'PH_SC6_PA4_LPOV_WE', + 800: 'PH_SC6_PA4_EOP_WE', + 801: 'PH_SC6_PA4_DATA_FIFO_EOP_RD', + 802: 'PH_SC6_PA4_EOPG_WE', + 803: 'PH_SC6_PA4_DEALLOC_4_0_RD', + 804: 'PH_SC6_PA5_DATA_FIFO_RD', + 805: 'PH_SC6_PA5_DATA_FIFO_WE', + 806: 'PH_SC6_PA5_FIFO_EMPTY', + 807: 'PH_SC6_PA5_FIFO_FULL', + 808: 'PH_SC6_PA5_NULL_WE', + 809: 'PH_SC6_PA5_EVENT_WE', + 810: 'PH_SC6_PA5_FPOV_WE', + 811: 'PH_SC6_PA5_LPOV_WE', + 812: 'PH_SC6_PA5_EOP_WE', + 813: 'PH_SC6_PA5_DATA_FIFO_EOP_RD', + 814: 'PH_SC6_PA5_EOPG_WE', + 815: 'PH_SC6_PA5_DEALLOC_4_0_RD', + 816: 'PH_SC6_PA6_DATA_FIFO_RD', + 817: 'PH_SC6_PA6_DATA_FIFO_WE', + 818: 'PH_SC6_PA6_FIFO_EMPTY', + 819: 'PH_SC6_PA6_FIFO_FULL', + 820: 'PH_SC6_PA6_NULL_WE', + 821: 'PH_SC6_PA6_EVENT_WE', + 822: 'PH_SC6_PA6_FPOV_WE', + 823: 'PH_SC6_PA6_LPOV_WE', + 824: 'PH_SC6_PA6_EOP_WE', + 825: 'PH_SC6_PA6_DATA_FIFO_EOP_RD', + 826: 'PH_SC6_PA6_EOPG_WE', + 827: 'PH_SC6_PA6_DEALLOC_4_0_RD', + 828: 'PH_SC6_PA7_DATA_FIFO_RD', + 829: 'PH_SC6_PA7_DATA_FIFO_WE', + 830: 'PH_SC6_PA7_FIFO_EMPTY', + 831: 'PH_SC6_PA7_FIFO_FULL', + 832: 'PH_SC6_PA7_NULL_WE', + 833: 'PH_SC6_PA7_EVENT_WE', + 834: 'PH_SC6_PA7_FPOV_WE', + 835: 'PH_SC6_PA7_LPOV_WE', + 836: 'PH_SC6_PA7_EOP_WE', + 837: 'PH_SC6_PA7_DATA_FIFO_EOP_RD', + 838: 'PH_SC6_PA7_EOPG_WE', + 839: 'PH_SC6_PA7_DEALLOC_4_0_RD', + 840: 'PH_SC7_SRPS_WINDOW_VALID', + 841: 'PH_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 842: 'PH_SC7_ARB_XFC_ONLY_PRIM_CYCLES', + 843: 'PH_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 844: 'PH_SC7_ARB_STALLED_FROM_BELOW', + 845: 'PH_SC7_ARB_STARVED_FROM_ABOVE', + 846: 'PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 847: 'PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 848: 'PH_SC7_ARB_BUSY', + 849: 'PH_SC7_ARB_PA_BUSY_SOP', + 850: 'PH_SC7_ARB_EOP_POP_SYNC_POP', + 851: 'PH_SC7_ARB_EVENT_SYNC_POP', + 852: 'PH_SC7_PS_ENG_MULTICYCLE_BUBBLE', + 853: 'PH_SC7_EOP_SYNC_WINDOW', + 854: 'PH_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', + 855: 'PH_SC7_BUSY_CNT_NOT_ZERO', + 856: 'PH_SC7_SEND', + 857: 'PH_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 858: 'PH_SC7_CREDIT_AT_MAX', + 859: 'PH_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 860: 'PH_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 861: 'PH_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 862: 'PH_SC7_GFX_PIPE0_TO_1_TRANSITION', + 863: 'PH_SC7_GFX_PIPE1_TO_0_TRANSITION', + 864: 'PH_SC7_PA0_DATA_FIFO_RD', + 865: 'PH_SC7_PA0_DATA_FIFO_WE', + 866: 'PH_SC7_PA0_FIFO_EMPTY', + 867: 'PH_SC7_PA0_FIFO_FULL', + 868: 'PH_SC7_PA0_NULL_WE', + 869: 'PH_SC7_PA0_EVENT_WE', + 870: 'PH_SC7_PA0_FPOV_WE', + 871: 'PH_SC7_PA0_LPOV_WE', + 872: 'PH_SC7_PA0_EOP_WE', + 873: 'PH_SC7_PA0_DATA_FIFO_EOP_RD', + 874: 'PH_SC7_PA0_EOPG_WE', + 875: 'PH_SC7_PA0_DEALLOC_4_0_RD', + 876: 'PH_SC7_PA1_DATA_FIFO_RD', + 877: 'PH_SC7_PA1_DATA_FIFO_WE', + 878: 'PH_SC7_PA1_FIFO_EMPTY', + 879: 'PH_SC7_PA1_FIFO_FULL', + 880: 'PH_SC7_PA1_NULL_WE', + 881: 'PH_SC7_PA1_EVENT_WE', + 882: 'PH_SC7_PA1_FPOV_WE', + 883: 'PH_SC7_PA1_LPOV_WE', + 884: 'PH_SC7_PA1_EOP_WE', + 885: 'PH_SC7_PA1_DATA_FIFO_EOP_RD', + 886: 'PH_SC7_PA1_EOPG_WE', + 887: 'PH_SC7_PA1_DEALLOC_4_0_RD', + 888: 'PH_SC7_PA2_DATA_FIFO_RD', + 889: 'PH_SC7_PA2_DATA_FIFO_WE', + 890: 'PH_SC7_PA2_FIFO_EMPTY', + 891: 'PH_SC7_PA2_FIFO_FULL', + 892: 'PH_SC7_PA2_NULL_WE', + 893: 'PH_SC7_PA2_EVENT_WE', + 894: 'PH_SC7_PA2_FPOV_WE', + 895: 'PH_SC7_PA2_LPOV_WE', + 896: 'PH_SC7_PA2_EOP_WE', + 897: 'PH_SC7_PA2_DATA_FIFO_EOP_RD', + 898: 'PH_SC7_PA2_EOPG_WE', + 899: 'PH_SC7_PA2_DEALLOC_4_0_RD', + 900: 'PH_SC7_PA3_DATA_FIFO_RD', + 901: 'PH_SC7_PA3_DATA_FIFO_WE', + 902: 'PH_SC7_PA3_FIFO_EMPTY', + 903: 'PH_SC7_PA3_FIFO_FULL', + 904: 'PH_SC7_PA3_NULL_WE', + 905: 'PH_SC7_PA3_EVENT_WE', + 906: 'PH_SC7_PA3_FPOV_WE', + 907: 'PH_SC7_PA3_LPOV_WE', + 908: 'PH_SC7_PA3_EOP_WE', + 909: 'PH_SC7_PA3_DATA_FIFO_EOP_RD', + 910: 'PH_SC7_PA3_EOPG_WE', + 911: 'PH_SC7_PA3_DEALLOC_4_0_RD', + 912: 'PH_SC7_PA4_DATA_FIFO_RD', + 913: 'PH_SC7_PA4_DATA_FIFO_WE', + 914: 'PH_SC7_PA4_FIFO_EMPTY', + 915: 'PH_SC7_PA4_FIFO_FULL', + 916: 'PH_SC7_PA4_NULL_WE', + 917: 'PH_SC7_PA4_EVENT_WE', + 918: 'PH_SC7_PA4_FPOV_WE', + 919: 'PH_SC7_PA4_LPOV_WE', + 920: 'PH_SC7_PA4_EOP_WE', + 921: 'PH_SC7_PA4_DATA_FIFO_EOP_RD', + 922: 'PH_SC7_PA4_EOPG_WE', + 923: 'PH_SC7_PA4_DEALLOC_4_0_RD', + 924: 'PH_SC7_PA5_DATA_FIFO_RD', + 925: 'PH_SC7_PA5_DATA_FIFO_WE', + 926: 'PH_SC7_PA5_FIFO_EMPTY', + 927: 'PH_SC7_PA5_FIFO_FULL', + 928: 'PH_SC7_PA5_NULL_WE', + 929: 'PH_SC7_PA5_EVENT_WE', + 930: 'PH_SC7_PA5_FPOV_WE', + 931: 'PH_SC7_PA5_LPOV_WE', + 932: 'PH_SC7_PA5_EOP_WE', + 933: 'PH_SC7_PA5_DATA_FIFO_EOP_RD', + 934: 'PH_SC7_PA5_EOPG_WE', + 935: 'PH_SC7_PA5_DEALLOC_4_0_RD', + 936: 'PH_SC7_PA6_DATA_FIFO_RD', + 937: 'PH_SC7_PA6_DATA_FIFO_WE', + 938: 'PH_SC7_PA6_FIFO_EMPTY', + 939: 'PH_SC7_PA6_FIFO_FULL', + 940: 'PH_SC7_PA6_NULL_WE', + 941: 'PH_SC7_PA6_EVENT_WE', + 942: 'PH_SC7_PA6_FPOV_WE', + 943: 'PH_SC7_PA6_LPOV_WE', + 944: 'PH_SC7_PA6_EOP_WE', + 945: 'PH_SC7_PA6_DATA_FIFO_EOP_RD', + 946: 'PH_SC7_PA6_EOPG_WE', + 947: 'PH_SC7_PA6_DEALLOC_4_0_RD', + 948: 'PH_SC7_PA7_DATA_FIFO_RD', + 949: 'PH_SC7_PA7_DATA_FIFO_WE', + 950: 'PH_SC7_PA7_FIFO_EMPTY', + 951: 'PH_SC7_PA7_FIFO_FULL', + 952: 'PH_SC7_PA7_NULL_WE', + 953: 'PH_SC7_PA7_EVENT_WE', + 954: 'PH_SC7_PA7_FPOV_WE', + 955: 'PH_SC7_PA7_LPOV_WE', + 956: 'PH_SC7_PA7_EOP_WE', + 957: 'PH_SC7_PA7_DATA_FIFO_EOP_RD', + 958: 'PH_SC7_PA7_EOPG_WE', + 959: 'PH_SC7_PA7_DEALLOC_4_0_RD', +} +PH_SC0_SRPS_WINDOW_VALID = 0 +PH_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 1 +PH_SC0_ARB_XFC_ONLY_PRIM_CYCLES = 2 +PH_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 3 +PH_SC0_ARB_STALLED_FROM_BELOW = 4 +PH_SC0_ARB_STARVED_FROM_ABOVE = 5 +PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 6 +PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 7 +PH_SC0_ARB_BUSY = 8 +PH_SC0_ARB_PA_BUSY_SOP = 9 +PH_SC0_ARB_EOP_POP_SYNC_POP = 10 +PH_SC0_ARB_EVENT_SYNC_POP = 11 +PH_SC0_PS_ENG_MULTICYCLE_BUBBLE = 12 +PH_SC0_EOP_SYNC_WINDOW = 13 +PH_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM = 14 +PH_SC0_BUSY_CNT_NOT_ZERO = 15 +PH_SC0_SEND = 16 +PH_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND = 17 +PH_SC0_CREDIT_AT_MAX = 18 +PH_SC0_CREDIT_AT_MAX_NO_PENDING_SEND = 19 +PH_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 20 +PH_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION = 21 +PH_SC0_GFX_PIPE0_TO_1_TRANSITION = 22 +PH_SC0_GFX_PIPE1_TO_0_TRANSITION = 23 +PH_SC0_PA0_DATA_FIFO_RD = 24 +PH_SC0_PA0_DATA_FIFO_WE = 25 +PH_SC0_PA0_FIFO_EMPTY = 26 +PH_SC0_PA0_FIFO_FULL = 27 +PH_SC0_PA0_NULL_WE = 28 +PH_SC0_PA0_EVENT_WE = 29 +PH_SC0_PA0_FPOV_WE = 30 +PH_SC0_PA0_LPOV_WE = 31 +PH_SC0_PA0_EOP_WE = 32 +PH_SC0_PA0_DATA_FIFO_EOP_RD = 33 +PH_SC0_PA0_EOPG_WE = 34 +PH_SC0_PA0_DEALLOC_4_0_RD = 35 +PH_SC0_PA1_DATA_FIFO_RD = 36 +PH_SC0_PA1_DATA_FIFO_WE = 37 +PH_SC0_PA1_FIFO_EMPTY = 38 +PH_SC0_PA1_FIFO_FULL = 39 +PH_SC0_PA1_NULL_WE = 40 +PH_SC0_PA1_EVENT_WE = 41 +PH_SC0_PA1_FPOV_WE = 42 +PH_SC0_PA1_LPOV_WE = 43 +PH_SC0_PA1_EOP_WE = 44 +PH_SC0_PA1_DATA_FIFO_EOP_RD = 45 +PH_SC0_PA1_EOPG_WE = 46 +PH_SC0_PA1_DEALLOC_4_0_RD = 47 +PH_SC0_PA2_DATA_FIFO_RD = 48 +PH_SC0_PA2_DATA_FIFO_WE = 49 +PH_SC0_PA2_FIFO_EMPTY = 50 +PH_SC0_PA2_FIFO_FULL = 51 +PH_SC0_PA2_NULL_WE = 52 +PH_SC0_PA2_EVENT_WE = 53 +PH_SC0_PA2_FPOV_WE = 54 +PH_SC0_PA2_LPOV_WE = 55 +PH_SC0_PA2_EOP_WE = 56 +PH_SC0_PA2_DATA_FIFO_EOP_RD = 57 +PH_SC0_PA2_EOPG_WE = 58 +PH_SC0_PA2_DEALLOC_4_0_RD = 59 +PH_SC0_PA3_DATA_FIFO_RD = 60 +PH_SC0_PA3_DATA_FIFO_WE = 61 +PH_SC0_PA3_FIFO_EMPTY = 62 +PH_SC0_PA3_FIFO_FULL = 63 +PH_SC0_PA3_NULL_WE = 64 +PH_SC0_PA3_EVENT_WE = 65 +PH_SC0_PA3_FPOV_WE = 66 +PH_SC0_PA3_LPOV_WE = 67 +PH_SC0_PA3_EOP_WE = 68 +PH_SC0_PA3_DATA_FIFO_EOP_RD = 69 +PH_SC0_PA3_EOPG_WE = 70 +PH_SC0_PA3_DEALLOC_4_0_RD = 71 +PH_SC0_PA4_DATA_FIFO_RD = 72 +PH_SC0_PA4_DATA_FIFO_WE = 73 +PH_SC0_PA4_FIFO_EMPTY = 74 +PH_SC0_PA4_FIFO_FULL = 75 +PH_SC0_PA4_NULL_WE = 76 +PH_SC0_PA4_EVENT_WE = 77 +PH_SC0_PA4_FPOV_WE = 78 +PH_SC0_PA4_LPOV_WE = 79 +PH_SC0_PA4_EOP_WE = 80 +PH_SC0_PA4_DATA_FIFO_EOP_RD = 81 +PH_SC0_PA4_EOPG_WE = 82 +PH_SC0_PA4_DEALLOC_4_0_RD = 83 +PH_SC0_PA5_DATA_FIFO_RD = 84 +PH_SC0_PA5_DATA_FIFO_WE = 85 +PH_SC0_PA5_FIFO_EMPTY = 86 +PH_SC0_PA5_FIFO_FULL = 87 +PH_SC0_PA5_NULL_WE = 88 +PH_SC0_PA5_EVENT_WE = 89 +PH_SC0_PA5_FPOV_WE = 90 +PH_SC0_PA5_LPOV_WE = 91 +PH_SC0_PA5_EOP_WE = 92 +PH_SC0_PA5_DATA_FIFO_EOP_RD = 93 +PH_SC0_PA5_EOPG_WE = 94 +PH_SC0_PA5_DEALLOC_4_0_RD = 95 +PH_SC0_PA6_DATA_FIFO_RD = 96 +PH_SC0_PA6_DATA_FIFO_WE = 97 +PH_SC0_PA6_FIFO_EMPTY = 98 +PH_SC0_PA6_FIFO_FULL = 99 +PH_SC0_PA6_NULL_WE = 100 +PH_SC0_PA6_EVENT_WE = 101 +PH_SC0_PA6_FPOV_WE = 102 +PH_SC0_PA6_LPOV_WE = 103 +PH_SC0_PA6_EOP_WE = 104 +PH_SC0_PA6_DATA_FIFO_EOP_RD = 105 +PH_SC0_PA6_EOPG_WE = 106 +PH_SC0_PA6_DEALLOC_4_0_RD = 107 +PH_SC0_PA7_DATA_FIFO_RD = 108 +PH_SC0_PA7_DATA_FIFO_WE = 109 +PH_SC0_PA7_FIFO_EMPTY = 110 +PH_SC0_PA7_FIFO_FULL = 111 +PH_SC0_PA7_NULL_WE = 112 +PH_SC0_PA7_EVENT_WE = 113 +PH_SC0_PA7_FPOV_WE = 114 +PH_SC0_PA7_LPOV_WE = 115 +PH_SC0_PA7_EOP_WE = 116 +PH_SC0_PA7_DATA_FIFO_EOP_RD = 117 +PH_SC0_PA7_EOPG_WE = 118 +PH_SC0_PA7_DEALLOC_4_0_RD = 119 +PH_SC1_SRPS_WINDOW_VALID = 120 +PH_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 121 +PH_SC1_ARB_XFC_ONLY_PRIM_CYCLES = 122 +PH_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 123 +PH_SC1_ARB_STALLED_FROM_BELOW = 124 +PH_SC1_ARB_STARVED_FROM_ABOVE = 125 +PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 126 +PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 127 +PH_SC1_ARB_BUSY = 128 +PH_SC1_ARB_PA_BUSY_SOP = 129 +PH_SC1_ARB_EOP_POP_SYNC_POP = 130 +PH_SC1_ARB_EVENT_SYNC_POP = 131 +PH_SC1_PS_ENG_MULTICYCLE_BUBBLE = 132 +PH_SC1_EOP_SYNC_WINDOW = 133 +PH_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM = 134 +PH_SC1_BUSY_CNT_NOT_ZERO = 135 +PH_SC1_SEND = 136 +PH_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND = 137 +PH_SC1_CREDIT_AT_MAX = 138 +PH_SC1_CREDIT_AT_MAX_NO_PENDING_SEND = 139 +PH_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 140 +PH_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 141 +PH_SC1_GFX_PIPE0_TO_1_TRANSITION = 142 +PH_SC1_GFX_PIPE1_TO_0_TRANSITION = 143 +PH_SC1_PA0_DATA_FIFO_RD = 144 +PH_SC1_PA0_DATA_FIFO_WE = 145 +PH_SC1_PA0_FIFO_EMPTY = 146 +PH_SC1_PA0_FIFO_FULL = 147 +PH_SC1_PA0_NULL_WE = 148 +PH_SC1_PA0_EVENT_WE = 149 +PH_SC1_PA0_FPOV_WE = 150 +PH_SC1_PA0_LPOV_WE = 151 +PH_SC1_PA0_EOP_WE = 152 +PH_SC1_PA0_DATA_FIFO_EOP_RD = 153 +PH_SC1_PA0_EOPG_WE = 154 +PH_SC1_PA0_DEALLOC_4_0_RD = 155 +PH_SC1_PA1_DATA_FIFO_RD = 156 +PH_SC1_PA1_DATA_FIFO_WE = 157 +PH_SC1_PA1_FIFO_EMPTY = 158 +PH_SC1_PA1_FIFO_FULL = 159 +PH_SC1_PA1_NULL_WE = 160 +PH_SC1_PA1_EVENT_WE = 161 +PH_SC1_PA1_FPOV_WE = 162 +PH_SC1_PA1_LPOV_WE = 163 +PH_SC1_PA1_EOP_WE = 164 +PH_SC1_PA1_DATA_FIFO_EOP_RD = 165 +PH_SC1_PA1_EOPG_WE = 166 +PH_SC1_PA1_DEALLOC_4_0_RD = 167 +PH_SC1_PA2_DATA_FIFO_RD = 168 +PH_SC1_PA2_DATA_FIFO_WE = 169 +PH_SC1_PA2_FIFO_EMPTY = 170 +PH_SC1_PA2_FIFO_FULL = 171 +PH_SC1_PA2_NULL_WE = 172 +PH_SC1_PA2_EVENT_WE = 173 +PH_SC1_PA2_FPOV_WE = 174 +PH_SC1_PA2_LPOV_WE = 175 +PH_SC1_PA2_EOP_WE = 176 +PH_SC1_PA2_DATA_FIFO_EOP_RD = 177 +PH_SC1_PA2_EOPG_WE = 178 +PH_SC1_PA2_DEALLOC_4_0_RD = 179 +PH_SC1_PA3_DATA_FIFO_RD = 180 +PH_SC1_PA3_DATA_FIFO_WE = 181 +PH_SC1_PA3_FIFO_EMPTY = 182 +PH_SC1_PA3_FIFO_FULL = 183 +PH_SC1_PA3_NULL_WE = 184 +PH_SC1_PA3_EVENT_WE = 185 +PH_SC1_PA3_FPOV_WE = 186 +PH_SC1_PA3_LPOV_WE = 187 +PH_SC1_PA3_EOP_WE = 188 +PH_SC1_PA3_DATA_FIFO_EOP_RD = 189 +PH_SC1_PA3_EOPG_WE = 190 +PH_SC1_PA3_DEALLOC_4_0_RD = 191 +PH_SC1_PA4_DATA_FIFO_RD = 192 +PH_SC1_PA4_DATA_FIFO_WE = 193 +PH_SC1_PA4_FIFO_EMPTY = 194 +PH_SC1_PA4_FIFO_FULL = 195 +PH_SC1_PA4_NULL_WE = 196 +PH_SC1_PA4_EVENT_WE = 197 +PH_SC1_PA4_FPOV_WE = 198 +PH_SC1_PA4_LPOV_WE = 199 +PH_SC1_PA4_EOP_WE = 200 +PH_SC1_PA4_DATA_FIFO_EOP_RD = 201 +PH_SC1_PA4_EOPG_WE = 202 +PH_SC1_PA4_DEALLOC_4_0_RD = 203 +PH_SC1_PA5_DATA_FIFO_RD = 204 +PH_SC1_PA5_DATA_FIFO_WE = 205 +PH_SC1_PA5_FIFO_EMPTY = 206 +PH_SC1_PA5_FIFO_FULL = 207 +PH_SC1_PA5_NULL_WE = 208 +PH_SC1_PA5_EVENT_WE = 209 +PH_SC1_PA5_FPOV_WE = 210 +PH_SC1_PA5_LPOV_WE = 211 +PH_SC1_PA5_EOP_WE = 212 +PH_SC1_PA5_DATA_FIFO_EOP_RD = 213 +PH_SC1_PA5_EOPG_WE = 214 +PH_SC1_PA5_DEALLOC_4_0_RD = 215 +PH_SC1_PA6_DATA_FIFO_RD = 216 +PH_SC1_PA6_DATA_FIFO_WE = 217 +PH_SC1_PA6_FIFO_EMPTY = 218 +PH_SC1_PA6_FIFO_FULL = 219 +PH_SC1_PA6_NULL_WE = 220 +PH_SC1_PA6_EVENT_WE = 221 +PH_SC1_PA6_FPOV_WE = 222 +PH_SC1_PA6_LPOV_WE = 223 +PH_SC1_PA6_EOP_WE = 224 +PH_SC1_PA6_DATA_FIFO_EOP_RD = 225 +PH_SC1_PA6_EOPG_WE = 226 +PH_SC1_PA6_DEALLOC_4_0_RD = 227 +PH_SC1_PA7_DATA_FIFO_RD = 228 +PH_SC1_PA7_DATA_FIFO_WE = 229 +PH_SC1_PA7_FIFO_EMPTY = 230 +PH_SC1_PA7_FIFO_FULL = 231 +PH_SC1_PA7_NULL_WE = 232 +PH_SC1_PA7_EVENT_WE = 233 +PH_SC1_PA7_FPOV_WE = 234 +PH_SC1_PA7_LPOV_WE = 235 +PH_SC1_PA7_EOP_WE = 236 +PH_SC1_PA7_DATA_FIFO_EOP_RD = 237 +PH_SC1_PA7_EOPG_WE = 238 +PH_SC1_PA7_DEALLOC_4_0_RD = 239 +PH_SC2_SRPS_WINDOW_VALID = 240 +PH_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 241 +PH_SC2_ARB_XFC_ONLY_PRIM_CYCLES = 242 +PH_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 243 +PH_SC2_ARB_STALLED_FROM_BELOW = 244 +PH_SC2_ARB_STARVED_FROM_ABOVE = 245 +PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 246 +PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 247 +PH_SC2_ARB_BUSY = 248 +PH_SC2_ARB_PA_BUSY_SOP = 249 +PH_SC2_ARB_EOP_POP_SYNC_POP = 250 +PH_SC2_ARB_EVENT_SYNC_POP = 251 +PH_SC2_PS_ENG_MULTICYCLE_BUBBLE = 252 +PH_SC2_EOP_SYNC_WINDOW = 253 +PH_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM = 254 +PH_SC2_BUSY_CNT_NOT_ZERO = 255 +PH_SC2_SEND = 256 +PH_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND = 257 +PH_SC2_CREDIT_AT_MAX = 258 +PH_SC2_CREDIT_AT_MAX_NO_PENDING_SEND = 259 +PH_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 260 +PH_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 261 +PH_SC2_GFX_PIPE0_TO_1_TRANSITION = 262 +PH_SC2_GFX_PIPE1_TO_0_TRANSITION = 263 +PH_SC2_PA0_DATA_FIFO_RD = 264 +PH_SC2_PA0_DATA_FIFO_WE = 265 +PH_SC2_PA0_FIFO_EMPTY = 266 +PH_SC2_PA0_FIFO_FULL = 267 +PH_SC2_PA0_NULL_WE = 268 +PH_SC2_PA0_EVENT_WE = 269 +PH_SC2_PA0_FPOV_WE = 270 +PH_SC2_PA0_LPOV_WE = 271 +PH_SC2_PA0_EOP_WE = 272 +PH_SC2_PA0_DATA_FIFO_EOP_RD = 273 +PH_SC2_PA0_EOPG_WE = 274 +PH_SC2_PA0_DEALLOC_4_0_RD = 275 +PH_SC2_PA1_DATA_FIFO_RD = 276 +PH_SC2_PA1_DATA_FIFO_WE = 277 +PH_SC2_PA1_FIFO_EMPTY = 278 +PH_SC2_PA1_FIFO_FULL = 279 +PH_SC2_PA1_NULL_WE = 280 +PH_SC2_PA1_EVENT_WE = 281 +PH_SC2_PA1_FPOV_WE = 282 +PH_SC2_PA1_LPOV_WE = 283 +PH_SC2_PA1_EOP_WE = 284 +PH_SC2_PA1_DATA_FIFO_EOP_RD = 285 +PH_SC2_PA1_EOPG_WE = 286 +PH_SC2_PA1_DEALLOC_4_0_RD = 287 +PH_SC2_PA2_DATA_FIFO_RD = 288 +PH_SC2_PA2_DATA_FIFO_WE = 289 +PH_SC2_PA2_FIFO_EMPTY = 290 +PH_SC2_PA2_FIFO_FULL = 291 +PH_SC2_PA2_NULL_WE = 292 +PH_SC2_PA2_EVENT_WE = 293 +PH_SC2_PA2_FPOV_WE = 294 +PH_SC2_PA2_LPOV_WE = 295 +PH_SC2_PA2_EOP_WE = 296 +PH_SC2_PA2_DATA_FIFO_EOP_RD = 297 +PH_SC2_PA2_EOPG_WE = 298 +PH_SC2_PA2_DEALLOC_4_0_RD = 299 +PH_SC2_PA3_DATA_FIFO_RD = 300 +PH_SC2_PA3_DATA_FIFO_WE = 301 +PH_SC2_PA3_FIFO_EMPTY = 302 +PH_SC2_PA3_FIFO_FULL = 303 +PH_SC2_PA3_NULL_WE = 304 +PH_SC2_PA3_EVENT_WE = 305 +PH_SC2_PA3_FPOV_WE = 306 +PH_SC2_PA3_LPOV_WE = 307 +PH_SC2_PA3_EOP_WE = 308 +PH_SC2_PA3_DATA_FIFO_EOP_RD = 309 +PH_SC2_PA3_EOPG_WE = 310 +PH_SC2_PA3_DEALLOC_4_0_RD = 311 +PH_SC2_PA4_DATA_FIFO_RD = 312 +PH_SC2_PA4_DATA_FIFO_WE = 313 +PH_SC2_PA4_FIFO_EMPTY = 314 +PH_SC2_PA4_FIFO_FULL = 315 +PH_SC2_PA4_NULL_WE = 316 +PH_SC2_PA4_EVENT_WE = 317 +PH_SC2_PA4_FPOV_WE = 318 +PH_SC2_PA4_LPOV_WE = 319 +PH_SC2_PA4_EOP_WE = 320 +PH_SC2_PA4_DATA_FIFO_EOP_RD = 321 +PH_SC2_PA4_EOPG_WE = 322 +PH_SC2_PA4_DEALLOC_4_0_RD = 323 +PH_SC2_PA5_DATA_FIFO_RD = 324 +PH_SC2_PA5_DATA_FIFO_WE = 325 +PH_SC2_PA5_FIFO_EMPTY = 326 +PH_SC2_PA5_FIFO_FULL = 327 +PH_SC2_PA5_NULL_WE = 328 +PH_SC2_PA5_EVENT_WE = 329 +PH_SC2_PA5_FPOV_WE = 330 +PH_SC2_PA5_LPOV_WE = 331 +PH_SC2_PA5_EOP_WE = 332 +PH_SC2_PA5_DATA_FIFO_EOP_RD = 333 +PH_SC2_PA5_EOPG_WE = 334 +PH_SC2_PA5_DEALLOC_4_0_RD = 335 +PH_SC2_PA6_DATA_FIFO_RD = 336 +PH_SC2_PA6_DATA_FIFO_WE = 337 +PH_SC2_PA6_FIFO_EMPTY = 338 +PH_SC2_PA6_FIFO_FULL = 339 +PH_SC2_PA6_NULL_WE = 340 +PH_SC2_PA6_EVENT_WE = 341 +PH_SC2_PA6_FPOV_WE = 342 +PH_SC2_PA6_LPOV_WE = 343 +PH_SC2_PA6_EOP_WE = 344 +PH_SC2_PA6_DATA_FIFO_EOP_RD = 345 +PH_SC2_PA6_EOPG_WE = 346 +PH_SC2_PA6_DEALLOC_4_0_RD = 347 +PH_SC2_PA7_DATA_FIFO_RD = 348 +PH_SC2_PA7_DATA_FIFO_WE = 349 +PH_SC2_PA7_FIFO_EMPTY = 350 +PH_SC2_PA7_FIFO_FULL = 351 +PH_SC2_PA7_NULL_WE = 352 +PH_SC2_PA7_EVENT_WE = 353 +PH_SC2_PA7_FPOV_WE = 354 +PH_SC2_PA7_LPOV_WE = 355 +PH_SC2_PA7_EOP_WE = 356 +PH_SC2_PA7_DATA_FIFO_EOP_RD = 357 +PH_SC2_PA7_EOPG_WE = 358 +PH_SC2_PA7_DEALLOC_4_0_RD = 359 +PH_SC3_SRPS_WINDOW_VALID = 360 +PH_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 361 +PH_SC3_ARB_XFC_ONLY_PRIM_CYCLES = 362 +PH_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 363 +PH_SC3_ARB_STALLED_FROM_BELOW = 364 +PH_SC3_ARB_STARVED_FROM_ABOVE = 365 +PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 366 +PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 367 +PH_SC3_ARB_BUSY = 368 +PH_SC3_ARB_PA_BUSY_SOP = 369 +PH_SC3_ARB_EOP_POP_SYNC_POP = 370 +PH_SC3_ARB_EVENT_SYNC_POP = 371 +PH_SC3_PS_ENG_MULTICYCLE_BUBBLE = 372 +PH_SC3_EOP_SYNC_WINDOW = 373 +PH_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM = 374 +PH_SC3_BUSY_CNT_NOT_ZERO = 375 +PH_SC3_SEND = 376 +PH_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND = 377 +PH_SC3_CREDIT_AT_MAX = 378 +PH_SC3_CREDIT_AT_MAX_NO_PENDING_SEND = 379 +PH_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 380 +PH_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 381 +PH_SC3_GFX_PIPE0_TO_1_TRANSITION = 382 +PH_SC3_GFX_PIPE1_TO_0_TRANSITION = 383 +PH_SC3_PA0_DATA_FIFO_RD = 384 +PH_SC3_PA0_DATA_FIFO_WE = 385 +PH_SC3_PA0_FIFO_EMPTY = 386 +PH_SC3_PA0_FIFO_FULL = 387 +PH_SC3_PA0_NULL_WE = 388 +PH_SC3_PA0_EVENT_WE = 389 +PH_SC3_PA0_FPOV_WE = 390 +PH_SC3_PA0_LPOV_WE = 391 +PH_SC3_PA0_EOP_WE = 392 +PH_SC3_PA0_DATA_FIFO_EOP_RD = 393 +PH_SC3_PA0_EOPG_WE = 394 +PH_SC3_PA0_DEALLOC_4_0_RD = 395 +PH_SC3_PA1_DATA_FIFO_RD = 396 +PH_SC3_PA1_DATA_FIFO_WE = 397 +PH_SC3_PA1_FIFO_EMPTY = 398 +PH_SC3_PA1_FIFO_FULL = 399 +PH_SC3_PA1_NULL_WE = 400 +PH_SC3_PA1_EVENT_WE = 401 +PH_SC3_PA1_FPOV_WE = 402 +PH_SC3_PA1_LPOV_WE = 403 +PH_SC3_PA1_EOP_WE = 404 +PH_SC3_PA1_DATA_FIFO_EOP_RD = 405 +PH_SC3_PA1_EOPG_WE = 406 +PH_SC3_PA1_DEALLOC_4_0_RD = 407 +PH_SC3_PA2_DATA_FIFO_RD = 408 +PH_SC3_PA2_DATA_FIFO_WE = 409 +PH_SC3_PA2_FIFO_EMPTY = 410 +PH_SC3_PA2_FIFO_FULL = 411 +PH_SC3_PA2_NULL_WE = 412 +PH_SC3_PA2_EVENT_WE = 413 +PH_SC3_PA2_FPOV_WE = 414 +PH_SC3_PA2_LPOV_WE = 415 +PH_SC3_PA2_EOP_WE = 416 +PH_SC3_PA2_DATA_FIFO_EOP_RD = 417 +PH_SC3_PA2_EOPG_WE = 418 +PH_SC3_PA2_DEALLOC_4_0_RD = 419 +PH_SC3_PA3_DATA_FIFO_RD = 420 +PH_SC3_PA3_DATA_FIFO_WE = 421 +PH_SC3_PA3_FIFO_EMPTY = 422 +PH_SC3_PA3_FIFO_FULL = 423 +PH_SC3_PA3_NULL_WE = 424 +PH_SC3_PA3_EVENT_WE = 425 +PH_SC3_PA3_FPOV_WE = 426 +PH_SC3_PA3_LPOV_WE = 427 +PH_SC3_PA3_EOP_WE = 428 +PH_SC3_PA3_DATA_FIFO_EOP_RD = 429 +PH_SC3_PA3_EOPG_WE = 430 +PH_SC3_PA3_DEALLOC_4_0_RD = 431 +PH_SC3_PA4_DATA_FIFO_RD = 432 +PH_SC3_PA4_DATA_FIFO_WE = 433 +PH_SC3_PA4_FIFO_EMPTY = 434 +PH_SC3_PA4_FIFO_FULL = 435 +PH_SC3_PA4_NULL_WE = 436 +PH_SC3_PA4_EVENT_WE = 437 +PH_SC3_PA4_FPOV_WE = 438 +PH_SC3_PA4_LPOV_WE = 439 +PH_SC3_PA4_EOP_WE = 440 +PH_SC3_PA4_DATA_FIFO_EOP_RD = 441 +PH_SC3_PA4_EOPG_WE = 442 +PH_SC3_PA4_DEALLOC_4_0_RD = 443 +PH_SC3_PA5_DATA_FIFO_RD = 444 +PH_SC3_PA5_DATA_FIFO_WE = 445 +PH_SC3_PA5_FIFO_EMPTY = 446 +PH_SC3_PA5_FIFO_FULL = 447 +PH_SC3_PA5_NULL_WE = 448 +PH_SC3_PA5_EVENT_WE = 449 +PH_SC3_PA5_FPOV_WE = 450 +PH_SC3_PA5_LPOV_WE = 451 +PH_SC3_PA5_EOP_WE = 452 +PH_SC3_PA5_DATA_FIFO_EOP_RD = 453 +PH_SC3_PA5_EOPG_WE = 454 +PH_SC3_PA5_DEALLOC_4_0_RD = 455 +PH_SC3_PA6_DATA_FIFO_RD = 456 +PH_SC3_PA6_DATA_FIFO_WE = 457 +PH_SC3_PA6_FIFO_EMPTY = 458 +PH_SC3_PA6_FIFO_FULL = 459 +PH_SC3_PA6_NULL_WE = 460 +PH_SC3_PA6_EVENT_WE = 461 +PH_SC3_PA6_FPOV_WE = 462 +PH_SC3_PA6_LPOV_WE = 463 +PH_SC3_PA6_EOP_WE = 464 +PH_SC3_PA6_DATA_FIFO_EOP_RD = 465 +PH_SC3_PA6_EOPG_WE = 466 +PH_SC3_PA6_DEALLOC_4_0_RD = 467 +PH_SC3_PA7_DATA_FIFO_RD = 468 +PH_SC3_PA7_DATA_FIFO_WE = 469 +PH_SC3_PA7_FIFO_EMPTY = 470 +PH_SC3_PA7_FIFO_FULL = 471 +PH_SC3_PA7_NULL_WE = 472 +PH_SC3_PA7_EVENT_WE = 473 +PH_SC3_PA7_FPOV_WE = 474 +PH_SC3_PA7_LPOV_WE = 475 +PH_SC3_PA7_EOP_WE = 476 +PH_SC3_PA7_DATA_FIFO_EOP_RD = 477 +PH_SC3_PA7_EOPG_WE = 478 +PH_SC3_PA7_DEALLOC_4_0_RD = 479 +PH_SC4_SRPS_WINDOW_VALID = 480 +PH_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 481 +PH_SC4_ARB_XFC_ONLY_PRIM_CYCLES = 482 +PH_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 483 +PH_SC4_ARB_STALLED_FROM_BELOW = 484 +PH_SC4_ARB_STARVED_FROM_ABOVE = 485 +PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 486 +PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 487 +PH_SC4_ARB_BUSY = 488 +PH_SC4_ARB_PA_BUSY_SOP = 489 +PH_SC4_ARB_EOP_POP_SYNC_POP = 490 +PH_SC4_ARB_EVENT_SYNC_POP = 491 +PH_SC4_PS_ENG_MULTICYCLE_BUBBLE = 492 +PH_SC4_EOP_SYNC_WINDOW = 493 +PH_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM = 494 +PH_SC4_BUSY_CNT_NOT_ZERO = 495 +PH_SC4_SEND = 496 +PH_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND = 497 +PH_SC4_CREDIT_AT_MAX = 498 +PH_SC4_CREDIT_AT_MAX_NO_PENDING_SEND = 499 +PH_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 500 +PH_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 501 +PH_SC4_GFX_PIPE0_TO_1_TRANSITION = 502 +PH_SC4_GFX_PIPE1_TO_0_TRANSITION = 503 +PH_SC4_PA0_DATA_FIFO_RD = 504 +PH_SC4_PA0_DATA_FIFO_WE = 505 +PH_SC4_PA0_FIFO_EMPTY = 506 +PH_SC4_PA0_FIFO_FULL = 507 +PH_SC4_PA0_NULL_WE = 508 +PH_SC4_PA0_EVENT_WE = 509 +PH_SC4_PA0_FPOV_WE = 510 +PH_SC4_PA0_LPOV_WE = 511 +PH_SC4_PA0_EOP_WE = 512 +PH_SC4_PA0_DATA_FIFO_EOP_RD = 513 +PH_SC4_PA0_EOPG_WE = 514 +PH_SC4_PA0_DEALLOC_4_0_RD = 515 +PH_SC4_PA1_DATA_FIFO_RD = 516 +PH_SC4_PA1_DATA_FIFO_WE = 517 +PH_SC4_PA1_FIFO_EMPTY = 518 +PH_SC4_PA1_FIFO_FULL = 519 +PH_SC4_PA1_NULL_WE = 520 +PH_SC4_PA1_EVENT_WE = 521 +PH_SC4_PA1_FPOV_WE = 522 +PH_SC4_PA1_LPOV_WE = 523 +PH_SC4_PA1_EOP_WE = 524 +PH_SC4_PA1_DATA_FIFO_EOP_RD = 525 +PH_SC4_PA1_EOPG_WE = 526 +PH_SC4_PA1_DEALLOC_4_0_RD = 527 +PH_SC4_PA2_DATA_FIFO_RD = 528 +PH_SC4_PA2_DATA_FIFO_WE = 529 +PH_SC4_PA2_FIFO_EMPTY = 530 +PH_SC4_PA2_FIFO_FULL = 531 +PH_SC4_PA2_NULL_WE = 532 +PH_SC4_PA2_EVENT_WE = 533 +PH_SC4_PA2_FPOV_WE = 534 +PH_SC4_PA2_LPOV_WE = 535 +PH_SC4_PA2_EOP_WE = 536 +PH_SC4_PA2_DATA_FIFO_EOP_RD = 537 +PH_SC4_PA2_EOPG_WE = 538 +PH_SC4_PA2_DEALLOC_4_0_RD = 539 +PH_SC4_PA3_DATA_FIFO_RD = 540 +PH_SC4_PA3_DATA_FIFO_WE = 541 +PH_SC4_PA3_FIFO_EMPTY = 542 +PH_SC4_PA3_FIFO_FULL = 543 +PH_SC4_PA3_NULL_WE = 544 +PH_SC4_PA3_EVENT_WE = 545 +PH_SC4_PA3_FPOV_WE = 546 +PH_SC4_PA3_LPOV_WE = 547 +PH_SC4_PA3_EOP_WE = 548 +PH_SC4_PA3_DATA_FIFO_EOP_RD = 549 +PH_SC4_PA3_EOPG_WE = 550 +PH_SC4_PA3_DEALLOC_4_0_RD = 551 +PH_SC4_PA4_DATA_FIFO_RD = 552 +PH_SC4_PA4_DATA_FIFO_WE = 553 +PH_SC4_PA4_FIFO_EMPTY = 554 +PH_SC4_PA4_FIFO_FULL = 555 +PH_SC4_PA4_NULL_WE = 556 +PH_SC4_PA4_EVENT_WE = 557 +PH_SC4_PA4_FPOV_WE = 558 +PH_SC4_PA4_LPOV_WE = 559 +PH_SC4_PA4_EOP_WE = 560 +PH_SC4_PA4_DATA_FIFO_EOP_RD = 561 +PH_SC4_PA4_EOPG_WE = 562 +PH_SC4_PA4_DEALLOC_4_0_RD = 563 +PH_SC4_PA5_DATA_FIFO_RD = 564 +PH_SC4_PA5_DATA_FIFO_WE = 565 +PH_SC4_PA5_FIFO_EMPTY = 566 +PH_SC4_PA5_FIFO_FULL = 567 +PH_SC4_PA5_NULL_WE = 568 +PH_SC4_PA5_EVENT_WE = 569 +PH_SC4_PA5_FPOV_WE = 570 +PH_SC4_PA5_LPOV_WE = 571 +PH_SC4_PA5_EOP_WE = 572 +PH_SC4_PA5_DATA_FIFO_EOP_RD = 573 +PH_SC4_PA5_EOPG_WE = 574 +PH_SC4_PA5_DEALLOC_4_0_RD = 575 +PH_SC4_PA6_DATA_FIFO_RD = 576 +PH_SC4_PA6_DATA_FIFO_WE = 577 +PH_SC4_PA6_FIFO_EMPTY = 578 +PH_SC4_PA6_FIFO_FULL = 579 +PH_SC4_PA6_NULL_WE = 580 +PH_SC4_PA6_EVENT_WE = 581 +PH_SC4_PA6_FPOV_WE = 582 +PH_SC4_PA6_LPOV_WE = 583 +PH_SC4_PA6_EOP_WE = 584 +PH_SC4_PA6_DATA_FIFO_EOP_RD = 585 +PH_SC4_PA6_EOPG_WE = 586 +PH_SC4_PA6_DEALLOC_4_0_RD = 587 +PH_SC4_PA7_DATA_FIFO_RD = 588 +PH_SC4_PA7_DATA_FIFO_WE = 589 +PH_SC4_PA7_FIFO_EMPTY = 590 +PH_SC4_PA7_FIFO_FULL = 591 +PH_SC4_PA7_NULL_WE = 592 +PH_SC4_PA7_EVENT_WE = 593 +PH_SC4_PA7_FPOV_WE = 594 +PH_SC4_PA7_LPOV_WE = 595 +PH_SC4_PA7_EOP_WE = 596 +PH_SC4_PA7_DATA_FIFO_EOP_RD = 597 +PH_SC4_PA7_EOPG_WE = 598 +PH_SC4_PA7_DEALLOC_4_0_RD = 599 +PH_SC5_SRPS_WINDOW_VALID = 600 +PH_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 601 +PH_SC5_ARB_XFC_ONLY_PRIM_CYCLES = 602 +PH_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 603 +PH_SC5_ARB_STALLED_FROM_BELOW = 604 +PH_SC5_ARB_STARVED_FROM_ABOVE = 605 +PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 606 +PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 607 +PH_SC5_ARB_BUSY = 608 +PH_SC5_ARB_PA_BUSY_SOP = 609 +PH_SC5_ARB_EOP_POP_SYNC_POP = 610 +PH_SC5_ARB_EVENT_SYNC_POP = 611 +PH_SC5_PS_ENG_MULTICYCLE_BUBBLE = 612 +PH_SC5_EOP_SYNC_WINDOW = 613 +PH_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM = 614 +PH_SC5_BUSY_CNT_NOT_ZERO = 615 +PH_SC5_SEND = 616 +PH_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND = 617 +PH_SC5_CREDIT_AT_MAX = 618 +PH_SC5_CREDIT_AT_MAX_NO_PENDING_SEND = 619 +PH_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 620 +PH_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 621 +PH_SC5_GFX_PIPE0_TO_1_TRANSITION = 622 +PH_SC5_GFX_PIPE1_TO_0_TRANSITION = 623 +PH_SC5_PA0_DATA_FIFO_RD = 624 +PH_SC5_PA0_DATA_FIFO_WE = 625 +PH_SC5_PA0_FIFO_EMPTY = 626 +PH_SC5_PA0_FIFO_FULL = 627 +PH_SC5_PA0_NULL_WE = 628 +PH_SC5_PA0_EVENT_WE = 629 +PH_SC5_PA0_FPOV_WE = 630 +PH_SC5_PA0_LPOV_WE = 631 +PH_SC5_PA0_EOP_WE = 632 +PH_SC5_PA0_DATA_FIFO_EOP_RD = 633 +PH_SC5_PA0_EOPG_WE = 634 +PH_SC5_PA0_DEALLOC_4_0_RD = 635 +PH_SC5_PA1_DATA_FIFO_RD = 636 +PH_SC5_PA1_DATA_FIFO_WE = 637 +PH_SC5_PA1_FIFO_EMPTY = 638 +PH_SC5_PA1_FIFO_FULL = 639 +PH_SC5_PA1_NULL_WE = 640 +PH_SC5_PA1_EVENT_WE = 641 +PH_SC5_PA1_FPOV_WE = 642 +PH_SC5_PA1_LPOV_WE = 643 +PH_SC5_PA1_EOP_WE = 644 +PH_SC5_PA1_DATA_FIFO_EOP_RD = 645 +PH_SC5_PA1_EOPG_WE = 646 +PH_SC5_PA1_DEALLOC_4_0_RD = 647 +PH_SC5_PA2_DATA_FIFO_RD = 648 +PH_SC5_PA2_DATA_FIFO_WE = 649 +PH_SC5_PA2_FIFO_EMPTY = 650 +PH_SC5_PA2_FIFO_FULL = 651 +PH_SC5_PA2_NULL_WE = 652 +PH_SC5_PA2_EVENT_WE = 653 +PH_SC5_PA2_FPOV_WE = 654 +PH_SC5_PA2_LPOV_WE = 655 +PH_SC5_PA2_EOP_WE = 656 +PH_SC5_PA2_DATA_FIFO_EOP_RD = 657 +PH_SC5_PA2_EOPG_WE = 658 +PH_SC5_PA2_DEALLOC_4_0_RD = 659 +PH_SC5_PA3_DATA_FIFO_RD = 660 +PH_SC5_PA3_DATA_FIFO_WE = 661 +PH_SC5_PA3_FIFO_EMPTY = 662 +PH_SC5_PA3_FIFO_FULL = 663 +PH_SC5_PA3_NULL_WE = 664 +PH_SC5_PA3_EVENT_WE = 665 +PH_SC5_PA3_FPOV_WE = 666 +PH_SC5_PA3_LPOV_WE = 667 +PH_SC5_PA3_EOP_WE = 668 +PH_SC5_PA3_DATA_FIFO_EOP_RD = 669 +PH_SC5_PA3_EOPG_WE = 670 +PH_SC5_PA3_DEALLOC_4_0_RD = 671 +PH_SC5_PA4_DATA_FIFO_RD = 672 +PH_SC5_PA4_DATA_FIFO_WE = 673 +PH_SC5_PA4_FIFO_EMPTY = 674 +PH_SC5_PA4_FIFO_FULL = 675 +PH_SC5_PA4_NULL_WE = 676 +PH_SC5_PA4_EVENT_WE = 677 +PH_SC5_PA4_FPOV_WE = 678 +PH_SC5_PA4_LPOV_WE = 679 +PH_SC5_PA4_EOP_WE = 680 +PH_SC5_PA4_DATA_FIFO_EOP_RD = 681 +PH_SC5_PA4_EOPG_WE = 682 +PH_SC5_PA4_DEALLOC_4_0_RD = 683 +PH_SC5_PA5_DATA_FIFO_RD = 684 +PH_SC5_PA5_DATA_FIFO_WE = 685 +PH_SC5_PA5_FIFO_EMPTY = 686 +PH_SC5_PA5_FIFO_FULL = 687 +PH_SC5_PA5_NULL_WE = 688 +PH_SC5_PA5_EVENT_WE = 689 +PH_SC5_PA5_FPOV_WE = 690 +PH_SC5_PA5_LPOV_WE = 691 +PH_SC5_PA5_EOP_WE = 692 +PH_SC5_PA5_DATA_FIFO_EOP_RD = 693 +PH_SC5_PA5_EOPG_WE = 694 +PH_SC5_PA5_DEALLOC_4_0_RD = 695 +PH_SC5_PA6_DATA_FIFO_RD = 696 +PH_SC5_PA6_DATA_FIFO_WE = 697 +PH_SC5_PA6_FIFO_EMPTY = 698 +PH_SC5_PA6_FIFO_FULL = 699 +PH_SC5_PA6_NULL_WE = 700 +PH_SC5_PA6_EVENT_WE = 701 +PH_SC5_PA6_FPOV_WE = 702 +PH_SC5_PA6_LPOV_WE = 703 +PH_SC5_PA6_EOP_WE = 704 +PH_SC5_PA6_DATA_FIFO_EOP_RD = 705 +PH_SC5_PA6_EOPG_WE = 706 +PH_SC5_PA6_DEALLOC_4_0_RD = 707 +PH_SC5_PA7_DATA_FIFO_RD = 708 +PH_SC5_PA7_DATA_FIFO_WE = 709 +PH_SC5_PA7_FIFO_EMPTY = 710 +PH_SC5_PA7_FIFO_FULL = 711 +PH_SC5_PA7_NULL_WE = 712 +PH_SC5_PA7_EVENT_WE = 713 +PH_SC5_PA7_FPOV_WE = 714 +PH_SC5_PA7_LPOV_WE = 715 +PH_SC5_PA7_EOP_WE = 716 +PH_SC5_PA7_DATA_FIFO_EOP_RD = 717 +PH_SC5_PA7_EOPG_WE = 718 +PH_SC5_PA7_DEALLOC_4_0_RD = 719 +PH_SC6_SRPS_WINDOW_VALID = 720 +PH_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 721 +PH_SC6_ARB_XFC_ONLY_PRIM_CYCLES = 722 +PH_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 723 +PH_SC6_ARB_STALLED_FROM_BELOW = 724 +PH_SC6_ARB_STARVED_FROM_ABOVE = 725 +PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 726 +PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 727 +PH_SC6_ARB_BUSY = 728 +PH_SC6_ARB_PA_BUSY_SOP = 729 +PH_SC6_ARB_EOP_POP_SYNC_POP = 730 +PH_SC6_ARB_EVENT_SYNC_POP = 731 +PH_SC6_PS_ENG_MULTICYCLE_BUBBLE = 732 +PH_SC6_EOP_SYNC_WINDOW = 733 +PH_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM = 734 +PH_SC6_BUSY_CNT_NOT_ZERO = 735 +PH_SC6_SEND = 736 +PH_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND = 737 +PH_SC6_CREDIT_AT_MAX = 738 +PH_SC6_CREDIT_AT_MAX_NO_PENDING_SEND = 739 +PH_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 740 +PH_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 741 +PH_SC6_GFX_PIPE0_TO_1_TRANSITION = 742 +PH_SC6_GFX_PIPE1_TO_0_TRANSITION = 743 +PH_SC6_PA0_DATA_FIFO_RD = 744 +PH_SC6_PA0_DATA_FIFO_WE = 745 +PH_SC6_PA0_FIFO_EMPTY = 746 +PH_SC6_PA0_FIFO_FULL = 747 +PH_SC6_PA0_NULL_WE = 748 +PH_SC6_PA0_EVENT_WE = 749 +PH_SC6_PA0_FPOV_WE = 750 +PH_SC6_PA0_LPOV_WE = 751 +PH_SC6_PA0_EOP_WE = 752 +PH_SC6_PA0_DATA_FIFO_EOP_RD = 753 +PH_SC6_PA0_EOPG_WE = 754 +PH_SC6_PA0_DEALLOC_4_0_RD = 755 +PH_SC6_PA1_DATA_FIFO_RD = 756 +PH_SC6_PA1_DATA_FIFO_WE = 757 +PH_SC6_PA1_FIFO_EMPTY = 758 +PH_SC6_PA1_FIFO_FULL = 759 +PH_SC6_PA1_NULL_WE = 760 +PH_SC6_PA1_EVENT_WE = 761 +PH_SC6_PA1_FPOV_WE = 762 +PH_SC6_PA1_LPOV_WE = 763 +PH_SC6_PA1_EOP_WE = 764 +PH_SC6_PA1_DATA_FIFO_EOP_RD = 765 +PH_SC6_PA1_EOPG_WE = 766 +PH_SC6_PA1_DEALLOC_4_0_RD = 767 +PH_SC6_PA2_DATA_FIFO_RD = 768 +PH_SC6_PA2_DATA_FIFO_WE = 769 +PH_SC6_PA2_FIFO_EMPTY = 770 +PH_SC6_PA2_FIFO_FULL = 771 +PH_SC6_PA2_NULL_WE = 772 +PH_SC6_PA2_EVENT_WE = 773 +PH_SC6_PA2_FPOV_WE = 774 +PH_SC6_PA2_LPOV_WE = 775 +PH_SC6_PA2_EOP_WE = 776 +PH_SC6_PA2_DATA_FIFO_EOP_RD = 777 +PH_SC6_PA2_EOPG_WE = 778 +PH_SC6_PA2_DEALLOC_4_0_RD = 779 +PH_SC6_PA3_DATA_FIFO_RD = 780 +PH_SC6_PA3_DATA_FIFO_WE = 781 +PH_SC6_PA3_FIFO_EMPTY = 782 +PH_SC6_PA3_FIFO_FULL = 783 +PH_SC6_PA3_NULL_WE = 784 +PH_SC6_PA3_EVENT_WE = 785 +PH_SC6_PA3_FPOV_WE = 786 +PH_SC6_PA3_LPOV_WE = 787 +PH_SC6_PA3_EOP_WE = 788 +PH_SC6_PA3_DATA_FIFO_EOP_RD = 789 +PH_SC6_PA3_EOPG_WE = 790 +PH_SC6_PA3_DEALLOC_4_0_RD = 791 +PH_SC6_PA4_DATA_FIFO_RD = 792 +PH_SC6_PA4_DATA_FIFO_WE = 793 +PH_SC6_PA4_FIFO_EMPTY = 794 +PH_SC6_PA4_FIFO_FULL = 795 +PH_SC6_PA4_NULL_WE = 796 +PH_SC6_PA4_EVENT_WE = 797 +PH_SC6_PA4_FPOV_WE = 798 +PH_SC6_PA4_LPOV_WE = 799 +PH_SC6_PA4_EOP_WE = 800 +PH_SC6_PA4_DATA_FIFO_EOP_RD = 801 +PH_SC6_PA4_EOPG_WE = 802 +PH_SC6_PA4_DEALLOC_4_0_RD = 803 +PH_SC6_PA5_DATA_FIFO_RD = 804 +PH_SC6_PA5_DATA_FIFO_WE = 805 +PH_SC6_PA5_FIFO_EMPTY = 806 +PH_SC6_PA5_FIFO_FULL = 807 +PH_SC6_PA5_NULL_WE = 808 +PH_SC6_PA5_EVENT_WE = 809 +PH_SC6_PA5_FPOV_WE = 810 +PH_SC6_PA5_LPOV_WE = 811 +PH_SC6_PA5_EOP_WE = 812 +PH_SC6_PA5_DATA_FIFO_EOP_RD = 813 +PH_SC6_PA5_EOPG_WE = 814 +PH_SC6_PA5_DEALLOC_4_0_RD = 815 +PH_SC6_PA6_DATA_FIFO_RD = 816 +PH_SC6_PA6_DATA_FIFO_WE = 817 +PH_SC6_PA6_FIFO_EMPTY = 818 +PH_SC6_PA6_FIFO_FULL = 819 +PH_SC6_PA6_NULL_WE = 820 +PH_SC6_PA6_EVENT_WE = 821 +PH_SC6_PA6_FPOV_WE = 822 +PH_SC6_PA6_LPOV_WE = 823 +PH_SC6_PA6_EOP_WE = 824 +PH_SC6_PA6_DATA_FIFO_EOP_RD = 825 +PH_SC6_PA6_EOPG_WE = 826 +PH_SC6_PA6_DEALLOC_4_0_RD = 827 +PH_SC6_PA7_DATA_FIFO_RD = 828 +PH_SC6_PA7_DATA_FIFO_WE = 829 +PH_SC6_PA7_FIFO_EMPTY = 830 +PH_SC6_PA7_FIFO_FULL = 831 +PH_SC6_PA7_NULL_WE = 832 +PH_SC6_PA7_EVENT_WE = 833 +PH_SC6_PA7_FPOV_WE = 834 +PH_SC6_PA7_LPOV_WE = 835 +PH_SC6_PA7_EOP_WE = 836 +PH_SC6_PA7_DATA_FIFO_EOP_RD = 837 +PH_SC6_PA7_EOPG_WE = 838 +PH_SC6_PA7_DEALLOC_4_0_RD = 839 +PH_SC7_SRPS_WINDOW_VALID = 840 +PH_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 841 +PH_SC7_ARB_XFC_ONLY_PRIM_CYCLES = 842 +PH_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 843 +PH_SC7_ARB_STALLED_FROM_BELOW = 844 +PH_SC7_ARB_STARVED_FROM_ABOVE = 845 +PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 846 +PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 847 +PH_SC7_ARB_BUSY = 848 +PH_SC7_ARB_PA_BUSY_SOP = 849 +PH_SC7_ARB_EOP_POP_SYNC_POP = 850 +PH_SC7_ARB_EVENT_SYNC_POP = 851 +PH_SC7_PS_ENG_MULTICYCLE_BUBBLE = 852 +PH_SC7_EOP_SYNC_WINDOW = 853 +PH_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM = 854 +PH_SC7_BUSY_CNT_NOT_ZERO = 855 +PH_SC7_SEND = 856 +PH_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND = 857 +PH_SC7_CREDIT_AT_MAX = 858 +PH_SC7_CREDIT_AT_MAX_NO_PENDING_SEND = 859 +PH_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 860 +PH_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 861 +PH_SC7_GFX_PIPE0_TO_1_TRANSITION = 862 +PH_SC7_GFX_PIPE1_TO_0_TRANSITION = 863 +PH_SC7_PA0_DATA_FIFO_RD = 864 +PH_SC7_PA0_DATA_FIFO_WE = 865 +PH_SC7_PA0_FIFO_EMPTY = 866 +PH_SC7_PA0_FIFO_FULL = 867 +PH_SC7_PA0_NULL_WE = 868 +PH_SC7_PA0_EVENT_WE = 869 +PH_SC7_PA0_FPOV_WE = 870 +PH_SC7_PA0_LPOV_WE = 871 +PH_SC7_PA0_EOP_WE = 872 +PH_SC7_PA0_DATA_FIFO_EOP_RD = 873 +PH_SC7_PA0_EOPG_WE = 874 +PH_SC7_PA0_DEALLOC_4_0_RD = 875 +PH_SC7_PA1_DATA_FIFO_RD = 876 +PH_SC7_PA1_DATA_FIFO_WE = 877 +PH_SC7_PA1_FIFO_EMPTY = 878 +PH_SC7_PA1_FIFO_FULL = 879 +PH_SC7_PA1_NULL_WE = 880 +PH_SC7_PA1_EVENT_WE = 881 +PH_SC7_PA1_FPOV_WE = 882 +PH_SC7_PA1_LPOV_WE = 883 +PH_SC7_PA1_EOP_WE = 884 +PH_SC7_PA1_DATA_FIFO_EOP_RD = 885 +PH_SC7_PA1_EOPG_WE = 886 +PH_SC7_PA1_DEALLOC_4_0_RD = 887 +PH_SC7_PA2_DATA_FIFO_RD = 888 +PH_SC7_PA2_DATA_FIFO_WE = 889 +PH_SC7_PA2_FIFO_EMPTY = 890 +PH_SC7_PA2_FIFO_FULL = 891 +PH_SC7_PA2_NULL_WE = 892 +PH_SC7_PA2_EVENT_WE = 893 +PH_SC7_PA2_FPOV_WE = 894 +PH_SC7_PA2_LPOV_WE = 895 +PH_SC7_PA2_EOP_WE = 896 +PH_SC7_PA2_DATA_FIFO_EOP_RD = 897 +PH_SC7_PA2_EOPG_WE = 898 +PH_SC7_PA2_DEALLOC_4_0_RD = 899 +PH_SC7_PA3_DATA_FIFO_RD = 900 +PH_SC7_PA3_DATA_FIFO_WE = 901 +PH_SC7_PA3_FIFO_EMPTY = 902 +PH_SC7_PA3_FIFO_FULL = 903 +PH_SC7_PA3_NULL_WE = 904 +PH_SC7_PA3_EVENT_WE = 905 +PH_SC7_PA3_FPOV_WE = 906 +PH_SC7_PA3_LPOV_WE = 907 +PH_SC7_PA3_EOP_WE = 908 +PH_SC7_PA3_DATA_FIFO_EOP_RD = 909 +PH_SC7_PA3_EOPG_WE = 910 +PH_SC7_PA3_DEALLOC_4_0_RD = 911 +PH_SC7_PA4_DATA_FIFO_RD = 912 +PH_SC7_PA4_DATA_FIFO_WE = 913 +PH_SC7_PA4_FIFO_EMPTY = 914 +PH_SC7_PA4_FIFO_FULL = 915 +PH_SC7_PA4_NULL_WE = 916 +PH_SC7_PA4_EVENT_WE = 917 +PH_SC7_PA4_FPOV_WE = 918 +PH_SC7_PA4_LPOV_WE = 919 +PH_SC7_PA4_EOP_WE = 920 +PH_SC7_PA4_DATA_FIFO_EOP_RD = 921 +PH_SC7_PA4_EOPG_WE = 922 +PH_SC7_PA4_DEALLOC_4_0_RD = 923 +PH_SC7_PA5_DATA_FIFO_RD = 924 +PH_SC7_PA5_DATA_FIFO_WE = 925 +PH_SC7_PA5_FIFO_EMPTY = 926 +PH_SC7_PA5_FIFO_FULL = 927 +PH_SC7_PA5_NULL_WE = 928 +PH_SC7_PA5_EVENT_WE = 929 +PH_SC7_PA5_FPOV_WE = 930 +PH_SC7_PA5_LPOV_WE = 931 +PH_SC7_PA5_EOP_WE = 932 +PH_SC7_PA5_DATA_FIFO_EOP_RD = 933 +PH_SC7_PA5_EOPG_WE = 934 +PH_SC7_PA5_DEALLOC_4_0_RD = 935 +PH_SC7_PA6_DATA_FIFO_RD = 936 +PH_SC7_PA6_DATA_FIFO_WE = 937 +PH_SC7_PA6_FIFO_EMPTY = 938 +PH_SC7_PA6_FIFO_FULL = 939 +PH_SC7_PA6_NULL_WE = 940 +PH_SC7_PA6_EVENT_WE = 941 +PH_SC7_PA6_FPOV_WE = 942 +PH_SC7_PA6_LPOV_WE = 943 +PH_SC7_PA6_EOP_WE = 944 +PH_SC7_PA6_DATA_FIFO_EOP_RD = 945 +PH_SC7_PA6_EOPG_WE = 946 +PH_SC7_PA6_DEALLOC_4_0_RD = 947 +PH_SC7_PA7_DATA_FIFO_RD = 948 +PH_SC7_PA7_DATA_FIFO_WE = 949 +PH_SC7_PA7_FIFO_EMPTY = 950 +PH_SC7_PA7_FIFO_FULL = 951 +PH_SC7_PA7_NULL_WE = 952 +PH_SC7_PA7_EVENT_WE = 953 +PH_SC7_PA7_FPOV_WE = 954 +PH_SC7_PA7_LPOV_WE = 955 +PH_SC7_PA7_EOP_WE = 956 +PH_SC7_PA7_DATA_FIFO_EOP_RD = 957 +PH_SC7_PA7_EOPG_WE = 958 +PH_SC7_PA7_DEALLOC_4_0_RD = 959 +PH_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SU_PERFCNT_SEL' +SU_PERFCNT_SEL__enumvalues = { + 0: 'PERF_PAPC_PASX_REQ', + 1: 'PERF_PAPC_PASX_DISABLE_PIPE', + 2: 'PERF_PAPC_PASX_FIRST_VECTOR', + 3: 'PERF_PAPC_PASX_SECOND_VECTOR', + 4: 'PERF_PAPC_PASX_FIRST_DEAD', + 5: 'PERF_PAPC_PASX_SECOND_DEAD', + 6: 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 7: 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 8: 'PERF_PAPC_PA_INPUT_PRIM', + 9: 'PERF_PAPC_PA_INPUT_NULL_PRIM', + 10: 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 11: 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 12: 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 13: 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 14: 'PERF_PAPC_CLPR_CULL_PRIM', + 15: 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', + 16: 'PERF_PAPC_CLPR_VV_CULL_PRIM', + 17: 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 18: 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 19: 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 20: 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 21: 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 22: 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 23: 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', + 24: 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 25: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 26: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 27: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 28: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 29: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 30: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 31: 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 32: 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', + 33: 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 34: 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 35: 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', + 36: 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 37: 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 38: 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 39: 'PERF_PAPC_CLSM_NULL_PRIM', + 40: 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 41: 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', + 42: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', + 43: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 44: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', + 45: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 46: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 47: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 48: 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', + 49: 'PERF_PAPC_SU_INPUT_PRIM', + 50: 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 51: 'PERF_PAPC_SU_INPUT_NULL_PRIM', + 52: 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 53: 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 54: 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 55: 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 56: 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 57: 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 58: 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 59: 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 60: 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 61: 'PERF_PAPC_SU_OUTPUT_PRIM', + 62: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 63: 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 64: 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 65: 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 66: 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', + 67: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 68: 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 69: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', + 70: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 71: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 72: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 73: 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 74: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 75: 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 76: 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 77: 'PERF_PAPC_PASX_REQ_IDLE', + 78: 'PERF_PAPC_PASX_REQ_BUSY', + 79: 'PERF_PAPC_PASX_REQ_STALLED', + 80: 'PERF_PAPC_PASX_REC_IDLE', + 81: 'PERF_PAPC_PASX_REC_BUSY', + 82: 'PERF_PAPC_PASX_REC_STARVED_SX', + 83: 'PERF_PAPC_PASX_REC_STALLED', + 84: 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 85: 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 86: 'PERF_PAPC_CCGSM_IDLE', + 87: 'PERF_PAPC_CCGSM_BUSY', + 88: 'PERF_PAPC_CCGSM_STALLED', + 89: 'PERF_PAPC_CLPRIM_IDLE', + 90: 'PERF_PAPC_CLPRIM_BUSY', + 91: 'PERF_PAPC_CLPRIM_STALLED', + 92: 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 93: 'PERF_PAPC_CLIPSM_IDLE', + 94: 'PERF_PAPC_CLIPSM_BUSY', + 95: 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 96: 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', + 97: 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 98: 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 99: 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 100: 'PERF_PAPC_CLIPGA_IDLE', + 101: 'PERF_PAPC_CLIPGA_BUSY', + 102: 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 103: 'PERF_PAPC_CLIPGA_STALLED', + 104: 'PERF_PAPC_CLIP_IDLE', + 105: 'PERF_PAPC_CLIP_BUSY', + 106: 'PERF_PAPC_SU_IDLE', + 107: 'PERF_PAPC_SU_BUSY', + 108: 'PERF_PAPC_SU_STARVED_CLIP', + 109: 'PERF_PAPC_SU_STALLED_SC', + 110: 'PERF_PAPC_CL_DYN_SCLK_VLD', + 111: 'PERF_PAPC_SU_DYN_SCLK_VLD', + 112: 'PERF_PAPC_PA_REG_SCLK_VLD', + 113: 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 114: 'PERF_PAPC_PASX_SE0_REQ', + 115: 'PERF_PAPC_PASX_SE1_REQ', + 116: 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 117: 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 118: 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', + 119: 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', + 120: 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 121: 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 122: 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 123: 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 124: 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 125: 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 126: 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 127: 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 128: 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 129: 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 130: 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 131: 'PERF_PAPC_SU_SE0_STALLED_SC', + 132: 'PERF_PAPC_SU_SE1_STALLED_SC', + 133: 'PERF_PAPC_SU_SE01_STALLED_SC', + 134: 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 135: 'PERF_PAPC_SU_CULLED_PRIM', + 136: 'PERF_PAPC_SU_OUTPUT_EOPG', + 137: 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 138: 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 139: 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 140: 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 141: 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 142: 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 143: 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 144: 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 145: 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 146: 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 147: 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 148: 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 149: 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 150: 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 151: 'PERF_PAPC_SU_SE2_STALLED_SC', + 152: 'PERF_PAPC_SU_SE3_STALLED_SC', + 153: 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', + 154: 'PERF_SMALL_PRIM_CULL_PRIM_1X1', + 155: 'PERF_SMALL_PRIM_CULL_PRIM_2X1', + 156: 'PERF_SMALL_PRIM_CULL_PRIM_1X2', + 157: 'PERF_SMALL_PRIM_CULL_PRIM_2X2', + 158: 'PERF_SMALL_PRIM_CULL_PRIM_3X1', + 159: 'PERF_SMALL_PRIM_CULL_PRIM_1X3', + 160: 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 161: 'PERF_SMALL_PRIM_CULL_PRIM_2X3', + 162: 'PERF_SMALL_PRIM_CULL_PRIM_NX1', + 163: 'PERF_SMALL_PRIM_CULL_PRIM_1XN', + 164: 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 165: 'PERF_SMALL_PRIM_CULL_PRIM_2XN', + 166: 'PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT', + 167: 'PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT', + 168: 'PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT', + 169: 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 170: 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 171: 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 172: 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 173: 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 174: 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 175: 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 176: 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 177: 'PERF_UTC_SIDEBAND_DRIVER_WAITING_ON_UTCL1', + 178: 'PERF_UTC_SIDEBAND_DRIVER_STALLING_CLIENT', + 179: 'PERF_UTC_SIDEBAND_DRIVER_BUSY', + 180: 'PERF_UTC_INDEX_DRIVER_WAITING_ON_UTCL1', + 181: 'PERF_UTC_INDEX_DRIVER_STALLING_CLIENT', + 182: 'PERF_UTC_INDEX_DRIVER_BUSY', + 183: 'PERF_UTC_POSITION_DRIVER_WAITING_ON_UTCL1', + 184: 'PERF_UTC_POSITION_DRIVER_STALLING_CLIENT', + 185: 'PERF_UTC_POSITION_DRIVER_BUSY', + 186: 'PERF_UTC_SIDEBAND_RECEIVER_STALLING_UTCL1', + 187: 'PERF_UTC_SIDEBAND_RECEIVER_STALLED_BY_ARBITER', + 188: 'PERF_UTC_SIDEBAND_RECEIVER_BUSY', + 189: 'PERF_UTC_INDEX_RECEIVER_STALLING_UTCL1', + 190: 'PERF_UTC_INDEX_RECEIVER_STALLED_BY_ARBITER', + 191: 'PERF_UTC_INDEX_RECEIVER_BUSY', + 192: 'PERF_UTC_POSITION_RECEIVER_STALLING_UTCL1', + 193: 'PERF_UTC_POSITION_RECEIVER_STALLED_BY_ARBITER', + 194: 'PERF_UTC_POSITION_RECEIVER_BUSY', + 195: 'PERF_TC_ARBITER_WAITING_FOR_TC_INTERFACE', + 196: 'PERF_TCIF_STALLING_CLIENT_NO_CREDITS', + 197: 'PERF_TCIF_BUSY', + 198: 'PERF_TCIF_SIDEBAND_RDREQ', + 199: 'PERF_TCIF_INDEX_RDREQ', + 200: 'PERF_TCIF_POSITION_RDREQ', + 201: 'PERF_SIDEBAND_WAITING_ON_UTCL1', + 202: 'PERF_SIDEBAND_WAITING_ON_FULL_SIDEBAND_MEMORY', + 203: 'PERF_WRITING_TO_SIDEBAND_MEMORY', + 204: 'PERF_SIDEBAND_EXPECTING_1_POSSIBLE_VALID_DWORD', + 205: 'PERF_SIDEBAND_EXPECTING_2_TO_15_POSSIBLE_VALID_DWORD', + 206: 'PERF_SIDEBAND_EXPECTING_16_POSSIBLE_VALID_DWORD', + 207: 'PERF_SIDEBAND_WAITING_ON_RETURNED_DATA', + 208: 'PERF_SIDEBAND_POP_BIT_FIFO_FULL', + 209: 'PERF_SIDEBAND_FIFO_VMID_FIFO_FULL', + 210: 'PERF_SIDEBAND_INVALID_REFETCH', + 211: 'PERF_SIDEBAND_QUALIFIED_BUSY', + 212: 'PERF_SIDEBAND_QUALIFIED_STARVED', + 213: 'PERF_SIDEBAND_0_VALID_DWORDS_RECEIVED_', + 214: 'PERF_SIDEBAND_1_TO_7_VALID_DWORDS_RECEIVED_', + 215: 'PERF_SIDEBAND_8_TO_15_VALID_DWORDS_RECEIVED_', + 216: 'PERF_SIDEBAND_16_VALID_DWORDS_RECEIVED_', + 217: 'PERF_INDEX_REQUEST_WAITING_ON_TOKENS', + 218: 'PERF_INDEX_REQUEST_WAITING_ON_FULL_RECEIVE_FIFO', + 219: 'PERF_INDEX_REQUEST_QUALIFIED_BUSY', + 220: 'PERF_INDEX_REQUEST_QUALIFIED_STARVED', + 221: 'PERF_INDEX_RECEIVE_WAITING_ON_RETURNED_CACHELINE', + 222: 'PERF_INDEX_RECEIVE_WAITING_ON_PRIM_INDICES_FIFO', + 223: 'PERF_INDEX_RECEIVE_PRIM_INDICES_FIFO_WRITE', + 224: 'PERF_INDEX_RECEIVE_QUALIFIED_BUSY', + 225: 'PERF_INDEX_RECEIVE_QUALIFIED_STARVED', + 226: 'PERF_INDEX_RECEIVE_0_VALID_DWORDS_THIS_CACHELINE', + 227: 'PERF_INDEX_RECEIVE_1_VALID_DWORDS_THIS_CACHELINE', + 228: 'PERF_INDEX_RECEIVE_2_VALID_DWORDS_THIS_CACHELINE', + 229: 'PERF_INDEX_RECEIVE_3_VALID_DWORDS_THIS_CACHELINE', + 230: 'PERF_INDEX_RECEIVE_4_VALID_DWORDS_THIS_CACHELINE', + 231: 'PERF_INDEX_RECEIVE_5_VALID_DWORDS_THIS_CACHELINE', + 232: 'PERF_INDEX_RECEIVE_6_VALID_DWORDS_THIS_CACHELINE', + 233: 'PERF_INDEX_RECEIVE_7_VALID_DWORDS_THIS_CACHELINE', + 234: 'PERF_INDEX_RECEIVE_8_VALID_DWORDS_THIS_CACHELINE', + 235: 'PERF_INDEX_RECEIVE_9_VALID_DWORDS_THIS_CACHELINE', + 236: 'PERF_INDEX_RECEIVE_10_VALID_DWORDS_THIS_CACHELINE', + 237: 'PERF_INDEX_RECEIVE_11_VALID_DWORDS_THIS_CACHELINE', + 238: 'PERF_INDEX_RECEIVE_12_VALID_DWORDS_THIS_CACHELINE', + 239: 'PERF_INDEX_RECEIVE_13_VALID_DWORDS_THIS_CACHELINE', + 240: 'PERF_INDEX_RECEIVE_14_VALID_DWORDS_THIS_CACHELINE', + 241: 'PERF_INDEX_RECEIVE_15_VALID_DWORDS_THIS_CACHELINE', + 242: 'PERF_INDEX_RECEIVE_16_VALID_DWORDS_THIS_CACHELINE', + 243: 'PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 244: 'PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 245: 'PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_V_FIFO', + 246: 'PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_S_FIFO', + 247: 'PERF_POS_REQ_STALLED_BY_FULL_PA_TO_WD_DEALLOC_INDEX_FIFO', + 248: 'PERF_POS_REQ_STALLED_BY_NO_TOKENS', + 249: 'PERF_POS_REQ_STARVED_BY_NO_PRIM', + 250: 'PERF_POS_REQ_STALLED_BY_UTCL1', + 251: 'PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 252: 'PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 253: 'PERF_POS_REQ_QUALIFIED_BUSY', + 254: 'PERF_POS_REQ_QUALIFIED_STARVED', + 255: 'PERF_POS_REQ_REUSE_0_NEW_VERTS_THIS_PRIM', + 256: 'PERF_POS_REQ_REUSE_1_NEW_VERTS_THIS_PRIM', + 257: 'PERF_POS_REQ_REUSE_2_NEW_VERTS_THIS_PRIM', + 258: 'PERF_POS_REQ_REUSE_3_NEW_VERTS_THIS_PRIM', + 259: 'PERF_POS_RET_FULL_FETCH_TO_SXIF_FIFO', + 260: 'PERF_POS_RET_FULL_PA_TO_WD_DEALLOC_POSITION_FIFO', + 261: 'PERF_POS_RET_WAITING_ON_RETURNED_CACHELINE', + 262: 'PERF_POS_RET_FETCH_TO_SXIF_FIFO_WRITE', + 263: 'PERF_POS_RET_QUALIFIED_BUSY', + 264: 'PERF_POS_RET_QUALIFIED_STARVED', + 265: 'PERF_POS_RET_1_CACHELINE_POSITION_USED', + 266: 'PERF_POS_RET_2_CACHELINE_POSITION_USED', + 267: 'PERF_POS_RET_3_CACHELINE_POSITION_USED', + 268: 'PERF_POS_RET_4_CACHELINE_POSITION_USED', + 269: 'PERF_TC_INDEX_LATENCY_BIN0', + 270: 'PERF_TC_INDEX_LATENCY_BIN1', + 271: 'PERF_TC_INDEX_LATENCY_BIN2', + 272: 'PERF_TC_INDEX_LATENCY_BIN3', + 273: 'PERF_TC_INDEX_LATENCY_BIN4', + 274: 'PERF_TC_INDEX_LATENCY_BIN5', + 275: 'PERF_TC_INDEX_LATENCY_BIN6', + 276: 'PERF_TC_INDEX_LATENCY_BIN7', + 277: 'PERF_TC_INDEX_LATENCY_BIN8', + 278: 'PERF_TC_INDEX_LATENCY_BIN9', + 279: 'PERF_TC_INDEX_LATENCY_BIN10', + 280: 'PERF_TC_INDEX_LATENCY_BIN11', + 281: 'PERF_TC_INDEX_LATENCY_BIN12', + 282: 'PERF_TC_INDEX_LATENCY_BIN13', + 283: 'PERF_TC_INDEX_LATENCY_BIN14', + 284: 'PERF_TC_INDEX_LATENCY_BIN15', + 285: 'PERF_TC_POSITION_LATENCY_BIN0', + 286: 'PERF_TC_POSITION_LATENCY_BIN1', + 287: 'PERF_TC_POSITION_LATENCY_BIN2', + 288: 'PERF_TC_POSITION_LATENCY_BIN3', + 289: 'PERF_TC_POSITION_LATENCY_BIN4', + 290: 'PERF_TC_POSITION_LATENCY_BIN5', + 291: 'PERF_TC_POSITION_LATENCY_BIN6', + 292: 'PERF_TC_POSITION_LATENCY_BIN7', + 293: 'PERF_TC_POSITION_LATENCY_BIN8', + 294: 'PERF_TC_POSITION_LATENCY_BIN9', + 295: 'PERF_TC_POSITION_LATENCY_BIN10', + 296: 'PERF_TC_POSITION_LATENCY_BIN11', + 297: 'PERF_TC_POSITION_LATENCY_BIN12', + 298: 'PERF_TC_POSITION_LATENCY_BIN13', + 299: 'PERF_TC_POSITION_LATENCY_BIN14', + 300: 'PERF_TC_POSITION_LATENCY_BIN15', + 301: 'PERF_TC_STREAM0_DATA_AVAILABLE', + 302: 'PERF_TC_STREAM1_DATA_AVAILABLE', + 303: 'PERF_TC_STREAM2_DATA_AVAILABLE', + 304: 'PERF_PAWD_DEALLOC_FIFO_IS_FULL', + 305: 'PERF_PAWD_DEALLOC_WAITING_TO_BE_READ', + 306: 'PERF_SHOOTDOWN_WAIT_ON_UTCL1', + 307: 'PERF_SHOOTDOWN_WAIT_ON_UTC_SIDEBAND', + 308: 'PERF_SHOOTDOWN_WAIT_ON_UTC_INDEX', + 309: 'PERF_SHOOTDOWN_WAIT_ON_UTC_POSITION', + 310: 'PERF_SHOOTDOWN_WAIT_ALL_CLEAN', + 311: 'PERF_SHOOTDOWN_WAIT_DEASSERT', + 312: 'PERF_UTCL1_TRANSLATION_MISS_CLIENT0', + 313: 'PERF_UTCL1_TRANSLATION_MISS_CLIENT1', + 314: 'PERF_UTCL1_TRANSLATION_MISS_CLIENT2', + 315: 'PERF_UTCL1_PERMISSION_MISS_CLIENT0', + 316: 'PERF_UTCL1_PERMISSION_MISS_CLIENT1', + 317: 'PERF_UTCL1_PERMISSION_MISS_CLIENT2', + 318: 'PERF_UTCL1_TRANSLATION_HIT_CLIENT0', + 319: 'PERF_UTCL1_TRANSLATION_HIT_CLIENT1', + 320: 'PERF_UTCL1_TRANSLATION_HIT_CLIENT2', + 321: 'PERF_UTCL1_REQUEST_CLIENT0', + 322: 'PERF_UTCL1_REQUEST_CLIENT1', + 323: 'PERF_UTCL1_REQUEST_CLIENT2', + 324: 'PERF_UTCL1_STALL_MISSFIFO_FULL', + 325: 'PERF_UTCL1_STALL_INFLIGHT_MAX', + 326: 'PERF_UTCL1_STALL_LRU_INFLIGHT', + 327: 'PERF_UTCL1_STALL_MULTI_MISS', + 328: 'PERF_UTCL1_LFIFO_FULL', + 329: 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT0', + 330: 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT1', + 331: 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT2', + 332: 'PERF_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 333: 'PERF_UTCL1_UTCL2_REQ', + 334: 'PERF_UTCL1_UTCL2_RET', + 335: 'PERF_UTCL1_UTCL2_INFLIGHT', + 336: 'PERF_CLIENT_UTCL1_INFLIGHT', + 337: 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 338: 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 339: 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 340: 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 341: 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 342: 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 343: 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 344: 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 345: 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 346: 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 347: 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 348: 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 349: 'PERF_PA_VERTEX_FIFO_FULL', + 350: 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', + 351: 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 352: 'PERF_PA_FETCH_TO_SXIF_FIFO_FULL', + 355: 'ENGG_CSB_MACHINE_IS_STARVED', + 356: 'ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 357: 'ENGG_CSB_MACHINE_STALLED_BY_SPI', + 358: 'ENGG_CSB_GE_INPUT_FIFO_FULL', + 359: 'ENGG_CSB_SPI_INPUT_FIFO_FULL', + 360: 'ENGG_CSB_OBJECTID_INPUT_FIFO_FULL', + 361: 'ENGG_CSB_PRIM_COUNT_EQ0', + 362: 'ENGG_CSB_GE_SENDING_SUBGROUP', + 363: 'ENGG_CSB_DELAY_BIN00', + 364: 'ENGG_CSB_DELAY_BIN01', + 365: 'ENGG_CSB_DELAY_BIN02', + 366: 'ENGG_CSB_DELAY_BIN03', + 367: 'ENGG_CSB_DELAY_BIN04', + 368: 'ENGG_CSB_DELAY_BIN05', + 369: 'ENGG_CSB_DELAY_BIN06', + 370: 'ENGG_CSB_DELAY_BIN07', + 371: 'ENGG_CSB_DELAY_BIN08', + 372: 'ENGG_CSB_DELAY_BIN09', + 373: 'ENGG_CSB_DELAY_BIN10', + 374: 'ENGG_CSB_DELAY_BIN11', + 375: 'ENGG_CSB_DELAY_BIN12', + 376: 'ENGG_CSB_DELAY_BIN13', + 377: 'ENGG_CSB_DELAY_BIN14', + 378: 'ENGG_CSB_DELAY_BIN15', + 379: 'ENGG_CSB_SPI_DELAY_BIN00', + 380: 'ENGG_CSB_SPI_DELAY_BIN01', + 381: 'ENGG_CSB_SPI_DELAY_BIN02', + 382: 'ENGG_CSB_SPI_DELAY_BIN03', + 383: 'ENGG_CSB_SPI_DELAY_BIN04', + 384: 'ENGG_CSB_SPI_DELAY_BIN05', + 385: 'ENGG_CSB_SPI_DELAY_BIN06', + 386: 'ENGG_CSB_SPI_DELAY_BIN07', + 387: 'ENGG_CSB_SPI_DELAY_BIN08', + 388: 'ENGG_CSB_SPI_DELAY_BIN09', + 389: 'ENGG_CSB_SPI_DELAY_BIN10', + 390: 'ENGG_CSB_SPI_DELAY_BIN11', + 391: 'ENGG_CSB_SPI_DELAY_BIN12', + 392: 'ENGG_CSB_SPI_DELAY_BIN13', + 393: 'ENGG_CSB_SPI_DELAY_BIN14', + 394: 'ENGG_CSB_SPI_DELAY_BIN15', + 395: 'ENGG_INDEX_REQ_STARVED', + 396: 'ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 397: 'ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 398: 'ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', + 399: 'ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 400: 'ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 401: 'ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 402: 'ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 403: 'ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 404: 'ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 405: 'ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 406: 'ENGG_INDEX_RET_SXRX_READING_EVENT', + 407: 'ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 408: 'ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 409: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 410: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 411: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 412: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 413: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS', + 414: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS', + 415: 'ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS', + 416: 'ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 417: 'ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 418: 'ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 419: 'ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 420: 'ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 421: 'ENGG_INDEX_PRIM_IF_QUALIFIED_BUSY', + 422: 'ENGG_INDEX_PRIM_IF_QUALIFIED_STARVED', + 423: 'ENGG_INDEX_PRIM_IF_REUSE_0_NEW_VERTS_THIS_PRIM', + 424: 'ENGG_INDEX_PRIM_IF_REUSE_1_NEW_VERTS_THIS_PRIM', + 425: 'ENGG_INDEX_PRIM_IF_REUSE_2_NEW_VERTS_THIS_PRIM', + 426: 'ENGG_INDEX_PRIM_IF_REUSE_3_NEW_VERTS_THIS_PRIM', + 427: 'ENGG_POS_REQ_STARVED', + 428: 'ENGG_POS_REQ_STALLED_BY_FULL_CLIPV_FIFO', +} +PERF_PAPC_PASX_REQ = 0 +PERF_PAPC_PASX_DISABLE_PIPE = 1 +PERF_PAPC_PASX_FIRST_VECTOR = 2 +PERF_PAPC_PASX_SECOND_VECTOR = 3 +PERF_PAPC_PASX_FIRST_DEAD = 4 +PERF_PAPC_PASX_SECOND_DEAD = 5 +PERF_PAPC_PASX_VTX_KILL_DISCARD = 6 +PERF_PAPC_PASX_VTX_NAN_DISCARD = 7 +PERF_PAPC_PA_INPUT_PRIM = 8 +PERF_PAPC_PA_INPUT_NULL_PRIM = 9 +PERF_PAPC_PA_INPUT_EVENT_FLAG = 10 +PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT = 11 +PERF_PAPC_PA_INPUT_END_OF_PACKET = 12 +PERF_PAPC_PA_INPUT_EXTENDED_EVENT = 13 +PERF_PAPC_CLPR_CULL_PRIM = 14 +PERF_PAPC_CLPR_VVUCP_CULL_PRIM = 15 +PERF_PAPC_CLPR_VV_CULL_PRIM = 16 +PERF_PAPC_CLPR_UCP_CULL_PRIM = 17 +PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM = 18 +PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM = 19 +PERF_PAPC_CLPR_CULL_TO_NULL_PRIM = 20 +PERF_PAPC_CLPR_VVUCP_CLIP_PRIM = 21 +PERF_PAPC_CLPR_VV_CLIP_PRIM = 22 +PERF_PAPC_CLPR_UCP_CLIP_PRIM = 23 +PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE = 24 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_1 = 25 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_2 = 26 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_3 = 27 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_4 = 28 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8 = 29 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12 = 30 +PERF_PAPC_CLPR_CLIP_PLANE_NEAR = 31 +PERF_PAPC_CLPR_CLIP_PLANE_FAR = 32 +PERF_PAPC_CLPR_CLIP_PLANE_LEFT = 33 +PERF_PAPC_CLPR_CLIP_PLANE_RIGHT = 34 +PERF_PAPC_CLPR_CLIP_PLANE_TOP = 35 +PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM = 36 +PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM = 37 +PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM = 38 +PERF_PAPC_CLSM_NULL_PRIM = 39 +PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM = 40 +PERF_PAPC_CLSM_CULL_TO_NULL_PRIM = 41 +PERF_PAPC_CLSM_OUT_PRIM_CNT_1 = 42 +PERF_PAPC_CLSM_OUT_PRIM_CNT_2 = 43 +PERF_PAPC_CLSM_OUT_PRIM_CNT_3 = 44 +PERF_PAPC_CLSM_OUT_PRIM_CNT_4 = 45 +PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8 = 46 +PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13 = 47 +PERF_PAPC_CLIPGA_VTE_KILL_PRIM = 48 +PERF_PAPC_SU_INPUT_PRIM = 49 +PERF_PAPC_SU_INPUT_CLIP_PRIM = 50 +PERF_PAPC_SU_INPUT_NULL_PRIM = 51 +PERF_PAPC_SU_INPUT_PRIM_DUAL = 52 +PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL = 53 +PERF_PAPC_SU_ZERO_AREA_CULL_PRIM = 54 +PERF_PAPC_SU_BACK_FACE_CULL_PRIM = 55 +PERF_PAPC_SU_FRONT_FACE_CULL_PRIM = 56 +PERF_PAPC_SU_POLYMODE_FACE_CULL = 57 +PERF_PAPC_SU_POLYMODE_BACK_CULL = 58 +PERF_PAPC_SU_POLYMODE_FRONT_CULL = 59 +PERF_PAPC_SU_POLYMODE_INVALID_FILL = 60 +PERF_PAPC_SU_OUTPUT_PRIM = 61 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM = 62 +PERF_PAPC_SU_OUTPUT_NULL_PRIM = 63 +PERF_PAPC_SU_OUTPUT_EVENT_FLAG = 64 +PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT = 65 +PERF_PAPC_SU_OUTPUT_END_OF_PACKET = 66 +PERF_PAPC_SU_OUTPUT_POLYMODE_FACE = 67 +PERF_PAPC_SU_OUTPUT_POLYMODE_BACK = 68 +PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT = 69 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE = 70 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK = 71 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT = 72 +PERF_PAPC_SU_OUTPUT_PRIM_DUAL = 73 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL = 74 +PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL = 75 +PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL = 76 +PERF_PAPC_PASX_REQ_IDLE = 77 +PERF_PAPC_PASX_REQ_BUSY = 78 +PERF_PAPC_PASX_REQ_STALLED = 79 +PERF_PAPC_PASX_REC_IDLE = 80 +PERF_PAPC_PASX_REC_BUSY = 81 +PERF_PAPC_PASX_REC_STARVED_SX = 82 +PERF_PAPC_PASX_REC_STALLED = 83 +PERF_PAPC_PASX_REC_STALLED_POS_MEM = 84 +PERF_PAPC_PASX_REC_STALLED_CCGSM_IN = 85 +PERF_PAPC_CCGSM_IDLE = 86 +PERF_PAPC_CCGSM_BUSY = 87 +PERF_PAPC_CCGSM_STALLED = 88 +PERF_PAPC_CLPRIM_IDLE = 89 +PERF_PAPC_CLPRIM_BUSY = 90 +PERF_PAPC_CLPRIM_STALLED = 91 +PERF_PAPC_CLPRIM_STARVED_CCGSM = 92 +PERF_PAPC_CLIPSM_IDLE = 93 +PERF_PAPC_CLIPSM_BUSY = 94 +PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH = 95 +PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ = 96 +PERF_PAPC_CLIPSM_WAIT_CLIPGA = 97 +PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP = 98 +PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM = 99 +PERF_PAPC_CLIPGA_IDLE = 100 +PERF_PAPC_CLIPGA_BUSY = 101 +PERF_PAPC_CLIPGA_STARVED_VTE_CLIP = 102 +PERF_PAPC_CLIPGA_STALLED = 103 +PERF_PAPC_CLIP_IDLE = 104 +PERF_PAPC_CLIP_BUSY = 105 +PERF_PAPC_SU_IDLE = 106 +PERF_PAPC_SU_BUSY = 107 +PERF_PAPC_SU_STARVED_CLIP = 108 +PERF_PAPC_SU_STALLED_SC = 109 +PERF_PAPC_CL_DYN_SCLK_VLD = 110 +PERF_PAPC_SU_DYN_SCLK_VLD = 111 +PERF_PAPC_PA_REG_SCLK_VLD = 112 +PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL = 113 +PERF_PAPC_PASX_SE0_REQ = 114 +PERF_PAPC_PASX_SE1_REQ = 115 +PERF_PAPC_PASX_SE0_FIRST_VECTOR = 116 +PERF_PAPC_PASX_SE0_SECOND_VECTOR = 117 +PERF_PAPC_PASX_SE1_FIRST_VECTOR = 118 +PERF_PAPC_PASX_SE1_SECOND_VECTOR = 119 +PERF_PAPC_SU_SE0_PRIM_FILTER_CULL = 120 +PERF_PAPC_SU_SE1_PRIM_FILTER_CULL = 121 +PERF_PAPC_SU_SE01_PRIM_FILTER_CULL = 122 +PERF_PAPC_SU_SE0_OUTPUT_PRIM = 123 +PERF_PAPC_SU_SE1_OUTPUT_PRIM = 124 +PERF_PAPC_SU_SE01_OUTPUT_PRIM = 125 +PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM = 126 +PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM = 127 +PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM = 128 +PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT = 129 +PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT = 130 +PERF_PAPC_SU_SE0_STALLED_SC = 131 +PERF_PAPC_SU_SE1_STALLED_SC = 132 +PERF_PAPC_SU_SE01_STALLED_SC = 133 +PERF_PAPC_CLSM_CLIPPING_PRIM = 134 +PERF_PAPC_SU_CULLED_PRIM = 135 +PERF_PAPC_SU_OUTPUT_EOPG = 136 +PERF_PAPC_SU_SE2_PRIM_FILTER_CULL = 137 +PERF_PAPC_SU_SE3_PRIM_FILTER_CULL = 138 +PERF_PAPC_SU_SE2_OUTPUT_PRIM = 139 +PERF_PAPC_SU_SE3_OUTPUT_PRIM = 140 +PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM = 141 +PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM = 142 +PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET = 143 +PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET = 144 +PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET = 145 +PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET = 146 +PERF_PAPC_SU_SE0_OUTPUT_EOPG = 147 +PERF_PAPC_SU_SE1_OUTPUT_EOPG = 148 +PERF_PAPC_SU_SE2_OUTPUT_EOPG = 149 +PERF_PAPC_SU_SE3_OUTPUT_EOPG = 150 +PERF_PAPC_SU_SE2_STALLED_SC = 151 +PERF_PAPC_SU_SE3_STALLED_SC = 152 +PERF_SU_SMALL_PRIM_FILTER_CULL_CNT = 153 +PERF_SMALL_PRIM_CULL_PRIM_1X1 = 154 +PERF_SMALL_PRIM_CULL_PRIM_2X1 = 155 +PERF_SMALL_PRIM_CULL_PRIM_1X2 = 156 +PERF_SMALL_PRIM_CULL_PRIM_2X2 = 157 +PERF_SMALL_PRIM_CULL_PRIM_3X1 = 158 +PERF_SMALL_PRIM_CULL_PRIM_1X3 = 159 +PERF_SMALL_PRIM_CULL_PRIM_3X2 = 160 +PERF_SMALL_PRIM_CULL_PRIM_2X3 = 161 +PERF_SMALL_PRIM_CULL_PRIM_NX1 = 162 +PERF_SMALL_PRIM_CULL_PRIM_1XN = 163 +PERF_SMALL_PRIM_CULL_PRIM_NX2 = 164 +PERF_SMALL_PRIM_CULL_PRIM_2XN = 165 +PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT = 166 +PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT = 167 +PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT = 168 +PERF_SC0_QUALIFIED_SEND_BUSY_EVENT = 169 +PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT = 170 +PERF_SC1_QUALIFIED_SEND_BUSY_EVENT = 171 +PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT = 172 +PERF_SC2_QUALIFIED_SEND_BUSY_EVENT = 173 +PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT = 174 +PERF_SC3_QUALIFIED_SEND_BUSY_EVENT = 175 +PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT = 176 +PERF_UTC_SIDEBAND_DRIVER_WAITING_ON_UTCL1 = 177 +PERF_UTC_SIDEBAND_DRIVER_STALLING_CLIENT = 178 +PERF_UTC_SIDEBAND_DRIVER_BUSY = 179 +PERF_UTC_INDEX_DRIVER_WAITING_ON_UTCL1 = 180 +PERF_UTC_INDEX_DRIVER_STALLING_CLIENT = 181 +PERF_UTC_INDEX_DRIVER_BUSY = 182 +PERF_UTC_POSITION_DRIVER_WAITING_ON_UTCL1 = 183 +PERF_UTC_POSITION_DRIVER_STALLING_CLIENT = 184 +PERF_UTC_POSITION_DRIVER_BUSY = 185 +PERF_UTC_SIDEBAND_RECEIVER_STALLING_UTCL1 = 186 +PERF_UTC_SIDEBAND_RECEIVER_STALLED_BY_ARBITER = 187 +PERF_UTC_SIDEBAND_RECEIVER_BUSY = 188 +PERF_UTC_INDEX_RECEIVER_STALLING_UTCL1 = 189 +PERF_UTC_INDEX_RECEIVER_STALLED_BY_ARBITER = 190 +PERF_UTC_INDEX_RECEIVER_BUSY = 191 +PERF_UTC_POSITION_RECEIVER_STALLING_UTCL1 = 192 +PERF_UTC_POSITION_RECEIVER_STALLED_BY_ARBITER = 193 +PERF_UTC_POSITION_RECEIVER_BUSY = 194 +PERF_TC_ARBITER_WAITING_FOR_TC_INTERFACE = 195 +PERF_TCIF_STALLING_CLIENT_NO_CREDITS = 196 +PERF_TCIF_BUSY = 197 +PERF_TCIF_SIDEBAND_RDREQ = 198 +PERF_TCIF_INDEX_RDREQ = 199 +PERF_TCIF_POSITION_RDREQ = 200 +PERF_SIDEBAND_WAITING_ON_UTCL1 = 201 +PERF_SIDEBAND_WAITING_ON_FULL_SIDEBAND_MEMORY = 202 +PERF_WRITING_TO_SIDEBAND_MEMORY = 203 +PERF_SIDEBAND_EXPECTING_1_POSSIBLE_VALID_DWORD = 204 +PERF_SIDEBAND_EXPECTING_2_TO_15_POSSIBLE_VALID_DWORD = 205 +PERF_SIDEBAND_EXPECTING_16_POSSIBLE_VALID_DWORD = 206 +PERF_SIDEBAND_WAITING_ON_RETURNED_DATA = 207 +PERF_SIDEBAND_POP_BIT_FIFO_FULL = 208 +PERF_SIDEBAND_FIFO_VMID_FIFO_FULL = 209 +PERF_SIDEBAND_INVALID_REFETCH = 210 +PERF_SIDEBAND_QUALIFIED_BUSY = 211 +PERF_SIDEBAND_QUALIFIED_STARVED = 212 +PERF_SIDEBAND_0_VALID_DWORDS_RECEIVED_ = 213 +PERF_SIDEBAND_1_TO_7_VALID_DWORDS_RECEIVED_ = 214 +PERF_SIDEBAND_8_TO_15_VALID_DWORDS_RECEIVED_ = 215 +PERF_SIDEBAND_16_VALID_DWORDS_RECEIVED_ = 216 +PERF_INDEX_REQUEST_WAITING_ON_TOKENS = 217 +PERF_INDEX_REQUEST_WAITING_ON_FULL_RECEIVE_FIFO = 218 +PERF_INDEX_REQUEST_QUALIFIED_BUSY = 219 +PERF_INDEX_REQUEST_QUALIFIED_STARVED = 220 +PERF_INDEX_RECEIVE_WAITING_ON_RETURNED_CACHELINE = 221 +PERF_INDEX_RECEIVE_WAITING_ON_PRIM_INDICES_FIFO = 222 +PERF_INDEX_RECEIVE_PRIM_INDICES_FIFO_WRITE = 223 +PERF_INDEX_RECEIVE_QUALIFIED_BUSY = 224 +PERF_INDEX_RECEIVE_QUALIFIED_STARVED = 225 +PERF_INDEX_RECEIVE_0_VALID_DWORDS_THIS_CACHELINE = 226 +PERF_INDEX_RECEIVE_1_VALID_DWORDS_THIS_CACHELINE = 227 +PERF_INDEX_RECEIVE_2_VALID_DWORDS_THIS_CACHELINE = 228 +PERF_INDEX_RECEIVE_3_VALID_DWORDS_THIS_CACHELINE = 229 +PERF_INDEX_RECEIVE_4_VALID_DWORDS_THIS_CACHELINE = 230 +PERF_INDEX_RECEIVE_5_VALID_DWORDS_THIS_CACHELINE = 231 +PERF_INDEX_RECEIVE_6_VALID_DWORDS_THIS_CACHELINE = 232 +PERF_INDEX_RECEIVE_7_VALID_DWORDS_THIS_CACHELINE = 233 +PERF_INDEX_RECEIVE_8_VALID_DWORDS_THIS_CACHELINE = 234 +PERF_INDEX_RECEIVE_9_VALID_DWORDS_THIS_CACHELINE = 235 +PERF_INDEX_RECEIVE_10_VALID_DWORDS_THIS_CACHELINE = 236 +PERF_INDEX_RECEIVE_11_VALID_DWORDS_THIS_CACHELINE = 237 +PERF_INDEX_RECEIVE_12_VALID_DWORDS_THIS_CACHELINE = 238 +PERF_INDEX_RECEIVE_13_VALID_DWORDS_THIS_CACHELINE = 239 +PERF_INDEX_RECEIVE_14_VALID_DWORDS_THIS_CACHELINE = 240 +PERF_INDEX_RECEIVE_15_VALID_DWORDS_THIS_CACHELINE = 241 +PERF_INDEX_RECEIVE_16_VALID_DWORDS_THIS_CACHELINE = 242 +PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO = 243 +PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO = 244 +PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_V_FIFO = 245 +PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_S_FIFO = 246 +PERF_POS_REQ_STALLED_BY_FULL_PA_TO_WD_DEALLOC_INDEX_FIFO = 247 +PERF_POS_REQ_STALLED_BY_NO_TOKENS = 248 +PERF_POS_REQ_STARVED_BY_NO_PRIM = 249 +PERF_POS_REQ_STALLED_BY_UTCL1 = 250 +PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_WRITE = 251 +PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE = 252 +PERF_POS_REQ_QUALIFIED_BUSY = 253 +PERF_POS_REQ_QUALIFIED_STARVED = 254 +PERF_POS_REQ_REUSE_0_NEW_VERTS_THIS_PRIM = 255 +PERF_POS_REQ_REUSE_1_NEW_VERTS_THIS_PRIM = 256 +PERF_POS_REQ_REUSE_2_NEW_VERTS_THIS_PRIM = 257 +PERF_POS_REQ_REUSE_3_NEW_VERTS_THIS_PRIM = 258 +PERF_POS_RET_FULL_FETCH_TO_SXIF_FIFO = 259 +PERF_POS_RET_FULL_PA_TO_WD_DEALLOC_POSITION_FIFO = 260 +PERF_POS_RET_WAITING_ON_RETURNED_CACHELINE = 261 +PERF_POS_RET_FETCH_TO_SXIF_FIFO_WRITE = 262 +PERF_POS_RET_QUALIFIED_BUSY = 263 +PERF_POS_RET_QUALIFIED_STARVED = 264 +PERF_POS_RET_1_CACHELINE_POSITION_USED = 265 +PERF_POS_RET_2_CACHELINE_POSITION_USED = 266 +PERF_POS_RET_3_CACHELINE_POSITION_USED = 267 +PERF_POS_RET_4_CACHELINE_POSITION_USED = 268 +PERF_TC_INDEX_LATENCY_BIN0 = 269 +PERF_TC_INDEX_LATENCY_BIN1 = 270 +PERF_TC_INDEX_LATENCY_BIN2 = 271 +PERF_TC_INDEX_LATENCY_BIN3 = 272 +PERF_TC_INDEX_LATENCY_BIN4 = 273 +PERF_TC_INDEX_LATENCY_BIN5 = 274 +PERF_TC_INDEX_LATENCY_BIN6 = 275 +PERF_TC_INDEX_LATENCY_BIN7 = 276 +PERF_TC_INDEX_LATENCY_BIN8 = 277 +PERF_TC_INDEX_LATENCY_BIN9 = 278 +PERF_TC_INDEX_LATENCY_BIN10 = 279 +PERF_TC_INDEX_LATENCY_BIN11 = 280 +PERF_TC_INDEX_LATENCY_BIN12 = 281 +PERF_TC_INDEX_LATENCY_BIN13 = 282 +PERF_TC_INDEX_LATENCY_BIN14 = 283 +PERF_TC_INDEX_LATENCY_BIN15 = 284 +PERF_TC_POSITION_LATENCY_BIN0 = 285 +PERF_TC_POSITION_LATENCY_BIN1 = 286 +PERF_TC_POSITION_LATENCY_BIN2 = 287 +PERF_TC_POSITION_LATENCY_BIN3 = 288 +PERF_TC_POSITION_LATENCY_BIN4 = 289 +PERF_TC_POSITION_LATENCY_BIN5 = 290 +PERF_TC_POSITION_LATENCY_BIN6 = 291 +PERF_TC_POSITION_LATENCY_BIN7 = 292 +PERF_TC_POSITION_LATENCY_BIN8 = 293 +PERF_TC_POSITION_LATENCY_BIN9 = 294 +PERF_TC_POSITION_LATENCY_BIN10 = 295 +PERF_TC_POSITION_LATENCY_BIN11 = 296 +PERF_TC_POSITION_LATENCY_BIN12 = 297 +PERF_TC_POSITION_LATENCY_BIN13 = 298 +PERF_TC_POSITION_LATENCY_BIN14 = 299 +PERF_TC_POSITION_LATENCY_BIN15 = 300 +PERF_TC_STREAM0_DATA_AVAILABLE = 301 +PERF_TC_STREAM1_DATA_AVAILABLE = 302 +PERF_TC_STREAM2_DATA_AVAILABLE = 303 +PERF_PAWD_DEALLOC_FIFO_IS_FULL = 304 +PERF_PAWD_DEALLOC_WAITING_TO_BE_READ = 305 +PERF_SHOOTDOWN_WAIT_ON_UTCL1 = 306 +PERF_SHOOTDOWN_WAIT_ON_UTC_SIDEBAND = 307 +PERF_SHOOTDOWN_WAIT_ON_UTC_INDEX = 308 +PERF_SHOOTDOWN_WAIT_ON_UTC_POSITION = 309 +PERF_SHOOTDOWN_WAIT_ALL_CLEAN = 310 +PERF_SHOOTDOWN_WAIT_DEASSERT = 311 +PERF_UTCL1_TRANSLATION_MISS_CLIENT0 = 312 +PERF_UTCL1_TRANSLATION_MISS_CLIENT1 = 313 +PERF_UTCL1_TRANSLATION_MISS_CLIENT2 = 314 +PERF_UTCL1_PERMISSION_MISS_CLIENT0 = 315 +PERF_UTCL1_PERMISSION_MISS_CLIENT1 = 316 +PERF_UTCL1_PERMISSION_MISS_CLIENT2 = 317 +PERF_UTCL1_TRANSLATION_HIT_CLIENT0 = 318 +PERF_UTCL1_TRANSLATION_HIT_CLIENT1 = 319 +PERF_UTCL1_TRANSLATION_HIT_CLIENT2 = 320 +PERF_UTCL1_REQUEST_CLIENT0 = 321 +PERF_UTCL1_REQUEST_CLIENT1 = 322 +PERF_UTCL1_REQUEST_CLIENT2 = 323 +PERF_UTCL1_STALL_MISSFIFO_FULL = 324 +PERF_UTCL1_STALL_INFLIGHT_MAX = 325 +PERF_UTCL1_STALL_LRU_INFLIGHT = 326 +PERF_UTCL1_STALL_MULTI_MISS = 327 +PERF_UTCL1_LFIFO_FULL = 328 +PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT0 = 329 +PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT1 = 330 +PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT2 = 331 +PERF_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS = 332 +PERF_UTCL1_UTCL2_REQ = 333 +PERF_UTCL1_UTCL2_RET = 334 +PERF_UTCL1_UTCL2_INFLIGHT = 335 +PERF_CLIENT_UTCL1_INFLIGHT = 336 +PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED = 337 +PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND = 338 +PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND = 339 +PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED = 340 +PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND = 341 +PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND = 342 +PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED = 343 +PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND = 344 +PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND = 345 +PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED = 346 +PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND = 347 +PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND = 348 +PERF_PA_VERTEX_FIFO_FULL = 349 +PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL = 350 +PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL = 351 +PERF_PA_FETCH_TO_SXIF_FIFO_FULL = 352 +ENGG_CSB_MACHINE_IS_STARVED = 355 +ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY = 356 +ENGG_CSB_MACHINE_STALLED_BY_SPI = 357 +ENGG_CSB_GE_INPUT_FIFO_FULL = 358 +ENGG_CSB_SPI_INPUT_FIFO_FULL = 359 +ENGG_CSB_OBJECTID_INPUT_FIFO_FULL = 360 +ENGG_CSB_PRIM_COUNT_EQ0 = 361 +ENGG_CSB_GE_SENDING_SUBGROUP = 362 +ENGG_CSB_DELAY_BIN00 = 363 +ENGG_CSB_DELAY_BIN01 = 364 +ENGG_CSB_DELAY_BIN02 = 365 +ENGG_CSB_DELAY_BIN03 = 366 +ENGG_CSB_DELAY_BIN04 = 367 +ENGG_CSB_DELAY_BIN05 = 368 +ENGG_CSB_DELAY_BIN06 = 369 +ENGG_CSB_DELAY_BIN07 = 370 +ENGG_CSB_DELAY_BIN08 = 371 +ENGG_CSB_DELAY_BIN09 = 372 +ENGG_CSB_DELAY_BIN10 = 373 +ENGG_CSB_DELAY_BIN11 = 374 +ENGG_CSB_DELAY_BIN12 = 375 +ENGG_CSB_DELAY_BIN13 = 376 +ENGG_CSB_DELAY_BIN14 = 377 +ENGG_CSB_DELAY_BIN15 = 378 +ENGG_CSB_SPI_DELAY_BIN00 = 379 +ENGG_CSB_SPI_DELAY_BIN01 = 380 +ENGG_CSB_SPI_DELAY_BIN02 = 381 +ENGG_CSB_SPI_DELAY_BIN03 = 382 +ENGG_CSB_SPI_DELAY_BIN04 = 383 +ENGG_CSB_SPI_DELAY_BIN05 = 384 +ENGG_CSB_SPI_DELAY_BIN06 = 385 +ENGG_CSB_SPI_DELAY_BIN07 = 386 +ENGG_CSB_SPI_DELAY_BIN08 = 387 +ENGG_CSB_SPI_DELAY_BIN09 = 388 +ENGG_CSB_SPI_DELAY_BIN10 = 389 +ENGG_CSB_SPI_DELAY_BIN11 = 390 +ENGG_CSB_SPI_DELAY_BIN12 = 391 +ENGG_CSB_SPI_DELAY_BIN13 = 392 +ENGG_CSB_SPI_DELAY_BIN14 = 393 +ENGG_CSB_SPI_DELAY_BIN15 = 394 +ENGG_INDEX_REQ_STARVED = 395 +ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 396 +ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 397 +ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS = 398 +ENGG_INDEX_RET_REQ2RTN_FIFO_FULL = 399 +ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY = 400 +ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL = 401 +ENGG_INDEX_RET_SXRX_STARVED_BY_CSB = 402 +ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS = 403 +ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO = 404 +ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO = 405 +ENGG_INDEX_RET_SXRX_READING_EVENT = 406 +ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP = 407 +ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0 = 408 +ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL = 409 +ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL = 410 +ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL = 411 +ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL = 412 +ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS = 413 +ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS = 414 +ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS = 415 +ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO = 416 +ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO = 417 +ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM = 418 +ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE = 419 +ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE = 420 +ENGG_INDEX_PRIM_IF_QUALIFIED_BUSY = 421 +ENGG_INDEX_PRIM_IF_QUALIFIED_STARVED = 422 +ENGG_INDEX_PRIM_IF_REUSE_0_NEW_VERTS_THIS_PRIM = 423 +ENGG_INDEX_PRIM_IF_REUSE_1_NEW_VERTS_THIS_PRIM = 424 +ENGG_INDEX_PRIM_IF_REUSE_2_NEW_VERTS_THIS_PRIM = 425 +ENGG_INDEX_PRIM_IF_REUSE_3_NEW_VERTS_THIS_PRIM = 426 +ENGG_POS_REQ_STARVED = 427 +ENGG_POS_REQ_STALLED_BY_FULL_CLIPV_FIFO = 428 +SU_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SC_PERFCNT_SEL' +SC_PERFCNT_SEL__enumvalues = { + 0: 'SC_SRPS_WINDOW_VALID', + 1: 'SC_PSSW_WINDOW_VALID', + 2: 'SC_TPQZ_WINDOW_VALID', + 3: 'SC_QZQP_WINDOW_VALID', + 4: 'SC_TRPK_WINDOW_VALID', + 5: 'SC_SRPS_WINDOW_VALID_BUSY', + 6: 'SC_PSSW_WINDOW_VALID_BUSY', + 7: 'SC_TPQZ_WINDOW_VALID_BUSY', + 8: 'SC_QZQP_WINDOW_VALID_BUSY', + 9: 'SC_TRPK_WINDOW_VALID_BUSY', + 10: 'SC_STARVED_BY_PA', + 11: 'SC_STALLED_BY_PRIMFIFO', + 12: 'SC_STALLED_BY_DB_TILE', + 13: 'SC_STARVED_BY_DB_TILE', + 14: 'SC_STALLED_BY_TILEORDERFIFO', + 15: 'SC_STALLED_BY_TILEFIFO', + 16: 'SC_STALLED_BY_DB_QUAD', + 17: 'SC_STARVED_BY_DB_QUAD', + 18: 'SC_STALLED_BY_QUADFIFO', + 19: 'SC_STALLED_BY_BCI', + 20: 'SC_STALLED_BY_SPI', + 21: 'SC_SCISSOR_DISCARD', + 22: 'SC_BB_DISCARD', + 23: 'SC_SUPERTILE_COUNT', + 24: 'SC_SUPERTILE_PER_PRIM_H0', + 25: 'SC_SUPERTILE_PER_PRIM_H1', + 26: 'SC_SUPERTILE_PER_PRIM_H2', + 27: 'SC_SUPERTILE_PER_PRIM_H3', + 28: 'SC_SUPERTILE_PER_PRIM_H4', + 29: 'SC_SUPERTILE_PER_PRIM_H5', + 30: 'SC_SUPERTILE_PER_PRIM_H6', + 31: 'SC_SUPERTILE_PER_PRIM_H7', + 32: 'SC_SUPERTILE_PER_PRIM_H8', + 33: 'SC_SUPERTILE_PER_PRIM_H9', + 34: 'SC_SUPERTILE_PER_PRIM_H10', + 35: 'SC_SUPERTILE_PER_PRIM_H11', + 36: 'SC_SUPERTILE_PER_PRIM_H12', + 37: 'SC_SUPERTILE_PER_PRIM_H13', + 38: 'SC_SUPERTILE_PER_PRIM_H14', + 39: 'SC_SUPERTILE_PER_PRIM_H15', + 40: 'SC_SUPERTILE_PER_PRIM_H16', + 41: 'SC_TILE_PER_PRIM_H0', + 42: 'SC_TILE_PER_PRIM_H1', + 43: 'SC_TILE_PER_PRIM_H2', + 44: 'SC_TILE_PER_PRIM_H3', + 45: 'SC_TILE_PER_PRIM_H4', + 46: 'SC_TILE_PER_PRIM_H5', + 47: 'SC_TILE_PER_PRIM_H6', + 48: 'SC_TILE_PER_PRIM_H7', + 49: 'SC_TILE_PER_PRIM_H8', + 50: 'SC_TILE_PER_PRIM_H9', + 51: 'SC_TILE_PER_PRIM_H10', + 52: 'SC_TILE_PER_PRIM_H11', + 53: 'SC_TILE_PER_PRIM_H12', + 54: 'SC_TILE_PER_PRIM_H13', + 55: 'SC_TILE_PER_PRIM_H14', + 56: 'SC_TILE_PER_PRIM_H15', + 57: 'SC_TILE_PER_PRIM_H16', + 58: 'SC_TILE_PER_SUPERTILE_H0', + 59: 'SC_TILE_PER_SUPERTILE_H1', + 60: 'SC_TILE_PER_SUPERTILE_H2', + 61: 'SC_TILE_PER_SUPERTILE_H3', + 62: 'SC_TILE_PER_SUPERTILE_H4', + 63: 'SC_TILE_PER_SUPERTILE_H5', + 64: 'SC_TILE_PER_SUPERTILE_H6', + 65: 'SC_TILE_PER_SUPERTILE_H7', + 66: 'SC_TILE_PER_SUPERTILE_H8', + 67: 'SC_TILE_PER_SUPERTILE_H9', + 68: 'SC_TILE_PER_SUPERTILE_H10', + 69: 'SC_TILE_PER_SUPERTILE_H11', + 70: 'SC_TILE_PER_SUPERTILE_H12', + 71: 'SC_TILE_PER_SUPERTILE_H13', + 72: 'SC_TILE_PER_SUPERTILE_H14', + 73: 'SC_TILE_PER_SUPERTILE_H15', + 74: 'SC_TILE_PER_SUPERTILE_H16', + 75: 'SC_TILE_PICKED_H1', + 76: 'SC_TILE_PICKED_H2', + 77: 'SC_TILE_PICKED_H3', + 78: 'SC_TILE_PICKED_H4', + 79: 'SC_QZ0_TILE_COUNT', + 80: 'SC_QZ1_TILE_COUNT', + 81: 'SC_QZ2_TILE_COUNT', + 82: 'SC_QZ3_TILE_COUNT', + 83: 'SC_QZ0_TILE_COVERED_COUNT', + 84: 'SC_QZ1_TILE_COVERED_COUNT', + 85: 'SC_QZ2_TILE_COVERED_COUNT', + 86: 'SC_QZ3_TILE_COVERED_COUNT', + 87: 'SC_QZ0_TILE_NOT_COVERED_COUNT', + 88: 'SC_QZ1_TILE_NOT_COVERED_COUNT', + 89: 'SC_QZ2_TILE_NOT_COVERED_COUNT', + 90: 'SC_QZ3_TILE_NOT_COVERED_COUNT', + 91: 'SC_QZ0_QUAD_PER_TILE_H0', + 92: 'SC_QZ0_QUAD_PER_TILE_H1', + 93: 'SC_QZ0_QUAD_PER_TILE_H2', + 94: 'SC_QZ0_QUAD_PER_TILE_H3', + 95: 'SC_QZ0_QUAD_PER_TILE_H4', + 96: 'SC_QZ0_QUAD_PER_TILE_H5', + 97: 'SC_QZ0_QUAD_PER_TILE_H6', + 98: 'SC_QZ0_QUAD_PER_TILE_H7', + 99: 'SC_QZ0_QUAD_PER_TILE_H8', + 100: 'SC_QZ0_QUAD_PER_TILE_H9', + 101: 'SC_QZ0_QUAD_PER_TILE_H10', + 102: 'SC_QZ0_QUAD_PER_TILE_H11', + 103: 'SC_QZ0_QUAD_PER_TILE_H12', + 104: 'SC_QZ0_QUAD_PER_TILE_H13', + 105: 'SC_QZ0_QUAD_PER_TILE_H14', + 106: 'SC_QZ0_QUAD_PER_TILE_H15', + 107: 'SC_QZ0_QUAD_PER_TILE_H16', + 108: 'SC_QZ1_QUAD_PER_TILE_H0', + 109: 'SC_QZ1_QUAD_PER_TILE_H1', + 110: 'SC_QZ1_QUAD_PER_TILE_H2', + 111: 'SC_QZ1_QUAD_PER_TILE_H3', + 112: 'SC_QZ1_QUAD_PER_TILE_H4', + 113: 'SC_QZ1_QUAD_PER_TILE_H5', + 114: 'SC_QZ1_QUAD_PER_TILE_H6', + 115: 'SC_QZ1_QUAD_PER_TILE_H7', + 116: 'SC_QZ1_QUAD_PER_TILE_H8', + 117: 'SC_QZ1_QUAD_PER_TILE_H9', + 118: 'SC_QZ1_QUAD_PER_TILE_H10', + 119: 'SC_QZ1_QUAD_PER_TILE_H11', + 120: 'SC_QZ1_QUAD_PER_TILE_H12', + 121: 'SC_QZ1_QUAD_PER_TILE_H13', + 122: 'SC_QZ1_QUAD_PER_TILE_H14', + 123: 'SC_QZ1_QUAD_PER_TILE_H15', + 124: 'SC_QZ1_QUAD_PER_TILE_H16', + 125: 'SC_QZ2_QUAD_PER_TILE_H0', + 126: 'SC_QZ2_QUAD_PER_TILE_H1', + 127: 'SC_QZ2_QUAD_PER_TILE_H2', + 128: 'SC_QZ2_QUAD_PER_TILE_H3', + 129: 'SC_QZ2_QUAD_PER_TILE_H4', + 130: 'SC_QZ2_QUAD_PER_TILE_H5', + 131: 'SC_QZ2_QUAD_PER_TILE_H6', + 132: 'SC_QZ2_QUAD_PER_TILE_H7', + 133: 'SC_QZ2_QUAD_PER_TILE_H8', + 134: 'SC_QZ2_QUAD_PER_TILE_H9', + 135: 'SC_QZ2_QUAD_PER_TILE_H10', + 136: 'SC_QZ2_QUAD_PER_TILE_H11', + 137: 'SC_QZ2_QUAD_PER_TILE_H12', + 138: 'SC_QZ2_QUAD_PER_TILE_H13', + 139: 'SC_QZ2_QUAD_PER_TILE_H14', + 140: 'SC_QZ2_QUAD_PER_TILE_H15', + 141: 'SC_QZ2_QUAD_PER_TILE_H16', + 142: 'SC_QZ3_QUAD_PER_TILE_H0', + 143: 'SC_QZ3_QUAD_PER_TILE_H1', + 144: 'SC_QZ3_QUAD_PER_TILE_H2', + 145: 'SC_QZ3_QUAD_PER_TILE_H3', + 146: 'SC_QZ3_QUAD_PER_TILE_H4', + 147: 'SC_QZ3_QUAD_PER_TILE_H5', + 148: 'SC_QZ3_QUAD_PER_TILE_H6', + 149: 'SC_QZ3_QUAD_PER_TILE_H7', + 150: 'SC_QZ3_QUAD_PER_TILE_H8', + 151: 'SC_QZ3_QUAD_PER_TILE_H9', + 152: 'SC_QZ3_QUAD_PER_TILE_H10', + 153: 'SC_QZ3_QUAD_PER_TILE_H11', + 154: 'SC_QZ3_QUAD_PER_TILE_H12', + 155: 'SC_QZ3_QUAD_PER_TILE_H13', + 156: 'SC_QZ3_QUAD_PER_TILE_H14', + 157: 'SC_QZ3_QUAD_PER_TILE_H15', + 158: 'SC_QZ3_QUAD_PER_TILE_H16', + 159: 'SC_QZ0_QUAD_COUNT', + 160: 'SC_QZ1_QUAD_COUNT', + 161: 'SC_QZ2_QUAD_COUNT', + 162: 'SC_QZ3_QUAD_COUNT', + 163: 'SC_P0_HIZ_TILE_COUNT', + 164: 'SC_P1_HIZ_TILE_COUNT', + 165: 'SC_P2_HIZ_TILE_COUNT', + 166: 'SC_P3_HIZ_TILE_COUNT', + 167: 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 168: 'SC_P0_HIZ_QUAD_PER_TILE_H1', + 169: 'SC_P0_HIZ_QUAD_PER_TILE_H2', + 170: 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 171: 'SC_P0_HIZ_QUAD_PER_TILE_H4', + 172: 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 173: 'SC_P0_HIZ_QUAD_PER_TILE_H6', + 174: 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 175: 'SC_P0_HIZ_QUAD_PER_TILE_H8', + 176: 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 177: 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 178: 'SC_P0_HIZ_QUAD_PER_TILE_H11', + 179: 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 180: 'SC_P0_HIZ_QUAD_PER_TILE_H13', + 181: 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 182: 'SC_P0_HIZ_QUAD_PER_TILE_H15', + 183: 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 184: 'SC_P1_HIZ_QUAD_PER_TILE_H0', + 185: 'SC_P1_HIZ_QUAD_PER_TILE_H1', + 186: 'SC_P1_HIZ_QUAD_PER_TILE_H2', + 187: 'SC_P1_HIZ_QUAD_PER_TILE_H3', + 188: 'SC_P1_HIZ_QUAD_PER_TILE_H4', + 189: 'SC_P1_HIZ_QUAD_PER_TILE_H5', + 190: 'SC_P1_HIZ_QUAD_PER_TILE_H6', + 191: 'SC_P1_HIZ_QUAD_PER_TILE_H7', + 192: 'SC_P1_HIZ_QUAD_PER_TILE_H8', + 193: 'SC_P1_HIZ_QUAD_PER_TILE_H9', + 194: 'SC_P1_HIZ_QUAD_PER_TILE_H10', + 195: 'SC_P1_HIZ_QUAD_PER_TILE_H11', + 196: 'SC_P1_HIZ_QUAD_PER_TILE_H12', + 197: 'SC_P1_HIZ_QUAD_PER_TILE_H13', + 198: 'SC_P1_HIZ_QUAD_PER_TILE_H14', + 199: 'SC_P1_HIZ_QUAD_PER_TILE_H15', + 200: 'SC_P1_HIZ_QUAD_PER_TILE_H16', + 201: 'SC_P2_HIZ_QUAD_PER_TILE_H0', + 202: 'SC_P2_HIZ_QUAD_PER_TILE_H1', + 203: 'SC_P2_HIZ_QUAD_PER_TILE_H2', + 204: 'SC_P2_HIZ_QUAD_PER_TILE_H3', + 205: 'SC_P2_HIZ_QUAD_PER_TILE_H4', + 206: 'SC_P2_HIZ_QUAD_PER_TILE_H5', + 207: 'SC_P2_HIZ_QUAD_PER_TILE_H6', + 208: 'SC_P2_HIZ_QUAD_PER_TILE_H7', + 209: 'SC_P2_HIZ_QUAD_PER_TILE_H8', + 210: 'SC_P2_HIZ_QUAD_PER_TILE_H9', + 211: 'SC_P2_HIZ_QUAD_PER_TILE_H10', + 212: 'SC_P2_HIZ_QUAD_PER_TILE_H11', + 213: 'SC_P2_HIZ_QUAD_PER_TILE_H12', + 214: 'SC_P2_HIZ_QUAD_PER_TILE_H13', + 215: 'SC_P2_HIZ_QUAD_PER_TILE_H14', + 216: 'SC_P2_HIZ_QUAD_PER_TILE_H15', + 217: 'SC_P2_HIZ_QUAD_PER_TILE_H16', + 218: 'SC_P3_HIZ_QUAD_PER_TILE_H0', + 219: 'SC_P3_HIZ_QUAD_PER_TILE_H1', + 220: 'SC_P3_HIZ_QUAD_PER_TILE_H2', + 221: 'SC_P3_HIZ_QUAD_PER_TILE_H3', + 222: 'SC_P3_HIZ_QUAD_PER_TILE_H4', + 223: 'SC_P3_HIZ_QUAD_PER_TILE_H5', + 224: 'SC_P3_HIZ_QUAD_PER_TILE_H6', + 225: 'SC_P3_HIZ_QUAD_PER_TILE_H7', + 226: 'SC_P3_HIZ_QUAD_PER_TILE_H8', + 227: 'SC_P3_HIZ_QUAD_PER_TILE_H9', + 228: 'SC_P3_HIZ_QUAD_PER_TILE_H10', + 229: 'SC_P3_HIZ_QUAD_PER_TILE_H11', + 230: 'SC_P3_HIZ_QUAD_PER_TILE_H12', + 231: 'SC_P3_HIZ_QUAD_PER_TILE_H13', + 232: 'SC_P3_HIZ_QUAD_PER_TILE_H14', + 233: 'SC_P3_HIZ_QUAD_PER_TILE_H15', + 234: 'SC_P3_HIZ_QUAD_PER_TILE_H16', + 235: 'SC_P0_HIZ_QUAD_COUNT', + 236: 'SC_P1_HIZ_QUAD_COUNT', + 237: 'SC_P2_HIZ_QUAD_COUNT', + 238: 'SC_P3_HIZ_QUAD_COUNT', + 239: 'SC_P0_DETAIL_QUAD_COUNT', + 240: 'SC_P1_DETAIL_QUAD_COUNT', + 241: 'SC_P2_DETAIL_QUAD_COUNT', + 242: 'SC_P3_DETAIL_QUAD_COUNT', + 243: 'SC_P0_DETAIL_QUAD_WITH_1_PIX', + 244: 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 245: 'SC_P0_DETAIL_QUAD_WITH_3_PIX', + 246: 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 247: 'SC_P1_DETAIL_QUAD_WITH_1_PIX', + 248: 'SC_P1_DETAIL_QUAD_WITH_2_PIX', + 249: 'SC_P1_DETAIL_QUAD_WITH_3_PIX', + 250: 'SC_P1_DETAIL_QUAD_WITH_4_PIX', + 251: 'SC_P2_DETAIL_QUAD_WITH_1_PIX', + 252: 'SC_P2_DETAIL_QUAD_WITH_2_PIX', + 253: 'SC_P2_DETAIL_QUAD_WITH_3_PIX', + 254: 'SC_P2_DETAIL_QUAD_WITH_4_PIX', + 255: 'SC_P3_DETAIL_QUAD_WITH_1_PIX', + 256: 'SC_P3_DETAIL_QUAD_WITH_2_PIX', + 257: 'SC_P3_DETAIL_QUAD_WITH_3_PIX', + 258: 'SC_P3_DETAIL_QUAD_WITH_4_PIX', + 259: 'SC_EARLYZ_QUAD_COUNT', + 260: 'SC_EARLYZ_QUAD_WITH_1_PIX', + 261: 'SC_EARLYZ_QUAD_WITH_2_PIX', + 262: 'SC_EARLYZ_QUAD_WITH_3_PIX', + 263: 'SC_EARLYZ_QUAD_WITH_4_PIX', + 264: 'SC_PKR_QUAD_PER_ROW_H1', + 265: 'SC_PKR_QUAD_PER_ROW_H2', + 266: 'SC_PKR_4X2_QUAD_SPLIT', + 267: 'SC_PKR_4X2_FILL_QUAD', + 268: 'SC_PKR_END_OF_VECTOR', + 269: 'SC_PKR_CONTROL_XFER', + 270: 'SC_PKR_DBHANG_FORCE_EOV', + 271: 'SC_REG_SCLK_BUSY', + 272: 'SC_GRP0_DYN_SCLK_BUSY', + 273: 'SC_GRP1_DYN_SCLK_BUSY', + 274: 'SC_GRP2_DYN_SCLK_BUSY', + 275: 'SC_GRP3_DYN_SCLK_BUSY', + 276: 'SC_GRP4_DYN_SCLK_BUSY', + 277: 'SC_PA0_SC_DATA_FIFO_RD', + 278: 'SC_PA0_SC_DATA_FIFO_WE', + 279: 'SC_PA1_SC_DATA_FIFO_RD', + 280: 'SC_PA1_SC_DATA_FIFO_WE', + 281: 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 282: 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', + 283: 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 284: 'SC_PS_ARB_STALLED_FROM_BELOW', + 285: 'SC_PS_ARB_STARVED_FROM_ABOVE', + 286: 'SC_PS_ARB_SC_BUSY', + 287: 'SC_PS_ARB_PA_SC_BUSY', + 288: 'SC_PA2_SC_DATA_FIFO_RD', + 289: 'SC_PA2_SC_DATA_FIFO_WE', + 290: 'SC_PA3_SC_DATA_FIFO_RD', + 291: 'SC_PA3_SC_DATA_FIFO_WE', + 292: 'SC_PA_SC_DEALLOC_0_0_WE', + 293: 'SC_PA_SC_DEALLOC_0_1_WE', + 294: 'SC_PA_SC_DEALLOC_1_0_WE', + 295: 'SC_PA_SC_DEALLOC_1_1_WE', + 296: 'SC_PA_SC_DEALLOC_2_0_WE', + 297: 'SC_PA_SC_DEALLOC_2_1_WE', + 298: 'SC_PA_SC_DEALLOC_3_0_WE', + 299: 'SC_PA_SC_DEALLOC_3_1_WE', + 300: 'SC_PA0_SC_EOP_WE', + 301: 'SC_PA0_SC_EOPG_WE', + 302: 'SC_PA0_SC_EVENT_WE', + 303: 'SC_PA1_SC_EOP_WE', + 304: 'SC_PA1_SC_EOPG_WE', + 305: 'SC_PA1_SC_EVENT_WE', + 306: 'SC_PA2_SC_EOP_WE', + 307: 'SC_PA2_SC_EOPG_WE', + 308: 'SC_PA2_SC_EVENT_WE', + 309: 'SC_PA3_SC_EOP_WE', + 310: 'SC_PA3_SC_EOPG_WE', + 311: 'SC_PA3_SC_EVENT_WE', + 312: 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 313: 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 314: 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 315: 'SC_PS_ARB_EOP_POP_SYNC_POP', + 316: 'SC_PS_ARB_EVENT_SYNC_POP', + 317: 'SC_SC_PS_ENG_MULTICYCLE_BUBBLE', + 318: 'SC_PA0_SC_FPOV_WE', + 319: 'SC_PA1_SC_FPOV_WE', + 320: 'SC_PA2_SC_FPOV_WE', + 321: 'SC_PA3_SC_FPOV_WE', + 322: 'SC_PA0_SC_LPOV_WE', + 323: 'SC_PA1_SC_LPOV_WE', + 324: 'SC_PA2_SC_LPOV_WE', + 325: 'SC_PA3_SC_LPOV_WE', + 326: 'SC_SC_SPI_DEALLOC_0_0', + 327: 'SC_SC_SPI_DEALLOC_0_1', + 328: 'SC_SC_SPI_DEALLOC_0_2', + 329: 'SC_SC_SPI_DEALLOC_1_0', + 330: 'SC_SC_SPI_DEALLOC_1_1', + 331: 'SC_SC_SPI_DEALLOC_1_2', + 332: 'SC_SC_SPI_DEALLOC_2_0', + 333: 'SC_SC_SPI_DEALLOC_2_1', + 334: 'SC_SC_SPI_DEALLOC_2_2', + 335: 'SC_SC_SPI_DEALLOC_3_0', + 336: 'SC_SC_SPI_DEALLOC_3_1', + 337: 'SC_SC_SPI_DEALLOC_3_2', + 338: 'SC_SC_SPI_FPOV_0', + 339: 'SC_SC_SPI_FPOV_1', + 340: 'SC_SC_SPI_FPOV_2', + 341: 'SC_SC_SPI_FPOV_3', + 342: 'SC_SC_SPI_EVENT', + 343: 'SC_PS_TS_EVENT_FIFO_PUSH', + 344: 'SC_PS_TS_EVENT_FIFO_POP', + 345: 'SC_PS_CTX_DONE_FIFO_PUSH', + 346: 'SC_PS_CTX_DONE_FIFO_POP', + 347: 'SC_MULTICYCLE_BUBBLE_FREEZE', + 348: 'SC_EOP_SYNC_WINDOW', + 349: 'SC_PA0_SC_NULL_WE', + 350: 'SC_PA0_SC_NULL_DEALLOC_WE', + 351: 'SC_PA0_SC_DATA_FIFO_EOPG_RD', + 352: 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 353: 'SC_PA0_SC_DEALLOC_0_RD', + 354: 'SC_PA0_SC_DEALLOC_1_RD', + 355: 'SC_PA1_SC_DATA_FIFO_EOPG_RD', + 356: 'SC_PA1_SC_DATA_FIFO_EOP_RD', + 357: 'SC_PA1_SC_DEALLOC_0_RD', + 358: 'SC_PA1_SC_DEALLOC_1_RD', + 359: 'SC_PA1_SC_NULL_WE', + 360: 'SC_PA1_SC_NULL_DEALLOC_WE', + 361: 'SC_PA2_SC_DATA_FIFO_EOPG_RD', + 362: 'SC_PA2_SC_DATA_FIFO_EOP_RD', + 363: 'SC_PA2_SC_DEALLOC_0_RD', + 364: 'SC_PA2_SC_DEALLOC_1_RD', + 365: 'SC_PA2_SC_NULL_WE', + 366: 'SC_PA2_SC_NULL_DEALLOC_WE', + 367: 'SC_PA3_SC_DATA_FIFO_EOPG_RD', + 368: 'SC_PA3_SC_DATA_FIFO_EOP_RD', + 369: 'SC_PA3_SC_DEALLOC_0_RD', + 370: 'SC_PA3_SC_DEALLOC_1_RD', + 371: 'SC_PA3_SC_NULL_WE', + 372: 'SC_PA3_SC_NULL_DEALLOC_WE', + 373: 'SC_PS_PA0_SC_FIFO_EMPTY', + 374: 'SC_PS_PA0_SC_FIFO_FULL', + 375: 'SC_RESERVED_0', + 376: 'SC_PS_PA1_SC_FIFO_EMPTY', + 377: 'SC_PS_PA1_SC_FIFO_FULL', + 378: 'SC_RESERVED_1', + 379: 'SC_PS_PA2_SC_FIFO_EMPTY', + 380: 'SC_PS_PA2_SC_FIFO_FULL', + 381: 'SC_RESERVED_2', + 382: 'SC_PS_PA3_SC_FIFO_EMPTY', + 383: 'SC_PS_PA3_SC_FIFO_FULL', + 384: 'SC_RESERVED_3', + 385: 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', + 386: 'SC_BUSY_CNT_NOT_ZERO', + 387: 'SC_BM_BUSY', + 388: 'SC_BACKEND_BUSY', + 389: 'SC_SCF_SCB_INTERFACE_BUSY', + 390: 'SC_SCB_BUSY', + 391: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 392: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 393: 'SC_PBB_BIN_HIST_NUM_PRIMS', + 394: 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 395: 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 396: 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 397: 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 398: 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 399: 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 400: 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 401: 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 402: 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 403: 'SC_PBB_BUSY', + 404: 'SC_PBB_BUSY_AND_NO_SENDS', + 405: 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 406: 'SC_PBB_NUM_BINS', + 407: 'SC_PBB_END_OF_BIN', + 408: 'SC_PBB_END_OF_BATCH', + 409: 'SC_PBB_PRIMBIN_PROCESSED', + 410: 'SC_PBB_PRIM_ADDED_TO_BATCH', + 411: 'SC_PBB_NONBINNED_PRIM', + 412: 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', + 413: 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 414: 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 415: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 416: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 417: 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 418: 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 419: 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 420: 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 421: 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 422: 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 423: 'SC_POPS_INTRA_WAVE_OVERLAPS', + 424: 'SC_POPS_FORCE_EOV', + 425: 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX', + 426: 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP', + 427: 'SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE', + 428: 'SC_FULL_FULL_QUAD', + 429: 'SC_FULL_HALF_QUAD', + 430: 'SC_FULL_QTR_QUAD', + 431: 'SC_HALF_FULL_QUAD', + 432: 'SC_HALF_HALF_QUAD', + 433: 'SC_HALF_QTR_QUAD', + 434: 'SC_QTR_FULL_QUAD', + 435: 'SC_QTR_HALF_QUAD', + 436: 'SC_QTR_QTR_QUAD', + 437: 'SC_GRP5_DYN_SCLK_BUSY', + 438: 'SC_GRP6_DYN_SCLK_BUSY', + 439: 'SC_GRP7_DYN_SCLK_BUSY', + 440: 'SC_GRP8_DYN_SCLK_BUSY', + 441: 'SC_GRP9_DYN_SCLK_BUSY', + 442: 'SC_PS_TO_BE_SCLK_GATE_STALL', + 443: 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 444: 'SC_PK_BUSY', + 445: 'SC_PK_MAX_DEALLOC_FORCE_EOV', + 446: 'SC_PK_DEALLOC_WAVE_BREAK', + 447: 'SC_SPI_SEND', + 448: 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 449: 'SC_SPI_CREDIT_AT_MAX', + 450: 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 451: 'SC_BCI_SEND', + 452: 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 453: 'SC_BCI_CREDIT_AT_MAX', + 454: 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 455: 'SC_SPIBC_FULL_FREEZE', + 456: 'SC_PW_BM_PASS_EMPTY_PRIM', + 457: 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 458: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 459: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 460: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 461: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 462: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 463: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 464: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 465: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 466: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 467: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 468: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 469: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 470: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 471: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 472: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 473: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 474: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 475: 'SC_DB0_TILE_INTERFACE_BUSY', + 476: 'SC_DB0_TILE_INTERFACE_SEND', + 477: 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 478: 'SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 479: 'SC_DB0_TILE_INTERFACE_SEND_SOP', + 480: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 481: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 482: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 483: 'SC_DB1_TILE_INTERFACE_BUSY', + 484: 'SC_DB1_TILE_INTERFACE_SEND', + 485: 'SC_DB1_TILE_INTERFACE_SEND_EVENT', + 486: 'SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 487: 'SC_DB1_TILE_INTERFACE_SEND_SOP', + 488: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 489: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX', + 490: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 491: 'SC_BACKEND_PRIM_FIFO_FULL', + 492: 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 493: 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 494: 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 495: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 496: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 497: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 498: 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 499: 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 500: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', +} +SC_SRPS_WINDOW_VALID = 0 +SC_PSSW_WINDOW_VALID = 1 +SC_TPQZ_WINDOW_VALID = 2 +SC_QZQP_WINDOW_VALID = 3 +SC_TRPK_WINDOW_VALID = 4 +SC_SRPS_WINDOW_VALID_BUSY = 5 +SC_PSSW_WINDOW_VALID_BUSY = 6 +SC_TPQZ_WINDOW_VALID_BUSY = 7 +SC_QZQP_WINDOW_VALID_BUSY = 8 +SC_TRPK_WINDOW_VALID_BUSY = 9 +SC_STARVED_BY_PA = 10 +SC_STALLED_BY_PRIMFIFO = 11 +SC_STALLED_BY_DB_TILE = 12 +SC_STARVED_BY_DB_TILE = 13 +SC_STALLED_BY_TILEORDERFIFO = 14 +SC_STALLED_BY_TILEFIFO = 15 +SC_STALLED_BY_DB_QUAD = 16 +SC_STARVED_BY_DB_QUAD = 17 +SC_STALLED_BY_QUADFIFO = 18 +SC_STALLED_BY_BCI = 19 +SC_STALLED_BY_SPI = 20 +SC_SCISSOR_DISCARD = 21 +SC_BB_DISCARD = 22 +SC_SUPERTILE_COUNT = 23 +SC_SUPERTILE_PER_PRIM_H0 = 24 +SC_SUPERTILE_PER_PRIM_H1 = 25 +SC_SUPERTILE_PER_PRIM_H2 = 26 +SC_SUPERTILE_PER_PRIM_H3 = 27 +SC_SUPERTILE_PER_PRIM_H4 = 28 +SC_SUPERTILE_PER_PRIM_H5 = 29 +SC_SUPERTILE_PER_PRIM_H6 = 30 +SC_SUPERTILE_PER_PRIM_H7 = 31 +SC_SUPERTILE_PER_PRIM_H8 = 32 +SC_SUPERTILE_PER_PRIM_H9 = 33 +SC_SUPERTILE_PER_PRIM_H10 = 34 +SC_SUPERTILE_PER_PRIM_H11 = 35 +SC_SUPERTILE_PER_PRIM_H12 = 36 +SC_SUPERTILE_PER_PRIM_H13 = 37 +SC_SUPERTILE_PER_PRIM_H14 = 38 +SC_SUPERTILE_PER_PRIM_H15 = 39 +SC_SUPERTILE_PER_PRIM_H16 = 40 +SC_TILE_PER_PRIM_H0 = 41 +SC_TILE_PER_PRIM_H1 = 42 +SC_TILE_PER_PRIM_H2 = 43 +SC_TILE_PER_PRIM_H3 = 44 +SC_TILE_PER_PRIM_H4 = 45 +SC_TILE_PER_PRIM_H5 = 46 +SC_TILE_PER_PRIM_H6 = 47 +SC_TILE_PER_PRIM_H7 = 48 +SC_TILE_PER_PRIM_H8 = 49 +SC_TILE_PER_PRIM_H9 = 50 +SC_TILE_PER_PRIM_H10 = 51 +SC_TILE_PER_PRIM_H11 = 52 +SC_TILE_PER_PRIM_H12 = 53 +SC_TILE_PER_PRIM_H13 = 54 +SC_TILE_PER_PRIM_H14 = 55 +SC_TILE_PER_PRIM_H15 = 56 +SC_TILE_PER_PRIM_H16 = 57 +SC_TILE_PER_SUPERTILE_H0 = 58 +SC_TILE_PER_SUPERTILE_H1 = 59 +SC_TILE_PER_SUPERTILE_H2 = 60 +SC_TILE_PER_SUPERTILE_H3 = 61 +SC_TILE_PER_SUPERTILE_H4 = 62 +SC_TILE_PER_SUPERTILE_H5 = 63 +SC_TILE_PER_SUPERTILE_H6 = 64 +SC_TILE_PER_SUPERTILE_H7 = 65 +SC_TILE_PER_SUPERTILE_H8 = 66 +SC_TILE_PER_SUPERTILE_H9 = 67 +SC_TILE_PER_SUPERTILE_H10 = 68 +SC_TILE_PER_SUPERTILE_H11 = 69 +SC_TILE_PER_SUPERTILE_H12 = 70 +SC_TILE_PER_SUPERTILE_H13 = 71 +SC_TILE_PER_SUPERTILE_H14 = 72 +SC_TILE_PER_SUPERTILE_H15 = 73 +SC_TILE_PER_SUPERTILE_H16 = 74 +SC_TILE_PICKED_H1 = 75 +SC_TILE_PICKED_H2 = 76 +SC_TILE_PICKED_H3 = 77 +SC_TILE_PICKED_H4 = 78 +SC_QZ0_TILE_COUNT = 79 +SC_QZ1_TILE_COUNT = 80 +SC_QZ2_TILE_COUNT = 81 +SC_QZ3_TILE_COUNT = 82 +SC_QZ0_TILE_COVERED_COUNT = 83 +SC_QZ1_TILE_COVERED_COUNT = 84 +SC_QZ2_TILE_COVERED_COUNT = 85 +SC_QZ3_TILE_COVERED_COUNT = 86 +SC_QZ0_TILE_NOT_COVERED_COUNT = 87 +SC_QZ1_TILE_NOT_COVERED_COUNT = 88 +SC_QZ2_TILE_NOT_COVERED_COUNT = 89 +SC_QZ3_TILE_NOT_COVERED_COUNT = 90 +SC_QZ0_QUAD_PER_TILE_H0 = 91 +SC_QZ0_QUAD_PER_TILE_H1 = 92 +SC_QZ0_QUAD_PER_TILE_H2 = 93 +SC_QZ0_QUAD_PER_TILE_H3 = 94 +SC_QZ0_QUAD_PER_TILE_H4 = 95 +SC_QZ0_QUAD_PER_TILE_H5 = 96 +SC_QZ0_QUAD_PER_TILE_H6 = 97 +SC_QZ0_QUAD_PER_TILE_H7 = 98 +SC_QZ0_QUAD_PER_TILE_H8 = 99 +SC_QZ0_QUAD_PER_TILE_H9 = 100 +SC_QZ0_QUAD_PER_TILE_H10 = 101 +SC_QZ0_QUAD_PER_TILE_H11 = 102 +SC_QZ0_QUAD_PER_TILE_H12 = 103 +SC_QZ0_QUAD_PER_TILE_H13 = 104 +SC_QZ0_QUAD_PER_TILE_H14 = 105 +SC_QZ0_QUAD_PER_TILE_H15 = 106 +SC_QZ0_QUAD_PER_TILE_H16 = 107 +SC_QZ1_QUAD_PER_TILE_H0 = 108 +SC_QZ1_QUAD_PER_TILE_H1 = 109 +SC_QZ1_QUAD_PER_TILE_H2 = 110 +SC_QZ1_QUAD_PER_TILE_H3 = 111 +SC_QZ1_QUAD_PER_TILE_H4 = 112 +SC_QZ1_QUAD_PER_TILE_H5 = 113 +SC_QZ1_QUAD_PER_TILE_H6 = 114 +SC_QZ1_QUAD_PER_TILE_H7 = 115 +SC_QZ1_QUAD_PER_TILE_H8 = 116 +SC_QZ1_QUAD_PER_TILE_H9 = 117 +SC_QZ1_QUAD_PER_TILE_H10 = 118 +SC_QZ1_QUAD_PER_TILE_H11 = 119 +SC_QZ1_QUAD_PER_TILE_H12 = 120 +SC_QZ1_QUAD_PER_TILE_H13 = 121 +SC_QZ1_QUAD_PER_TILE_H14 = 122 +SC_QZ1_QUAD_PER_TILE_H15 = 123 +SC_QZ1_QUAD_PER_TILE_H16 = 124 +SC_QZ2_QUAD_PER_TILE_H0 = 125 +SC_QZ2_QUAD_PER_TILE_H1 = 126 +SC_QZ2_QUAD_PER_TILE_H2 = 127 +SC_QZ2_QUAD_PER_TILE_H3 = 128 +SC_QZ2_QUAD_PER_TILE_H4 = 129 +SC_QZ2_QUAD_PER_TILE_H5 = 130 +SC_QZ2_QUAD_PER_TILE_H6 = 131 +SC_QZ2_QUAD_PER_TILE_H7 = 132 +SC_QZ2_QUAD_PER_TILE_H8 = 133 +SC_QZ2_QUAD_PER_TILE_H9 = 134 +SC_QZ2_QUAD_PER_TILE_H10 = 135 +SC_QZ2_QUAD_PER_TILE_H11 = 136 +SC_QZ2_QUAD_PER_TILE_H12 = 137 +SC_QZ2_QUAD_PER_TILE_H13 = 138 +SC_QZ2_QUAD_PER_TILE_H14 = 139 +SC_QZ2_QUAD_PER_TILE_H15 = 140 +SC_QZ2_QUAD_PER_TILE_H16 = 141 +SC_QZ3_QUAD_PER_TILE_H0 = 142 +SC_QZ3_QUAD_PER_TILE_H1 = 143 +SC_QZ3_QUAD_PER_TILE_H2 = 144 +SC_QZ3_QUAD_PER_TILE_H3 = 145 +SC_QZ3_QUAD_PER_TILE_H4 = 146 +SC_QZ3_QUAD_PER_TILE_H5 = 147 +SC_QZ3_QUAD_PER_TILE_H6 = 148 +SC_QZ3_QUAD_PER_TILE_H7 = 149 +SC_QZ3_QUAD_PER_TILE_H8 = 150 +SC_QZ3_QUAD_PER_TILE_H9 = 151 +SC_QZ3_QUAD_PER_TILE_H10 = 152 +SC_QZ3_QUAD_PER_TILE_H11 = 153 +SC_QZ3_QUAD_PER_TILE_H12 = 154 +SC_QZ3_QUAD_PER_TILE_H13 = 155 +SC_QZ3_QUAD_PER_TILE_H14 = 156 +SC_QZ3_QUAD_PER_TILE_H15 = 157 +SC_QZ3_QUAD_PER_TILE_H16 = 158 +SC_QZ0_QUAD_COUNT = 159 +SC_QZ1_QUAD_COUNT = 160 +SC_QZ2_QUAD_COUNT = 161 +SC_QZ3_QUAD_COUNT = 162 +SC_P0_HIZ_TILE_COUNT = 163 +SC_P1_HIZ_TILE_COUNT = 164 +SC_P2_HIZ_TILE_COUNT = 165 +SC_P3_HIZ_TILE_COUNT = 166 +SC_P0_HIZ_QUAD_PER_TILE_H0 = 167 +SC_P0_HIZ_QUAD_PER_TILE_H1 = 168 +SC_P0_HIZ_QUAD_PER_TILE_H2 = 169 +SC_P0_HIZ_QUAD_PER_TILE_H3 = 170 +SC_P0_HIZ_QUAD_PER_TILE_H4 = 171 +SC_P0_HIZ_QUAD_PER_TILE_H5 = 172 +SC_P0_HIZ_QUAD_PER_TILE_H6 = 173 +SC_P0_HIZ_QUAD_PER_TILE_H7 = 174 +SC_P0_HIZ_QUAD_PER_TILE_H8 = 175 +SC_P0_HIZ_QUAD_PER_TILE_H9 = 176 +SC_P0_HIZ_QUAD_PER_TILE_H10 = 177 +SC_P0_HIZ_QUAD_PER_TILE_H11 = 178 +SC_P0_HIZ_QUAD_PER_TILE_H12 = 179 +SC_P0_HIZ_QUAD_PER_TILE_H13 = 180 +SC_P0_HIZ_QUAD_PER_TILE_H14 = 181 +SC_P0_HIZ_QUAD_PER_TILE_H15 = 182 +SC_P0_HIZ_QUAD_PER_TILE_H16 = 183 +SC_P1_HIZ_QUAD_PER_TILE_H0 = 184 +SC_P1_HIZ_QUAD_PER_TILE_H1 = 185 +SC_P1_HIZ_QUAD_PER_TILE_H2 = 186 +SC_P1_HIZ_QUAD_PER_TILE_H3 = 187 +SC_P1_HIZ_QUAD_PER_TILE_H4 = 188 +SC_P1_HIZ_QUAD_PER_TILE_H5 = 189 +SC_P1_HIZ_QUAD_PER_TILE_H6 = 190 +SC_P1_HIZ_QUAD_PER_TILE_H7 = 191 +SC_P1_HIZ_QUAD_PER_TILE_H8 = 192 +SC_P1_HIZ_QUAD_PER_TILE_H9 = 193 +SC_P1_HIZ_QUAD_PER_TILE_H10 = 194 +SC_P1_HIZ_QUAD_PER_TILE_H11 = 195 +SC_P1_HIZ_QUAD_PER_TILE_H12 = 196 +SC_P1_HIZ_QUAD_PER_TILE_H13 = 197 +SC_P1_HIZ_QUAD_PER_TILE_H14 = 198 +SC_P1_HIZ_QUAD_PER_TILE_H15 = 199 +SC_P1_HIZ_QUAD_PER_TILE_H16 = 200 +SC_P2_HIZ_QUAD_PER_TILE_H0 = 201 +SC_P2_HIZ_QUAD_PER_TILE_H1 = 202 +SC_P2_HIZ_QUAD_PER_TILE_H2 = 203 +SC_P2_HIZ_QUAD_PER_TILE_H3 = 204 +SC_P2_HIZ_QUAD_PER_TILE_H4 = 205 +SC_P2_HIZ_QUAD_PER_TILE_H5 = 206 +SC_P2_HIZ_QUAD_PER_TILE_H6 = 207 +SC_P2_HIZ_QUAD_PER_TILE_H7 = 208 +SC_P2_HIZ_QUAD_PER_TILE_H8 = 209 +SC_P2_HIZ_QUAD_PER_TILE_H9 = 210 +SC_P2_HIZ_QUAD_PER_TILE_H10 = 211 +SC_P2_HIZ_QUAD_PER_TILE_H11 = 212 +SC_P2_HIZ_QUAD_PER_TILE_H12 = 213 +SC_P2_HIZ_QUAD_PER_TILE_H13 = 214 +SC_P2_HIZ_QUAD_PER_TILE_H14 = 215 +SC_P2_HIZ_QUAD_PER_TILE_H15 = 216 +SC_P2_HIZ_QUAD_PER_TILE_H16 = 217 +SC_P3_HIZ_QUAD_PER_TILE_H0 = 218 +SC_P3_HIZ_QUAD_PER_TILE_H1 = 219 +SC_P3_HIZ_QUAD_PER_TILE_H2 = 220 +SC_P3_HIZ_QUAD_PER_TILE_H3 = 221 +SC_P3_HIZ_QUAD_PER_TILE_H4 = 222 +SC_P3_HIZ_QUAD_PER_TILE_H5 = 223 +SC_P3_HIZ_QUAD_PER_TILE_H6 = 224 +SC_P3_HIZ_QUAD_PER_TILE_H7 = 225 +SC_P3_HIZ_QUAD_PER_TILE_H8 = 226 +SC_P3_HIZ_QUAD_PER_TILE_H9 = 227 +SC_P3_HIZ_QUAD_PER_TILE_H10 = 228 +SC_P3_HIZ_QUAD_PER_TILE_H11 = 229 +SC_P3_HIZ_QUAD_PER_TILE_H12 = 230 +SC_P3_HIZ_QUAD_PER_TILE_H13 = 231 +SC_P3_HIZ_QUAD_PER_TILE_H14 = 232 +SC_P3_HIZ_QUAD_PER_TILE_H15 = 233 +SC_P3_HIZ_QUAD_PER_TILE_H16 = 234 +SC_P0_HIZ_QUAD_COUNT = 235 +SC_P1_HIZ_QUAD_COUNT = 236 +SC_P2_HIZ_QUAD_COUNT = 237 +SC_P3_HIZ_QUAD_COUNT = 238 +SC_P0_DETAIL_QUAD_COUNT = 239 +SC_P1_DETAIL_QUAD_COUNT = 240 +SC_P2_DETAIL_QUAD_COUNT = 241 +SC_P3_DETAIL_QUAD_COUNT = 242 +SC_P0_DETAIL_QUAD_WITH_1_PIX = 243 +SC_P0_DETAIL_QUAD_WITH_2_PIX = 244 +SC_P0_DETAIL_QUAD_WITH_3_PIX = 245 +SC_P0_DETAIL_QUAD_WITH_4_PIX = 246 +SC_P1_DETAIL_QUAD_WITH_1_PIX = 247 +SC_P1_DETAIL_QUAD_WITH_2_PIX = 248 +SC_P1_DETAIL_QUAD_WITH_3_PIX = 249 +SC_P1_DETAIL_QUAD_WITH_4_PIX = 250 +SC_P2_DETAIL_QUAD_WITH_1_PIX = 251 +SC_P2_DETAIL_QUAD_WITH_2_PIX = 252 +SC_P2_DETAIL_QUAD_WITH_3_PIX = 253 +SC_P2_DETAIL_QUAD_WITH_4_PIX = 254 +SC_P3_DETAIL_QUAD_WITH_1_PIX = 255 +SC_P3_DETAIL_QUAD_WITH_2_PIX = 256 +SC_P3_DETAIL_QUAD_WITH_3_PIX = 257 +SC_P3_DETAIL_QUAD_WITH_4_PIX = 258 +SC_EARLYZ_QUAD_COUNT = 259 +SC_EARLYZ_QUAD_WITH_1_PIX = 260 +SC_EARLYZ_QUAD_WITH_2_PIX = 261 +SC_EARLYZ_QUAD_WITH_3_PIX = 262 +SC_EARLYZ_QUAD_WITH_4_PIX = 263 +SC_PKR_QUAD_PER_ROW_H1 = 264 +SC_PKR_QUAD_PER_ROW_H2 = 265 +SC_PKR_4X2_QUAD_SPLIT = 266 +SC_PKR_4X2_FILL_QUAD = 267 +SC_PKR_END_OF_VECTOR = 268 +SC_PKR_CONTROL_XFER = 269 +SC_PKR_DBHANG_FORCE_EOV = 270 +SC_REG_SCLK_BUSY = 271 +SC_GRP0_DYN_SCLK_BUSY = 272 +SC_GRP1_DYN_SCLK_BUSY = 273 +SC_GRP2_DYN_SCLK_BUSY = 274 +SC_GRP3_DYN_SCLK_BUSY = 275 +SC_GRP4_DYN_SCLK_BUSY = 276 +SC_PA0_SC_DATA_FIFO_RD = 277 +SC_PA0_SC_DATA_FIFO_WE = 278 +SC_PA1_SC_DATA_FIFO_RD = 279 +SC_PA1_SC_DATA_FIFO_WE = 280 +SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 281 +SC_PS_ARB_XFC_ONLY_PRIM_CYCLES = 282 +SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 283 +SC_PS_ARB_STALLED_FROM_BELOW = 284 +SC_PS_ARB_STARVED_FROM_ABOVE = 285 +SC_PS_ARB_SC_BUSY = 286 +SC_PS_ARB_PA_SC_BUSY = 287 +SC_PA2_SC_DATA_FIFO_RD = 288 +SC_PA2_SC_DATA_FIFO_WE = 289 +SC_PA3_SC_DATA_FIFO_RD = 290 +SC_PA3_SC_DATA_FIFO_WE = 291 +SC_PA_SC_DEALLOC_0_0_WE = 292 +SC_PA_SC_DEALLOC_0_1_WE = 293 +SC_PA_SC_DEALLOC_1_0_WE = 294 +SC_PA_SC_DEALLOC_1_1_WE = 295 +SC_PA_SC_DEALLOC_2_0_WE = 296 +SC_PA_SC_DEALLOC_2_1_WE = 297 +SC_PA_SC_DEALLOC_3_0_WE = 298 +SC_PA_SC_DEALLOC_3_1_WE = 299 +SC_PA0_SC_EOP_WE = 300 +SC_PA0_SC_EOPG_WE = 301 +SC_PA0_SC_EVENT_WE = 302 +SC_PA1_SC_EOP_WE = 303 +SC_PA1_SC_EOPG_WE = 304 +SC_PA1_SC_EVENT_WE = 305 +SC_PA2_SC_EOP_WE = 306 +SC_PA2_SC_EOPG_WE = 307 +SC_PA2_SC_EVENT_WE = 308 +SC_PA3_SC_EOP_WE = 309 +SC_PA3_SC_EOPG_WE = 310 +SC_PA3_SC_EVENT_WE = 311 +SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO = 312 +SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH = 313 +SC_PS_ARB_NULL_PRIM_BUBBLE_POP = 314 +SC_PS_ARB_EOP_POP_SYNC_POP = 315 +SC_PS_ARB_EVENT_SYNC_POP = 316 +SC_SC_PS_ENG_MULTICYCLE_BUBBLE = 317 +SC_PA0_SC_FPOV_WE = 318 +SC_PA1_SC_FPOV_WE = 319 +SC_PA2_SC_FPOV_WE = 320 +SC_PA3_SC_FPOV_WE = 321 +SC_PA0_SC_LPOV_WE = 322 +SC_PA1_SC_LPOV_WE = 323 +SC_PA2_SC_LPOV_WE = 324 +SC_PA3_SC_LPOV_WE = 325 +SC_SC_SPI_DEALLOC_0_0 = 326 +SC_SC_SPI_DEALLOC_0_1 = 327 +SC_SC_SPI_DEALLOC_0_2 = 328 +SC_SC_SPI_DEALLOC_1_0 = 329 +SC_SC_SPI_DEALLOC_1_1 = 330 +SC_SC_SPI_DEALLOC_1_2 = 331 +SC_SC_SPI_DEALLOC_2_0 = 332 +SC_SC_SPI_DEALLOC_2_1 = 333 +SC_SC_SPI_DEALLOC_2_2 = 334 +SC_SC_SPI_DEALLOC_3_0 = 335 +SC_SC_SPI_DEALLOC_3_1 = 336 +SC_SC_SPI_DEALLOC_3_2 = 337 +SC_SC_SPI_FPOV_0 = 338 +SC_SC_SPI_FPOV_1 = 339 +SC_SC_SPI_FPOV_2 = 340 +SC_SC_SPI_FPOV_3 = 341 +SC_SC_SPI_EVENT = 342 +SC_PS_TS_EVENT_FIFO_PUSH = 343 +SC_PS_TS_EVENT_FIFO_POP = 344 +SC_PS_CTX_DONE_FIFO_PUSH = 345 +SC_PS_CTX_DONE_FIFO_POP = 346 +SC_MULTICYCLE_BUBBLE_FREEZE = 347 +SC_EOP_SYNC_WINDOW = 348 +SC_PA0_SC_NULL_WE = 349 +SC_PA0_SC_NULL_DEALLOC_WE = 350 +SC_PA0_SC_DATA_FIFO_EOPG_RD = 351 +SC_PA0_SC_DATA_FIFO_EOP_RD = 352 +SC_PA0_SC_DEALLOC_0_RD = 353 +SC_PA0_SC_DEALLOC_1_RD = 354 +SC_PA1_SC_DATA_FIFO_EOPG_RD = 355 +SC_PA1_SC_DATA_FIFO_EOP_RD = 356 +SC_PA1_SC_DEALLOC_0_RD = 357 +SC_PA1_SC_DEALLOC_1_RD = 358 +SC_PA1_SC_NULL_WE = 359 +SC_PA1_SC_NULL_DEALLOC_WE = 360 +SC_PA2_SC_DATA_FIFO_EOPG_RD = 361 +SC_PA2_SC_DATA_FIFO_EOP_RD = 362 +SC_PA2_SC_DEALLOC_0_RD = 363 +SC_PA2_SC_DEALLOC_1_RD = 364 +SC_PA2_SC_NULL_WE = 365 +SC_PA2_SC_NULL_DEALLOC_WE = 366 +SC_PA3_SC_DATA_FIFO_EOPG_RD = 367 +SC_PA3_SC_DATA_FIFO_EOP_RD = 368 +SC_PA3_SC_DEALLOC_0_RD = 369 +SC_PA3_SC_DEALLOC_1_RD = 370 +SC_PA3_SC_NULL_WE = 371 +SC_PA3_SC_NULL_DEALLOC_WE = 372 +SC_PS_PA0_SC_FIFO_EMPTY = 373 +SC_PS_PA0_SC_FIFO_FULL = 374 +SC_RESERVED_0 = 375 +SC_PS_PA1_SC_FIFO_EMPTY = 376 +SC_PS_PA1_SC_FIFO_FULL = 377 +SC_RESERVED_1 = 378 +SC_PS_PA2_SC_FIFO_EMPTY = 379 +SC_PS_PA2_SC_FIFO_FULL = 380 +SC_RESERVED_2 = 381 +SC_PS_PA3_SC_FIFO_EMPTY = 382 +SC_PS_PA3_SC_FIFO_FULL = 383 +SC_RESERVED_3 = 384 +SC_BUSY_PROCESSING_MULTICYCLE_PRIM = 385 +SC_BUSY_CNT_NOT_ZERO = 386 +SC_BM_BUSY = 387 +SC_BACKEND_BUSY = 388 +SC_SCF_SCB_INTERFACE_BUSY = 389 +SC_SCB_BUSY = 390 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY = 391 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL = 392 +SC_PBB_BIN_HIST_NUM_PRIMS = 393 +SC_PBB_BATCH_HIST_NUM_PRIMS = 394 +SC_PBB_BIN_HIST_NUM_CONTEXTS = 395 +SC_PBB_BATCH_HIST_NUM_CONTEXTS = 396 +SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES = 397 +SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES = 398 +SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS = 399 +SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS = 400 +SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM = 401 +SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW = 402 +SC_PBB_BUSY = 403 +SC_PBB_BUSY_AND_NO_SENDS = 404 +SC_PBB_STALLS_PA_DUE_TO_NO_TILES = 405 +SC_PBB_NUM_BINS = 406 +SC_PBB_END_OF_BIN = 407 +SC_PBB_END_OF_BATCH = 408 +SC_PBB_PRIMBIN_PROCESSED = 409 +SC_PBB_PRIM_ADDED_TO_BATCH = 410 +SC_PBB_NONBINNED_PRIM = 411 +SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB = 412 +SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB = 413 +SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION = 414 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW = 415 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN = 416 +SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE = 417 +SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE = 418 +SC_PBB_BATCH_BREAK_DUE_TO_PRIM = 419 +SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE = 420 +SC_PBB_BATCH_BREAK_DUE_TO_EVENT = 421 +SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT = 422 +SC_POPS_INTRA_WAVE_OVERLAPS = 423 +SC_POPS_FORCE_EOV = 424 +SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX = 425 +SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP = 426 +SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE = 427 +SC_FULL_FULL_QUAD = 428 +SC_FULL_HALF_QUAD = 429 +SC_FULL_QTR_QUAD = 430 +SC_HALF_FULL_QUAD = 431 +SC_HALF_HALF_QUAD = 432 +SC_HALF_QTR_QUAD = 433 +SC_QTR_FULL_QUAD = 434 +SC_QTR_HALF_QUAD = 435 +SC_QTR_QTR_QUAD = 436 +SC_GRP5_DYN_SCLK_BUSY = 437 +SC_GRP6_DYN_SCLK_BUSY = 438 +SC_GRP7_DYN_SCLK_BUSY = 439 +SC_GRP8_DYN_SCLK_BUSY = 440 +SC_GRP9_DYN_SCLK_BUSY = 441 +SC_PS_TO_BE_SCLK_GATE_STALL = 442 +SC_PA_TO_PBB_SCLK_GATE_STALL_STALL = 443 +SC_PK_BUSY = 444 +SC_PK_MAX_DEALLOC_FORCE_EOV = 445 +SC_PK_DEALLOC_WAVE_BREAK = 446 +SC_SPI_SEND = 447 +SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 448 +SC_SPI_CREDIT_AT_MAX = 449 +SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND = 450 +SC_BCI_SEND = 451 +SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 452 +SC_BCI_CREDIT_AT_MAX = 453 +SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND = 454 +SC_SPIBC_FULL_FREEZE = 455 +SC_PW_BM_PASS_EMPTY_PRIM = 456 +SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM = 457 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0 = 458 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1 = 459 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2 = 460 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3 = 461 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4 = 462 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5 = 463 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6 = 464 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7 = 465 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8 = 466 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9 = 467 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10 = 468 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11 = 469 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12 = 470 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13 = 471 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14 = 472 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15 = 473 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16 = 474 +SC_DB0_TILE_INTERFACE_BUSY = 475 +SC_DB0_TILE_INTERFACE_SEND = 476 +SC_DB0_TILE_INTERFACE_SEND_EVENT = 477 +SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT = 478 +SC_DB0_TILE_INTERFACE_SEND_SOP = 479 +SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND = 480 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX = 481 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND = 482 +SC_DB1_TILE_INTERFACE_BUSY = 483 +SC_DB1_TILE_INTERFACE_SEND = 484 +SC_DB1_TILE_INTERFACE_SEND_EVENT = 485 +SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT = 486 +SC_DB1_TILE_INTERFACE_SEND_SOP = 487 +SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND = 488 +SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX = 489 +SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND = 490 +SC_BACKEND_PRIM_FIFO_FULL = 491 +SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER = 492 +SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH = 493 +SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH = 494 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT = 495 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT = 496 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV = 497 +SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE = 498 +SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE = 499 +SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT = 500 +SC_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SePairXsel' +SePairXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE = 3 +SePairXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairYsel' +SePairYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE = 3 +SePairYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairMap' +SePairMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_MAP_0', + 1: 'RASTER_CONFIG_SE_PAIR_MAP_1', + 2: 'RASTER_CONFIG_SE_PAIR_MAP_2', + 3: 'RASTER_CONFIG_SE_PAIR_MAP_3', +} +RASTER_CONFIG_SE_PAIR_MAP_0 = 0 +RASTER_CONFIG_SE_PAIR_MAP_1 = 1 +RASTER_CONFIG_SE_PAIR_MAP_2 = 2 +RASTER_CONFIG_SE_PAIR_MAP_3 = 3 +SePairMap = ctypes.c_uint32 # enum + +# values for enumeration 'SeXsel' +SeXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_XSEL_64_WIDE_TILE = 3 +SeXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeYsel' +SeYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_YSEL_64_WIDE_TILE = 3 +SeYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeMap' +SeMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_MAP_0', + 1: 'RASTER_CONFIG_SE_MAP_1', + 2: 'RASTER_CONFIG_SE_MAP_2', + 3: 'RASTER_CONFIG_SE_MAP_3', +} +RASTER_CONFIG_SE_MAP_0 = 0 +RASTER_CONFIG_SE_MAP_1 = 1 +RASTER_CONFIG_SE_MAP_2 = 2 +RASTER_CONFIG_SE_MAP_3 = 3 +SeMap = ctypes.c_uint32 # enum + +# values for enumeration 'ScXsel' +ScXsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_XSEL_64_WIDE_TILE = 3 +ScXsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScYsel' +ScYsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_YSEL_64_WIDE_TILE = 3 +ScYsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScMap' +ScMap__enumvalues = { + 0: 'RASTER_CONFIG_SC_MAP_0', + 1: 'RASTER_CONFIG_SC_MAP_1', + 2: 'RASTER_CONFIG_SC_MAP_2', + 3: 'RASTER_CONFIG_SC_MAP_3', +} +RASTER_CONFIG_SC_MAP_0 = 0 +RASTER_CONFIG_SC_MAP_1 = 1 +RASTER_CONFIG_SC_MAP_2 = 2 +RASTER_CONFIG_SC_MAP_3 = 3 +ScMap = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel2' +PkrXsel2__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL2_0', + 1: 'RASTER_CONFIG_PKR_XSEL2_1', + 2: 'RASTER_CONFIG_PKR_XSEL2_2', + 3: 'RASTER_CONFIG_PKR_XSEL2_3', +} +RASTER_CONFIG_PKR_XSEL2_0 = 0 +RASTER_CONFIG_PKR_XSEL2_1 = 1 +RASTER_CONFIG_PKR_XSEL2_2 = 2 +RASTER_CONFIG_PKR_XSEL2_3 = 3 +PkrXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel' +PkrXsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL_0', + 1: 'RASTER_CONFIG_PKR_XSEL_1', + 2: 'RASTER_CONFIG_PKR_XSEL_2', + 3: 'RASTER_CONFIG_PKR_XSEL_3', +} +RASTER_CONFIG_PKR_XSEL_0 = 0 +RASTER_CONFIG_PKR_XSEL_1 = 1 +RASTER_CONFIG_PKR_XSEL_2 = 2 +RASTER_CONFIG_PKR_XSEL_3 = 3 +PkrXsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrYsel' +PkrYsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_YSEL_0', + 1: 'RASTER_CONFIG_PKR_YSEL_1', + 2: 'RASTER_CONFIG_PKR_YSEL_2', + 3: 'RASTER_CONFIG_PKR_YSEL_3', +} +RASTER_CONFIG_PKR_YSEL_0 = 0 +RASTER_CONFIG_PKR_YSEL_1 = 1 +RASTER_CONFIG_PKR_YSEL_2 = 2 +RASTER_CONFIG_PKR_YSEL_3 = 3 +PkrYsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrMap' +PkrMap__enumvalues = { + 0: 'RASTER_CONFIG_PKR_MAP_0', + 1: 'RASTER_CONFIG_PKR_MAP_1', + 2: 'RASTER_CONFIG_PKR_MAP_2', + 3: 'RASTER_CONFIG_PKR_MAP_3', +} +RASTER_CONFIG_PKR_MAP_0 = 0 +RASTER_CONFIG_PKR_MAP_1 = 1 +RASTER_CONFIG_PKR_MAP_2 = 2 +RASTER_CONFIG_PKR_MAP_3 = 3 +PkrMap = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel' +RbXsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL_0', + 1: 'RASTER_CONFIG_RB_XSEL_1', +} +RASTER_CONFIG_RB_XSEL_0 = 0 +RASTER_CONFIG_RB_XSEL_1 = 1 +RbXsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbYsel' +RbYsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_YSEL_0', + 1: 'RASTER_CONFIG_RB_YSEL_1', +} +RASTER_CONFIG_RB_YSEL_0 = 0 +RASTER_CONFIG_RB_YSEL_1 = 1 +RbYsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel2' +RbXsel2__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL2_0', + 1: 'RASTER_CONFIG_RB_XSEL2_1', + 2: 'RASTER_CONFIG_RB_XSEL2_2', + 3: 'RASTER_CONFIG_RB_XSEL2_3', +} +RASTER_CONFIG_RB_XSEL2_0 = 0 +RASTER_CONFIG_RB_XSEL2_1 = 1 +RASTER_CONFIG_RB_XSEL2_2 = 2 +RASTER_CONFIG_RB_XSEL2_3 = 3 +RbXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'RbMap' +RbMap__enumvalues = { + 0: 'RASTER_CONFIG_RB_MAP_0', + 1: 'RASTER_CONFIG_RB_MAP_1', + 2: 'RASTER_CONFIG_RB_MAP_2', + 3: 'RASTER_CONFIG_RB_MAP_3', +} +RASTER_CONFIG_RB_MAP_0 = 0 +RASTER_CONFIG_RB_MAP_1 = 1 +RASTER_CONFIG_RB_MAP_2 = 2 +RASTER_CONFIG_RB_MAP_3 = 3 +RbMap = ctypes.c_uint32 # enum + +# values for enumeration 'BinningMode' +BinningMode__enumvalues = { + 0: 'BINNING_ALLOWED', + 1: 'FORCE_BINNING_ON', + 2: 'DISABLE_BINNING_USE_NEW_SC', + 3: 'DISABLE_BINNING_USE_LEGACY_SC', +} +BINNING_ALLOWED = 0 +FORCE_BINNING_ON = 1 +DISABLE_BINNING_USE_NEW_SC = 2 +DISABLE_BINNING_USE_LEGACY_SC = 3 +BinningMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinSizeExtend' +BinSizeExtend__enumvalues = { + 0: 'BIN_SIZE_32_PIXELS', + 1: 'BIN_SIZE_64_PIXELS', + 2: 'BIN_SIZE_128_PIXELS', + 3: 'BIN_SIZE_256_PIXELS', + 4: 'BIN_SIZE_512_PIXELS', +} +BIN_SIZE_32_PIXELS = 0 +BIN_SIZE_64_PIXELS = 1 +BIN_SIZE_128_PIXELS = 2 +BIN_SIZE_256_PIXELS = 3 +BIN_SIZE_512_PIXELS = 4 +BinSizeExtend = ctypes.c_uint32 # enum + +# values for enumeration 'BinMapMode' +BinMapMode__enumvalues = { + 0: 'BIN_MAP_MODE_NONE', + 1: 'BIN_MAP_MODE_RTA_INDEX', + 2: 'BIN_MAP_MODE_POPS', +} +BIN_MAP_MODE_NONE = 0 +BIN_MAP_MODE_RTA_INDEX = 1 +BIN_MAP_MODE_POPS = 2 +BinMapMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinEventCntl' +BinEventCntl__enumvalues = { + 0: 'BINNER_BREAK_BATCH', + 1: 'BINNER_PIPELINE', + 2: 'BINNER_DROP', + 3: 'BINNER_DROP_ASSERT', +} +BINNER_BREAK_BATCH = 0 +BINNER_PIPELINE = 1 +BINNER_DROP = 2 +BINNER_DROP_ASSERT = 3 +BinEventCntl = ctypes.c_uint32 # enum + +# values for enumeration 'CovToShaderSel' +CovToShaderSel__enumvalues = { + 0: 'INPUT_COVERAGE', + 1: 'INPUT_INNER_COVERAGE', + 2: 'INPUT_DEPTH_COVERAGE', + 3: 'RAW', +} +INPUT_COVERAGE = 0 +INPUT_INNER_COVERAGE = 1 +INPUT_DEPTH_COVERAGE = 2 +RAW = 3 +CovToShaderSel = ctypes.c_uint32 # enum + +# values for enumeration 'ScUncertaintyRegionMode' +ScUncertaintyRegionMode__enumvalues = { + 0: 'SC_HALF_LSB', + 1: 'SC_LSB_ONE_SIDED', + 2: 'SC_LSB_TWO_SIDED', +} +SC_HALF_LSB = 0 +SC_LSB_ONE_SIDED = 1 +SC_LSB_TWO_SIDED = 2 +ScUncertaintyRegionMode = ctypes.c_uint32 # enum + +# values for enumeration 'RMIPerfSel' +RMIPerfSel__enumvalues = { + 0: 'RMI_PERF_SEL_NONE', + 1: 'RMI_PERF_SEL_BUSY', + 2: 'RMI_PERF_SEL_REG_CLK_VLD', + 3: 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', + 4: 'RMI_PERF_SEL_DYN_CLK_RB_VLD', + 5: 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 6: 'RMI_PERF_SEL_PERF_WINDOW', + 7: 'RMI_PERF_SEL_EVENT_SEND', + 8: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0', + 9: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1', + 10: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2', + 11: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3', + 12: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4', + 13: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5', + 14: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6', + 15: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7', + 16: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8', + 17: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9', + 18: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10', + 19: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11', + 20: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12', + 21: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13', + 22: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14', + 23: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15', + 24: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL', + 25: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0', + 26: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1', + 27: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2', + 28: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3', + 29: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4', + 30: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5', + 31: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6', + 32: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7', + 33: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8', + 34: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9', + 35: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10', + 36: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11', + 37: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12', + 38: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13', + 39: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14', + 40: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15', + 41: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL', + 42: 'RMI_PERF_SEL_UTCL1_TRANSLATION_MISS', + 43: 'RMI_PERF_SEL_UTCL1_PERMISSION_MISS', + 44: 'RMI_PERF_SEL_UTCL1_TRANSLATION_HIT', + 45: 'RMI_PERF_SEL_UTCL1_REQUEST', + 46: 'RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 47: 'RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 48: 'RMI_PERF_SEL_UTCL1_LFIFO_FULL', + 49: 'RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 50: 'RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 51: 'RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 52: 'RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL', + 53: 'RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS', + 54: 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 55: 'RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY', + 56: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 57: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 58: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 59: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 60: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 61: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 62: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 63: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 64: 'RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID', + 65: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 66: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 67: 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 68: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 69: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 70: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 71: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 72: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 73: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 74: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 75: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 76: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 77: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 78: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 79: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 80: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 81: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 82: 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 83: 'RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY', + 84: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 85: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 86: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 87: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 88: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 89: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 90: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 91: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 92: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 93: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 94: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 95: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 96: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 97: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 98: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 99: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 100: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 101: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 102: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 103: 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 104: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 105: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 106: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 107: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 108: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 109: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 110: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 111: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 112: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 113: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 114: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 115: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 116: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 117: 'RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX', + 118: 'RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY', + 119: 'RMI_PERF_SEL_RB_RMI_WR_IDLE', + 120: 'RMI_PERF_SEL_RB_RMI_WR_STARVE', + 121: 'RMI_PERF_SEL_RB_RMI_WR_STALL', + 122: 'RMI_PERF_SEL_RB_RMI_WR_BUSY', + 123: 'RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY', + 124: 'RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX', + 125: 'RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY', + 126: 'RMI_PERF_SEL_RB_RMI_RD_IDLE', + 127: 'RMI_PERF_SEL_RB_RMI_RD_STARVE', + 128: 'RMI_PERF_SEL_RB_RMI_RD_STALL', + 129: 'RMI_PERF_SEL_RB_RMI_RD_BUSY', + 130: 'RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY', + 131: 'RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID', + 132: 'RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID', + 133: 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 134: 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 135: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 136: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 137: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 138: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 139: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 140: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 141: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 142: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 143: 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 144: 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', + 145: 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 146: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 147: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 148: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 149: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 150: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 151: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 152: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 153: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 154: 'RMI_PERF_SEL_RMI_TC_STALL_RDREQ', + 155: 'RMI_PERF_SEL_RMI_TC_STALL_WRREQ', + 156: 'RMI_PERF_SEL_RMI_TC_STALL_ALLREQ', + 157: 'RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND', + 158: 'RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND', + 159: 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 160: 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 161: 'RMI_PERF_SEL_UTCL1_BUSY', + 162: 'RMI_PERF_SEL_RMI_UTC_REQ', + 163: 'RMI_PERF_SEL_RMI_UTC_BUSY', + 164: 'RMI_PERF_SEL_UTCL1_UTCL2_REQ', + 165: 'RMI_PERF_SEL_LEVEL_ADD_UTCL1_TO_UTCL2', + 166: 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY', + 167: 'RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT', + 168: 'RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT', + 169: 'RMI_PERF_SEL_PROBE_UTCL1_VMID_BYPASS', + 170: 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT', + 171: 'RMI_PERF_SEL_XNACK_FIFO_NUM_USED', + 172: 'RMI_PERF_SEL_LAT_FIFO_NUM_USED', + 173: 'RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ', + 174: 'RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ', + 175: 'RMI_PERF_SEL_XNACK_FIFO_FULL', + 176: 'RMI_PERF_SEL_XNACK_FIFO_BUSY', + 177: 'RMI_PERF_SEL_LAT_FIFO_FULL', + 178: 'RMI_PERF_SEL_SKID_FIFO_DEPTH', + 179: 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 180: 'RMI_PERF_SEL_PRT_FIFO_NUM_USED', + 181: 'RMI_PERF_SEL_PRT_FIFO_REQ', + 182: 'RMI_PERF_SEL_PRT_FIFO_BUSY', + 183: 'RMI_PERF_SEL_TCIW_REQ', + 184: 'RMI_PERF_SEL_TCIW_BUSY', + 185: 'RMI_PERF_SEL_SKID_FIFO_REQ', + 186: 'RMI_PERF_SEL_SKID_FIFO_BUSY', + 187: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0', + 188: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1', + 189: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2', + 190: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3', + 191: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR', + 192: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR', + 193: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB', + 194: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB', + 195: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 196: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 197: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 198: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 199: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR', + 200: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR', + 201: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB', + 202: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB', + 203: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR', + 204: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR', + 205: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB', + 206: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB', + 207: 'RMI_PERF_SEL_POP_DEMUX_RTS_RTR', + 208: 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTR', + 209: 'RMI_PERF_SEL_POP_DEMUX_RTS_RTRB', + 210: 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB', + 211: 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR', + 212: 'RMI_PERF_SEL_LEVEL_ADD_RMI_TO_UTC', + 213: 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR', + 214: 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB', + 215: 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB', + 216: 'RMI_PERF_SEL_UTC_POP_RTS_RTR', + 217: 'RMI_PERF_SEL_UTC_POP_RTSB_RTR', + 218: 'RMI_PERF_SEL_UTC_POP_RTS_RTRB', + 219: 'RMI_PERF_SEL_UTC_POP_RTSB_RTRB', + 220: 'RMI_PERF_SEL_POP_XNACK_RTS_RTR', + 221: 'RMI_PERF_SEL_POP_XNACK_RTSB_RTR', + 222: 'RMI_PERF_SEL_POP_XNACK_RTS_RTRB', + 223: 'RMI_PERF_SEL_POP_XNACK_RTSB_RTRB', + 224: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR', + 225: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR', + 226: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB', + 227: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB', + 228: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR', + 229: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR', + 230: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB', + 231: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB', + 232: 'RMI_PERF_SEL_SKID_FIFO_IN_RTS', + 233: 'RMI_PERF_SEL_SKID_FIFO_IN_RTSB', + 234: 'RMI_PERF_SEL_SKID_FIFO_OUT_RTS', + 235: 'RMI_PERF_SEL_SKID_FIFO_OUT_RTSB', + 236: 'RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR', + 237: 'RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR', + 238: 'RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR', + 239: 'RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR', + 240: 'RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR', + 241: 'RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR', + 242: 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 243: 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 244: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 245: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 246: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 247: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 248: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 249: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 250: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 251: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 252: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 253: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0', + 254: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1', + 255: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2', + 256: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3', +} +RMI_PERF_SEL_NONE = 0 +RMI_PERF_SEL_BUSY = 1 +RMI_PERF_SEL_REG_CLK_VLD = 2 +RMI_PERF_SEL_DYN_CLK_CMN_VLD = 3 +RMI_PERF_SEL_DYN_CLK_RB_VLD = 4 +RMI_PERF_SEL_DYN_CLK_PERF_VLD = 5 +RMI_PERF_SEL_PERF_WINDOW = 6 +RMI_PERF_SEL_EVENT_SEND = 7 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0 = 8 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1 = 9 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2 = 10 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3 = 11 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4 = 12 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5 = 13 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6 = 14 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7 = 15 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8 = 16 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9 = 17 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10 = 18 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11 = 19 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12 = 20 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13 = 21 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14 = 22 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15 = 23 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL = 24 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0 = 25 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1 = 26 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2 = 27 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3 = 28 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4 = 29 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5 = 30 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6 = 31 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7 = 32 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8 = 33 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9 = 34 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10 = 35 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11 = 36 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12 = 37 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13 = 38 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14 = 39 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15 = 40 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL = 41 +RMI_PERF_SEL_UTCL1_TRANSLATION_MISS = 42 +RMI_PERF_SEL_UTCL1_PERMISSION_MISS = 43 +RMI_PERF_SEL_UTCL1_TRANSLATION_HIT = 44 +RMI_PERF_SEL_UTCL1_REQUEST = 45 +RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX = 46 +RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT = 47 +RMI_PERF_SEL_UTCL1_LFIFO_FULL = 48 +RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES = 49 +RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS = 50 +RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL = 51 +RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL = 52 +RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS = 53 +RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID = 54 +RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY = 55 +RMI_PERF_SEL_RB_RMI_WRREQ_CID0 = 56 +RMI_PERF_SEL_RB_RMI_WRREQ_CID1 = 57 +RMI_PERF_SEL_RB_RMI_WRREQ_CID2 = 58 +RMI_PERF_SEL_RB_RMI_WRREQ_CID3 = 59 +RMI_PERF_SEL_RB_RMI_WRREQ_CID4 = 60 +RMI_PERF_SEL_RB_RMI_WRREQ_CID5 = 61 +RMI_PERF_SEL_RB_RMI_WRREQ_CID6 = 62 +RMI_PERF_SEL_RB_RMI_WRREQ_CID7 = 63 +RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID = 64 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID = 65 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID = 66 +RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY = 67 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID = 68 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0 = 69 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1 = 70 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2 = 71 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3 = 72 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4 = 73 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5 = 74 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6 = 75 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7 = 76 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0 = 77 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1 = 78 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2 = 79 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3 = 80 +RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID = 81 +RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID = 82 +RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY = 83 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0 = 84 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1 = 85 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2 = 86 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3 = 87 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4 = 88 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5 = 89 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6 = 90 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7 = 91 +RMI_PERF_SEL_RB_RMI_RDREQ_CID0 = 92 +RMI_PERF_SEL_RB_RMI_RDREQ_CID1 = 93 +RMI_PERF_SEL_RB_RMI_RDREQ_CID2 = 94 +RMI_PERF_SEL_RB_RMI_RDREQ_CID3 = 95 +RMI_PERF_SEL_RB_RMI_RDREQ_CID4 = 96 +RMI_PERF_SEL_RB_RMI_RDREQ_CID5 = 97 +RMI_PERF_SEL_RB_RMI_RDREQ_CID6 = 98 +RMI_PERF_SEL_RB_RMI_RDREQ_CID7 = 99 +RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID = 100 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID = 101 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID = 102 +RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY = 103 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID = 104 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0 = 105 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1 = 106 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2 = 107 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3 = 108 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4 = 109 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5 = 110 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6 = 111 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7 = 112 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0 = 113 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1 = 114 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2 = 115 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3 = 116 +RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX = 117 +RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY = 118 +RMI_PERF_SEL_RB_RMI_WR_IDLE = 119 +RMI_PERF_SEL_RB_RMI_WR_STARVE = 120 +RMI_PERF_SEL_RB_RMI_WR_STALL = 121 +RMI_PERF_SEL_RB_RMI_WR_BUSY = 122 +RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY = 123 +RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX = 124 +RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY = 125 +RMI_PERF_SEL_RB_RMI_RD_IDLE = 126 +RMI_PERF_SEL_RB_RMI_RD_STARVE = 127 +RMI_PERF_SEL_RB_RMI_RD_STALL = 128 +RMI_PERF_SEL_RB_RMI_RD_BUSY = 129 +RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY = 130 +RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID = 131 +RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID = 132 +RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID = 133 +RMI_PERF_SEL_RMI_TC_REQ_BUSY = 134 +RMI_PERF_SEL_RMI_TC_WRREQ_CID0 = 135 +RMI_PERF_SEL_RMI_TC_WRREQ_CID1 = 136 +RMI_PERF_SEL_RMI_TC_WRREQ_CID2 = 137 +RMI_PERF_SEL_RMI_TC_WRREQ_CID3 = 138 +RMI_PERF_SEL_RMI_TC_WRREQ_CID4 = 139 +RMI_PERF_SEL_RMI_TC_WRREQ_CID5 = 140 +RMI_PERF_SEL_RMI_TC_WRREQ_CID6 = 141 +RMI_PERF_SEL_RMI_TC_WRREQ_CID7 = 142 +RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID = 143 +RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID = 144 +RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID = 145 +RMI_PERF_SEL_RMI_TC_RDREQ_CID0 = 146 +RMI_PERF_SEL_RMI_TC_RDREQ_CID1 = 147 +RMI_PERF_SEL_RMI_TC_RDREQ_CID2 = 148 +RMI_PERF_SEL_RMI_TC_RDREQ_CID3 = 149 +RMI_PERF_SEL_RMI_TC_RDREQ_CID4 = 150 +RMI_PERF_SEL_RMI_TC_RDREQ_CID5 = 151 +RMI_PERF_SEL_RMI_TC_RDREQ_CID6 = 152 +RMI_PERF_SEL_RMI_TC_RDREQ_CID7 = 153 +RMI_PERF_SEL_RMI_TC_STALL_RDREQ = 154 +RMI_PERF_SEL_RMI_TC_STALL_WRREQ = 155 +RMI_PERF_SEL_RMI_TC_STALL_ALLREQ = 156 +RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND = 157 +RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND = 158 +RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID = 159 +RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID = 160 +RMI_PERF_SEL_UTCL1_BUSY = 161 +RMI_PERF_SEL_RMI_UTC_REQ = 162 +RMI_PERF_SEL_RMI_UTC_BUSY = 163 +RMI_PERF_SEL_UTCL1_UTCL2_REQ = 164 +RMI_PERF_SEL_LEVEL_ADD_UTCL1_TO_UTCL2 = 165 +RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY = 166 +RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT = 167 +RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT = 168 +RMI_PERF_SEL_PROBE_UTCL1_VMID_BYPASS = 169 +RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT = 170 +RMI_PERF_SEL_XNACK_FIFO_NUM_USED = 171 +RMI_PERF_SEL_LAT_FIFO_NUM_USED = 172 +RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ = 173 +RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ = 174 +RMI_PERF_SEL_XNACK_FIFO_FULL = 175 +RMI_PERF_SEL_XNACK_FIFO_BUSY = 176 +RMI_PERF_SEL_LAT_FIFO_FULL = 177 +RMI_PERF_SEL_SKID_FIFO_DEPTH = 178 +RMI_PERF_SEL_TCIW_INFLIGHT_COUNT = 179 +RMI_PERF_SEL_PRT_FIFO_NUM_USED = 180 +RMI_PERF_SEL_PRT_FIFO_REQ = 181 +RMI_PERF_SEL_PRT_FIFO_BUSY = 182 +RMI_PERF_SEL_TCIW_REQ = 183 +RMI_PERF_SEL_TCIW_BUSY = 184 +RMI_PERF_SEL_SKID_FIFO_REQ = 185 +RMI_PERF_SEL_SKID_FIFO_BUSY = 186 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0 = 187 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1 = 188 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2 = 189 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3 = 190 +RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR = 191 +RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR = 192 +RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB = 193 +RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB = 194 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR = 195 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR = 196 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB = 197 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB = 198 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR = 199 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR = 200 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB = 201 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB = 202 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR = 203 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR = 204 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB = 205 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB = 206 +RMI_PERF_SEL_POP_DEMUX_RTS_RTR = 207 +RMI_PERF_SEL_POP_DEMUX_RTSB_RTR = 208 +RMI_PERF_SEL_POP_DEMUX_RTS_RTRB = 209 +RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB = 210 +RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR = 211 +RMI_PERF_SEL_LEVEL_ADD_RMI_TO_UTC = 212 +RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR = 213 +RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB = 214 +RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB = 215 +RMI_PERF_SEL_UTC_POP_RTS_RTR = 216 +RMI_PERF_SEL_UTC_POP_RTSB_RTR = 217 +RMI_PERF_SEL_UTC_POP_RTS_RTRB = 218 +RMI_PERF_SEL_UTC_POP_RTSB_RTRB = 219 +RMI_PERF_SEL_POP_XNACK_RTS_RTR = 220 +RMI_PERF_SEL_POP_XNACK_RTSB_RTR = 221 +RMI_PERF_SEL_POP_XNACK_RTS_RTRB = 222 +RMI_PERF_SEL_POP_XNACK_RTSB_RTRB = 223 +RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR = 224 +RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR = 225 +RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB = 226 +RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB = 227 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR = 228 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR = 229 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB = 230 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB = 231 +RMI_PERF_SEL_SKID_FIFO_IN_RTS = 232 +RMI_PERF_SEL_SKID_FIFO_IN_RTSB = 233 +RMI_PERF_SEL_SKID_FIFO_OUT_RTS = 234 +RMI_PERF_SEL_SKID_FIFO_OUT_RTSB = 235 +RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR = 236 +RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR = 237 +RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR = 238 +RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR = 239 +RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR = 240 +RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR = 241 +RMI_PERF_SEL_REORDER_FIFO_REQ = 242 +RMI_PERF_SEL_REORDER_FIFO_BUSY = 243 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID = 244 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0 = 245 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1 = 246 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2 = 247 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3 = 248 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4 = 249 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5 = 250 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6 = 251 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7 = 252 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0 = 253 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1 = 254 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2 = 255 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3 = 256 +RMIPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'GCRPerfSel' +GCRPerfSel__enumvalues = { + 0: 'GCR_PERF_SEL_NONE', + 1: 'GCR_PERF_SEL_SDMA0_ALL_REQ', + 2: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 3: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 4: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 5: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 6: 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 7: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 8: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 9: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 10: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 11: 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 12: 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 13: 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 14: 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', + 15: 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 16: 'GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ', + 17: 'GCR_PERF_SEL_SDMA1_ALL_REQ', + 18: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 19: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 20: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 21: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 22: 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 23: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 24: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 25: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 26: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 27: 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 28: 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 29: 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 30: 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', + 31: 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 32: 'GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ', + 33: 'GCR_PERF_SEL_CPG_ALL_REQ', + 34: 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', + 35: 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 36: 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 37: 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 38: 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 39: 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', + 40: 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 41: 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 42: 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 43: 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 44: 'GCR_PERF_SEL_CPG_METADATA_REQ', + 45: 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', + 46: 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 47: 'GCR_PERF_SEL_CPG_TCP_REQ', + 48: 'GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ', + 49: 'GCR_PERF_SEL_CPC_ALL_REQ', + 50: 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', + 51: 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 52: 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 53: 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 54: 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 55: 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', + 56: 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 57: 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 58: 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 59: 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 60: 'GCR_PERF_SEL_CPC_METADATA_REQ', + 61: 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', + 62: 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 63: 'GCR_PERF_SEL_CPC_TCP_REQ', + 64: 'GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ', + 65: 'GCR_PERF_SEL_CPF_ALL_REQ', + 66: 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', + 67: 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 68: 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 69: 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 70: 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 71: 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', + 72: 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 73: 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 74: 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 75: 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 76: 'GCR_PERF_SEL_CPF_METADATA_REQ', + 77: 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', + 78: 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 79: 'GCR_PERF_SEL_CPF_TCP_REQ', + 80: 'GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ', + 81: 'GCR_PERF_SEL_VIRT_REQ', + 82: 'GCR_PERF_SEL_PHY_REQ', + 83: 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 84: 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 85: 'GCR_PERF_SEL_ALL_REQ', + 86: 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 87: 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 88: 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 89: 'GCR_PERF_SEL_UTCL2_REQ', + 90: 'GCR_PERF_SEL_UTCL2_RET', + 91: 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 92: 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 93: 'GCR_PERF_SEL_UTCL2_FILTERED_RET', +} +GCR_PERF_SEL_NONE = 0 +GCR_PERF_SEL_SDMA0_ALL_REQ = 1 +GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ = 2 +GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ = 3 +GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ = 4 +GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ = 5 +GCR_PERF_SEL_SDMA0_GL2_ALL_REQ = 6 +GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ = 7 +GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ = 8 +GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ = 9 +GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ = 10 +GCR_PERF_SEL_SDMA0_GL1_ALL_REQ = 11 +GCR_PERF_SEL_SDMA0_METADATA_REQ = 12 +GCR_PERF_SEL_SDMA0_SQC_DATA_REQ = 13 +GCR_PERF_SEL_SDMA0_SQC_INST_REQ = 14 +GCR_PERF_SEL_SDMA0_TCP_REQ = 15 +GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ = 16 +GCR_PERF_SEL_SDMA1_ALL_REQ = 17 +GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ = 18 +GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ = 19 +GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ = 20 +GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ = 21 +GCR_PERF_SEL_SDMA1_GL2_ALL_REQ = 22 +GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ = 23 +GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ = 24 +GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ = 25 +GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ = 26 +GCR_PERF_SEL_SDMA1_GL1_ALL_REQ = 27 +GCR_PERF_SEL_SDMA1_METADATA_REQ = 28 +GCR_PERF_SEL_SDMA1_SQC_DATA_REQ = 29 +GCR_PERF_SEL_SDMA1_SQC_INST_REQ = 30 +GCR_PERF_SEL_SDMA1_TCP_REQ = 31 +GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ = 32 +GCR_PERF_SEL_CPG_ALL_REQ = 33 +GCR_PERF_SEL_CPG_GL2_RANGE_REQ = 34 +GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ = 35 +GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ = 36 +GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ = 37 +GCR_PERF_SEL_CPG_GL2_ALL_REQ = 38 +GCR_PERF_SEL_CPG_GL1_RANGE_REQ = 39 +GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ = 40 +GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ = 41 +GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ = 42 +GCR_PERF_SEL_CPG_GL1_ALL_REQ = 43 +GCR_PERF_SEL_CPG_METADATA_REQ = 44 +GCR_PERF_SEL_CPG_SQC_DATA_REQ = 45 +GCR_PERF_SEL_CPG_SQC_INST_REQ = 46 +GCR_PERF_SEL_CPG_TCP_REQ = 47 +GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ = 48 +GCR_PERF_SEL_CPC_ALL_REQ = 49 +GCR_PERF_SEL_CPC_GL2_RANGE_REQ = 50 +GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ = 51 +GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ = 52 +GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ = 53 +GCR_PERF_SEL_CPC_GL2_ALL_REQ = 54 +GCR_PERF_SEL_CPC_GL1_RANGE_REQ = 55 +GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ = 56 +GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ = 57 +GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ = 58 +GCR_PERF_SEL_CPC_GL1_ALL_REQ = 59 +GCR_PERF_SEL_CPC_METADATA_REQ = 60 +GCR_PERF_SEL_CPC_SQC_DATA_REQ = 61 +GCR_PERF_SEL_CPC_SQC_INST_REQ = 62 +GCR_PERF_SEL_CPC_TCP_REQ = 63 +GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ = 64 +GCR_PERF_SEL_CPF_ALL_REQ = 65 +GCR_PERF_SEL_CPF_GL2_RANGE_REQ = 66 +GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ = 67 +GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ = 68 +GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ = 69 +GCR_PERF_SEL_CPF_GL2_ALL_REQ = 70 +GCR_PERF_SEL_CPF_GL1_RANGE_REQ = 71 +GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ = 72 +GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ = 73 +GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ = 74 +GCR_PERF_SEL_CPF_GL1_ALL_REQ = 75 +GCR_PERF_SEL_CPF_METADATA_REQ = 76 +GCR_PERF_SEL_CPF_SQC_DATA_REQ = 77 +GCR_PERF_SEL_CPF_SQC_INST_REQ = 78 +GCR_PERF_SEL_CPF_TCP_REQ = 79 +GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ = 80 +GCR_PERF_SEL_VIRT_REQ = 81 +GCR_PERF_SEL_PHY_REQ = 82 +GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ = 83 +GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ = 84 +GCR_PERF_SEL_ALL_REQ = 85 +GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ = 86 +GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ = 87 +GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ = 88 +GCR_PERF_SEL_UTCL2_REQ = 89 +GCR_PERF_SEL_UTCL2_RET = 90 +GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT = 91 +GCR_PERF_SEL_UTCL2_INFLIGHT_REQ = 92 +GCR_PERF_SEL_UTCL2_FILTERED_RET = 93 +GCRPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1PerfSel' +UTCL1PerfSel__enumvalues = { + 0: 'UTCL1_PERF_SEL_NONE', + 1: 'UTCL1_PERF_SEL_REQS', + 2: 'UTCL1_PERF_SEL_HITS', + 3: 'UTCL1_PERF_SEL_MISSES', + 4: 'UTCL1_PERF_SEL_BYPASS_REQS', + 5: 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 6: 'UTCL1_PERF_SEL_NUM_SMALLK_PAGES', + 7: 'UTCL1_PERF_SEL_NUM_BIGK_PAGES', + 8: 'UTCL1_PERF_SEL_TOTAL_UTCL2_REQS', + 9: 'UTCL1_PERF_SEL_OUTSTANDING_UTCL2_REQS_ACCUM', + 10: 'UTCL1_PERF_SEL_STALL_ON_UTCL2_CREDITS', + 11: 'UTCL1_PERF_SEL_STALL_MH_OFIFO_FULL', + 12: 'UTCL1_PERF_SEL_STALL_MH_CAM_FULL', + 13: 'UTCL1_PERF_SEL_NONRANGE_INV_REQS', + 14: 'UTCL1_PERF_SEL_RANGE_INV_REQS', +} +UTCL1_PERF_SEL_NONE = 0 +UTCL1_PERF_SEL_REQS = 1 +UTCL1_PERF_SEL_HITS = 2 +UTCL1_PERF_SEL_MISSES = 3 +UTCL1_PERF_SEL_BYPASS_REQS = 4 +UTCL1_PERF_SEL_HIT_INV_FILTER_REQS = 5 +UTCL1_PERF_SEL_NUM_SMALLK_PAGES = 6 +UTCL1_PERF_SEL_NUM_BIGK_PAGES = 7 +UTCL1_PERF_SEL_TOTAL_UTCL2_REQS = 8 +UTCL1_PERF_SEL_OUTSTANDING_UTCL2_REQS_ACCUM = 9 +UTCL1_PERF_SEL_STALL_ON_UTCL2_CREDITS = 10 +UTCL1_PERF_SEL_STALL_MH_OFIFO_FULL = 11 +UTCL1_PERF_SEL_STALL_MH_CAM_FULL = 12 +UTCL1_PERF_SEL_NONRANGE_INV_REQS = 13 +UTCL1_PERF_SEL_RANGE_INV_REQS = 14 +UTCL1PerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERF_SEL' +SDMA_PERF_SEL__enumvalues = { + 0: 'SDMA_PERF_SEL_CYCLE', + 1: 'SDMA_PERF_SEL_IDLE', + 2: 'SDMA_PERF_SEL_REG_IDLE', + 3: 'SDMA_PERF_SEL_RB_EMPTY', + 4: 'SDMA_PERF_SEL_RB_FULL', + 5: 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERF_SEL_RB_RPTR_WB', + 9: 'SDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERF_SEL_RB_CMD_FULL', + 11: 'SDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERF_SEL_IB_CMD_FULL', + 13: 'SDMA_PERF_SEL_EX_IDLE', + 14: 'SDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERF_SEL_MC_WR_IDLE', + 17: 'SDMA_PERF_SEL_MC_WR_COUNT', + 18: 'SDMA_PERF_SEL_MC_RD_IDLE', + 19: 'SDMA_PERF_SEL_MC_RD_COUNT', + 20: 'SDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'SDMA_PERF_SEL_SEM_IDLE', + 25: 'SDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'SDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'SDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'SDMA_PERF_SEL_INT_IDLE', + 31: 'SDMA_PERF_SEL_INT_REQ_STALL', + 32: 'SDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'SDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'SDMA_PERF_SEL_NUM_PACKET', + 37: 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'SDMA_PERF_SEL_CE_WR_IDLE', + 39: 'SDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'SDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'SDMA_PERF_SEL_CE_IN_IDLE', + 43: 'SDMA_PERF_SEL_CE_DST_IDLE', + 46: 'SDMA_PERF_SEL_CE_AFIFO_FULL', + 49: 'SDMA_PERF_SEL_CE_INFO_FULL', + 50: 'SDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'SDMA_PERF_SEL_CE_RD_STALL', + 52: 'SDMA_PERF_SEL_CE_WR_STALL', + 53: 'SDMA_PERF_SEL_GFX_SELECT', + 54: 'SDMA_PERF_SEL_RLC0_SELECT', + 55: 'SDMA_PERF_SEL_RLC1_SELECT', + 56: 'SDMA_PERF_SEL_PAGE_SELECT', + 57: 'SDMA_PERF_SEL_CTX_CHANGE', + 58: 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'SDMA_PERF_SEL_DOORBELL', + 61: 'SDMA_PERF_SEL_RD_BA_RTR', + 62: 'SDMA_PERF_SEL_WR_BA_RTR', + 63: 'SDMA_PERF_SEL_F32_L1_WR_VLD', + 64: 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', + 66: 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 67: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 68: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 69: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 70: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 71: 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 72: 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 73: 'SDMA_PERF_SEL_UTCL2_FREE', + 74: 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 75: 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 76: 'SDMA_PERF_SEL_DMA_L1_RD_SEND', + 77: 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 78: 'SDMA_PERF_SEL_DMA_MC_RD_SEND', + 79: 'SDMA_PERF_SEL_GPUVM_INVREQ_HIGH', + 80: 'SDMA_PERF_SEL_GPUVM_INVREQ_LOW', + 81: 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 82: 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 83: 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 84: 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 85: 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 86: 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 87: 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 88: 'SDMA_PERF_SEL_L2_META_RET_VLD', + 89: 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 90: 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 91: 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', + 92: 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', + 93: 'SDMA_PERF_SEL_META_REQ_SEND', + 94: 'SDMA_PERF_SEL_META_RTN_VLD', + 95: 'SDMA_PERF_SEL_TLBI_SEND', + 96: 'SDMA_PERF_SEL_TLBI_RTN', + 97: 'SDMA_PERF_SEL_GCR_SEND', + 98: 'SDMA_PERF_SEL_GCR_RTN', + 99: 'SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER', + 100: 'SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER', +} +SDMA_PERF_SEL_CYCLE = 0 +SDMA_PERF_SEL_IDLE = 1 +SDMA_PERF_SEL_REG_IDLE = 2 +SDMA_PERF_SEL_RB_EMPTY = 3 +SDMA_PERF_SEL_RB_FULL = 4 +SDMA_PERF_SEL_RB_WPTR_WRAP = 5 +SDMA_PERF_SEL_RB_RPTR_WRAP = 6 +SDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERF_SEL_RB_RPTR_WB = 8 +SDMA_PERF_SEL_RB_CMD_IDLE = 9 +SDMA_PERF_SEL_RB_CMD_FULL = 10 +SDMA_PERF_SEL_IB_CMD_IDLE = 11 +SDMA_PERF_SEL_IB_CMD_FULL = 12 +SDMA_PERF_SEL_EX_IDLE = 13 +SDMA_PERF_SEL_SRBM_REG_SEND = 14 +SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERF_SEL_MC_WR_IDLE = 16 +SDMA_PERF_SEL_MC_WR_COUNT = 17 +SDMA_PERF_SEL_MC_RD_IDLE = 18 +SDMA_PERF_SEL_MC_RD_COUNT = 19 +SDMA_PERF_SEL_MC_RD_RET_STALL = 20 +SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +SDMA_PERF_SEL_SEM_IDLE = 24 +SDMA_PERF_SEL_SEM_REQ_STALL = 25 +SDMA_PERF_SEL_SEM_REQ_COUNT = 26 +SDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +SDMA_PERF_SEL_SEM_RESP_FAIL = 28 +SDMA_PERF_SEL_SEM_RESP_PASS = 29 +SDMA_PERF_SEL_INT_IDLE = 30 +SDMA_PERF_SEL_INT_REQ_STALL = 31 +SDMA_PERF_SEL_INT_REQ_COUNT = 32 +SDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +SDMA_PERF_SEL_INT_RESP_RETRY = 34 +SDMA_PERF_SEL_NUM_PACKET = 35 +SDMA_PERF_SEL_CE_WREQ_IDLE = 37 +SDMA_PERF_SEL_CE_WR_IDLE = 38 +SDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +SDMA_PERF_SEL_CE_RREQ_IDLE = 40 +SDMA_PERF_SEL_CE_OUT_IDLE = 41 +SDMA_PERF_SEL_CE_IN_IDLE = 42 +SDMA_PERF_SEL_CE_DST_IDLE = 43 +SDMA_PERF_SEL_CE_AFIFO_FULL = 46 +SDMA_PERF_SEL_CE_INFO_FULL = 49 +SDMA_PERF_SEL_CE_INFO1_FULL = 50 +SDMA_PERF_SEL_CE_RD_STALL = 51 +SDMA_PERF_SEL_CE_WR_STALL = 52 +SDMA_PERF_SEL_GFX_SELECT = 53 +SDMA_PERF_SEL_RLC0_SELECT = 54 +SDMA_PERF_SEL_RLC1_SELECT = 55 +SDMA_PERF_SEL_PAGE_SELECT = 56 +SDMA_PERF_SEL_CTX_CHANGE = 57 +SDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +SDMA_PERF_SEL_DOORBELL = 60 +SDMA_PERF_SEL_RD_BA_RTR = 61 +SDMA_PERF_SEL_WR_BA_RTR = 62 +SDMA_PERF_SEL_F32_L1_WR_VLD = 63 +SDMA_PERF_SEL_CE_L1_WR_VLD = 64 +SDMA_PERF_SEL_CPF_SDMA_INVREQ = 65 +SDMA_PERF_SEL_SDMA_CPF_INVACK = 66 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ = 67 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK = 68 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL = 69 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL = 70 +SDMA_PERF_SEL_UTCL2_RET_XNACK = 71 +SDMA_PERF_SEL_UTCL2_RET_ACK = 72 +SDMA_PERF_SEL_UTCL2_FREE = 73 +SDMA_PERF_SEL_SDMA_UTCL2_SEND = 74 +SDMA_PERF_SEL_DMA_L1_WR_SEND = 75 +SDMA_PERF_SEL_DMA_L1_RD_SEND = 76 +SDMA_PERF_SEL_DMA_MC_WR_SEND = 77 +SDMA_PERF_SEL_DMA_MC_RD_SEND = 78 +SDMA_PERF_SEL_GPUVM_INVREQ_HIGH = 79 +SDMA_PERF_SEL_GPUVM_INVREQ_LOW = 80 +SDMA_PERF_SEL_L1_WRL2_IDLE = 81 +SDMA_PERF_SEL_L1_RDL2_IDLE = 82 +SDMA_PERF_SEL_L1_WRMC_IDLE = 83 +SDMA_PERF_SEL_L1_RDMC_IDLE = 84 +SDMA_PERF_SEL_L1_WR_INV_IDLE = 85 +SDMA_PERF_SEL_L1_RD_INV_IDLE = 86 +SDMA_PERF_SEL_META_L2_REQ_SEND = 87 +SDMA_PERF_SEL_L2_META_RET_VLD = 88 +SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND = 89 +SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN = 90 +SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND = 91 +SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN = 92 +SDMA_PERF_SEL_META_REQ_SEND = 93 +SDMA_PERF_SEL_META_RTN_VLD = 94 +SDMA_PERF_SEL_TLBI_SEND = 95 +SDMA_PERF_SEL_TLBI_RTN = 96 +SDMA_PERF_SEL_GCR_SEND = 97 +SDMA_PERF_SEL_GCR_RTN = 98 +SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER = 99 +SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER = 100 +SDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_PIPES_BC_ENUM' +NUM_PIPES_BC_ENUM__enumvalues = { + 0: 'ADDR_NUM_PIPES_BC_P8', + 1: 'ADDR_NUM_PIPES_BC_P16', +} +ADDR_NUM_PIPES_BC_P8 = 0 +ADDR_NUM_PIPES_BC_P16 = 1 +NUM_PIPES_BC_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'NUM_BANKS_BC_ENUM' +NUM_BANKS_BC_ENUM__enumvalues = { + 0: 'ADDR_NUM_BANKS_BC_BANKS_1', + 1: 'ADDR_NUM_BANKS_BC_BANKS_2', + 2: 'ADDR_NUM_BANKS_BC_BANKS_4', + 3: 'ADDR_NUM_BANKS_BC_BANKS_8', + 4: 'ADDR_NUM_BANKS_BC_BANKS_16', +} +ADDR_NUM_BANKS_BC_BANKS_1 = 0 +ADDR_NUM_BANKS_BC_BANKS_2 = 1 +ADDR_NUM_BANKS_BC_BANKS_4 = 2 +ADDR_NUM_BANKS_BC_BANKS_8 = 3 +ADDR_NUM_BANKS_BC_BANKS_16 = 4 +NUM_BANKS_BC_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'SWIZZLE_TYPE_ENUM' +SWIZZLE_TYPE_ENUM__enumvalues = { + 0: 'SW_Z', + 1: 'SW_S', + 2: 'SW_D', + 3: 'SW_R', + 4: 'SW_L', +} +SW_Z = 0 +SW_S = 1 +SW_D = 2 +SW_R = 3 +SW_L = 4 +SWIZZLE_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TC_MICRO_TILE_MODE' +TC_MICRO_TILE_MODE__enumvalues = { + 0: 'MICRO_TILE_MODE_LINEAR', + 1: 'MICRO_TILE_MODE_RENDER_TARGET', + 2: 'MICRO_TILE_MODE_STD_2D', + 3: 'MICRO_TILE_MODE_STD_3D', + 4: 'MICRO_TILE_MODE_DISPLAY_2D', + 5: 'MICRO_TILE_MODE_DISPLAY_3D', + 6: 'MICRO_TILE_MODE_Z', +} +MICRO_TILE_MODE_LINEAR = 0 +MICRO_TILE_MODE_RENDER_TARGET = 1 +MICRO_TILE_MODE_STD_2D = 2 +MICRO_TILE_MODE_STD_3D = 3 +MICRO_TILE_MODE_DISPLAY_2D = 4 +MICRO_TILE_MODE_DISPLAY_3D = 5 +MICRO_TILE_MODE_Z = 6 +TC_MICRO_TILE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SWIZZLE_MODE_ENUM' +SWIZZLE_MODE_ENUM__enumvalues = { + 0: 'SW_LINEAR', + 1: 'SW_256B_S', + 2: 'SW_256B_D', + 3: 'SW_256B_R', + 4: 'SW_4KB_Z', + 5: 'SW_4KB_S', + 6: 'SW_4KB_D', + 7: 'SW_4KB_R', + 8: 'SW_64KB_Z', + 9: 'SW_64KB_S', + 10: 'SW_64KB_D', + 11: 'SW_64KB_R', + 12: 'SW_VAR_Z', + 13: 'SW_VAR_S', + 14: 'SW_VAR_D', + 15: 'SW_VAR_R', + 16: 'SW_64KB_Z_T', + 17: 'SW_64KB_S_T', + 18: 'SW_64KB_D_T', + 19: 'SW_64KB_R_T', + 20: 'SW_4KB_Z_X', + 21: 'SW_4KB_S_X', + 22: 'SW_4KB_D_X', + 23: 'SW_4KB_R_X', + 24: 'SW_64KB_Z_X', + 25: 'SW_64KB_S_X', + 26: 'SW_64KB_D_X', + 27: 'SW_64KB_R_X', + 28: 'SW_VAR_Z_X', + 29: 'SW_VAR_S_X', + 30: 'SW_VAR_D_X', + 31: 'SW_VAR_R_X', +} +SW_LINEAR = 0 +SW_256B_S = 1 +SW_256B_D = 2 +SW_256B_R = 3 +SW_4KB_Z = 4 +SW_4KB_S = 5 +SW_4KB_D = 6 +SW_4KB_R = 7 +SW_64KB_Z = 8 +SW_64KB_S = 9 +SW_64KB_D = 10 +SW_64KB_R = 11 +SW_VAR_Z = 12 +SW_VAR_S = 13 +SW_VAR_D = 14 +SW_VAR_R = 15 +SW_64KB_Z_T = 16 +SW_64KB_S_T = 17 +SW_64KB_D_T = 18 +SW_64KB_R_T = 19 +SW_4KB_Z_X = 20 +SW_4KB_S_X = 21 +SW_4KB_D_X = 22 +SW_4KB_R_X = 23 +SW_64KB_Z_X = 24 +SW_64KB_S_X = 25 +SW_64KB_D_X = 26 +SW_64KB_R_X = 27 +SW_VAR_Z_X = 28 +SW_VAR_S_X = 29 +SW_VAR_D_X = 30 +SW_VAR_R_X = 31 +SWIZZLE_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceEndian' +SurfaceEndian__enumvalues = { + 0: 'ENDIAN_NONE', + 1: 'ENDIAN_8IN16', + 2: 'ENDIAN_8IN32', + 3: 'ENDIAN_8IN64', +} +ENDIAN_NONE = 0 +ENDIAN_8IN16 = 1 +ENDIAN_8IN32 = 2 +ENDIAN_8IN64 = 3 +SurfaceEndian = ctypes.c_uint32 # enum + +# values for enumeration 'ArrayMode' +ArrayMode__enumvalues = { + 0: 'ARRAY_LINEAR_GENERAL', + 1: 'ARRAY_LINEAR_ALIGNED', + 2: 'ARRAY_1D_TILED_THIN1', + 3: 'ARRAY_1D_TILED_THICK', + 4: 'ARRAY_2D_TILED_THIN1', + 5: 'ARRAY_PRT_TILED_THIN1', + 6: 'ARRAY_PRT_2D_TILED_THIN1', + 7: 'ARRAY_2D_TILED_THICK', + 8: 'ARRAY_2D_TILED_XTHICK', + 9: 'ARRAY_PRT_TILED_THICK', + 10: 'ARRAY_PRT_2D_TILED_THICK', + 11: 'ARRAY_PRT_3D_TILED_THIN1', + 12: 'ARRAY_3D_TILED_THIN1', + 13: 'ARRAY_3D_TILED_THICK', + 14: 'ARRAY_3D_TILED_XTHICK', + 15: 'ARRAY_PRT_3D_TILED_THICK', +} +ARRAY_LINEAR_GENERAL = 0 +ARRAY_LINEAR_ALIGNED = 1 +ARRAY_1D_TILED_THIN1 = 2 +ARRAY_1D_TILED_THICK = 3 +ARRAY_2D_TILED_THIN1 = 4 +ARRAY_PRT_TILED_THIN1 = 5 +ARRAY_PRT_2D_TILED_THIN1 = 6 +ARRAY_2D_TILED_THICK = 7 +ARRAY_2D_TILED_XTHICK = 8 +ARRAY_PRT_TILED_THICK = 9 +ARRAY_PRT_2D_TILED_THICK = 10 +ARRAY_PRT_3D_TILED_THIN1 = 11 +ARRAY_3D_TILED_THIN1 = 12 +ARRAY_3D_TILED_THICK = 13 +ARRAY_3D_TILED_XTHICK = 14 +ARRAY_PRT_3D_TILED_THICK = 15 +ArrayMode = ctypes.c_uint32 # enum + +# values for enumeration 'NumPipes' +NumPipes__enumvalues = { + 0: 'ADDR_CONFIG_1_PIPE', + 1: 'ADDR_CONFIG_2_PIPE', + 2: 'ADDR_CONFIG_4_PIPE', + 3: 'ADDR_CONFIG_8_PIPE', + 4: 'ADDR_CONFIG_16_PIPE', + 5: 'ADDR_CONFIG_32_PIPE', + 6: 'ADDR_CONFIG_64_PIPE', +} +ADDR_CONFIG_1_PIPE = 0 +ADDR_CONFIG_2_PIPE = 1 +ADDR_CONFIG_4_PIPE = 2 +ADDR_CONFIG_8_PIPE = 3 +ADDR_CONFIG_16_PIPE = 4 +ADDR_CONFIG_32_PIPE = 5 +ADDR_CONFIG_64_PIPE = 6 +NumPipes = ctypes.c_uint32 # enum + +# values for enumeration 'NumBanksConfig' +NumBanksConfig__enumvalues = { + 0: 'ADDR_CONFIG_1_BANK', + 1: 'ADDR_CONFIG_2_BANK', + 2: 'ADDR_CONFIG_4_BANK', + 3: 'ADDR_CONFIG_8_BANK', + 4: 'ADDR_CONFIG_16_BANK', +} +ADDR_CONFIG_1_BANK = 0 +ADDR_CONFIG_2_BANK = 1 +ADDR_CONFIG_4_BANK = 2 +ADDR_CONFIG_8_BANK = 3 +ADDR_CONFIG_16_BANK = 4 +NumBanksConfig = ctypes.c_uint32 # enum + +# values for enumeration 'PipeInterleaveSize' +PipeInterleaveSize__enumvalues = { + 0: 'ADDR_CONFIG_PIPE_INTERLEAVE_256B', + 1: 'ADDR_CONFIG_PIPE_INTERLEAVE_512B', + 2: 'ADDR_CONFIG_PIPE_INTERLEAVE_1KB', + 3: 'ADDR_CONFIG_PIPE_INTERLEAVE_2KB', +} +ADDR_CONFIG_PIPE_INTERLEAVE_256B = 0 +ADDR_CONFIG_PIPE_INTERLEAVE_512B = 1 +ADDR_CONFIG_PIPE_INTERLEAVE_1KB = 2 +ADDR_CONFIG_PIPE_INTERLEAVE_2KB = 3 +PipeInterleaveSize = ctypes.c_uint32 # enum + +# values for enumeration 'BankInterleaveSize' +BankInterleaveSize__enumvalues = { + 0: 'ADDR_CONFIG_BANK_INTERLEAVE_1', + 1: 'ADDR_CONFIG_BANK_INTERLEAVE_2', + 2: 'ADDR_CONFIG_BANK_INTERLEAVE_4', + 3: 'ADDR_CONFIG_BANK_INTERLEAVE_8', +} +ADDR_CONFIG_BANK_INTERLEAVE_1 = 0 +ADDR_CONFIG_BANK_INTERLEAVE_2 = 1 +ADDR_CONFIG_BANK_INTERLEAVE_4 = 2 +ADDR_CONFIG_BANK_INTERLEAVE_8 = 3 +BankInterleaveSize = ctypes.c_uint32 # enum + +# values for enumeration 'NumShaderEngines' +NumShaderEngines__enumvalues = { + 0: 'ADDR_CONFIG_1_SHADER_ENGINE', + 1: 'ADDR_CONFIG_2_SHADER_ENGINE', + 2: 'ADDR_CONFIG_4_SHADER_ENGINE', + 3: 'ADDR_CONFIG_8_SHADER_ENGINE', +} +ADDR_CONFIG_1_SHADER_ENGINE = 0 +ADDR_CONFIG_2_SHADER_ENGINE = 1 +ADDR_CONFIG_4_SHADER_ENGINE = 2 +ADDR_CONFIG_8_SHADER_ENGINE = 3 +NumShaderEngines = ctypes.c_uint32 # enum + +# values for enumeration 'NumRbPerShaderEngine' +NumRbPerShaderEngine__enumvalues = { + 0: 'ADDR_CONFIG_1_RB_PER_SHADER_ENGINE', + 1: 'ADDR_CONFIG_2_RB_PER_SHADER_ENGINE', + 2: 'ADDR_CONFIG_4_RB_PER_SHADER_ENGINE', +} +ADDR_CONFIG_1_RB_PER_SHADER_ENGINE = 0 +ADDR_CONFIG_2_RB_PER_SHADER_ENGINE = 1 +ADDR_CONFIG_4_RB_PER_SHADER_ENGINE = 2 +NumRbPerShaderEngine = ctypes.c_uint32 # enum + +# values for enumeration 'NumGPUs' +NumGPUs__enumvalues = { + 0: 'ADDR_CONFIG_1_GPU', + 1: 'ADDR_CONFIG_2_GPU', + 2: 'ADDR_CONFIG_4_GPU', + 3: 'ADDR_CONFIG_8_GPU', +} +ADDR_CONFIG_1_GPU = 0 +ADDR_CONFIG_2_GPU = 1 +ADDR_CONFIG_4_GPU = 2 +ADDR_CONFIG_8_GPU = 3 +NumGPUs = ctypes.c_uint32 # enum + +# values for enumeration 'NumMaxCompressedFragments' +NumMaxCompressedFragments__enumvalues = { + 0: 'ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS', + 1: 'ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS', + 2: 'ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS', + 3: 'ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS', +} +ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS = 0 +ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS = 1 +ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS = 2 +ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS = 3 +NumMaxCompressedFragments = ctypes.c_uint32 # enum + +# values for enumeration 'ShaderEngineTileSize' +ShaderEngineTileSize__enumvalues = { + 0: 'ADDR_CONFIG_SE_TILE_16', + 1: 'ADDR_CONFIG_SE_TILE_32', +} +ADDR_CONFIG_SE_TILE_16 = 0 +ADDR_CONFIG_SE_TILE_32 = 1 +ShaderEngineTileSize = ctypes.c_uint32 # enum + +# values for enumeration 'MultiGPUTileSize' +MultiGPUTileSize__enumvalues = { + 0: 'ADDR_CONFIG_GPU_TILE_16', + 1: 'ADDR_CONFIG_GPU_TILE_32', + 2: 'ADDR_CONFIG_GPU_TILE_64', + 3: 'ADDR_CONFIG_GPU_TILE_128', +} +ADDR_CONFIG_GPU_TILE_16 = 0 +ADDR_CONFIG_GPU_TILE_32 = 1 +ADDR_CONFIG_GPU_TILE_64 = 2 +ADDR_CONFIG_GPU_TILE_128 = 3 +MultiGPUTileSize = ctypes.c_uint32 # enum + +# values for enumeration 'RowSize' +RowSize__enumvalues = { + 0: 'ADDR_CONFIG_1KB_ROW', + 1: 'ADDR_CONFIG_2KB_ROW', + 2: 'ADDR_CONFIG_4KB_ROW', +} +ADDR_CONFIG_1KB_ROW = 0 +ADDR_CONFIG_2KB_ROW = 1 +ADDR_CONFIG_4KB_ROW = 2 +RowSize = ctypes.c_uint32 # enum + +# values for enumeration 'NumLowerPipes' +NumLowerPipes__enumvalues = { + 0: 'ADDR_CONFIG_1_LOWER_PIPES', + 1: 'ADDR_CONFIG_2_LOWER_PIPES', +} +ADDR_CONFIG_1_LOWER_PIPES = 0 +ADDR_CONFIG_2_LOWER_PIPES = 1 +NumLowerPipes = ctypes.c_uint32 # enum + +# values for enumeration 'ColorTransform' +ColorTransform__enumvalues = { + 0: 'DCC_CT_AUTO', + 1: 'DCC_CT_NONE', + 2: 'ABGR_TO_A_BG_G_RB', + 3: 'BGRA_TO_BG_G_RB_A', +} +DCC_CT_AUTO = 0 +DCC_CT_NONE = 1 +ABGR_TO_A_BG_G_RB = 2 +BGRA_TO_BG_G_RB_A = 3 +ColorTransform = ctypes.c_uint32 # enum + +# values for enumeration 'CompareRef' +CompareRef__enumvalues = { + 0: 'REF_NEVER', + 1: 'REF_LESS', + 2: 'REF_EQUAL', + 3: 'REF_LEQUAL', + 4: 'REF_GREATER', + 5: 'REF_NOTEQUAL', + 6: 'REF_GEQUAL', + 7: 'REF_ALWAYS', +} +REF_NEVER = 0 +REF_LESS = 1 +REF_EQUAL = 2 +REF_LEQUAL = 3 +REF_GREATER = 4 +REF_NOTEQUAL = 5 +REF_GEQUAL = 6 +REF_ALWAYS = 7 +CompareRef = ctypes.c_uint32 # enum + +# values for enumeration 'ReadSize' +ReadSize__enumvalues = { + 0: 'READ_256_BITS', + 1: 'READ_512_BITS', +} +READ_256_BITS = 0 +READ_512_BITS = 1 +ReadSize = ctypes.c_uint32 # enum + +# values for enumeration 'DepthFormat' +DepthFormat__enumvalues = { + 0: 'DEPTH_INVALID', + 1: 'DEPTH_16', + 2: 'DEPTH_X8_24', + 3: 'DEPTH_8_24', + 4: 'DEPTH_X8_24_FLOAT', + 5: 'DEPTH_8_24_FLOAT', + 6: 'DEPTH_32_FLOAT', + 7: 'DEPTH_X24_8_32_FLOAT', +} +DEPTH_INVALID = 0 +DEPTH_16 = 1 +DEPTH_X8_24 = 2 +DEPTH_8_24 = 3 +DEPTH_X8_24_FLOAT = 4 +DEPTH_8_24_FLOAT = 5 +DEPTH_32_FLOAT = 6 +DEPTH_X24_8_32_FLOAT = 7 +DepthFormat = ctypes.c_uint32 # enum + +# values for enumeration 'ZFormat' +ZFormat__enumvalues = { + 0: 'Z_INVALID', + 1: 'Z_16', + 2: 'Z_24', + 3: 'Z_32_FLOAT', +} +Z_INVALID = 0 +Z_16 = 1 +Z_24 = 2 +Z_32_FLOAT = 3 +ZFormat = ctypes.c_uint32 # enum + +# values for enumeration 'StencilFormat' +StencilFormat__enumvalues = { + 0: 'STENCIL_INVALID', + 1: 'STENCIL_8', +} +STENCIL_INVALID = 0 +STENCIL_8 = 1 +StencilFormat = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskMode' +CmaskMode__enumvalues = { + 0: 'CMASK_CLEAR_NONE', + 1: 'CMASK_CLEAR_ONE', + 2: 'CMASK_CLEAR_ALL', + 3: 'CMASK_ANY_EXPANDED', + 4: 'CMASK_ALPHA0_FRAG1', + 5: 'CMASK_ALPHA0_FRAG2', + 6: 'CMASK_ALPHA0_FRAG4', + 7: 'CMASK_ALPHA0_FRAGS', + 8: 'CMASK_ALPHA1_FRAG1', + 9: 'CMASK_ALPHA1_FRAG2', + 10: 'CMASK_ALPHA1_FRAG4', + 11: 'CMASK_ALPHA1_FRAGS', + 12: 'CMASK_ALPHAX_FRAG1', + 13: 'CMASK_ALPHAX_FRAG2', + 14: 'CMASK_ALPHAX_FRAG4', + 15: 'CMASK_ALPHAX_FRAGS', +} +CMASK_CLEAR_NONE = 0 +CMASK_CLEAR_ONE = 1 +CMASK_CLEAR_ALL = 2 +CMASK_ANY_EXPANDED = 3 +CMASK_ALPHA0_FRAG1 = 4 +CMASK_ALPHA0_FRAG2 = 5 +CMASK_ALPHA0_FRAG4 = 6 +CMASK_ALPHA0_FRAGS = 7 +CMASK_ALPHA1_FRAG1 = 8 +CMASK_ALPHA1_FRAG2 = 9 +CMASK_ALPHA1_FRAG4 = 10 +CMASK_ALPHA1_FRAGS = 11 +CMASK_ALPHAX_FRAG1 = 12 +CMASK_ALPHAX_FRAG2 = 13 +CMASK_ALPHAX_FRAG4 = 14 +CMASK_ALPHAX_FRAGS = 15 +CmaskMode = ctypes.c_uint32 # enum + +# values for enumeration 'QuadExportFormat' +QuadExportFormat__enumvalues = { + 0: 'EXPORT_UNUSED', + 1: 'EXPORT_32_R', + 2: 'EXPORT_32_GR', + 3: 'EXPORT_32_AR', + 4: 'EXPORT_FP16_ABGR', + 5: 'EXPORT_UNSIGNED16_ABGR', + 6: 'EXPORT_SIGNED16_ABGR', + 7: 'EXPORT_32_ABGR', + 8: 'EXPORT_32BPP_8PIX', + 9: 'EXPORT_16_16_UNSIGNED_8PIX', + 10: 'EXPORT_16_16_SIGNED_8PIX', + 11: 'EXPORT_16_16_FLOAT_8PIX', +} +EXPORT_UNUSED = 0 +EXPORT_32_R = 1 +EXPORT_32_GR = 2 +EXPORT_32_AR = 3 +EXPORT_FP16_ABGR = 4 +EXPORT_UNSIGNED16_ABGR = 5 +EXPORT_SIGNED16_ABGR = 6 +EXPORT_32_ABGR = 7 +EXPORT_32BPP_8PIX = 8 +EXPORT_16_16_UNSIGNED_8PIX = 9 +EXPORT_16_16_SIGNED_8PIX = 10 +EXPORT_16_16_FLOAT_8PIX = 11 +QuadExportFormat = ctypes.c_uint32 # enum + +# values for enumeration 'QuadExportFormatOld' +QuadExportFormatOld__enumvalues = { + 0: 'EXPORT_4P_32BPC_ABGR', + 1: 'EXPORT_4P_16BPC_ABGR', + 2: 'EXPORT_4P_32BPC_GR', + 3: 'EXPORT_4P_32BPC_AR', + 4: 'EXPORT_2P_32BPC_ABGR', + 5: 'EXPORT_8P_32BPC_R', +} +EXPORT_4P_32BPC_ABGR = 0 +EXPORT_4P_16BPC_ABGR = 1 +EXPORT_4P_32BPC_GR = 2 +EXPORT_4P_32BPC_AR = 3 +EXPORT_2P_32BPC_ABGR = 4 +EXPORT_8P_32BPC_R = 5 +QuadExportFormatOld = ctypes.c_uint32 # enum + +# values for enumeration 'ColorFormat' +ColorFormat__enumvalues = { + 0: 'COLOR_INVALID', + 1: 'COLOR_8', + 2: 'COLOR_16', + 3: 'COLOR_8_8', + 4: 'COLOR_32', + 5: 'COLOR_16_16', + 6: 'COLOR_10_11_11', + 7: 'COLOR_11_11_10', + 8: 'COLOR_10_10_10_2', + 9: 'COLOR_2_10_10_10', + 10: 'COLOR_8_8_8_8', + 11: 'COLOR_32_32', + 12: 'COLOR_16_16_16_16', + 13: 'COLOR_RESERVED_13', + 14: 'COLOR_32_32_32_32', + 15: 'COLOR_RESERVED_15', + 16: 'COLOR_5_6_5', + 17: 'COLOR_1_5_5_5', + 18: 'COLOR_5_5_5_1', + 19: 'COLOR_4_4_4_4', + 20: 'COLOR_8_24', + 21: 'COLOR_24_8', + 22: 'COLOR_X24_8_32_FLOAT', + 23: 'COLOR_RESERVED_23', + 24: 'COLOR_RESERVED_24', + 25: 'COLOR_RESERVED_25', + 26: 'COLOR_RESERVED_26', + 27: 'COLOR_RESERVED_27', + 28: 'COLOR_RESERVED_28', + 29: 'COLOR_RESERVED_29', + 30: 'COLOR_RESERVED_30', + 31: 'COLOR_2_10_10_10_6E4', +} +COLOR_INVALID = 0 +COLOR_8 = 1 +COLOR_16 = 2 +COLOR_8_8 = 3 +COLOR_32 = 4 +COLOR_16_16 = 5 +COLOR_10_11_11 = 6 +COLOR_11_11_10 = 7 +COLOR_10_10_10_2 = 8 +COLOR_2_10_10_10 = 9 +COLOR_8_8_8_8 = 10 +COLOR_32_32 = 11 +COLOR_16_16_16_16 = 12 +COLOR_RESERVED_13 = 13 +COLOR_32_32_32_32 = 14 +COLOR_RESERVED_15 = 15 +COLOR_5_6_5 = 16 +COLOR_1_5_5_5 = 17 +COLOR_5_5_5_1 = 18 +COLOR_4_4_4_4 = 19 +COLOR_8_24 = 20 +COLOR_24_8 = 21 +COLOR_X24_8_32_FLOAT = 22 +COLOR_RESERVED_23 = 23 +COLOR_RESERVED_24 = 24 +COLOR_RESERVED_25 = 25 +COLOR_RESERVED_26 = 26 +COLOR_RESERVED_27 = 27 +COLOR_RESERVED_28 = 28 +COLOR_RESERVED_29 = 29 +COLOR_RESERVED_30 = 30 +COLOR_2_10_10_10_6E4 = 31 +ColorFormat = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceFormat' +SurfaceFormat__enumvalues = { + 0: 'FMT_INVALID', + 1: 'FMT_8', + 2: 'FMT_16', + 3: 'FMT_8_8', + 4: 'FMT_32', + 5: 'FMT_16_16', + 6: 'FMT_10_11_11', + 7: 'FMT_11_11_10', + 8: 'FMT_10_10_10_2', + 9: 'FMT_2_10_10_10', + 10: 'FMT_8_8_8_8', + 11: 'FMT_32_32', + 12: 'FMT_16_16_16_16', + 13: 'FMT_32_32_32', + 14: 'FMT_32_32_32_32', + 15: 'FMT_RESERVED_4', + 16: 'FMT_5_6_5', + 17: 'FMT_1_5_5_5', + 18: 'FMT_5_5_5_1', + 19: 'FMT_4_4_4_4', + 20: 'FMT_8_24', + 21: 'FMT_24_8', + 22: 'FMT_X24_8_32_FLOAT', + 23: 'FMT_RESERVED_33', + 24: 'FMT_11_11_10_FLOAT', + 25: 'FMT_16_FLOAT', + 26: 'FMT_32_FLOAT', + 27: 'FMT_16_16_FLOAT', + 28: 'FMT_8_24_FLOAT', + 29: 'FMT_24_8_FLOAT', + 30: 'FMT_32_32_FLOAT', + 31: 'FMT_10_11_11_FLOAT', + 32: 'FMT_16_16_16_16_FLOAT', + 33: 'FMT_3_3_2', + 34: 'FMT_6_5_5', + 35: 'FMT_32_32_32_32_FLOAT', + 36: 'FMT_RESERVED_36', + 37: 'FMT_1', + 38: 'FMT_1_REVERSED', + 39: 'FMT_GB_GR', + 40: 'FMT_BG_RG', + 41: 'FMT_32_AS_8', + 42: 'FMT_32_AS_8_8', + 43: 'FMT_5_9_9_9_SHAREDEXP', + 44: 'FMT_8_8_8', + 45: 'FMT_16_16_16', + 46: 'FMT_16_16_16_FLOAT', + 47: 'FMT_4_4', + 48: 'FMT_32_32_32_FLOAT', + 49: 'FMT_BC1', + 50: 'FMT_BC2', + 51: 'FMT_BC3', + 52: 'FMT_BC4', + 53: 'FMT_BC5', + 54: 'FMT_BC6', + 55: 'FMT_BC7', + 56: 'FMT_32_AS_32_32_32_32', + 57: 'FMT_APC3', + 58: 'FMT_APC4', + 59: 'FMT_APC5', + 60: 'FMT_APC6', + 61: 'FMT_APC7', + 62: 'FMT_CTX1', + 63: 'FMT_RESERVED_63', +} +FMT_INVALID = 0 +FMT_8 = 1 +FMT_16 = 2 +FMT_8_8 = 3 +FMT_32 = 4 +FMT_16_16 = 5 +FMT_10_11_11 = 6 +FMT_11_11_10 = 7 +FMT_10_10_10_2 = 8 +FMT_2_10_10_10 = 9 +FMT_8_8_8_8 = 10 +FMT_32_32 = 11 +FMT_16_16_16_16 = 12 +FMT_32_32_32 = 13 +FMT_32_32_32_32 = 14 +FMT_RESERVED_4 = 15 +FMT_5_6_5 = 16 +FMT_1_5_5_5 = 17 +FMT_5_5_5_1 = 18 +FMT_4_4_4_4 = 19 +FMT_8_24 = 20 +FMT_24_8 = 21 +FMT_X24_8_32_FLOAT = 22 +FMT_RESERVED_33 = 23 +FMT_11_11_10_FLOAT = 24 +FMT_16_FLOAT = 25 +FMT_32_FLOAT = 26 +FMT_16_16_FLOAT = 27 +FMT_8_24_FLOAT = 28 +FMT_24_8_FLOAT = 29 +FMT_32_32_FLOAT = 30 +FMT_10_11_11_FLOAT = 31 +FMT_16_16_16_16_FLOAT = 32 +FMT_3_3_2 = 33 +FMT_6_5_5 = 34 +FMT_32_32_32_32_FLOAT = 35 +FMT_RESERVED_36 = 36 +FMT_1 = 37 +FMT_1_REVERSED = 38 +FMT_GB_GR = 39 +FMT_BG_RG = 40 +FMT_32_AS_8 = 41 +FMT_32_AS_8_8 = 42 +FMT_5_9_9_9_SHAREDEXP = 43 +FMT_8_8_8 = 44 +FMT_16_16_16 = 45 +FMT_16_16_16_FLOAT = 46 +FMT_4_4 = 47 +FMT_32_32_32_FLOAT = 48 +FMT_BC1 = 49 +FMT_BC2 = 50 +FMT_BC3 = 51 +FMT_BC4 = 52 +FMT_BC5 = 53 +FMT_BC6 = 54 +FMT_BC7 = 55 +FMT_32_AS_32_32_32_32 = 56 +FMT_APC3 = 57 +FMT_APC4 = 58 +FMT_APC5 = 59 +FMT_APC6 = 60 +FMT_APC7 = 61 +FMT_CTX1 = 62 +FMT_RESERVED_63 = 63 +SurfaceFormat = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_FMASK' +IMG_NUM_FORMAT_FMASK__enumvalues = { + 0: 'IMG_NUM_FORMAT_FMASK_8_2_1', + 1: 'IMG_NUM_FORMAT_FMASK_8_4_1', + 2: 'IMG_NUM_FORMAT_FMASK_8_8_1', + 3: 'IMG_NUM_FORMAT_FMASK_8_2_2', + 4: 'IMG_NUM_FORMAT_FMASK_8_4_2', + 5: 'IMG_NUM_FORMAT_FMASK_8_4_4', + 6: 'IMG_NUM_FORMAT_FMASK_16_16_1', + 7: 'IMG_NUM_FORMAT_FMASK_16_8_2', + 8: 'IMG_NUM_FORMAT_FMASK_32_16_2', + 9: 'IMG_NUM_FORMAT_FMASK_32_8_4', + 10: 'IMG_NUM_FORMAT_FMASK_32_8_8', + 11: 'IMG_NUM_FORMAT_FMASK_64_16_4', + 12: 'IMG_NUM_FORMAT_FMASK_64_16_8', + 13: 'IMG_NUM_FORMAT_FMASK_RESERVED_13', + 14: 'IMG_NUM_FORMAT_FMASK_RESERVED_14', + 15: 'IMG_NUM_FORMAT_FMASK_RESERVED_15', +} +IMG_NUM_FORMAT_FMASK_8_2_1 = 0 +IMG_NUM_FORMAT_FMASK_8_4_1 = 1 +IMG_NUM_FORMAT_FMASK_8_8_1 = 2 +IMG_NUM_FORMAT_FMASK_8_2_2 = 3 +IMG_NUM_FORMAT_FMASK_8_4_2 = 4 +IMG_NUM_FORMAT_FMASK_8_4_4 = 5 +IMG_NUM_FORMAT_FMASK_16_16_1 = 6 +IMG_NUM_FORMAT_FMASK_16_8_2 = 7 +IMG_NUM_FORMAT_FMASK_32_16_2 = 8 +IMG_NUM_FORMAT_FMASK_32_8_4 = 9 +IMG_NUM_FORMAT_FMASK_32_8_8 = 10 +IMG_NUM_FORMAT_FMASK_64_16_4 = 11 +IMG_NUM_FORMAT_FMASK_64_16_8 = 12 +IMG_NUM_FORMAT_FMASK_RESERVED_13 = 13 +IMG_NUM_FORMAT_FMASK_RESERVED_14 = 14 +IMG_NUM_FORMAT_FMASK_RESERVED_15 = 15 +IMG_NUM_FORMAT_FMASK = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_N_IN_16' +IMG_NUM_FORMAT_N_IN_16__enumvalues = { + 0: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_0', + 1: 'IMG_NUM_FORMAT_N_IN_16_UNORM_10', + 2: 'IMG_NUM_FORMAT_N_IN_16_UNORM_9', + 3: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_3', + 4: 'IMG_NUM_FORMAT_N_IN_16_UINT_10', + 5: 'IMG_NUM_FORMAT_N_IN_16_UINT_9', + 6: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_6', + 7: 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10', + 8: 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9', + 9: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_9', + 10: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_10', + 11: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_11', + 12: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_12', + 13: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_13', + 14: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_14', + 15: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_15', +} +IMG_NUM_FORMAT_N_IN_16_RESERVED_0 = 0 +IMG_NUM_FORMAT_N_IN_16_UNORM_10 = 1 +IMG_NUM_FORMAT_N_IN_16_UNORM_9 = 2 +IMG_NUM_FORMAT_N_IN_16_RESERVED_3 = 3 +IMG_NUM_FORMAT_N_IN_16_UINT_10 = 4 +IMG_NUM_FORMAT_N_IN_16_UINT_9 = 5 +IMG_NUM_FORMAT_N_IN_16_RESERVED_6 = 6 +IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10 = 7 +IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9 = 8 +IMG_NUM_FORMAT_N_IN_16_RESERVED_9 = 9 +IMG_NUM_FORMAT_N_IN_16_RESERVED_10 = 10 +IMG_NUM_FORMAT_N_IN_16_RESERVED_11 = 11 +IMG_NUM_FORMAT_N_IN_16_RESERVED_12 = 12 +IMG_NUM_FORMAT_N_IN_16_RESERVED_13 = 13 +IMG_NUM_FORMAT_N_IN_16_RESERVED_14 = 14 +IMG_NUM_FORMAT_N_IN_16_RESERVED_15 = 15 +IMG_NUM_FORMAT_N_IN_16 = ctypes.c_uint32 # enum + +# values for enumeration 'TileType' +TileType__enumvalues = { + 0: 'ARRAY_COLOR_TILE', + 1: 'ARRAY_DEPTH_TILE', +} +ARRAY_COLOR_TILE = 0 +ARRAY_DEPTH_TILE = 1 +TileType = ctypes.c_uint32 # enum + +# values for enumeration 'NonDispTilingOrder' +NonDispTilingOrder__enumvalues = { + 0: 'ADDR_SURF_MICRO_TILING_DISPLAY', + 1: 'ADDR_SURF_MICRO_TILING_NON_DISPLAY', +} +ADDR_SURF_MICRO_TILING_DISPLAY = 0 +ADDR_SURF_MICRO_TILING_NON_DISPLAY = 1 +NonDispTilingOrder = ctypes.c_uint32 # enum + +# values for enumeration 'MicroTileMode' +MicroTileMode__enumvalues = { + 0: 'ADDR_SURF_DISPLAY_MICRO_TILING', + 1: 'ADDR_SURF_THIN_MICRO_TILING', + 2: 'ADDR_SURF_DEPTH_MICRO_TILING', + 3: 'ADDR_SURF_ROTATED_MICRO_TILING', + 4: 'ADDR_SURF_THICK_MICRO_TILING', +} +ADDR_SURF_DISPLAY_MICRO_TILING = 0 +ADDR_SURF_THIN_MICRO_TILING = 1 +ADDR_SURF_DEPTH_MICRO_TILING = 2 +ADDR_SURF_ROTATED_MICRO_TILING = 3 +ADDR_SURF_THICK_MICRO_TILING = 4 +MicroTileMode = ctypes.c_uint32 # enum + +# values for enumeration 'TileSplit' +TileSplit__enumvalues = { + 0: 'ADDR_SURF_TILE_SPLIT_64B', + 1: 'ADDR_SURF_TILE_SPLIT_128B', + 2: 'ADDR_SURF_TILE_SPLIT_256B', + 3: 'ADDR_SURF_TILE_SPLIT_512B', + 4: 'ADDR_SURF_TILE_SPLIT_1KB', + 5: 'ADDR_SURF_TILE_SPLIT_2KB', + 6: 'ADDR_SURF_TILE_SPLIT_4KB', +} +ADDR_SURF_TILE_SPLIT_64B = 0 +ADDR_SURF_TILE_SPLIT_128B = 1 +ADDR_SURF_TILE_SPLIT_256B = 2 +ADDR_SURF_TILE_SPLIT_512B = 3 +ADDR_SURF_TILE_SPLIT_1KB = 4 +ADDR_SURF_TILE_SPLIT_2KB = 5 +ADDR_SURF_TILE_SPLIT_4KB = 6 +TileSplit = ctypes.c_uint32 # enum + +# values for enumeration 'SampleSplit' +SampleSplit__enumvalues = { + 0: 'ADDR_SURF_SAMPLE_SPLIT_1', + 1: 'ADDR_SURF_SAMPLE_SPLIT_2', + 2: 'ADDR_SURF_SAMPLE_SPLIT_4', + 3: 'ADDR_SURF_SAMPLE_SPLIT_8', +} +ADDR_SURF_SAMPLE_SPLIT_1 = 0 +ADDR_SURF_SAMPLE_SPLIT_2 = 1 +ADDR_SURF_SAMPLE_SPLIT_4 = 2 +ADDR_SURF_SAMPLE_SPLIT_8 = 3 +SampleSplit = ctypes.c_uint32 # enum + +# values for enumeration 'PipeConfig' +PipeConfig__enumvalues = { + 0: 'ADDR_SURF_P2', + 1: 'ADDR_SURF_P2_RESERVED0', + 2: 'ADDR_SURF_P2_RESERVED1', + 3: 'ADDR_SURF_P2_RESERVED2', + 4: 'ADDR_SURF_P4_8x16', + 5: 'ADDR_SURF_P4_16x16', + 6: 'ADDR_SURF_P4_16x32', + 7: 'ADDR_SURF_P4_32x32', + 8: 'ADDR_SURF_P8_16x16_8x16', + 9: 'ADDR_SURF_P8_16x32_8x16', + 10: 'ADDR_SURF_P8_32x32_8x16', + 11: 'ADDR_SURF_P8_16x32_16x16', + 12: 'ADDR_SURF_P8_32x32_16x16', + 13: 'ADDR_SURF_P8_32x32_16x32', + 14: 'ADDR_SURF_P8_32x64_32x32', + 15: 'ADDR_SURF_P8_RESERVED0', + 16: 'ADDR_SURF_P16_32x32_8x16', + 17: 'ADDR_SURF_P16_32x32_16x16', + 18: 'ADDR_SURF_P16', +} +ADDR_SURF_P2 = 0 +ADDR_SURF_P2_RESERVED0 = 1 +ADDR_SURF_P2_RESERVED1 = 2 +ADDR_SURF_P2_RESERVED2 = 3 +ADDR_SURF_P4_8x16 = 4 +ADDR_SURF_P4_16x16 = 5 +ADDR_SURF_P4_16x32 = 6 +ADDR_SURF_P4_32x32 = 7 +ADDR_SURF_P8_16x16_8x16 = 8 +ADDR_SURF_P8_16x32_8x16 = 9 +ADDR_SURF_P8_32x32_8x16 = 10 +ADDR_SURF_P8_16x32_16x16 = 11 +ADDR_SURF_P8_32x32_16x16 = 12 +ADDR_SURF_P8_32x32_16x32 = 13 +ADDR_SURF_P8_32x64_32x32 = 14 +ADDR_SURF_P8_RESERVED0 = 15 +ADDR_SURF_P16_32x32_8x16 = 16 +ADDR_SURF_P16_32x32_16x16 = 17 +ADDR_SURF_P16 = 18 +PipeConfig = ctypes.c_uint32 # enum + +# values for enumeration 'SeEnable' +SeEnable__enumvalues = { + 0: 'ADDR_CONFIG_DISABLE_SE', + 1: 'ADDR_CONFIG_ENABLE_SE', +} +ADDR_CONFIG_DISABLE_SE = 0 +ADDR_CONFIG_ENABLE_SE = 1 +SeEnable = ctypes.c_uint32 # enum + +# values for enumeration 'NumBanks' +NumBanks__enumvalues = { + 0: 'ADDR_SURF_2_BANK', + 1: 'ADDR_SURF_4_BANK', + 2: 'ADDR_SURF_8_BANK', + 3: 'ADDR_SURF_16_BANK', +} +ADDR_SURF_2_BANK = 0 +ADDR_SURF_4_BANK = 1 +ADDR_SURF_8_BANK = 2 +ADDR_SURF_16_BANK = 3 +NumBanks = ctypes.c_uint32 # enum + +# values for enumeration 'BankWidth' +BankWidth__enumvalues = { + 0: 'ADDR_SURF_BANK_WIDTH_1', + 1: 'ADDR_SURF_BANK_WIDTH_2', + 2: 'ADDR_SURF_BANK_WIDTH_4', + 3: 'ADDR_SURF_BANK_WIDTH_8', +} +ADDR_SURF_BANK_WIDTH_1 = 0 +ADDR_SURF_BANK_WIDTH_2 = 1 +ADDR_SURF_BANK_WIDTH_4 = 2 +ADDR_SURF_BANK_WIDTH_8 = 3 +BankWidth = ctypes.c_uint32 # enum + +# values for enumeration 'BankHeight' +BankHeight__enumvalues = { + 0: 'ADDR_SURF_BANK_HEIGHT_1', + 1: 'ADDR_SURF_BANK_HEIGHT_2', + 2: 'ADDR_SURF_BANK_HEIGHT_4', + 3: 'ADDR_SURF_BANK_HEIGHT_8', +} +ADDR_SURF_BANK_HEIGHT_1 = 0 +ADDR_SURF_BANK_HEIGHT_2 = 1 +ADDR_SURF_BANK_HEIGHT_4 = 2 +ADDR_SURF_BANK_HEIGHT_8 = 3 +BankHeight = ctypes.c_uint32 # enum + +# values for enumeration 'BankWidthHeight' +BankWidthHeight__enumvalues = { + 0: 'ADDR_SURF_BANK_WH_1', + 1: 'ADDR_SURF_BANK_WH_2', + 2: 'ADDR_SURF_BANK_WH_4', + 3: 'ADDR_SURF_BANK_WH_8', +} +ADDR_SURF_BANK_WH_1 = 0 +ADDR_SURF_BANK_WH_2 = 1 +ADDR_SURF_BANK_WH_4 = 2 +ADDR_SURF_BANK_WH_8 = 3 +BankWidthHeight = ctypes.c_uint32 # enum + +# values for enumeration 'MacroTileAspect' +MacroTileAspect__enumvalues = { + 0: 'ADDR_SURF_MACRO_ASPECT_1', + 1: 'ADDR_SURF_MACRO_ASPECT_2', + 2: 'ADDR_SURF_MACRO_ASPECT_4', + 3: 'ADDR_SURF_MACRO_ASPECT_8', +} +ADDR_SURF_MACRO_ASPECT_1 = 0 +ADDR_SURF_MACRO_ASPECT_2 = 1 +ADDR_SURF_MACRO_ASPECT_4 = 2 +ADDR_SURF_MACRO_ASPECT_8 = 3 +MacroTileAspect = ctypes.c_uint32 # enum + +# values for enumeration 'PipeTiling' +PipeTiling__enumvalues = { + 0: 'CONFIG_1_PIPE', + 1: 'CONFIG_2_PIPE', + 2: 'CONFIG_4_PIPE', + 3: 'CONFIG_8_PIPE', +} +CONFIG_1_PIPE = 0 +CONFIG_2_PIPE = 1 +CONFIG_4_PIPE = 2 +CONFIG_8_PIPE = 3 +PipeTiling = ctypes.c_uint32 # enum + +# values for enumeration 'BankTiling' +BankTiling__enumvalues = { + 0: 'CONFIG_4_BANK', + 1: 'CONFIG_8_BANK', +} +CONFIG_4_BANK = 0 +CONFIG_8_BANK = 1 +BankTiling = ctypes.c_uint32 # enum + +# values for enumeration 'GroupInterleave' +GroupInterleave__enumvalues = { + 0: 'CONFIG_256B_GROUP', + 1: 'CONFIG_512B_GROUP', +} +CONFIG_256B_GROUP = 0 +CONFIG_512B_GROUP = 1 +GroupInterleave = ctypes.c_uint32 # enum + +# values for enumeration 'RowTiling' +RowTiling__enumvalues = { + 0: 'CONFIG_1KB_ROW', + 1: 'CONFIG_2KB_ROW', + 2: 'CONFIG_4KB_ROW', + 3: 'CONFIG_8KB_ROW', + 4: 'CONFIG_1KB_ROW_OPT', + 5: 'CONFIG_2KB_ROW_OPT', + 6: 'CONFIG_4KB_ROW_OPT', + 7: 'CONFIG_8KB_ROW_OPT', +} +CONFIG_1KB_ROW = 0 +CONFIG_2KB_ROW = 1 +CONFIG_4KB_ROW = 2 +CONFIG_8KB_ROW = 3 +CONFIG_1KB_ROW_OPT = 4 +CONFIG_2KB_ROW_OPT = 5 +CONFIG_4KB_ROW_OPT = 6 +CONFIG_8KB_ROW_OPT = 7 +RowTiling = ctypes.c_uint32 # enum + +# values for enumeration 'BankSwapBytes' +BankSwapBytes__enumvalues = { + 0: 'CONFIG_128B_SWAPS', + 1: 'CONFIG_256B_SWAPS', + 2: 'CONFIG_512B_SWAPS', + 3: 'CONFIG_1KB_SWAPS', +} +CONFIG_128B_SWAPS = 0 +CONFIG_256B_SWAPS = 1 +CONFIG_512B_SWAPS = 2 +CONFIG_1KB_SWAPS = 3 +BankSwapBytes = ctypes.c_uint32 # enum + +# values for enumeration 'SampleSplitBytes' +SampleSplitBytes__enumvalues = { + 0: 'CONFIG_1KB_SPLIT', + 1: 'CONFIG_2KB_SPLIT', + 2: 'CONFIG_4KB_SPLIT', + 3: 'CONFIG_8KB_SPLIT', +} +CONFIG_1KB_SPLIT = 0 +CONFIG_2KB_SPLIT = 1 +CONFIG_4KB_SPLIT = 2 +CONFIG_8KB_SPLIT = 3 +SampleSplitBytes = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceNumber' +SurfaceNumber__enumvalues = { + 0: 'NUMBER_UNORM', + 1: 'NUMBER_SNORM', + 2: 'NUMBER_USCALED', + 3: 'NUMBER_SSCALED', + 4: 'NUMBER_UINT', + 5: 'NUMBER_SINT', + 6: 'NUMBER_SRGB', + 7: 'NUMBER_FLOAT', +} +NUMBER_UNORM = 0 +NUMBER_SNORM = 1 +NUMBER_USCALED = 2 +NUMBER_SSCALED = 3 +NUMBER_UINT = 4 +NUMBER_SINT = 5 +NUMBER_SRGB = 6 +NUMBER_FLOAT = 7 +SurfaceNumber = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceSwap' +SurfaceSwap__enumvalues = { + 0: 'SWAP_STD', + 1: 'SWAP_ALT', + 2: 'SWAP_STD_REV', + 3: 'SWAP_ALT_REV', +} +SWAP_STD = 0 +SWAP_ALT = 1 +SWAP_STD_REV = 2 +SWAP_ALT_REV = 3 +SurfaceSwap = ctypes.c_uint32 # enum + +# values for enumeration 'RoundMode' +RoundMode__enumvalues = { + 0: 'ROUND_BY_HALF', + 1: 'ROUND_TRUNCATE', +} +ROUND_BY_HALF = 0 +ROUND_TRUNCATE = 1 +RoundMode = ctypes.c_uint32 # enum + +# values for enumeration 'BUF_FMT' +BUF_FMT__enumvalues = { + 0: 'BUF_FMT_INVALID', + 1: 'BUF_FMT_8_UNORM', + 2: 'BUF_FMT_8_SNORM', + 3: 'BUF_FMT_8_USCALED', + 4: 'BUF_FMT_8_SSCALED', + 5: 'BUF_FMT_8_UINT', + 6: 'BUF_FMT_8_SINT', + 7: 'BUF_FMT_16_UNORM', + 8: 'BUF_FMT_16_SNORM', + 9: 'BUF_FMT_16_USCALED', + 10: 'BUF_FMT_16_SSCALED', + 11: 'BUF_FMT_16_UINT', + 12: 'BUF_FMT_16_SINT', + 13: 'BUF_FMT_16_FLOAT', + 14: 'BUF_FMT_8_8_UNORM', + 15: 'BUF_FMT_8_8_SNORM', + 16: 'BUF_FMT_8_8_USCALED', + 17: 'BUF_FMT_8_8_SSCALED', + 18: 'BUF_FMT_8_8_UINT', + 19: 'BUF_FMT_8_8_SINT', + 20: 'BUF_FMT_32_UINT', + 21: 'BUF_FMT_32_SINT', + 22: 'BUF_FMT_32_FLOAT', + 23: 'BUF_FMT_16_16_UNORM', + 24: 'BUF_FMT_16_16_SNORM', + 25: 'BUF_FMT_16_16_USCALED', + 26: 'BUF_FMT_16_16_SSCALED', + 27: 'BUF_FMT_16_16_UINT', + 28: 'BUF_FMT_16_16_SINT', + 29: 'BUF_FMT_16_16_FLOAT', + 30: 'BUF_FMT_10_11_11_UNORM', + 31: 'BUF_FMT_10_11_11_SNORM', + 32: 'BUF_FMT_10_11_11_USCALED', + 33: 'BUF_FMT_10_11_11_SSCALED', + 34: 'BUF_FMT_10_11_11_UINT', + 35: 'BUF_FMT_10_11_11_SINT', + 36: 'BUF_FMT_10_11_11_FLOAT', + 37: 'BUF_FMT_11_11_10_UNORM', + 38: 'BUF_FMT_11_11_10_SNORM', + 39: 'BUF_FMT_11_11_10_USCALED', + 40: 'BUF_FMT_11_11_10_SSCALED', + 41: 'BUF_FMT_11_11_10_UINT', + 42: 'BUF_FMT_11_11_10_SINT', + 43: 'BUF_FMT_11_11_10_FLOAT', + 44: 'BUF_FMT_10_10_10_2_UNORM', + 45: 'BUF_FMT_10_10_10_2_SNORM', + 46: 'BUF_FMT_10_10_10_2_USCALED', + 47: 'BUF_FMT_10_10_10_2_SSCALED', + 48: 'BUF_FMT_10_10_10_2_UINT', + 49: 'BUF_FMT_10_10_10_2_SINT', + 50: 'BUF_FMT_2_10_10_10_UNORM', + 51: 'BUF_FMT_2_10_10_10_SNORM', + 52: 'BUF_FMT_2_10_10_10_USCALED', + 53: 'BUF_FMT_2_10_10_10_SSCALED', + 54: 'BUF_FMT_2_10_10_10_UINT', + 55: 'BUF_FMT_2_10_10_10_SINT', + 56: 'BUF_FMT_8_8_8_8_UNORM', + 57: 'BUF_FMT_8_8_8_8_SNORM', + 58: 'BUF_FMT_8_8_8_8_USCALED', + 59: 'BUF_FMT_8_8_8_8_SSCALED', + 60: 'BUF_FMT_8_8_8_8_UINT', + 61: 'BUF_FMT_8_8_8_8_SINT', + 62: 'BUF_FMT_32_32_UINT', + 63: 'BUF_FMT_32_32_SINT', + 64: 'BUF_FMT_32_32_FLOAT', + 65: 'BUF_FMT_16_16_16_16_UNORM', + 66: 'BUF_FMT_16_16_16_16_SNORM', + 67: 'BUF_FMT_16_16_16_16_USCALED', + 68: 'BUF_FMT_16_16_16_16_SSCALED', + 69: 'BUF_FMT_16_16_16_16_UINT', + 70: 'BUF_FMT_16_16_16_16_SINT', + 71: 'BUF_FMT_16_16_16_16_FLOAT', + 72: 'BUF_FMT_32_32_32_UINT', + 73: 'BUF_FMT_32_32_32_SINT', + 74: 'BUF_FMT_32_32_32_FLOAT', + 75: 'BUF_FMT_32_32_32_32_UINT', + 76: 'BUF_FMT_32_32_32_32_SINT', + 77: 'BUF_FMT_32_32_32_32_FLOAT', + 78: 'BUF_FMT_RESERVED_78', + 79: 'BUF_FMT_RESERVED_79', + 80: 'BUF_FMT_RESERVED_80', + 81: 'BUF_FMT_RESERVED_81', + 82: 'BUF_FMT_RESERVED_82', + 83: 'BUF_FMT_RESERVED_83', + 84: 'BUF_FMT_RESERVED_84', + 85: 'BUF_FMT_RESERVED_85', + 86: 'BUF_FMT_RESERVED_86', + 87: 'BUF_FMT_RESERVED_87', + 88: 'BUF_FMT_RESERVED_88', + 89: 'BUF_FMT_RESERVED_89', + 90: 'BUF_FMT_RESERVED_90', + 91: 'BUF_FMT_RESERVED_91', + 92: 'BUF_FMT_RESERVED_92', + 93: 'BUF_FMT_RESERVED_93', + 94: 'BUF_FMT_RESERVED_94', + 95: 'BUF_FMT_RESERVED_95', + 96: 'BUF_FMT_RESERVED_96', + 97: 'BUF_FMT_RESERVED_97', + 98: 'BUF_FMT_RESERVED_98', + 99: 'BUF_FMT_RESERVED_99', + 100: 'BUF_FMT_RESERVED_100', + 101: 'BUF_FMT_RESERVED_101', + 102: 'BUF_FMT_RESERVED_102', + 103: 'BUF_FMT_RESERVED_103', + 104: 'BUF_FMT_RESERVED_104', + 105: 'BUF_FMT_RESERVED_105', + 106: 'BUF_FMT_RESERVED_106', + 107: 'BUF_FMT_RESERVED_107', + 108: 'BUF_FMT_RESERVED_108', + 109: 'BUF_FMT_RESERVED_109', + 110: 'BUF_FMT_RESERVED_110', + 111: 'BUF_FMT_RESERVED_111', + 112: 'BUF_FMT_RESERVED_112', + 113: 'BUF_FMT_RESERVED_113', + 114: 'BUF_FMT_RESERVED_114', + 115: 'BUF_FMT_RESERVED_115', + 116: 'BUF_FMT_RESERVED_116', + 117: 'BUF_FMT_RESERVED_117', + 118: 'BUF_FMT_RESERVED_118', + 119: 'BUF_FMT_RESERVED_119', + 120: 'BUF_FMT_RESERVED_120', + 121: 'BUF_FMT_RESERVED_121', + 122: 'BUF_FMT_RESERVED_122', + 123: 'BUF_FMT_RESERVED_123', + 124: 'BUF_FMT_RESERVED_124', + 125: 'BUF_FMT_RESERVED_125', + 126: 'BUF_FMT_RESERVED_126', + 127: 'BUF_FMT_RESERVED_127', +} +BUF_FMT_INVALID = 0 +BUF_FMT_8_UNORM = 1 +BUF_FMT_8_SNORM = 2 +BUF_FMT_8_USCALED = 3 +BUF_FMT_8_SSCALED = 4 +BUF_FMT_8_UINT = 5 +BUF_FMT_8_SINT = 6 +BUF_FMT_16_UNORM = 7 +BUF_FMT_16_SNORM = 8 +BUF_FMT_16_USCALED = 9 +BUF_FMT_16_SSCALED = 10 +BUF_FMT_16_UINT = 11 +BUF_FMT_16_SINT = 12 +BUF_FMT_16_FLOAT = 13 +BUF_FMT_8_8_UNORM = 14 +BUF_FMT_8_8_SNORM = 15 +BUF_FMT_8_8_USCALED = 16 +BUF_FMT_8_8_SSCALED = 17 +BUF_FMT_8_8_UINT = 18 +BUF_FMT_8_8_SINT = 19 +BUF_FMT_32_UINT = 20 +BUF_FMT_32_SINT = 21 +BUF_FMT_32_FLOAT = 22 +BUF_FMT_16_16_UNORM = 23 +BUF_FMT_16_16_SNORM = 24 +BUF_FMT_16_16_USCALED = 25 +BUF_FMT_16_16_SSCALED = 26 +BUF_FMT_16_16_UINT = 27 +BUF_FMT_16_16_SINT = 28 +BUF_FMT_16_16_FLOAT = 29 +BUF_FMT_10_11_11_UNORM = 30 +BUF_FMT_10_11_11_SNORM = 31 +BUF_FMT_10_11_11_USCALED = 32 +BUF_FMT_10_11_11_SSCALED = 33 +BUF_FMT_10_11_11_UINT = 34 +BUF_FMT_10_11_11_SINT = 35 +BUF_FMT_10_11_11_FLOAT = 36 +BUF_FMT_11_11_10_UNORM = 37 +BUF_FMT_11_11_10_SNORM = 38 +BUF_FMT_11_11_10_USCALED = 39 +BUF_FMT_11_11_10_SSCALED = 40 +BUF_FMT_11_11_10_UINT = 41 +BUF_FMT_11_11_10_SINT = 42 +BUF_FMT_11_11_10_FLOAT = 43 +BUF_FMT_10_10_10_2_UNORM = 44 +BUF_FMT_10_10_10_2_SNORM = 45 +BUF_FMT_10_10_10_2_USCALED = 46 +BUF_FMT_10_10_10_2_SSCALED = 47 +BUF_FMT_10_10_10_2_UINT = 48 +BUF_FMT_10_10_10_2_SINT = 49 +BUF_FMT_2_10_10_10_UNORM = 50 +BUF_FMT_2_10_10_10_SNORM = 51 +BUF_FMT_2_10_10_10_USCALED = 52 +BUF_FMT_2_10_10_10_SSCALED = 53 +BUF_FMT_2_10_10_10_UINT = 54 +BUF_FMT_2_10_10_10_SINT = 55 +BUF_FMT_8_8_8_8_UNORM = 56 +BUF_FMT_8_8_8_8_SNORM = 57 +BUF_FMT_8_8_8_8_USCALED = 58 +BUF_FMT_8_8_8_8_SSCALED = 59 +BUF_FMT_8_8_8_8_UINT = 60 +BUF_FMT_8_8_8_8_SINT = 61 +BUF_FMT_32_32_UINT = 62 +BUF_FMT_32_32_SINT = 63 +BUF_FMT_32_32_FLOAT = 64 +BUF_FMT_16_16_16_16_UNORM = 65 +BUF_FMT_16_16_16_16_SNORM = 66 +BUF_FMT_16_16_16_16_USCALED = 67 +BUF_FMT_16_16_16_16_SSCALED = 68 +BUF_FMT_16_16_16_16_UINT = 69 +BUF_FMT_16_16_16_16_SINT = 70 +BUF_FMT_16_16_16_16_FLOAT = 71 +BUF_FMT_32_32_32_UINT = 72 +BUF_FMT_32_32_32_SINT = 73 +BUF_FMT_32_32_32_FLOAT = 74 +BUF_FMT_32_32_32_32_UINT = 75 +BUF_FMT_32_32_32_32_SINT = 76 +BUF_FMT_32_32_32_32_FLOAT = 77 +BUF_FMT_RESERVED_78 = 78 +BUF_FMT_RESERVED_79 = 79 +BUF_FMT_RESERVED_80 = 80 +BUF_FMT_RESERVED_81 = 81 +BUF_FMT_RESERVED_82 = 82 +BUF_FMT_RESERVED_83 = 83 +BUF_FMT_RESERVED_84 = 84 +BUF_FMT_RESERVED_85 = 85 +BUF_FMT_RESERVED_86 = 86 +BUF_FMT_RESERVED_87 = 87 +BUF_FMT_RESERVED_88 = 88 +BUF_FMT_RESERVED_89 = 89 +BUF_FMT_RESERVED_90 = 90 +BUF_FMT_RESERVED_91 = 91 +BUF_FMT_RESERVED_92 = 92 +BUF_FMT_RESERVED_93 = 93 +BUF_FMT_RESERVED_94 = 94 +BUF_FMT_RESERVED_95 = 95 +BUF_FMT_RESERVED_96 = 96 +BUF_FMT_RESERVED_97 = 97 +BUF_FMT_RESERVED_98 = 98 +BUF_FMT_RESERVED_99 = 99 +BUF_FMT_RESERVED_100 = 100 +BUF_FMT_RESERVED_101 = 101 +BUF_FMT_RESERVED_102 = 102 +BUF_FMT_RESERVED_103 = 103 +BUF_FMT_RESERVED_104 = 104 +BUF_FMT_RESERVED_105 = 105 +BUF_FMT_RESERVED_106 = 106 +BUF_FMT_RESERVED_107 = 107 +BUF_FMT_RESERVED_108 = 108 +BUF_FMT_RESERVED_109 = 109 +BUF_FMT_RESERVED_110 = 110 +BUF_FMT_RESERVED_111 = 111 +BUF_FMT_RESERVED_112 = 112 +BUF_FMT_RESERVED_113 = 113 +BUF_FMT_RESERVED_114 = 114 +BUF_FMT_RESERVED_115 = 115 +BUF_FMT_RESERVED_116 = 116 +BUF_FMT_RESERVED_117 = 117 +BUF_FMT_RESERVED_118 = 118 +BUF_FMT_RESERVED_119 = 119 +BUF_FMT_RESERVED_120 = 120 +BUF_FMT_RESERVED_121 = 121 +BUF_FMT_RESERVED_122 = 122 +BUF_FMT_RESERVED_123 = 123 +BUF_FMT_RESERVED_124 = 124 +BUF_FMT_RESERVED_125 = 125 +BUF_FMT_RESERVED_126 = 126 +BUF_FMT_RESERVED_127 = 127 +BUF_FMT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_FMT' +IMG_FMT__enumvalues = { + 0: 'IMG_FMT_INVALID', + 1: 'IMG_FMT_8_UNORM', + 2: 'IMG_FMT_8_SNORM', + 3: 'IMG_FMT_8_USCALED', + 4: 'IMG_FMT_8_SSCALED', + 5: 'IMG_FMT_8_UINT', + 6: 'IMG_FMT_8_SINT', + 7: 'IMG_FMT_16_UNORM', + 8: 'IMG_FMT_16_SNORM', + 9: 'IMG_FMT_16_USCALED', + 10: 'IMG_FMT_16_SSCALED', + 11: 'IMG_FMT_16_UINT', + 12: 'IMG_FMT_16_SINT', + 13: 'IMG_FMT_16_FLOAT', + 14: 'IMG_FMT_8_8_UNORM', + 15: 'IMG_FMT_8_8_SNORM', + 16: 'IMG_FMT_8_8_USCALED', + 17: 'IMG_FMT_8_8_SSCALED', + 18: 'IMG_FMT_8_8_UINT', + 19: 'IMG_FMT_8_8_SINT', + 20: 'IMG_FMT_32_UINT', + 21: 'IMG_FMT_32_SINT', + 22: 'IMG_FMT_32_FLOAT', + 23: 'IMG_FMT_16_16_UNORM', + 24: 'IMG_FMT_16_16_SNORM', + 25: 'IMG_FMT_16_16_USCALED', + 26: 'IMG_FMT_16_16_SSCALED', + 27: 'IMG_FMT_16_16_UINT', + 28: 'IMG_FMT_16_16_SINT', + 29: 'IMG_FMT_16_16_FLOAT', + 30: 'IMG_FMT_10_11_11_UNORM', + 31: 'IMG_FMT_10_11_11_SNORM', + 32: 'IMG_FMT_10_11_11_USCALED', + 33: 'IMG_FMT_10_11_11_SSCALED', + 34: 'IMG_FMT_10_11_11_UINT', + 35: 'IMG_FMT_10_11_11_SINT', + 36: 'IMG_FMT_10_11_11_FLOAT', + 37: 'IMG_FMT_11_11_10_UNORM', + 38: 'IMG_FMT_11_11_10_SNORM', + 39: 'IMG_FMT_11_11_10_USCALED', + 40: 'IMG_FMT_11_11_10_SSCALED', + 41: 'IMG_FMT_11_11_10_UINT', + 42: 'IMG_FMT_11_11_10_SINT', + 43: 'IMG_FMT_11_11_10_FLOAT', + 44: 'IMG_FMT_10_10_10_2_UNORM', + 45: 'IMG_FMT_10_10_10_2_SNORM', + 46: 'IMG_FMT_10_10_10_2_USCALED', + 47: 'IMG_FMT_10_10_10_2_SSCALED', + 48: 'IMG_FMT_10_10_10_2_UINT', + 49: 'IMG_FMT_10_10_10_2_SINT', + 50: 'IMG_FMT_2_10_10_10_UNORM', + 51: 'IMG_FMT_2_10_10_10_SNORM', + 52: 'IMG_FMT_2_10_10_10_USCALED', + 53: 'IMG_FMT_2_10_10_10_SSCALED', + 54: 'IMG_FMT_2_10_10_10_UINT', + 55: 'IMG_FMT_2_10_10_10_SINT', + 56: 'IMG_FMT_8_8_8_8_UNORM', + 57: 'IMG_FMT_8_8_8_8_SNORM', + 58: 'IMG_FMT_8_8_8_8_USCALED', + 59: 'IMG_FMT_8_8_8_8_SSCALED', + 60: 'IMG_FMT_8_8_8_8_UINT', + 61: 'IMG_FMT_8_8_8_8_SINT', + 62: 'IMG_FMT_32_32_UINT', + 63: 'IMG_FMT_32_32_SINT', + 64: 'IMG_FMT_32_32_FLOAT', + 65: 'IMG_FMT_16_16_16_16_UNORM', + 66: 'IMG_FMT_16_16_16_16_SNORM', + 67: 'IMG_FMT_16_16_16_16_USCALED', + 68: 'IMG_FMT_16_16_16_16_SSCALED', + 69: 'IMG_FMT_16_16_16_16_UINT', + 70: 'IMG_FMT_16_16_16_16_SINT', + 71: 'IMG_FMT_16_16_16_16_FLOAT', + 72: 'IMG_FMT_32_32_32_UINT', + 73: 'IMG_FMT_32_32_32_SINT', + 74: 'IMG_FMT_32_32_32_FLOAT', + 75: 'IMG_FMT_32_32_32_32_UINT', + 76: 'IMG_FMT_32_32_32_32_SINT', + 77: 'IMG_FMT_32_32_32_32_FLOAT', + 78: 'IMG_FMT_RESERVED_78', + 79: 'IMG_FMT_RESERVED_79', + 80: 'IMG_FMT_RESERVED_80', + 81: 'IMG_FMT_RESERVED_81', + 82: 'IMG_FMT_RESERVED_82', + 83: 'IMG_FMT_RESERVED_83', + 84: 'IMG_FMT_RESERVED_84', + 85: 'IMG_FMT_RESERVED_85', + 86: 'IMG_FMT_RESERVED_86', + 87: 'IMG_FMT_RESERVED_87', + 88: 'IMG_FMT_RESERVED_88', + 89: 'IMG_FMT_RESERVED_89', + 90: 'IMG_FMT_RESERVED_90', + 91: 'IMG_FMT_RESERVED_91', + 92: 'IMG_FMT_RESERVED_92', + 93: 'IMG_FMT_RESERVED_93', + 94: 'IMG_FMT_RESERVED_94', + 95: 'IMG_FMT_RESERVED_95', + 96: 'IMG_FMT_RESERVED_96', + 97: 'IMG_FMT_RESERVED_97', + 98: 'IMG_FMT_RESERVED_98', + 99: 'IMG_FMT_RESERVED_99', + 100: 'IMG_FMT_RESERVED_100', + 101: 'IMG_FMT_RESERVED_101', + 102: 'IMG_FMT_RESERVED_102', + 103: 'IMG_FMT_RESERVED_103', + 104: 'IMG_FMT_RESERVED_104', + 105: 'IMG_FMT_RESERVED_105', + 106: 'IMG_FMT_RESERVED_106', + 107: 'IMG_FMT_RESERVED_107', + 108: 'IMG_FMT_RESERVED_108', + 109: 'IMG_FMT_RESERVED_109', + 110: 'IMG_FMT_RESERVED_110', + 111: 'IMG_FMT_RESERVED_111', + 112: 'IMG_FMT_RESERVED_112', + 113: 'IMG_FMT_RESERVED_113', + 114: 'IMG_FMT_RESERVED_114', + 115: 'IMG_FMT_RESERVED_115', + 116: 'IMG_FMT_RESERVED_116', + 117: 'IMG_FMT_RESERVED_117', + 118: 'IMG_FMT_RESERVED_118', + 119: 'IMG_FMT_RESERVED_119', + 120: 'IMG_FMT_RESERVED_120', + 121: 'IMG_FMT_RESERVED_121', + 122: 'IMG_FMT_RESERVED_122', + 123: 'IMG_FMT_RESERVED_123', + 124: 'IMG_FMT_RESERVED_124', + 125: 'IMG_FMT_RESERVED_125', + 126: 'IMG_FMT_RESERVED_126', + 127: 'IMG_FMT_RESERVED_127', + 128: 'IMG_FMT_8_SRGB', + 129: 'IMG_FMT_8_8_SRGB', + 130: 'IMG_FMT_8_8_8_8_SRGB', + 131: 'IMG_FMT_6E4_FLOAT', + 132: 'IMG_FMT_5_9_9_9_FLOAT', + 133: 'IMG_FMT_5_6_5_UNORM', + 134: 'IMG_FMT_1_5_5_5_UNORM', + 135: 'IMG_FMT_5_5_5_1_UNORM', + 136: 'IMG_FMT_4_4_4_4_UNORM', + 137: 'IMG_FMT_4_4_UNORM', + 138: 'IMG_FMT_1_UNORM', + 139: 'IMG_FMT_1_REVERSED_UNORM', + 140: 'IMG_FMT_32_FLOAT_CLAMP', + 141: 'IMG_FMT_8_24_UNORM', + 142: 'IMG_FMT_8_24_UINT', + 143: 'IMG_FMT_24_8_UNORM', + 144: 'IMG_FMT_24_8_UINT', + 145: 'IMG_FMT_X24_8_32_UINT', + 146: 'IMG_FMT_X24_8_32_FLOAT', + 147: 'IMG_FMT_GB_GR_UNORM', + 148: 'IMG_FMT_GB_GR_SNORM', + 149: 'IMG_FMT_GB_GR_UINT', + 150: 'IMG_FMT_GB_GR_SRGB', + 151: 'IMG_FMT_BG_RG_UNORM', + 152: 'IMG_FMT_BG_RG_SNORM', + 153: 'IMG_FMT_BG_RG_UINT', + 154: 'IMG_FMT_BG_RG_SRGB', + 155: 'IMG_FMT_RESERVED_155', + 156: 'IMG_FMT_FMASK8_S2_F1', + 157: 'IMG_FMT_FMASK8_S4_F1', + 158: 'IMG_FMT_FMASK8_S8_F1', + 159: 'IMG_FMT_FMASK8_S2_F2', + 160: 'IMG_FMT_FMASK8_S4_F2', + 161: 'IMG_FMT_FMASK8_S4_F4', + 162: 'IMG_FMT_FMASK16_S16_F1', + 163: 'IMG_FMT_FMASK16_S8_F2', + 164: 'IMG_FMT_FMASK32_S16_F2', + 165: 'IMG_FMT_FMASK32_S8_F4', + 166: 'IMG_FMT_FMASK32_S8_F8', + 167: 'IMG_FMT_FMASK64_S16_F4', + 168: 'IMG_FMT_FMASK64_S16_F8', + 169: 'IMG_FMT_BC1_UNORM', + 170: 'IMG_FMT_BC1_SRGB', + 171: 'IMG_FMT_BC2_UNORM', + 172: 'IMG_FMT_BC2_SRGB', + 173: 'IMG_FMT_BC3_UNORM', + 174: 'IMG_FMT_BC3_SRGB', + 175: 'IMG_FMT_BC4_UNORM', + 176: 'IMG_FMT_BC4_SNORM', + 177: 'IMG_FMT_BC5_UNORM', + 178: 'IMG_FMT_BC5_SNORM', + 179: 'IMG_FMT_BC6_UFLOAT', + 180: 'IMG_FMT_BC6_SFLOAT', + 181: 'IMG_FMT_BC7_UNORM', + 182: 'IMG_FMT_BC7_SRGB', + 265: 'IMG_FMT_MM_8_UNORM', + 266: 'IMG_FMT_MM_8_UINT', + 267: 'IMG_FMT_MM_8_8_UNORM', + 268: 'IMG_FMT_MM_8_8_UINT', + 269: 'IMG_FMT_MM_8_8_8_8_UNORM', + 270: 'IMG_FMT_MM_8_8_8_8_UINT', + 271: 'IMG_FMT_MM_VYUY8_UNORM', + 272: 'IMG_FMT_MM_VYUY8_UINT', + 273: 'IMG_FMT_MM_10_11_11_UNORM', + 274: 'IMG_FMT_MM_10_11_11_UINT', + 275: 'IMG_FMT_MM_2_10_10_10_UNORM', + 276: 'IMG_FMT_MM_2_10_10_10_UINT', + 277: 'IMG_FMT_MM_16_16_16_16_UNORM', + 278: 'IMG_FMT_MM_16_16_16_16_UINT', + 279: 'IMG_FMT_MM_10_IN_16_UNORM', + 280: 'IMG_FMT_MM_10_IN_16_UINT', + 281: 'IMG_FMT_MM_10_IN_16_16_UNORM', + 282: 'IMG_FMT_MM_10_IN_16_16_UINT', + 283: 'IMG_FMT_MM_10_IN_16_16_16_16_UNORM', + 284: 'IMG_FMT_MM_10_IN_16_16_16_16_UINT', + 285: 'IMG_FMT_RESERVED_285', + 286: 'IMG_FMT_RESERVED_286', + 287: 'IMG_FMT_RESERVED_287', + 288: 'IMG_FMT_RESERVED_288', + 289: 'IMG_FMT_RESERVED_289', + 290: 'IMG_FMT_RESERVED_290', + 291: 'IMG_FMT_RESERVED_291', + 292: 'IMG_FMT_RESERVED_292', + 293: 'IMG_FMT_RESERVED_293', + 294: 'IMG_FMT_RESERVED_294', + 295: 'IMG_FMT_RESERVED_295', + 296: 'IMG_FMT_RESERVED_296', + 297: 'IMG_FMT_RESERVED_297', + 298: 'IMG_FMT_RESERVED_298', + 299: 'IMG_FMT_RESERVED_299', + 300: 'IMG_FMT_RESERVED_300', + 301: 'IMG_FMT_RESERVED_301', + 302: 'IMG_FMT_RESERVED_302', + 303: 'IMG_FMT_RESERVED_303', + 304: 'IMG_FMT_RESERVED_304', + 305: 'IMG_FMT_RESERVED_305', + 306: 'IMG_FMT_RESERVED_306', + 307: 'IMG_FMT_RESERVED_307', + 308: 'IMG_FMT_RESERVED_308', + 309: 'IMG_FMT_RESERVED_309', + 310: 'IMG_FMT_RESERVED_310', + 311: 'IMG_FMT_RESERVED_311', + 312: 'IMG_FMT_RESERVED_312', + 313: 'IMG_FMT_RESERVED_313', + 314: 'IMG_FMT_RESERVED_314', + 315: 'IMG_FMT_RESERVED_315', + 316: 'IMG_FMT_RESERVED_316', + 317: 'IMG_FMT_RESERVED_317', + 318: 'IMG_FMT_RESERVED_318', + 319: 'IMG_FMT_RESERVED_319', + 320: 'IMG_FMT_RESERVED_320', + 321: 'IMG_FMT_RESERVED_321', + 322: 'IMG_FMT_RESERVED_322', + 323: 'IMG_FMT_RESERVED_323', + 324: 'IMG_FMT_RESERVED_324', + 325: 'IMG_FMT_RESERVED_325', + 326: 'IMG_FMT_RESERVED_326', + 327: 'IMG_FMT_RESERVED_327', + 328: 'IMG_FMT_RESERVED_328', + 329: 'IMG_FMT_RESERVED_329', + 330: 'IMG_FMT_RESERVED_330', + 331: 'IMG_FMT_RESERVED_331', + 332: 'IMG_FMT_RESERVED_332', + 333: 'IMG_FMT_RESERVED_333', + 334: 'IMG_FMT_RESERVED_334', + 335: 'IMG_FMT_RESERVED_335', + 336: 'IMG_FMT_RESERVED_336', + 337: 'IMG_FMT_RESERVED_337', + 338: 'IMG_FMT_RESERVED_338', + 339: 'IMG_FMT_RESERVED_339', + 340: 'IMG_FMT_RESERVED_340', + 341: 'IMG_FMT_RESERVED_341', + 342: 'IMG_FMT_RESERVED_342', + 343: 'IMG_FMT_RESERVED_343', + 344: 'IMG_FMT_RESERVED_344', + 345: 'IMG_FMT_RESERVED_345', + 346: 'IMG_FMT_RESERVED_346', + 347: 'IMG_FMT_RESERVED_347', + 348: 'IMG_FMT_RESERVED_348', + 349: 'IMG_FMT_RESERVED_349', + 350: 'IMG_FMT_RESERVED_350', + 351: 'IMG_FMT_RESERVED_351', + 352: 'IMG_FMT_RESERVED_352', + 353: 'IMG_FMT_RESERVED_353', + 354: 'IMG_FMT_RESERVED_354', + 355: 'IMG_FMT_RESERVED_355', + 356: 'IMG_FMT_RESERVED_356', + 357: 'IMG_FMT_RESERVED_357', + 358: 'IMG_FMT_RESERVED_358', + 359: 'IMG_FMT_RESERVED_359', + 360: 'IMG_FMT_RESERVED_360', + 361: 'IMG_FMT_RESERVED_361', + 362: 'IMG_FMT_RESERVED_362', + 363: 'IMG_FMT_RESERVED_363', + 364: 'IMG_FMT_RESERVED_364', + 365: 'IMG_FMT_RESERVED_365', + 366: 'IMG_FMT_RESERVED_366', + 367: 'IMG_FMT_RESERVED_367', + 368: 'IMG_FMT_RESERVED_368', + 369: 'IMG_FMT_RESERVED_369', + 370: 'IMG_FMT_RESERVED_370', + 371: 'IMG_FMT_RESERVED_371', + 372: 'IMG_FMT_RESERVED_372', + 373: 'IMG_FMT_RESERVED_373', + 374: 'IMG_FMT_RESERVED_374', + 375: 'IMG_FMT_RESERVED_375', + 376: 'IMG_FMT_RESERVED_376', + 377: 'IMG_FMT_RESERVED_377', + 378: 'IMG_FMT_RESERVED_378', + 379: 'IMG_FMT_RESERVED_379', + 380: 'IMG_FMT_RESERVED_380', + 381: 'IMG_FMT_RESERVED_381', + 382: 'IMG_FMT_RESERVED_382', + 383: 'IMG_FMT_RESERVED_383', + 384: 'IMG_FMT_RESERVED_384', + 385: 'IMG_FMT_RESERVED_385', + 386: 'IMG_FMT_RESERVED_386', + 387: 'IMG_FMT_RESERVED_387', + 388: 'IMG_FMT_RESERVED_388', + 389: 'IMG_FMT_RESERVED_389', + 390: 'IMG_FMT_RESERVED_390', + 391: 'IMG_FMT_RESERVED_391', + 392: 'IMG_FMT_RESERVED_392', + 393: 'IMG_FMT_RESERVED_393', + 394: 'IMG_FMT_RESERVED_394', + 395: 'IMG_FMT_RESERVED_395', + 396: 'IMG_FMT_RESERVED_396', + 397: 'IMG_FMT_RESERVED_397', + 398: 'IMG_FMT_RESERVED_398', + 399: 'IMG_FMT_RESERVED_399', + 400: 'IMG_FMT_RESERVED_400', + 401: 'IMG_FMT_RESERVED_401', + 402: 'IMG_FMT_RESERVED_402', + 403: 'IMG_FMT_RESERVED_403', + 404: 'IMG_FMT_RESERVED_404', + 405: 'IMG_FMT_RESERVED_405', + 406: 'IMG_FMT_RESERVED_406', + 407: 'IMG_FMT_RESERVED_407', + 408: 'IMG_FMT_RESERVED_408', + 409: 'IMG_FMT_RESERVED_409', + 410: 'IMG_FMT_RESERVED_410', + 411: 'IMG_FMT_RESERVED_411', + 412: 'IMG_FMT_RESERVED_412', + 413: 'IMG_FMT_RESERVED_413', + 414: 'IMG_FMT_RESERVED_414', + 415: 'IMG_FMT_RESERVED_415', + 416: 'IMG_FMT_RESERVED_416', + 417: 'IMG_FMT_RESERVED_417', + 418: 'IMG_FMT_RESERVED_418', + 419: 'IMG_FMT_RESERVED_419', + 420: 'IMG_FMT_RESERVED_420', + 421: 'IMG_FMT_RESERVED_421', + 422: 'IMG_FMT_RESERVED_422', + 423: 'IMG_FMT_RESERVED_423', + 424: 'IMG_FMT_RESERVED_424', + 425: 'IMG_FMT_RESERVED_425', + 426: 'IMG_FMT_RESERVED_426', + 427: 'IMG_FMT_RESERVED_427', + 428: 'IMG_FMT_RESERVED_428', + 429: 'IMG_FMT_RESERVED_429', + 430: 'IMG_FMT_RESERVED_430', + 431: 'IMG_FMT_RESERVED_431', + 432: 'IMG_FMT_RESERVED_432', + 433: 'IMG_FMT_RESERVED_433', + 434: 'IMG_FMT_RESERVED_434', + 435: 'IMG_FMT_RESERVED_435', + 436: 'IMG_FMT_RESERVED_436', + 437: 'IMG_FMT_RESERVED_437', + 438: 'IMG_FMT_RESERVED_438', + 439: 'IMG_FMT_RESERVED_439', + 440: 'IMG_FMT_RESERVED_440', + 441: 'IMG_FMT_RESERVED_441', + 442: 'IMG_FMT_RESERVED_442', + 443: 'IMG_FMT_RESERVED_443', + 444: 'IMG_FMT_RESERVED_444', + 445: 'IMG_FMT_RESERVED_445', + 446: 'IMG_FMT_RESERVED_446', + 447: 'IMG_FMT_RESERVED_447', + 448: 'IMG_FMT_RESERVED_448', + 449: 'IMG_FMT_RESERVED_449', + 450: 'IMG_FMT_RESERVED_450', + 451: 'IMG_FMT_RESERVED_451', + 452: 'IMG_FMT_RESERVED_452', + 453: 'IMG_FMT_RESERVED_453', + 454: 'IMG_FMT_RESERVED_454', + 455: 'IMG_FMT_RESERVED_455', + 456: 'IMG_FMT_RESERVED_456', + 457: 'IMG_FMT_RESERVED_457', + 458: 'IMG_FMT_RESERVED_458', + 459: 'IMG_FMT_RESERVED_459', + 460: 'IMG_FMT_RESERVED_460', + 461: 'IMG_FMT_RESERVED_461', + 462: 'IMG_FMT_RESERVED_462', + 463: 'IMG_FMT_RESERVED_463', + 464: 'IMG_FMT_RESERVED_464', + 465: 'IMG_FMT_RESERVED_465', + 466: 'IMG_FMT_RESERVED_466', + 467: 'IMG_FMT_RESERVED_467', + 468: 'IMG_FMT_RESERVED_468', + 469: 'IMG_FMT_RESERVED_469', + 470: 'IMG_FMT_RESERVED_470', + 471: 'IMG_FMT_RESERVED_471', + 472: 'IMG_FMT_RESERVED_472', + 473: 'IMG_FMT_RESERVED_473', + 474: 'IMG_FMT_RESERVED_474', + 475: 'IMG_FMT_RESERVED_475', + 476: 'IMG_FMT_RESERVED_476', + 477: 'IMG_FMT_RESERVED_477', + 478: 'IMG_FMT_RESERVED_478', + 479: 'IMG_FMT_RESERVED_479', + 480: 'IMG_FMT_RESERVED_480', + 481: 'IMG_FMT_RESERVED_481', + 482: 'IMG_FMT_RESERVED_482', + 483: 'IMG_FMT_RESERVED_483', + 484: 'IMG_FMT_RESERVED_484', + 485: 'IMG_FMT_RESERVED_485', + 486: 'IMG_FMT_RESERVED_486', + 487: 'IMG_FMT_RESERVED_487', + 488: 'IMG_FMT_RESERVED_488', + 489: 'IMG_FMT_RESERVED_489', + 490: 'IMG_FMT_RESERVED_490', + 491: 'IMG_FMT_RESERVED_491', + 492: 'IMG_FMT_RESERVED_492', + 493: 'IMG_FMT_RESERVED_493', + 494: 'IMG_FMT_RESERVED_494', + 495: 'IMG_FMT_RESERVED_495', + 496: 'IMG_FMT_RESERVED_496', + 497: 'IMG_FMT_RESERVED_497', + 498: 'IMG_FMT_RESERVED_498', + 499: 'IMG_FMT_RESERVED_499', + 500: 'IMG_FMT_RESERVED_500', + 501: 'IMG_FMT_RESERVED_501', + 502: 'IMG_FMT_RESERVED_502', + 503: 'IMG_FMT_RESERVED_503', + 504: 'IMG_FMT_RESERVED_504', + 505: 'IMG_FMT_RESERVED_505', + 506: 'IMG_FMT_RESERVED_506', + 507: 'IMG_FMT_RESERVED_507', + 508: 'IMG_FMT_RESERVED_508', + 509: 'IMG_FMT_RESERVED_509', + 510: 'IMG_FMT_RESERVED_510', + 511: 'IMG_FMT_RESERVED_511', +} +IMG_FMT_INVALID = 0 +IMG_FMT_8_UNORM = 1 +IMG_FMT_8_SNORM = 2 +IMG_FMT_8_USCALED = 3 +IMG_FMT_8_SSCALED = 4 +IMG_FMT_8_UINT = 5 +IMG_FMT_8_SINT = 6 +IMG_FMT_16_UNORM = 7 +IMG_FMT_16_SNORM = 8 +IMG_FMT_16_USCALED = 9 +IMG_FMT_16_SSCALED = 10 +IMG_FMT_16_UINT = 11 +IMG_FMT_16_SINT = 12 +IMG_FMT_16_FLOAT = 13 +IMG_FMT_8_8_UNORM = 14 +IMG_FMT_8_8_SNORM = 15 +IMG_FMT_8_8_USCALED = 16 +IMG_FMT_8_8_SSCALED = 17 +IMG_FMT_8_8_UINT = 18 +IMG_FMT_8_8_SINT = 19 +IMG_FMT_32_UINT = 20 +IMG_FMT_32_SINT = 21 +IMG_FMT_32_FLOAT = 22 +IMG_FMT_16_16_UNORM = 23 +IMG_FMT_16_16_SNORM = 24 +IMG_FMT_16_16_USCALED = 25 +IMG_FMT_16_16_SSCALED = 26 +IMG_FMT_16_16_UINT = 27 +IMG_FMT_16_16_SINT = 28 +IMG_FMT_16_16_FLOAT = 29 +IMG_FMT_10_11_11_UNORM = 30 +IMG_FMT_10_11_11_SNORM = 31 +IMG_FMT_10_11_11_USCALED = 32 +IMG_FMT_10_11_11_SSCALED = 33 +IMG_FMT_10_11_11_UINT = 34 +IMG_FMT_10_11_11_SINT = 35 +IMG_FMT_10_11_11_FLOAT = 36 +IMG_FMT_11_11_10_UNORM = 37 +IMG_FMT_11_11_10_SNORM = 38 +IMG_FMT_11_11_10_USCALED = 39 +IMG_FMT_11_11_10_SSCALED = 40 +IMG_FMT_11_11_10_UINT = 41 +IMG_FMT_11_11_10_SINT = 42 +IMG_FMT_11_11_10_FLOAT = 43 +IMG_FMT_10_10_10_2_UNORM = 44 +IMG_FMT_10_10_10_2_SNORM = 45 +IMG_FMT_10_10_10_2_USCALED = 46 +IMG_FMT_10_10_10_2_SSCALED = 47 +IMG_FMT_10_10_10_2_UINT = 48 +IMG_FMT_10_10_10_2_SINT = 49 +IMG_FMT_2_10_10_10_UNORM = 50 +IMG_FMT_2_10_10_10_SNORM = 51 +IMG_FMT_2_10_10_10_USCALED = 52 +IMG_FMT_2_10_10_10_SSCALED = 53 +IMG_FMT_2_10_10_10_UINT = 54 +IMG_FMT_2_10_10_10_SINT = 55 +IMG_FMT_8_8_8_8_UNORM = 56 +IMG_FMT_8_8_8_8_SNORM = 57 +IMG_FMT_8_8_8_8_USCALED = 58 +IMG_FMT_8_8_8_8_SSCALED = 59 +IMG_FMT_8_8_8_8_UINT = 60 +IMG_FMT_8_8_8_8_SINT = 61 +IMG_FMT_32_32_UINT = 62 +IMG_FMT_32_32_SINT = 63 +IMG_FMT_32_32_FLOAT = 64 +IMG_FMT_16_16_16_16_UNORM = 65 +IMG_FMT_16_16_16_16_SNORM = 66 +IMG_FMT_16_16_16_16_USCALED = 67 +IMG_FMT_16_16_16_16_SSCALED = 68 +IMG_FMT_16_16_16_16_UINT = 69 +IMG_FMT_16_16_16_16_SINT = 70 +IMG_FMT_16_16_16_16_FLOAT = 71 +IMG_FMT_32_32_32_UINT = 72 +IMG_FMT_32_32_32_SINT = 73 +IMG_FMT_32_32_32_FLOAT = 74 +IMG_FMT_32_32_32_32_UINT = 75 +IMG_FMT_32_32_32_32_SINT = 76 +IMG_FMT_32_32_32_32_FLOAT = 77 +IMG_FMT_RESERVED_78 = 78 +IMG_FMT_RESERVED_79 = 79 +IMG_FMT_RESERVED_80 = 80 +IMG_FMT_RESERVED_81 = 81 +IMG_FMT_RESERVED_82 = 82 +IMG_FMT_RESERVED_83 = 83 +IMG_FMT_RESERVED_84 = 84 +IMG_FMT_RESERVED_85 = 85 +IMG_FMT_RESERVED_86 = 86 +IMG_FMT_RESERVED_87 = 87 +IMG_FMT_RESERVED_88 = 88 +IMG_FMT_RESERVED_89 = 89 +IMG_FMT_RESERVED_90 = 90 +IMG_FMT_RESERVED_91 = 91 +IMG_FMT_RESERVED_92 = 92 +IMG_FMT_RESERVED_93 = 93 +IMG_FMT_RESERVED_94 = 94 +IMG_FMT_RESERVED_95 = 95 +IMG_FMT_RESERVED_96 = 96 +IMG_FMT_RESERVED_97 = 97 +IMG_FMT_RESERVED_98 = 98 +IMG_FMT_RESERVED_99 = 99 +IMG_FMT_RESERVED_100 = 100 +IMG_FMT_RESERVED_101 = 101 +IMG_FMT_RESERVED_102 = 102 +IMG_FMT_RESERVED_103 = 103 +IMG_FMT_RESERVED_104 = 104 +IMG_FMT_RESERVED_105 = 105 +IMG_FMT_RESERVED_106 = 106 +IMG_FMT_RESERVED_107 = 107 +IMG_FMT_RESERVED_108 = 108 +IMG_FMT_RESERVED_109 = 109 +IMG_FMT_RESERVED_110 = 110 +IMG_FMT_RESERVED_111 = 111 +IMG_FMT_RESERVED_112 = 112 +IMG_FMT_RESERVED_113 = 113 +IMG_FMT_RESERVED_114 = 114 +IMG_FMT_RESERVED_115 = 115 +IMG_FMT_RESERVED_116 = 116 +IMG_FMT_RESERVED_117 = 117 +IMG_FMT_RESERVED_118 = 118 +IMG_FMT_RESERVED_119 = 119 +IMG_FMT_RESERVED_120 = 120 +IMG_FMT_RESERVED_121 = 121 +IMG_FMT_RESERVED_122 = 122 +IMG_FMT_RESERVED_123 = 123 +IMG_FMT_RESERVED_124 = 124 +IMG_FMT_RESERVED_125 = 125 +IMG_FMT_RESERVED_126 = 126 +IMG_FMT_RESERVED_127 = 127 +IMG_FMT_8_SRGB = 128 +IMG_FMT_8_8_SRGB = 129 +IMG_FMT_8_8_8_8_SRGB = 130 +IMG_FMT_6E4_FLOAT = 131 +IMG_FMT_5_9_9_9_FLOAT = 132 +IMG_FMT_5_6_5_UNORM = 133 +IMG_FMT_1_5_5_5_UNORM = 134 +IMG_FMT_5_5_5_1_UNORM = 135 +IMG_FMT_4_4_4_4_UNORM = 136 +IMG_FMT_4_4_UNORM = 137 +IMG_FMT_1_UNORM = 138 +IMG_FMT_1_REVERSED_UNORM = 139 +IMG_FMT_32_FLOAT_CLAMP = 140 +IMG_FMT_8_24_UNORM = 141 +IMG_FMT_8_24_UINT = 142 +IMG_FMT_24_8_UNORM = 143 +IMG_FMT_24_8_UINT = 144 +IMG_FMT_X24_8_32_UINT = 145 +IMG_FMT_X24_8_32_FLOAT = 146 +IMG_FMT_GB_GR_UNORM = 147 +IMG_FMT_GB_GR_SNORM = 148 +IMG_FMT_GB_GR_UINT = 149 +IMG_FMT_GB_GR_SRGB = 150 +IMG_FMT_BG_RG_UNORM = 151 +IMG_FMT_BG_RG_SNORM = 152 +IMG_FMT_BG_RG_UINT = 153 +IMG_FMT_BG_RG_SRGB = 154 +IMG_FMT_RESERVED_155 = 155 +IMG_FMT_FMASK8_S2_F1 = 156 +IMG_FMT_FMASK8_S4_F1 = 157 +IMG_FMT_FMASK8_S8_F1 = 158 +IMG_FMT_FMASK8_S2_F2 = 159 +IMG_FMT_FMASK8_S4_F2 = 160 +IMG_FMT_FMASK8_S4_F4 = 161 +IMG_FMT_FMASK16_S16_F1 = 162 +IMG_FMT_FMASK16_S8_F2 = 163 +IMG_FMT_FMASK32_S16_F2 = 164 +IMG_FMT_FMASK32_S8_F4 = 165 +IMG_FMT_FMASK32_S8_F8 = 166 +IMG_FMT_FMASK64_S16_F4 = 167 +IMG_FMT_FMASK64_S16_F8 = 168 +IMG_FMT_BC1_UNORM = 169 +IMG_FMT_BC1_SRGB = 170 +IMG_FMT_BC2_UNORM = 171 +IMG_FMT_BC2_SRGB = 172 +IMG_FMT_BC3_UNORM = 173 +IMG_FMT_BC3_SRGB = 174 +IMG_FMT_BC4_UNORM = 175 +IMG_FMT_BC4_SNORM = 176 +IMG_FMT_BC5_UNORM = 177 +IMG_FMT_BC5_SNORM = 178 +IMG_FMT_BC6_UFLOAT = 179 +IMG_FMT_BC6_SFLOAT = 180 +IMG_FMT_BC7_UNORM = 181 +IMG_FMT_BC7_SRGB = 182 +IMG_FMT_MM_8_UNORM = 265 +IMG_FMT_MM_8_UINT = 266 +IMG_FMT_MM_8_8_UNORM = 267 +IMG_FMT_MM_8_8_UINT = 268 +IMG_FMT_MM_8_8_8_8_UNORM = 269 +IMG_FMT_MM_8_8_8_8_UINT = 270 +IMG_FMT_MM_VYUY8_UNORM = 271 +IMG_FMT_MM_VYUY8_UINT = 272 +IMG_FMT_MM_10_11_11_UNORM = 273 +IMG_FMT_MM_10_11_11_UINT = 274 +IMG_FMT_MM_2_10_10_10_UNORM = 275 +IMG_FMT_MM_2_10_10_10_UINT = 276 +IMG_FMT_MM_16_16_16_16_UNORM = 277 +IMG_FMT_MM_16_16_16_16_UINT = 278 +IMG_FMT_MM_10_IN_16_UNORM = 279 +IMG_FMT_MM_10_IN_16_UINT = 280 +IMG_FMT_MM_10_IN_16_16_UNORM = 281 +IMG_FMT_MM_10_IN_16_16_UINT = 282 +IMG_FMT_MM_10_IN_16_16_16_16_UNORM = 283 +IMG_FMT_MM_10_IN_16_16_16_16_UINT = 284 +IMG_FMT_RESERVED_285 = 285 +IMG_FMT_RESERVED_286 = 286 +IMG_FMT_RESERVED_287 = 287 +IMG_FMT_RESERVED_288 = 288 +IMG_FMT_RESERVED_289 = 289 +IMG_FMT_RESERVED_290 = 290 +IMG_FMT_RESERVED_291 = 291 +IMG_FMT_RESERVED_292 = 292 +IMG_FMT_RESERVED_293 = 293 +IMG_FMT_RESERVED_294 = 294 +IMG_FMT_RESERVED_295 = 295 +IMG_FMT_RESERVED_296 = 296 +IMG_FMT_RESERVED_297 = 297 +IMG_FMT_RESERVED_298 = 298 +IMG_FMT_RESERVED_299 = 299 +IMG_FMT_RESERVED_300 = 300 +IMG_FMT_RESERVED_301 = 301 +IMG_FMT_RESERVED_302 = 302 +IMG_FMT_RESERVED_303 = 303 +IMG_FMT_RESERVED_304 = 304 +IMG_FMT_RESERVED_305 = 305 +IMG_FMT_RESERVED_306 = 306 +IMG_FMT_RESERVED_307 = 307 +IMG_FMT_RESERVED_308 = 308 +IMG_FMT_RESERVED_309 = 309 +IMG_FMT_RESERVED_310 = 310 +IMG_FMT_RESERVED_311 = 311 +IMG_FMT_RESERVED_312 = 312 +IMG_FMT_RESERVED_313 = 313 +IMG_FMT_RESERVED_314 = 314 +IMG_FMT_RESERVED_315 = 315 +IMG_FMT_RESERVED_316 = 316 +IMG_FMT_RESERVED_317 = 317 +IMG_FMT_RESERVED_318 = 318 +IMG_FMT_RESERVED_319 = 319 +IMG_FMT_RESERVED_320 = 320 +IMG_FMT_RESERVED_321 = 321 +IMG_FMT_RESERVED_322 = 322 +IMG_FMT_RESERVED_323 = 323 +IMG_FMT_RESERVED_324 = 324 +IMG_FMT_RESERVED_325 = 325 +IMG_FMT_RESERVED_326 = 326 +IMG_FMT_RESERVED_327 = 327 +IMG_FMT_RESERVED_328 = 328 +IMG_FMT_RESERVED_329 = 329 +IMG_FMT_RESERVED_330 = 330 +IMG_FMT_RESERVED_331 = 331 +IMG_FMT_RESERVED_332 = 332 +IMG_FMT_RESERVED_333 = 333 +IMG_FMT_RESERVED_334 = 334 +IMG_FMT_RESERVED_335 = 335 +IMG_FMT_RESERVED_336 = 336 +IMG_FMT_RESERVED_337 = 337 +IMG_FMT_RESERVED_338 = 338 +IMG_FMT_RESERVED_339 = 339 +IMG_FMT_RESERVED_340 = 340 +IMG_FMT_RESERVED_341 = 341 +IMG_FMT_RESERVED_342 = 342 +IMG_FMT_RESERVED_343 = 343 +IMG_FMT_RESERVED_344 = 344 +IMG_FMT_RESERVED_345 = 345 +IMG_FMT_RESERVED_346 = 346 +IMG_FMT_RESERVED_347 = 347 +IMG_FMT_RESERVED_348 = 348 +IMG_FMT_RESERVED_349 = 349 +IMG_FMT_RESERVED_350 = 350 +IMG_FMT_RESERVED_351 = 351 +IMG_FMT_RESERVED_352 = 352 +IMG_FMT_RESERVED_353 = 353 +IMG_FMT_RESERVED_354 = 354 +IMG_FMT_RESERVED_355 = 355 +IMG_FMT_RESERVED_356 = 356 +IMG_FMT_RESERVED_357 = 357 +IMG_FMT_RESERVED_358 = 358 +IMG_FMT_RESERVED_359 = 359 +IMG_FMT_RESERVED_360 = 360 +IMG_FMT_RESERVED_361 = 361 +IMG_FMT_RESERVED_362 = 362 +IMG_FMT_RESERVED_363 = 363 +IMG_FMT_RESERVED_364 = 364 +IMG_FMT_RESERVED_365 = 365 +IMG_FMT_RESERVED_366 = 366 +IMG_FMT_RESERVED_367 = 367 +IMG_FMT_RESERVED_368 = 368 +IMG_FMT_RESERVED_369 = 369 +IMG_FMT_RESERVED_370 = 370 +IMG_FMT_RESERVED_371 = 371 +IMG_FMT_RESERVED_372 = 372 +IMG_FMT_RESERVED_373 = 373 +IMG_FMT_RESERVED_374 = 374 +IMG_FMT_RESERVED_375 = 375 +IMG_FMT_RESERVED_376 = 376 +IMG_FMT_RESERVED_377 = 377 +IMG_FMT_RESERVED_378 = 378 +IMG_FMT_RESERVED_379 = 379 +IMG_FMT_RESERVED_380 = 380 +IMG_FMT_RESERVED_381 = 381 +IMG_FMT_RESERVED_382 = 382 +IMG_FMT_RESERVED_383 = 383 +IMG_FMT_RESERVED_384 = 384 +IMG_FMT_RESERVED_385 = 385 +IMG_FMT_RESERVED_386 = 386 +IMG_FMT_RESERVED_387 = 387 +IMG_FMT_RESERVED_388 = 388 +IMG_FMT_RESERVED_389 = 389 +IMG_FMT_RESERVED_390 = 390 +IMG_FMT_RESERVED_391 = 391 +IMG_FMT_RESERVED_392 = 392 +IMG_FMT_RESERVED_393 = 393 +IMG_FMT_RESERVED_394 = 394 +IMG_FMT_RESERVED_395 = 395 +IMG_FMT_RESERVED_396 = 396 +IMG_FMT_RESERVED_397 = 397 +IMG_FMT_RESERVED_398 = 398 +IMG_FMT_RESERVED_399 = 399 +IMG_FMT_RESERVED_400 = 400 +IMG_FMT_RESERVED_401 = 401 +IMG_FMT_RESERVED_402 = 402 +IMG_FMT_RESERVED_403 = 403 +IMG_FMT_RESERVED_404 = 404 +IMG_FMT_RESERVED_405 = 405 +IMG_FMT_RESERVED_406 = 406 +IMG_FMT_RESERVED_407 = 407 +IMG_FMT_RESERVED_408 = 408 +IMG_FMT_RESERVED_409 = 409 +IMG_FMT_RESERVED_410 = 410 +IMG_FMT_RESERVED_411 = 411 +IMG_FMT_RESERVED_412 = 412 +IMG_FMT_RESERVED_413 = 413 +IMG_FMT_RESERVED_414 = 414 +IMG_FMT_RESERVED_415 = 415 +IMG_FMT_RESERVED_416 = 416 +IMG_FMT_RESERVED_417 = 417 +IMG_FMT_RESERVED_418 = 418 +IMG_FMT_RESERVED_419 = 419 +IMG_FMT_RESERVED_420 = 420 +IMG_FMT_RESERVED_421 = 421 +IMG_FMT_RESERVED_422 = 422 +IMG_FMT_RESERVED_423 = 423 +IMG_FMT_RESERVED_424 = 424 +IMG_FMT_RESERVED_425 = 425 +IMG_FMT_RESERVED_426 = 426 +IMG_FMT_RESERVED_427 = 427 +IMG_FMT_RESERVED_428 = 428 +IMG_FMT_RESERVED_429 = 429 +IMG_FMT_RESERVED_430 = 430 +IMG_FMT_RESERVED_431 = 431 +IMG_FMT_RESERVED_432 = 432 +IMG_FMT_RESERVED_433 = 433 +IMG_FMT_RESERVED_434 = 434 +IMG_FMT_RESERVED_435 = 435 +IMG_FMT_RESERVED_436 = 436 +IMG_FMT_RESERVED_437 = 437 +IMG_FMT_RESERVED_438 = 438 +IMG_FMT_RESERVED_439 = 439 +IMG_FMT_RESERVED_440 = 440 +IMG_FMT_RESERVED_441 = 441 +IMG_FMT_RESERVED_442 = 442 +IMG_FMT_RESERVED_443 = 443 +IMG_FMT_RESERVED_444 = 444 +IMG_FMT_RESERVED_445 = 445 +IMG_FMT_RESERVED_446 = 446 +IMG_FMT_RESERVED_447 = 447 +IMG_FMT_RESERVED_448 = 448 +IMG_FMT_RESERVED_449 = 449 +IMG_FMT_RESERVED_450 = 450 +IMG_FMT_RESERVED_451 = 451 +IMG_FMT_RESERVED_452 = 452 +IMG_FMT_RESERVED_453 = 453 +IMG_FMT_RESERVED_454 = 454 +IMG_FMT_RESERVED_455 = 455 +IMG_FMT_RESERVED_456 = 456 +IMG_FMT_RESERVED_457 = 457 +IMG_FMT_RESERVED_458 = 458 +IMG_FMT_RESERVED_459 = 459 +IMG_FMT_RESERVED_460 = 460 +IMG_FMT_RESERVED_461 = 461 +IMG_FMT_RESERVED_462 = 462 +IMG_FMT_RESERVED_463 = 463 +IMG_FMT_RESERVED_464 = 464 +IMG_FMT_RESERVED_465 = 465 +IMG_FMT_RESERVED_466 = 466 +IMG_FMT_RESERVED_467 = 467 +IMG_FMT_RESERVED_468 = 468 +IMG_FMT_RESERVED_469 = 469 +IMG_FMT_RESERVED_470 = 470 +IMG_FMT_RESERVED_471 = 471 +IMG_FMT_RESERVED_472 = 472 +IMG_FMT_RESERVED_473 = 473 +IMG_FMT_RESERVED_474 = 474 +IMG_FMT_RESERVED_475 = 475 +IMG_FMT_RESERVED_476 = 476 +IMG_FMT_RESERVED_477 = 477 +IMG_FMT_RESERVED_478 = 478 +IMG_FMT_RESERVED_479 = 479 +IMG_FMT_RESERVED_480 = 480 +IMG_FMT_RESERVED_481 = 481 +IMG_FMT_RESERVED_482 = 482 +IMG_FMT_RESERVED_483 = 483 +IMG_FMT_RESERVED_484 = 484 +IMG_FMT_RESERVED_485 = 485 +IMG_FMT_RESERVED_486 = 486 +IMG_FMT_RESERVED_487 = 487 +IMG_FMT_RESERVED_488 = 488 +IMG_FMT_RESERVED_489 = 489 +IMG_FMT_RESERVED_490 = 490 +IMG_FMT_RESERVED_491 = 491 +IMG_FMT_RESERVED_492 = 492 +IMG_FMT_RESERVED_493 = 493 +IMG_FMT_RESERVED_494 = 494 +IMG_FMT_RESERVED_495 = 495 +IMG_FMT_RESERVED_496 = 496 +IMG_FMT_RESERVED_497 = 497 +IMG_FMT_RESERVED_498 = 498 +IMG_FMT_RESERVED_499 = 499 +IMG_FMT_RESERVED_500 = 500 +IMG_FMT_RESERVED_501 = 501 +IMG_FMT_RESERVED_502 = 502 +IMG_FMT_RESERVED_503 = 503 +IMG_FMT_RESERVED_504 = 504 +IMG_FMT_RESERVED_505 = 505 +IMG_FMT_RESERVED_506 = 506 +IMG_FMT_RESERVED_507 = 507 +IMG_FMT_RESERVED_508 = 508 +IMG_FMT_RESERVED_509 = 509 +IMG_FMT_RESERVED_510 = 510 +IMG_FMT_RESERVED_511 = 511 +IMG_FMT = ctypes.c_uint32 # enum + +# values for enumeration 'BUF_DATA_FORMAT' +BUF_DATA_FORMAT__enumvalues = { + 0: 'BUF_DATA_FORMAT_INVALID', + 1: 'BUF_DATA_FORMAT_8', + 2: 'BUF_DATA_FORMAT_16', + 3: 'BUF_DATA_FORMAT_8_8', + 4: 'BUF_DATA_FORMAT_32', + 5: 'BUF_DATA_FORMAT_16_16', + 6: 'BUF_DATA_FORMAT_10_11_11', + 7: 'BUF_DATA_FORMAT_11_11_10', + 8: 'BUF_DATA_FORMAT_10_10_10_2', + 9: 'BUF_DATA_FORMAT_2_10_10_10', + 10: 'BUF_DATA_FORMAT_8_8_8_8', + 11: 'BUF_DATA_FORMAT_32_32', + 12: 'BUF_DATA_FORMAT_16_16_16_16', + 13: 'BUF_DATA_FORMAT_32_32_32', + 14: 'BUF_DATA_FORMAT_32_32_32_32', + 15: 'BUF_DATA_FORMAT_RESERVED_15', +} +BUF_DATA_FORMAT_INVALID = 0 +BUF_DATA_FORMAT_8 = 1 +BUF_DATA_FORMAT_16 = 2 +BUF_DATA_FORMAT_8_8 = 3 +BUF_DATA_FORMAT_32 = 4 +BUF_DATA_FORMAT_16_16 = 5 +BUF_DATA_FORMAT_10_11_11 = 6 +BUF_DATA_FORMAT_11_11_10 = 7 +BUF_DATA_FORMAT_10_10_10_2 = 8 +BUF_DATA_FORMAT_2_10_10_10 = 9 +BUF_DATA_FORMAT_8_8_8_8 = 10 +BUF_DATA_FORMAT_32_32 = 11 +BUF_DATA_FORMAT_16_16_16_16 = 12 +BUF_DATA_FORMAT_32_32_32 = 13 +BUF_DATA_FORMAT_32_32_32_32 = 14 +BUF_DATA_FORMAT_RESERVED_15 = 15 +BUF_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_DATA_FORMAT' +IMG_DATA_FORMAT__enumvalues = { + 0: 'IMG_DATA_FORMAT_INVALID', + 1: 'IMG_DATA_FORMAT_8', + 2: 'IMG_DATA_FORMAT_16', + 3: 'IMG_DATA_FORMAT_8_8', + 4: 'IMG_DATA_FORMAT_32', + 5: 'IMG_DATA_FORMAT_16_16', + 6: 'IMG_DATA_FORMAT_10_11_11', + 7: 'IMG_DATA_FORMAT_11_11_10', + 8: 'IMG_DATA_FORMAT_10_10_10_2', + 9: 'IMG_DATA_FORMAT_2_10_10_10', + 10: 'IMG_DATA_FORMAT_8_8_8_8', + 11: 'IMG_DATA_FORMAT_32_32', + 12: 'IMG_DATA_FORMAT_16_16_16_16', + 13: 'IMG_DATA_FORMAT_32_32_32', + 14: 'IMG_DATA_FORMAT_32_32_32_32', + 15: 'IMG_DATA_FORMAT_RESERVED_15', + 16: 'IMG_DATA_FORMAT_5_6_5', + 17: 'IMG_DATA_FORMAT_1_5_5_5', + 18: 'IMG_DATA_FORMAT_5_5_5_1', + 19: 'IMG_DATA_FORMAT_4_4_4_4', + 20: 'IMG_DATA_FORMAT_8_24', + 21: 'IMG_DATA_FORMAT_24_8', + 22: 'IMG_DATA_FORMAT_X24_8_32', + 23: 'IMG_DATA_FORMAT_RESERVED_23', + 24: 'IMG_DATA_FORMAT_RESERVED_24', + 25: 'IMG_DATA_FORMAT_RESERVED_25', + 26: 'IMG_DATA_FORMAT_RESERVED_26', + 27: 'IMG_DATA_FORMAT_RESERVED_27', + 28: 'IMG_DATA_FORMAT_RESERVED_28', + 29: 'IMG_DATA_FORMAT_RESERVED_29', + 30: 'IMG_DATA_FORMAT_RESERVED_30', + 31: 'IMG_DATA_FORMAT_6E4', + 32: 'IMG_DATA_FORMAT_GB_GR', + 33: 'IMG_DATA_FORMAT_BG_RG', + 34: 'IMG_DATA_FORMAT_5_9_9_9', + 35: 'IMG_DATA_FORMAT_BC1', + 36: 'IMG_DATA_FORMAT_BC2', + 37: 'IMG_DATA_FORMAT_BC3', + 38: 'IMG_DATA_FORMAT_BC4', + 39: 'IMG_DATA_FORMAT_BC5', + 40: 'IMG_DATA_FORMAT_BC6', + 41: 'IMG_DATA_FORMAT_BC7', + 42: 'IMG_DATA_FORMAT_RESERVED_42', + 43: 'IMG_DATA_FORMAT_RESERVED_43', + 44: 'IMG_DATA_FORMAT_FMASK8_S2_F1', + 45: 'IMG_DATA_FORMAT_FMASK8_S4_F1', + 46: 'IMG_DATA_FORMAT_FMASK8_S8_F1', + 47: 'IMG_DATA_FORMAT_FMASK8_S2_F2', + 48: 'IMG_DATA_FORMAT_FMASK8_S4_F2', + 49: 'IMG_DATA_FORMAT_FMASK8_S4_F4', + 50: 'IMG_DATA_FORMAT_FMASK16_S16_F1', + 51: 'IMG_DATA_FORMAT_FMASK16_S8_F2', + 52: 'IMG_DATA_FORMAT_FMASK32_S16_F2', + 53: 'IMG_DATA_FORMAT_FMASK32_S8_F4', + 54: 'IMG_DATA_FORMAT_FMASK32_S8_F8', + 55: 'IMG_DATA_FORMAT_FMASK64_S16_F4', + 56: 'IMG_DATA_FORMAT_FMASK64_S16_F8', + 57: 'IMG_DATA_FORMAT_4_4', + 58: 'IMG_DATA_FORMAT_6_5_5', + 59: 'IMG_DATA_FORMAT_1', + 60: 'IMG_DATA_FORMAT_1_REVERSED', + 61: 'IMG_DATA_FORMAT_RESERVED_61', + 62: 'IMG_DATA_FORMAT_RESERVED_62', + 63: 'IMG_DATA_FORMAT_32_AS_32_32_32_32', + 75: 'IMG_DATA_FORMAT_RESERVED_75', + 76: 'IMG_DATA_FORMAT_MM_8', + 77: 'IMG_DATA_FORMAT_MM_8_8', + 78: 'IMG_DATA_FORMAT_MM_8_8_8_8', + 79: 'IMG_DATA_FORMAT_MM_VYUY8', + 80: 'IMG_DATA_FORMAT_MM_10_11_11', + 81: 'IMG_DATA_FORMAT_MM_2_10_10_10', + 82: 'IMG_DATA_FORMAT_MM_16_16_16_16', + 83: 'IMG_DATA_FORMAT_MM_10_IN_16', + 84: 'IMG_DATA_FORMAT_MM_10_IN_16_16', + 85: 'IMG_DATA_FORMAT_MM_10_IN_16_16_16_16', + 86: 'IMG_DATA_FORMAT_RESERVED_86', + 87: 'IMG_DATA_FORMAT_RESERVED_87', + 88: 'IMG_DATA_FORMAT_RESERVED_88', + 89: 'IMG_DATA_FORMAT_RESERVED_89', + 90: 'IMG_DATA_FORMAT_RESERVED_90', + 91: 'IMG_DATA_FORMAT_RESERVED_91', + 92: 'IMG_DATA_FORMAT_RESERVED_92', + 93: 'IMG_DATA_FORMAT_RESERVED_93', + 94: 'IMG_DATA_FORMAT_RESERVED_94', + 95: 'IMG_DATA_FORMAT_RESERVED_95', + 96: 'IMG_DATA_FORMAT_RESERVED_96', + 97: 'IMG_DATA_FORMAT_RESERVED_97', + 98: 'IMG_DATA_FORMAT_RESERVED_98', + 99: 'IMG_DATA_FORMAT_RESERVED_99', + 100: 'IMG_DATA_FORMAT_RESERVED_100', + 101: 'IMG_DATA_FORMAT_RESERVED_101', + 102: 'IMG_DATA_FORMAT_RESERVED_102', + 103: 'IMG_DATA_FORMAT_RESERVED_103', + 104: 'IMG_DATA_FORMAT_RESERVED_104', + 105: 'IMG_DATA_FORMAT_RESERVED_105', + 106: 'IMG_DATA_FORMAT_RESERVED_106', + 107: 'IMG_DATA_FORMAT_RESERVED_107', + 108: 'IMG_DATA_FORMAT_RESERVED_108', + 109: 'IMG_DATA_FORMAT_RESERVED_109', + 110: 'IMG_DATA_FORMAT_RESERVED_110', + 111: 'IMG_DATA_FORMAT_RESERVED_111', + 112: 'IMG_DATA_FORMAT_RESERVED_112', + 113: 'IMG_DATA_FORMAT_RESERVED_113', + 114: 'IMG_DATA_FORMAT_RESERVED_114', + 115: 'IMG_DATA_FORMAT_RESERVED_115', + 116: 'IMG_DATA_FORMAT_RESERVED_116', + 117: 'IMG_DATA_FORMAT_RESERVED_117', + 118: 'IMG_DATA_FORMAT_RESERVED_118', + 119: 'IMG_DATA_FORMAT_RESERVED_119', + 120: 'IMG_DATA_FORMAT_RESERVED_120', + 121: 'IMG_DATA_FORMAT_RESERVED_121', + 122: 'IMG_DATA_FORMAT_RESERVED_122', + 123: 'IMG_DATA_FORMAT_RESERVED_123', + 124: 'IMG_DATA_FORMAT_RESERVED_124', + 125: 'IMG_DATA_FORMAT_RESERVED_125', + 126: 'IMG_DATA_FORMAT_RESERVED_126', + 127: 'IMG_DATA_FORMAT_RESERVED_127', +} +IMG_DATA_FORMAT_INVALID = 0 +IMG_DATA_FORMAT_8 = 1 +IMG_DATA_FORMAT_16 = 2 +IMG_DATA_FORMAT_8_8 = 3 +IMG_DATA_FORMAT_32 = 4 +IMG_DATA_FORMAT_16_16 = 5 +IMG_DATA_FORMAT_10_11_11 = 6 +IMG_DATA_FORMAT_11_11_10 = 7 +IMG_DATA_FORMAT_10_10_10_2 = 8 +IMG_DATA_FORMAT_2_10_10_10 = 9 +IMG_DATA_FORMAT_8_8_8_8 = 10 +IMG_DATA_FORMAT_32_32 = 11 +IMG_DATA_FORMAT_16_16_16_16 = 12 +IMG_DATA_FORMAT_32_32_32 = 13 +IMG_DATA_FORMAT_32_32_32_32 = 14 +IMG_DATA_FORMAT_RESERVED_15 = 15 +IMG_DATA_FORMAT_5_6_5 = 16 +IMG_DATA_FORMAT_1_5_5_5 = 17 +IMG_DATA_FORMAT_5_5_5_1 = 18 +IMG_DATA_FORMAT_4_4_4_4 = 19 +IMG_DATA_FORMAT_8_24 = 20 +IMG_DATA_FORMAT_24_8 = 21 +IMG_DATA_FORMAT_X24_8_32 = 22 +IMG_DATA_FORMAT_RESERVED_23 = 23 +IMG_DATA_FORMAT_RESERVED_24 = 24 +IMG_DATA_FORMAT_RESERVED_25 = 25 +IMG_DATA_FORMAT_RESERVED_26 = 26 +IMG_DATA_FORMAT_RESERVED_27 = 27 +IMG_DATA_FORMAT_RESERVED_28 = 28 +IMG_DATA_FORMAT_RESERVED_29 = 29 +IMG_DATA_FORMAT_RESERVED_30 = 30 +IMG_DATA_FORMAT_6E4 = 31 +IMG_DATA_FORMAT_GB_GR = 32 +IMG_DATA_FORMAT_BG_RG = 33 +IMG_DATA_FORMAT_5_9_9_9 = 34 +IMG_DATA_FORMAT_BC1 = 35 +IMG_DATA_FORMAT_BC2 = 36 +IMG_DATA_FORMAT_BC3 = 37 +IMG_DATA_FORMAT_BC4 = 38 +IMG_DATA_FORMAT_BC5 = 39 +IMG_DATA_FORMAT_BC6 = 40 +IMG_DATA_FORMAT_BC7 = 41 +IMG_DATA_FORMAT_RESERVED_42 = 42 +IMG_DATA_FORMAT_RESERVED_43 = 43 +IMG_DATA_FORMAT_FMASK8_S2_F1 = 44 +IMG_DATA_FORMAT_FMASK8_S4_F1 = 45 +IMG_DATA_FORMAT_FMASK8_S8_F1 = 46 +IMG_DATA_FORMAT_FMASK8_S2_F2 = 47 +IMG_DATA_FORMAT_FMASK8_S4_F2 = 48 +IMG_DATA_FORMAT_FMASK8_S4_F4 = 49 +IMG_DATA_FORMAT_FMASK16_S16_F1 = 50 +IMG_DATA_FORMAT_FMASK16_S8_F2 = 51 +IMG_DATA_FORMAT_FMASK32_S16_F2 = 52 +IMG_DATA_FORMAT_FMASK32_S8_F4 = 53 +IMG_DATA_FORMAT_FMASK32_S8_F8 = 54 +IMG_DATA_FORMAT_FMASK64_S16_F4 = 55 +IMG_DATA_FORMAT_FMASK64_S16_F8 = 56 +IMG_DATA_FORMAT_4_4 = 57 +IMG_DATA_FORMAT_6_5_5 = 58 +IMG_DATA_FORMAT_1 = 59 +IMG_DATA_FORMAT_1_REVERSED = 60 +IMG_DATA_FORMAT_RESERVED_61 = 61 +IMG_DATA_FORMAT_RESERVED_62 = 62 +IMG_DATA_FORMAT_32_AS_32_32_32_32 = 63 +IMG_DATA_FORMAT_RESERVED_75 = 75 +IMG_DATA_FORMAT_MM_8 = 76 +IMG_DATA_FORMAT_MM_8_8 = 77 +IMG_DATA_FORMAT_MM_8_8_8_8 = 78 +IMG_DATA_FORMAT_MM_VYUY8 = 79 +IMG_DATA_FORMAT_MM_10_11_11 = 80 +IMG_DATA_FORMAT_MM_2_10_10_10 = 81 +IMG_DATA_FORMAT_MM_16_16_16_16 = 82 +IMG_DATA_FORMAT_MM_10_IN_16 = 83 +IMG_DATA_FORMAT_MM_10_IN_16_16 = 84 +IMG_DATA_FORMAT_MM_10_IN_16_16_16_16 = 85 +IMG_DATA_FORMAT_RESERVED_86 = 86 +IMG_DATA_FORMAT_RESERVED_87 = 87 +IMG_DATA_FORMAT_RESERVED_88 = 88 +IMG_DATA_FORMAT_RESERVED_89 = 89 +IMG_DATA_FORMAT_RESERVED_90 = 90 +IMG_DATA_FORMAT_RESERVED_91 = 91 +IMG_DATA_FORMAT_RESERVED_92 = 92 +IMG_DATA_FORMAT_RESERVED_93 = 93 +IMG_DATA_FORMAT_RESERVED_94 = 94 +IMG_DATA_FORMAT_RESERVED_95 = 95 +IMG_DATA_FORMAT_RESERVED_96 = 96 +IMG_DATA_FORMAT_RESERVED_97 = 97 +IMG_DATA_FORMAT_RESERVED_98 = 98 +IMG_DATA_FORMAT_RESERVED_99 = 99 +IMG_DATA_FORMAT_RESERVED_100 = 100 +IMG_DATA_FORMAT_RESERVED_101 = 101 +IMG_DATA_FORMAT_RESERVED_102 = 102 +IMG_DATA_FORMAT_RESERVED_103 = 103 +IMG_DATA_FORMAT_RESERVED_104 = 104 +IMG_DATA_FORMAT_RESERVED_105 = 105 +IMG_DATA_FORMAT_RESERVED_106 = 106 +IMG_DATA_FORMAT_RESERVED_107 = 107 +IMG_DATA_FORMAT_RESERVED_108 = 108 +IMG_DATA_FORMAT_RESERVED_109 = 109 +IMG_DATA_FORMAT_RESERVED_110 = 110 +IMG_DATA_FORMAT_RESERVED_111 = 111 +IMG_DATA_FORMAT_RESERVED_112 = 112 +IMG_DATA_FORMAT_RESERVED_113 = 113 +IMG_DATA_FORMAT_RESERVED_114 = 114 +IMG_DATA_FORMAT_RESERVED_115 = 115 +IMG_DATA_FORMAT_RESERVED_116 = 116 +IMG_DATA_FORMAT_RESERVED_117 = 117 +IMG_DATA_FORMAT_RESERVED_118 = 118 +IMG_DATA_FORMAT_RESERVED_119 = 119 +IMG_DATA_FORMAT_RESERVED_120 = 120 +IMG_DATA_FORMAT_RESERVED_121 = 121 +IMG_DATA_FORMAT_RESERVED_122 = 122 +IMG_DATA_FORMAT_RESERVED_123 = 123 +IMG_DATA_FORMAT_RESERVED_124 = 124 +IMG_DATA_FORMAT_RESERVED_125 = 125 +IMG_DATA_FORMAT_RESERVED_126 = 126 +IMG_DATA_FORMAT_RESERVED_127 = 127 +IMG_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'BUF_NUM_FORMAT' +BUF_NUM_FORMAT__enumvalues = { + 0: 'BUF_NUM_FORMAT_UNORM', + 1: 'BUF_NUM_FORMAT_SNORM', + 2: 'BUF_NUM_FORMAT_USCALED', + 3: 'BUF_NUM_FORMAT_SSCALED', + 4: 'BUF_NUM_FORMAT_UINT', + 5: 'BUF_NUM_FORMAT_SINT', + 6: 'BUF_NUM_FORMAT_SNORM_NZ', + 7: 'BUF_NUM_FORMAT_FLOAT', +} +BUF_NUM_FORMAT_UNORM = 0 +BUF_NUM_FORMAT_SNORM = 1 +BUF_NUM_FORMAT_USCALED = 2 +BUF_NUM_FORMAT_SSCALED = 3 +BUF_NUM_FORMAT_UINT = 4 +BUF_NUM_FORMAT_SINT = 5 +BUF_NUM_FORMAT_SNORM_NZ = 6 +BUF_NUM_FORMAT_FLOAT = 7 +BUF_NUM_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT' +IMG_NUM_FORMAT__enumvalues = { + 0: 'IMG_NUM_FORMAT_UNORM', + 1: 'IMG_NUM_FORMAT_SNORM', + 2: 'IMG_NUM_FORMAT_USCALED', + 3: 'IMG_NUM_FORMAT_SSCALED', + 4: 'IMG_NUM_FORMAT_UINT', + 5: 'IMG_NUM_FORMAT_SINT', + 6: 'IMG_NUM_FORMAT_SNORM_NZ', + 7: 'IMG_NUM_FORMAT_FLOAT', + 8: 'IMG_NUM_FORMAT_RESERVED_8', + 9: 'IMG_NUM_FORMAT_SRGB', + 10: 'IMG_NUM_FORMAT_UBNORM', + 11: 'IMG_NUM_FORMAT_UBNORM_NZ', + 12: 'IMG_NUM_FORMAT_UBINT', + 13: 'IMG_NUM_FORMAT_UBSCALED', + 14: 'IMG_NUM_FORMAT_RESERVED_14', + 15: 'IMG_NUM_FORMAT_RESERVED_15', +} +IMG_NUM_FORMAT_UNORM = 0 +IMG_NUM_FORMAT_SNORM = 1 +IMG_NUM_FORMAT_USCALED = 2 +IMG_NUM_FORMAT_SSCALED = 3 +IMG_NUM_FORMAT_UINT = 4 +IMG_NUM_FORMAT_SINT = 5 +IMG_NUM_FORMAT_SNORM_NZ = 6 +IMG_NUM_FORMAT_FLOAT = 7 +IMG_NUM_FORMAT_RESERVED_8 = 8 +IMG_NUM_FORMAT_SRGB = 9 +IMG_NUM_FORMAT_UBNORM = 10 +IMG_NUM_FORMAT_UBNORM_NZ = 11 +IMG_NUM_FORMAT_UBINT = 12 +IMG_NUM_FORMAT_UBSCALED = 13 +IMG_NUM_FORMAT_RESERVED_14 = 14 +IMG_NUM_FORMAT_RESERVED_15 = 15 +IMG_NUM_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IH_PERF_SEL' +IH_PERF_SEL__enumvalues = { + 0: 'IH_PERF_SEL_CYCLE', + 1: 'IH_PERF_SEL_IDLE', + 2: 'IH_PERF_SEL_INPUT_IDLE', + 3: 'IH_PERF_SEL_BUFFER_IDLE', + 4: 'IH_PERF_SEL_RB0_FULL', + 5: 'IH_PERF_SEL_RB0_OVERFLOW', + 6: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 7: 'IH_PERF_SEL_RB0_WPTR_WRAP', + 8: 'IH_PERF_SEL_RB0_RPTR_WRAP', + 9: 'IH_PERF_SEL_MC_WR_IDLE', + 10: 'IH_PERF_SEL_MC_WR_COUNT', + 11: 'IH_PERF_SEL_MC_WR_STALL', + 12: 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 13: 'IH_PERF_SEL_MC_WR_CLEAN_STALL', + 14: 'IH_PERF_SEL_BIF_LINE0_RISING', + 15: 'IH_PERF_SEL_BIF_LINE0_FALLING', + 16: 'IH_PERF_SEL_RB1_FULL', + 17: 'IH_PERF_SEL_RB1_OVERFLOW', + 18: 'IH_PERF_SEL_COOKIE_REC_ERROR', + 19: 'IH_PERF_SEL_RB1_WPTR_WRAP', + 20: 'IH_PERF_SEL_RB1_RPTR_WRAP', + 21: 'IH_PERF_SEL_RB2_FULL', + 22: 'IH_PERF_SEL_RB2_OVERFLOW', + 23: 'IH_PERF_SEL_CLIENT_CREDIT_ERROR', + 24: 'IH_PERF_SEL_RB2_WPTR_WRAP', + 25: 'IH_PERF_SEL_RB2_RPTR_WRAP', + 26: 'IH_PERF_SEL_STORM_CLIENT_INT_DROP', + 27: 'IH_PERF_SEL_SELF_IV_VALID', + 28: 'IH_PERF_SEL_BUFFER_FIFO_FULL', + 29: 'IH_PERF_SEL_RB0_FULL_VF0', + 30: 'IH_PERF_SEL_RB0_FULL_VF1', + 31: 'IH_PERF_SEL_RB0_FULL_VF2', + 32: 'IH_PERF_SEL_RB0_FULL_VF3', + 33: 'IH_PERF_SEL_RB0_FULL_VF4', + 34: 'IH_PERF_SEL_RB0_FULL_VF5', + 35: 'IH_PERF_SEL_RB0_FULL_VF6', + 36: 'IH_PERF_SEL_RB0_FULL_VF7', + 37: 'IH_PERF_SEL_RB0_FULL_VF8', + 38: 'IH_PERF_SEL_RB0_FULL_VF9', + 39: 'IH_PERF_SEL_RB0_FULL_VF10', + 40: 'IH_PERF_SEL_RB0_FULL_VF11', + 41: 'IH_PERF_SEL_RB0_FULL_VF12', + 42: 'IH_PERF_SEL_RB0_FULL_VF13', + 43: 'IH_PERF_SEL_RB0_FULL_VF14', + 44: 'IH_PERF_SEL_RB0_FULL_VF15', + 45: 'IH_PERF_SEL_RB0_FULL_VF16', + 46: 'IH_PERF_SEL_RB0_FULL_VF17', + 47: 'IH_PERF_SEL_RB0_FULL_VF18', + 48: 'IH_PERF_SEL_RB0_FULL_VF19', + 49: 'IH_PERF_SEL_RB0_FULL_VF20', + 50: 'IH_PERF_SEL_RB0_FULL_VF21', + 51: 'IH_PERF_SEL_RB0_FULL_VF22', + 52: 'IH_PERF_SEL_RB0_FULL_VF23', + 53: 'IH_PERF_SEL_RB0_FULL_VF24', + 54: 'IH_PERF_SEL_RB0_FULL_VF25', + 55: 'IH_PERF_SEL_RB0_FULL_VF26', + 56: 'IH_PERF_SEL_RB0_FULL_VF27', + 57: 'IH_PERF_SEL_RB0_FULL_VF28', + 58: 'IH_PERF_SEL_RB0_FULL_VF29', + 59: 'IH_PERF_SEL_RB0_FULL_VF30', + 60: 'IH_PERF_SEL_RB0_OVERFLOW_VF0', + 61: 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 62: 'IH_PERF_SEL_RB0_OVERFLOW_VF2', + 63: 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 64: 'IH_PERF_SEL_RB0_OVERFLOW_VF4', + 65: 'IH_PERF_SEL_RB0_OVERFLOW_VF5', + 66: 'IH_PERF_SEL_RB0_OVERFLOW_VF6', + 67: 'IH_PERF_SEL_RB0_OVERFLOW_VF7', + 68: 'IH_PERF_SEL_RB0_OVERFLOW_VF8', + 69: 'IH_PERF_SEL_RB0_OVERFLOW_VF9', + 70: 'IH_PERF_SEL_RB0_OVERFLOW_VF10', + 71: 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 72: 'IH_PERF_SEL_RB0_OVERFLOW_VF12', + 73: 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 74: 'IH_PERF_SEL_RB0_OVERFLOW_VF14', + 75: 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 76: 'IH_PERF_SEL_RB0_OVERFLOW_VF16', + 77: 'IH_PERF_SEL_RB0_OVERFLOW_VF17', + 78: 'IH_PERF_SEL_RB0_OVERFLOW_VF18', + 79: 'IH_PERF_SEL_RB0_OVERFLOW_VF19', + 80: 'IH_PERF_SEL_RB0_OVERFLOW_VF20', + 81: 'IH_PERF_SEL_RB0_OVERFLOW_VF21', + 82: 'IH_PERF_SEL_RB0_OVERFLOW_VF22', + 83: 'IH_PERF_SEL_RB0_OVERFLOW_VF23', + 84: 'IH_PERF_SEL_RB0_OVERFLOW_VF24', + 85: 'IH_PERF_SEL_RB0_OVERFLOW_VF25', + 86: 'IH_PERF_SEL_RB0_OVERFLOW_VF26', + 87: 'IH_PERF_SEL_RB0_OVERFLOW_VF27', + 88: 'IH_PERF_SEL_RB0_OVERFLOW_VF28', + 89: 'IH_PERF_SEL_RB0_OVERFLOW_VF29', + 90: 'IH_PERF_SEL_RB0_OVERFLOW_VF30', + 91: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 92: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 93: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 94: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 95: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 96: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 97: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 98: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 99: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 100: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', + 101: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 102: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 103: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 104: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 105: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 106: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 107: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF16', + 108: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF17', + 109: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF18', + 110: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF19', + 111: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF20', + 112: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF21', + 113: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF22', + 114: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF23', + 115: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF24', + 116: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF25', + 117: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF26', + 118: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF27', + 119: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF28', + 120: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF29', + 121: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF30', + 122: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', + 123: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 124: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 125: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', + 126: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 127: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', + 128: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 129: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', + 130: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 131: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', + 132: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 133: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 134: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 135: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 136: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 137: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', + 138: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF16', + 139: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF17', + 140: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF18', + 141: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF19', + 142: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF20', + 143: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF21', + 144: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF22', + 145: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF23', + 146: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF24', + 147: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF25', + 148: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF26', + 149: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF27', + 150: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF28', + 151: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF29', + 152: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF30', + 153: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', + 154: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', + 155: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 156: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', + 157: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 158: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', + 159: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 160: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', + 161: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 162: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', + 163: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 164: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 165: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 166: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 167: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 168: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', + 169: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF16', + 170: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF17', + 171: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF18', + 172: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF19', + 173: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF20', + 174: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF21', + 175: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF22', + 176: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF23', + 177: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF24', + 178: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF25', + 179: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF26', + 180: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF27', + 181: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF28', + 182: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF29', + 183: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF30', + 184: 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 185: 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 186: 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 187: 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 188: 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 189: 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 190: 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 191: 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 192: 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 193: 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', + 194: 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 195: 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 196: 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 197: 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 198: 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 199: 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 200: 'IH_PERF_SEL_BIF_LINE0_RISING_VF16', + 201: 'IH_PERF_SEL_BIF_LINE0_RISING_VF17', + 202: 'IH_PERF_SEL_BIF_LINE0_RISING_VF18', + 203: 'IH_PERF_SEL_BIF_LINE0_RISING_VF19', + 204: 'IH_PERF_SEL_BIF_LINE0_RISING_VF20', + 205: 'IH_PERF_SEL_BIF_LINE0_RISING_VF21', + 206: 'IH_PERF_SEL_BIF_LINE0_RISING_VF22', + 207: 'IH_PERF_SEL_BIF_LINE0_RISING_VF23', + 208: 'IH_PERF_SEL_BIF_LINE0_RISING_VF24', + 209: 'IH_PERF_SEL_BIF_LINE0_RISING_VF25', + 210: 'IH_PERF_SEL_BIF_LINE0_RISING_VF26', + 211: 'IH_PERF_SEL_BIF_LINE0_RISING_VF27', + 212: 'IH_PERF_SEL_BIF_LINE0_RISING_VF28', + 213: 'IH_PERF_SEL_BIF_LINE0_RISING_VF29', + 214: 'IH_PERF_SEL_BIF_LINE0_RISING_VF30', + 215: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 216: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 217: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 218: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 219: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 220: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 221: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 222: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 223: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 224: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 225: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 226: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 227: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 228: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 229: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 230: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 231: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF16', + 232: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF17', + 233: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF18', + 234: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF19', + 235: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF20', + 236: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF21', + 237: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF22', + 238: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF23', + 239: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF24', + 240: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF25', + 241: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF26', + 242: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF27', + 243: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF28', + 244: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF29', + 245: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF30', + 246: 'IH_PERF_SEL_CLIENT0_INT', + 247: 'IH_PERF_SEL_CLIENT1_INT', + 248: 'IH_PERF_SEL_CLIENT2_INT', + 249: 'IH_PERF_SEL_CLIENT3_INT', + 250: 'IH_PERF_SEL_CLIENT4_INT', + 251: 'IH_PERF_SEL_CLIENT5_INT', + 252: 'IH_PERF_SEL_CLIENT6_INT', + 253: 'IH_PERF_SEL_CLIENT7_INT', + 254: 'IH_PERF_SEL_CLIENT8_INT', + 255: 'IH_PERF_SEL_CLIENT9_INT', + 256: 'IH_PERF_SEL_CLIENT10_INT', + 257: 'IH_PERF_SEL_CLIENT11_INT', + 258: 'IH_PERF_SEL_CLIENT12_INT', + 259: 'IH_PERF_SEL_CLIENT13_INT', + 260: 'IH_PERF_SEL_CLIENT14_INT', + 261: 'IH_PERF_SEL_CLIENT15_INT', + 262: 'IH_PERF_SEL_CLIENT16_INT', + 263: 'IH_PERF_SEL_CLIENT17_INT', + 264: 'IH_PERF_SEL_CLIENT18_INT', + 265: 'IH_PERF_SEL_CLIENT19_INT', + 266: 'IH_PERF_SEL_CLIENT20_INT', + 267: 'IH_PERF_SEL_CLIENT21_INT', + 268: 'IH_PERF_SEL_CLIENT22_INT', + 269: 'IH_PERF_SEL_CLIENT23_INT', + 270: 'IH_PERF_SEL_CLIENT24_INT', + 271: 'IH_PERF_SEL_CLIENT25_INT', + 272: 'IH_PERF_SEL_CLIENT26_INT', + 273: 'IH_PERF_SEL_CLIENT27_INT', + 274: 'IH_PERF_SEL_CLIENT28_INT', + 275: 'IH_PERF_SEL_CLIENT29_INT', + 276: 'IH_PERF_SEL_CLIENT30_INT', + 277: 'IH_PERF_SEL_CLIENT31_INT', + 278: 'IH_PERF_SEL_RB1_FULL_VF0', + 279: 'IH_PERF_SEL_RB1_FULL_VF1', + 280: 'IH_PERF_SEL_RB1_FULL_VF2', + 281: 'IH_PERF_SEL_RB1_FULL_VF3', + 282: 'IH_PERF_SEL_RB1_FULL_VF4', + 283: 'IH_PERF_SEL_RB1_FULL_VF5', + 284: 'IH_PERF_SEL_RB1_FULL_VF6', + 285: 'IH_PERF_SEL_RB1_FULL_VF7', + 286: 'IH_PERF_SEL_RB1_FULL_VF8', + 287: 'IH_PERF_SEL_RB1_FULL_VF9', + 288: 'IH_PERF_SEL_RB1_FULL_VF10', + 289: 'IH_PERF_SEL_RB1_FULL_VF11', + 290: 'IH_PERF_SEL_RB1_FULL_VF12', + 291: 'IH_PERF_SEL_RB1_FULL_VF13', + 292: 'IH_PERF_SEL_RB1_FULL_VF14', + 293: 'IH_PERF_SEL_RB1_FULL_VF15', + 294: 'IH_PERF_SEL_RB1_FULL_VF16', + 295: 'IH_PERF_SEL_RB1_FULL_VF17', + 296: 'IH_PERF_SEL_RB1_FULL_VF18', + 297: 'IH_PERF_SEL_RB1_FULL_VF19', + 298: 'IH_PERF_SEL_RB1_FULL_VF20', + 299: 'IH_PERF_SEL_RB1_FULL_VF21', + 300: 'IH_PERF_SEL_RB1_FULL_VF22', + 301: 'IH_PERF_SEL_RB1_FULL_VF23', + 302: 'IH_PERF_SEL_RB1_FULL_VF24', + 303: 'IH_PERF_SEL_RB1_FULL_VF25', + 304: 'IH_PERF_SEL_RB1_FULL_VF26', + 305: 'IH_PERF_SEL_RB1_FULL_VF27', + 306: 'IH_PERF_SEL_RB1_FULL_VF28', + 307: 'IH_PERF_SEL_RB1_FULL_VF29', + 308: 'IH_PERF_SEL_RB1_FULL_VF30', + 309: 'IH_PERF_SEL_RB1_OVERFLOW_VF0', + 310: 'IH_PERF_SEL_RB1_OVERFLOW_VF1', + 311: 'IH_PERF_SEL_RB1_OVERFLOW_VF2', + 312: 'IH_PERF_SEL_RB1_OVERFLOW_VF3', + 313: 'IH_PERF_SEL_RB1_OVERFLOW_VF4', + 314: 'IH_PERF_SEL_RB1_OVERFLOW_VF5', + 315: 'IH_PERF_SEL_RB1_OVERFLOW_VF6', + 316: 'IH_PERF_SEL_RB1_OVERFLOW_VF7', + 317: 'IH_PERF_SEL_RB1_OVERFLOW_VF8', + 318: 'IH_PERF_SEL_RB1_OVERFLOW_VF9', + 319: 'IH_PERF_SEL_RB1_OVERFLOW_VF10', + 320: 'IH_PERF_SEL_RB1_OVERFLOW_VF11', + 321: 'IH_PERF_SEL_RB1_OVERFLOW_VF12', + 322: 'IH_PERF_SEL_RB1_OVERFLOW_VF13', + 323: 'IH_PERF_SEL_RB1_OVERFLOW_VF14', + 324: 'IH_PERF_SEL_RB1_OVERFLOW_VF15', + 325: 'IH_PERF_SEL_RB1_OVERFLOW_VF16', + 326: 'IH_PERF_SEL_RB1_OVERFLOW_VF17', + 327: 'IH_PERF_SEL_RB1_OVERFLOW_VF18', + 328: 'IH_PERF_SEL_RB1_OVERFLOW_VF19', + 329: 'IH_PERF_SEL_RB1_OVERFLOW_VF20', + 330: 'IH_PERF_SEL_RB1_OVERFLOW_VF21', + 331: 'IH_PERF_SEL_RB1_OVERFLOW_VF22', + 332: 'IH_PERF_SEL_RB1_OVERFLOW_VF23', + 333: 'IH_PERF_SEL_RB1_OVERFLOW_VF24', + 334: 'IH_PERF_SEL_RB1_OVERFLOW_VF25', + 335: 'IH_PERF_SEL_RB1_OVERFLOW_VF26', + 336: 'IH_PERF_SEL_RB1_OVERFLOW_VF27', + 337: 'IH_PERF_SEL_RB1_OVERFLOW_VF28', + 338: 'IH_PERF_SEL_RB1_OVERFLOW_VF29', + 339: 'IH_PERF_SEL_RB1_OVERFLOW_VF30', + 340: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', + 341: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 342: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 343: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', + 344: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 345: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', + 346: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 347: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', + 348: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 349: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', + 350: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 351: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 352: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 353: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 354: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 355: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', + 356: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF16', + 357: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF17', + 358: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF18', + 359: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF19', + 360: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF20', + 361: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF21', + 362: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF22', + 363: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF23', + 364: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF24', + 365: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF25', + 366: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF26', + 367: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF27', + 368: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF28', + 369: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF29', + 370: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF30', + 371: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', + 372: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', + 373: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 374: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', + 375: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 376: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', + 377: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 378: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', + 379: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 380: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', + 381: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 382: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 383: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 384: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 385: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 386: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', + 387: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF16', + 388: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF17', + 389: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF18', + 390: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF19', + 391: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF20', + 392: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF21', + 393: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF22', + 394: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF23', + 395: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF24', + 396: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF25', + 397: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF26', + 398: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF27', + 399: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF28', + 400: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF29', + 401: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF30', + 402: 'IH_PERF_SEL_RB2_FULL_VF0', + 403: 'IH_PERF_SEL_RB2_FULL_VF1', + 404: 'IH_PERF_SEL_RB2_FULL_VF2', + 405: 'IH_PERF_SEL_RB2_FULL_VF3', + 406: 'IH_PERF_SEL_RB2_FULL_VF4', + 407: 'IH_PERF_SEL_RB2_FULL_VF5', + 408: 'IH_PERF_SEL_RB2_FULL_VF6', + 409: 'IH_PERF_SEL_RB2_FULL_VF7', + 410: 'IH_PERF_SEL_RB2_FULL_VF8', + 411: 'IH_PERF_SEL_RB2_FULL_VF9', + 412: 'IH_PERF_SEL_RB2_FULL_VF10', + 413: 'IH_PERF_SEL_RB2_FULL_VF11', + 414: 'IH_PERF_SEL_RB2_FULL_VF12', + 415: 'IH_PERF_SEL_RB2_FULL_VF13', + 416: 'IH_PERF_SEL_RB2_FULL_VF14', + 417: 'IH_PERF_SEL_RB2_FULL_VF15', + 418: 'IH_PERF_SEL_RB2_FULL_VF16', + 419: 'IH_PERF_SEL_RB2_FULL_VF17', + 420: 'IH_PERF_SEL_RB2_FULL_VF18', + 421: 'IH_PERF_SEL_RB2_FULL_VF19', + 422: 'IH_PERF_SEL_RB2_FULL_VF20', + 423: 'IH_PERF_SEL_RB2_FULL_VF21', + 424: 'IH_PERF_SEL_RB2_FULL_VF22', + 425: 'IH_PERF_SEL_RB2_FULL_VF23', + 426: 'IH_PERF_SEL_RB2_FULL_VF24', + 427: 'IH_PERF_SEL_RB2_FULL_VF25', + 428: 'IH_PERF_SEL_RB2_FULL_VF26', + 429: 'IH_PERF_SEL_RB2_FULL_VF27', + 430: 'IH_PERF_SEL_RB2_FULL_VF28', + 431: 'IH_PERF_SEL_RB2_FULL_VF29', + 432: 'IH_PERF_SEL_RB2_FULL_VF30', + 433: 'IH_PERF_SEL_RB2_OVERFLOW_VF0', + 434: 'IH_PERF_SEL_RB2_OVERFLOW_VF1', + 435: 'IH_PERF_SEL_RB2_OVERFLOW_VF2', + 436: 'IH_PERF_SEL_RB2_OVERFLOW_VF3', + 437: 'IH_PERF_SEL_RB2_OVERFLOW_VF4', + 438: 'IH_PERF_SEL_RB2_OVERFLOW_VF5', + 439: 'IH_PERF_SEL_RB2_OVERFLOW_VF6', + 440: 'IH_PERF_SEL_RB2_OVERFLOW_VF7', + 441: 'IH_PERF_SEL_RB2_OVERFLOW_VF8', + 442: 'IH_PERF_SEL_RB2_OVERFLOW_VF9', + 443: 'IH_PERF_SEL_RB2_OVERFLOW_VF10', + 444: 'IH_PERF_SEL_RB2_OVERFLOW_VF11', + 445: 'IH_PERF_SEL_RB2_OVERFLOW_VF12', + 446: 'IH_PERF_SEL_RB2_OVERFLOW_VF13', + 447: 'IH_PERF_SEL_RB2_OVERFLOW_VF14', + 448: 'IH_PERF_SEL_RB2_OVERFLOW_VF15', + 449: 'IH_PERF_SEL_RB2_OVERFLOW_VF16', + 450: 'IH_PERF_SEL_RB2_OVERFLOW_VF17', + 451: 'IH_PERF_SEL_RB2_OVERFLOW_VF18', + 452: 'IH_PERF_SEL_RB2_OVERFLOW_VF19', + 453: 'IH_PERF_SEL_RB2_OVERFLOW_VF20', + 454: 'IH_PERF_SEL_RB2_OVERFLOW_VF21', + 455: 'IH_PERF_SEL_RB2_OVERFLOW_VF22', + 456: 'IH_PERF_SEL_RB2_OVERFLOW_VF23', + 457: 'IH_PERF_SEL_RB2_OVERFLOW_VF24', + 458: 'IH_PERF_SEL_RB2_OVERFLOW_VF25', + 459: 'IH_PERF_SEL_RB2_OVERFLOW_VF26', + 460: 'IH_PERF_SEL_RB2_OVERFLOW_VF27', + 461: 'IH_PERF_SEL_RB2_OVERFLOW_VF28', + 462: 'IH_PERF_SEL_RB2_OVERFLOW_VF29', + 463: 'IH_PERF_SEL_RB2_OVERFLOW_VF30', + 464: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', + 465: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 466: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 467: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', + 468: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 469: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', + 470: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 471: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', + 472: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 473: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', + 474: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 475: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 476: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 477: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 478: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 479: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', + 480: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF16', + 481: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF17', + 482: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF18', + 483: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF19', + 484: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF20', + 485: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF21', + 486: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF22', + 487: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF23', + 488: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF24', + 489: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF25', + 490: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF26', + 491: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF27', + 492: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF28', + 493: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF29', + 494: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF30', + 495: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', + 496: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', + 497: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 498: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', + 499: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 500: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', + 501: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 502: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', + 503: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 504: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', + 505: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 506: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 507: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 508: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 509: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 510: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', + 511: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF16', + 512: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF17', + 513: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF18', + 514: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF19', + 515: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF20', + 516: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF21', + 517: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF22', + 518: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF23', + 519: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF24', + 520: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF25', + 521: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF26', + 522: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF27', + 523: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF28', + 524: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF29', + 525: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF30', + 526: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP', + 527: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0', + 528: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1', + 529: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2', + 530: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3', + 531: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4', + 532: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5', + 533: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6', + 534: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7', + 535: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8', + 536: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9', + 537: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10', + 538: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11', + 539: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12', + 540: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13', + 541: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14', + 542: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15', + 543: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF16', + 544: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF17', + 545: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF18', + 546: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF19', + 547: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF20', + 548: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF21', + 549: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF22', + 550: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF23', + 551: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF24', + 552: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF25', + 553: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF26', + 554: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF27', + 555: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF28', + 556: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF29', + 557: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF30', + 558: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP', + 559: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0', + 560: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1', + 561: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2', + 562: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3', + 563: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4', + 564: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5', + 565: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6', + 566: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7', + 567: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8', + 568: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9', + 569: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10', + 570: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11', + 571: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12', + 572: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13', + 573: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14', + 574: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15', + 575: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF16', + 576: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF17', + 577: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF18', + 578: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF19', + 579: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF20', + 580: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF21', + 581: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF22', + 582: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF23', + 583: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF24', + 584: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF25', + 585: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF26', + 586: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF27', + 587: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF28', + 588: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF29', + 589: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF30', + 590: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP', + 591: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0', + 592: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1', + 593: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2', + 594: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3', + 595: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4', + 596: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5', + 597: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6', + 598: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7', + 599: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8', + 600: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9', + 601: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10', + 602: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11', + 603: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12', + 604: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13', + 605: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14', + 606: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15', + 607: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF16', + 608: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF17', + 609: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF18', + 610: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF19', + 611: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF20', + 612: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF21', + 613: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF22', + 614: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF23', + 615: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF24', + 616: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF25', + 617: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF26', + 618: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF27', + 619: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF28', + 620: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF29', + 621: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF30', + 622: 'IH_PERF_SEL_RB0_LOAD_RPTR', + 623: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF0', + 624: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF1', + 625: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF2', + 626: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF3', + 627: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF4', + 628: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF5', + 629: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF6', + 630: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF7', + 631: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF8', + 632: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF9', + 633: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF10', + 634: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF11', + 635: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF12', + 636: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF13', + 637: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF14', + 638: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF15', + 639: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF16', + 640: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF17', + 641: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF18', + 642: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF19', + 643: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF20', + 644: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF21', + 645: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF22', + 646: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF23', + 647: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF24', + 648: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF25', + 649: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF26', + 650: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF27', + 651: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF28', + 652: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF29', + 653: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF30', + 654: 'IH_PERF_SEL_RB1_LOAD_RPTR', + 655: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF0', + 656: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF1', + 657: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF2', + 658: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF3', + 659: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF4', + 660: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF5', + 661: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF6', + 662: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF7', + 663: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF8', + 664: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF9', + 665: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF10', + 666: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF11', + 667: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF12', + 668: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF13', + 669: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF14', + 670: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF15', + 671: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF16', + 672: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF17', + 673: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF18', + 674: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF19', + 675: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF20', + 676: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF21', + 677: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF22', + 678: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF23', + 679: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF24', + 680: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF25', + 681: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF26', + 682: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF27', + 683: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF28', + 684: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF29', + 685: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF30', + 686: 'IH_PERF_SEL_RB2_LOAD_RPTR', + 687: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF0', + 688: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF1', + 689: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF2', + 690: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF3', + 691: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF4', + 692: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF5', + 693: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF6', + 694: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF7', + 695: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF8', + 696: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF9', + 697: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF10', + 698: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF11', + 699: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF12', + 700: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF13', + 701: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF14', + 702: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF15', + 703: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF16', + 704: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF17', + 705: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF18', + 706: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF19', + 707: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF20', + 708: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF21', + 709: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF22', + 710: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF23', + 711: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF24', + 712: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF25', + 713: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF26', + 714: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF27', + 715: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF28', + 716: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF29', + 717: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF30', +} +IH_PERF_SEL_CYCLE = 0 +IH_PERF_SEL_IDLE = 1 +IH_PERF_SEL_INPUT_IDLE = 2 +IH_PERF_SEL_BUFFER_IDLE = 3 +IH_PERF_SEL_RB0_FULL = 4 +IH_PERF_SEL_RB0_OVERFLOW = 5 +IH_PERF_SEL_RB0_WPTR_WRITEBACK = 6 +IH_PERF_SEL_RB0_WPTR_WRAP = 7 +IH_PERF_SEL_RB0_RPTR_WRAP = 8 +IH_PERF_SEL_MC_WR_IDLE = 9 +IH_PERF_SEL_MC_WR_COUNT = 10 +IH_PERF_SEL_MC_WR_STALL = 11 +IH_PERF_SEL_MC_WR_CLEAN_PENDING = 12 +IH_PERF_SEL_MC_WR_CLEAN_STALL = 13 +IH_PERF_SEL_BIF_LINE0_RISING = 14 +IH_PERF_SEL_BIF_LINE0_FALLING = 15 +IH_PERF_SEL_RB1_FULL = 16 +IH_PERF_SEL_RB1_OVERFLOW = 17 +IH_PERF_SEL_COOKIE_REC_ERROR = 18 +IH_PERF_SEL_RB1_WPTR_WRAP = 19 +IH_PERF_SEL_RB1_RPTR_WRAP = 20 +IH_PERF_SEL_RB2_FULL = 21 +IH_PERF_SEL_RB2_OVERFLOW = 22 +IH_PERF_SEL_CLIENT_CREDIT_ERROR = 23 +IH_PERF_SEL_RB2_WPTR_WRAP = 24 +IH_PERF_SEL_RB2_RPTR_WRAP = 25 +IH_PERF_SEL_STORM_CLIENT_INT_DROP = 26 +IH_PERF_SEL_SELF_IV_VALID = 27 +IH_PERF_SEL_BUFFER_FIFO_FULL = 28 +IH_PERF_SEL_RB0_FULL_VF0 = 29 +IH_PERF_SEL_RB0_FULL_VF1 = 30 +IH_PERF_SEL_RB0_FULL_VF2 = 31 +IH_PERF_SEL_RB0_FULL_VF3 = 32 +IH_PERF_SEL_RB0_FULL_VF4 = 33 +IH_PERF_SEL_RB0_FULL_VF5 = 34 +IH_PERF_SEL_RB0_FULL_VF6 = 35 +IH_PERF_SEL_RB0_FULL_VF7 = 36 +IH_PERF_SEL_RB0_FULL_VF8 = 37 +IH_PERF_SEL_RB0_FULL_VF9 = 38 +IH_PERF_SEL_RB0_FULL_VF10 = 39 +IH_PERF_SEL_RB0_FULL_VF11 = 40 +IH_PERF_SEL_RB0_FULL_VF12 = 41 +IH_PERF_SEL_RB0_FULL_VF13 = 42 +IH_PERF_SEL_RB0_FULL_VF14 = 43 +IH_PERF_SEL_RB0_FULL_VF15 = 44 +IH_PERF_SEL_RB0_FULL_VF16 = 45 +IH_PERF_SEL_RB0_FULL_VF17 = 46 +IH_PERF_SEL_RB0_FULL_VF18 = 47 +IH_PERF_SEL_RB0_FULL_VF19 = 48 +IH_PERF_SEL_RB0_FULL_VF20 = 49 +IH_PERF_SEL_RB0_FULL_VF21 = 50 +IH_PERF_SEL_RB0_FULL_VF22 = 51 +IH_PERF_SEL_RB0_FULL_VF23 = 52 +IH_PERF_SEL_RB0_FULL_VF24 = 53 +IH_PERF_SEL_RB0_FULL_VF25 = 54 +IH_PERF_SEL_RB0_FULL_VF26 = 55 +IH_PERF_SEL_RB0_FULL_VF27 = 56 +IH_PERF_SEL_RB0_FULL_VF28 = 57 +IH_PERF_SEL_RB0_FULL_VF29 = 58 +IH_PERF_SEL_RB0_FULL_VF30 = 59 +IH_PERF_SEL_RB0_OVERFLOW_VF0 = 60 +IH_PERF_SEL_RB0_OVERFLOW_VF1 = 61 +IH_PERF_SEL_RB0_OVERFLOW_VF2 = 62 +IH_PERF_SEL_RB0_OVERFLOW_VF3 = 63 +IH_PERF_SEL_RB0_OVERFLOW_VF4 = 64 +IH_PERF_SEL_RB0_OVERFLOW_VF5 = 65 +IH_PERF_SEL_RB0_OVERFLOW_VF6 = 66 +IH_PERF_SEL_RB0_OVERFLOW_VF7 = 67 +IH_PERF_SEL_RB0_OVERFLOW_VF8 = 68 +IH_PERF_SEL_RB0_OVERFLOW_VF9 = 69 +IH_PERF_SEL_RB0_OVERFLOW_VF10 = 70 +IH_PERF_SEL_RB0_OVERFLOW_VF11 = 71 +IH_PERF_SEL_RB0_OVERFLOW_VF12 = 72 +IH_PERF_SEL_RB0_OVERFLOW_VF13 = 73 +IH_PERF_SEL_RB0_OVERFLOW_VF14 = 74 +IH_PERF_SEL_RB0_OVERFLOW_VF15 = 75 +IH_PERF_SEL_RB0_OVERFLOW_VF16 = 76 +IH_PERF_SEL_RB0_OVERFLOW_VF17 = 77 +IH_PERF_SEL_RB0_OVERFLOW_VF18 = 78 +IH_PERF_SEL_RB0_OVERFLOW_VF19 = 79 +IH_PERF_SEL_RB0_OVERFLOW_VF20 = 80 +IH_PERF_SEL_RB0_OVERFLOW_VF21 = 81 +IH_PERF_SEL_RB0_OVERFLOW_VF22 = 82 +IH_PERF_SEL_RB0_OVERFLOW_VF23 = 83 +IH_PERF_SEL_RB0_OVERFLOW_VF24 = 84 +IH_PERF_SEL_RB0_OVERFLOW_VF25 = 85 +IH_PERF_SEL_RB0_OVERFLOW_VF26 = 86 +IH_PERF_SEL_RB0_OVERFLOW_VF27 = 87 +IH_PERF_SEL_RB0_OVERFLOW_VF28 = 88 +IH_PERF_SEL_RB0_OVERFLOW_VF29 = 89 +IH_PERF_SEL_RB0_OVERFLOW_VF30 = 90 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0 = 91 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1 = 92 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2 = 93 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3 = 94 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4 = 95 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5 = 96 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6 = 97 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7 = 98 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8 = 99 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9 = 100 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10 = 101 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11 = 102 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12 = 103 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13 = 104 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14 = 105 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15 = 106 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF16 = 107 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF17 = 108 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF18 = 109 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF19 = 110 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF20 = 111 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF21 = 112 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF22 = 113 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF23 = 114 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF24 = 115 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF25 = 116 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF26 = 117 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF27 = 118 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF28 = 119 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF29 = 120 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF30 = 121 +IH_PERF_SEL_RB0_WPTR_WRAP_VF0 = 122 +IH_PERF_SEL_RB0_WPTR_WRAP_VF1 = 123 +IH_PERF_SEL_RB0_WPTR_WRAP_VF2 = 124 +IH_PERF_SEL_RB0_WPTR_WRAP_VF3 = 125 +IH_PERF_SEL_RB0_WPTR_WRAP_VF4 = 126 +IH_PERF_SEL_RB0_WPTR_WRAP_VF5 = 127 +IH_PERF_SEL_RB0_WPTR_WRAP_VF6 = 128 +IH_PERF_SEL_RB0_WPTR_WRAP_VF7 = 129 +IH_PERF_SEL_RB0_WPTR_WRAP_VF8 = 130 +IH_PERF_SEL_RB0_WPTR_WRAP_VF9 = 131 +IH_PERF_SEL_RB0_WPTR_WRAP_VF10 = 132 +IH_PERF_SEL_RB0_WPTR_WRAP_VF11 = 133 +IH_PERF_SEL_RB0_WPTR_WRAP_VF12 = 134 +IH_PERF_SEL_RB0_WPTR_WRAP_VF13 = 135 +IH_PERF_SEL_RB0_WPTR_WRAP_VF14 = 136 +IH_PERF_SEL_RB0_WPTR_WRAP_VF15 = 137 +IH_PERF_SEL_RB0_WPTR_WRAP_VF16 = 138 +IH_PERF_SEL_RB0_WPTR_WRAP_VF17 = 139 +IH_PERF_SEL_RB0_WPTR_WRAP_VF18 = 140 +IH_PERF_SEL_RB0_WPTR_WRAP_VF19 = 141 +IH_PERF_SEL_RB0_WPTR_WRAP_VF20 = 142 +IH_PERF_SEL_RB0_WPTR_WRAP_VF21 = 143 +IH_PERF_SEL_RB0_WPTR_WRAP_VF22 = 144 +IH_PERF_SEL_RB0_WPTR_WRAP_VF23 = 145 +IH_PERF_SEL_RB0_WPTR_WRAP_VF24 = 146 +IH_PERF_SEL_RB0_WPTR_WRAP_VF25 = 147 +IH_PERF_SEL_RB0_WPTR_WRAP_VF26 = 148 +IH_PERF_SEL_RB0_WPTR_WRAP_VF27 = 149 +IH_PERF_SEL_RB0_WPTR_WRAP_VF28 = 150 +IH_PERF_SEL_RB0_WPTR_WRAP_VF29 = 151 +IH_PERF_SEL_RB0_WPTR_WRAP_VF30 = 152 +IH_PERF_SEL_RB0_RPTR_WRAP_VF0 = 153 +IH_PERF_SEL_RB0_RPTR_WRAP_VF1 = 154 +IH_PERF_SEL_RB0_RPTR_WRAP_VF2 = 155 +IH_PERF_SEL_RB0_RPTR_WRAP_VF3 = 156 +IH_PERF_SEL_RB0_RPTR_WRAP_VF4 = 157 +IH_PERF_SEL_RB0_RPTR_WRAP_VF5 = 158 +IH_PERF_SEL_RB0_RPTR_WRAP_VF6 = 159 +IH_PERF_SEL_RB0_RPTR_WRAP_VF7 = 160 +IH_PERF_SEL_RB0_RPTR_WRAP_VF8 = 161 +IH_PERF_SEL_RB0_RPTR_WRAP_VF9 = 162 +IH_PERF_SEL_RB0_RPTR_WRAP_VF10 = 163 +IH_PERF_SEL_RB0_RPTR_WRAP_VF11 = 164 +IH_PERF_SEL_RB0_RPTR_WRAP_VF12 = 165 +IH_PERF_SEL_RB0_RPTR_WRAP_VF13 = 166 +IH_PERF_SEL_RB0_RPTR_WRAP_VF14 = 167 +IH_PERF_SEL_RB0_RPTR_WRAP_VF15 = 168 +IH_PERF_SEL_RB0_RPTR_WRAP_VF16 = 169 +IH_PERF_SEL_RB0_RPTR_WRAP_VF17 = 170 +IH_PERF_SEL_RB0_RPTR_WRAP_VF18 = 171 +IH_PERF_SEL_RB0_RPTR_WRAP_VF19 = 172 +IH_PERF_SEL_RB0_RPTR_WRAP_VF20 = 173 +IH_PERF_SEL_RB0_RPTR_WRAP_VF21 = 174 +IH_PERF_SEL_RB0_RPTR_WRAP_VF22 = 175 +IH_PERF_SEL_RB0_RPTR_WRAP_VF23 = 176 +IH_PERF_SEL_RB0_RPTR_WRAP_VF24 = 177 +IH_PERF_SEL_RB0_RPTR_WRAP_VF25 = 178 +IH_PERF_SEL_RB0_RPTR_WRAP_VF26 = 179 +IH_PERF_SEL_RB0_RPTR_WRAP_VF27 = 180 +IH_PERF_SEL_RB0_RPTR_WRAP_VF28 = 181 +IH_PERF_SEL_RB0_RPTR_WRAP_VF29 = 182 +IH_PERF_SEL_RB0_RPTR_WRAP_VF30 = 183 +IH_PERF_SEL_BIF_LINE0_RISING_VF0 = 184 +IH_PERF_SEL_BIF_LINE0_RISING_VF1 = 185 +IH_PERF_SEL_BIF_LINE0_RISING_VF2 = 186 +IH_PERF_SEL_BIF_LINE0_RISING_VF3 = 187 +IH_PERF_SEL_BIF_LINE0_RISING_VF4 = 188 +IH_PERF_SEL_BIF_LINE0_RISING_VF5 = 189 +IH_PERF_SEL_BIF_LINE0_RISING_VF6 = 190 +IH_PERF_SEL_BIF_LINE0_RISING_VF7 = 191 +IH_PERF_SEL_BIF_LINE0_RISING_VF8 = 192 +IH_PERF_SEL_BIF_LINE0_RISING_VF9 = 193 +IH_PERF_SEL_BIF_LINE0_RISING_VF10 = 194 +IH_PERF_SEL_BIF_LINE0_RISING_VF11 = 195 +IH_PERF_SEL_BIF_LINE0_RISING_VF12 = 196 +IH_PERF_SEL_BIF_LINE0_RISING_VF13 = 197 +IH_PERF_SEL_BIF_LINE0_RISING_VF14 = 198 +IH_PERF_SEL_BIF_LINE0_RISING_VF15 = 199 +IH_PERF_SEL_BIF_LINE0_RISING_VF16 = 200 +IH_PERF_SEL_BIF_LINE0_RISING_VF17 = 201 +IH_PERF_SEL_BIF_LINE0_RISING_VF18 = 202 +IH_PERF_SEL_BIF_LINE0_RISING_VF19 = 203 +IH_PERF_SEL_BIF_LINE0_RISING_VF20 = 204 +IH_PERF_SEL_BIF_LINE0_RISING_VF21 = 205 +IH_PERF_SEL_BIF_LINE0_RISING_VF22 = 206 +IH_PERF_SEL_BIF_LINE0_RISING_VF23 = 207 +IH_PERF_SEL_BIF_LINE0_RISING_VF24 = 208 +IH_PERF_SEL_BIF_LINE0_RISING_VF25 = 209 +IH_PERF_SEL_BIF_LINE0_RISING_VF26 = 210 +IH_PERF_SEL_BIF_LINE0_RISING_VF27 = 211 +IH_PERF_SEL_BIF_LINE0_RISING_VF28 = 212 +IH_PERF_SEL_BIF_LINE0_RISING_VF29 = 213 +IH_PERF_SEL_BIF_LINE0_RISING_VF30 = 214 +IH_PERF_SEL_BIF_LINE0_FALLING_VF0 = 215 +IH_PERF_SEL_BIF_LINE0_FALLING_VF1 = 216 +IH_PERF_SEL_BIF_LINE0_FALLING_VF2 = 217 +IH_PERF_SEL_BIF_LINE0_FALLING_VF3 = 218 +IH_PERF_SEL_BIF_LINE0_FALLING_VF4 = 219 +IH_PERF_SEL_BIF_LINE0_FALLING_VF5 = 220 +IH_PERF_SEL_BIF_LINE0_FALLING_VF6 = 221 +IH_PERF_SEL_BIF_LINE0_FALLING_VF7 = 222 +IH_PERF_SEL_BIF_LINE0_FALLING_VF8 = 223 +IH_PERF_SEL_BIF_LINE0_FALLING_VF9 = 224 +IH_PERF_SEL_BIF_LINE0_FALLING_VF10 = 225 +IH_PERF_SEL_BIF_LINE0_FALLING_VF11 = 226 +IH_PERF_SEL_BIF_LINE0_FALLING_VF12 = 227 +IH_PERF_SEL_BIF_LINE0_FALLING_VF13 = 228 +IH_PERF_SEL_BIF_LINE0_FALLING_VF14 = 229 +IH_PERF_SEL_BIF_LINE0_FALLING_VF15 = 230 +IH_PERF_SEL_BIF_LINE0_FALLING_VF16 = 231 +IH_PERF_SEL_BIF_LINE0_FALLING_VF17 = 232 +IH_PERF_SEL_BIF_LINE0_FALLING_VF18 = 233 +IH_PERF_SEL_BIF_LINE0_FALLING_VF19 = 234 +IH_PERF_SEL_BIF_LINE0_FALLING_VF20 = 235 +IH_PERF_SEL_BIF_LINE0_FALLING_VF21 = 236 +IH_PERF_SEL_BIF_LINE0_FALLING_VF22 = 237 +IH_PERF_SEL_BIF_LINE0_FALLING_VF23 = 238 +IH_PERF_SEL_BIF_LINE0_FALLING_VF24 = 239 +IH_PERF_SEL_BIF_LINE0_FALLING_VF25 = 240 +IH_PERF_SEL_BIF_LINE0_FALLING_VF26 = 241 +IH_PERF_SEL_BIF_LINE0_FALLING_VF27 = 242 +IH_PERF_SEL_BIF_LINE0_FALLING_VF28 = 243 +IH_PERF_SEL_BIF_LINE0_FALLING_VF29 = 244 +IH_PERF_SEL_BIF_LINE0_FALLING_VF30 = 245 +IH_PERF_SEL_CLIENT0_INT = 246 +IH_PERF_SEL_CLIENT1_INT = 247 +IH_PERF_SEL_CLIENT2_INT = 248 +IH_PERF_SEL_CLIENT3_INT = 249 +IH_PERF_SEL_CLIENT4_INT = 250 +IH_PERF_SEL_CLIENT5_INT = 251 +IH_PERF_SEL_CLIENT6_INT = 252 +IH_PERF_SEL_CLIENT7_INT = 253 +IH_PERF_SEL_CLIENT8_INT = 254 +IH_PERF_SEL_CLIENT9_INT = 255 +IH_PERF_SEL_CLIENT10_INT = 256 +IH_PERF_SEL_CLIENT11_INT = 257 +IH_PERF_SEL_CLIENT12_INT = 258 +IH_PERF_SEL_CLIENT13_INT = 259 +IH_PERF_SEL_CLIENT14_INT = 260 +IH_PERF_SEL_CLIENT15_INT = 261 +IH_PERF_SEL_CLIENT16_INT = 262 +IH_PERF_SEL_CLIENT17_INT = 263 +IH_PERF_SEL_CLIENT18_INT = 264 +IH_PERF_SEL_CLIENT19_INT = 265 +IH_PERF_SEL_CLIENT20_INT = 266 +IH_PERF_SEL_CLIENT21_INT = 267 +IH_PERF_SEL_CLIENT22_INT = 268 +IH_PERF_SEL_CLIENT23_INT = 269 +IH_PERF_SEL_CLIENT24_INT = 270 +IH_PERF_SEL_CLIENT25_INT = 271 +IH_PERF_SEL_CLIENT26_INT = 272 +IH_PERF_SEL_CLIENT27_INT = 273 +IH_PERF_SEL_CLIENT28_INT = 274 +IH_PERF_SEL_CLIENT29_INT = 275 +IH_PERF_SEL_CLIENT30_INT = 276 +IH_PERF_SEL_CLIENT31_INT = 277 +IH_PERF_SEL_RB1_FULL_VF0 = 278 +IH_PERF_SEL_RB1_FULL_VF1 = 279 +IH_PERF_SEL_RB1_FULL_VF2 = 280 +IH_PERF_SEL_RB1_FULL_VF3 = 281 +IH_PERF_SEL_RB1_FULL_VF4 = 282 +IH_PERF_SEL_RB1_FULL_VF5 = 283 +IH_PERF_SEL_RB1_FULL_VF6 = 284 +IH_PERF_SEL_RB1_FULL_VF7 = 285 +IH_PERF_SEL_RB1_FULL_VF8 = 286 +IH_PERF_SEL_RB1_FULL_VF9 = 287 +IH_PERF_SEL_RB1_FULL_VF10 = 288 +IH_PERF_SEL_RB1_FULL_VF11 = 289 +IH_PERF_SEL_RB1_FULL_VF12 = 290 +IH_PERF_SEL_RB1_FULL_VF13 = 291 +IH_PERF_SEL_RB1_FULL_VF14 = 292 +IH_PERF_SEL_RB1_FULL_VF15 = 293 +IH_PERF_SEL_RB1_FULL_VF16 = 294 +IH_PERF_SEL_RB1_FULL_VF17 = 295 +IH_PERF_SEL_RB1_FULL_VF18 = 296 +IH_PERF_SEL_RB1_FULL_VF19 = 297 +IH_PERF_SEL_RB1_FULL_VF20 = 298 +IH_PERF_SEL_RB1_FULL_VF21 = 299 +IH_PERF_SEL_RB1_FULL_VF22 = 300 +IH_PERF_SEL_RB1_FULL_VF23 = 301 +IH_PERF_SEL_RB1_FULL_VF24 = 302 +IH_PERF_SEL_RB1_FULL_VF25 = 303 +IH_PERF_SEL_RB1_FULL_VF26 = 304 +IH_PERF_SEL_RB1_FULL_VF27 = 305 +IH_PERF_SEL_RB1_FULL_VF28 = 306 +IH_PERF_SEL_RB1_FULL_VF29 = 307 +IH_PERF_SEL_RB1_FULL_VF30 = 308 +IH_PERF_SEL_RB1_OVERFLOW_VF0 = 309 +IH_PERF_SEL_RB1_OVERFLOW_VF1 = 310 +IH_PERF_SEL_RB1_OVERFLOW_VF2 = 311 +IH_PERF_SEL_RB1_OVERFLOW_VF3 = 312 +IH_PERF_SEL_RB1_OVERFLOW_VF4 = 313 +IH_PERF_SEL_RB1_OVERFLOW_VF5 = 314 +IH_PERF_SEL_RB1_OVERFLOW_VF6 = 315 +IH_PERF_SEL_RB1_OVERFLOW_VF7 = 316 +IH_PERF_SEL_RB1_OVERFLOW_VF8 = 317 +IH_PERF_SEL_RB1_OVERFLOW_VF9 = 318 +IH_PERF_SEL_RB1_OVERFLOW_VF10 = 319 +IH_PERF_SEL_RB1_OVERFLOW_VF11 = 320 +IH_PERF_SEL_RB1_OVERFLOW_VF12 = 321 +IH_PERF_SEL_RB1_OVERFLOW_VF13 = 322 +IH_PERF_SEL_RB1_OVERFLOW_VF14 = 323 +IH_PERF_SEL_RB1_OVERFLOW_VF15 = 324 +IH_PERF_SEL_RB1_OVERFLOW_VF16 = 325 +IH_PERF_SEL_RB1_OVERFLOW_VF17 = 326 +IH_PERF_SEL_RB1_OVERFLOW_VF18 = 327 +IH_PERF_SEL_RB1_OVERFLOW_VF19 = 328 +IH_PERF_SEL_RB1_OVERFLOW_VF20 = 329 +IH_PERF_SEL_RB1_OVERFLOW_VF21 = 330 +IH_PERF_SEL_RB1_OVERFLOW_VF22 = 331 +IH_PERF_SEL_RB1_OVERFLOW_VF23 = 332 +IH_PERF_SEL_RB1_OVERFLOW_VF24 = 333 +IH_PERF_SEL_RB1_OVERFLOW_VF25 = 334 +IH_PERF_SEL_RB1_OVERFLOW_VF26 = 335 +IH_PERF_SEL_RB1_OVERFLOW_VF27 = 336 +IH_PERF_SEL_RB1_OVERFLOW_VF28 = 337 +IH_PERF_SEL_RB1_OVERFLOW_VF29 = 338 +IH_PERF_SEL_RB1_OVERFLOW_VF30 = 339 +IH_PERF_SEL_RB1_WPTR_WRAP_VF0 = 340 +IH_PERF_SEL_RB1_WPTR_WRAP_VF1 = 341 +IH_PERF_SEL_RB1_WPTR_WRAP_VF2 = 342 +IH_PERF_SEL_RB1_WPTR_WRAP_VF3 = 343 +IH_PERF_SEL_RB1_WPTR_WRAP_VF4 = 344 +IH_PERF_SEL_RB1_WPTR_WRAP_VF5 = 345 +IH_PERF_SEL_RB1_WPTR_WRAP_VF6 = 346 +IH_PERF_SEL_RB1_WPTR_WRAP_VF7 = 347 +IH_PERF_SEL_RB1_WPTR_WRAP_VF8 = 348 +IH_PERF_SEL_RB1_WPTR_WRAP_VF9 = 349 +IH_PERF_SEL_RB1_WPTR_WRAP_VF10 = 350 +IH_PERF_SEL_RB1_WPTR_WRAP_VF11 = 351 +IH_PERF_SEL_RB1_WPTR_WRAP_VF12 = 352 +IH_PERF_SEL_RB1_WPTR_WRAP_VF13 = 353 +IH_PERF_SEL_RB1_WPTR_WRAP_VF14 = 354 +IH_PERF_SEL_RB1_WPTR_WRAP_VF15 = 355 +IH_PERF_SEL_RB1_WPTR_WRAP_VF16 = 356 +IH_PERF_SEL_RB1_WPTR_WRAP_VF17 = 357 +IH_PERF_SEL_RB1_WPTR_WRAP_VF18 = 358 +IH_PERF_SEL_RB1_WPTR_WRAP_VF19 = 359 +IH_PERF_SEL_RB1_WPTR_WRAP_VF20 = 360 +IH_PERF_SEL_RB1_WPTR_WRAP_VF21 = 361 +IH_PERF_SEL_RB1_WPTR_WRAP_VF22 = 362 +IH_PERF_SEL_RB1_WPTR_WRAP_VF23 = 363 +IH_PERF_SEL_RB1_WPTR_WRAP_VF24 = 364 +IH_PERF_SEL_RB1_WPTR_WRAP_VF25 = 365 +IH_PERF_SEL_RB1_WPTR_WRAP_VF26 = 366 +IH_PERF_SEL_RB1_WPTR_WRAP_VF27 = 367 +IH_PERF_SEL_RB1_WPTR_WRAP_VF28 = 368 +IH_PERF_SEL_RB1_WPTR_WRAP_VF29 = 369 +IH_PERF_SEL_RB1_WPTR_WRAP_VF30 = 370 +IH_PERF_SEL_RB1_RPTR_WRAP_VF0 = 371 +IH_PERF_SEL_RB1_RPTR_WRAP_VF1 = 372 +IH_PERF_SEL_RB1_RPTR_WRAP_VF2 = 373 +IH_PERF_SEL_RB1_RPTR_WRAP_VF3 = 374 +IH_PERF_SEL_RB1_RPTR_WRAP_VF4 = 375 +IH_PERF_SEL_RB1_RPTR_WRAP_VF5 = 376 +IH_PERF_SEL_RB1_RPTR_WRAP_VF6 = 377 +IH_PERF_SEL_RB1_RPTR_WRAP_VF7 = 378 +IH_PERF_SEL_RB1_RPTR_WRAP_VF8 = 379 +IH_PERF_SEL_RB1_RPTR_WRAP_VF9 = 380 +IH_PERF_SEL_RB1_RPTR_WRAP_VF10 = 381 +IH_PERF_SEL_RB1_RPTR_WRAP_VF11 = 382 +IH_PERF_SEL_RB1_RPTR_WRAP_VF12 = 383 +IH_PERF_SEL_RB1_RPTR_WRAP_VF13 = 384 +IH_PERF_SEL_RB1_RPTR_WRAP_VF14 = 385 +IH_PERF_SEL_RB1_RPTR_WRAP_VF15 = 386 +IH_PERF_SEL_RB1_RPTR_WRAP_VF16 = 387 +IH_PERF_SEL_RB1_RPTR_WRAP_VF17 = 388 +IH_PERF_SEL_RB1_RPTR_WRAP_VF18 = 389 +IH_PERF_SEL_RB1_RPTR_WRAP_VF19 = 390 +IH_PERF_SEL_RB1_RPTR_WRAP_VF20 = 391 +IH_PERF_SEL_RB1_RPTR_WRAP_VF21 = 392 +IH_PERF_SEL_RB1_RPTR_WRAP_VF22 = 393 +IH_PERF_SEL_RB1_RPTR_WRAP_VF23 = 394 +IH_PERF_SEL_RB1_RPTR_WRAP_VF24 = 395 +IH_PERF_SEL_RB1_RPTR_WRAP_VF25 = 396 +IH_PERF_SEL_RB1_RPTR_WRAP_VF26 = 397 +IH_PERF_SEL_RB1_RPTR_WRAP_VF27 = 398 +IH_PERF_SEL_RB1_RPTR_WRAP_VF28 = 399 +IH_PERF_SEL_RB1_RPTR_WRAP_VF29 = 400 +IH_PERF_SEL_RB1_RPTR_WRAP_VF30 = 401 +IH_PERF_SEL_RB2_FULL_VF0 = 402 +IH_PERF_SEL_RB2_FULL_VF1 = 403 +IH_PERF_SEL_RB2_FULL_VF2 = 404 +IH_PERF_SEL_RB2_FULL_VF3 = 405 +IH_PERF_SEL_RB2_FULL_VF4 = 406 +IH_PERF_SEL_RB2_FULL_VF5 = 407 +IH_PERF_SEL_RB2_FULL_VF6 = 408 +IH_PERF_SEL_RB2_FULL_VF7 = 409 +IH_PERF_SEL_RB2_FULL_VF8 = 410 +IH_PERF_SEL_RB2_FULL_VF9 = 411 +IH_PERF_SEL_RB2_FULL_VF10 = 412 +IH_PERF_SEL_RB2_FULL_VF11 = 413 +IH_PERF_SEL_RB2_FULL_VF12 = 414 +IH_PERF_SEL_RB2_FULL_VF13 = 415 +IH_PERF_SEL_RB2_FULL_VF14 = 416 +IH_PERF_SEL_RB2_FULL_VF15 = 417 +IH_PERF_SEL_RB2_FULL_VF16 = 418 +IH_PERF_SEL_RB2_FULL_VF17 = 419 +IH_PERF_SEL_RB2_FULL_VF18 = 420 +IH_PERF_SEL_RB2_FULL_VF19 = 421 +IH_PERF_SEL_RB2_FULL_VF20 = 422 +IH_PERF_SEL_RB2_FULL_VF21 = 423 +IH_PERF_SEL_RB2_FULL_VF22 = 424 +IH_PERF_SEL_RB2_FULL_VF23 = 425 +IH_PERF_SEL_RB2_FULL_VF24 = 426 +IH_PERF_SEL_RB2_FULL_VF25 = 427 +IH_PERF_SEL_RB2_FULL_VF26 = 428 +IH_PERF_SEL_RB2_FULL_VF27 = 429 +IH_PERF_SEL_RB2_FULL_VF28 = 430 +IH_PERF_SEL_RB2_FULL_VF29 = 431 +IH_PERF_SEL_RB2_FULL_VF30 = 432 +IH_PERF_SEL_RB2_OVERFLOW_VF0 = 433 +IH_PERF_SEL_RB2_OVERFLOW_VF1 = 434 +IH_PERF_SEL_RB2_OVERFLOW_VF2 = 435 +IH_PERF_SEL_RB2_OVERFLOW_VF3 = 436 +IH_PERF_SEL_RB2_OVERFLOW_VF4 = 437 +IH_PERF_SEL_RB2_OVERFLOW_VF5 = 438 +IH_PERF_SEL_RB2_OVERFLOW_VF6 = 439 +IH_PERF_SEL_RB2_OVERFLOW_VF7 = 440 +IH_PERF_SEL_RB2_OVERFLOW_VF8 = 441 +IH_PERF_SEL_RB2_OVERFLOW_VF9 = 442 +IH_PERF_SEL_RB2_OVERFLOW_VF10 = 443 +IH_PERF_SEL_RB2_OVERFLOW_VF11 = 444 +IH_PERF_SEL_RB2_OVERFLOW_VF12 = 445 +IH_PERF_SEL_RB2_OVERFLOW_VF13 = 446 +IH_PERF_SEL_RB2_OVERFLOW_VF14 = 447 +IH_PERF_SEL_RB2_OVERFLOW_VF15 = 448 +IH_PERF_SEL_RB2_OVERFLOW_VF16 = 449 +IH_PERF_SEL_RB2_OVERFLOW_VF17 = 450 +IH_PERF_SEL_RB2_OVERFLOW_VF18 = 451 +IH_PERF_SEL_RB2_OVERFLOW_VF19 = 452 +IH_PERF_SEL_RB2_OVERFLOW_VF20 = 453 +IH_PERF_SEL_RB2_OVERFLOW_VF21 = 454 +IH_PERF_SEL_RB2_OVERFLOW_VF22 = 455 +IH_PERF_SEL_RB2_OVERFLOW_VF23 = 456 +IH_PERF_SEL_RB2_OVERFLOW_VF24 = 457 +IH_PERF_SEL_RB2_OVERFLOW_VF25 = 458 +IH_PERF_SEL_RB2_OVERFLOW_VF26 = 459 +IH_PERF_SEL_RB2_OVERFLOW_VF27 = 460 +IH_PERF_SEL_RB2_OVERFLOW_VF28 = 461 +IH_PERF_SEL_RB2_OVERFLOW_VF29 = 462 +IH_PERF_SEL_RB2_OVERFLOW_VF30 = 463 +IH_PERF_SEL_RB2_WPTR_WRAP_VF0 = 464 +IH_PERF_SEL_RB2_WPTR_WRAP_VF1 = 465 +IH_PERF_SEL_RB2_WPTR_WRAP_VF2 = 466 +IH_PERF_SEL_RB2_WPTR_WRAP_VF3 = 467 +IH_PERF_SEL_RB2_WPTR_WRAP_VF4 = 468 +IH_PERF_SEL_RB2_WPTR_WRAP_VF5 = 469 +IH_PERF_SEL_RB2_WPTR_WRAP_VF6 = 470 +IH_PERF_SEL_RB2_WPTR_WRAP_VF7 = 471 +IH_PERF_SEL_RB2_WPTR_WRAP_VF8 = 472 +IH_PERF_SEL_RB2_WPTR_WRAP_VF9 = 473 +IH_PERF_SEL_RB2_WPTR_WRAP_VF10 = 474 +IH_PERF_SEL_RB2_WPTR_WRAP_VF11 = 475 +IH_PERF_SEL_RB2_WPTR_WRAP_VF12 = 476 +IH_PERF_SEL_RB2_WPTR_WRAP_VF13 = 477 +IH_PERF_SEL_RB2_WPTR_WRAP_VF14 = 478 +IH_PERF_SEL_RB2_WPTR_WRAP_VF15 = 479 +IH_PERF_SEL_RB2_WPTR_WRAP_VF16 = 480 +IH_PERF_SEL_RB2_WPTR_WRAP_VF17 = 481 +IH_PERF_SEL_RB2_WPTR_WRAP_VF18 = 482 +IH_PERF_SEL_RB2_WPTR_WRAP_VF19 = 483 +IH_PERF_SEL_RB2_WPTR_WRAP_VF20 = 484 +IH_PERF_SEL_RB2_WPTR_WRAP_VF21 = 485 +IH_PERF_SEL_RB2_WPTR_WRAP_VF22 = 486 +IH_PERF_SEL_RB2_WPTR_WRAP_VF23 = 487 +IH_PERF_SEL_RB2_WPTR_WRAP_VF24 = 488 +IH_PERF_SEL_RB2_WPTR_WRAP_VF25 = 489 +IH_PERF_SEL_RB2_WPTR_WRAP_VF26 = 490 +IH_PERF_SEL_RB2_WPTR_WRAP_VF27 = 491 +IH_PERF_SEL_RB2_WPTR_WRAP_VF28 = 492 +IH_PERF_SEL_RB2_WPTR_WRAP_VF29 = 493 +IH_PERF_SEL_RB2_WPTR_WRAP_VF30 = 494 +IH_PERF_SEL_RB2_RPTR_WRAP_VF0 = 495 +IH_PERF_SEL_RB2_RPTR_WRAP_VF1 = 496 +IH_PERF_SEL_RB2_RPTR_WRAP_VF2 = 497 +IH_PERF_SEL_RB2_RPTR_WRAP_VF3 = 498 +IH_PERF_SEL_RB2_RPTR_WRAP_VF4 = 499 +IH_PERF_SEL_RB2_RPTR_WRAP_VF5 = 500 +IH_PERF_SEL_RB2_RPTR_WRAP_VF6 = 501 +IH_PERF_SEL_RB2_RPTR_WRAP_VF7 = 502 +IH_PERF_SEL_RB2_RPTR_WRAP_VF8 = 503 +IH_PERF_SEL_RB2_RPTR_WRAP_VF9 = 504 +IH_PERF_SEL_RB2_RPTR_WRAP_VF10 = 505 +IH_PERF_SEL_RB2_RPTR_WRAP_VF11 = 506 +IH_PERF_SEL_RB2_RPTR_WRAP_VF12 = 507 +IH_PERF_SEL_RB2_RPTR_WRAP_VF13 = 508 +IH_PERF_SEL_RB2_RPTR_WRAP_VF14 = 509 +IH_PERF_SEL_RB2_RPTR_WRAP_VF15 = 510 +IH_PERF_SEL_RB2_RPTR_WRAP_VF16 = 511 +IH_PERF_SEL_RB2_RPTR_WRAP_VF17 = 512 +IH_PERF_SEL_RB2_RPTR_WRAP_VF18 = 513 +IH_PERF_SEL_RB2_RPTR_WRAP_VF19 = 514 +IH_PERF_SEL_RB2_RPTR_WRAP_VF20 = 515 +IH_PERF_SEL_RB2_RPTR_WRAP_VF21 = 516 +IH_PERF_SEL_RB2_RPTR_WRAP_VF22 = 517 +IH_PERF_SEL_RB2_RPTR_WRAP_VF23 = 518 +IH_PERF_SEL_RB2_RPTR_WRAP_VF24 = 519 +IH_PERF_SEL_RB2_RPTR_WRAP_VF25 = 520 +IH_PERF_SEL_RB2_RPTR_WRAP_VF26 = 521 +IH_PERF_SEL_RB2_RPTR_WRAP_VF27 = 522 +IH_PERF_SEL_RB2_RPTR_WRAP_VF28 = 523 +IH_PERF_SEL_RB2_RPTR_WRAP_VF29 = 524 +IH_PERF_SEL_RB2_RPTR_WRAP_VF30 = 525 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP = 526 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0 = 527 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1 = 528 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2 = 529 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3 = 530 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4 = 531 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5 = 532 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6 = 533 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7 = 534 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8 = 535 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9 = 536 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10 = 537 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11 = 538 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12 = 539 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13 = 540 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14 = 541 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15 = 542 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF16 = 543 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF17 = 544 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF18 = 545 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF19 = 546 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF20 = 547 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF21 = 548 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF22 = 549 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF23 = 550 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF24 = 551 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF25 = 552 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF26 = 553 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF27 = 554 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF28 = 555 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF29 = 556 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF30 = 557 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP = 558 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0 = 559 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1 = 560 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2 = 561 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3 = 562 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4 = 563 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5 = 564 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6 = 565 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7 = 566 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8 = 567 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9 = 568 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10 = 569 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11 = 570 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12 = 571 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13 = 572 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14 = 573 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15 = 574 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF16 = 575 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF17 = 576 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF18 = 577 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF19 = 578 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF20 = 579 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF21 = 580 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF22 = 581 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF23 = 582 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF24 = 583 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF25 = 584 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF26 = 585 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF27 = 586 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF28 = 587 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF29 = 588 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF30 = 589 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP = 590 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0 = 591 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1 = 592 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2 = 593 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3 = 594 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4 = 595 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5 = 596 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6 = 597 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7 = 598 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8 = 599 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9 = 600 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10 = 601 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11 = 602 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12 = 603 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13 = 604 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14 = 605 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15 = 606 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF16 = 607 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF17 = 608 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF18 = 609 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF19 = 610 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF20 = 611 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF21 = 612 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF22 = 613 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF23 = 614 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF24 = 615 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF25 = 616 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF26 = 617 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF27 = 618 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF28 = 619 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF29 = 620 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF30 = 621 +IH_PERF_SEL_RB0_LOAD_RPTR = 622 +IH_PERF_SEL_RB0_LOAD_RPTR_VF0 = 623 +IH_PERF_SEL_RB0_LOAD_RPTR_VF1 = 624 +IH_PERF_SEL_RB0_LOAD_RPTR_VF2 = 625 +IH_PERF_SEL_RB0_LOAD_RPTR_VF3 = 626 +IH_PERF_SEL_RB0_LOAD_RPTR_VF4 = 627 +IH_PERF_SEL_RB0_LOAD_RPTR_VF5 = 628 +IH_PERF_SEL_RB0_LOAD_RPTR_VF6 = 629 +IH_PERF_SEL_RB0_LOAD_RPTR_VF7 = 630 +IH_PERF_SEL_RB0_LOAD_RPTR_VF8 = 631 +IH_PERF_SEL_RB0_LOAD_RPTR_VF9 = 632 +IH_PERF_SEL_RB0_LOAD_RPTR_VF10 = 633 +IH_PERF_SEL_RB0_LOAD_RPTR_VF11 = 634 +IH_PERF_SEL_RB0_LOAD_RPTR_VF12 = 635 +IH_PERF_SEL_RB0_LOAD_RPTR_VF13 = 636 +IH_PERF_SEL_RB0_LOAD_RPTR_VF14 = 637 +IH_PERF_SEL_RB0_LOAD_RPTR_VF15 = 638 +IH_PERF_SEL_RB0_LOAD_RPTR_VF16 = 639 +IH_PERF_SEL_RB0_LOAD_RPTR_VF17 = 640 +IH_PERF_SEL_RB0_LOAD_RPTR_VF18 = 641 +IH_PERF_SEL_RB0_LOAD_RPTR_VF19 = 642 +IH_PERF_SEL_RB0_LOAD_RPTR_VF20 = 643 +IH_PERF_SEL_RB0_LOAD_RPTR_VF21 = 644 +IH_PERF_SEL_RB0_LOAD_RPTR_VF22 = 645 +IH_PERF_SEL_RB0_LOAD_RPTR_VF23 = 646 +IH_PERF_SEL_RB0_LOAD_RPTR_VF24 = 647 +IH_PERF_SEL_RB0_LOAD_RPTR_VF25 = 648 +IH_PERF_SEL_RB0_LOAD_RPTR_VF26 = 649 +IH_PERF_SEL_RB0_LOAD_RPTR_VF27 = 650 +IH_PERF_SEL_RB0_LOAD_RPTR_VF28 = 651 +IH_PERF_SEL_RB0_LOAD_RPTR_VF29 = 652 +IH_PERF_SEL_RB0_LOAD_RPTR_VF30 = 653 +IH_PERF_SEL_RB1_LOAD_RPTR = 654 +IH_PERF_SEL_RB1_LOAD_RPTR_VF0 = 655 +IH_PERF_SEL_RB1_LOAD_RPTR_VF1 = 656 +IH_PERF_SEL_RB1_LOAD_RPTR_VF2 = 657 +IH_PERF_SEL_RB1_LOAD_RPTR_VF3 = 658 +IH_PERF_SEL_RB1_LOAD_RPTR_VF4 = 659 +IH_PERF_SEL_RB1_LOAD_RPTR_VF5 = 660 +IH_PERF_SEL_RB1_LOAD_RPTR_VF6 = 661 +IH_PERF_SEL_RB1_LOAD_RPTR_VF7 = 662 +IH_PERF_SEL_RB1_LOAD_RPTR_VF8 = 663 +IH_PERF_SEL_RB1_LOAD_RPTR_VF9 = 664 +IH_PERF_SEL_RB1_LOAD_RPTR_VF10 = 665 +IH_PERF_SEL_RB1_LOAD_RPTR_VF11 = 666 +IH_PERF_SEL_RB1_LOAD_RPTR_VF12 = 667 +IH_PERF_SEL_RB1_LOAD_RPTR_VF13 = 668 +IH_PERF_SEL_RB1_LOAD_RPTR_VF14 = 669 +IH_PERF_SEL_RB1_LOAD_RPTR_VF15 = 670 +IH_PERF_SEL_RB1_LOAD_RPTR_VF16 = 671 +IH_PERF_SEL_RB1_LOAD_RPTR_VF17 = 672 +IH_PERF_SEL_RB1_LOAD_RPTR_VF18 = 673 +IH_PERF_SEL_RB1_LOAD_RPTR_VF19 = 674 +IH_PERF_SEL_RB1_LOAD_RPTR_VF20 = 675 +IH_PERF_SEL_RB1_LOAD_RPTR_VF21 = 676 +IH_PERF_SEL_RB1_LOAD_RPTR_VF22 = 677 +IH_PERF_SEL_RB1_LOAD_RPTR_VF23 = 678 +IH_PERF_SEL_RB1_LOAD_RPTR_VF24 = 679 +IH_PERF_SEL_RB1_LOAD_RPTR_VF25 = 680 +IH_PERF_SEL_RB1_LOAD_RPTR_VF26 = 681 +IH_PERF_SEL_RB1_LOAD_RPTR_VF27 = 682 +IH_PERF_SEL_RB1_LOAD_RPTR_VF28 = 683 +IH_PERF_SEL_RB1_LOAD_RPTR_VF29 = 684 +IH_PERF_SEL_RB1_LOAD_RPTR_VF30 = 685 +IH_PERF_SEL_RB2_LOAD_RPTR = 686 +IH_PERF_SEL_RB2_LOAD_RPTR_VF0 = 687 +IH_PERF_SEL_RB2_LOAD_RPTR_VF1 = 688 +IH_PERF_SEL_RB2_LOAD_RPTR_VF2 = 689 +IH_PERF_SEL_RB2_LOAD_RPTR_VF3 = 690 +IH_PERF_SEL_RB2_LOAD_RPTR_VF4 = 691 +IH_PERF_SEL_RB2_LOAD_RPTR_VF5 = 692 +IH_PERF_SEL_RB2_LOAD_RPTR_VF6 = 693 +IH_PERF_SEL_RB2_LOAD_RPTR_VF7 = 694 +IH_PERF_SEL_RB2_LOAD_RPTR_VF8 = 695 +IH_PERF_SEL_RB2_LOAD_RPTR_VF9 = 696 +IH_PERF_SEL_RB2_LOAD_RPTR_VF10 = 697 +IH_PERF_SEL_RB2_LOAD_RPTR_VF11 = 698 +IH_PERF_SEL_RB2_LOAD_RPTR_VF12 = 699 +IH_PERF_SEL_RB2_LOAD_RPTR_VF13 = 700 +IH_PERF_SEL_RB2_LOAD_RPTR_VF14 = 701 +IH_PERF_SEL_RB2_LOAD_RPTR_VF15 = 702 +IH_PERF_SEL_RB2_LOAD_RPTR_VF16 = 703 +IH_PERF_SEL_RB2_LOAD_RPTR_VF17 = 704 +IH_PERF_SEL_RB2_LOAD_RPTR_VF18 = 705 +IH_PERF_SEL_RB2_LOAD_RPTR_VF19 = 706 +IH_PERF_SEL_RB2_LOAD_RPTR_VF20 = 707 +IH_PERF_SEL_RB2_LOAD_RPTR_VF21 = 708 +IH_PERF_SEL_RB2_LOAD_RPTR_VF22 = 709 +IH_PERF_SEL_RB2_LOAD_RPTR_VF23 = 710 +IH_PERF_SEL_RB2_LOAD_RPTR_VF24 = 711 +IH_PERF_SEL_RB2_LOAD_RPTR_VF25 = 712 +IH_PERF_SEL_RB2_LOAD_RPTR_VF26 = 713 +IH_PERF_SEL_RB2_LOAD_RPTR_VF27 = 714 +IH_PERF_SEL_RB2_LOAD_RPTR_VF28 = 715 +IH_PERF_SEL_RB2_LOAD_RPTR_VF29 = 716 +IH_PERF_SEL_RB2_LOAD_RPTR_VF30 = 717 +IH_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'IH_CLIENT_TYPE' +IH_CLIENT_TYPE__enumvalues = { + 0: 'IH_GFX_VMID_CLIENT', + 1: 'IH_MM_VMID_CLIENT', + 2: 'IH_MULTI_VMID_CLIENT', + 3: 'IH_CLIENT_TYPE_RESERVED', +} +IH_GFX_VMID_CLIENT = 0 +IH_MM_VMID_CLIENT = 1 +IH_MULTI_VMID_CLIENT = 2 +IH_CLIENT_TYPE_RESERVED = 3 +IH_CLIENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'IH_RING_ID' +IH_RING_ID__enumvalues = { + 0: 'IH_RING_ID_INTERRUPT', + 1: 'IH_RING_ID_REQUEST', + 2: 'IH_RING_ID_TRANSLATION', + 3: 'IH_RING_ID_RESERVED', +} +IH_RING_ID_INTERRUPT = 0 +IH_RING_ID_REQUEST = 1 +IH_RING_ID_TRANSLATION = 2 +IH_RING_ID_RESERVED = 3 +IH_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'IH_VF_RB_SELECT' +IH_VF_RB_SELECT__enumvalues = { + 0: 'IH_VF_RB_SELECT_CLIENT_FCN_ID', + 1: 'IH_VF_RB_SELECT_IH_FCN_ID', + 2: 'IH_VF_RB_SELECT_PF', + 3: 'IH_VF_RB_SELECT_RESERVED', +} +IH_VF_RB_SELECT_CLIENT_FCN_ID = 0 +IH_VF_RB_SELECT_IH_FCN_ID = 1 +IH_VF_RB_SELECT_PF = 2 +IH_VF_RB_SELECT_RESERVED = 3 +IH_VF_RB_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'IH_INTERFACE_TYPE' +IH_INTERFACE_TYPE__enumvalues = { + 0: 'IH_LEGACY_INTERFACE', + 1: 'IH_REGISTER_WRITE_INTERFACE', +} +IH_LEGACY_INTERFACE = 0 +IH_REGISTER_WRITE_INTERFACE = 1 +IH_INTERFACE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SEM_PERF_SEL' +SEM_PERF_SEL__enumvalues = { + 0: 'SEM_PERF_SEL_CYCLE', + 1: 'SEM_PERF_SEL_IDLE', + 2: 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', + 3: 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', + 4: 'SEM_PERF_SEL_UVD_REQ_SIGNAL', + 5: 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', + 6: 'SEM_PERF_SEL_ACP_REQ_SIGNAL', + 7: 'SEM_PERF_SEL_ISP_REQ_SIGNAL', + 8: 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', + 9: 'SEM_PERF_SEL_VP8_REQ_SIGNAL', + 10: 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', + 11: 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', + 12: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 13: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 14: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 15: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 16: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 17: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 18: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 19: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 20: 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 21: 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 22: 'SEM_PERF_SEL_UVD_REQ_WAIT', + 23: 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 24: 'SEM_PERF_SEL_ACP_REQ_WAIT', + 25: 'SEM_PERF_SEL_ISP_REQ_WAIT', + 26: 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 27: 'SEM_PERF_SEL_VP8_REQ_WAIT', + 28: 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 29: 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 30: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 31: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 32: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 33: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 34: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 35: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 36: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 37: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 38: 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 39: 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 40: 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 41: 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 42: 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 43: 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 44: 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 45: 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 46: 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 47: 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 48: 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 49: 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 50: 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 51: 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 52: 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 53: 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 54: 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 55: 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 56: 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 57: 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 58: 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 59: 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 60: 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 61: 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 62: 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 63: 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 64: 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 65: 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 66: 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 67: 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 68: 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 69: 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 70: 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 71: 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 72: 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 73: 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 74: 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 75: 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 76: 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 77: 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 78: 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 79: 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 80: 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 81: 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 82: 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 83: 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 84: 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 85: 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 86: 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 87: 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 88: 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 89: 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 90: 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 91: 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 92: 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 93: 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 94: 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 95: 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 96: 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 97: 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 98: 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 99: 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 100: 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 101: 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 102: 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 103: 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 104: 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 105: 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 106: 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 107: 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 108: 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 109: 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 110: 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 111: 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 112: 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 113: 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 114: 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 115: 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 116: 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 117: 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 118: 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 119: 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 120: 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 121: 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 122: 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 123: 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 124: 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 125: 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 126: 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 127: 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 128: 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 129: 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 130: 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 131: 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 132: 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 133: 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 134: 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 135: 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 136: 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 137: 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 138: 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 139: 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 140: 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 141: 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 142: 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 143: 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 144: 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 145: 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 146: 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 147: 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 148: 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 149: 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 150: 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 151: 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 152: 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 153: 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 154: 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 155: 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 156: 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 157: 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 158: 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 159: 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 160: 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 161: 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 162: 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 163: 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 164: 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 165: 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 166: 'SEM_PERF_SEL_MC_RD_REQ', + 167: 'SEM_PERF_SEL_MC_RD_RET', + 168: 'SEM_PERF_SEL_MC_WR_REQ', + 169: 'SEM_PERF_SEL_MC_WR_RET', + 170: 'SEM_PERF_SEL_ATC_REQ', + 171: 'SEM_PERF_SEL_ATC_RET', + 172: 'SEM_PERF_SEL_ATC_XNACK', + 173: 'SEM_PERF_SEL_ATC_INVALIDATION', + 174: 'SEM_PERF_SEL_ATC_VM_INVALIDATION', +} +SEM_PERF_SEL_CYCLE = 0 +SEM_PERF_SEL_IDLE = 1 +SEM_PERF_SEL_SDMA0_REQ_SIGNAL = 2 +SEM_PERF_SEL_SDMA1_REQ_SIGNAL = 3 +SEM_PERF_SEL_UVD_REQ_SIGNAL = 4 +SEM_PERF_SEL_VCE0_REQ_SIGNAL = 5 +SEM_PERF_SEL_ACP_REQ_SIGNAL = 6 +SEM_PERF_SEL_ISP_REQ_SIGNAL = 7 +SEM_PERF_SEL_VCE1_REQ_SIGNAL = 8 +SEM_PERF_SEL_VP8_REQ_SIGNAL = 9 +SEM_PERF_SEL_CPG_E0_REQ_SIGNAL = 10 +SEM_PERF_SEL_CPG_E1_REQ_SIGNAL = 11 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL = 12 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL = 13 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL = 14 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL = 15 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL = 16 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL = 17 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL = 18 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL = 19 +SEM_PERF_SEL_SDMA0_REQ_WAIT = 20 +SEM_PERF_SEL_SDMA1_REQ_WAIT = 21 +SEM_PERF_SEL_UVD_REQ_WAIT = 22 +SEM_PERF_SEL_VCE0_REQ_WAIT = 23 +SEM_PERF_SEL_ACP_REQ_WAIT = 24 +SEM_PERF_SEL_ISP_REQ_WAIT = 25 +SEM_PERF_SEL_VCE1_REQ_WAIT = 26 +SEM_PERF_SEL_VP8_REQ_WAIT = 27 +SEM_PERF_SEL_CPG_E0_REQ_WAIT = 28 +SEM_PERF_SEL_CPG_E1_REQ_WAIT = 29 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT = 30 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT = 31 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT = 32 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT = 33 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT = 34 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT = 35 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT = 36 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT = 37 +SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT = 38 +SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT = 39 +SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT = 40 +SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT = 41 +SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT = 42 +SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT = 43 +SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT = 44 +SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT = 45 +SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT = 46 +SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT = 47 +SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT = 48 +SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT = 49 +SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT = 50 +SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT = 51 +SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT = 52 +SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT = 53 +SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT = 54 +SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT = 55 +SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT = 56 +SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT = 57 +SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT = 58 +SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT = 59 +SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT = 60 +SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT = 61 +SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT = 62 +SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT = 63 +SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT = 64 +SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT = 65 +SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT = 66 +SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT = 67 +SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT = 68 +SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT = 69 +SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT = 70 +SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT = 71 +SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT = 72 +SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT = 73 +SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT = 74 +SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT = 75 +SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT = 76 +SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT = 77 +SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT = 78 +SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT = 79 +SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT = 80 +SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT = 81 +SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT = 82 +SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT = 83 +SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT = 84 +SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT = 85 +SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT = 86 +SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT = 87 +SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT = 88 +SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT = 89 +SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT = 90 +SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT = 91 +SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT = 92 +SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT = 93 +SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT = 94 +SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT = 95 +SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT = 96 +SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT = 97 +SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT = 98 +SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT = 99 +SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT = 100 +SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT = 101 +SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT = 102 +SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT = 103 +SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT = 104 +SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT = 105 +SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT = 106 +SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT = 107 +SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT = 108 +SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT = 109 +SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT = 110 +SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT = 111 +SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT = 112 +SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT = 113 +SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT = 114 +SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT = 115 +SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT = 116 +SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT = 117 +SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT = 118 +SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT = 119 +SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT = 120 +SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT = 121 +SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT = 122 +SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT = 123 +SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT = 124 +SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT = 125 +SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT = 126 +SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT = 127 +SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT = 128 +SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT = 129 +SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT = 130 +SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT = 131 +SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT = 132 +SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT = 133 +SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT = 134 +SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT = 135 +SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT = 136 +SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT = 137 +SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT = 138 +SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT = 139 +SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT = 140 +SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT = 141 +SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT = 142 +SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT = 143 +SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT = 144 +SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT = 145 +SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT = 146 +SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT = 147 +SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT = 148 +SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT = 149 +SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT = 150 +SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT = 151 +SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT = 152 +SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT = 153 +SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT = 154 +SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT = 155 +SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT = 156 +SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT = 157 +SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT = 158 +SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT = 159 +SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT = 160 +SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT = 161 +SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT = 162 +SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT = 163 +SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT = 164 +SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT = 165 +SEM_PERF_SEL_MC_RD_REQ = 166 +SEM_PERF_SEL_MC_RD_RET = 167 +SEM_PERF_SEL_MC_WR_REQ = 168 +SEM_PERF_SEL_MC_WR_RET = 169 +SEM_PERF_SEL_ATC_REQ = 170 +SEM_PERF_SEL_ATC_RET = 171 +SEM_PERF_SEL_ATC_XNACK = 172 +SEM_PERF_SEL_ATC_INVALIDATION = 173 +SEM_PERF_SEL_ATC_VM_INVALIDATION = 174 +SEM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'EFC_SURFACE_PIXEL_FORMAT' +EFC_SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'EFC_ARGB1555', + 2: 'EFC_RGBA5551', + 3: 'EFC_RGB565', + 4: 'EFC_BGR565', + 5: 'EFC_ARGB4444', + 6: 'EFC_RGBA4444', + 8: 'EFC_ARGB8888', + 9: 'EFC_RGBA8888', + 10: 'EFC_ARGB2101010', + 11: 'EFC_RGBA1010102', + 12: 'EFC_AYCrCb8888', + 13: 'EFC_YCrCbA8888', + 14: 'EFC_ACrYCb8888', + 15: 'EFC_CrYCbA8888', + 16: 'EFC_ARGB16161616_10MSB', + 17: 'EFC_RGBA16161616_10MSB', + 18: 'EFC_ARGB16161616_10LSB', + 19: 'EFC_RGBA16161616_10LSB', + 20: 'EFC_ARGB16161616_12MSB', + 21: 'EFC_RGBA16161616_12MSB', + 22: 'EFC_ARGB16161616_12LSB', + 23: 'EFC_RGBA16161616_12LSB', + 24: 'EFC_ARGB16161616_FLOAT', + 25: 'EFC_RGBA16161616_FLOAT', + 26: 'EFC_ARGB16161616_UNORM', + 27: 'EFC_RGBA16161616_UNORM', + 28: 'EFC_ARGB16161616_SNORM', + 29: 'EFC_RGBA16161616_SNORM', + 32: 'EFC_AYCrCb16161616_10MSB', + 33: 'EFC_AYCrCb16161616_10LSB', + 34: 'EFC_YCrCbA16161616_10MSB', + 35: 'EFC_YCrCbA16161616_10LSB', + 36: 'EFC_ACrYCb16161616_10MSB', + 37: 'EFC_ACrYCb16161616_10LSB', + 38: 'EFC_CrYCbA16161616_10MSB', + 39: 'EFC_CrYCbA16161616_10LSB', + 40: 'EFC_AYCrCb16161616_12MSB', + 41: 'EFC_AYCrCb16161616_12LSB', + 42: 'EFC_YCrCbA16161616_12MSB', + 43: 'EFC_YCrCbA16161616_12LSB', + 44: 'EFC_ACrYCb16161616_12MSB', + 45: 'EFC_ACrYCb16161616_12LSB', + 46: 'EFC_CrYCbA16161616_12MSB', + 47: 'EFC_CrYCbA16161616_12LSB', + 64: 'EFC_Y8_CrCb88_420_PLANAR', + 65: 'EFC_Y8_CbCr88_420_PLANAR', + 66: 'EFC_Y10_CrCb1010_420_PLANAR', + 67: 'EFC_Y10_CbCr1010_420_PLANAR', + 68: 'EFC_Y12_CrCb1212_420_PLANAR', + 69: 'EFC_Y12_CbCr1212_420_PLANAR', + 72: 'EFC_YCrYCb8888_422_PACKED', + 73: 'EFC_YCbYCr8888_422_PACKED', + 74: 'EFC_CrYCbY8888_422_PACKED', + 75: 'EFC_CbYCrY8888_422_PACKED', + 76: 'EFC_YCrYCb10101010_422_PACKED', + 77: 'EFC_YCbYCr10101010_422_PACKED', + 78: 'EFC_CrYCbY10101010_422_PACKED', + 79: 'EFC_CbYCrY10101010_422_PACKED', + 80: 'EFC_YCrYCb12121212_422_PACKED', + 81: 'EFC_YCbYCr12121212_422_PACKED', + 82: 'EFC_CrYCbY12121212_422_PACKED', + 83: 'EFC_CbYCrY12121212_422_PACKED', + 112: 'EFC_RGB111110_FIX', + 113: 'EFC_BGR101111_FIX', + 114: 'EFC_ACrYCb2101010', + 115: 'EFC_CrYCbA1010102', + 118: 'EFC_RGB111110_FLOAT', + 119: 'EFC_BGR101111_FLOAT', + 120: 'EFC_MONO_8', + 121: 'EFC_MONO_10MSB', + 122: 'EFC_MONO_10LSB', + 123: 'EFC_MONO_12MSB', + 124: 'EFC_MONO_12LSB', + 125: 'EFC_MONO_16', +} +EFC_ARGB1555 = 1 +EFC_RGBA5551 = 2 +EFC_RGB565 = 3 +EFC_BGR565 = 4 +EFC_ARGB4444 = 5 +EFC_RGBA4444 = 6 +EFC_ARGB8888 = 8 +EFC_RGBA8888 = 9 +EFC_ARGB2101010 = 10 +EFC_RGBA1010102 = 11 +EFC_AYCrCb8888 = 12 +EFC_YCrCbA8888 = 13 +EFC_ACrYCb8888 = 14 +EFC_CrYCbA8888 = 15 +EFC_ARGB16161616_10MSB = 16 +EFC_RGBA16161616_10MSB = 17 +EFC_ARGB16161616_10LSB = 18 +EFC_RGBA16161616_10LSB = 19 +EFC_ARGB16161616_12MSB = 20 +EFC_RGBA16161616_12MSB = 21 +EFC_ARGB16161616_12LSB = 22 +EFC_RGBA16161616_12LSB = 23 +EFC_ARGB16161616_FLOAT = 24 +EFC_RGBA16161616_FLOAT = 25 +EFC_ARGB16161616_UNORM = 26 +EFC_RGBA16161616_UNORM = 27 +EFC_ARGB16161616_SNORM = 28 +EFC_RGBA16161616_SNORM = 29 +EFC_AYCrCb16161616_10MSB = 32 +EFC_AYCrCb16161616_10LSB = 33 +EFC_YCrCbA16161616_10MSB = 34 +EFC_YCrCbA16161616_10LSB = 35 +EFC_ACrYCb16161616_10MSB = 36 +EFC_ACrYCb16161616_10LSB = 37 +EFC_CrYCbA16161616_10MSB = 38 +EFC_CrYCbA16161616_10LSB = 39 +EFC_AYCrCb16161616_12MSB = 40 +EFC_AYCrCb16161616_12LSB = 41 +EFC_YCrCbA16161616_12MSB = 42 +EFC_YCrCbA16161616_12LSB = 43 +EFC_ACrYCb16161616_12MSB = 44 +EFC_ACrYCb16161616_12LSB = 45 +EFC_CrYCbA16161616_12MSB = 46 +EFC_CrYCbA16161616_12LSB = 47 +EFC_Y8_CrCb88_420_PLANAR = 64 +EFC_Y8_CbCr88_420_PLANAR = 65 +EFC_Y10_CrCb1010_420_PLANAR = 66 +EFC_Y10_CbCr1010_420_PLANAR = 67 +EFC_Y12_CrCb1212_420_PLANAR = 68 +EFC_Y12_CbCr1212_420_PLANAR = 69 +EFC_YCrYCb8888_422_PACKED = 72 +EFC_YCbYCr8888_422_PACKED = 73 +EFC_CrYCbY8888_422_PACKED = 74 +EFC_CbYCrY8888_422_PACKED = 75 +EFC_YCrYCb10101010_422_PACKED = 76 +EFC_YCbYCr10101010_422_PACKED = 77 +EFC_CrYCbY10101010_422_PACKED = 78 +EFC_CbYCrY10101010_422_PACKED = 79 +EFC_YCrYCb12121212_422_PACKED = 80 +EFC_YCbYCr12121212_422_PACKED = 81 +EFC_CrYCbY12121212_422_PACKED = 82 +EFC_CbYCrY12121212_422_PACKED = 83 +EFC_RGB111110_FIX = 112 +EFC_BGR101111_FIX = 113 +EFC_ACrYCb2101010 = 114 +EFC_CrYCbA1010102 = 115 +EFC_RGB111110_FLOAT = 118 +EFC_BGR101111_FLOAT = 119 +EFC_MONO_8 = 120 +EFC_MONO_10MSB = 121 +EFC_MONO_10LSB = 122 +EFC_MONO_12MSB = 123 +EFC_MONO_12LSB = 124 +EFC_MONO_16 = 125 +EFC_SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'UVDFirmwareCommand' +UVDFirmwareCommand__enumvalues = { + 0: 'UVDFC_FENCE', + 1: 'UVDFC_TRAP', + 2: 'UVDFC_DECODED_ADDR', + 3: 'UVDFC_MBLOCK_ADDR', + 4: 'UVDFC_ITBUF_ADDR', + 5: 'UVDFC_DISPLAY_ADDR', + 6: 'UVDFC_EOD', + 7: 'UVDFC_DISPLAY_PITCH', + 8: 'UVDFC_DISPLAY_TILING', + 9: 'UVDFC_BITSTREAM_ADDR', + 10: 'UVDFC_BITSTREAM_SIZE', +} +UVDFC_FENCE = 0 +UVDFC_TRAP = 1 +UVDFC_DECODED_ADDR = 2 +UVDFC_MBLOCK_ADDR = 3 +UVDFC_ITBUF_ADDR = 4 +UVDFC_DISPLAY_ADDR = 5 +UVDFC_EOD = 6 +UVDFC_DISPLAY_PITCH = 7 +UVDFC_DISPLAY_TILING = 8 +UVDFC_BITSTREAM_ADDR = 9 +UVDFC_BITSTREAM_SIZE = 10 +UVDFirmwareCommand = ctypes.c_uint32 # enum +__all__ = \ + ['ABGR_TO_A_BG_G_RB', 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', + 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', 'ACrYCb16161616_10LSB', + 'ACrYCb16161616_10MSB', 'ACrYCb16161616_12LSB', + 'ACrYCb16161616_12MSB', 'ACrYCb2101010', 'ACrYCb8888', + 'ADDR_CONFIG_16_BANK', 'ADDR_CONFIG_16_PIPE', + 'ADDR_CONFIG_1KB_ROW', 'ADDR_CONFIG_1_BANK', 'ADDR_CONFIG_1_GPU', + 'ADDR_CONFIG_1_LOWER_PIPES', + 'ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_1_PIPE', + 'ADDR_CONFIG_1_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_1_SHADER_ENGINE', 'ADDR_CONFIG_2KB_ROW', + 'ADDR_CONFIG_2_BANK', 'ADDR_CONFIG_2_GPU', + 'ADDR_CONFIG_2_LOWER_PIPES', + 'ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_2_PIPE', + 'ADDR_CONFIG_2_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_2_SHADER_ENGINE', 'ADDR_CONFIG_32_PIPE', + 'ADDR_CONFIG_4KB_ROW', 'ADDR_CONFIG_4_BANK', 'ADDR_CONFIG_4_GPU', + 'ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_4_PIPE', + 'ADDR_CONFIG_4_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_4_SHADER_ENGINE', 'ADDR_CONFIG_64_PIPE', + 'ADDR_CONFIG_8_BANK', 'ADDR_CONFIG_8_GPU', + 'ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_8_PIPE', + 'ADDR_CONFIG_8_SHADER_ENGINE', 'ADDR_CONFIG_BANK_INTERLEAVE_1', + 'ADDR_CONFIG_BANK_INTERLEAVE_2', 'ADDR_CONFIG_BANK_INTERLEAVE_4', + 'ADDR_CONFIG_BANK_INTERLEAVE_8', 'ADDR_CONFIG_DISABLE_SE', + 'ADDR_CONFIG_ENABLE_SE', 'ADDR_CONFIG_GPU_TILE_128', + 'ADDR_CONFIG_GPU_TILE_16', 'ADDR_CONFIG_GPU_TILE_32', + 'ADDR_CONFIG_GPU_TILE_64', 'ADDR_CONFIG_PIPE_INTERLEAVE_1KB', + 'ADDR_CONFIG_PIPE_INTERLEAVE_256B', + 'ADDR_CONFIG_PIPE_INTERLEAVE_2KB', + 'ADDR_CONFIG_PIPE_INTERLEAVE_512B', 'ADDR_CONFIG_SE_TILE_16', + 'ADDR_CONFIG_SE_TILE_32', 'ADDR_NUM_BANKS_BC_BANKS_1', + 'ADDR_NUM_BANKS_BC_BANKS_16', 'ADDR_NUM_BANKS_BC_BANKS_2', + 'ADDR_NUM_BANKS_BC_BANKS_4', 'ADDR_NUM_BANKS_BC_BANKS_8', + 'ADDR_NUM_PIPES_BC_P16', 'ADDR_NUM_PIPES_BC_P8', + 'ADDR_SURF_16_BANK', 'ADDR_SURF_2_BANK', 'ADDR_SURF_4_BANK', + 'ADDR_SURF_8_BANK', 'ADDR_SURF_BANK_HEIGHT_1', + 'ADDR_SURF_BANK_HEIGHT_2', 'ADDR_SURF_BANK_HEIGHT_4', + 'ADDR_SURF_BANK_HEIGHT_8', 'ADDR_SURF_BANK_WH_1', + 'ADDR_SURF_BANK_WH_2', 'ADDR_SURF_BANK_WH_4', + 'ADDR_SURF_BANK_WH_8', 'ADDR_SURF_BANK_WIDTH_1', + 'ADDR_SURF_BANK_WIDTH_2', 'ADDR_SURF_BANK_WIDTH_4', + 'ADDR_SURF_BANK_WIDTH_8', 'ADDR_SURF_DEPTH_MICRO_TILING', + 'ADDR_SURF_DISPLAY_MICRO_TILING', 'ADDR_SURF_MACRO_ASPECT_1', + 'ADDR_SURF_MACRO_ASPECT_2', 'ADDR_SURF_MACRO_ASPECT_4', + 'ADDR_SURF_MACRO_ASPECT_8', 'ADDR_SURF_MICRO_TILING_DISPLAY', + 'ADDR_SURF_MICRO_TILING_NON_DISPLAY', 'ADDR_SURF_P16', + 'ADDR_SURF_P16_32x32_16x16', 'ADDR_SURF_P16_32x32_8x16', + 'ADDR_SURF_P2', 'ADDR_SURF_P2_RESERVED0', + 'ADDR_SURF_P2_RESERVED1', 'ADDR_SURF_P2_RESERVED2', + 'ADDR_SURF_P4_16x16', 'ADDR_SURF_P4_16x32', 'ADDR_SURF_P4_32x32', + 'ADDR_SURF_P4_8x16', 'ADDR_SURF_P8_16x16_8x16', + 'ADDR_SURF_P8_16x32_16x16', 'ADDR_SURF_P8_16x32_8x16', + 'ADDR_SURF_P8_32x32_16x16', 'ADDR_SURF_P8_32x32_16x32', + 'ADDR_SURF_P8_32x32_8x16', 'ADDR_SURF_P8_32x64_32x32', + 'ADDR_SURF_P8_RESERVED0', 'ADDR_SURF_ROTATED_MICRO_TILING', + 'ADDR_SURF_SAMPLE_SPLIT_1', 'ADDR_SURF_SAMPLE_SPLIT_2', + 'ADDR_SURF_SAMPLE_SPLIT_4', 'ADDR_SURF_SAMPLE_SPLIT_8', + 'ADDR_SURF_THICK_MICRO_TILING', 'ADDR_SURF_THIN_MICRO_TILING', + 'ADDR_SURF_TILE_SPLIT_128B', 'ADDR_SURF_TILE_SPLIT_1KB', + 'ADDR_SURF_TILE_SPLIT_256B', 'ADDR_SURF_TILE_SPLIT_2KB', + 'ADDR_SURF_TILE_SPLIT_4KB', 'ADDR_SURF_TILE_SPLIT_512B', + 'ADDR_SURF_TILE_SPLIT_64B', 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', + 'AFMT_AUDIO_CRC_AUTO_RESTART', 'AFMT_AUDIO_CRC_CH0_SIG', + 'AFMT_AUDIO_CRC_CH1_SIG', 'AFMT_AUDIO_CRC_CH2_SIG', + 'AFMT_AUDIO_CRC_CH3_SIG', 'AFMT_AUDIO_CRC_CH4_SIG', + 'AFMT_AUDIO_CRC_CH5_SIG', 'AFMT_AUDIO_CRC_CH6_SIG', + 'AFMT_AUDIO_CRC_CH7_SIG', 'AFMT_AUDIO_CRC_CONTROL_CH_SEL', + 'AFMT_AUDIO_CRC_CONTROL_CONT', 'AFMT_AUDIO_CRC_CONTROL_SOURCE', + 'AFMT_AUDIO_CRC_ONESHOT', 'AFMT_AUDIO_CRC_RESERVED_10', + 'AFMT_AUDIO_CRC_RESERVED_11', 'AFMT_AUDIO_CRC_RESERVED_12', + 'AFMT_AUDIO_CRC_RESERVED_13', 'AFMT_AUDIO_CRC_RESERVED_14', + 'AFMT_AUDIO_CRC_RESERVED_8', 'AFMT_AUDIO_CRC_RESERVED_9', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', + 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', + 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD', + 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND', + 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS', + 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 'AFMT_AUDIO_PACKET_SENT_ENABLED', 'AFMT_AUDIO_SRC_CONTROL_SELECT', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', 'AFMT_AUDIO_SRC_RESERVED', + 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE', + 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 'AFMT_INTERRUPT_DISABLE', 'AFMT_INTERRUPT_ENABLE', + 'AFMT_INTERRUPT_STATUS_CHG_MASK', + 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 'AFMT_RAMP_CONTROL0_SIGN', 'AFMT_RAMP_SIGNED', + 'AFMT_RAMP_UNSIGNED', 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', + 'AFMT_VBI_GSP0_INDEX', 'AFMT_VBI_GSP10_INDEX', + 'AFMT_VBI_GSP1_INDEX', 'AFMT_VBI_GSP2_INDEX', + 'AFMT_VBI_GSP3_INDEX', 'AFMT_VBI_GSP4_INDEX', + 'AFMT_VBI_GSP5_INDEX', 'AFMT_VBI_GSP6_INDEX', + 'AFMT_VBI_GSP7_INDEX', 'AFMT_VBI_GSP8_INDEX', + 'AFMT_VBI_GSP9_INDEX', 'AFMT_VBI_GSP_INDEX', + 'ALLOW_SR_ON_TRANS_REQ', 'ALLOW_SR_ON_TRANS_REQ_DISABLE', + 'ALLOW_SR_ON_TRANS_REQ_ENABLE', 'ALPHA_DATA_ON_ALPHA_PORT', + 'ALPHA_DATA_ON_CB_B_PORT', 'ALPHA_DATA_ON_CR_R_PORT', + 'ALPHA_DATA_ON_Y_G_PORT', 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', 'AM_1D_TILED_THICK', + 'AM_1D_TILED_THIN1', 'AM_2D_TILED_THICK', 'AM_2D_TILED_THIN1', + 'AM_2D_TILED_XTHICK', 'AM_3D_TILED_THICK', 'AM_3D_TILED_THIN1', + 'AM_3D_TILED_XTHICK', 'AM_LINEAR_ALIGNED', 'AM_LINEAR_GENERAL', + 'AM_PRT_2D_TILED_THICK', 'AM_PRT_2D_TILED_THIN1', + 'AM_PRT_3D_TILED_THICK', 'AM_PRT_3D_TILED_THIN1', + 'AM_PRT_TILED_THICK', 'AM_PRT_TILED_THIN1', 'ARGB1555', + 'ARGB16161616_10LSB', 'ARGB16161616_10MSB', 'ARGB16161616_12LSB', + 'ARGB16161616_12MSB', 'ARGB16161616_FLOAT', 'ARGB16161616_SNORM', + 'ARGB16161616_UNORM', 'ARGB2101010', 'ARGB4444', 'ARGB8888', + 'ARRAY_1D', 'ARRAY_1D_TILED_THICK', 'ARRAY_1D_TILED_THIN1', + 'ARRAY_2D', 'ARRAY_2D_ALT_COLOR', 'ARRAY_2D_ALT_DEPTH', + 'ARRAY_2D_COLOR', 'ARRAY_2D_DEPTH', 'ARRAY_2D_TILED_THICK', + 'ARRAY_2D_TILED_THIN1', 'ARRAY_2D_TILED_XTHICK', 'ARRAY_3D', + 'ARRAY_3D_SLICE', 'ARRAY_3D_SLICE_COLOR', 'ARRAY_3D_TILED_THICK', + 'ARRAY_3D_TILED_THIN1', 'ARRAY_3D_TILED_XTHICK', + 'ARRAY_COLOR_TILE', 'ARRAY_DEPTH_TILE', 'ARRAY_LINEAR', + 'ARRAY_LINEAR_ALIGNED', 'ARRAY_LINEAR_GENERAL', 'ARRAY_MODE', + 'ARRAY_PRT_2D_TILED_THICK', 'ARRAY_PRT_2D_TILED_THIN1', + 'ARRAY_PRT_3D_TILED_THICK', 'ARRAY_PRT_3D_TILED_THIN1', + 'ARRAY_PRT_TILED_THICK', 'ARRAY_PRT_TILED_THIN1', 'ARRAY_TILED', + 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', 'AUDIO_LAYOUT_SELECT', + 'AUTOCAL_MODE_AUTOCENTER', 'AUTOCAL_MODE_AUTOREPLICATE', + 'AUTOCAL_MODE_AUTOSCALE', 'AUTOCAL_MODE_OFF', + 'AYCrCb16161616_10LSB', 'AYCrCb16161616_10MSB', + 'AYCrCb16161616_12LSB', 'AYCrCb16161616_12MSB', 'AYCrCb8888', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', + 'AZ_CORB_SIZE', 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 'AZ_CORB_SIZE_256ENTRIES', 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 'AZ_CORB_SIZE_RESERVED', 'AZ_GLOBAL_CAPABILITIES', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', + 'AZ_LATENCY_COUNTER_CONTROL', 'AZ_LATENCY_COUNTER_NO_RESET', + 'AZ_LATENCY_COUNTER_RESET_DONE', 'AZ_RIRB_SIZE', + 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', 'AZ_RIRB_SIZE_256ENTRIES', + 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', 'AZ_RIRB_SIZE_UNDEFINED', + 'AZ_RIRB_WRITE_POINTER_DO_RESET', + 'AZ_RIRB_WRITE_POINTER_NOT_RESET', 'AZ_RIRB_WRITE_POINTER_RESET', + 'AZ_STATE_CHANGE_STATUS', + 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', 'ArrayMode', + 'BANK_HEIGHT', 'BANK_WIDTH', 'BGR101111_FIX', 'BGR101111_FLOAT', + 'BGR565', 'BGRA_TO_BG_G_RB_A', 'BINNER_BREAK_BATCH', + 'BINNER_DROP', 'BINNER_DROP_ASSERT', 'BINNER_PIPELINE', + 'BINNING_ALLOWED', 'BIN_CONF_OVERRIDE_CHECK', 'BIN_MAP_MODE_NONE', + 'BIN_MAP_MODE_POPS', 'BIN_MAP_MODE_RTA_INDEX', + 'BIN_SIZE_128_PIXELS', 'BIN_SIZE_256_PIXELS', + 'BIN_SIZE_32_PIXELS', 'BIN_SIZE_512_PIXELS', 'BIN_SIZE_64_PIXELS', + 'BITS_31_0', 'BITS_32_1', 'BITS_33_2', 'BITS_34_3', 'BITS_35_4', + 'BITS_36_5', 'BITS_37_6', 'BITS_38_7', 'BLEND_BOTH_INV_SRC_ALPHA', + 'BLEND_BOTH_SRC_ALPHA', 'BLEND_CONSTANT_ALPHA', + 'BLEND_CONSTANT_COLOR', 'BLEND_DST_ALPHA', 'BLEND_DST_COLOR', + 'BLEND_INV_SRC1_ALPHA', 'BLEND_INV_SRC1_COLOR', 'BLEND_ONE', + 'BLEND_ONE_MINUS_CONSTANT_ALPHA', + 'BLEND_ONE_MINUS_CONSTANT_COLOR', 'BLEND_ONE_MINUS_DST_ALPHA', + 'BLEND_ONE_MINUS_DST_COLOR', 'BLEND_ONE_MINUS_SRC_ALPHA', + 'BLEND_ONE_MINUS_SRC_COLOR', 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', 'BLEND_SRC1_ALPHA', + 'BLEND_SRC1_COLOR', 'BLEND_SRC_ALPHA', 'BLEND_SRC_ALPHA_SATURATE', + 'BLEND_SRC_COLOR', 'BLEND_ZERO', 'BLOCK_CONTEXT_DONE', 'BOTH_EYE', + 'BOTTOM_OF_PIPE_TS', 'BREAK_BATCH', 'BUF_DATA_FORMAT', + 'BUF_DATA_FORMAT_10_10_10_2', 'BUF_DATA_FORMAT_10_11_11', + 'BUF_DATA_FORMAT_11_11_10', 'BUF_DATA_FORMAT_16', + 'BUF_DATA_FORMAT_16_16', 'BUF_DATA_FORMAT_16_16_16_16', + 'BUF_DATA_FORMAT_2_10_10_10', 'BUF_DATA_FORMAT_32', + 'BUF_DATA_FORMAT_32_32', 'BUF_DATA_FORMAT_32_32_32', + 'BUF_DATA_FORMAT_32_32_32_32', 'BUF_DATA_FORMAT_8', + 'BUF_DATA_FORMAT_8_8', 'BUF_DATA_FORMAT_8_8_8_8', + 'BUF_DATA_FORMAT_INVALID', 'BUF_DATA_FORMAT_RESERVED_15', + 'BUF_FMT', 'BUF_FMT_10_10_10_2_SINT', 'BUF_FMT_10_10_10_2_SNORM', + 'BUF_FMT_10_10_10_2_SSCALED', 'BUF_FMT_10_10_10_2_UINT', + 'BUF_FMT_10_10_10_2_UNORM', 'BUF_FMT_10_10_10_2_USCALED', + 'BUF_FMT_10_11_11_FLOAT', 'BUF_FMT_10_11_11_SINT', + 'BUF_FMT_10_11_11_SNORM', 'BUF_FMT_10_11_11_SSCALED', + 'BUF_FMT_10_11_11_UINT', 'BUF_FMT_10_11_11_UNORM', + 'BUF_FMT_10_11_11_USCALED', 'BUF_FMT_11_11_10_FLOAT', + 'BUF_FMT_11_11_10_SINT', 'BUF_FMT_11_11_10_SNORM', + 'BUF_FMT_11_11_10_SSCALED', 'BUF_FMT_11_11_10_UINT', + 'BUF_FMT_11_11_10_UNORM', 'BUF_FMT_11_11_10_USCALED', + 'BUF_FMT_16_16_16_16_FLOAT', 'BUF_FMT_16_16_16_16_SINT', + 'BUF_FMT_16_16_16_16_SNORM', 'BUF_FMT_16_16_16_16_SSCALED', + 'BUF_FMT_16_16_16_16_UINT', 'BUF_FMT_16_16_16_16_UNORM', + 'BUF_FMT_16_16_16_16_USCALED', 'BUF_FMT_16_16_FLOAT', + 'BUF_FMT_16_16_SINT', 'BUF_FMT_16_16_SNORM', + 'BUF_FMT_16_16_SSCALED', 'BUF_FMT_16_16_UINT', + 'BUF_FMT_16_16_UNORM', 'BUF_FMT_16_16_USCALED', + 'BUF_FMT_16_FLOAT', 'BUF_FMT_16_SINT', 'BUF_FMT_16_SNORM', + 'BUF_FMT_16_SSCALED', 'BUF_FMT_16_UINT', 'BUF_FMT_16_UNORM', + 'BUF_FMT_16_USCALED', 'BUF_FMT_2_10_10_10_SINT', + 'BUF_FMT_2_10_10_10_SNORM', 'BUF_FMT_2_10_10_10_SSCALED', + 'BUF_FMT_2_10_10_10_UINT', 'BUF_FMT_2_10_10_10_UNORM', + 'BUF_FMT_2_10_10_10_USCALED', 'BUF_FMT_32_32_32_32_FLOAT', + 'BUF_FMT_32_32_32_32_SINT', 'BUF_FMT_32_32_32_32_UINT', + 'BUF_FMT_32_32_32_FLOAT', 'BUF_FMT_32_32_32_SINT', + 'BUF_FMT_32_32_32_UINT', 'BUF_FMT_32_32_FLOAT', + 'BUF_FMT_32_32_SINT', 'BUF_FMT_32_32_UINT', 'BUF_FMT_32_FLOAT', + 'BUF_FMT_32_SINT', 'BUF_FMT_32_UINT', 'BUF_FMT_8_8_8_8_SINT', + 'BUF_FMT_8_8_8_8_SNORM', 'BUF_FMT_8_8_8_8_SSCALED', + 'BUF_FMT_8_8_8_8_UINT', 'BUF_FMT_8_8_8_8_UNORM', + 'BUF_FMT_8_8_8_8_USCALED', 'BUF_FMT_8_8_SINT', + 'BUF_FMT_8_8_SNORM', 'BUF_FMT_8_8_SSCALED', 'BUF_FMT_8_8_UINT', + 'BUF_FMT_8_8_UNORM', 'BUF_FMT_8_8_USCALED', 'BUF_FMT_8_SINT', + 'BUF_FMT_8_SNORM', 'BUF_FMT_8_SSCALED', 'BUF_FMT_8_UINT', + 'BUF_FMT_8_UNORM', 'BUF_FMT_8_USCALED', 'BUF_FMT_INVALID', + 'BUF_FMT_RESERVED_100', 'BUF_FMT_RESERVED_101', + 'BUF_FMT_RESERVED_102', 'BUF_FMT_RESERVED_103', + 'BUF_FMT_RESERVED_104', 'BUF_FMT_RESERVED_105', + 'BUF_FMT_RESERVED_106', 'BUF_FMT_RESERVED_107', + 'BUF_FMT_RESERVED_108', 'BUF_FMT_RESERVED_109', + 'BUF_FMT_RESERVED_110', 'BUF_FMT_RESERVED_111', + 'BUF_FMT_RESERVED_112', 'BUF_FMT_RESERVED_113', + 'BUF_FMT_RESERVED_114', 'BUF_FMT_RESERVED_115', + 'BUF_FMT_RESERVED_116', 'BUF_FMT_RESERVED_117', + 'BUF_FMT_RESERVED_118', 'BUF_FMT_RESERVED_119', + 'BUF_FMT_RESERVED_120', 'BUF_FMT_RESERVED_121', + 'BUF_FMT_RESERVED_122', 'BUF_FMT_RESERVED_123', + 'BUF_FMT_RESERVED_124', 'BUF_FMT_RESERVED_125', + 'BUF_FMT_RESERVED_126', 'BUF_FMT_RESERVED_127', + 'BUF_FMT_RESERVED_78', 'BUF_FMT_RESERVED_79', + 'BUF_FMT_RESERVED_80', 'BUF_FMT_RESERVED_81', + 'BUF_FMT_RESERVED_82', 'BUF_FMT_RESERVED_83', + 'BUF_FMT_RESERVED_84', 'BUF_FMT_RESERVED_85', + 'BUF_FMT_RESERVED_86', 'BUF_FMT_RESERVED_87', + 'BUF_FMT_RESERVED_88', 'BUF_FMT_RESERVED_89', + 'BUF_FMT_RESERVED_90', 'BUF_FMT_RESERVED_91', + 'BUF_FMT_RESERVED_92', 'BUF_FMT_RESERVED_93', + 'BUF_FMT_RESERVED_94', 'BUF_FMT_RESERVED_95', + 'BUF_FMT_RESERVED_96', 'BUF_FMT_RESERVED_97', + 'BUF_FMT_RESERVED_98', 'BUF_FMT_RESERVED_99', 'BUF_NUM_FORMAT', + 'BUF_NUM_FORMAT_FLOAT', 'BUF_NUM_FORMAT_SINT', + 'BUF_NUM_FORMAT_SNORM', 'BUF_NUM_FORMAT_SNORM_NZ', + 'BUF_NUM_FORMAT_SSCALED', 'BUF_NUM_FORMAT_UINT', + 'BUF_NUM_FORMAT_UNORM', 'BUF_NUM_FORMAT_USCALED', 'BYPASS_EN', + 'BYPASS_GAMUT', 'BYPASS_ICSC', 'BankHeight', 'BankInterleaveSize', + 'BankSwapBytes', 'BankTiling', 'BankWidth', 'BankWidthHeight', + 'BinEventCntl', 'BinMapMode', 'BinSizeExtend', 'BinningMode', + 'BlendOp', 'BlendOpt', 'CACHE_BYPASS', 'CACHE_FLUSH', + 'CACHE_FLUSH_AND_INV_EVENT', 'CACHE_FLUSH_AND_INV_TS_EVENT', + 'CACHE_FLUSH_TS', 'CACHE_LRU_RD', 'CACHE_LRU_WR', 'CACHE_NOA', + 'CACHE_STREAM', 'CBMode', 'CBPerfClearFilterSel', + 'CBPerfOpFilterSel', 'CBPerfSel', 'CB_B_DATA_ON_ALPHA_PORT', + 'CB_B_DATA_ON_CB_B_PORT', 'CB_B_DATA_ON_CR_R_PORT', + 'CB_B_DATA_ON_Y_G_PORT', 'CB_DCC_DECOMPRESS', 'CB_DECOMPRESS', + 'CB_DISABLE', 'CB_ELIMINATE_FAST_CLEAR', 'CB_FMASK_DECOMPRESS', + 'CB_NORMAL', 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', + 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', + 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 'CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL', + 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', 'CB_PERF_SEL_BUSY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB', + 'CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY', + 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VLD', + 'CB_PERF_SEL_CC_BC_CS_FRAG_VALID', + 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_CC_CACHE_FLUSH', 'CB_PERF_SEL_CC_CACHE_HIT', + 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CC_CACHE_STALL', + 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED', + 'CB_PERF_SEL_CC_DCC_RDREQ_STALL', + 'CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_CC_EVENFIFO_STUTTER_STALL', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB', + 'CB_PERF_SEL_CC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_MC_EARLY_WRITE_RETURN', + 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_MC_WRITE_ACK64B', + 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_MC_WRITE_REQUEST_PARTIAL', + 'CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_CC_ODDFIFO_STUTTER_STALL', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB', + 'CB_PERF_SEL_CC_RB_FULL', 'CB_PERF_SEL_CC_SF_FULL', + 'CB_PERF_SEL_CC_SURFACE_SYNC', 'CB_PERF_SEL_CMASK_READ_DATA_0xC', + 'CB_PERF_SEL_CMASK_READ_DATA_0xD', + 'CB_PERF_SEL_CMASK_READ_DATA_0xE', + 'CB_PERF_SEL_CMASK_READ_DATA_0xF', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xC', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xD', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xE', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xF', + 'CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY', + 'CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_CM_CACHE_FLUSH', 'CB_PERF_SEL_CM_CACHE_HIT', + 'CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CM_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CM_CACHE_STALL', + 'CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_TAG_MISS', + 'CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READY', + 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB', + 'CB_PERF_SEL_CM_FC_TILE_VALID_READY', + 'CB_PERF_SEL_CM_FC_TILE_VALID_READYB', + 'CB_PERF_SEL_CM_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CM_MC_EARLY_WRITE_RETURN', + 'CB_PERF_SEL_CM_MC_READ_REQUEST', + 'CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CM_MC_WRITE_ACK64B', + 'CB_PERF_SEL_CM_MC_WRITE_REQUEST', + 'CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CM_TQ_FIFO_STUTTER_STALL', + 'CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL', + 'CB_PERF_SEL_CM_TQ_FULL', 'CB_PERF_SEL_CORE_SCLK_VLD', + 'CB_PERF_SEL_DB_CB_CONTEXT_DONE', 'CB_PERF_SEL_DB_CB_EOP_DONE', + 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READY', + 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB', + 'CB_PERF_SEL_DB_CB_TILE_TILENOTEVENT', + 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_TILE_VALID_READY', + 'CB_PERF_SEL_DB_CB_TILE_VALID_READYB', + 'CB_PERF_SEL_DC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_DC_MC_EARLY_WRITE_RETURN', + 'CB_PERF_SEL_DC_MC_WRITE_ACK64B', 'CB_PERF_SEL_DRAWN_BUSY', + 'CB_PERF_SEL_DRAWN_PIXEL', 'CB_PERF_SEL_DRAWN_QUAD', + 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', 'CB_PERF_SEL_DRAWN_TILE', + 'CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT', + 'CB_PERF_SEL_EVENT', 'CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_PIXEL_DATA', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_DB_DATA_TS', + 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 'CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY', + 'CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_FC_CACHE_FLUSH', 'CB_PERF_SEL_FC_CACHE_HIT', + 'CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_FC_CACHE_STALL', + 'CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_TAG_MISS', + 'CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB', + 'CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_FLUSH', 'CB_PERF_SEL_FC_DCC_CACHE_HIT', + 'CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS', + 'CB_PERF_SEL_FC_DCC_CACHE_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS', + 'CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR', + 'CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT', + 'CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS', + 'CB_PERF_SEL_FC_DOC_IS_STALLED', + 'CB_PERF_SEL_FC_DOC_MRTS_COMBINED', + 'CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS', + 'CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT', + 'CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS', + 'CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL', + 'CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS', + 'CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FC_KEYID_STUTTER_STALL', + 'CB_PERF_SEL_FC_MC_DCC_READ_REQUEST', + 'CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST', + 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_EARLY_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_EARLY_WRITE_RETURN', + 'CB_PERF_SEL_FC_MC_READ_REQUEST', + 'CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_WRITE_ACK64B', + 'CB_PERF_SEL_FC_MC_WRITE_REQUEST', + 'CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED', + 'CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FC_QUAD_STUTTER_STALL', + 'CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_FC_SEQUENCER_CLEAR', + 'CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR', + 'CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE', + 'CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS', + 'CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FC_TILE_STUTTER_STALL', + 'CB_PERF_SEL_FOP_FMASK_BYPASS_STALL', + 'CB_PERF_SEL_FOP_FMASK_RAW_STALL', + 'CB_PERF_SEL_FOP_IN_VALIDB_READY', + 'CB_PERF_SEL_FOP_IN_VALIDB_READYB', + 'CB_PERF_SEL_FOP_IN_VALID_READY', + 'CB_PERF_SEL_FOP_IN_VALID_READYB', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_FLOAT_8PIX', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_SIGNED_8PIX', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_16_16_UNSIGNED_8PIX', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32BPP_8PIX', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR', + 'CB_PERF_SEL_LQUAD_NO_TILE', + 'CB_PERF_SEL_MERGE_PIXELS_WITH_BLEND_ENABLED', + 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY', + 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB', + 'CB_PERF_SEL_NACK_CC_READ', 'CB_PERF_SEL_NACK_CC_WRITE', + 'CB_PERF_SEL_NACK_CM_READ', 'CB_PERF_SEL_NACK_CM_WRITE', + 'CB_PERF_SEL_NACK_DC_READ', 'CB_PERF_SEL_NACK_DC_WRITE', + 'CB_PERF_SEL_NACK_FC_READ', 'CB_PERF_SEL_NACK_FC_WRITE', + 'CB_PERF_SEL_NONE', 'CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT', + 'CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS', + 'CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 'CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS', + 'CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS', + 'CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST', + 'CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED', + 'CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID', + 'CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL', + 'CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT', + 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK', + 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_0', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_1', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_2', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_3', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_4', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_5', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_6', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_7', + 'CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT', + 'CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 'CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD', + 'CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS', + 'CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK', + 'CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING', + 'CB_PERF_SEL_RBP_SPLIT_MICROTILE', + 'CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK', + 'CB_PERF_SEL_REG_SCLK0_VLD', 'CB_PERF_SEL_REG_SCLK1_VLD', + 'CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY', + 'CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT', 'CB_RESERVED', + 'CB_RESOLVE', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 'CENTERS_ONLY', 'CENTROIDS_AND_CENTERS', 'CENTROIDS_ONLY', + 'CHA_PERF_SEL', 'CHA_PERF_SEL_ARB_REQUESTS', 'CHA_PERF_SEL_BUSY', + 'CHA_PERF_SEL_CYCLE', 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 'CHA_PERF_SEL_IO_32B_WDS_CHC1', 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 'CHA_PERF_SEL_IO_32B_WDS_CHC3', 'CHA_PERF_SEL_IO_32B_WDS_CHC4', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC4', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC4', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC4', 'CHA_PERF_SEL_REQUEST_CHC0', + 'CHA_PERF_SEL_REQUEST_CHC1', 'CHA_PERF_SEL_REQUEST_CHC2', + 'CHA_PERF_SEL_REQUEST_CHC3', 'CHA_PERF_SEL_REQUEST_CHC4', + 'CHA_PERF_SEL_REQUEST_CHC5', 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'CHA_PERF_SEL_STALL_CHC0', 'CHA_PERF_SEL_STALL_CHC1', + 'CHA_PERF_SEL_STALL_CHC2', 'CHA_PERF_SEL_STALL_CHC3', + 'CHA_PERF_SEL_STALL_CHC4', 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4', 'CHCG_PERF_SEL', + 'CHCG_PERF_SEL_CORE_REG_SCLK_VLD', 'CHCG_PERF_SEL_CYCLE', + 'CHCG_PERF_SEL_GATE_EN1', 'CHCG_PERF_SEL_GATE_EN2', + 'CHCG_PERF_SEL_REQ', 'CHCG_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES', + 'CHCG_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES', 'CHC_PERF_SEL', + 'CHC_PERF_SEL_CORE_REG_SCLK_VLD', 'CHC_PERF_SEL_CYCLE', + 'CHC_PERF_SEL_GATE_EN1', 'CHC_PERF_SEL_GATE_EN2', + 'CHC_PERF_SEL_REQ', 'CHC_PERF_SEL_TA_CHC_ADDR_STARVE_CYCLES', + 'CHC_PERF_SEL_TA_CHC_DATA_STARVE_CYCLES', 'CHUNK_SIZE', + 'CHUNK_SIZE_16KB', 'CHUNK_SIZE_1KB', 'CHUNK_SIZE_2KB', + 'CHUNK_SIZE_32KB', 'CHUNK_SIZE_4KB', 'CHUNK_SIZE_64KB', + 'CHUNK_SIZE_8KB', 'CLEAR_SMU_INTR', 'CLKGATE_BASE_MODE', + 'CLKGATE_SM_MODE', 'CLOCK_BRANCH_SOFT_RESET', + 'CLOCK_BRANCH_SOFT_RESET_FORCE', 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 'CLOCK_GATING_DISABLE', 'CLOCK_GATING_DISABLED', + 'CLOCK_GATING_DISABLED_IN_DCO', 'CLOCK_GATING_DISABLE_ENUM', + 'CLOCK_GATING_DISABLE_ENUM_DISABLED', + 'CLOCK_GATING_DISABLE_ENUM_ENABLED', 'CLOCK_GATING_EN', + 'CLOCK_GATING_ENABLE', 'CLOCK_GATING_ENABLED', + 'CLOCK_GATING_ENABLED_IN_DCO', 'CMASK_ADDR_COMPATIBLE', + 'CMASK_ADDR_LINEAR', 'CMASK_ADDR_TILED', 'CMASK_ALPHA0_FRAG1', + 'CMASK_ALPHA0_FRAG2', 'CMASK_ALPHA0_FRAG4', 'CMASK_ALPHA0_FRAGS', + 'CMASK_ALPHA1_FRAG1', 'CMASK_ALPHA1_FRAG2', 'CMASK_ALPHA1_FRAG4', + 'CMASK_ALPHA1_FRAGS', 'CMASK_ALPHAX_FRAG1', 'CMASK_ALPHAX_FRAG2', + 'CMASK_ALPHAX_FRAG4', 'CMASK_ALPHAX_FRAGS', 'CMASK_ANY_EXPANDED', + 'CMASK_CLEAR_ALL', 'CMASK_CLEAR_NONE', 'CMASK_CLEAR_ONE', + 'CMASK_CLR00_F0', 'CMASK_CLR00_F1', 'CMASK_CLR00_F2', + 'CMASK_CLR00_FX', 'CMASK_CLR01_F0', 'CMASK_CLR01_F1', + 'CMASK_CLR01_F2', 'CMASK_CLR01_FX', 'CMASK_CLR10_F0', + 'CMASK_CLR10_F1', 'CMASK_CLR10_F2', 'CMASK_CLR10_FX', + 'CMASK_CLR11_F0', 'CMASK_CLR11_F1', 'CMASK_CLR11_F2', + 'CMASK_CLR11_FX', 'CMC_3DLUT_17CUBE', 'CMC_3DLUT_30BIT', + 'CMC_3DLUT_30BIT_ENUM', 'CMC_3DLUT_36BIT', 'CMC_3DLUT_9CUBE', + 'CMC_3DLUT_RAM_SEL', 'CMC_3DLUT_SIZE_ENUM', + 'CMC_LUT_2CFG_MEMORY_A', 'CMC_LUT_2CFG_MEMORY_B', + 'CMC_LUT_2CFG_NO_MEMORY', 'CMC_LUT_2_CONFIG_ENUM', + 'CMC_LUT_2_MODE_BYPASS', 'CMC_LUT_2_MODE_ENUM', + 'CMC_LUT_2_MODE_RAMA_LUT', 'CMC_LUT_2_MODE_RAMB_LUT', + 'CMC_LUT_NUM_SEG', 'CMC_LUT_RAM_SEL', 'CMC_RAM0_ACCESS', + 'CMC_RAM1_ACCESS', 'CMC_RAM2_ACCESS', 'CMC_RAM3_ACCESS', + 'CMC_RAMA_ACCESS', 'CMC_RAMB_ACCESS', 'CMC_SEGMENTS_1', + 'CMC_SEGMENTS_128', 'CMC_SEGMENTS_16', 'CMC_SEGMENTS_2', + 'CMC_SEGMENTS_32', 'CMC_SEGMENTS_4', 'CMC_SEGMENTS_64', + 'CMC_SEGMENTS_8', 'CM_BYPASS', 'CM_COEF_FORMAT_ENUM', + 'CM_DATA_SIGNED', 'CM_DISABLE', 'CM_EN', 'CM_ENABLE', + 'CM_GAMUT_REMAP_MODE_ENUM', 'CM_ICSC_MODE_ENUM', + 'CM_LUT_2_CONFIG_ENUM', 'CM_LUT_2_MODE_ENUM', + 'CM_LUT_4_CONFIG_ENUM', 'CM_LUT_4_MODE_ENUM', 'CM_LUT_NUM_SEG', + 'CM_LUT_RAM_SEL', 'CM_NOT_PENDING', 'CM_PENDING', + 'CM_WRITE_BASE_ONLY', 'CM_YES_PENDING', 'CNVC_BYPASS', + 'CNVC_BYPASS_DISABLE', 'CNVC_BYPASS_EN', 'CNVC_DIS', 'CNVC_EN', + 'CNVC_ENABLE', 'CNVC_NOT_PENDING', 'CNVC_PENDING', 'CNVC_ROUND', + 'CNVC_TRUNCATE', 'CNVC_YES_PENDING', 'CNV_CSC_BYPASS_ENUM', + 'CNV_CSC_BYPASS_NEG', 'CNV_CSC_BYPASS_POS', 'CNV_EYE_SELECT', + 'CNV_FRAME_CAPTURE_DISABLE', 'CNV_FRAME_CAPTURE_ENABLE', + 'CNV_FRAME_CAPTURE_EN_ENUM', 'CNV_FRAME_CAPTURE_RATE_0', + 'CNV_FRAME_CAPTURE_RATE_1', 'CNV_FRAME_CAPTURE_RATE_2', + 'CNV_FRAME_CAPTURE_RATE_3', 'CNV_FRAME_CAPTURE_RATE_ENUM', + 'CNV_INTERLACED_FIELD_ORDER_BOT', + 'CNV_INTERLACED_FIELD_ORDER_ENUM', + 'CNV_INTERLACED_FIELD_ORDER_TOP', 'CNV_INTERLACED_MODE_ENUM', + 'CNV_INTERLACED_MODE_INTERLACED', + 'CNV_INTERLACED_MODE_PROGRESSIVE', 'CNV_NEW_CONTENT_ENUM', + 'CNV_NEW_CONTENT_NEG', 'CNV_NEW_CONTENT_POS', 'CNV_OUT_BPC_10BPC', + 'CNV_OUT_BPC_8BPC', 'CNV_OUT_BPC_ENUM', + 'CNV_STEREO_POLARITY_ENUM', 'CNV_STEREO_POLARITY_LEFT', + 'CNV_STEREO_POLARITY_RIGHT', 'CNV_STEREO_SPLIT_DISABLE', + 'CNV_STEREO_SPLIT_ENABLE', 'CNV_STEREO_SPLIT_ENUM', + 'CNV_STEREO_TYPE_ENUM', 'CNV_STEREO_TYPE_FRAME_SEQUENTIAL', + 'CNV_STEREO_TYPE_RESERVED0', 'CNV_STEREO_TYPE_RESERVED1', + 'CNV_STEREO_TYPE_RESERVED2', 'CNV_TEST_CRC_CONT_DISABLE', + 'CNV_TEST_CRC_CONT_ENABLE', 'CNV_TEST_CRC_CONT_EN_ENUM', + 'CNV_TEST_CRC_DISABLE', 'CNV_TEST_CRC_ENABLE', + 'CNV_TEST_CRC_EN_ENUM', 'CNV_UPDATE_LOCK', 'CNV_UPDATE_LOCK_ENUM', + 'CNV_UPDATE_PENDING_ENUM', 'CNV_UPDATE_PENDING_NEG', + 'CNV_UPDATE_PENDING_POS', 'CNV_UPDATE_UNLOCK', + 'CNV_WINDOW_CROP_DISABLE', 'CNV_WINDOW_CROP_ENABLE', + 'CNV_WINDOW_CROP_EN_ENUM', 'COEF_ICSC', 'COEF_ICSC_B', + 'COEF_RAM_SELECT_BACK', 'COEF_RAM_SELECT_CURRENT', + 'COEF_RAM_SELECT_RD', 'COLOR_10_10_10_2', 'COLOR_10_11_11', + 'COLOR_11_11_10', 'COLOR_16', 'COLOR_16_16', 'COLOR_16_16_16_16', + 'COLOR_1_5_5_5', 'COLOR_24BIT_1BIT_AND', + 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', 'COLOR_24_8', + 'COLOR_2_10_10_10', 'COLOR_2_10_10_10_6E4', 'COLOR_32', + 'COLOR_32_32', 'COLOR_32_32_32_32', 'COLOR_4_4_4_4', + 'COLOR_5_5_5_1', 'COLOR_5_6_5', 'COLOR_64BIT_FP_PREMULT', + 'COLOR_64BIT_FP_UNPREMULT', 'COLOR_8', 'COLOR_8_24', 'COLOR_8_8', + 'COLOR_8_8_8_8', 'COLOR_INVALID', 'COLOR_KEYER_MODE', + 'COLOR_RESERVED_13', 'COLOR_RESERVED_15', 'COLOR_RESERVED_23', + 'COLOR_RESERVED_24', 'COLOR_RESERVED_25', 'COLOR_RESERVED_26', + 'COLOR_RESERVED_27', 'COLOR_RESERVED_28', 'COLOR_RESERVED_29', + 'COLOR_RESERVED_30', 'COLOR_X24_8_32_FLOAT', 'COMB_DST_MINUS_SRC', + 'COMB_DST_PLUS_SRC', 'COMB_MAX_DST_SRC', 'COMB_MIN_DST_SRC', + 'COMB_SRC_MINUS_DST', 'CONFIG_128B_SWAPS', 'CONFIG_1KB_ROW', + 'CONFIG_1KB_ROW_OPT', 'CONFIG_1KB_SPLIT', 'CONFIG_1KB_SWAPS', + 'CONFIG_1_PIPE', 'CONFIG_256B_GROUP', 'CONFIG_256B_SWAPS', + 'CONFIG_2KB_ROW', 'CONFIG_2KB_ROW_OPT', 'CONFIG_2KB_SPLIT', + 'CONFIG_2_PIPE', 'CONFIG_4KB_ROW', 'CONFIG_4KB_ROW_OPT', + 'CONFIG_4KB_SPLIT', 'CONFIG_4_BANK', 'CONFIG_4_PIPE', + 'CONFIG_512B_GROUP', 'CONFIG_512B_SWAPS', 'CONFIG_8KB_ROW', + 'CONFIG_8KB_ROW_OPT', 'CONFIG_8KB_SPLIT', 'CONFIG_8_BANK', + 'CONFIG_8_PIPE', 'CONFIG_SPACE1_END', 'CONFIG_SPACE1_START', + 'CONFIG_SPACE2_END', 'CONFIG_SPACE2_START', 'CONFIG_SPACE_END', + 'CONFIG_SPACE_START', 'CONTEXT_DONE', 'CONTEXT_SPACE_END', + 'CONTEXT_SPACE_START', 'CONTEXT_SUSPEND', + 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', + 'CORB_READ_POINTER_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', 'COUNTER_RING_0', + 'COUNTER_RING_1', 'COUNTER_RING_SPLIT', 'CPC_LATENCY_STATS_SEL', + 'CPC_LATENCY_STATS_SEL_INVAL_LAST', + 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 'CPC_LATENCY_STATS_SEL_XNACK_MIN', 'CPC_PERFCOUNT_SEL', + 'CPC_PERF_SEL_ALWAYS_COUNT', 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 'CPC_PERF_SEL_CPC_GCRIU_IDLE', 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 'CPC_PERF_SEL_CPC_STAT_BUSY', 'CPC_PERF_SEL_CPC_STAT_IDLE', + 'CPC_PERF_SEL_CPC_STAT_STALL', 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 'CPC_PERF_SEL_CPC_TCIU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', + 'CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE', + 'CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE', + 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPC_TAG_RAM', + 'CPF_LATENCY_STATS_SEL', 'CPF_LATENCY_STATS_SEL_INVAL_LAST', + 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 'CPF_LATENCY_STATS_SEL_READ_LAST', + 'CPF_LATENCY_STATS_SEL_READ_MAX', + 'CPF_LATENCY_STATS_SEL_READ_MIN', + 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 'CPF_LATENCY_STATS_SEL_XNACK_MIN', 'CPF_PERFCOUNTWINDOW_SEL', + 'CPF_PERFCOUNT_SEL', 'CPF_PERFWINDOW_SEL_CSF', + 'CPF_PERFWINDOW_SEL_HQD1', 'CPF_PERFWINDOW_SEL_HQD2', + 'CPF_PERFWINDOW_SEL_RDMA', 'CPF_PERFWINDOW_SEL_RWPP', + 'CPF_PERF_SEL_ALWAYS_COUNT', + 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_CPF_GCRIU_BUSY', 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 'CPF_PERF_SEL_CPF_GCRIU_STALL', 'CPF_PERF_SEL_CPF_STAT_BUSY', + 'CPF_PERF_SEL_CPF_STAT_IDLE', 'CPF_PERF_SEL_CPF_STAT_STALL', + 'CPF_PERF_SEL_CPF_TCIU_BUSY', 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 'CPF_PERF_SEL_CPF_TCIU_STALL', 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', + 'CPF_PERF_SEL_CPG_TCIU_STALL', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR', + 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 'CPF_PERF_SEL_GUS_READ_REQUEST_SEND', + 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SEND', + 'CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS', + 'CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE', + 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPF_TAG_RAM', + 'CPG_LATENCY_STATS_SEL', 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 'CPG_LATENCY_STATS_SEL_INVAL_LAST', + 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 'CPG_LATENCY_STATS_SEL_READ_LAST', + 'CPG_LATENCY_STATS_SEL_READ_MAX', + 'CPG_LATENCY_STATS_SEL_READ_MIN', + 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 'CPG_LATENCY_STATS_SEL_XNACK_MIN', 'CPG_PERFCOUNTWINDOW_SEL', + 'CPG_PERFCOUNT_SEL', 'CPG_PERFWINDOW_SEL_APPEND', + 'CPG_PERFWINDOW_SEL_CE', 'CPG_PERFWINDOW_SEL_CEDMA', + 'CPG_PERFWINDOW_SEL_CPC_IC', 'CPG_PERFWINDOW_SEL_CPG_IC', + 'CPG_PERFWINDOW_SEL_DDID', 'CPG_PERFWINDOW_SEL_DFY', + 'CPG_PERFWINDOW_SEL_DMA', 'CPG_PERFWINDOW_SEL_ME', + 'CPG_PERFWINDOW_SEL_MEC1', 'CPG_PERFWINDOW_SEL_MEC2', + 'CPG_PERFWINDOW_SEL_MEMRD', 'CPG_PERFWINDOW_SEL_MEMWR', + 'CPG_PERFWINDOW_SEL_MES', 'CPG_PERFWINDOW_SEL_PFP', + 'CPG_PERFWINDOW_SEL_PQ1', 'CPG_PERFWINDOW_SEL_PQ2', + 'CPG_PERFWINDOW_SEL_PQ3', 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', 'CPG_PERFWINDOW_SEL_QURD', + 'CPG_PERFWINDOW_SEL_QU_EOP', 'CPG_PERFWINDOW_SEL_QU_PIPE', + 'CPG_PERFWINDOW_SEL_QU_STRM', 'CPG_PERFWINDOW_SEL_RB', + 'CPG_PERFWINDOW_SEL_RESERVED1', 'CPG_PERFWINDOW_SEL_RESERVED2', + 'CPG_PERFWINDOW_SEL_SHADOW', 'CPG_PERFWINDOW_SEL_SR', + 'CPG_PERFWINDOW_SEL_VGT0', 'CPG_PERFWINDOW_SEL_VGT1', + 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', 'CPG_PERF_SEL_ALWAYS_COUNT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 'CPG_PERF_SEL_CPG_GCRIU_IDLE', 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 'CPG_PERF_SEL_CPG_STAT_BUSY', 'CPG_PERF_SEL_CPG_STAT_IDLE', + 'CPG_PERF_SEL_CPG_STAT_STALL', 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 'CPG_PERF_SEL_CPG_TCIU_IDLE', 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', + 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', + 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR', + 'CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL', + 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', 'CPG_PERF_SEL_ME_PARSER_BUSY', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', + 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 'CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS', + 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPG_TAG_RAM', + 'CP_ALPHA_TAG_RAM_SEL', 'CP_DDID_CNTL_MODE', 'CP_DDID_CNTL_SIZE', + 'CP_DDID_CNTL_VMID_SEL', 'CP_ME_ID', 'CP_PERFMON_ENABLE_MODE', + 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 'CP_PERFMON_ENABLE_MODE_RESERVED_1', 'CP_PERFMON_STATE', + 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'CP_PERFMON_STATE_RESERVED_3', 'CP_PERFMON_STATE_START_COUNTING', + 'CP_PERFMON_STATE_STOP_COUNTING', 'CP_PIPE_ID', 'CP_RING_ID', + 'CRC_CUR_0', 'CRC_CUR_1', 'CRC_CUR_BITS_0', 'CRC_CUR_BITS_1', + 'CRC_CUR_BITS_SEL', 'CRC_CUR_SEL', 'CRC_INTERLACE_0', + 'CRC_INTERLACE_1', 'CRC_INTERLACE_2', 'CRC_INTERLACE_3', + 'CRC_INTERLACE_SEL', 'CRC_IN_CUR_0', 'CRC_IN_CUR_1', + 'CRC_IN_CUR_SEL', 'CRC_IN_PIX_0', 'CRC_IN_PIX_1', 'CRC_IN_PIX_2', + 'CRC_IN_PIX_3', 'CRC_IN_PIX_4', 'CRC_IN_PIX_5', 'CRC_IN_PIX_6', + 'CRC_IN_PIX_7', 'CRC_IN_PIX_SEL', 'CRC_SRC_0', 'CRC_SRC_1', + 'CRC_SRC_2', 'CRC_SRC_3', 'CRC_SRC_SEL', 'CRC_STEREO_0', + 'CRC_STEREO_1', 'CRC_STEREO_2', 'CRC_STEREO_3', 'CRC_STEREO_SEL', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'CROB_MEM_PWR_LIGHT_SLEEP_MODE', 'CROSSBAR_FOR_ALPHA', + 'CROSSBAR_FOR_CB_B', 'CROSSBAR_FOR_CR_R', 'CROSSBAR_FOR_Y_G', + 'CR_R_DATA_ON_ALPHA_PORT', 'CR_R_DATA_ON_CB_B_PORT', + 'CR_R_DATA_ON_CR_R_PORT', 'CR_R_DATA_ON_Y_G_PORT', + 'CSCNTL_ADDR_WIDTH', 'CSCNTL_DATA_WIDTH', 'CSCNTL_TYPE', + 'CSCNTL_TYPE_EVENT', 'CSCNTL_TYPE_PRIVATE', 'CSCNTL_TYPE_STATE', + 'CSCNTL_TYPE_TG', 'CSCNTL_TYPE_WIDTH', 'CSDATA_ADDR_WIDTH', + 'CSDATA_DATA_WIDTH', 'CSDATA_TYPE', 'CSDATA_TYPE_EVENT', + 'CSDATA_TYPE_PRIVATE', 'CSDATA_TYPE_STATE', 'CSDATA_TYPE_TG', + 'CSDATA_TYPE_WIDTH', 'CS_CONTEXT_DONE', 'CS_DONE', 'CS_NA', + 'CS_PARTIAL_FLUSH', 'CS_STAGE_ON', 'CURSOR_2X_MAGNIFY', + 'CURSOR_2X_MAGNIFY_IS_DISABLE', 'CURSOR_2X_MAGNIFY_IS_ENABLE', + 'CURSOR_COLOR_24BIT_1BIT_AND', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 'CURSOR_COLOR_64BIT_FP_PREMULT', + 'CURSOR_COLOR_64BIT_FP_UNPREMULT', 'CURSOR_ENABLE', + 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', + 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', 'CURSOR_IS_DISABLE', + 'CURSOR_IS_ENABLE', 'CURSOR_IS_NOT_SNOOP', 'CURSOR_IS_SNOOP', + 'CURSOR_LINES_PER_CHUNK', 'CURSOR_LINE_PER_CHUNK_1', + 'CURSOR_LINE_PER_CHUNK_16', 'CURSOR_LINE_PER_CHUNK_2', + 'CURSOR_LINE_PER_CHUNK_4', 'CURSOR_LINE_PER_CHUNK_8', + 'CURSOR_MODE', 'CURSOR_MONO_2BIT', + 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_EN', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_SEL', 'CURSOR_PITCH', + 'CURSOR_PITCH_128_PIXELS', 'CURSOR_PITCH_256_PIXELS', + 'CURSOR_PITCH_64_PIXELS', 'CURSOR_SNOOP', 'CURSOR_STEREO_EN', + 'CURSOR_STEREO_IS_DISABLED', 'CURSOR_STEREO_IS_ENABLED', + 'CURSOR_SURFACE_IS_NOT_TMZ', 'CURSOR_SURFACE_IS_TMZ', + 'CURSOR_SURFACE_TMZ', 'CURSOR_SYSTEM', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', + 'CUR_CLAMP_DIS', 'CUR_CLAMP_EN', 'CUR_DIS', + 'CUR_DYNAMIC_EXPANSION', 'CUR_EN', 'CUR_ENABLE', + 'CUR_EXPAND_MODE', 'CUR_FP_NO_ROM', 'CUR_FP_USE_ROM', + 'CUR_INV_CLAMP', 'CUR_MODE', 'CUR_NOT_PENDING', 'CUR_PENDING', + 'CUR_ROM_EN', 'CUR_YES_PENDING', 'CUR_ZERO_EXPANSION', + 'CbYCrY10101010_422_PACKED', 'CbYCrY12121212_422_PACKED', + 'CbYCrY8888_422_PACKED', 'CmaskAddr', 'CmaskCode', 'CmaskMode', + 'ColorArray', 'ColorFormat', 'ColorTransform', 'CombFunc', + 'CompareFrag', 'CompareRef', 'ConservativeZExport', + 'CovToShaderSel', 'CrYCbA1010102', 'CrYCbA16161616_10LSB', + 'CrYCbA16161616_10MSB', 'CrYCbA16161616_12LSB', + 'CrYCbA16161616_12MSB', 'CrYCbA8888', 'CrYCbY10101010_422_PACKED', + 'CrYCbY12121212_422_PACKED', 'CrYCbY8888_422_PACKED', + 'DAC_MUX_SELECT', 'DAC_MUX_SELECT_DACA', 'DAC_MUX_SELECT_DACB', + 'DB_BREAK_BATCH_EVENT', 'DB_CACHE_FLUSH', + 'DB_CACHE_FLUSH_AND_INV', 'DB_CACHE_FLUSH_AND_INV_EVENT', + 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', 'DB_CACHE_FLUSH_TS', + 'DB_CONTEXT_DONE_EVENT', 'DB_CONTEXT_SUSPEND_EVENT', + 'DB_FLUSH_AND_INV_DB_DATA_TS', 'DB_FLUSH_AND_INV_DB_META', + 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 'DB_PERF_SEL_CB_DB_rdreq_sends', + 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 'DB_PERF_SEL_CB_DB_wrreq_sends', + 'DB_PERF_SEL_DB_CB_context_dones', 'DB_PERF_SEL_DB_CB_eop_dones', + 'DB_PERF_SEL_DB_CB_lquad_busy', + 'DB_PERF_SEL_DB_CB_lquad_double_format', + 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix', + 'DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending', + 'DB_PERF_SEL_DB_CB_lquad_quads', 'DB_PERF_SEL_DB_CB_lquad_sends', + 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 'DB_PERF_SEL_DB_CB_lquad_stalls', 'DB_PERF_SEL_DB_CB_rdret_ack', + 'DB_PERF_SEL_DB_CB_rdret_nack', 'DB_PERF_SEL_DB_CB_tile_busy', + 'DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS', + 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS', + 'DB_PERF_SEL_DB_CB_tile_sends', 'DB_PERF_SEL_DB_CB_tile_stalls', + 'DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event', + 'DB_PERF_SEL_DB_CB_wrret_ack', 'DB_PERF_SEL_DB_CB_wrret_nack', + 'DB_PERF_SEL_DB_SC_c_tile_rate', 'DB_PERF_SEL_DB_SC_quad_busy', + 'DB_PERF_SEL_DB_SC_quad_double_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_quad_pre_invoke', + 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 'DB_PERF_SEL_DB_SC_quad_sends', 'DB_PERF_SEL_DB_SC_quad_stalls', + 'DB_PERF_SEL_DB_SC_quad_tiles', 'DB_PERF_SEL_DB_SC_s_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_busy', 'DB_PERF_SEL_DB_SC_tile_culled', + 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 'DB_PERF_SEL_DB_SC_tile_no_ops', 'DB_PERF_SEL_DB_SC_tile_sends', + 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 'DB_PERF_SEL_DB_SC_tile_stalls', + 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_tiles', 'DB_PERF_SEL_DB_SC_z_tile_rate', + 'DB_PERF_SEL_DFSM_Flush_flushabit', + 'DB_PERF_SEL_DFSM_Flush_flushabit_camcoord_fifo', + 'DB_PERF_SEL_DFSM_Flush_flushabit_forceflush', + 'DB_PERF_SEL_DFSM_Flush_flushabit_nearlyfull', + 'DB_PERF_SEL_DFSM_Flush_flushabit_passthrough', + 'DB_PERF_SEL_DFSM_Flush_flushabit_primitivesinflightwatermark', + 'DB_PERF_SEL_DFSM_Flush_flushabit_punch_stalling', + 'DB_PERF_SEL_DFSM_Flush_flushabit_retainedtilefifo_watermark', + 'DB_PERF_SEL_DFSM_Flush_flushabit_tilesinflightwatermark', + 'DB_PERF_SEL_DFSM_Flush_flushall', + 'DB_PERF_SEL_DFSM_Flush_flushall_dfsmflush', + 'DB_PERF_SEL_DFSM_Flush_flushall_opmodechange', + 'DB_PERF_SEL_DFSM_Flush_flushall_sampleratechange', + 'DB_PERF_SEL_DFSM_Flush_flushall_watchdog', + 'DB_PERF_SEL_DFSM_Stall_bypass_fifo', + 'DB_PERF_SEL_DFSM_Stall_cam_fifo', + 'DB_PERF_SEL_DFSM_Stall_control_fifo', + 'DB_PERF_SEL_DFSM_Stall_middle_output', + 'DB_PERF_SEL_DFSM_Stall_opmode_change', + 'DB_PERF_SEL_DFSM_Stall_overflow_counter', + 'DB_PERF_SEL_DFSM_Stall_pops_stall_overflow', + 'DB_PERF_SEL_DFSM_Stall_pops_stall_self_flush', + 'DB_PERF_SEL_DFSM_Stall_retained_tile_fifo', + 'DB_PERF_SEL_DFSM_Stall_stalling_general', + 'DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream', + 'DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO', + 'DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow', + 'DB_PERF_SEL_DFSM_evicted_squads_above_watermark', + 'DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark', + 'DB_PERF_SEL_DFSM_evicted_tiles_above_watermark', + 'DB_PERF_SEL_DFSM_full_cleared_squads_out', + 'DB_PERF_SEL_DFSM_fully_cleared_pixels_out', + 'DB_PERF_SEL_DFSM_fully_cleared_quads_out', + 'DB_PERF_SEL_DFSM_lit_pixels_in', + 'DB_PERF_SEL_DFSM_lit_samples_in', + 'DB_PERF_SEL_DFSM_lit_samples_out', + 'DB_PERF_SEL_DFSM_prez_killed_squad', 'DB_PERF_SEL_DFSM_quads_in', + 'DB_PERF_SEL_DFSM_squads_in', + 'DB_PERF_SEL_DFSM_stalled_by_downstream', + 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 'DB_PERF_SEL_Depth_Tile_Cache_event', + 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 'DB_PERF_SEL_Op_Pipe_Busy', 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 'DB_PERF_SEL_Op_Pipe_Postz_Busy', 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 'DB_PERF_SEL_Plane_Cache_flushes', + 'DB_PERF_SEL_Plane_Cache_frees', 'DB_PERF_SEL_Plane_Cache_hits', + 'DB_PERF_SEL_Plane_Cache_misses', + 'DB_PERF_SEL_Plane_Cache_starves', + 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 'DB_PERF_SEL_PostZ_Samples_failing_S', + 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 'DB_PERF_SEL_PreZ_Samples_failing_S', + 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 'DB_PERF_SEL_SC_DB_quad_busy', + 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 'DB_PERF_SEL_SC_DB_quad_pixels', 'DB_PERF_SEL_SC_DB_quad_quads', + 'DB_PERF_SEL_SC_DB_quad_sends', 'DB_PERF_SEL_SC_DB_quad_squads', + 'DB_PERF_SEL_SC_DB_quad_tiles', 'DB_PERF_SEL_SC_DB_tile_backface', + 'DB_PERF_SEL_SC_DB_tile_busy', 'DB_PERF_SEL_SC_DB_tile_covered', + 'DB_PERF_SEL_SC_DB_tile_events', 'DB_PERF_SEL_SC_DB_tile_sends', + 'DB_PERF_SEL_SC_DB_tile_stalls', 'DB_PERF_SEL_SC_DB_tile_tiles', + 'DB_PERF_SEL_SH_quads_outstanding_sum', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 'DB_PERF_SEL_SX_DB_quad_busy', + 'DB_PERF_SEL_SX_DB_quad_double_format', + 'DB_PERF_SEL_SX_DB_quad_export_quads', + 'DB_PERF_SEL_SX_DB_quad_exports', + 'DB_PERF_SEL_SX_DB_quad_fast_format', + 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 'DB_PERF_SEL_SX_DB_quad_pixels', 'DB_PERF_SEL_SX_DB_quad_quads', + 'DB_PERF_SEL_SX_DB_quad_sends', + 'DB_PERF_SEL_SX_DB_quad_slow_format', + 'DB_PERF_SEL_SX_DB_quad_stalls', + 'DB_PERF_SEL_Stencil_Cache_flushes', + 'DB_PERF_SEL_Stencil_Cache_frees', + 'DB_PERF_SEL_Stencil_Cache_hits', + 'DB_PERF_SEL_Stencil_Cache_misses', + 'DB_PERF_SEL_Stencil_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_flushes', 'DB_PERF_SEL_Tile_Cache_hits', + 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Tile_Cache_misses', 'DB_PERF_SEL_Tile_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_surface_stall', + 'DB_PERF_SEL_Z_Cache_frees', 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 'DB_PERF_SEL_Z_Cache_pmask_hits', + 'DB_PERF_SEL_Z_Cache_pmask_misses', + 'DB_PERF_SEL_Z_Cache_pmask_starves', + 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 'DB_PERF_SEL_clock_main_active', + 'DB_PERF_SEL_clock_mem_export_active', + 'DB_PERF_SEL_clock_reg_active', + 'DB_PERF_SEL_depth_bounds_tile_culled', 'DB_PERF_SEL_di_dt_stall', + 'DB_PERF_SEL_dk_squad_busy', 'DB_PERF_SEL_dk_squad_sends', + 'DB_PERF_SEL_dk_squad_stalls', 'DB_PERF_SEL_dk_tile_busy', + 'DB_PERF_SEL_dk_tile_quad_starves', 'DB_PERF_SEL_dk_tile_sends', + 'DB_PERF_SEL_dk_tile_stalls', 'DB_PERF_SEL_dkg_tile_rate_tile', + 'DB_PERF_SEL_dtt_sm_clash_stall', 'DB_PERF_SEL_dtt_sm_miss_stall', + 'DB_PERF_SEL_dtt_sm_slot_stall', + 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 'DB_PERF_SEL_esr_eot_fwd_busy', 'DB_PERF_SEL_esr_eot_fwd_forward', + 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 'DB_PERF_SEL_esr_ps_lqf_busy', 'DB_PERF_SEL_esr_ps_lqf_stall', + 'DB_PERF_SEL_esr_ps_out_busy', 'DB_PERF_SEL_esr_ps_sqq_busy', + 'DB_PERF_SEL_esr_ps_sqq_stall', 'DB_PERF_SEL_esr_ps_src_in_sends', + 'DB_PERF_SEL_esr_ps_src_in_squads', + 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_stall', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 'DB_PERF_SEL_esr_ps_src_out_stall', 'DB_PERF_SEL_esr_sqq_zi_busy', + 'DB_PERF_SEL_esr_sqq_zi_stall', 'DB_PERF_SEL_etr_out_busy', + 'DB_PERF_SEL_etr_out_cb_tile_stall', + 'DB_PERF_SEL_etr_out_esr_stall', + 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 'DB_PERF_SEL_etr_out_send', 'DB_PERF_SEL_flush_10plane', + 'DB_PERF_SEL_flush_11plane', 'DB_PERF_SEL_flush_12plane', + 'DB_PERF_SEL_flush_13plane', 'DB_PERF_SEL_flush_14plane', + 'DB_PERF_SEL_flush_15plane', 'DB_PERF_SEL_flush_16plane', + 'DB_PERF_SEL_flush_1plane', 'DB_PERF_SEL_flush_2plane', + 'DB_PERF_SEL_flush_3plane', 'DB_PERF_SEL_flush_4plane', + 'DB_PERF_SEL_flush_5plane', 'DB_PERF_SEL_flush_6plane', + 'DB_PERF_SEL_flush_7plane', 'DB_PERF_SEL_flush_8plane', + 'DB_PERF_SEL_flush_9plane', 'DB_PERF_SEL_flush_compressed', + 'DB_PERF_SEL_flush_compressed_stencil', + 'DB_PERF_SEL_flush_expanded_stencil', + 'DB_PERF_SEL_flush_expanded_z', 'DB_PERF_SEL_flush_plane_le4', + 'DB_PERF_SEL_flush_single_stencil', 'DB_PERF_SEL_his_tile_culled', + 'DB_PERF_SEL_hiz_tc_read_starved', + 'DB_PERF_SEL_hiz_tc_write_stall', 'DB_PERF_SEL_hiz_tile_culled', + 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 'DB_PERF_SEL_mi_rdreq_busy', 'DB_PERF_SEL_mi_rdreq_stall', + 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 'DB_PERF_SEL_mi_wrreq_busy', 'DB_PERF_SEL_mi_wrreq_stall', + 'DB_PERF_SEL_planes_flushed', 'DB_PERF_SEL_postzl_full_launch', + 'DB_PERF_SEL_postzl_partial_launch', + 'DB_PERF_SEL_postzl_partial_waiting', + 'DB_PERF_SEL_postzl_se_busy', 'DB_PERF_SEL_postzl_se_stall', + 'DB_PERF_SEL_postzl_sq_pt_busy', 'DB_PERF_SEL_postzl_sq_pt_stall', + 'DB_PERF_SEL_postzl_src_in_sends', + 'DB_PERF_SEL_postzl_src_in_squads', + 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 'DB_PERF_SEL_postzl_src_in_stall', + 'DB_PERF_SEL_postzl_src_in_tile_rate', + 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_postzl_src_out_stall', + 'DB_PERF_SEL_postzl_tile_init_stall', + 'DB_PERF_SEL_postzl_tile_mem_stall', + 'DB_PERF_SEL_prezl_src_in_sends', + 'DB_PERF_SEL_prezl_src_in_squads', + 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 'DB_PERF_SEL_prezl_src_in_stall', + 'DB_PERF_SEL_prezl_src_in_tile_rate', + 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_prezl_src_out_stall', + 'DB_PERF_SEL_prezl_tile_init_stall', + 'DB_PERF_SEL_prezl_tile_mem_stall', 'DB_PERF_SEL_qc_busy', + 'DB_PERF_SEL_qc_conflicts', 'DB_PERF_SEL_qc_full_stall', + 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', 'DB_PERF_SEL_qc_xfc', + 'DB_PERF_SEL_quad_rd_32byte_reqs', 'DB_PERF_SEL_quad_rd_busy', + 'DB_PERF_SEL_quad_rd_mi_stall', 'DB_PERF_SEL_quad_rd_panic', + 'DB_PERF_SEL_quad_rd_rw_collision', 'DB_PERF_SEL_quad_rd_sends', + 'DB_PERF_SEL_quad_rd_tag_stall', 'DB_PERF_SEL_quad_rdret_busy', + 'DB_PERF_SEL_quad_rdret_sends', 'DB_PERF_SEL_quad_wr_acks', + 'DB_PERF_SEL_quad_wr_busy', 'DB_PERF_SEL_quad_wr_coherency_stall', + 'DB_PERF_SEL_quad_wr_mi_stall', 'DB_PERF_SEL_quad_wr_sends', + 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 'DB_PERF_SEL_sc_kick_end', 'DB_PERF_SEL_sc_kick_start', + 'DB_PERF_SEL_tcp_dispatcher_flushes', + 'DB_PERF_SEL_tcp_dispatcher_reads', + 'DB_PERF_SEL_tcp_prefetcher_flushes', + 'DB_PERF_SEL_tcp_prefetcher_reads', + 'DB_PERF_SEL_tcp_preloader_flushes', + 'DB_PERF_SEL_tcp_preloader_reads', 'DB_PERF_SEL_tile_rd_sends', + 'DB_PERF_SEL_tile_wr_acks', 'DB_PERF_SEL_tile_wr_sends', + 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 'DB_PERF_SEL_tiles_decomp_on_expclear', + 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 'DB_PERF_SEL_tiles_z_fully_summarized', 'DB_PERF_SEL_tl_busy', + 'DB_PERF_SEL_tl_dtc_read_starved', 'DB_PERF_SEL_tl_events', + 'DB_PERF_SEL_tl_expand_squads', + 'DB_PERF_SEL_tl_flush_expand_squads', + 'DB_PERF_SEL_tl_in_fast_z_stall', + 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 'DB_PERF_SEL_tl_in_xfc', 'DB_PERF_SEL_tl_out_squads', + 'DB_PERF_SEL_tl_out_xfc', 'DB_PERF_SEL_tl_postZ_noop_squads', + 'DB_PERF_SEL_tl_postZ_squads', 'DB_PERF_SEL_tl_preZ_noop_squads', + 'DB_PERF_SEL_tl_preZ_squads', + 'DB_PERF_SEL_tl_stencil_locked_stall', + 'DB_PERF_SEL_tl_stencil_stall', 'DB_PERF_SEL_tl_summarize_squads', + 'DB_PERF_SEL_tl_tile_ops', 'DB_PERF_SEL_tl_z_decompress_stall', + 'DB_PERF_SEL_tl_z_fetch_stall', 'DB_PERF_SEL_ts_tc_update_stall', + 'DB_PERF_SEL_tsc_insert_summarize_stall', + 'DB_PERF_SEL_unmapped_z_tile_culled', + 'DB_PERF_SEL_zf_plane_multicycle', 'DB_PSINVOKE_CHANGE_EVENT', + 'DB_VPORT_CHANGED_EVENT', 'DCCG_AUDIO_DTO0_SOURCE_SEL', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG4', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG5', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', + 'DCCG_AUDIO_DTO2_SOURCE_SEL', 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1', 'DCCG_AUDIO_DTO_SEL', + 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', + 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 'DCCG_AUDIO_DTO_USE_512FBR_DTO', + 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', 'DCCG_DEEP_COLOR_CNTL', + 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', 'DCCG_DEEP_COLOR_DTO_DISABLE', + 'DCCG_FIFO_ERRDET_OVR_DISABLE', 'DCCG_FIFO_ERRDET_OVR_EN', + 'DCCG_FIFO_ERRDET_OVR_ENABLE', 'DCCG_FIFO_ERRDET_RESET', + 'DCCG_FIFO_ERRDET_RESET_FORCE', 'DCCG_FIFO_ERRDET_RESET_NOOP', + 'DCCG_FIFO_ERRDET_STATE', 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 'DCCG_FIFO_ERRDET_STATE_DETECTION', 'DCCG_PERF_MODE_HSYNC', + 'DCCG_PERF_MODE_HSYNC_NOOP', 'DCCG_PERF_MODE_HSYNC_START', + 'DCCG_PERF_MODE_VSYNC', 'DCCG_PERF_MODE_VSYNC_NOOP', + 'DCCG_PERF_MODE_VSYNC_START', 'DCCG_PERF_OTG_SELECT', + 'DCCG_PERF_RUN', 'DCCG_PERF_RUN_NOOP', 'DCCG_PERF_RUN_START', + 'DCCG_PERF_SEL_OTG0', 'DCCG_PERF_SEL_OTG1', 'DCCG_PERF_SEL_OTG2', + 'DCCG_PERF_SEL_OTG3', 'DCCG_PERF_SEL_OTG4', 'DCCG_PERF_SEL_OTG5', + 'DCCG_PERF_SEL_RESERVED', 'DCC_CT_AUTO', 'DCC_CT_NONE', + 'DCIOCHIP_2BIT_DISABLE', 'DCIOCHIP_2BIT_ENABLE', + 'DCIOCHIP_4BIT_DISABLE', 'DCIOCHIP_4BIT_ENABLE', + 'DCIOCHIP_5BIT_DISABLE', 'DCIOCHIP_5BIT_ENABLE', + 'DCIOCHIP_AUXSLAVE_PAD_MODE', 'DCIOCHIP_AUXSLAVE_PAD_MODE_AUX', + 'DCIOCHIP_AUXSLAVE_PAD_MODE_I2C', 'DCIOCHIP_AUX_ALL_PWR_OK', + 'DCIOCHIP_AUX_ALL_PWR_OK_0', 'DCIOCHIP_AUX_ALL_PWR_OK_1', + 'DCIOCHIP_AUX_CSEL0P9', 'DCIOCHIP_AUX_CSEL1P1', + 'DCIOCHIP_AUX_CSEL_DEC0P9', 'DCIOCHIP_AUX_CSEL_DEC1P0', + 'DCIOCHIP_AUX_CSEL_INC1P0', 'DCIOCHIP_AUX_CSEL_INC1P1', + 'DCIOCHIP_AUX_FALLSLEWSEL', 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', 'DCIOCHIP_AUX_HYS_TUNE', + 'DCIOCHIP_AUX_HYS_TUNE_0', 'DCIOCHIP_AUX_HYS_TUNE_1', + 'DCIOCHIP_AUX_HYS_TUNE_2', 'DCIOCHIP_AUX_HYS_TUNE_3', + 'DCIOCHIP_AUX_RECEIVER_SEL', 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 'DCIOCHIP_AUX_RECEIVER_SEL_1', 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 'DCIOCHIP_AUX_RECEIVER_SEL_3', 'DCIOCHIP_AUX_RSEL0P9', + 'DCIOCHIP_AUX_RSEL1P1', 'DCIOCHIP_AUX_RSEL_DEC0P9', + 'DCIOCHIP_AUX_RSEL_DEC1P0', 'DCIOCHIP_AUX_RSEL_INC1P0', + 'DCIOCHIP_AUX_RSEL_INC1P1', 'DCIOCHIP_AUX_SPIKESEL', + 'DCIOCHIP_AUX_SPIKESEL_10NS', 'DCIOCHIP_AUX_SPIKESEL_50NS', + 'DCIOCHIP_AUX_VOD_TUNE', 'DCIOCHIP_AUX_VOD_TUNE_0', + 'DCIOCHIP_AUX_VOD_TUNE_1', 'DCIOCHIP_AUX_VOD_TUNE_2', + 'DCIOCHIP_AUX_VOD_TUNE_3', 'DCIOCHIP_DVO_VREFPON', + 'DCIOCHIP_DVO_VREFPON_DISABLE', 'DCIOCHIP_DVO_VREFPON_ENABLE', + 'DCIOCHIP_DVO_VREFSEL', 'DCIOCHIP_DVO_VREFSEL_EXTERNAL', + 'DCIOCHIP_DVO_VREFSEL_ONCHIP', 'DCIOCHIP_ENABLE_2BIT', + 'DCIOCHIP_ENABLE_4BIT', 'DCIOCHIP_ENABLE_5BIT', + 'DCIOCHIP_GPIO_I2C_DISABLE', 'DCIOCHIP_GPIO_I2C_DRIVE', + 'DCIOCHIP_GPIO_I2C_DRIVE_HIGH', 'DCIOCHIP_GPIO_I2C_DRIVE_LOW', + 'DCIOCHIP_GPIO_I2C_EN', 'DCIOCHIP_GPIO_I2C_ENABLE', + 'DCIOCHIP_GPIO_I2C_MASK', 'DCIOCHIP_GPIO_I2C_MASK_DISABLE', + 'DCIOCHIP_GPIO_I2C_MASK_ENABLE', 'DCIOCHIP_GPIO_MASK_EN', + 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', 'DCIOCHIP_HPD_SEL', + 'DCIOCHIP_HPD_SEL_ASYNC', 'DCIOCHIP_HPD_SEL_CLOCKED', + 'DCIOCHIP_I2C_COMPSEL', 'DCIOCHIP_I2C_FALLSLEWSEL', + 'DCIOCHIP_I2C_FALLSLEWSEL_00', 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 'DCIOCHIP_I2C_FALLSLEWSEL_10', 'DCIOCHIP_I2C_FALLSLEWSEL_11', + 'DCIOCHIP_I2C_RECEIVER_SEL', 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 'DCIOCHIP_I2C_RECEIVER_SEL_1', 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 'DCIOCHIP_I2C_RECEIVER_SEL_3', 'DCIOCHIP_I2C_REC_COMPARATOR', + 'DCIOCHIP_I2C_REC_SCHMIT', 'DCIOCHIP_I2C_VPH_1V2_EN', + 'DCIOCHIP_I2C_VPH_1V2_EN_0', 'DCIOCHIP_I2C_VPH_1V2_EN_1', + 'DCIOCHIP_INVERT', 'DCIOCHIP_MASIK_5BIT_DISABLE', + 'DCIOCHIP_MASIK_5BIT_ENABLE', 'DCIOCHIP_MASK', + 'DCIOCHIP_MASK_2BIT', 'DCIOCHIP_MASK_2BIT_DISABLE', + 'DCIOCHIP_MASK_2BIT_ENABLE', 'DCIOCHIP_MASK_4BIT', + 'DCIOCHIP_MASK_4BIT_DISABLE', 'DCIOCHIP_MASK_4BIT_ENABLE', + 'DCIOCHIP_MASK_5BIT', 'DCIOCHIP_MASK_DISABLE', + 'DCIOCHIP_MASK_ENABLE', 'DCIOCHIP_PAD_MODE', + 'DCIOCHIP_PAD_MODE_DDC', 'DCIOCHIP_PAD_MODE_DP', 'DCIOCHIP_PD_EN', + 'DCIOCHIP_PD_EN_ALLOW', 'DCIOCHIP_PD_EN_NOTALLOW', + 'DCIOCHIP_POL_INVERT', 'DCIOCHIP_POL_NON_INVERT', + 'DCIOCHIP_REF_27_SRC_SEL', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', 'DCIOCHIP_SPDIF1_IMODE', + 'DCIOCHIP_SPDIF1_IMODE_OE_A', 'DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO', + 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN', + 'DCIO_BL_PWM_CNTL_BL_PWM_EN', + 'DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN', 'DCIO_BL_PWM_DISABLE', + 'DCIO_BL_PWM_ENABLE', 'DCIO_BL_PWM_FRACTIONAL_DISABLE', + 'DCIO_BL_PWM_FRACTIONAL_ENABLE', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 'DCIO_BL_PWM_GRP1_REG_LOCK', 'DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE', + 'DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', + 'DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 'DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL', + 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM', + 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL', + 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS', 'DCIO_DACA_SOFT_RESET', + 'DCIO_DACA_SOFT_RESET_ASSERT', 'DCIO_DACA_SOFT_RESET_DEASSERT', + 'DCIO_DCRXPHY_SOFT_RESET', 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', + 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 'DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN', + 'DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN', + 'DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN', 'DCIO_DC_GENERICA_SEL', + 'DCIO_DC_GENERICB_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL', + 'DCIO_DC_GPU_TIMER_READ_SELECT', + 'DCIO_DC_GPU_TIMER_START_POSITION', + 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL', + 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL', + 'DCIO_DIO_EXT_VSYNC_MASK', 'DCIO_DIO_OTG_EXT_VSYNC_MUX', + 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', 'DCIO_DPCS_INTERRUPT_DISABLE', + 'DCIO_DPCS_INTERRUPT_ENABLE', 'DCIO_DPCS_INTERRUPT_MASK', + 'DCIO_DPCS_INTERRUPT_TYPE', + 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', 'DCIO_DPHY_LANE_SEL', + 'DCIO_DPHY_LANE_SEL_LANE0', 'DCIO_DPHY_LANE_SEL_LANE1', + 'DCIO_DPHY_LANE_SEL_LANE2', 'DCIO_DPHY_LANE_SEL_LANE3', + 'DCIO_DSYNC_SOFT_RESET', 'DCIO_DSYNC_SOFT_RESET_ASSERT', + 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 'DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE', + 'DCIO_DVO_ALTER_MAPPING_EN_DEFAULT', 'DCIO_EXT_VSYNC_MASK_NONE', + 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', 'DCIO_EXT_VSYNC_MASK_PIPE0', + 'DCIO_EXT_VSYNC_MASK_PIPE1', 'DCIO_EXT_VSYNC_MASK_PIPE2', + 'DCIO_EXT_VSYNC_MASK_PIPE3', 'DCIO_EXT_VSYNC_MASK_PIPE4', + 'DCIO_EXT_VSYNC_MASK_PIPE5', 'DCIO_EXT_VSYNC_MUX_GENERICB', + 'DCIO_EXT_VSYNC_MUX_OTG0', 'DCIO_EXT_VSYNC_MUX_OTG1', + 'DCIO_EXT_VSYNC_MUX_OTG2', 'DCIO_EXT_VSYNC_MUX_OTG3', + 'DCIO_EXT_VSYNC_MUX_OTG4', 'DCIO_EXT_VSYNC_MUX_OTG5', + 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 'DCIO_GENERICA_SEL_DACA_FIELD_NUMBER', + 'DCIO_GENERICA_SEL_DACA_PIXCLK', + 'DCIO_GENERICA_SEL_DACA_STEREOSYNC', + 'DCIO_GENERICA_SEL_DACB_FIELD_NUMBER', + 'DCIO_GENERICA_SEL_DACB_PIXCLK', 'DCIO_GENERICA_SEL_DVOA_CTL3', + 'DCIO_GENERICA_SEL_DVOA_STEREOSYNC', + 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 'DCIO_GENERICA_SEL_GENERICA_DPRX', + 'DCIO_GENERICA_SEL_GENERICB_DPRX', 'DCIO_GENERICA_SEL_P1_PLLCLK', + 'DCIO_GENERICA_SEL_P2_PLLCLK', 'DCIO_GENERICA_SEL_STEREOSYNC', + 'DCIO_GENERICA_SEL_SYNCEN', 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK', + 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2', + 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK', + 'DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK', + 'DCIO_GENERICB_SEL_DACA_FIELD_NUMBER', + 'DCIO_GENERICB_SEL_DACA_PIXCLK', + 'DCIO_GENERICB_SEL_DACA_STEREOSYNC', + 'DCIO_GENERICB_SEL_DACB_FIELD_NUMBER', + 'DCIO_GENERICB_SEL_DACB_PIXCLK', 'DCIO_GENERICB_SEL_DVOA_CTL3', + 'DCIO_GENERICB_SEL_DVOA_STEREOSYNC', + 'DCIO_GENERICB_SEL_GENERICB_DCCG', 'DCIO_GENERICB_SEL_P1_PLLCLK', + 'DCIO_GENERICB_SEL_P2_PLLCLK', 'DCIO_GENERICB_SEL_STEREOSYNC', + 'DCIO_GENERICB_SEL_SYNCEN', 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK', + 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2', + 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK', + 'DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK', 'DCIO_GENLK_CLK_GSL_MASK', + 'DCIO_GENLK_CLK_GSL_MASK_NO', 'DCIO_GENLK_CLK_GSL_MASK_STEREO', + 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', + 'DCIO_GENLK_VSYNC_GSL_MASK', 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', + 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_START_0_END_27', 'DCIO_GPU_TIMER_START_10_END_37', + 'DCIO_GPU_TIMER_START_1_END_28', 'DCIO_GPU_TIMER_START_2_END_29', + 'DCIO_GPU_TIMER_START_3_END_30', 'DCIO_GPU_TIMER_START_4_END_31', + 'DCIO_GPU_TIMER_START_6_END_33', 'DCIO_GPU_TIMER_START_8_END_35', + 'DCIO_GSL_SEL', 'DCIO_GSL_SEL_GROUP_0', 'DCIO_GSL_SEL_GROUP_1', + 'DCIO_GSL_SEL_GROUP_2', 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', + 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', + 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', 'DCIO_IMPCAL_STEP_DELAY', + 'DCIO_IMPCAL_STEP_DELAY_10us', 'DCIO_IMPCAL_STEP_DELAY_11us', + 'DCIO_IMPCAL_STEP_DELAY_12us', 'DCIO_IMPCAL_STEP_DELAY_13us', + 'DCIO_IMPCAL_STEP_DELAY_14us', 'DCIO_IMPCAL_STEP_DELAY_15us', + 'DCIO_IMPCAL_STEP_DELAY_16us', 'DCIO_IMPCAL_STEP_DELAY_1us', + 'DCIO_IMPCAL_STEP_DELAY_2us', 'DCIO_IMPCAL_STEP_DELAY_3us', + 'DCIO_IMPCAL_STEP_DELAY_4us', 'DCIO_IMPCAL_STEP_DELAY_5us', + 'DCIO_IMPCAL_STEP_DELAY_6us', 'DCIO_IMPCAL_STEP_DELAY_7us', + 'DCIO_IMPCAL_STEP_DELAY_8us', 'DCIO_IMPCAL_STEP_DELAY_9us', + 'DCIO_LVTMA_BLON_OFF', 'DCIO_LVTMA_BLON_ON', + 'DCIO_LVTMA_BLON_POL_INVERT', 'DCIO_LVTMA_BLON_POL_NON_INVERT', + 'DCIO_LVTMA_DIGON_OFF', 'DCIO_LVTMA_DIGON_ON', + 'DCIO_LVTMA_DIGON_POL_INVERT', 'DCIO_LVTMA_DIGON_POL_NON_INVERT', + 'DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE', + 'DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN', + 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE', + 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE', + 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF', + 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON', + 'DCIO_LVTMA_SYNCEN_POL_INVERT', + 'DCIO_LVTMA_SYNCEN_POL_NON_INVERT', + 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON', + 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE', + 'DCIO_SWAPLOCK_A_GSL_MASK', 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', 'DCIO_SWAPLOCK_B_GSL_MASK', + 'DCIO_SWAPLOCK_B_GSL_MASK_NO', 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', 'DCIO_TEST_CLK_SEL_DISPCLK', + 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', 'DCIO_TEST_CLK_SEL_SOCCLK', + 'DCIO_UNIPHYA_FBDIV_CLK', 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYA_TEST_REFDIV_CLK', 'DCIO_UNIPHYB_FBDIV_CLK', + 'DCIO_UNIPHYB_FBDIV_SSC_CLK', 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYB_TEST_REFDIV_CLK', 'DCIO_UNIPHYC_FBDIV_CLK', + 'DCIO_UNIPHYC_FBDIV_SSC_CLK', 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYC_TEST_REFDIV_CLK', 'DCIO_UNIPHYD_FBDIV_CLK', + 'DCIO_UNIPHYD_FBDIV_SSC_CLK', 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYD_TEST_REFDIV_CLK', 'DCIO_UNIPHYE_FBDIV_CLK', + 'DCIO_UNIPHYE_FBDIV_SSC_CLK', 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYE_TEST_REFDIV_CLK', 'DCIO_UNIPHYF_FBDIV_CLK', + 'DCIO_UNIPHYF_FBDIV_SSC_CLK', 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYF_TEST_REFDIV_CLK', 'DCIO_UNIPHYG_FBDIV_CLK', + 'DCIO_UNIPHYG_FBDIV_SSC_CLK', 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYG_TEST_REFDIV_CLK', 'DCIO_UNIPHY_CHANNEL_INVERTED', + 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', 'DCIO_UNIPHY_IMPCAL_SEL', + 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', + 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT', + 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK', + 'DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS', + 'DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE', + 'DCIO_VIP_ALTER_MAPPING_EN_DEFAULT', 'DCIO_VIP_MUX_EN_DVO', + 'DCIO_VIP_MUX_EN_VIP', 'DC_DMCUB_INT_TYPE', + 'DC_DMCUB_TIMER_WINDOW', 'DC_MEM_GLOBAL_PWR_REQ_DIS', + 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 'DC_SMU_INTERRUPT_ENABLE', 'DDID_VMID_CNTL', 'DDID_VMID_PIPE', + 'DENORM_TRUNCATE', 'DEPTH_16', 'DEPTH_32_FLOAT', 'DEPTH_8_24', + 'DEPTH_8_24_FLOAT', 'DEPTH_INVALID', 'DEPTH_MICRO_TILING', + 'DEPTH_X24_8_32_FLOAT', 'DEPTH_X8_24', 'DEPTH_X8_24_FLOAT', + 'DETILE_BUFFER_PACKER_ENABLE', 'DETILE_BUFFER_PACKER_IS_DISABLE', + 'DETILE_BUFFER_PACKER_IS_ENABLE', + 'DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'DET_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'DET_MEM_PWR_LIGHT_SLEEP_MODE', 'DFQ_MIN_FREE_ENTRIES', + 'DFQ_MIN_FREE_ENTRIES_0', 'DFQ_MIN_FREE_ENTRIES_1', + 'DFQ_MIN_FREE_ENTRIES_2', 'DFQ_MIN_FREE_ENTRIES_3', + 'DFQ_MIN_FREE_ENTRIES_4', 'DFQ_MIN_FREE_ENTRIES_5', + 'DFQ_MIN_FREE_ENTRIES_6', 'DFQ_MIN_FREE_ENTRIES_7', + 'DFQ_NUM_ENTRIES', 'DFQ_NUM_ENTRIES_0', 'DFQ_NUM_ENTRIES_1', + 'DFQ_NUM_ENTRIES_2', 'DFQ_NUM_ENTRIES_3', 'DFQ_NUM_ENTRIES_4', + 'DFQ_NUM_ENTRIES_5', 'DFQ_NUM_ENTRIES_6', 'DFQ_NUM_ENTRIES_7', + 'DFQ_NUM_ENTRIES_8', 'DFQ_SIZE', 'DFQ_SIZE_0', 'DFQ_SIZE_1', + 'DFQ_SIZE_2', 'DFQ_SIZE_3', 'DFQ_SIZE_4', 'DFQ_SIZE_5', + 'DFQ_SIZE_6', 'DFQ_SIZE_7', 'DFSMFlushEvents', + 'DIG_10BIT_TEST_PATTERN', 'DIG_ALL_PIXEL', + 'DIG_ALTERNATING_TEST_PATTERN', 'DIG_BE_CNTL_HPD1', + 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', 'DIG_BE_CNTL_HPD4', + 'DIG_BE_CNTL_HPD5', 'DIG_BE_CNTL_HPD6', 'DIG_BE_CNTL_HPD_SELECT', + 'DIG_BE_CNTL_MODE', 'DIG_BE_CNTL_NO_HPD', 'DIG_BE_DP_MST_MODE', + 'DIG_BE_DP_SST_MODE', 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', + 'DIG_BE_RESERVED3', 'DIG_BE_RESERVED4', 'DIG_BE_TMDS_DVI_MODE', + 'DIG_BE_TMDS_HDMI_MODE', 'DIG_DIGITAL_BYPASS_SEL', + 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 'DIG_DIGITAL_BYPASS_SEL_ALPHA', 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 'DIG_EVEN_PIXEL_ONLY', 'DIG_FE_CNTL_SOURCE_SELECT', + 'DIG_FE_CNTL_STEREOSYNC_SELECT', 'DIG_FE_SOURCE_FROM_OTG0', + 'DIG_FE_SOURCE_FROM_OTG1', 'DIG_FE_SOURCE_FROM_OTG2', + 'DIG_FE_SOURCE_FROM_OTG3', 'DIG_FE_SOURCE_FROM_OTG4', + 'DIG_FE_SOURCE_FROM_OTG5', 'DIG_FE_SOURCE_RESERVED', + 'DIG_FE_STEREOSYNC_FROM_OTG0', 'DIG_FE_STEREOSYNC_FROM_OTG1', + 'DIG_FE_STEREOSYNC_FROM_OTG2', 'DIG_FE_STEREOSYNC_FROM_OTG3', + 'DIG_FE_STEREOSYNC_FROM_OTG4', 'DIG_FE_STEREOSYNC_FROM_OTG5', + 'DIG_FE_STEREOSYNC_RESERVED', 'DIG_FIFO_ERROR_ACK', + 'DIG_FIFO_ERROR_ACK_INT', 'DIG_FIFO_ERROR_NOT_ACK', + 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', + 'DIG_FIFO_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', 'DIG_FIFO_READ_CLOCK_SRC', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', + 'DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL', + 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 'DIG_INPUT_PIXEL_SEL', 'DIG_IN_DEBUG_MODE', + 'DIG_IN_NORMAL_OPERATION', 'DIG_ODD_PIXEL_ONLY', + 'DIG_OUTPUT_CRC_CNTL_LINK_SEL', 'DIG_OUTPUT_CRC_DATA_SEL', + 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', 'DIG_OUTPUT_CRC_FOR_AUDIO', + 'DIG_OUTPUT_CRC_FOR_FULLFRAME', 'DIG_OUTPUT_CRC_FOR_VBI', + 'DIG_OUTPUT_CRC_ON_LINK0', 'DIG_OUTPUT_CRC_ON_LINK1', + 'DIG_RANDOM_PATTERN_ENABLED', 'DIG_RANDOM_PATTERN_RESETED', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL', + 'DIG_TEST_PATTERN_NORMAL', 'DIG_TEST_PATTERN_RANDOM', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET', + 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN', 'DIM_TYPE', 'DIM_TYPE_1D', + 'DIM_TYPE_2D', 'DIM_TYPE_3D', 'DIM_TYPE_RESERVED', + 'DIOMEM_DISABLE_MEM_PWR_CTRL', 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', + 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', 'DIOMEM_NO_FORCE_REQ', + 'DIOMEM_NO_FORCE_REQUEST', 'DIOMEM_PWR_DIS_CTRL', + 'DIOMEM_PWR_FORCE_CTRL', 'DIOMEM_PWR_FORCE_CTRL2', + 'DIOMEM_PWR_SEL_CTRL', 'DIOMEM_PWR_SEL_CTRL2', 'DIO_FIFO_ERROR', + 'DIO_FIFO_ERROR_00', 'DIO_FIFO_ERROR_01', 'DIO_FIFO_ERROR_10', + 'DIO_FIFO_ERROR_11', + 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', + 'DISABLE_BINNING_USE_LEGACY_SC', 'DISABLE_BINNING_USE_NEW_SC', + 'DISABLE_CLOCK_GATING', 'DISABLE_CLOCK_GATING_IN_DCO', + 'DISABLE_JITTER_REMOVAL', 'DISABLE_MEM_PWR_CTRL', 'DISABLE_TF0', + 'DISABLE_TF1', 'DISABLE_THE_CLOCK', 'DISABLE_THE_FEATURE', + 'DISABLE_THE_INTERRUPT', 'DISPCLK_CHG_FWD_CORR_DISABLE', + 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', + 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 'DISPCLK_FREQ_RAMP_COMPLETED', 'DISPCLK_FREQ_RAMP_DONE', + 'DISPCLK_FREQ_RAMP_IN_PROGRESS', 'DISPLAY_MICRO_TILING', 'DIV_2', + 'DIV_4', 'DIV_8', 'DI_INDEX_SIZE_16_BIT', 'DI_INDEX_SIZE_32_BIT', + 'DI_INDEX_SIZE_8_BIT', 'DI_MAJOR_MODE_0', 'DI_MAJOR_MODE_1', + 'DI_PT_2D_RECTANGLE', 'DI_PT_LINELIST', 'DI_PT_LINELIST_ADJ', + 'DI_PT_LINELOOP', 'DI_PT_LINESTRIP', 'DI_PT_LINESTRIP_ADJ', + 'DI_PT_NONE', 'DI_PT_PATCH', 'DI_PT_POINTLIST', 'DI_PT_POLYGON', + 'DI_PT_QUADLIST', 'DI_PT_QUADSTRIP', 'DI_PT_RECTLIST', + 'DI_PT_TRIFAN', 'DI_PT_TRILIST', 'DI_PT_TRILIST_ADJ', + 'DI_PT_TRISTRIP', 'DI_PT_TRISTRIP_ADJ', 'DI_PT_TRI_WITH_WFLAGS', + 'DI_PT_UNUSED_1', 'DI_PT_UNUSED_3', 'DI_PT_UNUSED_4', + 'DI_SRC_SEL_AUTO_INDEX', 'DI_SRC_SEL_DMA', 'DI_SRC_SEL_IMMEDIATE', + 'DI_SRC_SEL_RESERVED', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', + 'DMDATA_CLEAR_UNDERFLOW_STATUS', 'DMDATA_DONE', + 'DMDATA_DONT_CLEAR', 'DMDATA_HARDWARE_UPDATE_MODE', 'DMDATA_MODE', + 'DMDATA_NOT_SENT_TO_DIG', 'DMDATA_NOT_UNDERFLOW', + 'DMDATA_NOT_UPDATED', 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', + 'DMDATA_QOS_LEVEL_FROM_TTU', 'DMDATA_QOS_MODE', 'DMDATA_REPEAT', + 'DMDATA_SENT_TO_DIG', 'DMDATA_SOFTWARE_UPDATE_MODE', + 'DMDATA_UNDERFLOW', 'DMDATA_UNDERFLOWED', + 'DMDATA_UNDERFLOW_CLEAR', 'DMDATA_UPDATED', + 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', + 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', 'DMDATA_WAS_UPDATED', + 'DMU_CLOCK_GATING_DISABLE', 'DMU_CLOCK_ON', + 'DMU_CLOCK_STATUS_OFF', 'DMU_CLOCK_STATUS_ON', + 'DMU_DC_GPU_TIMER_READ_SELECT', 'DMU_DC_GPU_TIMER_START_POSITION', + 'DMU_DISABLE_CLOCK_GATING', 'DMU_ENABLE_CLOCK_GATING', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_56', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_FLIP_AWAY_84', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VREADY_44', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM_32', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_STARTUP_20', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_8', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE_NO_LOCK_72', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_58', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_FLIP_AWAY_86', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VREADY_46', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM_34', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_STARTUP_22', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_10', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE_NO_LOCK_74', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_57', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_FLIP_AWAY_85', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VREADY_45', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM_33', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_STARTUP_21', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_9', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE_NO_LOCK_73', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_59', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_FLIP_AWAY_87', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VREADY_47', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM_35', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_STARTUP_23', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_11', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE_NO_LOCK_75', + 'DMU_GPU_TIMER_START_0_END_27', 'DMU_GPU_TIMER_START_10_END_37', + 'DMU_GPU_TIMER_START_1_END_28', 'DMU_GPU_TIMER_START_2_END_29', + 'DMU_GPU_TIMER_START_3_END_30', 'DMU_GPU_TIMER_START_4_END_31', + 'DMU_GPU_TIMER_START_6_END_33', 'DMU_GPU_TIMER_START_8_END_35', + 'DOLBY_VISION_DISABLED', 'DOLBY_VISION_ENABLE', + 'DOLBY_VISION_ENABLED', 'DONUTS', 'DOUT_I2C_ACK', + 'DOUT_I2C_ACK_TO_CLEAN', + 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_ABORT_XFER', + 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', + 'DOUT_I2C_CONTROL_DDC_SELECT', 'DOUT_I2C_CONTROL_GO', + 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_SELECT_DDC1', 'DOUT_I2C_CONTROL_SELECT_DDC2', + 'DOUT_I2C_CONTROL_SELECT_DDC3', 'DOUT_I2C_CONTROL_SELECT_DDC4', + 'DOUT_I2C_CONTROL_SELECT_DDC5', 'DOUT_I2C_CONTROL_SELECT_DDC6', + 'DOUT_I2C_CONTROL_SELECT_DDCVGA', 'DOUT_I2C_CONTROL_SEND_RESET', + 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH', + 'DOUT_I2C_CONTROL_SOFT_RESET', 'DOUT_I2C_CONTROL_START_TRANSFER', + 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 'DOUT_I2C_CONTROL_SW_STATUS_RESET', 'DOUT_I2C_CONTROL_TRANS0', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', + 'DOUT_I2C_CONTROL_TRANSACTION_COUNT', + 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 'DOUT_I2C_DATA_INDEX_WRITE', 'DOUT_I2C_DATA__INDEX_WRITE', + 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 'DOUT_I2C_DDC_EDID_DETECT_STATUS', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL', + 'DOUT_I2C_DDC_SETUP_EDID_CONNECT_DETECTED', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE', + 'DOUT_I2C_DDC_SETUP_EDID_DISCONNECT_DETECTED', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', + 'DOUT_I2C_DDC_SPEED_THRESHOLD', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', + 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET', + 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_NO_ACK', 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', + 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DPCSRX_BPHY_PCS_RX0_CLK', + 'DPCSRX_BPHY_PCS_RX1_CLK', 'DPCSRX_BPHY_PCS_RX2_CLK', + 'DPCSRX_BPHY_PCS_RX3_CLK', + 'DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL', 'DPCSTX_DVI_LINK_MODE', + 'DPCSTX_DVI_LINK_MODE_DUAL_LINK_MASTER', + 'DPCSTX_DVI_LINK_MODE_DUAL_LINK_SLAVER', + 'DPCSTX_DVI_LINK_MODE_NORMAL', 'DPHY_8B10B_CUR_DISP', + 'DPHY_8B10B_CUR_DISP_ONE', 'DPHY_8B10B_CUR_DISP_ZERO', + 'DPHY_8B10B_NOT_RESET', 'DPHY_8B10B_OUTPUT', 'DPHY_8B10B_RESET', + 'DPHY_8B10B_RESETET', 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 'DPHY_ATEST_LANE0_REG_PATTERN', 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 'DPHY_ATEST_LANE1_REG_PATTERN', 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 'DPHY_ATEST_LANE2_REG_PATTERN', 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 'DPHY_ATEST_LANE3_REG_PATTERN', 'DPHY_ATEST_SEL_LANE0', + 'DPHY_ATEST_SEL_LANE1', 'DPHY_ATEST_SEL_LANE2', + 'DPHY_ATEST_SEL_LANE3', 'DPHY_BYPASS', 'DPHY_CRC_CONTINUOUS', + 'DPHY_CRC_CONT_EN', 'DPHY_CRC_DISABLED', 'DPHY_CRC_EN', + 'DPHY_CRC_ENABLED', 'DPHY_CRC_FIELD', 'DPHY_CRC_LANE0_SELECTED', + 'DPHY_CRC_LANE1_SELECTED', 'DPHY_CRC_LANE2_SELECTED', + 'DPHY_CRC_LANE3_SELECTED', 'DPHY_CRC_MST_PHASE_ERROR_ACK', + 'DPHY_CRC_MST_PHASE_ERROR_ACKED', + 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', 'DPHY_CRC_ONE_SHOT', + 'DPHY_CRC_SEL', 'DPHY_CRC_START_FROM_BOTTOM_FIELD', + 'DPHY_CRC_START_FROM_TOP_FIELD', 'DPHY_DBG_OUTPUT', + 'DPHY_FAST_TRAINING_CAPABLE', 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 'DPHY_FEC_ACTIVE', 'DPHY_FEC_DISABLED', 'DPHY_FEC_ENABLE', + 'DPHY_FEC_ENABLED', 'DPHY_FEC_NOT_ACTIVE', 'DPHY_FEC_READY', + 'DPHY_FEC_READY_DIS', 'DPHY_FEC_READY_EN', + 'DPHY_LOAD_BS_COUNT_NOT_STARTED', 'DPHY_LOAD_BS_COUNT_START', + 'DPHY_LOAD_BS_COUNT_STARTED', 'DPHY_NO_SKEW', + 'DPHY_PRBS11_SELECTED', 'DPHY_PRBS23_SELECTED', + 'DPHY_PRBS7_SELECTED', 'DPHY_PRBS_DISABLE', 'DPHY_PRBS_EN', + 'DPHY_PRBS_ENABLE', 'DPHY_PRBS_SEL', + 'DPHY_RX_FAST_TRAINING_CAPABLE', 'DPHY_SKEW_BYPASS', + 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 'DPHY_SW_FAST_TRAINING_START', 'DPHY_SW_FAST_TRAINING_STARTED', + 'DPHY_TRAINING_PATTERN_1', 'DPHY_TRAINING_PATTERN_2', + 'DPHY_TRAINING_PATTERN_3', 'DPHY_TRAINING_PATTERN_4', + 'DPHY_TRAINING_PATTERN_SEL', 'DPHY_WITH_SKEW', 'DPREFCLK_SRC_SEL', + 'DPREFCLK_SRC_SEL_CK', 'DPREFCLK_SRC_SEL_P0PLL', + 'DPREFCLK_SRC_SEL_P1PLL', 'DPREFCLK_SRC_SEL_P2PLL', + 'DPTE_GROUP_SIZE', 'DPTE_GROUP_SIZE_1024B', + 'DPTE_GROUP_SIZE_128B', 'DPTE_GROUP_SIZE_2048B', + 'DPTE_GROUP_SIZE_256B', 'DPTE_GROUP_SIZE_4096B', + 'DPTE_GROUP_SIZE_512B', 'DPTE_GROUP_SIZE_64B', + 'DPTE_GROUP_SIZE_8192B', 'DP_AUX_ARB_CONTROL_ARB_PRIORITY', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', + 'DP_AUX_CONTROL_HPD1_SELECTED', 'DP_AUX_CONTROL_HPD2_SELECTED', + 'DP_AUX_CONTROL_HPD3_SELECTED', 'DP_AUX_CONTROL_HPD4_SELECTED', + 'DP_AUX_CONTROL_HPD5_SELECTED', 'DP_AUX_CONTROL_HPD6_SELECTED', + 'DP_AUX_CONTROL_HPD_SEL', 'DP_AUX_CONTROL_NO_HPD_SELECTED', + 'DP_AUX_CONTROL_TEST_MODE', 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 'DP_AUX_CONTROL_TEST_MODE_ENABLE', + 'DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', + 'DP_AUX_ERR_OCCURRED_ACK', 'DP_AUX_ERR_OCCURRED__ACK', + 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 'DP_AUX_INT_ACK', 'DP_AUX_INT_LS_UPDATE_ACK', + 'DP_AUX_INT_LS_UPDATE_NOT_ACK', 'DP_AUX_INT__ACK', + 'DP_AUX_INT__NOT_ACK', 'DP_AUX_LS_UPDATE_ACK', + 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', 'DP_AUX_PHY_WAKE_LOW_PRIORITY', + 'DP_AUX_PHY_WAKE_PRIORITY', 'DP_AUX_POTENTIAL_ERR_REACHED_ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', 'DP_AUX_RESET', + 'DP_AUX_RESET_ASSERTED', 'DP_AUX_RESET_DEASSERTED', + 'DP_AUX_RESET_DONE', 'DP_AUX_RESET_SEQUENCE_DONE', + 'DP_AUX_RESET_SEQUENCE_NOT_DONE', 'DP_AUX_RX_TIMEOUT_LEN_MUL', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 'DP_AUX_SW_CONTROL_LS_READ_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__TRIG', 'DP_AUX_SW_CONTROL_SW_GO', + 'DP_AUX_SW_CONTROL_SW__GO', 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 'DP_AUX_TX_PRECHARGE_LEN_MUL', 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', + 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', 'DP_COMBINE_FOUR_PIXEL', + 'DP_COMBINE_ONE_PIXEL', 'DP_COMBINE_PIXEL_NUM', + 'DP_COMBINE_TWO_PIXEL', 'DP_COMPONENT_DEPTH', + 'DP_COMPONENT_DEPTH_10BPC', 'DP_COMPONENT_DEPTH_12BPC', + 'DP_COMPONENT_DEPTH_16BPC_RESERVED', 'DP_COMPONENT_DEPTH_6BPC', + 'DP_COMPONENT_DEPTH_8BPC', 'DP_COMPONENT_DEPTH_RESERVED', + 'DP_DPHY_8B10B_EXT_DISP', 'DP_DPHY_8B10B_EXT_DISP_ONE', + 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', + 'DP_DPHY_HBR2_PASS_THROUGH', 'DP_DPHY_HBR2_PATTERN_1', + 'DP_DPHY_HBR2_PATTERN_2_NEG', 'DP_DPHY_HBR2_PATTERN_2_POS', + 'DP_DPHY_HBR2_PATTERN_3', 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE', + 'DP_DSC_444_SIMPLE_422', 'DP_DSC_DISABLE', 'DP_DSC_MODE', + 'DP_DSC_NATIVE_422_420', 'DP_DTO_DESPREAD_DISABLE', + 'DP_DTO_DESPREAD_ENABLE', 'DP_DTO_DS_DISABLE', + 'DP_EMBEDDED_PANEL', 'DP_EMBEDDED_PANEL_MODE', + 'DP_EXTERNAL_PANEL', 'DP_LINK_TRAINING_ALREADY_COMPLETE', + 'DP_LINK_TRAINING_COMPLETE', 'DP_LINK_TRAINING_NOT_COMPLETE', + 'DP_LINK_TRAINING_SWITCH_MODE', 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', 'DP_ML_PHY_SEQ_IMMEDIATE', + 'DP_ML_PHY_SEQ_LINE_NUM', 'DP_ML_PHY_SEQ_MODE', + 'DP_MSA_V_TIMING_OVERRIDE_EN', 'DP_MSE_BLANK_CODE', + 'DP_MSE_BLANK_CODE_SF_FILLED', 'DP_MSE_BLANK_CODE_ZERO_FILLED', + 'DP_MSE_LINK_LINE', 'DP_MSE_LINK_LINE_128_MTP_LONG', + 'DP_MSE_LINK_LINE_256_MTP_LONG', 'DP_MSE_LINK_LINE_32_MTP_LONG', + 'DP_MSE_LINK_LINE_64_MTP_LONG', 'DP_MSE_NOT_ZERO_FE_ENCODER', + 'DP_MSE_SAT_UPDATE_ACT', 'DP_MSE_SAT_UPDATE_NO_ACTION', + 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', + 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', 'DP_MSE_TIMESTAMP_MODE', + 'DP_MSE_ZERO_ENCODER', 'DP_MSE_ZERO_FE_ENCODER', + 'DP_MSO_FOUR_SSTLINK', 'DP_MSO_NUM_OF_SST_LINKS', + 'DP_MSO_ONE_SSTLINK', 'DP_MSO_TWO_SSTLINK', 'DP_PIXEL_ENCODING', + 'DP_PIXEL_ENCODING_RESERVED', 'DP_PIXEL_ENCODING_RGB444', + 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', 'DP_PIXEL_ENCODING_YCBCR420', + 'DP_PIXEL_ENCODING_YCBCR422', 'DP_PIXEL_ENCODING_YCBCR444', + 'DP_PIXEL_ENCODING_Y_ONLY', 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'DP_SEC_ASP_HIGH_PRIORITY', 'DP_SEC_ASP_LOW_PRIORITY', + 'DP_SEC_ASP_PRIORITY', 'DP_SEC_AUDIO_MUTE', + 'DP_SEC_AUDIO_MUTE_HW_CTRL', 'DP_SEC_AUDIO_MUTE_SW_CTRL', + 'DP_SEC_COLLISION_ACK', 'DP_SEC_COLLISION_ACK_CLR_FLAG', + 'DP_SEC_COLLISION_ACK_NO_EFFECT', 'DP_SEC_GSP0_PRIORITY', + 'DP_SEC_GSP_SEND', 'DP_SEC_GSP_SEND_ANY_LINE', + 'DP_SEC_GSP_SEND_PPS', 'DP_SEC_LINE_REFERENCE', + 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', 'DP_SEC_TIMESTAMP_MODE', + 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', 'DP_STEER_OVERFLOW_ACK', + 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', 'DP_STEER_OVERFLOW_MASK', + 'DP_STEER_OVERFLOW_MASKED', 'DP_STEER_OVERFLOW_UNMASK', + 'DP_SYNC_POLARITY', 'DP_SYNC_POLARITY_ACTIVE_HIGH', + 'DP_SYNC_POLARITY_ACTIVE_LOW', 'DP_TU_OVERFLOW_ACK', + 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_TU_OVERFLOW_ACK_NO_EFFECT', 'DP_UDI_1_LANE', 'DP_UDI_2_LANES', + 'DP_UDI_4_LANES', 'DP_UDI_LANES', 'DP_UDI_LANES_RESERVED', + 'DP_VID_ENHANCED_FRAME_MODE', 'DP_VID_M_1X_INPUT_PIXEL_RATE', + 'DP_VID_M_2X_INPUT_PIXEL_RATE', 'DP_VID_M_4X_INPUT_PIXEL_RATE', + 'DP_VID_M_8X_INPUT_PIXEL_RATE', 'DP_VID_M_N_CALC_AUTO', + 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', + 'DP_VID_M_N_DOUBLE_BUFFER_MODE', 'DP_VID_M_N_GEN_EN', + 'DP_VID_M_N_PROGRAMMED_VIA_REG', 'DP_VID_N_MUL', + 'DP_VID_STREAM_DISABLE_ACK', 'DP_VID_STREAM_DISABLE_MASK', + 'DP_VID_STREAM_DIS_DEFER', 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', 'DP_VID_STREAM_DIS_NO_DEFER', + 'DP_VID_VBID_FIELD_POL', 'DP_VID_VBID_FIELD_POL_INV', + 'DP_VID_VBID_FIELD_POL_NORMAL', 'DRAW_DONE', + 'DRR_UPDATE_LOCK_SEL', 'DRR_UPDATE_LOCK_SEL_0', + 'DRR_UPDATE_LOCK_SEL_1', 'DRR_UPDATE_LOCK_SEL_2', + 'DRR_UPDATE_LOCK_SEL_3', 'DRR_UPDATE_LOCK_SEL_4', + 'DRR_UPDATE_LOCK_SEL_5', 'DSCCIF_BITS_PER_COMPONENT_ENUM', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCCIF_ENABLE_ENUM', 'DSCCIF_ENABLE_ENUM_DISABLED', + 'DSCCIF_ENABLE_ENUM_ENABLED', 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 'DSCC_BITS_PER_COMPONENT_ENUM', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCC_DSC_VERSION_MAJOR_ENUM', + 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', + 'DSCC_ENABLE_ENUM', 'DSCC_ENABLE_ENUM_DISABLED', + 'DSCC_ENABLE_ENUM_ENABLED', 'DSCC_ICH_RESET_ENUM', + 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', 'DSCC_LINEBUF_DEPTH_ENUM', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 'DSCC_MEM_PWR_DIS_ENUM', 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', + 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', 'DSCC_MEM_PWR_FORCE_ENUM', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 'DSCL_MODE_CHROMA_SCALING_BYPASS', 'DSCL_MODE_DSCL_BYPASS', + 'DSCL_MODE_LUMA_SCALING_BYPASS', 'DSCL_MODE_SCALING_444_BYPASS', + 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 'DSCL_MODE_SCALING_YCBCR_ENABLE', 'DSCL_MODE_SEL', 'DSM_DATA_SEL', + 'DSM_DATA_SEL_0', 'DSM_DATA_SEL_1', 'DSM_DATA_SEL_BOTH', + 'DSM_DATA_SEL_DISABLE', 'DSM_ENABLE_ERROR_INJECT', + 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 'DSM_ENABLE_ERROR_INJECT_SINGLE', + 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE', + 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED', + 'DSM_SELECT_INJECT_DELAY', 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', + 'DSM_SELECT_INJECT_DELAY_NO_DELAY', 'DSM_SINGLE_WRITE', + 'DSM_SINGLE_WRITE_DIS', 'DSM_SINGLE_WRITE_EN', 'DS_HW_CAL_DIS', + 'DS_HW_CAL_EN', 'DS_HW_CAL_ENABLE', 'DS_JITTER_COUNT_SRC_SEL', + 'DS_JITTER_COUNT_SRC_SEL0', 'DS_JITTER_COUNT_SRC_SEL1', + 'DS_REF_IS_EXT_GENLOCK', 'DS_REF_IS_PCIE', 'DS_REF_IS_XTALIN', + 'DS_REF_SRC', 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_IN_PHASE', 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_PHASE', 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', + 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', 'DVOACLKD_IN_PHASE', + 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', 'DVOACLK_COARSE_SKEW_CNTL', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 'DVOACLK_FINE_SKEW_CNTL', 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', 'DVO_ENABLE_RST', + 'DVO_ENABLE_RST_DISABLE', 'DVO_ENABLE_RST_ENABLE', + 'DWB_DATA_DEPTH_WARMUP_10BPC', 'DWB_DATA_DEPTH_WARMUP_8BPC', + 'DWB_DATA_DEPTH_WARMUP_ENUM', 'DWB_GMC_WARM_UP_DISABLE', + 'DWB_GMC_WARM_UP_ENABLE', 'DWB_GMC_WARM_UP_ENABLE_ENUM', + 'DWB_MODE_WARMUP_420', 'DWB_MODE_WARMUP_444', + 'DWB_MODE_WARMUP_ENUM', 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE', + 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0', + 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1', + 'DYNAMIC_DEEP_SLEEP_EN', 'DYNAMIC_DEEP_SLEEP_ENABLE', + 'DYNAMIC_LIGHT_SLEEP_EN', 'DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DYNAMIC_SHUT_DOWN_ENABLE', 'DbMemArbWatermarks', + 'DbPRTFaultBehavior', 'DbPSLControl', 'DepthArray', 'DepthFormat', + 'EARLY_Z_THEN_LATE_Z', 'EARLY_Z_THEN_RE_Z', + 'EFC_ACrYCb16161616_10LSB', 'EFC_ACrYCb16161616_10MSB', + 'EFC_ACrYCb16161616_12LSB', 'EFC_ACrYCb16161616_12MSB', + 'EFC_ACrYCb2101010', 'EFC_ACrYCb8888', 'EFC_ARGB1555', + 'EFC_ARGB16161616_10LSB', 'EFC_ARGB16161616_10MSB', + 'EFC_ARGB16161616_12LSB', 'EFC_ARGB16161616_12MSB', + 'EFC_ARGB16161616_FLOAT', 'EFC_ARGB16161616_SNORM', + 'EFC_ARGB16161616_UNORM', 'EFC_ARGB2101010', 'EFC_ARGB4444', + 'EFC_ARGB8888', 'EFC_AYCrCb16161616_10LSB', + 'EFC_AYCrCb16161616_10MSB', 'EFC_AYCrCb16161616_12LSB', + 'EFC_AYCrCb16161616_12MSB', 'EFC_AYCrCb8888', 'EFC_BGR101111_FIX', + 'EFC_BGR101111_FLOAT', 'EFC_BGR565', + 'EFC_CbYCrY10101010_422_PACKED', 'EFC_CbYCrY12121212_422_PACKED', + 'EFC_CbYCrY8888_422_PACKED', 'EFC_CrYCbA1010102', + 'EFC_CrYCbA16161616_10LSB', 'EFC_CrYCbA16161616_10MSB', + 'EFC_CrYCbA16161616_12LSB', 'EFC_CrYCbA16161616_12MSB', + 'EFC_CrYCbA8888', 'EFC_CrYCbY10101010_422_PACKED', + 'EFC_CrYCbY12121212_422_PACKED', 'EFC_CrYCbY8888_422_PACKED', + 'EFC_MONO_10LSB', 'EFC_MONO_10MSB', 'EFC_MONO_12LSB', + 'EFC_MONO_12MSB', 'EFC_MONO_16', 'EFC_MONO_8', + 'EFC_RGB111110_FIX', 'EFC_RGB111110_FLOAT', 'EFC_RGB565', + 'EFC_RGBA1010102', 'EFC_RGBA16161616_10LSB', + 'EFC_RGBA16161616_10MSB', 'EFC_RGBA16161616_12LSB', + 'EFC_RGBA16161616_12MSB', 'EFC_RGBA16161616_FLOAT', + 'EFC_RGBA16161616_SNORM', 'EFC_RGBA16161616_UNORM', + 'EFC_RGBA4444', 'EFC_RGBA5551', 'EFC_RGBA8888', + 'EFC_SURFACE_PIXEL_FORMAT', 'EFC_Y10_CbCr1010_420_PLANAR', + 'EFC_Y10_CrCb1010_420_PLANAR', 'EFC_Y12_CbCr1212_420_PLANAR', + 'EFC_Y12_CrCb1212_420_PLANAR', 'EFC_Y8_CbCr88_420_PLANAR', + 'EFC_Y8_CrCb88_420_PLANAR', 'EFC_YCbYCr10101010_422_PACKED', + 'EFC_YCbYCr12121212_422_PACKED', 'EFC_YCbYCr8888_422_PACKED', + 'EFC_YCrCbA16161616_10LSB', 'EFC_YCrCbA16161616_10MSB', + 'EFC_YCrCbA16161616_12LSB', 'EFC_YCrCbA16161616_12MSB', + 'EFC_YCrCbA8888', 'EFC_YCrYCb10101010_422_PACKED', + 'EFC_YCrYCb12121212_422_PACKED', 'EFC_YCrYCb8888_422_PACKED', + 'EIGHT_BANKS', 'EIGHT_FRAGMENTS', 'EIGHT_PIPES', + 'EIGHT_SHADER_ENGINS', 'ENABLE', 'ENABLE_CLOCK', 'ENABLE_ENUM', + 'ENABLE_ENUM_DISABLED', 'ENABLE_ENUM_ENABLED', + 'ENABLE_JITTER_REMOVAL', 'ENABLE_LEGACY_PIPELINE', + 'ENABLE_MEM_PWR_CTRL', 'ENABLE_NGG_PIPELINE', 'ENABLE_THE_CLOCK', + 'ENABLE_THE_FEATURE', 'ENABLE_THE_INTERRUPT', 'ENDIAN_8IN16', + 'ENDIAN_8IN32', 'ENDIAN_8IN64', 'ENDIAN_NONE', + 'END_OF_PIPE_IB_END', 'END_OF_PIPE_INCR_DE', + 'ENGG_CSB_DELAY_BIN00', 'ENGG_CSB_DELAY_BIN01', + 'ENGG_CSB_DELAY_BIN02', 'ENGG_CSB_DELAY_BIN03', + 'ENGG_CSB_DELAY_BIN04', 'ENGG_CSB_DELAY_BIN05', + 'ENGG_CSB_DELAY_BIN06', 'ENGG_CSB_DELAY_BIN07', + 'ENGG_CSB_DELAY_BIN08', 'ENGG_CSB_DELAY_BIN09', + 'ENGG_CSB_DELAY_BIN10', 'ENGG_CSB_DELAY_BIN11', + 'ENGG_CSB_DELAY_BIN12', 'ENGG_CSB_DELAY_BIN13', + 'ENGG_CSB_DELAY_BIN14', 'ENGG_CSB_DELAY_BIN15', + 'ENGG_CSB_GE_INPUT_FIFO_FULL', 'ENGG_CSB_GE_SENDING_SUBGROUP', + 'ENGG_CSB_MACHINE_IS_STARVED', + 'ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 'ENGG_CSB_MACHINE_STALLED_BY_SPI', + 'ENGG_CSB_OBJECTID_INPUT_FIFO_FULL', 'ENGG_CSB_PRIM_COUNT_EQ0', + 'ENGG_CSB_SPI_DELAY_BIN00', 'ENGG_CSB_SPI_DELAY_BIN01', + 'ENGG_CSB_SPI_DELAY_BIN02', 'ENGG_CSB_SPI_DELAY_BIN03', + 'ENGG_CSB_SPI_DELAY_BIN04', 'ENGG_CSB_SPI_DELAY_BIN05', + 'ENGG_CSB_SPI_DELAY_BIN06', 'ENGG_CSB_SPI_DELAY_BIN07', + 'ENGG_CSB_SPI_DELAY_BIN08', 'ENGG_CSB_SPI_DELAY_BIN09', + 'ENGG_CSB_SPI_DELAY_BIN10', 'ENGG_CSB_SPI_DELAY_BIN11', + 'ENGG_CSB_SPI_DELAY_BIN12', 'ENGG_CSB_SPI_DELAY_BIN13', + 'ENGG_CSB_SPI_DELAY_BIN14', 'ENGG_CSB_SPI_DELAY_BIN15', + 'ENGG_CSB_SPI_INPUT_FIFO_FULL', + 'ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 'ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 'ENGG_INDEX_PRIM_IF_QUALIFIED_BUSY', + 'ENGG_INDEX_PRIM_IF_QUALIFIED_STARVED', + 'ENGG_INDEX_PRIM_IF_REUSE_0_NEW_VERTS_THIS_PRIM', + 'ENGG_INDEX_PRIM_IF_REUSE_1_NEW_VERTS_THIS_PRIM', + 'ENGG_INDEX_PRIM_IF_REUSE_2_NEW_VERTS_THIS_PRIM', + 'ENGG_INDEX_PRIM_IF_REUSE_3_NEW_VERTS_THIS_PRIM', + 'ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 'ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 'ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 'ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', 'ENGG_INDEX_REQ_STARVED', + 'ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 'ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 'ENGG_INDEX_RET_SXRX_READING_EVENT', + 'ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS', + 'ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS', + 'ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 'ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 'ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 'ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 'ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 'ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 'ENGG_POS_REQ_STALLED_BY_FULL_CLIPV_FIFO', 'ENGG_POS_REQ_STARVED', + 'ENUMS_GDS_PERFCOUNT_SELECT_H', 'ENUM_DPG_BIT_DEPTH', + 'ENUM_DPG_BIT_DEPTH_10BPC', 'ENUM_DPG_BIT_DEPTH_12BPC', + 'ENUM_DPG_BIT_DEPTH_6BPC', 'ENUM_DPG_BIT_DEPTH_8BPC', + 'ENUM_DPG_DISABLE', 'ENUM_DPG_DYNAMIC_RANGE', + 'ENUM_DPG_DYNAMIC_RANGE_CEA', 'ENUM_DPG_DYNAMIC_RANGE_VESA', + 'ENUM_DPG_EN', 'ENUM_DPG_ENABLE', 'ENUM_DPG_FIELD_POLARITY', + 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', 'ENUM_DPG_MODE', + 'ENUM_DPG_MODE_HORIZONTAL_BAR', 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 'ENUM_DPG_MODE_RGB_DUAL_RAMP', 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 'ENUM_DPG_MODE_RGB_XR_BIAS', 'ENUM_DPG_MODE_VERTICAL_BAR', + 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 'ENUM_FMT_PTI_FIELD_POLARITY', + 'ENUM_FMT_PTI_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 'ENUM_FMT_PTI_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', + 'ENUM_NUM_SIMD_PER_CU', 'ES_STAGE_DS', 'ES_STAGE_OFF', + 'ES_STAGE_REAL', 'EXPORT_16_16_FLOAT_8PIX', + 'EXPORT_16_16_SIGNED_8PIX', 'EXPORT_16_16_UNSIGNED_8PIX', + 'EXPORT_2C_32BPC_AR', 'EXPORT_2C_32BPC_GR', + 'EXPORT_2P_32BPC_ABGR', 'EXPORT_32BPP_8PIX', 'EXPORT_32_ABGR', + 'EXPORT_32_AR', 'EXPORT_32_GR', 'EXPORT_32_R', 'EXPORT_4C_16BPC', + 'EXPORT_4C_32BPC', 'EXPORT_4P_16BPC_ABGR', 'EXPORT_4P_32BPC_ABGR', + 'EXPORT_4P_32BPC_AR', 'EXPORT_4P_32BPC_GR', 'EXPORT_8P_32BPC_R', + 'EXPORT_ANY_Z', 'EXPORT_FP16_ABGR', 'EXPORT_GREATER_THAN_Z', + 'EXPORT_LESS_THAN_Z', 'EXPORT_RESERVED', 'EXPORT_SIGNED16_ABGR', + 'EXPORT_UNSIGNED16_ABGR', 'EXPORT_UNUSED', 'FAULT_FAIL', + 'FAULT_ONE', 'FAULT_PASS', 'FAULT_ZERO', 'FEC_ACTIVE_STATUS', + 'FIX_S2_13', 'FIX_S3_12', 'FLIP_ANY_FRAME', 'FLIP_LEFT_EYE', + 'FLIP_RATE', 'FLIP_RATE_0', 'FLIP_RATE_1', 'FLIP_RATE_2', + 'FLIP_RATE_3', 'FLIP_RATE_4', 'FLIP_RATE_5', 'FLIP_RATE_6', + 'FLIP_RATE_7', 'FLIP_RIGHT_EYE', 'FLUSH_AND_INV_CB_DATA_TS', + 'FLUSH_AND_INV_CB_META', 'FLUSH_AND_INV_CB_PIXEL_DATA', + 'FLUSH_AND_INV_DB_DATA_TS', 'FLUSH_AND_INV_DB_META', + 'FLUSH_CONTROL_FLUSH_NOT_STARTED', 'FLUSH_CONTROL_FLUSH_STARTED', + 'FLUSH_DFSM', 'FLUSH_ES_OUTPUT', 'FLUSH_HS_OUTPUT', 'FLUSH_SX_TS', + 'FMTMEM_DISABLE_MEM_PWR_CTRL', 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', 'FMTMEM_NO_FORCE_REQUEST', + 'FMTMEM_PWR_DIS_CTRL', 'FMTMEM_PWR_FORCE_CTRL', 'FMT_1', + 'FMT_10_10_10_2', 'FMT_10_11_11', 'FMT_10_11_11_FLOAT', + 'FMT_11_11_10', 'FMT_11_11_10_FLOAT', 'FMT_16', 'FMT_16_16', + 'FMT_16_16_16', 'FMT_16_16_16_16', 'FMT_16_16_16_16_FLOAT', + 'FMT_16_16_16_FLOAT', 'FMT_16_16_FLOAT', 'FMT_16_FLOAT', + 'FMT_1_5_5_5', 'FMT_1_REVERSED', 'FMT_24_8', 'FMT_24_8_FLOAT', + 'FMT_2_10_10_10', 'FMT_32', 'FMT_32_32', 'FMT_32_32_32', + 'FMT_32_32_32_32', 'FMT_32_32_32_32_FLOAT', 'FMT_32_32_32_FLOAT', + 'FMT_32_32_FLOAT', 'FMT_32_AS_32_32_32_32', 'FMT_32_AS_8', + 'FMT_32_AS_8_8', 'FMT_32_FLOAT', 'FMT_3_3_2', 'FMT_4_4', + 'FMT_4_4_4_4', 'FMT_5_5_5_1', 'FMT_5_6_5', + 'FMT_5_9_9_9_SHAREDEXP', 'FMT_6_5_5', 'FMT_8', 'FMT_8_24', + 'FMT_8_24_FLOAT', 'FMT_8_8', 'FMT_8_8_8', 'FMT_8_8_8_8', + 'FMT_APC3', 'FMT_APC4', 'FMT_APC5', 'FMT_APC6', 'FMT_APC7', + 'FMT_BC1', 'FMT_BC2', 'FMT_BC3', 'FMT_BC4', 'FMT_BC5', 'FMT_BC6', + 'FMT_BC7', 'FMT_BG_RG', 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 'FMT_CLAMP_CNTL_COLOR_FORMAT', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', + 'FMT_CONTROL_PIXEL_ENCODING', + 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', + 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 'FMT_CONTROL_SUBSAMPLING_MODE', + 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', + 'FMT_CONTROL_SUBSAMPLING_ORDER', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', 'FMT_CTX1', + 'FMT_DYNAMIC_EXP_MODE', 'FMT_DYNAMIC_EXP_MODE_10to12', + 'FMT_DYNAMIC_EXP_MODE_8to12', 'FMT_FRAME_RANDOM_ENABLE_CONTROL', + 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', 'FMT_GB_GR', 'FMT_INVALID', + 'FMT_POWER_STATE_ENUM', 'FMT_POWER_STATE_ENUM_DS', + 'FMT_POWER_STATE_ENUM_LS', 'FMT_POWER_STATE_ENUM_ON', + 'FMT_POWER_STATE_ENUM_SD', 'FMT_RESERVED_33', 'FMT_RESERVED_36', + 'FMT_RESERVED_4', 'FMT_RESERVED_63', + 'FMT_RGB_RANDOM_ENABLE_CONTROL', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', + 'FMT_SPATIAL_DITHER_MODE', 'FMT_SPATIAL_DITHER_MODE_0', + 'FMT_SPATIAL_DITHER_MODE_1', 'FMT_SPATIAL_DITHER_MODE_2', + 'FMT_SPATIAL_DITHER_MODE_3', 'FMT_STEREOSYNC_OVERRIDE_CONTROL', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', + 'FMT_X24_8_32_FLOAT', 'FORCE_00', 'FORCE_BINNING_ON', + 'FORCE_DEEP_SLEEP_REQUEST', 'FORCE_DISABLE', 'FORCE_EARLY_Z', + 'FORCE_ENABLE', 'FORCE_FF', 'FORCE_LATE_Z', + 'FORCE_LIGHT_SLEEP_REQ', 'FORCE_LIGHT_SLEEP_REQUEST', 'FORCE_OFF', + 'FORCE_OPT_AUTO', 'FORCE_OPT_DISABLE', + 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 'FORCE_OPT_ENABLE_IF_SRC_A_1', 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', 'FORCE_RESERVED', 'FORCE_RE_Z', + 'FORCE_SENT', 'FORCE_SHUT_DOWN_REQUEST', 'FORCE_SUMM_BOTH', + 'FORCE_SUMM_MAXZ', 'FORCE_SUMM_MINZ', 'FORCE_SUMM_OFF', + 'FOUR_BANKS', 'FOUR_FRAGMENTS', 'FOUR_PIPES', 'FOUR_RB_PER_SE', + 'FOUR_SHADER_ENGINS', 'FRAG_ALWAYS', 'FRAG_EQUAL', 'FRAG_GEQUAL', + 'FRAG_GREATER', 'FRAG_LEQUAL', 'FRAG_LESS', 'FRAG_NEVER', + 'FRAG_NOTEQUAL', 'FULL_TILE_WAVE_BREAK_BC_ONLY', + 'FULL_TILE_WAVE_BREAK_BOTH', 'FULL_TILE_WAVE_BREAK_NBC_ONLY', + 'FULL_TILE_WAVE_BREAK_NONE', 'ForceControl', 'FullTileWaveBreak', + 'GAMUT_COEF', 'GAMUT_COEF_B', 'GATCL1RequestType', + 'GATCL1_TYPE_BYPASS', 'GATCL1_TYPE_NORMAL', + 'GATCL1_TYPE_SHOOTDOWN', 'GB_EDC_DED_MODE', + 'GB_EDC_DED_MODE_HALT', 'GB_EDC_DED_MODE_INT_HALT', + 'GB_EDC_DED_MODE_LOG', 'GCRPerfSel', 'GCR_PERF_SEL_ALL_REQ', + 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CPC_ALL_REQ', 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPC_METADATA_REQ', + 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 'GCR_PERF_SEL_CPC_TCP_REQ', + 'GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPF_ALL_REQ', 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPF_METADATA_REQ', + 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 'GCR_PERF_SEL_CPF_TCP_REQ', + 'GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPG_ALL_REQ', 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPG_METADATA_REQ', + 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 'GCR_PERF_SEL_CPG_TCP_REQ', + 'GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ', 'GCR_PERF_SEL_NONE', + 'GCR_PERF_SEL_PHY_REQ', 'GCR_PERF_SEL_SDMA0_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 'GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_SDMA1_ALL_REQ', 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 'GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_FILTERED_RET', + 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 'GCR_PERF_SEL_UTCL2_REQ', 'GCR_PERF_SEL_UTCL2_RET', + 'GCR_PERF_SEL_VIRT_REQ', 'GDS_PERFCOUNT_SELECT', + 'GDS_PERF_SEL_DS_ADDR_CONFL', 'GDS_PERF_SEL_DS_BANK_CONFL', + 'GDS_PERF_SEL_GWS_BYPASS', 'GDS_PERF_SEL_GWS_RELEASED', + 'GDS_PERF_SEL_RBUF_HIT', 'GDS_PERF_SEL_RBUF_MISS', + 'GDS_PERF_SEL_SE0_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE0_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE0_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE0_SH0_NORET', + 'GDS_PERF_SEL_SE0_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_SH0_RET', + 'GDS_PERF_SEL_SE0_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE0_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE0_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE0_SH1_NORET', + 'GDS_PERF_SEL_SE0_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_SH1_RET', + 'GDS_PERF_SEL_SE1_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE1_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE1_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE1_SH0_NORET', + 'GDS_PERF_SEL_SE1_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE1_SH0_RET', + 'GDS_PERF_SEL_SE1_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE1_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE1_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE1_SH1_NORET', + 'GDS_PERF_SEL_SE1_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE1_SH1_RET', + 'GDS_PERF_SEL_SE2_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE2_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE2_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE2_SH0_NORET', + 'GDS_PERF_SEL_SE2_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE2_SH0_RET', + 'GDS_PERF_SEL_SE2_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE2_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE2_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE2_SH1_NORET', + 'GDS_PERF_SEL_SE2_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE2_SH1_RET', + 'GDS_PERF_SEL_SE3_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE3_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE3_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE3_SH0_NORET', + 'GDS_PERF_SEL_SE3_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE3_SH0_RET', + 'GDS_PERF_SEL_SE3_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE3_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE3_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE3_SH1_NORET', + 'GDS_PERF_SEL_SE3_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE3_SH1_RET', + 'GDS_PERF_SEL_WBUF_FLUSH', 'GDS_PERF_SEL_WBUF_WR', + 'GDS_PERF_SEL_WR_COMP', 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', + 'GENERIC_STEREOSYNC_SEL', 'GENERIC_STEREOSYNC_SEL_D1', + 'GENERIC_STEREOSYNC_SEL_D2', 'GENERIC_STEREOSYNC_SEL_D3', + 'GENERIC_STEREOSYNC_SEL_D4', 'GENERIC_STEREOSYNC_SEL_D5', + 'GENERIC_STEREOSYNC_SEL_D6', 'GENERIC_STEREOSYNC_SEL_RESERVED', + 'GE_PERFCOUNT_SELECT', 'GL0V_CACHE_POLICIES', + 'GL0V_CACHE_POLICY_HIT_EVICT', 'GL0V_CACHE_POLICY_HIT_LRU', + 'GL0V_CACHE_POLICY_MISS_EVICT', 'GL0V_CACHE_POLICY_MISS_LRU', + 'GL1A_PERF_SEL', 'GL1A_PERF_SEL_ARB_REQUESTS', + 'GL1A_PERF_SEL_BUSY', 'GL1A_PERF_SEL_CYCLE', + 'GL1A_PERF_SEL_IO_32B_WDS_GL1C0', + 'GL1A_PERF_SEL_IO_32B_WDS_GL1C1', + 'GL1A_PERF_SEL_IO_32B_WDS_GL1C2', + 'GL1A_PERF_SEL_IO_32B_WDS_GL1C3', + 'GL1A_PERF_SEL_IO_32B_WDS_GL1C4', + 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C0', + 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C1', + 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C2', + 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C3', + 'GL1A_PERF_SEL_IO_BURST_COUNT_GL1C4', + 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C0', + 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C1', + 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C2', + 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C3', + 'GL1A_PERF_SEL_MEM_32B_WDS_GL1C4', + 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C0', + 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C1', + 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C2', + 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C3', + 'GL1A_PERF_SEL_MEM_BURST_COUNT_GL1C4', + 'GL1A_PERF_SEL_REQUEST_GL1C0', 'GL1A_PERF_SEL_REQUEST_GL1C1', + 'GL1A_PERF_SEL_REQUEST_GL1C2', 'GL1A_PERF_SEL_REQUEST_GL1C3', + 'GL1A_PERF_SEL_REQUEST_GL1C4', 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'GL1A_PERF_SEL_STALL_GL1C0', 'GL1A_PERF_SEL_STALL_GL1C1', + 'GL1A_PERF_SEL_STALL_GL1C2', 'GL1A_PERF_SEL_STALL_GL1C3', + 'GL1A_PERF_SEL_STALL_GL1C4', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C4', 'GL1CG_PERF_SEL', + 'GL1CG_PERF_SEL_CORE_REG_SCLK_VLD', 'GL1CG_PERF_SEL_CYCLE', + 'GL1CG_PERF_SEL_GATE_EN1', 'GL1CG_PERF_SEL_GATE_EN2', + 'GL1CG_PERF_SEL_REQ', 'GL1CG_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES', + 'GL1CG_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES', 'GL1C_PERF_SEL', + 'GL1C_PERF_SEL_CORE_REG_SCLK_VLD', 'GL1C_PERF_SEL_CYCLE', + 'GL1C_PERF_SEL_GATE_EN1', 'GL1C_PERF_SEL_GATE_EN2', + 'GL1C_PERF_SEL_REQ', 'GL1C_PERF_SEL_TA_GL1C_ADDR_STARVE_CYCLES', + 'GL1C_PERF_SEL_TA_GL1C_DATA_STARVE_CYCLES', 'GL1_CACHE_POLICIES', + 'GL1_CACHE_POLICY_HIT_EVICT', 'GL1_CACHE_POLICY_HIT_LRU', + 'GL1_CACHE_POLICY_MISS_EVICT', 'GL1_CACHE_POLICY_MISS_LRU', + 'GL1_CACHE_STORE_POLICIES', 'GL1_CACHE_STORE_POLICY_BYPASS', + 'GL2A_PERF_SEL', 'GL2A_PERF_SEL_BUSY', 'GL2A_PERF_SEL_CYCLE', + 'GL2A_PERF_SEL_NONE', 'GL2A_PERF_SEL_REQ_BURST_GL2C0', + 'GL2A_PERF_SEL_REQ_BURST_GL2C1', 'GL2A_PERF_SEL_REQ_BURST_GL2C2', + 'GL2A_PERF_SEL_REQ_BURST_GL2C3', 'GL2A_PERF_SEL_REQ_BURST_GL2C4', + 'GL2A_PERF_SEL_REQ_BURST_GL2C5', 'GL2A_PERF_SEL_REQ_BURST_GL2C6', + 'GL2A_PERF_SEL_REQ_BURST_GL2C7', 'GL2A_PERF_SEL_REQ_GL2C0', + 'GL2A_PERF_SEL_REQ_GL2C1', 'GL2A_PERF_SEL_REQ_GL2C2', + 'GL2A_PERF_SEL_REQ_GL2C3', 'GL2A_PERF_SEL_REQ_GL2C4', + 'GL2A_PERF_SEL_REQ_GL2C5', 'GL2A_PERF_SEL_REQ_GL2C6', + 'GL2A_PERF_SEL_REQ_GL2C7', 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7', + 'GL2A_PERF_SEL_REQ_STALL_GL2C0', 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 'GL2A_PERF_SEL_REQ_STALL_GL2C2', 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 'GL2A_PERF_SEL_REQ_STALL_GL2C4', 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 'GL2A_PERF_SEL_REQ_STALL_GL2C6', 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', + 'GL2A_PERF_SEL_RTN_CLIENT0', 'GL2A_PERF_SEL_RTN_CLIENT1', + 'GL2A_PERF_SEL_RTN_CLIENT2', 'GL2A_PERF_SEL_RTN_CLIENT3', + 'GL2A_PERF_SEL_RTN_CLIENT4', 'GL2A_PERF_SEL_RTN_CLIENT5', + 'GL2A_PERF_SEL_RTN_CLIENT6', 'GL2A_PERF_SEL_RTN_CLIENT7', + 'GL2A_PERF_SEL_RTN_STALL_GL2C0', 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 'GL2A_PERF_SEL_RTN_STALL_GL2C2', 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 'GL2A_PERF_SEL_RTN_STALL_GL2C4', 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 'GL2A_PERF_SEL_RTN_STALL_GL2C6', 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 'GL2C_PERF_SEL', 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 'GL2C_PERF_SEL_ATOMIC', 'GL2C_PERF_SEL_BUBBLE', + 'GL2C_PERF_SEL_BUSY', 'GL2C_PERF_SEL_BYPASS_REQ', + 'GL2C_PERF_SEL_CLIENT0_REQ', 'GL2C_PERF_SEL_CLIENT1_REQ', + 'GL2C_PERF_SEL_CLIENT2_REQ', 'GL2C_PERF_SEL_CLIENT3_REQ', + 'GL2C_PERF_SEL_CLIENT4_REQ', 'GL2C_PERF_SEL_CLIENT5_REQ', + 'GL2C_PERF_SEL_CLIENT6_REQ', 'GL2C_PERF_SEL_CLIENT7_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL0_REQ', 'GL2C_PERF_SEL_CM_CHANNEL10_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL11_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL12_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL13_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL14_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL15_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL16_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL17_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL18_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL19_REQ', 'GL2C_PERF_SEL_CM_CHANNEL1_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL20_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL21_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL22_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL23_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL24_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL25_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL26_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL27_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL28_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL29_REQ', 'GL2C_PERF_SEL_CM_CHANNEL2_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL30_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL31_REQ', 'GL2C_PERF_SEL_CM_CHANNEL3_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL4_REQ', 'GL2C_PERF_SEL_CM_CHANNEL5_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL6_REQ', 'GL2C_PERF_SEL_CM_CHANNEL7_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL8_REQ', 'GL2C_PERF_SEL_CM_CHANNEL9_REQ', + 'GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ', + 'GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ', + 'GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ', + 'GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_READ_REQ', + 'GL2C_PERF_SEL_CM_COMP_STENCIL_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ', + 'GL2C_PERF_SEL_CM_DCC_STALL', 'GL2C_PERF_SEL_CM_FULL_WRITE_REQ', + 'GL2C_PERF_SEL_CM_MERGE_BUF_FULL', + 'GL2C_PERF_SEL_CM_METADATA_WR_REQ', 'GL2C_PERF_SEL_CM_NOOP_REQ', + 'GL2C_PERF_SEL_CM_NO_ACK_REQ', 'GL2C_PERF_SEL_CM_READ_BACK_REQ', + 'GL2C_PERF_SEL_CM_RVF_FULL', 'GL2C_PERF_SEL_CM_SDR_FULL', + 'GL2C_PERF_SEL_CM_WR_ACK_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', 'GL2C_PERF_SEL_CYCLE', + 'GL2C_PERF_SEL_C_RO_S_REQ', 'GL2C_PERF_SEL_C_RO_US_REQ', + 'GL2C_PERF_SEL_C_RW_S_REQ', 'GL2C_PERF_SEL_C_RW_US_REQ', + 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', 'GL2C_PERF_SEL_EA_ATOMIC', + 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', 'GL2C_PERF_SEL_EA_RDREQ_128B', + 'GL2C_PERF_SEL_EA_RDREQ_32B', 'GL2C_PERF_SEL_EA_RDREQ_64B', + 'GL2C_PERF_SEL_EA_RDREQ_96B', 'GL2C_PERF_SEL_EA_RDREQ_DRAM', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', 'GL2C_PERF_SEL_EA_RDRET_NACK', + 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 'GL2C_PERF_SEL_EA_RD_MDC_32B', 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', + 'GL2C_PERF_SEL_EA_WRREQ_64B', 'GL2C_PERF_SEL_EA_WRREQ_DRAM', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 'GL2C_PERF_SEL_EA_WRRET_NACK', 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', + 'GL2C_PERF_SEL_EVICT', 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', + 'GL2C_PERF_SEL_FULL_HIT', 'GL2C_PERF_SEL_GARLIC_READ', + 'GL2C_PERF_SEL_GARLIC_WRITE', 'GL2C_PERF_SEL_GCR_ALL', + 'GL2C_PERF_SEL_GCR_DISCARD', 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', 'GL2C_PERF_SEL_GCR_INV', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', 'GL2C_PERF_SEL_GCR_MDC_INV', + 'GL2C_PERF_SEL_GCR_MDC_INV_ALL', + 'GL2C_PERF_SEL_GCR_MDC_INV_RANGE', 'GL2C_PERF_SEL_GCR_RANGE', + 'GL2C_PERF_SEL_GCR_UNSHARED', 'GL2C_PERF_SEL_GCR_VOL', + 'GL2C_PERF_SEL_GCR_WB', 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_EVICT', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', 'GL2C_PERF_SEL_GL2A_LEVEL', + 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', 'GL2C_PERF_SEL_HIT', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_COMP', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_HI_PRIO', + 'GL2C_PERF_SEL_IB_CM_STALL', 'GL2C_PERF_SEL_IB_REQ', + 'GL2C_PERF_SEL_IB_STALL', 'GL2C_PERF_SEL_IB_TAG_STALL', + 'GL2C_PERF_SEL_INTERNAL_PROBE', 'GL2C_PERF_SEL_IO_READ', + 'GL2C_PERF_SEL_IO_WRITE', 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', + 'GL2C_PERF_SEL_LRU_REQ', 'GL2C_PERF_SEL_MC_RDREQ', + 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', 'GL2C_PERF_SEL_MC_WRREQ', + 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', 'GL2C_PERF_SEL_MC_WRREQ_STALL', + 'GL2C_PERF_SEL_MDC_INV_METADATA', 'GL2C_PERF_SEL_MDC_LEVEL', + 'GL2C_PERF_SEL_MDC_REQ', 'GL2C_PERF_SEL_MDC_SECTOR_HIT', + 'GL2C_PERF_SEL_MDC_SECTOR_MISS', + 'GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_MDC_TAG_HIT', + 'GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 'GL2C_PERF_SEL_MDC_TAG_STALL', + 'GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 'GL2C_PERF_SEL_METADATA_READ_REQ', 'GL2C_PERF_SEL_MISS', + 'GL2C_PERF_SEL_NOA_REQ', 'GL2C_PERF_SEL_NONE', + 'GL2C_PERF_SEL_NOP_ACK', 'GL2C_PERF_SEL_NOP_RTN0', + 'GL2C_PERF_SEL_NORMAL_EVICT', 'GL2C_PERF_SEL_NORMAL_WRITEBACK', + 'GL2C_PERF_SEL_ONION_READ', 'GL2C_PERF_SEL_ONION_WRITE', + 'GL2C_PERF_SEL_PARTIAL_32B_HIT', 'GL2C_PERF_SEL_PARTIAL_64B_HIT', + 'GL2C_PERF_SEL_PARTIAL_96B_HIT', 'GL2C_PERF_SEL_PROBE', + 'GL2C_PERF_SEL_PROBE_ALL', 'GL2C_PERF_SEL_PROBE_EVICT', + 'GL2C_PERF_SEL_PROBE_FILTER_DISABLED', + 'GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 'GL2C_PERF_SEL_READ', 'GL2C_PERF_SEL_READ_128_REQ', + 'GL2C_PERF_SEL_READ_32_REQ', 'GL2C_PERF_SEL_READ_64_REQ', + 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', 'GL2C_PERF_SEL_REQ', + 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', 'GL2C_PERF_SEL_RETURN_ACK', + 'GL2C_PERF_SEL_RETURN_DATA', 'GL2C_PERF_SEL_SHARED_REQ', + 'GL2C_PERF_SEL_SRC_FIFO_FULL', 'GL2C_PERF_SEL_STREAM_REQ', + 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_STALL', + 'GL2C_PERF_SEL_TAG_READ_DST_STALL', 'GL2C_PERF_SEL_TAG_STALL', + 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', 'GL2C_PERF_SEL_UC_REQ', + 'GL2C_PERF_SEL_UNCACHED_WRITE', 'GL2C_PERF_SEL_VOL_REQ', + 'GL2C_PERF_SEL_WRITE', 'GL2C_PERF_SEL_WRITEBACK', + 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 'GL2C_PERF_SEL_WRITE_32_REQ', 'GL2C_PERF_SEL_WRITE_64_REQ', + 'GL2_CACHE_POLICIES', 'GL2_CACHE_POLICY_BYPASS', + 'GL2_CACHE_POLICY_LRU', 'GL2_CACHE_POLICY_NOA', + 'GL2_CACHE_POLICY_STREAM', 'GL2_EA_CID', 'GL2_EA_CID_CLIENT', + 'GL2_EA_CID_CP', 'GL2_EA_CID_CPDMA', 'GL2_EA_CID_DCC', + 'GL2_EA_CID_FMASK', 'GL2_EA_CID_HTILE', 'GL2_EA_CID_RLC', + 'GL2_EA_CID_RT', 'GL2_EA_CID_SDMA', 'GL2_EA_CID_TCPMETA', + 'GL2_EA_CID_UTCL2', 'GL2_EA_CID_ZPCPSD', 'GL2_EA_CID_Z_STENCIL', + 'GL2_NACKS', 'GL2_NACK_DATA_ERROR', 'GL2_NACK_NO_FAULT', + 'GL2_NACK_PAGE_FAULT', 'GL2_NACK_PROTECTION_FAULT', 'GL2_OP', + 'GL2_OP_ATOMIC_ADD_32', 'GL2_OP_ATOMIC_ADD_64', + 'GL2_OP_ATOMIC_ADD_RTN_32', 'GL2_OP_ATOMIC_ADD_RTN_64', + 'GL2_OP_ATOMIC_AND_32', 'GL2_OP_ATOMIC_AND_64', + 'GL2_OP_ATOMIC_AND_RTN_32', 'GL2_OP_ATOMIC_AND_RTN_64', + 'GL2_OP_ATOMIC_CMPSWAP_32', 'GL2_OP_ATOMIC_CMPSWAP_64', + 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_DEC_32', 'GL2_OP_ATOMIC_DEC_64', + 'GL2_OP_ATOMIC_DEC_RTN_32', 'GL2_OP_ATOMIC_DEC_RTN_64', + 'GL2_OP_ATOMIC_FCMPSWAP_32', 'GL2_OP_ATOMIC_FCMPSWAP_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_FMAX_32', 'GL2_OP_ATOMIC_FMAX_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMAX_RTN_32', 'GL2_OP_ATOMIC_FMAX_RTN_64', + 'GL2_OP_ATOMIC_FMIN_32', 'GL2_OP_ATOMIC_FMIN_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMIN_RTN_32', 'GL2_OP_ATOMIC_FMIN_RTN_64', + 'GL2_OP_ATOMIC_INC_32', 'GL2_OP_ATOMIC_INC_64', + 'GL2_OP_ATOMIC_INC_RTN_32', 'GL2_OP_ATOMIC_INC_RTN_64', + 'GL2_OP_ATOMIC_OR_32', 'GL2_OP_ATOMIC_OR_64', + 'GL2_OP_ATOMIC_OR_RTN_32', 'GL2_OP_ATOMIC_OR_RTN_64', + 'GL2_OP_ATOMIC_SMAX_32', 'GL2_OP_ATOMIC_SMAX_64', + 'GL2_OP_ATOMIC_SMAX_RTN_32', 'GL2_OP_ATOMIC_SMAX_RTN_64', + 'GL2_OP_ATOMIC_SMIN_32', 'GL2_OP_ATOMIC_SMIN_64', + 'GL2_OP_ATOMIC_SMIN_RTN_32', 'GL2_OP_ATOMIC_SMIN_RTN_64', + 'GL2_OP_ATOMIC_SUB_32', 'GL2_OP_ATOMIC_SUB_64', + 'GL2_OP_ATOMIC_SUB_RTN_32', 'GL2_OP_ATOMIC_SUB_RTN_64', + 'GL2_OP_ATOMIC_SWAP_32', 'GL2_OP_ATOMIC_SWAP_64', + 'GL2_OP_ATOMIC_SWAP_RTN_32', 'GL2_OP_ATOMIC_SWAP_RTN_64', + 'GL2_OP_ATOMIC_UMAX_32', 'GL2_OP_ATOMIC_UMAX_64', + 'GL2_OP_ATOMIC_UMAX_RTN_32', 'GL2_OP_ATOMIC_UMAX_RTN_64', + 'GL2_OP_ATOMIC_UMIN_32', 'GL2_OP_ATOMIC_UMIN_64', + 'GL2_OP_ATOMIC_UMIN_RTN_32', 'GL2_OP_ATOMIC_UMIN_RTN_64', + 'GL2_OP_ATOMIC_XOR_32', 'GL2_OP_ATOMIC_XOR_64', + 'GL2_OP_ATOMIC_XOR_RTN_32', 'GL2_OP_ATOMIC_XOR_RTN_64', + 'GL2_OP_GL1_INV', 'GL2_OP_MASKS', 'GL2_OP_MASK_64', + 'GL2_OP_MASK_FLUSH_DENROM', 'GL2_OP_MASK_NO_RTN', + 'GL2_OP_NOP_ACK', 'GL2_OP_NOP_RTN0', 'GL2_OP_PROBE_FILTER', + 'GL2_OP_READ', 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', 'GL2_OP_WRITE', + 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE', + 'GLOBAL_CONTROL_CONTROLLER_RESET', 'GLOBAL_CONTROL_FLUSH_CONTROL', + 'GLOBAL_STATUS_FLUSH_STATUS', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 'GL__CONSTANT_ALPHA', 'GL__CONSTANT_COLOR', 'GL__DST_ALPHA', + 'GL__DST_COLOR', 'GL__ONE', 'GL__ONE_MINUS_CONSTANT_ALPHA', + 'GL__ONE_MINUS_CONSTANT_COLOR', 'GL__ONE_MINUS_DST_ALPHA', + 'GL__ONE_MINUS_DST_COLOR', 'GL__ONE_MINUS_SRC_ALPHA', + 'GL__ONE_MINUS_SRC_COLOR', 'GL__SRC_ALPHA', + 'GL__SRC_ALPHA_SATURATE', 'GL__SRC_COLOR', 'GL__ZERO', + 'GRBM_PERF_SEL', 'GRBM_PERF_SEL_BCI_BUSY', + 'GRBM_PERF_SEL_CB_BUSY', 'GRBM_PERF_SEL_CB_CLEAN', + 'GRBM_PERF_SEL_CH_BUSY', 'GRBM_PERF_SEL_COUNT', + 'GRBM_PERF_SEL_CPAXI_BUSY', 'GRBM_PERF_SEL_CPC_BUSY', + 'GRBM_PERF_SEL_CPF_BUSY', 'GRBM_PERF_SEL_CPG_BUSY', + 'GRBM_PERF_SEL_CP_BUSY', 'GRBM_PERF_SEL_CP_COHER_BUSY', + 'GRBM_PERF_SEL_CP_DMA_BUSY', 'GRBM_PERF_SEL_DB_BUSY', + 'GRBM_PERF_SEL_DB_CLEAN', 'GRBM_PERF_SEL_EA_BUSY', + 'GRBM_PERF_SEL_GDS_BUSY', 'GRBM_PERF_SEL_GE_BUSY', + 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', 'GRBM_PERF_SEL_GL1CC_BUSY', + 'GRBM_PERF_SEL_GL2CC_BUSY', 'GRBM_PERF_SEL_GUI_ACTIVE', + 'GRBM_PERF_SEL_GUS_BUSY', 'GRBM_PERF_SEL_PA_BUSY', + 'GRBM_PERF_SEL_PH_BUSY', 'GRBM_PERF_SEL_PMM_BUSY', + 'GRBM_PERF_SEL_RESERVED_0', 'GRBM_PERF_SEL_RESERVED_1', + 'GRBM_PERF_SEL_RESERVED_2', 'GRBM_PERF_SEL_RESERVED_3', + 'GRBM_PERF_SEL_RESERVED_4', 'GRBM_PERF_SEL_RESERVED_5', + 'GRBM_PERF_SEL_RESERVED_6', 'GRBM_PERF_SEL_RESERVED_7', + 'GRBM_PERF_SEL_RESERVED_8', 'GRBM_PERF_SEL_RESERVED_9', + 'GRBM_PERF_SEL_RLC_BUSY', 'GRBM_PERF_SEL_RMI_BUSY', + 'GRBM_PERF_SEL_SC_BUSY', 'GRBM_PERF_SEL_SDMA_BUSY', + 'GRBM_PERF_SEL_SPI_BUSY', 'GRBM_PERF_SEL_SX_BUSY', + 'GRBM_PERF_SEL_TA_BUSY', 'GRBM_PERF_SEL_TCP_BUSY', + 'GRBM_PERF_SEL_USER_DEFINED', 'GRBM_PERF_SEL_UTCL1_BUSY', + 'GRBM_PERF_SEL_UTCL2_BUSY', 'GRBM_SE0_PERF_SEL', + 'GRBM_SE0_PERF_SEL_BCI_BUSY', 'GRBM_SE0_PERF_SEL_CB_BUSY', + 'GRBM_SE0_PERF_SEL_CB_CLEAN', 'GRBM_SE0_PERF_SEL_COUNT', + 'GRBM_SE0_PERF_SEL_DB_BUSY', 'GRBM_SE0_PERF_SEL_DB_CLEAN', + 'GRBM_SE0_PERF_SEL_GL1CC_BUSY', 'GRBM_SE0_PERF_SEL_PA_BUSY', + 'GRBM_SE0_PERF_SEL_RESERVED_0', 'GRBM_SE0_PERF_SEL_RESERVED_1', + 'GRBM_SE0_PERF_SEL_RESERVED_2', 'GRBM_SE0_PERF_SEL_RMI_BUSY', + 'GRBM_SE0_PERF_SEL_SC_BUSY', 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 'GRBM_SE0_PERF_SEL_SX_BUSY', 'GRBM_SE0_PERF_SEL_TA_BUSY', + 'GRBM_SE0_PERF_SEL_TCP_BUSY', 'GRBM_SE0_PERF_SEL_USER_DEFINED', + 'GRBM_SE0_PERF_SEL_UTCL1_BUSY', 'GRBM_SE1_PERF_SEL', + 'GRBM_SE1_PERF_SEL_BCI_BUSY', 'GRBM_SE1_PERF_SEL_CB_BUSY', + 'GRBM_SE1_PERF_SEL_CB_CLEAN', 'GRBM_SE1_PERF_SEL_COUNT', + 'GRBM_SE1_PERF_SEL_DB_BUSY', 'GRBM_SE1_PERF_SEL_DB_CLEAN', + 'GRBM_SE1_PERF_SEL_GL1CC_BUSY', 'GRBM_SE1_PERF_SEL_PA_BUSY', + 'GRBM_SE1_PERF_SEL_RESERVED_0', 'GRBM_SE1_PERF_SEL_RESERVED_1', + 'GRBM_SE1_PERF_SEL_RESERVED_2', 'GRBM_SE1_PERF_SEL_RMI_BUSY', + 'GRBM_SE1_PERF_SEL_SC_BUSY', 'GRBM_SE1_PERF_SEL_SPI_BUSY', + 'GRBM_SE1_PERF_SEL_SX_BUSY', 'GRBM_SE1_PERF_SEL_TA_BUSY', + 'GRBM_SE1_PERF_SEL_TCP_BUSY', 'GRBM_SE1_PERF_SEL_USER_DEFINED', + 'GRBM_SE1_PERF_SEL_UTCL1_BUSY', 'GRBM_SE2_PERF_SEL', + 'GRBM_SE2_PERF_SEL_BCI_BUSY', 'GRBM_SE2_PERF_SEL_CB_BUSY', + 'GRBM_SE2_PERF_SEL_CB_CLEAN', 'GRBM_SE2_PERF_SEL_COUNT', + 'GRBM_SE2_PERF_SEL_DB_BUSY', 'GRBM_SE2_PERF_SEL_DB_CLEAN', + 'GRBM_SE2_PERF_SEL_GL1CC_BUSY', 'GRBM_SE2_PERF_SEL_PA_BUSY', + 'GRBM_SE2_PERF_SEL_RESERVED_0', 'GRBM_SE2_PERF_SEL_RESERVED_1', + 'GRBM_SE2_PERF_SEL_RESERVED_2', 'GRBM_SE2_PERF_SEL_RMI_BUSY', + 'GRBM_SE2_PERF_SEL_SC_BUSY', 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 'GRBM_SE2_PERF_SEL_SX_BUSY', 'GRBM_SE2_PERF_SEL_TA_BUSY', + 'GRBM_SE2_PERF_SEL_TCP_BUSY', 'GRBM_SE2_PERF_SEL_USER_DEFINED', + 'GRBM_SE2_PERF_SEL_UTCL1_BUSY', 'GRBM_SE3_PERF_SEL', + 'GRBM_SE3_PERF_SEL_BCI_BUSY', 'GRBM_SE3_PERF_SEL_CB_BUSY', + 'GRBM_SE3_PERF_SEL_CB_CLEAN', 'GRBM_SE3_PERF_SEL_COUNT', + 'GRBM_SE3_PERF_SEL_DB_BUSY', 'GRBM_SE3_PERF_SEL_DB_CLEAN', + 'GRBM_SE3_PERF_SEL_GL1CC_BUSY', 'GRBM_SE3_PERF_SEL_PA_BUSY', + 'GRBM_SE3_PERF_SEL_RESERVED_0', 'GRBM_SE3_PERF_SEL_RESERVED_1', + 'GRBM_SE3_PERF_SEL_RESERVED_2', 'GRBM_SE3_PERF_SEL_RMI_BUSY', + 'GRBM_SE3_PERF_SEL_SC_BUSY', 'GRBM_SE3_PERF_SEL_SPI_BUSY', + 'GRBM_SE3_PERF_SEL_SX_BUSY', 'GRBM_SE3_PERF_SEL_TA_BUSY', + 'GRBM_SE3_PERF_SEL_TCP_BUSY', 'GRBM_SE3_PERF_SEL_USER_DEFINED', + 'GRBM_SE3_PERF_SEL_UTCL1_BUSY', 'GSTHREADID_SIZE', 'GS_CUT_1024', + 'GS_CUT_128', 'GS_CUT_256', 'GS_CUT_512', 'GS_OFF', + 'GS_SCENARIO_A', 'GS_SCENARIO_B', 'GS_SCENARIO_C', + 'GS_SCENARIO_G', 'GS_STAGE_OFF', 'GS_STAGE_ON', 'GroupInterleave', + 'HDMI_ACR_0_MULTIPLE_RESERVED', 'HDMI_ACR_1_MULTIPLE', + 'HDMI_ACR_2_MULTIPLE', 'HDMI_ACR_3_MULTIPLE_RESERVED', + 'HDMI_ACR_4_MULTIPLE', 'HDMI_ACR_5_MULTIPLE_RESERVED', + 'HDMI_ACR_6_MULTIPLE_RESERVED', 'HDMI_ACR_7_MULTIPLE_RESERVED', + 'HDMI_ACR_AUDIO_PRIORITY', 'HDMI_ACR_CONT', + 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', + 'HDMI_ACR_NOT_SEND', 'HDMI_ACR_N_MULTIPLE', + 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 'HDMI_ACR_PKT_SEND', 'HDMI_ACR_SELECT', 'HDMI_ACR_SELECT_32K', + 'HDMI_ACR_SELECT_44K', 'HDMI_ACR_SELECT_48K', + 'HDMI_ACR_SELECT_HW', 'HDMI_ACR_SEND', 'HDMI_ACR_SOURCE', + 'HDMI_ACR_SOURCE_HW', 'HDMI_ACR_SOURCE_SW', + 'HDMI_AUDIO_DELAY_56CLK', 'HDMI_AUDIO_DELAY_58CLK', + 'HDMI_AUDIO_DELAY_DISABLE', 'HDMI_AUDIO_DELAY_EN', + 'HDMI_AUDIO_DELAY_RESERVED', 'HDMI_AUDIO_INFO_CONT', + 'HDMI_AUDIO_INFO_CONT_DISABLE', 'HDMI_AUDIO_INFO_CONT_ENABLE', + 'HDMI_AUDIO_INFO_NOT_SEND', 'HDMI_AUDIO_INFO_PKT_SEND', + 'HDMI_AUDIO_INFO_SEND', + 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', + 'HDMI_AUDIO_SEND_MAX_PACKETS', + 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_RATE', 'HDMI_DEEP_COLOR_DEPTH', + 'HDMI_DEEP_COLOR_DEPTH_24BPP', 'HDMI_DEEP_COLOR_DEPTH_30BPP', + 'HDMI_DEEP_COLOR_DEPTH_36BPP', 'HDMI_DEEP_COLOR_DEPTH_48BPP', + 'HDMI_DEFAULT_PAHSE', 'HDMI_DEFAULT_PHASE_IS_0', + 'HDMI_DEFAULT_PHASE_IS_1', 'HDMI_ERROR_ACK', 'HDMI_ERROR_ACK_INT', + 'HDMI_ERROR_MASK', 'HDMI_ERROR_MASK_INT', 'HDMI_ERROR_NOT_ACK', + 'HDMI_ERROR_NOT_MASK', 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', + 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', 'HDMI_GC_AVMUTE', + 'HDMI_GC_AVMUTE_CONT', 'HDMI_GC_AVMUTE_CONT_DISABLE', + 'HDMI_GC_AVMUTE_CONT_ENABLE', 'HDMI_GC_AVMUTE_SET', + 'HDMI_GC_AVMUTE_UNSET', 'HDMI_GC_CONT', 'HDMI_GC_CONT_DISABLE', + 'HDMI_GC_CONT_ENABLE', 'HDMI_GC_NOT_SEND', 'HDMI_GC_PKT_SEND', + 'HDMI_GC_SEND', 'HDMI_GENERIC_CONT', 'HDMI_GENERIC_CONT_DISABLE', + 'HDMI_GENERIC_CONT_ENABLE', 'HDMI_GENERIC_NOT_SEND', + 'HDMI_GENERIC_PKT_SEND', 'HDMI_GENERIC_SEND', 'HDMI_ISRC_CONT', + 'HDMI_ISRC_CONT_DISABLE', 'HDMI_ISRC_CONT_ENABLE', + 'HDMI_ISRC_NOT_SEND', 'HDMI_ISRC_PKT_SEND', 'HDMI_ISRC_SEND', + 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', 'HDMI_KEEPOUT_MODE', + 'HDMI_METADATA_ENABLE', 'HDMI_METADATA_NOT_SEND', + 'HDMI_METADATA_PKT_SEND', 'HDMI_MPEG_INFO_CONT', + 'HDMI_MPEG_INFO_CONT_DISABLE', 'HDMI_MPEG_INFO_CONT_ENABLE', + 'HDMI_MPEG_INFO_NOT_SEND', 'HDMI_MPEG_INFO_PKT_SEND', + 'HDMI_MPEG_INFO_SEND', 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 'HDMI_NO_EXTRA_NULL_PACKET_FILLED', 'HDMI_NULL_NOT_SEND', + 'HDMI_NULL_PKT_SEND', 'HDMI_NULL_SEND', 'HDMI_PACKET_GEN_VERSION', + 'HDMI_PACKET_GEN_VERSION_NEW', 'HDMI_PACKET_GEN_VERSION_OLD', + 'HDMI_PACKET_LINE_REFERENCE', 'HDMI_PACKING_PHASE_OVERRIDE', + 'HDMI_PACKING_PHASE_SET_BY_HW', 'HDMI_PACKING_PHASE_SET_BY_SW', + 'HDMI_PKT_LINE_REF_OTGSOF', 'HDMI_PKT_LINE_REF_VSYNC', + 'HDMI_SEND_MAX_AUDIO_PACKETS', 'HDP_ENDIAN_8IN16', + 'HDP_ENDIAN_8IN32', 'HDP_ENDIAN_8IN64', 'HDP_ENDIAN_NONE', + 'HPD_INT_CONTROL_ACK', 'HPD_INT_CONTROL_ACK_0', + 'HPD_INT_CONTROL_ACK_1', 'HPD_INT_CONTROL_GEN_INT_ON_CON', + 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', 'HPD_INT_CONTROL_POLARITY', + 'HPD_INT_CONTROL_RX_INT_ACK', 'HPD_INT_CONTROL_RX_INT_ACK_0', + 'HPD_INT_CONTROL_RX_INT_ACK_1', 'HS_GS', 'HS_STAGE_OFF', + 'HS_STAGE_ON', 'HUBP_BLANK_EN', 'HUBP_BLANK_SW_ASSERT', + 'HUBP_BLANK_SW_DEASSERT', 'HUBP_DISABLE', 'HUBP_DISABLED', + 'HUBP_ENABLED', 'HUBP_IN_ACTIVE', 'HUBP_IN_BLANK', + 'HUBP_IN_VBLANK', 'HUBP_MEASURE_WIN_MODE_DCFCLK', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', 'HUBP_NO_OUTSTANDING_REQ', + 'HUBP_TTU_DISABLE', 'HUBP_TTU_DISABLED', 'HUBP_TTU_ENABLED', + 'HUBP_VREADY_AT_OR_AFTER_VSYNC', 'HUBP_VTG_SEL', + 'HUBP_XFC_CHUNK_SIZE_16KB', 'HUBP_XFC_CHUNK_SIZE_1KB', + 'HUBP_XFC_CHUNK_SIZE_256B', 'HUBP_XFC_CHUNK_SIZE_2KB', + 'HUBP_XFC_CHUNK_SIZE_32KB', 'HUBP_XFC_CHUNK_SIZE_4KB', + 'HUBP_XFC_CHUNK_SIZE_512B', 'HUBP_XFC_CHUNK_SIZE_8KB', + 'HUBP_XFC_CHUNK_SIZE_ENUM', 'HUBP_XFC_FRAME_MODE_ENUM', + 'HUBP_XFC_FULL_FRAME_MODE', 'HUBP_XFC_PARTIAL_FRAME_MODE', + 'HUBP_XFC_PIXEL_FORMAT_ENUM', 'HUBP_XFC_PIXEL_IS_32BPP', + 'HUBP_XFC_PIXEL_IS_64BPP', 'HW_MIRRORING_DISABLE', + 'HW_MIRRORING_ENABLE', 'H_MIRROR_EN', 'Hdp_SurfaceEndian', + 'ID_STREAM_DISABLE_ACKED', 'ID_STREAM_DISABLE_NO_ACK', + 'IHC_INTERRUPT_LINE_STATUS', 'IH_CLIENT_TYPE', + 'IH_CLIENT_TYPE_RESERVED', 'IH_GFX_VMID_CLIENT', + 'IH_INTERFACE_TYPE', 'IH_LEGACY_INTERFACE', 'IH_MM_VMID_CLIENT', + 'IH_MULTI_VMID_CLIENT', 'IH_PERF_SEL', + 'IH_PERF_SEL_BIF_LINE0_FALLING', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF16', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF17', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF18', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF19', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF20', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF21', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF22', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF23', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF24', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF25', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF26', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF27', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF28', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF29', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF30', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 'IH_PERF_SEL_BIF_LINE0_RISING', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF16', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF17', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF18', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF19', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF20', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF21', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF22', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF23', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF24', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF25', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF26', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF27', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF28', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF29', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF30', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', + 'IH_PERF_SEL_BUFFER_FIFO_FULL', 'IH_PERF_SEL_BUFFER_IDLE', + 'IH_PERF_SEL_CLIENT0_INT', 'IH_PERF_SEL_CLIENT10_INT', + 'IH_PERF_SEL_CLIENT11_INT', 'IH_PERF_SEL_CLIENT12_INT', + 'IH_PERF_SEL_CLIENT13_INT', 'IH_PERF_SEL_CLIENT14_INT', + 'IH_PERF_SEL_CLIENT15_INT', 'IH_PERF_SEL_CLIENT16_INT', + 'IH_PERF_SEL_CLIENT17_INT', 'IH_PERF_SEL_CLIENT18_INT', + 'IH_PERF_SEL_CLIENT19_INT', 'IH_PERF_SEL_CLIENT1_INT', + 'IH_PERF_SEL_CLIENT20_INT', 'IH_PERF_SEL_CLIENT21_INT', + 'IH_PERF_SEL_CLIENT22_INT', 'IH_PERF_SEL_CLIENT23_INT', + 'IH_PERF_SEL_CLIENT24_INT', 'IH_PERF_SEL_CLIENT25_INT', + 'IH_PERF_SEL_CLIENT26_INT', 'IH_PERF_SEL_CLIENT27_INT', + 'IH_PERF_SEL_CLIENT28_INT', 'IH_PERF_SEL_CLIENT29_INT', + 'IH_PERF_SEL_CLIENT2_INT', 'IH_PERF_SEL_CLIENT30_INT', + 'IH_PERF_SEL_CLIENT31_INT', 'IH_PERF_SEL_CLIENT3_INT', + 'IH_PERF_SEL_CLIENT4_INT', 'IH_PERF_SEL_CLIENT5_INT', + 'IH_PERF_SEL_CLIENT6_INT', 'IH_PERF_SEL_CLIENT7_INT', + 'IH_PERF_SEL_CLIENT8_INT', 'IH_PERF_SEL_CLIENT9_INT', + 'IH_PERF_SEL_CLIENT_CREDIT_ERROR', 'IH_PERF_SEL_COOKIE_REC_ERROR', + 'IH_PERF_SEL_CYCLE', 'IH_PERF_SEL_IDLE', 'IH_PERF_SEL_INPUT_IDLE', + 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 'IH_PERF_SEL_MC_WR_CLEAN_STALL', 'IH_PERF_SEL_MC_WR_COUNT', + 'IH_PERF_SEL_MC_WR_IDLE', 'IH_PERF_SEL_MC_WR_STALL', + 'IH_PERF_SEL_RB0_FULL', 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF16', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF17', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF18', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF19', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF20', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF21', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF22', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF23', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF24', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF25', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF26', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF27', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF28', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF29', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF30', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB0_FULL_VF0', + 'IH_PERF_SEL_RB0_FULL_VF1', 'IH_PERF_SEL_RB0_FULL_VF10', + 'IH_PERF_SEL_RB0_FULL_VF11', 'IH_PERF_SEL_RB0_FULL_VF12', + 'IH_PERF_SEL_RB0_FULL_VF13', 'IH_PERF_SEL_RB0_FULL_VF14', + 'IH_PERF_SEL_RB0_FULL_VF15', 'IH_PERF_SEL_RB0_FULL_VF16', + 'IH_PERF_SEL_RB0_FULL_VF17', 'IH_PERF_SEL_RB0_FULL_VF18', + 'IH_PERF_SEL_RB0_FULL_VF19', 'IH_PERF_SEL_RB0_FULL_VF2', + 'IH_PERF_SEL_RB0_FULL_VF20', 'IH_PERF_SEL_RB0_FULL_VF21', + 'IH_PERF_SEL_RB0_FULL_VF22', 'IH_PERF_SEL_RB0_FULL_VF23', + 'IH_PERF_SEL_RB0_FULL_VF24', 'IH_PERF_SEL_RB0_FULL_VF25', + 'IH_PERF_SEL_RB0_FULL_VF26', 'IH_PERF_SEL_RB0_FULL_VF27', + 'IH_PERF_SEL_RB0_FULL_VF28', 'IH_PERF_SEL_RB0_FULL_VF29', + 'IH_PERF_SEL_RB0_FULL_VF3', 'IH_PERF_SEL_RB0_FULL_VF30', + 'IH_PERF_SEL_RB0_FULL_VF4', 'IH_PERF_SEL_RB0_FULL_VF5', + 'IH_PERF_SEL_RB0_FULL_VF6', 'IH_PERF_SEL_RB0_FULL_VF7', + 'IH_PERF_SEL_RB0_FULL_VF8', 'IH_PERF_SEL_RB0_FULL_VF9', + 'IH_PERF_SEL_RB0_LOAD_RPTR', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF0', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF1', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF15', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF16', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF17', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF18', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF19', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF20', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF21', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF22', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF23', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF24', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF25', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF26', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF27', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF28', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF29', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF3', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF30', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB0_OVERFLOW', + 'IH_PERF_SEL_RB0_OVERFLOW_VF0', 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 'IH_PERF_SEL_RB0_OVERFLOW_VF10', 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 'IH_PERF_SEL_RB0_OVERFLOW_VF12', 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 'IH_PERF_SEL_RB0_OVERFLOW_VF14', 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 'IH_PERF_SEL_RB0_OVERFLOW_VF16', 'IH_PERF_SEL_RB0_OVERFLOW_VF17', + 'IH_PERF_SEL_RB0_OVERFLOW_VF18', 'IH_PERF_SEL_RB0_OVERFLOW_VF19', + 'IH_PERF_SEL_RB0_OVERFLOW_VF2', 'IH_PERF_SEL_RB0_OVERFLOW_VF20', + 'IH_PERF_SEL_RB0_OVERFLOW_VF21', 'IH_PERF_SEL_RB0_OVERFLOW_VF22', + 'IH_PERF_SEL_RB0_OVERFLOW_VF23', 'IH_PERF_SEL_RB0_OVERFLOW_VF24', + 'IH_PERF_SEL_RB0_OVERFLOW_VF25', 'IH_PERF_SEL_RB0_OVERFLOW_VF26', + 'IH_PERF_SEL_RB0_OVERFLOW_VF27', 'IH_PERF_SEL_RB0_OVERFLOW_VF28', + 'IH_PERF_SEL_RB0_OVERFLOW_VF29', 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 'IH_PERF_SEL_RB0_OVERFLOW_VF30', 'IH_PERF_SEL_RB0_OVERFLOW_VF4', + 'IH_PERF_SEL_RB0_OVERFLOW_VF5', 'IH_PERF_SEL_RB0_OVERFLOW_VF6', + 'IH_PERF_SEL_RB0_OVERFLOW_VF7', 'IH_PERF_SEL_RB0_OVERFLOW_VF8', + 'IH_PERF_SEL_RB0_OVERFLOW_VF9', 'IH_PERF_SEL_RB0_RPTR_WRAP', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF16', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF17', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF18', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF19', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF20', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF21', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF22', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF23', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF24', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF25', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF26', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF27', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF28', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF29', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF30', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRAP', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF16', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF17', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF18', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF19', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF20', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF21', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF22', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF23', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF24', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF25', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF26', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF27', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF28', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF29', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF30', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF16', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF17', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF18', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF19', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF20', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF21', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF22', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF23', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF24', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF25', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF26', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF27', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF28', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF29', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF30', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', 'IH_PERF_SEL_RB1_FULL', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF16', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF17', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF18', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF19', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF20', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF21', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF22', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF23', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF24', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF25', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF26', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF27', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF28', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF29', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF30', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB1_FULL_VF0', + 'IH_PERF_SEL_RB1_FULL_VF1', 'IH_PERF_SEL_RB1_FULL_VF10', + 'IH_PERF_SEL_RB1_FULL_VF11', 'IH_PERF_SEL_RB1_FULL_VF12', + 'IH_PERF_SEL_RB1_FULL_VF13', 'IH_PERF_SEL_RB1_FULL_VF14', + 'IH_PERF_SEL_RB1_FULL_VF15', 'IH_PERF_SEL_RB1_FULL_VF16', + 'IH_PERF_SEL_RB1_FULL_VF17', 'IH_PERF_SEL_RB1_FULL_VF18', + 'IH_PERF_SEL_RB1_FULL_VF19', 'IH_PERF_SEL_RB1_FULL_VF2', + 'IH_PERF_SEL_RB1_FULL_VF20', 'IH_PERF_SEL_RB1_FULL_VF21', + 'IH_PERF_SEL_RB1_FULL_VF22', 'IH_PERF_SEL_RB1_FULL_VF23', + 'IH_PERF_SEL_RB1_FULL_VF24', 'IH_PERF_SEL_RB1_FULL_VF25', + 'IH_PERF_SEL_RB1_FULL_VF26', 'IH_PERF_SEL_RB1_FULL_VF27', + 'IH_PERF_SEL_RB1_FULL_VF28', 'IH_PERF_SEL_RB1_FULL_VF29', + 'IH_PERF_SEL_RB1_FULL_VF3', 'IH_PERF_SEL_RB1_FULL_VF30', + 'IH_PERF_SEL_RB1_FULL_VF4', 'IH_PERF_SEL_RB1_FULL_VF5', + 'IH_PERF_SEL_RB1_FULL_VF6', 'IH_PERF_SEL_RB1_FULL_VF7', + 'IH_PERF_SEL_RB1_FULL_VF8', 'IH_PERF_SEL_RB1_FULL_VF9', + 'IH_PERF_SEL_RB1_LOAD_RPTR', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF0', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF1', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF15', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF16', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF17', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF18', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF19', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF20', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF21', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF22', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF23', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF24', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF25', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF26', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF27', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF28', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF29', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF3', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF30', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB1_OVERFLOW', + 'IH_PERF_SEL_RB1_OVERFLOW_VF0', 'IH_PERF_SEL_RB1_OVERFLOW_VF1', + 'IH_PERF_SEL_RB1_OVERFLOW_VF10', 'IH_PERF_SEL_RB1_OVERFLOW_VF11', + 'IH_PERF_SEL_RB1_OVERFLOW_VF12', 'IH_PERF_SEL_RB1_OVERFLOW_VF13', + 'IH_PERF_SEL_RB1_OVERFLOW_VF14', 'IH_PERF_SEL_RB1_OVERFLOW_VF15', + 'IH_PERF_SEL_RB1_OVERFLOW_VF16', 'IH_PERF_SEL_RB1_OVERFLOW_VF17', + 'IH_PERF_SEL_RB1_OVERFLOW_VF18', 'IH_PERF_SEL_RB1_OVERFLOW_VF19', + 'IH_PERF_SEL_RB1_OVERFLOW_VF2', 'IH_PERF_SEL_RB1_OVERFLOW_VF20', + 'IH_PERF_SEL_RB1_OVERFLOW_VF21', 'IH_PERF_SEL_RB1_OVERFLOW_VF22', + 'IH_PERF_SEL_RB1_OVERFLOW_VF23', 'IH_PERF_SEL_RB1_OVERFLOW_VF24', + 'IH_PERF_SEL_RB1_OVERFLOW_VF25', 'IH_PERF_SEL_RB1_OVERFLOW_VF26', + 'IH_PERF_SEL_RB1_OVERFLOW_VF27', 'IH_PERF_SEL_RB1_OVERFLOW_VF28', + 'IH_PERF_SEL_RB1_OVERFLOW_VF29', 'IH_PERF_SEL_RB1_OVERFLOW_VF3', + 'IH_PERF_SEL_RB1_OVERFLOW_VF30', 'IH_PERF_SEL_RB1_OVERFLOW_VF4', + 'IH_PERF_SEL_RB1_OVERFLOW_VF5', 'IH_PERF_SEL_RB1_OVERFLOW_VF6', + 'IH_PERF_SEL_RB1_OVERFLOW_VF7', 'IH_PERF_SEL_RB1_OVERFLOW_VF8', + 'IH_PERF_SEL_RB1_OVERFLOW_VF9', 'IH_PERF_SEL_RB1_RPTR_WRAP', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF16', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF17', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF18', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF19', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF20', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF21', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF22', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF23', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF24', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF25', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF26', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF27', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF28', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF29', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF30', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB1_WPTR_WRAP', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF16', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF17', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF18', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF19', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF20', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF21', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF22', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF23', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF24', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF25', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF26', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF27', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF28', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF29', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF30', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_FULL', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF16', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF17', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF18', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF19', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF20', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF21', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF22', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF23', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF24', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF25', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF26', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF27', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF28', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF29', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF30', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB2_FULL_VF0', + 'IH_PERF_SEL_RB2_FULL_VF1', 'IH_PERF_SEL_RB2_FULL_VF10', + 'IH_PERF_SEL_RB2_FULL_VF11', 'IH_PERF_SEL_RB2_FULL_VF12', + 'IH_PERF_SEL_RB2_FULL_VF13', 'IH_PERF_SEL_RB2_FULL_VF14', + 'IH_PERF_SEL_RB2_FULL_VF15', 'IH_PERF_SEL_RB2_FULL_VF16', + 'IH_PERF_SEL_RB2_FULL_VF17', 'IH_PERF_SEL_RB2_FULL_VF18', + 'IH_PERF_SEL_RB2_FULL_VF19', 'IH_PERF_SEL_RB2_FULL_VF2', + 'IH_PERF_SEL_RB2_FULL_VF20', 'IH_PERF_SEL_RB2_FULL_VF21', + 'IH_PERF_SEL_RB2_FULL_VF22', 'IH_PERF_SEL_RB2_FULL_VF23', + 'IH_PERF_SEL_RB2_FULL_VF24', 'IH_PERF_SEL_RB2_FULL_VF25', + 'IH_PERF_SEL_RB2_FULL_VF26', 'IH_PERF_SEL_RB2_FULL_VF27', + 'IH_PERF_SEL_RB2_FULL_VF28', 'IH_PERF_SEL_RB2_FULL_VF29', + 'IH_PERF_SEL_RB2_FULL_VF3', 'IH_PERF_SEL_RB2_FULL_VF30', + 'IH_PERF_SEL_RB2_FULL_VF4', 'IH_PERF_SEL_RB2_FULL_VF5', + 'IH_PERF_SEL_RB2_FULL_VF6', 'IH_PERF_SEL_RB2_FULL_VF7', + 'IH_PERF_SEL_RB2_FULL_VF8', 'IH_PERF_SEL_RB2_FULL_VF9', + 'IH_PERF_SEL_RB2_LOAD_RPTR', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF0', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF1', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF15', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF16', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF17', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF18', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF19', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF20', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF21', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF22', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF23', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF24', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF25', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF26', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF27', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF28', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF29', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF3', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF30', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB2_OVERFLOW', + 'IH_PERF_SEL_RB2_OVERFLOW_VF0', 'IH_PERF_SEL_RB2_OVERFLOW_VF1', + 'IH_PERF_SEL_RB2_OVERFLOW_VF10', 'IH_PERF_SEL_RB2_OVERFLOW_VF11', + 'IH_PERF_SEL_RB2_OVERFLOW_VF12', 'IH_PERF_SEL_RB2_OVERFLOW_VF13', + 'IH_PERF_SEL_RB2_OVERFLOW_VF14', 'IH_PERF_SEL_RB2_OVERFLOW_VF15', + 'IH_PERF_SEL_RB2_OVERFLOW_VF16', 'IH_PERF_SEL_RB2_OVERFLOW_VF17', + 'IH_PERF_SEL_RB2_OVERFLOW_VF18', 'IH_PERF_SEL_RB2_OVERFLOW_VF19', + 'IH_PERF_SEL_RB2_OVERFLOW_VF2', 'IH_PERF_SEL_RB2_OVERFLOW_VF20', + 'IH_PERF_SEL_RB2_OVERFLOW_VF21', 'IH_PERF_SEL_RB2_OVERFLOW_VF22', + 'IH_PERF_SEL_RB2_OVERFLOW_VF23', 'IH_PERF_SEL_RB2_OVERFLOW_VF24', + 'IH_PERF_SEL_RB2_OVERFLOW_VF25', 'IH_PERF_SEL_RB2_OVERFLOW_VF26', + 'IH_PERF_SEL_RB2_OVERFLOW_VF27', 'IH_PERF_SEL_RB2_OVERFLOW_VF28', + 'IH_PERF_SEL_RB2_OVERFLOW_VF29', 'IH_PERF_SEL_RB2_OVERFLOW_VF3', + 'IH_PERF_SEL_RB2_OVERFLOW_VF30', 'IH_PERF_SEL_RB2_OVERFLOW_VF4', + 'IH_PERF_SEL_RB2_OVERFLOW_VF5', 'IH_PERF_SEL_RB2_OVERFLOW_VF6', + 'IH_PERF_SEL_RB2_OVERFLOW_VF7', 'IH_PERF_SEL_RB2_OVERFLOW_VF8', + 'IH_PERF_SEL_RB2_OVERFLOW_VF9', 'IH_PERF_SEL_RB2_RPTR_WRAP', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF16', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF17', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF18', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF19', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF20', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF21', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF22', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF23', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF24', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF25', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF26', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF27', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF28', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF29', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF30', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_WPTR_WRAP', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF16', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF17', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF18', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF19', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF20', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF21', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF22', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF23', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF24', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF25', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF26', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF27', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF28', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF29', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF30', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', 'IH_PERF_SEL_SELF_IV_VALID', + 'IH_PERF_SEL_STORM_CLIENT_INT_DROP', + 'IH_REGISTER_WRITE_INTERFACE', 'IH_RING_ID', + 'IH_RING_ID_INTERRUPT', 'IH_RING_ID_REQUEST', + 'IH_RING_ID_RESERVED', 'IH_RING_ID_TRANSLATION', + 'IH_VF_RB_SELECT', 'IH_VF_RB_SELECT_CLIENT_FCN_ID', + 'IH_VF_RB_SELECT_IH_FCN_ID', 'IH_VF_RB_SELECT_PF', + 'IH_VF_RB_SELECT_RESERVED', 'IMG_DATA_FORMAT', + 'IMG_DATA_FORMAT_1', 'IMG_DATA_FORMAT_10_10_10_2', + 'IMG_DATA_FORMAT_10_11_11', 'IMG_DATA_FORMAT_11_11_10', + 'IMG_DATA_FORMAT_16', 'IMG_DATA_FORMAT_16_16', + 'IMG_DATA_FORMAT_16_16_16_16', 'IMG_DATA_FORMAT_1_5_5_5', + 'IMG_DATA_FORMAT_1_REVERSED', 'IMG_DATA_FORMAT_24_8', + 'IMG_DATA_FORMAT_2_10_10_10', 'IMG_DATA_FORMAT_32', + 'IMG_DATA_FORMAT_32_32', 'IMG_DATA_FORMAT_32_32_32', + 'IMG_DATA_FORMAT_32_32_32_32', + 'IMG_DATA_FORMAT_32_AS_32_32_32_32', 'IMG_DATA_FORMAT_4_4', + 'IMG_DATA_FORMAT_4_4_4_4', 'IMG_DATA_FORMAT_5_5_5_1', + 'IMG_DATA_FORMAT_5_6_5', 'IMG_DATA_FORMAT_5_9_9_9', + 'IMG_DATA_FORMAT_6E4', 'IMG_DATA_FORMAT_6_5_5', + 'IMG_DATA_FORMAT_8', 'IMG_DATA_FORMAT_8_24', + 'IMG_DATA_FORMAT_8_8', 'IMG_DATA_FORMAT_8_8_8_8', + 'IMG_DATA_FORMAT_BC1', 'IMG_DATA_FORMAT_BC2', + 'IMG_DATA_FORMAT_BC3', 'IMG_DATA_FORMAT_BC4', + 'IMG_DATA_FORMAT_BC5', 'IMG_DATA_FORMAT_BC6', + 'IMG_DATA_FORMAT_BC7', 'IMG_DATA_FORMAT_BG_RG', + 'IMG_DATA_FORMAT_FMASK16_S16_F1', 'IMG_DATA_FORMAT_FMASK16_S8_F2', + 'IMG_DATA_FORMAT_FMASK32_S16_F2', 'IMG_DATA_FORMAT_FMASK32_S8_F4', + 'IMG_DATA_FORMAT_FMASK32_S8_F8', 'IMG_DATA_FORMAT_FMASK64_S16_F4', + 'IMG_DATA_FORMAT_FMASK64_S16_F8', 'IMG_DATA_FORMAT_FMASK8_S2_F1', + 'IMG_DATA_FORMAT_FMASK8_S2_F2', 'IMG_DATA_FORMAT_FMASK8_S4_F1', + 'IMG_DATA_FORMAT_FMASK8_S4_F2', 'IMG_DATA_FORMAT_FMASK8_S4_F4', + 'IMG_DATA_FORMAT_FMASK8_S8_F1', 'IMG_DATA_FORMAT_GB_GR', + 'IMG_DATA_FORMAT_INVALID', 'IMG_DATA_FORMAT_MM_10_11_11', + 'IMG_DATA_FORMAT_MM_10_IN_16', 'IMG_DATA_FORMAT_MM_10_IN_16_16', + 'IMG_DATA_FORMAT_MM_10_IN_16_16_16_16', + 'IMG_DATA_FORMAT_MM_16_16_16_16', 'IMG_DATA_FORMAT_MM_2_10_10_10', + 'IMG_DATA_FORMAT_MM_8', 'IMG_DATA_FORMAT_MM_8_8', + 'IMG_DATA_FORMAT_MM_8_8_8_8', 'IMG_DATA_FORMAT_MM_VYUY8', + 'IMG_DATA_FORMAT_RESERVED_100', 'IMG_DATA_FORMAT_RESERVED_101', + 'IMG_DATA_FORMAT_RESERVED_102', 'IMG_DATA_FORMAT_RESERVED_103', + 'IMG_DATA_FORMAT_RESERVED_104', 'IMG_DATA_FORMAT_RESERVED_105', + 'IMG_DATA_FORMAT_RESERVED_106', 'IMG_DATA_FORMAT_RESERVED_107', + 'IMG_DATA_FORMAT_RESERVED_108', 'IMG_DATA_FORMAT_RESERVED_109', + 'IMG_DATA_FORMAT_RESERVED_110', 'IMG_DATA_FORMAT_RESERVED_111', + 'IMG_DATA_FORMAT_RESERVED_112', 'IMG_DATA_FORMAT_RESERVED_113', + 'IMG_DATA_FORMAT_RESERVED_114', 'IMG_DATA_FORMAT_RESERVED_115', + 'IMG_DATA_FORMAT_RESERVED_116', 'IMG_DATA_FORMAT_RESERVED_117', + 'IMG_DATA_FORMAT_RESERVED_118', 'IMG_DATA_FORMAT_RESERVED_119', + 'IMG_DATA_FORMAT_RESERVED_120', 'IMG_DATA_FORMAT_RESERVED_121', + 'IMG_DATA_FORMAT_RESERVED_122', 'IMG_DATA_FORMAT_RESERVED_123', + 'IMG_DATA_FORMAT_RESERVED_124', 'IMG_DATA_FORMAT_RESERVED_125', + 'IMG_DATA_FORMAT_RESERVED_126', 'IMG_DATA_FORMAT_RESERVED_127', + 'IMG_DATA_FORMAT_RESERVED_15', 'IMG_DATA_FORMAT_RESERVED_23', + 'IMG_DATA_FORMAT_RESERVED_24', 'IMG_DATA_FORMAT_RESERVED_25', + 'IMG_DATA_FORMAT_RESERVED_26', 'IMG_DATA_FORMAT_RESERVED_27', + 'IMG_DATA_FORMAT_RESERVED_28', 'IMG_DATA_FORMAT_RESERVED_29', + 'IMG_DATA_FORMAT_RESERVED_30', 'IMG_DATA_FORMAT_RESERVED_42', + 'IMG_DATA_FORMAT_RESERVED_43', 'IMG_DATA_FORMAT_RESERVED_61', + 'IMG_DATA_FORMAT_RESERVED_62', 'IMG_DATA_FORMAT_RESERVED_75', + 'IMG_DATA_FORMAT_RESERVED_86', 'IMG_DATA_FORMAT_RESERVED_87', + 'IMG_DATA_FORMAT_RESERVED_88', 'IMG_DATA_FORMAT_RESERVED_89', + 'IMG_DATA_FORMAT_RESERVED_90', 'IMG_DATA_FORMAT_RESERVED_91', + 'IMG_DATA_FORMAT_RESERVED_92', 'IMG_DATA_FORMAT_RESERVED_93', + 'IMG_DATA_FORMAT_RESERVED_94', 'IMG_DATA_FORMAT_RESERVED_95', + 'IMG_DATA_FORMAT_RESERVED_96', 'IMG_DATA_FORMAT_RESERVED_97', + 'IMG_DATA_FORMAT_RESERVED_98', 'IMG_DATA_FORMAT_RESERVED_99', + 'IMG_DATA_FORMAT_X24_8_32', 'IMG_FMT', 'IMG_FMT_10_10_10_2_SINT', + 'IMG_FMT_10_10_10_2_SNORM', 'IMG_FMT_10_10_10_2_SSCALED', + 'IMG_FMT_10_10_10_2_UINT', 'IMG_FMT_10_10_10_2_UNORM', + 'IMG_FMT_10_10_10_2_USCALED', 'IMG_FMT_10_11_11_FLOAT', + 'IMG_FMT_10_11_11_SINT', 'IMG_FMT_10_11_11_SNORM', + 'IMG_FMT_10_11_11_SSCALED', 'IMG_FMT_10_11_11_UINT', + 'IMG_FMT_10_11_11_UNORM', 'IMG_FMT_10_11_11_USCALED', + 'IMG_FMT_11_11_10_FLOAT', 'IMG_FMT_11_11_10_SINT', + 'IMG_FMT_11_11_10_SNORM', 'IMG_FMT_11_11_10_SSCALED', + 'IMG_FMT_11_11_10_UINT', 'IMG_FMT_11_11_10_UNORM', + 'IMG_FMT_11_11_10_USCALED', 'IMG_FMT_16_16_16_16_FLOAT', + 'IMG_FMT_16_16_16_16_SINT', 'IMG_FMT_16_16_16_16_SNORM', + 'IMG_FMT_16_16_16_16_SSCALED', 'IMG_FMT_16_16_16_16_UINT', + 'IMG_FMT_16_16_16_16_UNORM', 'IMG_FMT_16_16_16_16_USCALED', + 'IMG_FMT_16_16_FLOAT', 'IMG_FMT_16_16_SINT', + 'IMG_FMT_16_16_SNORM', 'IMG_FMT_16_16_SSCALED', + 'IMG_FMT_16_16_UINT', 'IMG_FMT_16_16_UNORM', + 'IMG_FMT_16_16_USCALED', 'IMG_FMT_16_FLOAT', 'IMG_FMT_16_SINT', + 'IMG_FMT_16_SNORM', 'IMG_FMT_16_SSCALED', 'IMG_FMT_16_UINT', + 'IMG_FMT_16_UNORM', 'IMG_FMT_16_USCALED', 'IMG_FMT_1_5_5_5_UNORM', + 'IMG_FMT_1_REVERSED_UNORM', 'IMG_FMT_1_UNORM', + 'IMG_FMT_24_8_UINT', 'IMG_FMT_24_8_UNORM', + 'IMG_FMT_2_10_10_10_SINT', 'IMG_FMT_2_10_10_10_SNORM', + 'IMG_FMT_2_10_10_10_SSCALED', 'IMG_FMT_2_10_10_10_UINT', + 'IMG_FMT_2_10_10_10_UNORM', 'IMG_FMT_2_10_10_10_USCALED', + 'IMG_FMT_32_32_32_32_FLOAT', 'IMG_FMT_32_32_32_32_SINT', + 'IMG_FMT_32_32_32_32_UINT', 'IMG_FMT_32_32_32_FLOAT', + 'IMG_FMT_32_32_32_SINT', 'IMG_FMT_32_32_32_UINT', + 'IMG_FMT_32_32_FLOAT', 'IMG_FMT_32_32_SINT', 'IMG_FMT_32_32_UINT', + 'IMG_FMT_32_FLOAT', 'IMG_FMT_32_FLOAT_CLAMP', 'IMG_FMT_32_SINT', + 'IMG_FMT_32_UINT', 'IMG_FMT_4_4_4_4_UNORM', 'IMG_FMT_4_4_UNORM', + 'IMG_FMT_5_5_5_1_UNORM', 'IMG_FMT_5_6_5_UNORM', + 'IMG_FMT_5_9_9_9_FLOAT', 'IMG_FMT_6E4_FLOAT', 'IMG_FMT_8_24_UINT', + 'IMG_FMT_8_24_UNORM', 'IMG_FMT_8_8_8_8_SINT', + 'IMG_FMT_8_8_8_8_SNORM', 'IMG_FMT_8_8_8_8_SRGB', + 'IMG_FMT_8_8_8_8_SSCALED', 'IMG_FMT_8_8_8_8_UINT', + 'IMG_FMT_8_8_8_8_UNORM', 'IMG_FMT_8_8_8_8_USCALED', + 'IMG_FMT_8_8_SINT', 'IMG_FMT_8_8_SNORM', 'IMG_FMT_8_8_SRGB', + 'IMG_FMT_8_8_SSCALED', 'IMG_FMT_8_8_UINT', 'IMG_FMT_8_8_UNORM', + 'IMG_FMT_8_8_USCALED', 'IMG_FMT_8_SINT', 'IMG_FMT_8_SNORM', + 'IMG_FMT_8_SRGB', 'IMG_FMT_8_SSCALED', 'IMG_FMT_8_UINT', + 'IMG_FMT_8_UNORM', 'IMG_FMT_8_USCALED', 'IMG_FMT_BC1_SRGB', + 'IMG_FMT_BC1_UNORM', 'IMG_FMT_BC2_SRGB', 'IMG_FMT_BC2_UNORM', + 'IMG_FMT_BC3_SRGB', 'IMG_FMT_BC3_UNORM', 'IMG_FMT_BC4_SNORM', + 'IMG_FMT_BC4_UNORM', 'IMG_FMT_BC5_SNORM', 'IMG_FMT_BC5_UNORM', + 'IMG_FMT_BC6_SFLOAT', 'IMG_FMT_BC6_UFLOAT', 'IMG_FMT_BC7_SRGB', + 'IMG_FMT_BC7_UNORM', 'IMG_FMT_BG_RG_SNORM', 'IMG_FMT_BG_RG_SRGB', + 'IMG_FMT_BG_RG_UINT', 'IMG_FMT_BG_RG_UNORM', + 'IMG_FMT_FMASK16_S16_F1', 'IMG_FMT_FMASK16_S8_F2', + 'IMG_FMT_FMASK32_S16_F2', 'IMG_FMT_FMASK32_S8_F4', + 'IMG_FMT_FMASK32_S8_F8', 'IMG_FMT_FMASK64_S16_F4', + 'IMG_FMT_FMASK64_S16_F8', 'IMG_FMT_FMASK8_S2_F1', + 'IMG_FMT_FMASK8_S2_F2', 'IMG_FMT_FMASK8_S4_F1', + 'IMG_FMT_FMASK8_S4_F2', 'IMG_FMT_FMASK8_S4_F4', + 'IMG_FMT_FMASK8_S8_F1', 'IMG_FMT_GB_GR_SNORM', + 'IMG_FMT_GB_GR_SRGB', 'IMG_FMT_GB_GR_UINT', 'IMG_FMT_GB_GR_UNORM', + 'IMG_FMT_INVALID', 'IMG_FMT_MM_10_11_11_UINT', + 'IMG_FMT_MM_10_11_11_UNORM', 'IMG_FMT_MM_10_IN_16_16_16_16_UINT', + 'IMG_FMT_MM_10_IN_16_16_16_16_UNORM', + 'IMG_FMT_MM_10_IN_16_16_UINT', 'IMG_FMT_MM_10_IN_16_16_UNORM', + 'IMG_FMT_MM_10_IN_16_UINT', 'IMG_FMT_MM_10_IN_16_UNORM', + 'IMG_FMT_MM_16_16_16_16_UINT', 'IMG_FMT_MM_16_16_16_16_UNORM', + 'IMG_FMT_MM_2_10_10_10_UINT', 'IMG_FMT_MM_2_10_10_10_UNORM', + 'IMG_FMT_MM_8_8_8_8_UINT', 'IMG_FMT_MM_8_8_8_8_UNORM', + 'IMG_FMT_MM_8_8_UINT', 'IMG_FMT_MM_8_8_UNORM', + 'IMG_FMT_MM_8_UINT', 'IMG_FMT_MM_8_UNORM', + 'IMG_FMT_MM_VYUY8_UINT', 'IMG_FMT_MM_VYUY8_UNORM', + 'IMG_FMT_RESERVED_100', 'IMG_FMT_RESERVED_101', + 'IMG_FMT_RESERVED_102', 'IMG_FMT_RESERVED_103', + 'IMG_FMT_RESERVED_104', 'IMG_FMT_RESERVED_105', + 'IMG_FMT_RESERVED_106', 'IMG_FMT_RESERVED_107', + 'IMG_FMT_RESERVED_108', 'IMG_FMT_RESERVED_109', + 'IMG_FMT_RESERVED_110', 'IMG_FMT_RESERVED_111', + 'IMG_FMT_RESERVED_112', 'IMG_FMT_RESERVED_113', + 'IMG_FMT_RESERVED_114', 'IMG_FMT_RESERVED_115', + 'IMG_FMT_RESERVED_116', 'IMG_FMT_RESERVED_117', + 'IMG_FMT_RESERVED_118', 'IMG_FMT_RESERVED_119', + 'IMG_FMT_RESERVED_120', 'IMG_FMT_RESERVED_121', + 'IMG_FMT_RESERVED_122', 'IMG_FMT_RESERVED_123', + 'IMG_FMT_RESERVED_124', 'IMG_FMT_RESERVED_125', + 'IMG_FMT_RESERVED_126', 'IMG_FMT_RESERVED_127', + 'IMG_FMT_RESERVED_155', 'IMG_FMT_RESERVED_285', + 'IMG_FMT_RESERVED_286', 'IMG_FMT_RESERVED_287', + 'IMG_FMT_RESERVED_288', 'IMG_FMT_RESERVED_289', + 'IMG_FMT_RESERVED_290', 'IMG_FMT_RESERVED_291', + 'IMG_FMT_RESERVED_292', 'IMG_FMT_RESERVED_293', + 'IMG_FMT_RESERVED_294', 'IMG_FMT_RESERVED_295', + 'IMG_FMT_RESERVED_296', 'IMG_FMT_RESERVED_297', + 'IMG_FMT_RESERVED_298', 'IMG_FMT_RESERVED_299', + 'IMG_FMT_RESERVED_300', 'IMG_FMT_RESERVED_301', + 'IMG_FMT_RESERVED_302', 'IMG_FMT_RESERVED_303', + 'IMG_FMT_RESERVED_304', 'IMG_FMT_RESERVED_305', + 'IMG_FMT_RESERVED_306', 'IMG_FMT_RESERVED_307', + 'IMG_FMT_RESERVED_308', 'IMG_FMT_RESERVED_309', + 'IMG_FMT_RESERVED_310', 'IMG_FMT_RESERVED_311', + 'IMG_FMT_RESERVED_312', 'IMG_FMT_RESERVED_313', + 'IMG_FMT_RESERVED_314', 'IMG_FMT_RESERVED_315', + 'IMG_FMT_RESERVED_316', 'IMG_FMT_RESERVED_317', + 'IMG_FMT_RESERVED_318', 'IMG_FMT_RESERVED_319', + 'IMG_FMT_RESERVED_320', 'IMG_FMT_RESERVED_321', + 'IMG_FMT_RESERVED_322', 'IMG_FMT_RESERVED_323', + 'IMG_FMT_RESERVED_324', 'IMG_FMT_RESERVED_325', + 'IMG_FMT_RESERVED_326', 'IMG_FMT_RESERVED_327', + 'IMG_FMT_RESERVED_328', 'IMG_FMT_RESERVED_329', + 'IMG_FMT_RESERVED_330', 'IMG_FMT_RESERVED_331', + 'IMG_FMT_RESERVED_332', 'IMG_FMT_RESERVED_333', + 'IMG_FMT_RESERVED_334', 'IMG_FMT_RESERVED_335', + 'IMG_FMT_RESERVED_336', 'IMG_FMT_RESERVED_337', + 'IMG_FMT_RESERVED_338', 'IMG_FMT_RESERVED_339', + 'IMG_FMT_RESERVED_340', 'IMG_FMT_RESERVED_341', + 'IMG_FMT_RESERVED_342', 'IMG_FMT_RESERVED_343', + 'IMG_FMT_RESERVED_344', 'IMG_FMT_RESERVED_345', + 'IMG_FMT_RESERVED_346', 'IMG_FMT_RESERVED_347', + 'IMG_FMT_RESERVED_348', 'IMG_FMT_RESERVED_349', + 'IMG_FMT_RESERVED_350', 'IMG_FMT_RESERVED_351', + 'IMG_FMT_RESERVED_352', 'IMG_FMT_RESERVED_353', + 'IMG_FMT_RESERVED_354', 'IMG_FMT_RESERVED_355', + 'IMG_FMT_RESERVED_356', 'IMG_FMT_RESERVED_357', + 'IMG_FMT_RESERVED_358', 'IMG_FMT_RESERVED_359', + 'IMG_FMT_RESERVED_360', 'IMG_FMT_RESERVED_361', + 'IMG_FMT_RESERVED_362', 'IMG_FMT_RESERVED_363', + 'IMG_FMT_RESERVED_364', 'IMG_FMT_RESERVED_365', + 'IMG_FMT_RESERVED_366', 'IMG_FMT_RESERVED_367', + 'IMG_FMT_RESERVED_368', 'IMG_FMT_RESERVED_369', + 'IMG_FMT_RESERVED_370', 'IMG_FMT_RESERVED_371', + 'IMG_FMT_RESERVED_372', 'IMG_FMT_RESERVED_373', + 'IMG_FMT_RESERVED_374', 'IMG_FMT_RESERVED_375', + 'IMG_FMT_RESERVED_376', 'IMG_FMT_RESERVED_377', + 'IMG_FMT_RESERVED_378', 'IMG_FMT_RESERVED_379', + 'IMG_FMT_RESERVED_380', 'IMG_FMT_RESERVED_381', + 'IMG_FMT_RESERVED_382', 'IMG_FMT_RESERVED_383', + 'IMG_FMT_RESERVED_384', 'IMG_FMT_RESERVED_385', + 'IMG_FMT_RESERVED_386', 'IMG_FMT_RESERVED_387', + 'IMG_FMT_RESERVED_388', 'IMG_FMT_RESERVED_389', + 'IMG_FMT_RESERVED_390', 'IMG_FMT_RESERVED_391', + 'IMG_FMT_RESERVED_392', 'IMG_FMT_RESERVED_393', + 'IMG_FMT_RESERVED_394', 'IMG_FMT_RESERVED_395', + 'IMG_FMT_RESERVED_396', 'IMG_FMT_RESERVED_397', + 'IMG_FMT_RESERVED_398', 'IMG_FMT_RESERVED_399', + 'IMG_FMT_RESERVED_400', 'IMG_FMT_RESERVED_401', + 'IMG_FMT_RESERVED_402', 'IMG_FMT_RESERVED_403', + 'IMG_FMT_RESERVED_404', 'IMG_FMT_RESERVED_405', + 'IMG_FMT_RESERVED_406', 'IMG_FMT_RESERVED_407', + 'IMG_FMT_RESERVED_408', 'IMG_FMT_RESERVED_409', + 'IMG_FMT_RESERVED_410', 'IMG_FMT_RESERVED_411', + 'IMG_FMT_RESERVED_412', 'IMG_FMT_RESERVED_413', + 'IMG_FMT_RESERVED_414', 'IMG_FMT_RESERVED_415', + 'IMG_FMT_RESERVED_416', 'IMG_FMT_RESERVED_417', + 'IMG_FMT_RESERVED_418', 'IMG_FMT_RESERVED_419', + 'IMG_FMT_RESERVED_420', 'IMG_FMT_RESERVED_421', + 'IMG_FMT_RESERVED_422', 'IMG_FMT_RESERVED_423', + 'IMG_FMT_RESERVED_424', 'IMG_FMT_RESERVED_425', + 'IMG_FMT_RESERVED_426', 'IMG_FMT_RESERVED_427', + 'IMG_FMT_RESERVED_428', 'IMG_FMT_RESERVED_429', + 'IMG_FMT_RESERVED_430', 'IMG_FMT_RESERVED_431', + 'IMG_FMT_RESERVED_432', 'IMG_FMT_RESERVED_433', + 'IMG_FMT_RESERVED_434', 'IMG_FMT_RESERVED_435', + 'IMG_FMT_RESERVED_436', 'IMG_FMT_RESERVED_437', + 'IMG_FMT_RESERVED_438', 'IMG_FMT_RESERVED_439', + 'IMG_FMT_RESERVED_440', 'IMG_FMT_RESERVED_441', + 'IMG_FMT_RESERVED_442', 'IMG_FMT_RESERVED_443', + 'IMG_FMT_RESERVED_444', 'IMG_FMT_RESERVED_445', + 'IMG_FMT_RESERVED_446', 'IMG_FMT_RESERVED_447', + 'IMG_FMT_RESERVED_448', 'IMG_FMT_RESERVED_449', + 'IMG_FMT_RESERVED_450', 'IMG_FMT_RESERVED_451', + 'IMG_FMT_RESERVED_452', 'IMG_FMT_RESERVED_453', + 'IMG_FMT_RESERVED_454', 'IMG_FMT_RESERVED_455', + 'IMG_FMT_RESERVED_456', 'IMG_FMT_RESERVED_457', + 'IMG_FMT_RESERVED_458', 'IMG_FMT_RESERVED_459', + 'IMG_FMT_RESERVED_460', 'IMG_FMT_RESERVED_461', + 'IMG_FMT_RESERVED_462', 'IMG_FMT_RESERVED_463', + 'IMG_FMT_RESERVED_464', 'IMG_FMT_RESERVED_465', + 'IMG_FMT_RESERVED_466', 'IMG_FMT_RESERVED_467', + 'IMG_FMT_RESERVED_468', 'IMG_FMT_RESERVED_469', + 'IMG_FMT_RESERVED_470', 'IMG_FMT_RESERVED_471', + 'IMG_FMT_RESERVED_472', 'IMG_FMT_RESERVED_473', + 'IMG_FMT_RESERVED_474', 'IMG_FMT_RESERVED_475', + 'IMG_FMT_RESERVED_476', 'IMG_FMT_RESERVED_477', + 'IMG_FMT_RESERVED_478', 'IMG_FMT_RESERVED_479', + 'IMG_FMT_RESERVED_480', 'IMG_FMT_RESERVED_481', + 'IMG_FMT_RESERVED_482', 'IMG_FMT_RESERVED_483', + 'IMG_FMT_RESERVED_484', 'IMG_FMT_RESERVED_485', + 'IMG_FMT_RESERVED_486', 'IMG_FMT_RESERVED_487', + 'IMG_FMT_RESERVED_488', 'IMG_FMT_RESERVED_489', + 'IMG_FMT_RESERVED_490', 'IMG_FMT_RESERVED_491', + 'IMG_FMT_RESERVED_492', 'IMG_FMT_RESERVED_493', + 'IMG_FMT_RESERVED_494', 'IMG_FMT_RESERVED_495', + 'IMG_FMT_RESERVED_496', 'IMG_FMT_RESERVED_497', + 'IMG_FMT_RESERVED_498', 'IMG_FMT_RESERVED_499', + 'IMG_FMT_RESERVED_500', 'IMG_FMT_RESERVED_501', + 'IMG_FMT_RESERVED_502', 'IMG_FMT_RESERVED_503', + 'IMG_FMT_RESERVED_504', 'IMG_FMT_RESERVED_505', + 'IMG_FMT_RESERVED_506', 'IMG_FMT_RESERVED_507', + 'IMG_FMT_RESERVED_508', 'IMG_FMT_RESERVED_509', + 'IMG_FMT_RESERVED_510', 'IMG_FMT_RESERVED_511', + 'IMG_FMT_RESERVED_78', 'IMG_FMT_RESERVED_79', + 'IMG_FMT_RESERVED_80', 'IMG_FMT_RESERVED_81', + 'IMG_FMT_RESERVED_82', 'IMG_FMT_RESERVED_83', + 'IMG_FMT_RESERVED_84', 'IMG_FMT_RESERVED_85', + 'IMG_FMT_RESERVED_86', 'IMG_FMT_RESERVED_87', + 'IMG_FMT_RESERVED_88', 'IMG_FMT_RESERVED_89', + 'IMG_FMT_RESERVED_90', 'IMG_FMT_RESERVED_91', + 'IMG_FMT_RESERVED_92', 'IMG_FMT_RESERVED_93', + 'IMG_FMT_RESERVED_94', 'IMG_FMT_RESERVED_95', + 'IMG_FMT_RESERVED_96', 'IMG_FMT_RESERVED_97', + 'IMG_FMT_RESERVED_98', 'IMG_FMT_RESERVED_99', + 'IMG_FMT_X24_8_32_FLOAT', 'IMG_FMT_X24_8_32_UINT', + 'IMG_NUM_FORMAT', 'IMG_NUM_FORMAT_FLOAT', 'IMG_NUM_FORMAT_FMASK', + 'IMG_NUM_FORMAT_FMASK_16_16_1', 'IMG_NUM_FORMAT_FMASK_16_8_2', + 'IMG_NUM_FORMAT_FMASK_32_16_2', 'IMG_NUM_FORMAT_FMASK_32_8_4', + 'IMG_NUM_FORMAT_FMASK_32_8_8', 'IMG_NUM_FORMAT_FMASK_64_16_4', + 'IMG_NUM_FORMAT_FMASK_64_16_8', 'IMG_NUM_FORMAT_FMASK_8_2_1', + 'IMG_NUM_FORMAT_FMASK_8_2_2', 'IMG_NUM_FORMAT_FMASK_8_4_1', + 'IMG_NUM_FORMAT_FMASK_8_4_2', 'IMG_NUM_FORMAT_FMASK_8_4_4', + 'IMG_NUM_FORMAT_FMASK_8_8_1', 'IMG_NUM_FORMAT_FMASK_RESERVED_13', + 'IMG_NUM_FORMAT_FMASK_RESERVED_14', + 'IMG_NUM_FORMAT_FMASK_RESERVED_15', 'IMG_NUM_FORMAT_N_IN_16', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_0', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_10', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_11', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_12', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_13', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_14', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_15', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_3', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_6', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_9', + 'IMG_NUM_FORMAT_N_IN_16_UINT_10', 'IMG_NUM_FORMAT_N_IN_16_UINT_9', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_10', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_9', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9', + 'IMG_NUM_FORMAT_RESERVED_14', 'IMG_NUM_FORMAT_RESERVED_15', + 'IMG_NUM_FORMAT_RESERVED_8', 'IMG_NUM_FORMAT_SINT', + 'IMG_NUM_FORMAT_SNORM', 'IMG_NUM_FORMAT_SNORM_NZ', + 'IMG_NUM_FORMAT_SRGB', 'IMG_NUM_FORMAT_SSCALED', + 'IMG_NUM_FORMAT_UBINT', 'IMG_NUM_FORMAT_UBNORM', + 'IMG_NUM_FORMAT_UBNORM_NZ', 'IMG_NUM_FORMAT_UBSCALED', + 'IMG_NUM_FORMAT_UINT', 'IMG_NUM_FORMAT_UNORM', + 'IMG_NUM_FORMAT_USCALED', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 'INPUT_COVERAGE', 'INPUT_DEPTH_COVERAGE', 'INPUT_INNER_COVERAGE', + 'INST_ID_ECC_INTERRUPT_MSG', 'INST_ID_HOST_REG_TRAP_MSG', + 'INST_ID_HW_TRAP', 'INST_ID_KILL_SEQ', 'INST_ID_PRIV_START', + 'INST_ID_SPI_WREXEC', 'INST_ID_TTRACE_NEW_PC_MSG', + 'INTERRUPT_LINE_ASSERTED', 'INTERRUPT_LINE_NOT_ASSERTED', + 'INT_DISABLED', 'INT_ENABLED', 'INT_LEVEL', 'INT_MASK', + 'INT_PULSE', 'INVALID_REG_ACCESS_TYPE', 'IP_USB_PD_REVISION_ID', + 'IQ_DEQUEUE_RETRY', 'IQ_INTR_TYPE_IB', 'IQ_INTR_TYPE_MQD', + 'IQ_INTR_TYPE_PQ', 'IQ_OFFLOAD_RETRY', 'IQ_QUEUE_SLEEP', + 'IQ_SCH_WAVE_MSG', 'IQ_SEM_REARM', 'JITTER_REMOVE_DISABLE', + 'LATE_Z', 'LB_ALPHA_DISABLE', 'LB_ALPHA_EN', 'LB_ALPHA_ENABLE', + 'LB_INTERLEAVE_DISABLE', 'LB_INTERLEAVE_EN', + 'LB_INTERLEAVE_ENABLE', 'LEFT_EYE', 'LEGACY_NUM_BANKS', + 'LEGACY_PIPE_INTERLEAVE', 'LEGACY_PIPE_INTERLEAVE_256B', + 'LEGACY_PIPE_INTERLEAVE_512B', 'LINESTRIP', 'LS_STAGE_OFF', + 'LS_STAGE_ON', 'LUT_2CFG_MEMORY_A', 'LUT_2CFG_MEMORY_B', + 'LUT_2CFG_NO_MEMORY', 'LUT_2_MODE_BYPASS', 'LUT_2_MODE_RAMA_LUT', + 'LUT_2_MODE_RAMB_LUT', 'LUT_4CFG_MEMORY_A', 'LUT_4CFG_MEMORY_B', + 'LUT_4CFG_NO_MEMORY', 'LUT_4CFG_ROM_A', 'LUT_4CFG_ROM_B', + 'LUT_4_MODE_BYPASS', 'LUT_4_MODE_RAMA_LUT', 'LUT_4_MODE_RAMB_LUT', + 'LUT_4_MODE_ROMA_LUT', 'LUT_4_MODE_ROMB_LUT', + 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', + 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT', 'MACRO_TILE_ASPECT', + 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', + 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_LOCK_SEL', 'MASTER_UPDATE_LOCK_SEL_0', + 'MASTER_UPDATE_LOCK_SEL_1', 'MASTER_UPDATE_LOCK_SEL_2', + 'MASTER_UPDATE_LOCK_SEL_3', 'MASTER_UPDATE_LOCK_SEL_4', + 'MASTER_UPDATE_LOCK_SEL_5', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 'MAX_COMPRESSED_FRAGS', 'MEM_ARB_MODE_AGE', 'MEM_ARB_MODE_BOTH', + 'MEM_ARB_MODE_FIXED', 'MEM_ARB_MODE_WEIGHT', 'MEM_PWR_DIS_CTRL', + 'MEM_PWR_FORCE_CTRL', 'MEM_PWR_FORCE_CTRL2', 'MEM_PWR_SEL_CTRL', + 'MEM_PWR_SEL_CTRL2', 'METADATA_HUBP_SEL', 'METADATA_HUBP_SEL_0', + 'METADATA_HUBP_SEL_1', 'METADATA_HUBP_SEL_2', + 'METADATA_HUBP_SEL_3', 'METADATA_HUBP_SEL_4', + 'METADATA_HUBP_SEL_5', 'METADATA_HUBP_SEL_RESERVED', + 'METADATA_STREAM_DP', 'METADATA_STREAM_DVE', + 'METADATA_STREAM_TYPE_SEL', 'META_CHUNK_SIZE', + 'META_CHUNK_SIZE_1KB', 'META_CHUNK_SIZE_2KB', + 'META_CHUNK_SIZE_4KB', 'META_CHUNK_SIZE_8KB', 'META_LINEAR', + 'META_SURF_LINEAR', 'META_SURF_TILED', 'ME_ID0', 'ME_ID1', + 'ME_ID2', 'ME_ID3', 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL', + 'MICRO_TILE_MODE_DISPLAY_2D', 'MICRO_TILE_MODE_DISPLAY_3D', + 'MICRO_TILE_MODE_LINEAR', 'MICRO_TILE_MODE_NEW', + 'MICRO_TILE_MODE_RENDER_TARGET', 'MICRO_TILE_MODE_STD_2D', + 'MICRO_TILE_MODE_STD_3D', 'MICRO_TILE_MODE_Z', + 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL', 'MIN_CHUNK_SIZE', + 'MIN_CHUNK_SIZE_1024B', 'MIN_CHUNK_SIZE_256B', + 'MIN_CHUNK_SIZE_512B', 'MIN_META_CHUNK_SIZE', + 'MIN_META_CHUNK_SIZE_128B', 'MIN_META_CHUNK_SIZE_256B', + 'MIN_META_CHUNK_SIZE_64B', 'MMHUBBUB_XFC_FRAME_MODE_ENUM', + 'MMHUBBUB_XFC_FULL_FRAME_MODE', 'MMHUBBUB_XFC_PARTIAL_FRAME_MODE', + 'MMHUBBUB_XFC_PIXEL_FORMAT_ENUM', 'MMHUBBUB_XFC_PIXEL_IS_32BPP', + 'MMHUBBUB_XFC_PIXEL_IS_64BPP', + 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_ENUM', + 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_MMHUB', + 'MMHUBBUB_XFC_XFCMON_INTERFACE_SEL_SYSHUB', + 'MMHUBBUB_XFC_XFCMON_MODE_CONTINUOUS', + 'MMHUBBUB_XFC_XFCMON_MODE_ENUM', + 'MMHUBBUB_XFC_XFCMON_MODE_ONE_SHOT', + 'MMHUBBUB_XFC_XFCMON_MODE_PERIODS', 'MONO_10LSB', 'MONO_10MSB', + 'MONO_12LSB', 'MONO_12MSB', 'MONO_16', 'MONO_2BIT', 'MONO_8', + 'MPCC_BG_COLOR_BPC', 'MPCC_BG_COLOR_BPC_10bit', + 'MPCC_BG_COLOR_BPC_11bit', 'MPCC_BG_COLOR_BPC_12bit', + 'MPCC_BG_COLOR_BPC_8bit', 'MPCC_BG_COLOR_BPC_9bit', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', 'MPCC_CONTROL_MPCC_MODE', + 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', + 'MPCC_OGAM_MODE_0', 'MPCC_OGAM_MODE_1', 'MPCC_OGAM_MODE_2', + 'MPCC_OGAM_MODE_MPCC_OGAM_MODE', 'MPCC_OGAM_MODE_RSV', + 'MPCC_SM_CONTROL_MPCC_SM_EN', 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_FALSE', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_ACK_TRUE', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_FALSE', + 'MPCC_STALL_STATUS_MPCC_STALL_INT_MASK_TRUE', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', 'MPC_CFG_MPC_TEST_CLK_SEL', + 'MPC_CFG_MPC_TEST_CLK_SEL_0', 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 'MPC_CFG_MPC_TEST_CLK_SEL_2', 'MPC_CFG_MPC_TEST_CLK_SEL_3', + 'MPC_CRC_CALC_INTERLACE_MODE', 'MPC_CRC_CALC_MODE', + 'MPC_CRC_CALC_STEREO_MODE', 'MPC_CRC_CONTINUOUS_MODE', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', + 'MPC_CRC_INTERLACE_MODE_BOTTOM', 'MPC_CRC_INTERLACE_MODE_TOP', + 'MPC_CRC_ONE_SHOT_MODE', 'MPC_CRC_SOURCE_SELECT', + 'MPC_CRC_SOURCE_SEL_DPP', 'MPC_CRC_SOURCE_SEL_DWB', + 'MPC_CRC_SOURCE_SEL_OPP', 'MPC_CRC_SOURCE_SEL_OTHER', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 'MPC_CRC_STEREO_MODE_LEFT', 'MPC_CRC_STEREO_MODE_RIGHT', + 'MPC_OCSC_COEF_FORMAT', 'MPC_OCSC_COEF_FORMAT_S2_13', + 'MPC_OCSC_COEF_FORMAT_S3_12', 'MPC_OUT_CSC_MODE', + 'MPC_OUT_CSC_MODE_0', 'MPC_OUT_CSC_MODE_1', 'MPC_OUT_CSC_MODE_2', + 'MPC_OUT_CSC_MODE_RSV', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', + 'MPC_OUT_RATE_CONTROL_DISABLE_SET', + 'MPC_OUT_RATE_CONTROL_SET_DISABLE', + 'MPC_OUT_RATE_CONTROL_SET_ENABLE', 'MPTE_GROUP_SIZE', + 'MPTE_GROUP_SIZE_1024B', 'MPTE_GROUP_SIZE_128B', + 'MPTE_GROUP_SIZE_2048B', 'MPTE_GROUP_SIZE_256B', + 'MPTE_GROUP_SIZE_4096B', 'MPTE_GROUP_SIZE_512B', + 'MPTE_GROUP_SIZE_64B', 'MPTE_GROUP_SIZE_8192B', + 'MSA_V_TIMING_OVERRIDE_DISABLED', 'MSA_V_TIMING_OVERRIDE_ENABLED', + 'MTYPE', 'MTYPE_CC', 'MTYPE_C_RO_S', 'MTYPE_C_RO_US', + 'MTYPE_C_RW_S', 'MTYPE_C_RW_US', 'MTYPE_NC', 'MTYPE_RESERVED_1', + 'MTYPE_RESERVED_5', 'MTYPE_RESERVED_7', 'MTYPE_UC', 'MTYPE_WC', + 'MULT_16', 'MULT_8', 'MacroTileAspect', 'MemArbMode', + 'MicroTileMode', 'MultiGPUTileSize', 'NON_BYPASS', 'NOT_SENT', + 'NO_DIST', 'NO_DIV', 'NO_FORCE', 'NO_FORCE_REQ', + 'NO_FORCE_REQUEST', 'NO_MIN_CHUNK_SIZE', 'NO_MIN_META_CHUNK_SIZE', + 'NO_OUTSTANDING_REQ', 'NUMBER_FLOAT', 'NUMBER_SINT', + 'NUMBER_SNORM', 'NUMBER_SRGB', 'NUMBER_SSCALED', 'NUMBER_UINT', + 'NUMBER_UNORM', 'NUMBER_USCALED', 'NUM_BANKS', + 'NUM_BANKS_BC_ENUM', 'NUM_PIPES', 'NUM_PIPES_BC_ENUM', + 'NUM_RB_PER_SE', 'NUM_SE', 'NUM_SIMD_PER_CU', + 'NonDispTilingOrder', 'NumBanks', 'NumBanksConfig', 'NumGPUs', + 'NumLowerPipes', 'NumMaxCompressedFragments', 'NumPipes', + 'NumRbPerShaderEngine', 'NumShaderEngines', 'OBUF_BYPASS_DIS', + 'OBUF_BYPASS_EN', 'OBUF_BYPASS_SEL', 'OBUF_FULL', + 'OBUF_FULL_RECOUT', 'OBUF_HALF_RECOUT', + 'OBUF_IS_HALF_RECOUT_WIDTH_SEL', 'OBUF_RECOUT', + 'OBUF_USE_FULL_BUFFER_SEL', 'OFFCHIP_HS_DEALLOC', 'OFF_SEQ', + 'ONE_BANK', 'ONE_FRAGMENT', 'ONE_PIPE', 'ONE_RB_PER_SE', + 'ONE_SHADER_ENGIN', 'ON_SEQ', 'OPP_PIPE_CLOCK_DISABLE', + 'OPP_PIPE_CLOCK_ENABLE', 'OPP_PIPE_CLOCK_ENABLE_CONTROL', + 'OPP_PIPE_CRC_CONT_EN', 'OPP_PIPE_CRC_DISABLE', 'OPP_PIPE_CRC_EN', + 'OPP_PIPE_CRC_ENABLE', 'OPP_PIPE_CRC_INTERLACE_EN', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 'OPP_PIPE_CRC_INTERLACE_MODE', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', 'OPP_PIPE_CRC_MODE_CONTINUOUS', + 'OPP_PIPE_CRC_MODE_ONE_SHOT', 'OPP_PIPE_CRC_ONE_SHOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', + 'OPP_PIPE_CRC_PIXEL_SELECT', + 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 'OPP_PIPE_CRC_SOURCE_SELECT', 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', 'OPP_PIPE_CRC_STEREO_EN', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', + 'OPP_PIPE_CRC_STEREO_MODE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_LEFT', 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL', + 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', 'OPP_TEST_CLK_SEL_CONTROL', + 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', 'OPP_TEST_CLK_SEL_DISPCLK_OPP4', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP5', 'OPP_TEST_CLK_SEL_DISPCLK_P', + 'OPP_TEST_CLK_SEL_DISPCLK_R', 'OPP_TEST_CLK_SEL_RESERVED0', + 'OPP_TOP_CLOCK_DISABLED_STATUS', 'OPP_TOP_CLOCK_ENABLED_STATUS', + 'OPP_TOP_CLOCK_ENABLE_STATUS', 'OPP_TOP_CLOCK_GATING_CONTROL', + 'OPP_TOP_CLOCK_GATING_DISABLED', 'OPP_TOP_CLOCK_GATING_ENABLED', + 'OPT_COMB_ADD', 'OPT_COMB_BLEND_DISABLED', 'OPT_COMB_MAX', + 'OPT_COMB_MIN', 'OPT_COMB_NONE', 'OPT_COMB_REVSUBTRACT', + 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', + 'OTG_ADD_PIXEL', 'OTG_ADD_PIXEL_FORCE', 'OTG_ADD_PIXEL_NOOP', + 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN', + 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_FALSE', + 'OTG_BLANK_CONTROL_OTG_BLANK_DATA_EN_TRUE', + 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE', + 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_FALSE', + 'OTG_BLANK_CONTROL_OTG_BLANK_DE_MODE_TRUE', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_RESERVED', + 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE', + 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_FALSE', + 'OTG_CONTROL_OTG_DISP_READ_REQUEST_DISABLE_TRUE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', + 'OTG_CONTROL_OTG_MASTER_EN', 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 'OTG_CONTROL_OTG_MASTER_EN_TRUE', 'OTG_CONTROL_OTG_SOF_PULL_EN', + 'OTG_CONTROL_OTG_SOF_PULL_EN_FALSE', + 'OTG_CONTROL_OTG_SOF_PULL_EN_TRUE', + 'OTG_CONTROL_OTG_START_POINT_CNTL', + 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', + 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_0', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_1', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_2', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_FORMAT_3', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_FALSE', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_COMBINE_MODE_TRUE', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_1', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_2', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_3', + 'OTG_CRC_CNTL2_OTG_CRC_DATA_STREAM_SPLIT_MODE_DSIABLE', + 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE', + 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_FALSE', + 'OTG_CRC_CNTL2_OTG_CRC_DSC_MODE_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', 'OTG_CRC_CNTL_OTG_CRC_EN', + 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_0', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_1', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_2', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_RANGE_TIMING_DBUF_UPDATE_MODE_3', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', + 'OTG_DROP_PIXEL', 'OTG_DROP_PIXEL_FORCE', 'OTG_DROP_PIXEL_NOOP', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_CONTINUOUS', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_DISABLE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_ONESHOT', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_ENABLE_RESERVED', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE', + 'OTG_EXT_TIMING_SYNC_CONTROL_OTG_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_FALSE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_CLEAR_TRUE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_FALSE', + 'OTG_EXT_TIMING_SYNC_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_INT_TYPE_TRUE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE', + 'OTG_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE', + 'OTG_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_OTG_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_FALSE', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_ALIGNMENT_TRUE', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_FALSE', + 'OTG_FIELD_INDICATION_CONTROL_OTG_FIELD_INDICATION_OUTPUT_POLARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DSI_FREEZE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG4', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG5', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL', + 'OTG_GSL_MASTER_MODE', 'OTG_GSL_MASTER_MODE_0', + 'OTG_GSL_MASTER_MODE_1', 'OTG_GSL_MASTER_MODE_2', + 'OTG_GSL_MASTER_MODE_3', 'OTG_HORZ_REPETITION_COUNT', + 'OTG_HORZ_REPETITION_COUNT_0', 'OTG_HORZ_REPETITION_COUNT_1', + 'OTG_HORZ_REPETITION_COUNT_10', 'OTG_HORZ_REPETITION_COUNT_11', + 'OTG_HORZ_REPETITION_COUNT_12', 'OTG_HORZ_REPETITION_COUNT_13', + 'OTG_HORZ_REPETITION_COUNT_14', 'OTG_HORZ_REPETITION_COUNT_15', + 'OTG_HORZ_REPETITION_COUNT_2', 'OTG_HORZ_REPETITION_COUNT_3', + 'OTG_HORZ_REPETITION_COUNT_4', 'OTG_HORZ_REPETITION_COUNT_5', + 'OTG_HORZ_REPETITION_COUNT_6', 'OTG_HORZ_REPETITION_COUNT_7', + 'OTG_HORZ_REPETITION_COUNT_8', 'OTG_HORZ_REPETITION_COUNT_9', + 'OTG_H_SYNC_A_POL', 'OTG_H_SYNC_A_POL_HIGH', + 'OTG_H_SYNC_A_POL_LOW', 'OTG_H_TIMING_DIV_BY2', + 'OTG_H_TIMING_DIV_BY2_FALSE', 'OTG_H_TIMING_DIV_BY2_TRUE', + 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE', + 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE_0', + 'OTG_H_TIMING_DIV_BY2_UPDATE_MODE_1', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_V_UPDATE_INT_TYPE_TRUE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', + 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE', + 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DEBUG', + 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_DISABLE', + 'OTG_MVP_INBAND_CNTL_INSERT_OTG_MVP_INBAND_OUT_MODE_NORMAL', + 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR', + 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE', + 'OTG_MVP_STATUS_OTG_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE', + 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR', + 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_FALSE', + 'OTG_MVP_STATUS_OTG_FLIP_NOW_CLEAR_TRUE', 'OTG_PIPE_ABORT', + 'OTG_PIPE_ABORT_0', 'OTG_PIPE_ABORT_1', + 'OTG_PTI_CONTROL_OTG_PIT_EN', 'OTG_PTI_CONTROL_OTG_PIT_EN_FALSE', + 'OTG_PTI_CONTROL_OTG_PIT_EN_TRUE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', + 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY', + 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_FALSE', + 'OTG_START_LINE_CONTROL_OTG_INTERLACE_START_LINE_EARLY_TRUE', + 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN', + 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_FALSE', + 'OTG_START_LINE_CONTROL_OTG_LEGACY_REQUESTOR_EN_TRUE', + 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN', + 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_FALSE', + 'OTG_START_LINE_CONTROL_OTG_PREFETCH_EN_TRUE', + 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY', + 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_FALSE', + 'OTG_START_LINE_CONTROL_OTG_PROGRESSIVE_START_LINE_EARLY_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG4', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG5', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_DSI_FORCE_TOTAL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGA_FREQUENCY_SELECT', 'OTG_TRIGA_FREQUENCY_SELECT_0', + 'OTG_TRIGA_FREQUENCY_SELECT_1', 'OTG_TRIGA_FREQUENCY_SELECT_2', + 'OTG_TRIGA_FREQUENCY_SELECT_3', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG4', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG5', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_DSI_FORCE_TOTAL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_FREQUENCY_SELECT', 'OTG_TRIGB_FREQUENCY_SELECT_0', + 'OTG_TRIGB_FREQUENCY_SELECT_1', 'OTG_TRIGB_FREQUENCY_SELECT_2', + 'OTG_TRIGB_FREQUENCY_SELECT_3', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', + 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE', + 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_FALSE', + 'OTG_VGA_PARAMETER_CAPTURE_MODE_OTG_VGA_PARAMETER_CAPTURE_MODE_TRUE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', + 'OTG_V_SYNC_A_POL', 'OTG_V_SYNC_A_POL_HIGH', + 'OTG_V_SYNC_A_POL_LOW', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN', + 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_SET_V_TOTAL_MIN_MASK_EN_TRUE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE', + 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR', + 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_FALSE', + 'OTG_V_UPDATE_INT_STATUS_OTG_V_UPDATE_INT_CLEAR_TRUE', + 'OUTPUT_LINE', 'OUTPUT_POINT', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'OUTPUT_TRIANGLE_CCW', 'OUTPUT_TRIANGLE_CW', 'OUTSTANDING_REQ', + 'OVERRUN', 'P16_32x32_16x16', 'P16_32x32_8x16', 'P16_ADDR_SURF', + 'P2', 'P4_16x16', 'P4_16x32', 'P4_32x32', 'P4_8x16', + 'P8_16x16_8x16', 'P8_16x32_16x16', 'P8_16x32_8x16', + 'P8_32x32_16x16', 'P8_32x32_16x32', 'P8_32x32_8x16', + 'P8_32x64_32x32', 'PART_FRAC_EVEN', 'PART_FRAC_ODD', + 'PART_INTEGER', 'PART_POW2', 'PATCHES', 'PERFCOUNTER_ACTIVE', + 'PERFCOUNTER_CNT0_STATE', 'PERFCOUNTER_CNT0_STATE_FREEZE', + 'PERFCOUNTER_CNT0_STATE_HW', 'PERFCOUNTER_CNT0_STATE_RESET', + 'PERFCOUNTER_CNT0_STATE_START', 'PERFCOUNTER_CNT1_STATE', + 'PERFCOUNTER_CNT1_STATE_FREEZE', 'PERFCOUNTER_CNT1_STATE_HW', + 'PERFCOUNTER_CNT1_STATE_RESET', 'PERFCOUNTER_CNT1_STATE_START', + 'PERFCOUNTER_CNT2_STATE', 'PERFCOUNTER_CNT2_STATE_FREEZE', + 'PERFCOUNTER_CNT2_STATE_HW', 'PERFCOUNTER_CNT2_STATE_RESET', + 'PERFCOUNTER_CNT2_STATE_START', 'PERFCOUNTER_CNT3_STATE', + 'PERFCOUNTER_CNT3_STATE_FREEZE', 'PERFCOUNTER_CNT3_STATE_HW', + 'PERFCOUNTER_CNT3_STATE_RESET', 'PERFCOUNTER_CNT3_STATE_START', + 'PERFCOUNTER_CNT4_STATE', 'PERFCOUNTER_CNT4_STATE_FREEZE', + 'PERFCOUNTER_CNT4_STATE_HW', 'PERFCOUNTER_CNT4_STATE_RESET', + 'PERFCOUNTER_CNT4_STATE_START', 'PERFCOUNTER_CNT5_STATE', + 'PERFCOUNTER_CNT5_STATE_FREEZE', 'PERFCOUNTER_CNT5_STATE_HW', + 'PERFCOUNTER_CNT5_STATE_RESET', 'PERFCOUNTER_CNT5_STATE_START', + 'PERFCOUNTER_CNT6_STATE', 'PERFCOUNTER_CNT6_STATE_FREEZE', + 'PERFCOUNTER_CNT6_STATE_HW', 'PERFCOUNTER_CNT6_STATE_RESET', + 'PERFCOUNTER_CNT6_STATE_START', 'PERFCOUNTER_CNT7_STATE', + 'PERFCOUNTER_CNT7_STATE_FREEZE', 'PERFCOUNTER_CNT7_STATE_HW', + 'PERFCOUNTER_CNT7_STATE_RESET', 'PERFCOUNTER_CNT7_STATE_START', + 'PERFCOUNTER_CNTL_SEL', 'PERFCOUNTER_CNTL_SEL_0', + 'PERFCOUNTER_CNTL_SEL_1', 'PERFCOUNTER_CNTL_SEL_2', + 'PERFCOUNTER_CNTL_SEL_3', 'PERFCOUNTER_CNTL_SEL_4', + 'PERFCOUNTER_CNTL_SEL_5', 'PERFCOUNTER_CNTL_SEL_6', + 'PERFCOUNTER_CNTL_SEL_7', 'PERFCOUNTER_CNTOFF_START_DIS', + 'PERFCOUNTER_CNTOFF_START_DISABLE', + 'PERFCOUNTER_CNTOFF_START_ENABLE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', 'PERFCOUNTER_CVALUE_SEL', + 'PERFCOUNTER_CVALUE_SEL_11_0', 'PERFCOUNTER_CVALUE_SEL_15_0', + 'PERFCOUNTER_CVALUE_SEL_23_12', 'PERFCOUNTER_CVALUE_SEL_31_16', + 'PERFCOUNTER_CVALUE_SEL_35_24', 'PERFCOUNTER_CVALUE_SEL_47_0', + 'PERFCOUNTER_CVALUE_SEL_47_32', 'PERFCOUNTER_CVALUE_SEL_47_36', + 'PERFCOUNTER_HW_CNTL_SEL', 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', + 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', 'PERFCOUNTER_HW_STOP1_0', + 'PERFCOUNTER_HW_STOP1_1', 'PERFCOUNTER_HW_STOP1_SEL', + 'PERFCOUNTER_HW_STOP2_0', 'PERFCOUNTER_HW_STOP2_1', + 'PERFCOUNTER_HW_STOP2_SEL', 'PERFCOUNTER_INC_MODE', + 'PERFCOUNTER_INC_MODE_BOTH_EDGE', 'PERFCOUNTER_INC_MODE_LSB', + 'PERFCOUNTER_INC_MODE_MULTI_BIT', 'PERFCOUNTER_INC_MODE_NEG_EDGE', + 'PERFCOUNTER_INC_MODE_POS_EDGE', 'PERFCOUNTER_INT_DISABLE', + 'PERFCOUNTER_INT_EN', 'PERFCOUNTER_INT_ENABLE', + 'PERFCOUNTER_INT_TYPE', 'PERFCOUNTER_INT_TYPE_LEVEL', + 'PERFCOUNTER_INT_TYPE_PULSE', 'PERFCOUNTER_IS_ACTIVE', + 'PERFCOUNTER_IS_IDLE', 'PERFCOUNTER_OFF_MASK', + 'PERFCOUNTER_OFF_MASK_DISABLE', 'PERFCOUNTER_OFF_MASK_ENABLE', + 'PERFCOUNTER_RESTART_DISABLE', 'PERFCOUNTER_RESTART_EN', + 'PERFCOUNTER_RESTART_ENABLE', 'PERFCOUNTER_RUNEN_MODE', + 'PERFCOUNTER_RUNEN_MODE_EDGE', 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 'PERFCOUNTER_SAMPLE', 'PERFCOUNTER_START', + 'PERFCOUNTER_STATE_SEL0', 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 'PERFCOUNTER_STATE_SEL0_LOCAL', 'PERFCOUNTER_STATE_SEL1', + 'PERFCOUNTER_STATE_SEL1_GLOBAL', 'PERFCOUNTER_STATE_SEL1_LOCAL', + 'PERFCOUNTER_STATE_SEL2', 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 'PERFCOUNTER_STATE_SEL2_LOCAL', 'PERFCOUNTER_STATE_SEL3', + 'PERFCOUNTER_STATE_SEL3_GLOBAL', 'PERFCOUNTER_STATE_SEL3_LOCAL', + 'PERFCOUNTER_STATE_SEL4', 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 'PERFCOUNTER_STATE_SEL4_LOCAL', 'PERFCOUNTER_STATE_SEL5', + 'PERFCOUNTER_STATE_SEL5_GLOBAL', 'PERFCOUNTER_STATE_SEL5_LOCAL', + 'PERFCOUNTER_STATE_SEL6', 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 'PERFCOUNTER_STATE_SEL6_LOCAL', 'PERFCOUNTER_STATE_SEL7', + 'PERFCOUNTER_STATE_SEL7_GLOBAL', 'PERFCOUNTER_STATE_SEL7_LOCAL', + 'PERFCOUNTER_STOP', 'PERFMON_CNTOFF_AND', 'PERFMON_CNTOFF_AND_OR', + 'PERFMON_CNTOFF_INT_DISABLE', 'PERFMON_CNTOFF_INT_EN', + 'PERFMON_CNTOFF_INT_ENABLE', 'PERFMON_CNTOFF_INT_TYPE', + 'PERFMON_CNTOFF_INT_TYPE_LEVEL', 'PERFMON_CNTOFF_INT_TYPE_PULSE', + 'PERFMON_CNTOFF_OR', 'PERFMON_COUNTER_MODE', + 'PERFMON_COUNTER_MODE_ACCUM', + 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 'PERFMON_COUNTER_MODE_DIRTY', + 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_MAX', 'PERFMON_COUNTER_MODE_RESERVED', + 'PERFMON_COUNTER_MODE_SAMPLE', 'PERFMON_SPM_MODE', + 'PERFMON_SPM_MODE_16BIT_CLAMP', 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_32BIT_CLAMP', 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_OFF', 'PERFMON_SPM_MODE_RESERVED_5', + 'PERFMON_SPM_MODE_RESERVED_6', 'PERFMON_SPM_MODE_RESERVED_7', + 'PERFMON_SPM_MODE_TEST_MODE_0', 'PERFMON_SPM_MODE_TEST_MODE_1', + 'PERFMON_SPM_MODE_TEST_MODE_2', 'PERFMON_STATE', + 'PERFMON_STATE_FREEZE', 'PERFMON_STATE_HW', 'PERFMON_STATE_RESET', + 'PERFMON_STATE_START', 'PERF_CLIENT_UTCL1_INFLIGHT', + 'PERF_INDEX_RECEIVE_0_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_10_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_11_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_12_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_13_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_14_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_15_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_16_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_1_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_2_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_3_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_4_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_5_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_6_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_7_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_8_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_9_VALID_DWORDS_THIS_CACHELINE', + 'PERF_INDEX_RECEIVE_PRIM_INDICES_FIFO_WRITE', + 'PERF_INDEX_RECEIVE_QUALIFIED_BUSY', + 'PERF_INDEX_RECEIVE_QUALIFIED_STARVED', + 'PERF_INDEX_RECEIVE_WAITING_ON_PRIM_INDICES_FIFO', + 'PERF_INDEX_RECEIVE_WAITING_ON_RETURNED_CACHELINE', + 'PERF_INDEX_REQUEST_QUALIFIED_BUSY', + 'PERF_INDEX_REQUEST_QUALIFIED_STARVED', + 'PERF_INDEX_REQUEST_WAITING_ON_FULL_RECEIVE_FIFO', + 'PERF_INDEX_REQUEST_WAITING_ON_TOKENS', 'PERF_PAPC_CCGSM_BUSY', + 'PERF_PAPC_CCGSM_IDLE', 'PERF_PAPC_CCGSM_STALLED', + 'PERF_PAPC_CLIPGA_BUSY', 'PERF_PAPC_CLIPGA_IDLE', + 'PERF_PAPC_CLIPGA_STALLED', 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', 'PERF_PAPC_CLIPSM_BUSY', + 'PERF_PAPC_CLIPSM_IDLE', 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', 'PERF_PAPC_CLIP_BUSY', + 'PERF_PAPC_CLIP_IDLE', 'PERF_PAPC_CLPRIM_BUSY', + 'PERF_PAPC_CLPRIM_IDLE', 'PERF_PAPC_CLPRIM_STALLED', + 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', 'PERF_PAPC_CLPR_CULL_PRIM', + 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 'PERF_PAPC_CLPR_VV_CULL_PRIM', 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', 'PERF_PAPC_CLSM_NULL_PRIM', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 'PERF_PAPC_CL_DYN_SCLK_VLD', 'PERF_PAPC_PASX_DISABLE_PIPE', + 'PERF_PAPC_PASX_FIRST_DEAD', 'PERF_PAPC_PASX_FIRST_VECTOR', + 'PERF_PAPC_PASX_REC_BUSY', 'PERF_PAPC_PASX_REC_IDLE', + 'PERF_PAPC_PASX_REC_STALLED', + 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 'PERF_PAPC_PASX_REC_STARVED_SX', 'PERF_PAPC_PASX_REQ', + 'PERF_PAPC_PASX_REQ_BUSY', 'PERF_PAPC_PASX_REQ_IDLE', + 'PERF_PAPC_PASX_REQ_STALLED', 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 'PERF_PAPC_PASX_SE0_REQ', 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', 'PERF_PAPC_PASX_SE1_REQ', + 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', 'PERF_PAPC_PASX_SECOND_DEAD', + 'PERF_PAPC_PASX_SECOND_VECTOR', 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_PA_INPUT_NULL_PRIM', 'PERF_PAPC_PA_INPUT_PRIM', + 'PERF_PAPC_PA_REG_SCLK_VLD', 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 'PERF_PAPC_SU_BUSY', 'PERF_PAPC_SU_CULLED_PRIM', + 'PERF_PAPC_SU_DYN_SCLK_VLD', 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 'PERF_PAPC_SU_IDLE', 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_INPUT_NULL_PRIM', 'PERF_PAPC_SU_INPUT_PRIM', + 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', 'PERF_PAPC_SU_OUTPUT_EOPG', + 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', 'PERF_PAPC_SU_OUTPUT_PRIM', + 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE01_STALLED_SC', + 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE0_STALLED_SC', + 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE1_STALLED_SC', + 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE2_STALLED_SC', + 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE3_STALLED_SC', 'PERF_PAPC_SU_STALLED_SC', + 'PERF_PAPC_SU_STARVED_CLIP', 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 'PERF_PAWD_DEALLOC_FIFO_IS_FULL', + 'PERF_PAWD_DEALLOC_WAITING_TO_BE_READ', + 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 'PERF_PA_FETCH_TO_SXIF_FIFO_FULL', + 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', + 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 'PERF_PA_SE0_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 'PERF_PA_SE1_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 'PERF_PA_SE2_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_NO_SEND', + 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_ASSERTED_WITH_SEND', + 'PERF_PA_SE3_OUTPUT_QUALIFIED_CLKEN_NOT_ASSERTED', + 'PERF_PA_VERTEX_FIFO_FULL', + 'PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 'PERF_POS_REQ_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 'PERF_POS_REQ_QUALIFIED_BUSY', 'PERF_POS_REQ_QUALIFIED_STARVED', + 'PERF_POS_REQ_REUSE_0_NEW_VERTS_THIS_PRIM', + 'PERF_POS_REQ_REUSE_1_NEW_VERTS_THIS_PRIM', + 'PERF_POS_REQ_REUSE_2_NEW_VERTS_THIS_PRIM', + 'PERF_POS_REQ_REUSE_3_NEW_VERTS_THIS_PRIM', + 'PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 'PERF_POS_REQ_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 'PERF_POS_REQ_STALLED_BY_FULL_PA_TO_WD_DEALLOC_INDEX_FIFO', + 'PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_S_FIFO', + 'PERF_POS_REQ_STALLED_BY_FULL_POSREQ_TO_POSRTN_V_FIFO', + 'PERF_POS_REQ_STALLED_BY_NO_TOKENS', + 'PERF_POS_REQ_STALLED_BY_UTCL1', + 'PERF_POS_REQ_STARVED_BY_NO_PRIM', + 'PERF_POS_RET_1_CACHELINE_POSITION_USED', + 'PERF_POS_RET_2_CACHELINE_POSITION_USED', + 'PERF_POS_RET_3_CACHELINE_POSITION_USED', + 'PERF_POS_RET_4_CACHELINE_POSITION_USED', + 'PERF_POS_RET_FETCH_TO_SXIF_FIFO_WRITE', + 'PERF_POS_RET_FULL_FETCH_TO_SXIF_FIFO', + 'PERF_POS_RET_FULL_PA_TO_WD_DEALLOC_POSITION_FIFO', + 'PERF_POS_RET_QUALIFIED_BUSY', 'PERF_POS_RET_QUALIFIED_STARVED', + 'PERF_POS_RET_WAITING_ON_RETURNED_CACHELINE', + 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SHOOTDOWN_WAIT_ALL_CLEAN', 'PERF_SHOOTDOWN_WAIT_DEASSERT', + 'PERF_SHOOTDOWN_WAIT_ON_UTCL1', + 'PERF_SHOOTDOWN_WAIT_ON_UTC_INDEX', + 'PERF_SHOOTDOWN_WAIT_ON_UTC_POSITION', + 'PERF_SHOOTDOWN_WAIT_ON_UTC_SIDEBAND', + 'PERF_SIDEBAND_0_VALID_DWORDS_RECEIVED_', + 'PERF_SIDEBAND_16_VALID_DWORDS_RECEIVED_', + 'PERF_SIDEBAND_1_TO_7_VALID_DWORDS_RECEIVED_', + 'PERF_SIDEBAND_8_TO_15_VALID_DWORDS_RECEIVED_', + 'PERF_SIDEBAND_EXPECTING_16_POSSIBLE_VALID_DWORD', + 'PERF_SIDEBAND_EXPECTING_1_POSSIBLE_VALID_DWORD', + 'PERF_SIDEBAND_EXPECTING_2_TO_15_POSSIBLE_VALID_DWORD', + 'PERF_SIDEBAND_FIFO_VMID_FIFO_FULL', + 'PERF_SIDEBAND_INVALID_REFETCH', + 'PERF_SIDEBAND_POP_BIT_FIFO_FULL', 'PERF_SIDEBAND_QUALIFIED_BUSY', + 'PERF_SIDEBAND_QUALIFIED_STARVED', + 'PERF_SIDEBAND_WAITING_ON_FULL_SIDEBAND_MEMORY', + 'PERF_SIDEBAND_WAITING_ON_RETURNED_DATA', + 'PERF_SIDEBAND_WAITING_ON_UTCL1', 'PERF_SMALL_PRIM_CULL_PRIM_1X1', + 'PERF_SMALL_PRIM_CULL_PRIM_1X2', 'PERF_SMALL_PRIM_CULL_PRIM_1X3', + 'PERF_SMALL_PRIM_CULL_PRIM_1XN', 'PERF_SMALL_PRIM_CULL_PRIM_2X1', + 'PERF_SMALL_PRIM_CULL_PRIM_2X2', 'PERF_SMALL_PRIM_CULL_PRIM_2X3', + 'PERF_SMALL_PRIM_CULL_PRIM_2XN', 'PERF_SMALL_PRIM_CULL_PRIM_3X1', + 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 'PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_NX1', 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 'PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT', + 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', 'PERF_TCIF_BUSY', + 'PERF_TCIF_INDEX_RDREQ', 'PERF_TCIF_POSITION_RDREQ', + 'PERF_TCIF_SIDEBAND_RDREQ', + 'PERF_TCIF_STALLING_CLIENT_NO_CREDITS', + 'PERF_TC_ARBITER_WAITING_FOR_TC_INTERFACE', + 'PERF_TC_INDEX_LATENCY_BIN0', 'PERF_TC_INDEX_LATENCY_BIN1', + 'PERF_TC_INDEX_LATENCY_BIN10', 'PERF_TC_INDEX_LATENCY_BIN11', + 'PERF_TC_INDEX_LATENCY_BIN12', 'PERF_TC_INDEX_LATENCY_BIN13', + 'PERF_TC_INDEX_LATENCY_BIN14', 'PERF_TC_INDEX_LATENCY_BIN15', + 'PERF_TC_INDEX_LATENCY_BIN2', 'PERF_TC_INDEX_LATENCY_BIN3', + 'PERF_TC_INDEX_LATENCY_BIN4', 'PERF_TC_INDEX_LATENCY_BIN5', + 'PERF_TC_INDEX_LATENCY_BIN6', 'PERF_TC_INDEX_LATENCY_BIN7', + 'PERF_TC_INDEX_LATENCY_BIN8', 'PERF_TC_INDEX_LATENCY_BIN9', + 'PERF_TC_POSITION_LATENCY_BIN0', 'PERF_TC_POSITION_LATENCY_BIN1', + 'PERF_TC_POSITION_LATENCY_BIN10', + 'PERF_TC_POSITION_LATENCY_BIN11', + 'PERF_TC_POSITION_LATENCY_BIN12', + 'PERF_TC_POSITION_LATENCY_BIN13', + 'PERF_TC_POSITION_LATENCY_BIN14', + 'PERF_TC_POSITION_LATENCY_BIN15', 'PERF_TC_POSITION_LATENCY_BIN2', + 'PERF_TC_POSITION_LATENCY_BIN3', 'PERF_TC_POSITION_LATENCY_BIN4', + 'PERF_TC_POSITION_LATENCY_BIN5', 'PERF_TC_POSITION_LATENCY_BIN6', + 'PERF_TC_POSITION_LATENCY_BIN7', 'PERF_TC_POSITION_LATENCY_BIN8', + 'PERF_TC_POSITION_LATENCY_BIN9', 'PERF_TC_STREAM0_DATA_AVAILABLE', + 'PERF_TC_STREAM1_DATA_AVAILABLE', + 'PERF_TC_STREAM2_DATA_AVAILABLE', 'PERF_UTCL1_LFIFO_FULL', + 'PERF_UTCL1_PERMISSION_MISS_CLIENT0', + 'PERF_UTCL1_PERMISSION_MISS_CLIENT1', + 'PERF_UTCL1_PERMISSION_MISS_CLIENT2', + 'PERF_UTCL1_REQUEST_CLIENT0', 'PERF_UTCL1_REQUEST_CLIENT1', + 'PERF_UTCL1_REQUEST_CLIENT2', 'PERF_UTCL1_STALL_INFLIGHT_MAX', + 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT0', + 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT1', + 'PERF_UTCL1_STALL_LFIFO_NOT_RES_CLIENT2', + 'PERF_UTCL1_STALL_LRU_INFLIGHT', 'PERF_UTCL1_STALL_MISSFIFO_FULL', + 'PERF_UTCL1_STALL_MULTI_MISS', + 'PERF_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'PERF_UTCL1_TRANSLATION_HIT_CLIENT0', + 'PERF_UTCL1_TRANSLATION_HIT_CLIENT1', + 'PERF_UTCL1_TRANSLATION_HIT_CLIENT2', + 'PERF_UTCL1_TRANSLATION_MISS_CLIENT0', + 'PERF_UTCL1_TRANSLATION_MISS_CLIENT1', + 'PERF_UTCL1_TRANSLATION_MISS_CLIENT2', + 'PERF_UTCL1_UTCL2_INFLIGHT', 'PERF_UTCL1_UTCL2_REQ', + 'PERF_UTCL1_UTCL2_RET', 'PERF_UTC_INDEX_DRIVER_BUSY', + 'PERF_UTC_INDEX_DRIVER_STALLING_CLIENT', + 'PERF_UTC_INDEX_DRIVER_WAITING_ON_UTCL1', + 'PERF_UTC_INDEX_RECEIVER_BUSY', + 'PERF_UTC_INDEX_RECEIVER_STALLED_BY_ARBITER', + 'PERF_UTC_INDEX_RECEIVER_STALLING_UTCL1', + 'PERF_UTC_POSITION_DRIVER_BUSY', + 'PERF_UTC_POSITION_DRIVER_STALLING_CLIENT', + 'PERF_UTC_POSITION_DRIVER_WAITING_ON_UTCL1', + 'PERF_UTC_POSITION_RECEIVER_BUSY', + 'PERF_UTC_POSITION_RECEIVER_STALLED_BY_ARBITER', + 'PERF_UTC_POSITION_RECEIVER_STALLING_UTCL1', + 'PERF_UTC_SIDEBAND_DRIVER_BUSY', + 'PERF_UTC_SIDEBAND_DRIVER_STALLING_CLIENT', + 'PERF_UTC_SIDEBAND_DRIVER_WAITING_ON_UTCL1', + 'PERF_UTC_SIDEBAND_RECEIVER_BUSY', + 'PERF_UTC_SIDEBAND_RECEIVER_STALLED_BY_ARBITER', + 'PERF_UTC_SIDEBAND_RECEIVER_STALLING_UTCL1', + 'PERF_WRITING_TO_SIDEBAND_MEMORY', 'PERSISTENT_SPACE_END', + 'PERSISTENT_SPACE_START', 'PH_PERFCNT_SEL', 'PH_SC0_ARB_BUSY', + 'PH_SC0_ARB_EOP_POP_SYNC_POP', 'PH_SC0_ARB_EVENT_SYNC_POP', + 'PH_SC0_ARB_PA_BUSY_SOP', 'PH_SC0_ARB_STALLED_FROM_BELOW', + 'PH_SC0_ARB_STARVED_FROM_ABOVE', + 'PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC0_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC0_BUSY_CNT_NOT_ZERO', + 'PH_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC0_CREDIT_AT_MAX', + 'PH_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC0_EOP_SYNC_WINDOW', 'PH_SC0_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC0_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 'PH_SC0_PA0_DATA_FIFO_EOP_RD', 'PH_SC0_PA0_DATA_FIFO_RD', + 'PH_SC0_PA0_DATA_FIFO_WE', 'PH_SC0_PA0_DEALLOC_4_0_RD', + 'PH_SC0_PA0_EOPG_WE', 'PH_SC0_PA0_EOP_WE', 'PH_SC0_PA0_EVENT_WE', + 'PH_SC0_PA0_FIFO_EMPTY', 'PH_SC0_PA0_FIFO_FULL', + 'PH_SC0_PA0_FPOV_WE', 'PH_SC0_PA0_LPOV_WE', 'PH_SC0_PA0_NULL_WE', + 'PH_SC0_PA1_DATA_FIFO_EOP_RD', 'PH_SC0_PA1_DATA_FIFO_RD', + 'PH_SC0_PA1_DATA_FIFO_WE', 'PH_SC0_PA1_DEALLOC_4_0_RD', + 'PH_SC0_PA1_EOPG_WE', 'PH_SC0_PA1_EOP_WE', 'PH_SC0_PA1_EVENT_WE', + 'PH_SC0_PA1_FIFO_EMPTY', 'PH_SC0_PA1_FIFO_FULL', + 'PH_SC0_PA1_FPOV_WE', 'PH_SC0_PA1_LPOV_WE', 'PH_SC0_PA1_NULL_WE', + 'PH_SC0_PA2_DATA_FIFO_EOP_RD', 'PH_SC0_PA2_DATA_FIFO_RD', + 'PH_SC0_PA2_DATA_FIFO_WE', 'PH_SC0_PA2_DEALLOC_4_0_RD', + 'PH_SC0_PA2_EOPG_WE', 'PH_SC0_PA2_EOP_WE', 'PH_SC0_PA2_EVENT_WE', + 'PH_SC0_PA2_FIFO_EMPTY', 'PH_SC0_PA2_FIFO_FULL', + 'PH_SC0_PA2_FPOV_WE', 'PH_SC0_PA2_LPOV_WE', 'PH_SC0_PA2_NULL_WE', + 'PH_SC0_PA3_DATA_FIFO_EOP_RD', 'PH_SC0_PA3_DATA_FIFO_RD', + 'PH_SC0_PA3_DATA_FIFO_WE', 'PH_SC0_PA3_DEALLOC_4_0_RD', + 'PH_SC0_PA3_EOPG_WE', 'PH_SC0_PA3_EOP_WE', 'PH_SC0_PA3_EVENT_WE', + 'PH_SC0_PA3_FIFO_EMPTY', 'PH_SC0_PA3_FIFO_FULL', + 'PH_SC0_PA3_FPOV_WE', 'PH_SC0_PA3_LPOV_WE', 'PH_SC0_PA3_NULL_WE', + 'PH_SC0_PA4_DATA_FIFO_EOP_RD', 'PH_SC0_PA4_DATA_FIFO_RD', + 'PH_SC0_PA4_DATA_FIFO_WE', 'PH_SC0_PA4_DEALLOC_4_0_RD', + 'PH_SC0_PA4_EOPG_WE', 'PH_SC0_PA4_EOP_WE', 'PH_SC0_PA4_EVENT_WE', + 'PH_SC0_PA4_FIFO_EMPTY', 'PH_SC0_PA4_FIFO_FULL', + 'PH_SC0_PA4_FPOV_WE', 'PH_SC0_PA4_LPOV_WE', 'PH_SC0_PA4_NULL_WE', + 'PH_SC0_PA5_DATA_FIFO_EOP_RD', 'PH_SC0_PA5_DATA_FIFO_RD', + 'PH_SC0_PA5_DATA_FIFO_WE', 'PH_SC0_PA5_DEALLOC_4_0_RD', + 'PH_SC0_PA5_EOPG_WE', 'PH_SC0_PA5_EOP_WE', 'PH_SC0_PA5_EVENT_WE', + 'PH_SC0_PA5_FIFO_EMPTY', 'PH_SC0_PA5_FIFO_FULL', + 'PH_SC0_PA5_FPOV_WE', 'PH_SC0_PA5_LPOV_WE', 'PH_SC0_PA5_NULL_WE', + 'PH_SC0_PA6_DATA_FIFO_EOP_RD', 'PH_SC0_PA6_DATA_FIFO_RD', + 'PH_SC0_PA6_DATA_FIFO_WE', 'PH_SC0_PA6_DEALLOC_4_0_RD', + 'PH_SC0_PA6_EOPG_WE', 'PH_SC0_PA6_EOP_WE', 'PH_SC0_PA6_EVENT_WE', + 'PH_SC0_PA6_FIFO_EMPTY', 'PH_SC0_PA6_FIFO_FULL', + 'PH_SC0_PA6_FPOV_WE', 'PH_SC0_PA6_LPOV_WE', 'PH_SC0_PA6_NULL_WE', + 'PH_SC0_PA7_DATA_FIFO_EOP_RD', 'PH_SC0_PA7_DATA_FIFO_RD', + 'PH_SC0_PA7_DATA_FIFO_WE', 'PH_SC0_PA7_DEALLOC_4_0_RD', + 'PH_SC0_PA7_EOPG_WE', 'PH_SC0_PA7_EOP_WE', 'PH_SC0_PA7_EVENT_WE', + 'PH_SC0_PA7_FIFO_EMPTY', 'PH_SC0_PA7_FIFO_FULL', + 'PH_SC0_PA7_FPOV_WE', 'PH_SC0_PA7_LPOV_WE', 'PH_SC0_PA7_NULL_WE', + 'PH_SC0_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC0_SEND', + 'PH_SC0_SRPS_WINDOW_VALID', 'PH_SC1_ARB_BUSY', + 'PH_SC1_ARB_EOP_POP_SYNC_POP', 'PH_SC1_ARB_EVENT_SYNC_POP', + 'PH_SC1_ARB_PA_BUSY_SOP', 'PH_SC1_ARB_STALLED_FROM_BELOW', + 'PH_SC1_ARB_STARVED_FROM_ABOVE', + 'PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC1_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC1_BUSY_CNT_NOT_ZERO', + 'PH_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC1_CREDIT_AT_MAX', + 'PH_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC1_EOP_SYNC_WINDOW', 'PH_SC1_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC1_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC1_PA0_DATA_FIFO_EOP_RD', 'PH_SC1_PA0_DATA_FIFO_RD', + 'PH_SC1_PA0_DATA_FIFO_WE', 'PH_SC1_PA0_DEALLOC_4_0_RD', + 'PH_SC1_PA0_EOPG_WE', 'PH_SC1_PA0_EOP_WE', 'PH_SC1_PA0_EVENT_WE', + 'PH_SC1_PA0_FIFO_EMPTY', 'PH_SC1_PA0_FIFO_FULL', + 'PH_SC1_PA0_FPOV_WE', 'PH_SC1_PA0_LPOV_WE', 'PH_SC1_PA0_NULL_WE', + 'PH_SC1_PA1_DATA_FIFO_EOP_RD', 'PH_SC1_PA1_DATA_FIFO_RD', + 'PH_SC1_PA1_DATA_FIFO_WE', 'PH_SC1_PA1_DEALLOC_4_0_RD', + 'PH_SC1_PA1_EOPG_WE', 'PH_SC1_PA1_EOP_WE', 'PH_SC1_PA1_EVENT_WE', + 'PH_SC1_PA1_FIFO_EMPTY', 'PH_SC1_PA1_FIFO_FULL', + 'PH_SC1_PA1_FPOV_WE', 'PH_SC1_PA1_LPOV_WE', 'PH_SC1_PA1_NULL_WE', + 'PH_SC1_PA2_DATA_FIFO_EOP_RD', 'PH_SC1_PA2_DATA_FIFO_RD', + 'PH_SC1_PA2_DATA_FIFO_WE', 'PH_SC1_PA2_DEALLOC_4_0_RD', + 'PH_SC1_PA2_EOPG_WE', 'PH_SC1_PA2_EOP_WE', 'PH_SC1_PA2_EVENT_WE', + 'PH_SC1_PA2_FIFO_EMPTY', 'PH_SC1_PA2_FIFO_FULL', + 'PH_SC1_PA2_FPOV_WE', 'PH_SC1_PA2_LPOV_WE', 'PH_SC1_PA2_NULL_WE', + 'PH_SC1_PA3_DATA_FIFO_EOP_RD', 'PH_SC1_PA3_DATA_FIFO_RD', + 'PH_SC1_PA3_DATA_FIFO_WE', 'PH_SC1_PA3_DEALLOC_4_0_RD', + 'PH_SC1_PA3_EOPG_WE', 'PH_SC1_PA3_EOP_WE', 'PH_SC1_PA3_EVENT_WE', + 'PH_SC1_PA3_FIFO_EMPTY', 'PH_SC1_PA3_FIFO_FULL', + 'PH_SC1_PA3_FPOV_WE', 'PH_SC1_PA3_LPOV_WE', 'PH_SC1_PA3_NULL_WE', + 'PH_SC1_PA4_DATA_FIFO_EOP_RD', 'PH_SC1_PA4_DATA_FIFO_RD', + 'PH_SC1_PA4_DATA_FIFO_WE', 'PH_SC1_PA4_DEALLOC_4_0_RD', + 'PH_SC1_PA4_EOPG_WE', 'PH_SC1_PA4_EOP_WE', 'PH_SC1_PA4_EVENT_WE', + 'PH_SC1_PA4_FIFO_EMPTY', 'PH_SC1_PA4_FIFO_FULL', + 'PH_SC1_PA4_FPOV_WE', 'PH_SC1_PA4_LPOV_WE', 'PH_SC1_PA4_NULL_WE', + 'PH_SC1_PA5_DATA_FIFO_EOP_RD', 'PH_SC1_PA5_DATA_FIFO_RD', + 'PH_SC1_PA5_DATA_FIFO_WE', 'PH_SC1_PA5_DEALLOC_4_0_RD', + 'PH_SC1_PA5_EOPG_WE', 'PH_SC1_PA5_EOP_WE', 'PH_SC1_PA5_EVENT_WE', + 'PH_SC1_PA5_FIFO_EMPTY', 'PH_SC1_PA5_FIFO_FULL', + 'PH_SC1_PA5_FPOV_WE', 'PH_SC1_PA5_LPOV_WE', 'PH_SC1_PA5_NULL_WE', + 'PH_SC1_PA6_DATA_FIFO_EOP_RD', 'PH_SC1_PA6_DATA_FIFO_RD', + 'PH_SC1_PA6_DATA_FIFO_WE', 'PH_SC1_PA6_DEALLOC_4_0_RD', + 'PH_SC1_PA6_EOPG_WE', 'PH_SC1_PA6_EOP_WE', 'PH_SC1_PA6_EVENT_WE', + 'PH_SC1_PA6_FIFO_EMPTY', 'PH_SC1_PA6_FIFO_FULL', + 'PH_SC1_PA6_FPOV_WE', 'PH_SC1_PA6_LPOV_WE', 'PH_SC1_PA6_NULL_WE', + 'PH_SC1_PA7_DATA_FIFO_EOP_RD', 'PH_SC1_PA7_DATA_FIFO_RD', + 'PH_SC1_PA7_DATA_FIFO_WE', 'PH_SC1_PA7_DEALLOC_4_0_RD', + 'PH_SC1_PA7_EOPG_WE', 'PH_SC1_PA7_EOP_WE', 'PH_SC1_PA7_EVENT_WE', + 'PH_SC1_PA7_FIFO_EMPTY', 'PH_SC1_PA7_FIFO_FULL', + 'PH_SC1_PA7_FPOV_WE', 'PH_SC1_PA7_LPOV_WE', 'PH_SC1_PA7_NULL_WE', + 'PH_SC1_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC1_SEND', + 'PH_SC1_SRPS_WINDOW_VALID', 'PH_SC2_ARB_BUSY', + 'PH_SC2_ARB_EOP_POP_SYNC_POP', 'PH_SC2_ARB_EVENT_SYNC_POP', + 'PH_SC2_ARB_PA_BUSY_SOP', 'PH_SC2_ARB_STALLED_FROM_BELOW', + 'PH_SC2_ARB_STARVED_FROM_ABOVE', + 'PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC2_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC2_BUSY_CNT_NOT_ZERO', + 'PH_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC2_CREDIT_AT_MAX', + 'PH_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC2_EOP_SYNC_WINDOW', 'PH_SC2_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC2_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC2_PA0_DATA_FIFO_EOP_RD', 'PH_SC2_PA0_DATA_FIFO_RD', + 'PH_SC2_PA0_DATA_FIFO_WE', 'PH_SC2_PA0_DEALLOC_4_0_RD', + 'PH_SC2_PA0_EOPG_WE', 'PH_SC2_PA0_EOP_WE', 'PH_SC2_PA0_EVENT_WE', + 'PH_SC2_PA0_FIFO_EMPTY', 'PH_SC2_PA0_FIFO_FULL', + 'PH_SC2_PA0_FPOV_WE', 'PH_SC2_PA0_LPOV_WE', 'PH_SC2_PA0_NULL_WE', + 'PH_SC2_PA1_DATA_FIFO_EOP_RD', 'PH_SC2_PA1_DATA_FIFO_RD', + 'PH_SC2_PA1_DATA_FIFO_WE', 'PH_SC2_PA1_DEALLOC_4_0_RD', + 'PH_SC2_PA1_EOPG_WE', 'PH_SC2_PA1_EOP_WE', 'PH_SC2_PA1_EVENT_WE', + 'PH_SC2_PA1_FIFO_EMPTY', 'PH_SC2_PA1_FIFO_FULL', + 'PH_SC2_PA1_FPOV_WE', 'PH_SC2_PA1_LPOV_WE', 'PH_SC2_PA1_NULL_WE', + 'PH_SC2_PA2_DATA_FIFO_EOP_RD', 'PH_SC2_PA2_DATA_FIFO_RD', + 'PH_SC2_PA2_DATA_FIFO_WE', 'PH_SC2_PA2_DEALLOC_4_0_RD', + 'PH_SC2_PA2_EOPG_WE', 'PH_SC2_PA2_EOP_WE', 'PH_SC2_PA2_EVENT_WE', + 'PH_SC2_PA2_FIFO_EMPTY', 'PH_SC2_PA2_FIFO_FULL', + 'PH_SC2_PA2_FPOV_WE', 'PH_SC2_PA2_LPOV_WE', 'PH_SC2_PA2_NULL_WE', + 'PH_SC2_PA3_DATA_FIFO_EOP_RD', 'PH_SC2_PA3_DATA_FIFO_RD', + 'PH_SC2_PA3_DATA_FIFO_WE', 'PH_SC2_PA3_DEALLOC_4_0_RD', + 'PH_SC2_PA3_EOPG_WE', 'PH_SC2_PA3_EOP_WE', 'PH_SC2_PA3_EVENT_WE', + 'PH_SC2_PA3_FIFO_EMPTY', 'PH_SC2_PA3_FIFO_FULL', + 'PH_SC2_PA3_FPOV_WE', 'PH_SC2_PA3_LPOV_WE', 'PH_SC2_PA3_NULL_WE', + 'PH_SC2_PA4_DATA_FIFO_EOP_RD', 'PH_SC2_PA4_DATA_FIFO_RD', + 'PH_SC2_PA4_DATA_FIFO_WE', 'PH_SC2_PA4_DEALLOC_4_0_RD', + 'PH_SC2_PA4_EOPG_WE', 'PH_SC2_PA4_EOP_WE', 'PH_SC2_PA4_EVENT_WE', + 'PH_SC2_PA4_FIFO_EMPTY', 'PH_SC2_PA4_FIFO_FULL', + 'PH_SC2_PA4_FPOV_WE', 'PH_SC2_PA4_LPOV_WE', 'PH_SC2_PA4_NULL_WE', + 'PH_SC2_PA5_DATA_FIFO_EOP_RD', 'PH_SC2_PA5_DATA_FIFO_RD', + 'PH_SC2_PA5_DATA_FIFO_WE', 'PH_SC2_PA5_DEALLOC_4_0_RD', + 'PH_SC2_PA5_EOPG_WE', 'PH_SC2_PA5_EOP_WE', 'PH_SC2_PA5_EVENT_WE', + 'PH_SC2_PA5_FIFO_EMPTY', 'PH_SC2_PA5_FIFO_FULL', + 'PH_SC2_PA5_FPOV_WE', 'PH_SC2_PA5_LPOV_WE', 'PH_SC2_PA5_NULL_WE', + 'PH_SC2_PA6_DATA_FIFO_EOP_RD', 'PH_SC2_PA6_DATA_FIFO_RD', + 'PH_SC2_PA6_DATA_FIFO_WE', 'PH_SC2_PA6_DEALLOC_4_0_RD', + 'PH_SC2_PA6_EOPG_WE', 'PH_SC2_PA6_EOP_WE', 'PH_SC2_PA6_EVENT_WE', + 'PH_SC2_PA6_FIFO_EMPTY', 'PH_SC2_PA6_FIFO_FULL', + 'PH_SC2_PA6_FPOV_WE', 'PH_SC2_PA6_LPOV_WE', 'PH_SC2_PA6_NULL_WE', + 'PH_SC2_PA7_DATA_FIFO_EOP_RD', 'PH_SC2_PA7_DATA_FIFO_RD', + 'PH_SC2_PA7_DATA_FIFO_WE', 'PH_SC2_PA7_DEALLOC_4_0_RD', + 'PH_SC2_PA7_EOPG_WE', 'PH_SC2_PA7_EOP_WE', 'PH_SC2_PA7_EVENT_WE', + 'PH_SC2_PA7_FIFO_EMPTY', 'PH_SC2_PA7_FIFO_FULL', + 'PH_SC2_PA7_FPOV_WE', 'PH_SC2_PA7_LPOV_WE', 'PH_SC2_PA7_NULL_WE', + 'PH_SC2_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC2_SEND', + 'PH_SC2_SRPS_WINDOW_VALID', 'PH_SC3_ARB_BUSY', + 'PH_SC3_ARB_EOP_POP_SYNC_POP', 'PH_SC3_ARB_EVENT_SYNC_POP', + 'PH_SC3_ARB_PA_BUSY_SOP', 'PH_SC3_ARB_STALLED_FROM_BELOW', + 'PH_SC3_ARB_STARVED_FROM_ABOVE', + 'PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC3_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC3_BUSY_CNT_NOT_ZERO', + 'PH_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC3_CREDIT_AT_MAX', + 'PH_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC3_EOP_SYNC_WINDOW', 'PH_SC3_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC3_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC3_PA0_DATA_FIFO_EOP_RD', 'PH_SC3_PA0_DATA_FIFO_RD', + 'PH_SC3_PA0_DATA_FIFO_WE', 'PH_SC3_PA0_DEALLOC_4_0_RD', + 'PH_SC3_PA0_EOPG_WE', 'PH_SC3_PA0_EOP_WE', 'PH_SC3_PA0_EVENT_WE', + 'PH_SC3_PA0_FIFO_EMPTY', 'PH_SC3_PA0_FIFO_FULL', + 'PH_SC3_PA0_FPOV_WE', 'PH_SC3_PA0_LPOV_WE', 'PH_SC3_PA0_NULL_WE', + 'PH_SC3_PA1_DATA_FIFO_EOP_RD', 'PH_SC3_PA1_DATA_FIFO_RD', + 'PH_SC3_PA1_DATA_FIFO_WE', 'PH_SC3_PA1_DEALLOC_4_0_RD', + 'PH_SC3_PA1_EOPG_WE', 'PH_SC3_PA1_EOP_WE', 'PH_SC3_PA1_EVENT_WE', + 'PH_SC3_PA1_FIFO_EMPTY', 'PH_SC3_PA1_FIFO_FULL', + 'PH_SC3_PA1_FPOV_WE', 'PH_SC3_PA1_LPOV_WE', 'PH_SC3_PA1_NULL_WE', + 'PH_SC3_PA2_DATA_FIFO_EOP_RD', 'PH_SC3_PA2_DATA_FIFO_RD', + 'PH_SC3_PA2_DATA_FIFO_WE', 'PH_SC3_PA2_DEALLOC_4_0_RD', + 'PH_SC3_PA2_EOPG_WE', 'PH_SC3_PA2_EOP_WE', 'PH_SC3_PA2_EVENT_WE', + 'PH_SC3_PA2_FIFO_EMPTY', 'PH_SC3_PA2_FIFO_FULL', + 'PH_SC3_PA2_FPOV_WE', 'PH_SC3_PA2_LPOV_WE', 'PH_SC3_PA2_NULL_WE', + 'PH_SC3_PA3_DATA_FIFO_EOP_RD', 'PH_SC3_PA3_DATA_FIFO_RD', + 'PH_SC3_PA3_DATA_FIFO_WE', 'PH_SC3_PA3_DEALLOC_4_0_RD', + 'PH_SC3_PA3_EOPG_WE', 'PH_SC3_PA3_EOP_WE', 'PH_SC3_PA3_EVENT_WE', + 'PH_SC3_PA3_FIFO_EMPTY', 'PH_SC3_PA3_FIFO_FULL', + 'PH_SC3_PA3_FPOV_WE', 'PH_SC3_PA3_LPOV_WE', 'PH_SC3_PA3_NULL_WE', + 'PH_SC3_PA4_DATA_FIFO_EOP_RD', 'PH_SC3_PA4_DATA_FIFO_RD', + 'PH_SC3_PA4_DATA_FIFO_WE', 'PH_SC3_PA4_DEALLOC_4_0_RD', + 'PH_SC3_PA4_EOPG_WE', 'PH_SC3_PA4_EOP_WE', 'PH_SC3_PA4_EVENT_WE', + 'PH_SC3_PA4_FIFO_EMPTY', 'PH_SC3_PA4_FIFO_FULL', + 'PH_SC3_PA4_FPOV_WE', 'PH_SC3_PA4_LPOV_WE', 'PH_SC3_PA4_NULL_WE', + 'PH_SC3_PA5_DATA_FIFO_EOP_RD', 'PH_SC3_PA5_DATA_FIFO_RD', + 'PH_SC3_PA5_DATA_FIFO_WE', 'PH_SC3_PA5_DEALLOC_4_0_RD', + 'PH_SC3_PA5_EOPG_WE', 'PH_SC3_PA5_EOP_WE', 'PH_SC3_PA5_EVENT_WE', + 'PH_SC3_PA5_FIFO_EMPTY', 'PH_SC3_PA5_FIFO_FULL', + 'PH_SC3_PA5_FPOV_WE', 'PH_SC3_PA5_LPOV_WE', 'PH_SC3_PA5_NULL_WE', + 'PH_SC3_PA6_DATA_FIFO_EOP_RD', 'PH_SC3_PA6_DATA_FIFO_RD', + 'PH_SC3_PA6_DATA_FIFO_WE', 'PH_SC3_PA6_DEALLOC_4_0_RD', + 'PH_SC3_PA6_EOPG_WE', 'PH_SC3_PA6_EOP_WE', 'PH_SC3_PA6_EVENT_WE', + 'PH_SC3_PA6_FIFO_EMPTY', 'PH_SC3_PA6_FIFO_FULL', + 'PH_SC3_PA6_FPOV_WE', 'PH_SC3_PA6_LPOV_WE', 'PH_SC3_PA6_NULL_WE', + 'PH_SC3_PA7_DATA_FIFO_EOP_RD', 'PH_SC3_PA7_DATA_FIFO_RD', + 'PH_SC3_PA7_DATA_FIFO_WE', 'PH_SC3_PA7_DEALLOC_4_0_RD', + 'PH_SC3_PA7_EOPG_WE', 'PH_SC3_PA7_EOP_WE', 'PH_SC3_PA7_EVENT_WE', + 'PH_SC3_PA7_FIFO_EMPTY', 'PH_SC3_PA7_FIFO_FULL', + 'PH_SC3_PA7_FPOV_WE', 'PH_SC3_PA7_LPOV_WE', 'PH_SC3_PA7_NULL_WE', + 'PH_SC3_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC3_SEND', + 'PH_SC3_SRPS_WINDOW_VALID', 'PH_SC4_ARB_BUSY', + 'PH_SC4_ARB_EOP_POP_SYNC_POP', 'PH_SC4_ARB_EVENT_SYNC_POP', + 'PH_SC4_ARB_PA_BUSY_SOP', 'PH_SC4_ARB_STALLED_FROM_BELOW', + 'PH_SC4_ARB_STARVED_FROM_ABOVE', + 'PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC4_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC4_BUSY_CNT_NOT_ZERO', + 'PH_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC4_CREDIT_AT_MAX', + 'PH_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC4_EOP_SYNC_WINDOW', 'PH_SC4_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC4_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC4_PA0_DATA_FIFO_EOP_RD', 'PH_SC4_PA0_DATA_FIFO_RD', + 'PH_SC4_PA0_DATA_FIFO_WE', 'PH_SC4_PA0_DEALLOC_4_0_RD', + 'PH_SC4_PA0_EOPG_WE', 'PH_SC4_PA0_EOP_WE', 'PH_SC4_PA0_EVENT_WE', + 'PH_SC4_PA0_FIFO_EMPTY', 'PH_SC4_PA0_FIFO_FULL', + 'PH_SC4_PA0_FPOV_WE', 'PH_SC4_PA0_LPOV_WE', 'PH_SC4_PA0_NULL_WE', + 'PH_SC4_PA1_DATA_FIFO_EOP_RD', 'PH_SC4_PA1_DATA_FIFO_RD', + 'PH_SC4_PA1_DATA_FIFO_WE', 'PH_SC4_PA1_DEALLOC_4_0_RD', + 'PH_SC4_PA1_EOPG_WE', 'PH_SC4_PA1_EOP_WE', 'PH_SC4_PA1_EVENT_WE', + 'PH_SC4_PA1_FIFO_EMPTY', 'PH_SC4_PA1_FIFO_FULL', + 'PH_SC4_PA1_FPOV_WE', 'PH_SC4_PA1_LPOV_WE', 'PH_SC4_PA1_NULL_WE', + 'PH_SC4_PA2_DATA_FIFO_EOP_RD', 'PH_SC4_PA2_DATA_FIFO_RD', + 'PH_SC4_PA2_DATA_FIFO_WE', 'PH_SC4_PA2_DEALLOC_4_0_RD', + 'PH_SC4_PA2_EOPG_WE', 'PH_SC4_PA2_EOP_WE', 'PH_SC4_PA2_EVENT_WE', + 'PH_SC4_PA2_FIFO_EMPTY', 'PH_SC4_PA2_FIFO_FULL', + 'PH_SC4_PA2_FPOV_WE', 'PH_SC4_PA2_LPOV_WE', 'PH_SC4_PA2_NULL_WE', + 'PH_SC4_PA3_DATA_FIFO_EOP_RD', 'PH_SC4_PA3_DATA_FIFO_RD', + 'PH_SC4_PA3_DATA_FIFO_WE', 'PH_SC4_PA3_DEALLOC_4_0_RD', + 'PH_SC4_PA3_EOPG_WE', 'PH_SC4_PA3_EOP_WE', 'PH_SC4_PA3_EVENT_WE', + 'PH_SC4_PA3_FIFO_EMPTY', 'PH_SC4_PA3_FIFO_FULL', + 'PH_SC4_PA3_FPOV_WE', 'PH_SC4_PA3_LPOV_WE', 'PH_SC4_PA3_NULL_WE', + 'PH_SC4_PA4_DATA_FIFO_EOP_RD', 'PH_SC4_PA4_DATA_FIFO_RD', + 'PH_SC4_PA4_DATA_FIFO_WE', 'PH_SC4_PA4_DEALLOC_4_0_RD', + 'PH_SC4_PA4_EOPG_WE', 'PH_SC4_PA4_EOP_WE', 'PH_SC4_PA4_EVENT_WE', + 'PH_SC4_PA4_FIFO_EMPTY', 'PH_SC4_PA4_FIFO_FULL', + 'PH_SC4_PA4_FPOV_WE', 'PH_SC4_PA4_LPOV_WE', 'PH_SC4_PA4_NULL_WE', + 'PH_SC4_PA5_DATA_FIFO_EOP_RD', 'PH_SC4_PA5_DATA_FIFO_RD', + 'PH_SC4_PA5_DATA_FIFO_WE', 'PH_SC4_PA5_DEALLOC_4_0_RD', + 'PH_SC4_PA5_EOPG_WE', 'PH_SC4_PA5_EOP_WE', 'PH_SC4_PA5_EVENT_WE', + 'PH_SC4_PA5_FIFO_EMPTY', 'PH_SC4_PA5_FIFO_FULL', + 'PH_SC4_PA5_FPOV_WE', 'PH_SC4_PA5_LPOV_WE', 'PH_SC4_PA5_NULL_WE', + 'PH_SC4_PA6_DATA_FIFO_EOP_RD', 'PH_SC4_PA6_DATA_FIFO_RD', + 'PH_SC4_PA6_DATA_FIFO_WE', 'PH_SC4_PA6_DEALLOC_4_0_RD', + 'PH_SC4_PA6_EOPG_WE', 'PH_SC4_PA6_EOP_WE', 'PH_SC4_PA6_EVENT_WE', + 'PH_SC4_PA6_FIFO_EMPTY', 'PH_SC4_PA6_FIFO_FULL', + 'PH_SC4_PA6_FPOV_WE', 'PH_SC4_PA6_LPOV_WE', 'PH_SC4_PA6_NULL_WE', + 'PH_SC4_PA7_DATA_FIFO_EOP_RD', 'PH_SC4_PA7_DATA_FIFO_RD', + 'PH_SC4_PA7_DATA_FIFO_WE', 'PH_SC4_PA7_DEALLOC_4_0_RD', + 'PH_SC4_PA7_EOPG_WE', 'PH_SC4_PA7_EOP_WE', 'PH_SC4_PA7_EVENT_WE', + 'PH_SC4_PA7_FIFO_EMPTY', 'PH_SC4_PA7_FIFO_FULL', + 'PH_SC4_PA7_FPOV_WE', 'PH_SC4_PA7_LPOV_WE', 'PH_SC4_PA7_NULL_WE', + 'PH_SC4_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC4_SEND', + 'PH_SC4_SRPS_WINDOW_VALID', 'PH_SC5_ARB_BUSY', + 'PH_SC5_ARB_EOP_POP_SYNC_POP', 'PH_SC5_ARB_EVENT_SYNC_POP', + 'PH_SC5_ARB_PA_BUSY_SOP', 'PH_SC5_ARB_STALLED_FROM_BELOW', + 'PH_SC5_ARB_STARVED_FROM_ABOVE', + 'PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC5_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC5_BUSY_CNT_NOT_ZERO', + 'PH_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC5_CREDIT_AT_MAX', + 'PH_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC5_EOP_SYNC_WINDOW', 'PH_SC5_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC5_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC5_PA0_DATA_FIFO_EOP_RD', 'PH_SC5_PA0_DATA_FIFO_RD', + 'PH_SC5_PA0_DATA_FIFO_WE', 'PH_SC5_PA0_DEALLOC_4_0_RD', + 'PH_SC5_PA0_EOPG_WE', 'PH_SC5_PA0_EOP_WE', 'PH_SC5_PA0_EVENT_WE', + 'PH_SC5_PA0_FIFO_EMPTY', 'PH_SC5_PA0_FIFO_FULL', + 'PH_SC5_PA0_FPOV_WE', 'PH_SC5_PA0_LPOV_WE', 'PH_SC5_PA0_NULL_WE', + 'PH_SC5_PA1_DATA_FIFO_EOP_RD', 'PH_SC5_PA1_DATA_FIFO_RD', + 'PH_SC5_PA1_DATA_FIFO_WE', 'PH_SC5_PA1_DEALLOC_4_0_RD', + 'PH_SC5_PA1_EOPG_WE', 'PH_SC5_PA1_EOP_WE', 'PH_SC5_PA1_EVENT_WE', + 'PH_SC5_PA1_FIFO_EMPTY', 'PH_SC5_PA1_FIFO_FULL', + 'PH_SC5_PA1_FPOV_WE', 'PH_SC5_PA1_LPOV_WE', 'PH_SC5_PA1_NULL_WE', + 'PH_SC5_PA2_DATA_FIFO_EOP_RD', 'PH_SC5_PA2_DATA_FIFO_RD', + 'PH_SC5_PA2_DATA_FIFO_WE', 'PH_SC5_PA2_DEALLOC_4_0_RD', + 'PH_SC5_PA2_EOPG_WE', 'PH_SC5_PA2_EOP_WE', 'PH_SC5_PA2_EVENT_WE', + 'PH_SC5_PA2_FIFO_EMPTY', 'PH_SC5_PA2_FIFO_FULL', + 'PH_SC5_PA2_FPOV_WE', 'PH_SC5_PA2_LPOV_WE', 'PH_SC5_PA2_NULL_WE', + 'PH_SC5_PA3_DATA_FIFO_EOP_RD', 'PH_SC5_PA3_DATA_FIFO_RD', + 'PH_SC5_PA3_DATA_FIFO_WE', 'PH_SC5_PA3_DEALLOC_4_0_RD', + 'PH_SC5_PA3_EOPG_WE', 'PH_SC5_PA3_EOP_WE', 'PH_SC5_PA3_EVENT_WE', + 'PH_SC5_PA3_FIFO_EMPTY', 'PH_SC5_PA3_FIFO_FULL', + 'PH_SC5_PA3_FPOV_WE', 'PH_SC5_PA3_LPOV_WE', 'PH_SC5_PA3_NULL_WE', + 'PH_SC5_PA4_DATA_FIFO_EOP_RD', 'PH_SC5_PA4_DATA_FIFO_RD', + 'PH_SC5_PA4_DATA_FIFO_WE', 'PH_SC5_PA4_DEALLOC_4_0_RD', + 'PH_SC5_PA4_EOPG_WE', 'PH_SC5_PA4_EOP_WE', 'PH_SC5_PA4_EVENT_WE', + 'PH_SC5_PA4_FIFO_EMPTY', 'PH_SC5_PA4_FIFO_FULL', + 'PH_SC5_PA4_FPOV_WE', 'PH_SC5_PA4_LPOV_WE', 'PH_SC5_PA4_NULL_WE', + 'PH_SC5_PA5_DATA_FIFO_EOP_RD', 'PH_SC5_PA5_DATA_FIFO_RD', + 'PH_SC5_PA5_DATA_FIFO_WE', 'PH_SC5_PA5_DEALLOC_4_0_RD', + 'PH_SC5_PA5_EOPG_WE', 'PH_SC5_PA5_EOP_WE', 'PH_SC5_PA5_EVENT_WE', + 'PH_SC5_PA5_FIFO_EMPTY', 'PH_SC5_PA5_FIFO_FULL', + 'PH_SC5_PA5_FPOV_WE', 'PH_SC5_PA5_LPOV_WE', 'PH_SC5_PA5_NULL_WE', + 'PH_SC5_PA6_DATA_FIFO_EOP_RD', 'PH_SC5_PA6_DATA_FIFO_RD', + 'PH_SC5_PA6_DATA_FIFO_WE', 'PH_SC5_PA6_DEALLOC_4_0_RD', + 'PH_SC5_PA6_EOPG_WE', 'PH_SC5_PA6_EOP_WE', 'PH_SC5_PA6_EVENT_WE', + 'PH_SC5_PA6_FIFO_EMPTY', 'PH_SC5_PA6_FIFO_FULL', + 'PH_SC5_PA6_FPOV_WE', 'PH_SC5_PA6_LPOV_WE', 'PH_SC5_PA6_NULL_WE', + 'PH_SC5_PA7_DATA_FIFO_EOP_RD', 'PH_SC5_PA7_DATA_FIFO_RD', + 'PH_SC5_PA7_DATA_FIFO_WE', 'PH_SC5_PA7_DEALLOC_4_0_RD', + 'PH_SC5_PA7_EOPG_WE', 'PH_SC5_PA7_EOP_WE', 'PH_SC5_PA7_EVENT_WE', + 'PH_SC5_PA7_FIFO_EMPTY', 'PH_SC5_PA7_FIFO_FULL', + 'PH_SC5_PA7_FPOV_WE', 'PH_SC5_PA7_LPOV_WE', 'PH_SC5_PA7_NULL_WE', + 'PH_SC5_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC5_SEND', + 'PH_SC5_SRPS_WINDOW_VALID', 'PH_SC6_ARB_BUSY', + 'PH_SC6_ARB_EOP_POP_SYNC_POP', 'PH_SC6_ARB_EVENT_SYNC_POP', + 'PH_SC6_ARB_PA_BUSY_SOP', 'PH_SC6_ARB_STALLED_FROM_BELOW', + 'PH_SC6_ARB_STARVED_FROM_ABOVE', + 'PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC6_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC6_BUSY_CNT_NOT_ZERO', + 'PH_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC6_CREDIT_AT_MAX', + 'PH_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC6_EOP_SYNC_WINDOW', 'PH_SC6_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC6_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC6_PA0_DATA_FIFO_EOP_RD', 'PH_SC6_PA0_DATA_FIFO_RD', + 'PH_SC6_PA0_DATA_FIFO_WE', 'PH_SC6_PA0_DEALLOC_4_0_RD', + 'PH_SC6_PA0_EOPG_WE', 'PH_SC6_PA0_EOP_WE', 'PH_SC6_PA0_EVENT_WE', + 'PH_SC6_PA0_FIFO_EMPTY', 'PH_SC6_PA0_FIFO_FULL', + 'PH_SC6_PA0_FPOV_WE', 'PH_SC6_PA0_LPOV_WE', 'PH_SC6_PA0_NULL_WE', + 'PH_SC6_PA1_DATA_FIFO_EOP_RD', 'PH_SC6_PA1_DATA_FIFO_RD', + 'PH_SC6_PA1_DATA_FIFO_WE', 'PH_SC6_PA1_DEALLOC_4_0_RD', + 'PH_SC6_PA1_EOPG_WE', 'PH_SC6_PA1_EOP_WE', 'PH_SC6_PA1_EVENT_WE', + 'PH_SC6_PA1_FIFO_EMPTY', 'PH_SC6_PA1_FIFO_FULL', + 'PH_SC6_PA1_FPOV_WE', 'PH_SC6_PA1_LPOV_WE', 'PH_SC6_PA1_NULL_WE', + 'PH_SC6_PA2_DATA_FIFO_EOP_RD', 'PH_SC6_PA2_DATA_FIFO_RD', + 'PH_SC6_PA2_DATA_FIFO_WE', 'PH_SC6_PA2_DEALLOC_4_0_RD', + 'PH_SC6_PA2_EOPG_WE', 'PH_SC6_PA2_EOP_WE', 'PH_SC6_PA2_EVENT_WE', + 'PH_SC6_PA2_FIFO_EMPTY', 'PH_SC6_PA2_FIFO_FULL', + 'PH_SC6_PA2_FPOV_WE', 'PH_SC6_PA2_LPOV_WE', 'PH_SC6_PA2_NULL_WE', + 'PH_SC6_PA3_DATA_FIFO_EOP_RD', 'PH_SC6_PA3_DATA_FIFO_RD', + 'PH_SC6_PA3_DATA_FIFO_WE', 'PH_SC6_PA3_DEALLOC_4_0_RD', + 'PH_SC6_PA3_EOPG_WE', 'PH_SC6_PA3_EOP_WE', 'PH_SC6_PA3_EVENT_WE', + 'PH_SC6_PA3_FIFO_EMPTY', 'PH_SC6_PA3_FIFO_FULL', + 'PH_SC6_PA3_FPOV_WE', 'PH_SC6_PA3_LPOV_WE', 'PH_SC6_PA3_NULL_WE', + 'PH_SC6_PA4_DATA_FIFO_EOP_RD', 'PH_SC6_PA4_DATA_FIFO_RD', + 'PH_SC6_PA4_DATA_FIFO_WE', 'PH_SC6_PA4_DEALLOC_4_0_RD', + 'PH_SC6_PA4_EOPG_WE', 'PH_SC6_PA4_EOP_WE', 'PH_SC6_PA4_EVENT_WE', + 'PH_SC6_PA4_FIFO_EMPTY', 'PH_SC6_PA4_FIFO_FULL', + 'PH_SC6_PA4_FPOV_WE', 'PH_SC6_PA4_LPOV_WE', 'PH_SC6_PA4_NULL_WE', + 'PH_SC6_PA5_DATA_FIFO_EOP_RD', 'PH_SC6_PA5_DATA_FIFO_RD', + 'PH_SC6_PA5_DATA_FIFO_WE', 'PH_SC6_PA5_DEALLOC_4_0_RD', + 'PH_SC6_PA5_EOPG_WE', 'PH_SC6_PA5_EOP_WE', 'PH_SC6_PA5_EVENT_WE', + 'PH_SC6_PA5_FIFO_EMPTY', 'PH_SC6_PA5_FIFO_FULL', + 'PH_SC6_PA5_FPOV_WE', 'PH_SC6_PA5_LPOV_WE', 'PH_SC6_PA5_NULL_WE', + 'PH_SC6_PA6_DATA_FIFO_EOP_RD', 'PH_SC6_PA6_DATA_FIFO_RD', + 'PH_SC6_PA6_DATA_FIFO_WE', 'PH_SC6_PA6_DEALLOC_4_0_RD', + 'PH_SC6_PA6_EOPG_WE', 'PH_SC6_PA6_EOP_WE', 'PH_SC6_PA6_EVENT_WE', + 'PH_SC6_PA6_FIFO_EMPTY', 'PH_SC6_PA6_FIFO_FULL', + 'PH_SC6_PA6_FPOV_WE', 'PH_SC6_PA6_LPOV_WE', 'PH_SC6_PA6_NULL_WE', + 'PH_SC6_PA7_DATA_FIFO_EOP_RD', 'PH_SC6_PA7_DATA_FIFO_RD', + 'PH_SC6_PA7_DATA_FIFO_WE', 'PH_SC6_PA7_DEALLOC_4_0_RD', + 'PH_SC6_PA7_EOPG_WE', 'PH_SC6_PA7_EOP_WE', 'PH_SC6_PA7_EVENT_WE', + 'PH_SC6_PA7_FIFO_EMPTY', 'PH_SC6_PA7_FIFO_FULL', + 'PH_SC6_PA7_FPOV_WE', 'PH_SC6_PA7_LPOV_WE', 'PH_SC6_PA7_NULL_WE', + 'PH_SC6_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC6_SEND', + 'PH_SC6_SRPS_WINDOW_VALID', 'PH_SC7_ARB_BUSY', + 'PH_SC7_ARB_EOP_POP_SYNC_POP', 'PH_SC7_ARB_EVENT_SYNC_POP', + 'PH_SC7_ARB_PA_BUSY_SOP', 'PH_SC7_ARB_STALLED_FROM_BELOW', + 'PH_SC7_ARB_STARVED_FROM_ABOVE', + 'PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_SC7_ARB_XFC_ONLY_PRIM_CYCLES', 'PH_SC7_BUSY_CNT_NOT_ZERO', + 'PH_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', 'PH_SC7_CREDIT_AT_MAX', + 'PH_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_SC7_EOP_SYNC_WINDOW', 'PH_SC7_GFX_PIPE0_TO_1_TRANSITION', + 'PH_SC7_GFX_PIPE1_TO_0_TRANSITION', + 'PH_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_SC7_PA0_DATA_FIFO_EOP_RD', 'PH_SC7_PA0_DATA_FIFO_RD', + 'PH_SC7_PA0_DATA_FIFO_WE', 'PH_SC7_PA0_DEALLOC_4_0_RD', + 'PH_SC7_PA0_EOPG_WE', 'PH_SC7_PA0_EOP_WE', 'PH_SC7_PA0_EVENT_WE', + 'PH_SC7_PA0_FIFO_EMPTY', 'PH_SC7_PA0_FIFO_FULL', + 'PH_SC7_PA0_FPOV_WE', 'PH_SC7_PA0_LPOV_WE', 'PH_SC7_PA0_NULL_WE', + 'PH_SC7_PA1_DATA_FIFO_EOP_RD', 'PH_SC7_PA1_DATA_FIFO_RD', + 'PH_SC7_PA1_DATA_FIFO_WE', 'PH_SC7_PA1_DEALLOC_4_0_RD', + 'PH_SC7_PA1_EOPG_WE', 'PH_SC7_PA1_EOP_WE', 'PH_SC7_PA1_EVENT_WE', + 'PH_SC7_PA1_FIFO_EMPTY', 'PH_SC7_PA1_FIFO_FULL', + 'PH_SC7_PA1_FPOV_WE', 'PH_SC7_PA1_LPOV_WE', 'PH_SC7_PA1_NULL_WE', + 'PH_SC7_PA2_DATA_FIFO_EOP_RD', 'PH_SC7_PA2_DATA_FIFO_RD', + 'PH_SC7_PA2_DATA_FIFO_WE', 'PH_SC7_PA2_DEALLOC_4_0_RD', + 'PH_SC7_PA2_EOPG_WE', 'PH_SC7_PA2_EOP_WE', 'PH_SC7_PA2_EVENT_WE', + 'PH_SC7_PA2_FIFO_EMPTY', 'PH_SC7_PA2_FIFO_FULL', + 'PH_SC7_PA2_FPOV_WE', 'PH_SC7_PA2_LPOV_WE', 'PH_SC7_PA2_NULL_WE', + 'PH_SC7_PA3_DATA_FIFO_EOP_RD', 'PH_SC7_PA3_DATA_FIFO_RD', + 'PH_SC7_PA3_DATA_FIFO_WE', 'PH_SC7_PA3_DEALLOC_4_0_RD', + 'PH_SC7_PA3_EOPG_WE', 'PH_SC7_PA3_EOP_WE', 'PH_SC7_PA3_EVENT_WE', + 'PH_SC7_PA3_FIFO_EMPTY', 'PH_SC7_PA3_FIFO_FULL', + 'PH_SC7_PA3_FPOV_WE', 'PH_SC7_PA3_LPOV_WE', 'PH_SC7_PA3_NULL_WE', + 'PH_SC7_PA4_DATA_FIFO_EOP_RD', 'PH_SC7_PA4_DATA_FIFO_RD', + 'PH_SC7_PA4_DATA_FIFO_WE', 'PH_SC7_PA4_DEALLOC_4_0_RD', + 'PH_SC7_PA4_EOPG_WE', 'PH_SC7_PA4_EOP_WE', 'PH_SC7_PA4_EVENT_WE', + 'PH_SC7_PA4_FIFO_EMPTY', 'PH_SC7_PA4_FIFO_FULL', + 'PH_SC7_PA4_FPOV_WE', 'PH_SC7_PA4_LPOV_WE', 'PH_SC7_PA4_NULL_WE', + 'PH_SC7_PA5_DATA_FIFO_EOP_RD', 'PH_SC7_PA5_DATA_FIFO_RD', + 'PH_SC7_PA5_DATA_FIFO_WE', 'PH_SC7_PA5_DEALLOC_4_0_RD', + 'PH_SC7_PA5_EOPG_WE', 'PH_SC7_PA5_EOP_WE', 'PH_SC7_PA5_EVENT_WE', + 'PH_SC7_PA5_FIFO_EMPTY', 'PH_SC7_PA5_FIFO_FULL', + 'PH_SC7_PA5_FPOV_WE', 'PH_SC7_PA5_LPOV_WE', 'PH_SC7_PA5_NULL_WE', + 'PH_SC7_PA6_DATA_FIFO_EOP_RD', 'PH_SC7_PA6_DATA_FIFO_RD', + 'PH_SC7_PA6_DATA_FIFO_WE', 'PH_SC7_PA6_DEALLOC_4_0_RD', + 'PH_SC7_PA6_EOPG_WE', 'PH_SC7_PA6_EOP_WE', 'PH_SC7_PA6_EVENT_WE', + 'PH_SC7_PA6_FIFO_EMPTY', 'PH_SC7_PA6_FIFO_FULL', + 'PH_SC7_PA6_FPOV_WE', 'PH_SC7_PA6_LPOV_WE', 'PH_SC7_PA6_NULL_WE', + 'PH_SC7_PA7_DATA_FIFO_EOP_RD', 'PH_SC7_PA7_DATA_FIFO_RD', + 'PH_SC7_PA7_DATA_FIFO_WE', 'PH_SC7_PA7_DEALLOC_4_0_RD', + 'PH_SC7_PA7_EOPG_WE', 'PH_SC7_PA7_EOP_WE', 'PH_SC7_PA7_EVENT_WE', + 'PH_SC7_PA7_FIFO_EMPTY', 'PH_SC7_PA7_FIFO_FULL', + 'PH_SC7_PA7_FPOV_WE', 'PH_SC7_PA7_LPOV_WE', 'PH_SC7_PA7_NULL_WE', + 'PH_SC7_PS_ENG_MULTICYCLE_BUBBLE', 'PH_SC7_SEND', + 'PH_SC7_SRPS_WINDOW_VALID', 'PIPELINESTAT_START', + 'PIPELINESTAT_STOP', 'PIPE_ALIGNED', 'PIPE_ALIGNED_SURF', + 'PIPE_CONFIG', 'PIPE_ID0', 'PIPE_ID1', 'PIPE_ID2', 'PIPE_ID3', + 'PIPE_INTERLEAVE', 'PIPE_INTERLEAVE_1KB', 'PIPE_INTERLEAVE_256B', + 'PIPE_INTERLEAVE_512B', 'PIPE_PHYPLL_PIXEL_RATE_SOURCE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF', + 'PIPE_PIXEL_RATE_PLL_SOURCE', + 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', + 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', 'PIPE_PIXEL_RATE_SOURCE', + 'PIPE_PIXEL_RATE_SOURCE_P0PLL', 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 'PIPE_PIXEL_RATE_SOURCE_P2PLL', 'PIPE_UNALIGNED_SURF', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE', 'PIXEL_DEPTH_10BPC', + 'PIXEL_DEPTH_8BPC', 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 'PIXEL_PIPE_OCCLUSION_COUNT_1', 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 'PIXEL_PIPE_OCCLUSION_COUNT_3', 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', 'PIXEL_PIPE_STAT_CONTROL', + 'PIXEL_PIPE_STAT_DUMP', 'PIXEL_PIPE_STAT_RESET', + 'PIXEL_PIPE_STRIDE_128_BITS', 'PIXEL_PIPE_STRIDE_256_BITS', + 'PIXEL_PIPE_STRIDE_32_BITS', 'PIXEL_PIPE_STRIDE_64_BITS', + 'PIX_DYNAMIC_EXPANSION', 'PIX_EXPAND_MODE', 'PIX_ZERO_EXPANSION', + 'PLL_CFG_IF_SOFT_RESET', 'PLL_CFG_IF_SOFT_RESET_FORCE', + 'PLL_CFG_IF_SOFT_RESET_NOOP', 'PM_ASSERT_RESET', + 'PM_ASSERT_RESET_0', 'PM_ASSERT_RESET_1', 'POINTLIST', + 'POST_CLAMP_TF0', 'POST_CLAMP_TF1', 'POWER_STATE_ENUM', + 'POWER_STATE_ENUM_DS', 'POWER_STATE_ENUM_LS', + 'POWER_STATE_ENUM_ON', 'POWER_STATE_ENUM_SD', 'PRE_CLAMP_TF0', + 'PRE_CLAMP_TF1', 'PROG_SEQ', 'PSLC_ASAP', 'PSLC_AUTO', + 'PSLC_COUNTDOWN', 'PSLC_ON_HANG_ONLY', 'PS_DONE', + 'PS_PARTIAL_FLUSH', 'PTE_ROW_HEIGHT_LINEAR', + 'PTE_ROW_HEIGHT_LINEAR_1024L', 'PTE_ROW_HEIGHT_LINEAR_128L', + 'PTE_ROW_HEIGHT_LINEAR_16L', 'PTE_ROW_HEIGHT_LINEAR_256L', + 'PTE_ROW_HEIGHT_LINEAR_32L', 'PTE_ROW_HEIGHT_LINEAR_512L', + 'PTE_ROW_HEIGHT_LINEAR_64L', 'PTE_ROW_HEIGHT_LINEAR_8L', + 'PerfCounter_Vals', 'PipeConfig', 'PipeInterleaveSize', + 'PipeTiling', 'PixelPipeCounterId', 'PixelPipeStride', 'PkrMap', + 'PkrXsel', 'PkrXsel2', 'PkrYsel', 'QuadExportFormat', + 'QuadExportFormatOld', 'RAMA_ACCESS', 'RAMB_ACCESS', 'RANGE_00', + 'RANGE_FF', 'RASTER_CONFIG_PKR_MAP_0', 'RASTER_CONFIG_PKR_MAP_1', + 'RASTER_CONFIG_PKR_MAP_2', 'RASTER_CONFIG_PKR_MAP_3', + 'RASTER_CONFIG_PKR_XSEL2_0', 'RASTER_CONFIG_PKR_XSEL2_1', + 'RASTER_CONFIG_PKR_XSEL2_2', 'RASTER_CONFIG_PKR_XSEL2_3', + 'RASTER_CONFIG_PKR_XSEL_0', 'RASTER_CONFIG_PKR_XSEL_1', + 'RASTER_CONFIG_PKR_XSEL_2', 'RASTER_CONFIG_PKR_XSEL_3', + 'RASTER_CONFIG_PKR_YSEL_0', 'RASTER_CONFIG_PKR_YSEL_1', + 'RASTER_CONFIG_PKR_YSEL_2', 'RASTER_CONFIG_PKR_YSEL_3', + 'RASTER_CONFIG_RB_MAP_0', 'RASTER_CONFIG_RB_MAP_1', + 'RASTER_CONFIG_RB_MAP_2', 'RASTER_CONFIG_RB_MAP_3', + 'RASTER_CONFIG_RB_XSEL2_0', 'RASTER_CONFIG_RB_XSEL2_1', + 'RASTER_CONFIG_RB_XSEL2_2', 'RASTER_CONFIG_RB_XSEL2_3', + 'RASTER_CONFIG_RB_XSEL_0', 'RASTER_CONFIG_RB_XSEL_1', + 'RASTER_CONFIG_RB_YSEL_0', 'RASTER_CONFIG_RB_YSEL_1', + 'RASTER_CONFIG_SC_MAP_0', 'RASTER_CONFIG_SC_MAP_1', + 'RASTER_CONFIG_SC_MAP_2', 'RASTER_CONFIG_SC_MAP_3', + 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', 'RASTER_CONFIG_SE_MAP_0', + 'RASTER_CONFIG_SE_MAP_1', 'RASTER_CONFIG_SE_MAP_2', + 'RASTER_CONFIG_SE_MAP_3', 'RASTER_CONFIG_SE_PAIR_MAP_0', + 'RASTER_CONFIG_SE_PAIR_MAP_1', 'RASTER_CONFIG_SE_PAIR_MAP_2', + 'RASTER_CONFIG_SE_PAIR_MAP_3', + 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', 'RAW', 'RB_ALIGNED', + 'RB_ALIGNED_META_SURF', 'RB_UNALIGNED_META_SURF', + 'RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_BYPASS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_CLOCK_ON', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_GATE_DIS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SYMCLK_DIV2_TX_EN', + 'RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET', + 'RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET', + 'RDPCSTX_CNTL_RDPCS_TX_FIFO_EN', + 'RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN', + 'RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK', + 'RDPCSTX_MEM_POWER_CTRL2_RDPCS_MEM_POWER_CTRL_POFF', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE', + 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE', + 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE', + 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV', + 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV', + 'RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH', + 'RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE', + 'RDPCS_CBUS_SOFT_RESET_DISABLE', 'RDPCS_CBUS_SOFT_RESET_ENABLE', + 'RDPCS_DPALT_4LANE_TOGGLE_2LANE', + 'RDPCS_DPALT_4LANE_TOGGLE_4LANE', + 'RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 'RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_DISABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_ENABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE', + 'RDPCS_EXT_REFCLK_DISABLE', 'RDPCS_EXT_REFCLK_ENABLE', + 'RDPCS_EXT_REFCLK_EN_DISABLE', 'RDPCS_EXT_REFCLK_EN_ENABLE', + 'RDPCS_MEM_POWER_CTRL_POFF_FOR_NO_PERIPHERY', + 'RDPCS_MEM_POWER_CTRL_POFF_FOR_RM3', + 'RDPCS_MEM_POWER_CTRL_POFF_FOR_SD', + 'RDPCS_MEM_POWER_CTRL_POFF_FOR_STANDARD', + 'RDPCS_MEM_PWR_DEEP_SLEEP', 'RDPCS_MEM_PWR_LIGHT_SLEEP', + 'RDPCS_MEM_PWR_NO_FORCE', 'RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 'RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 'RDPCS_MEM_PWR_PWR_STATE_ON', 'RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN', + 'RDPCS_MEM_PWR_SHUT_DOWN', 'RDPCS_PHY_CR_MUX_SEL_FOR_DC', + 'RDPCS_PHY_CR_MUX_SEL_FOR_USB', 'RDPCS_PHY_CR_PARA_SEL_CR', + 'RDPCS_PHY_CR_PARA_SEL_JTAG', 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8', + 'RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT', + 'RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT', 'RDPCS_PHY_DP_TX_RATE', + 'RDPCS_PHY_DP_TX_RATE_DIV2', 'RDPCS_PHY_DP_TX_RATE_DIV4', + 'RDPCS_PHY_DP_TX_TERM_CTRL_40', 'RDPCS_PHY_DP_TX_TERM_CTRL_42', + 'RDPCS_PHY_DP_TX_TERM_CTRL_44', 'RDPCS_PHY_DP_TX_TERM_CTRL_46', + 'RDPCS_PHY_DP_TX_TERM_CTRL_48', 'RDPCS_PHY_DP_TX_TERM_CTRL_50', + 'RDPCS_PHY_DP_TX_TERM_CTRL_52', 'RDPCS_PHY_DP_TX_TERM_CTRL_54', + 'RDPCS_PHY_DP_TX_WIDTH_10', 'RDPCS_PHY_DP_TX_WIDTH_16', + 'RDPCS_PHY_DP_TX_WIDTH_20', 'RDPCS_PHY_DP_TX_WIDTH_8', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', + 'RDPCS_PHY_REF_RANGE_0', 'RDPCS_PHY_REF_RANGE_1', + 'RDPCS_PHY_REF_RANGE_2', 'RDPCS_PHY_REF_RANGE_3', + 'RDPCS_PHY_REF_RANGE_4', 'RDPCS_PHY_REF_RANGE_5', + 'RDPCS_PHY_REF_RANGE_6', 'RDPCS_PHY_REF_RANGE_7', + 'RDPCS_REG_FIFO_ERROR_MASK_DISABLE', + 'RDPCS_REG_FIFO_ERROR_MASK_ENABLE', 'RDPCS_SRAMCLK_BYPASS', + 'RDPCS_SRAMCLK_DISABLE', 'RDPCS_SRAMCLK_ENABLE', + 'RDPCS_SRAMCLK_GATE_DISABLE', 'RDPCS_SRAMCLK_GATE_ENABLE', + 'RDPCS_SRAMCLK_NOT_BYPASS', 'RDPCS_SRAM_EXT_LD_DONE', + 'RDPCS_SRAM_EXT_LD_NOT_DONE', 'RDPCS_SRAM_INIT_DONE', + 'RDPCS_SRAM_INIT_NOT_DONE', 'RDPCS_SRAM_SRAM_RESET_DISABLE', + 'RDPCS_SYMCLK_DIV2_CLOCK_OFF', 'RDPCS_SYMCLK_DIV2_CLOCK_ON', + 'RDPCS_SYMCLK_DIV2_DISABLE', 'RDPCS_SYMCLK_DIV2_ENABLE', + 'RDPCS_SYMCLK_DIV2_GATE_DISABLE', 'RDPCS_SYMCLK_DIV2_GATE_ENABLE', + 'RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF', 'RDPCS_SYMCLK_SRAMCLK_CLOCK_ON', + 'RDPCS_TEST_CLK_SEL', 'RDPCS_TEST_CLK_SEL_CFGCLK', + 'RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_EXT_CR_CLK', + 'RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 'RDPCS_TEST_CLK_SEL_NONE', 'RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 'RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk', 'RDPCS_TEST_CLK_SEL_SRAMCLK', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 'RDPCS_TEST_CLK_SEL_dtb_out0', 'RDPCS_TEST_CLK_SEL_dtb_out1', + 'RDPCS_TX_FIFO_DISABLE', 'RDPCS_TX_FIFO_ENABLE', + 'RDPCS_TX_FIFO_ERROR_MASK_DISABLE', + 'RDPCS_TX_FIFO_ERROR_MASK_ENABLE', 'RDPCS_TX_FIFO_LANE_DISABLE', + 'RDPCS_TX_FIFO_LANE_ENABLE', 'RDPCS_TX_SOFT_RESET_DISABLE', + 'RDPCS_TX_SOFT_RESET_ENABLE', + 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE', + 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE', 'READ_256_BITS', + 'READ_512_BITS', 'READ_SEQ', 'RECTLIST', 'REFCLK_CLOCK_EN', + 'REFCLK_CLOCK_EN_ALLOW_SRC_SEL', 'REFCLK_CLOCK_EN_XTALIN_CLK', + 'REFCLK_SRC_SEL', 'REFCLK_SRC_SEL_CPL_REFCLK', + 'REFCLK_SRC_SEL_PCIE_REFCLK', 'REFER_TO_DP_SOF', + 'REFER_TO_OTG_SOF', 'REF_ALWAYS', 'REF_EQUAL', 'REF_GEQUAL', + 'REF_GREATER', 'REF_LEQUAL', 'REF_LESS', 'REF_NEVER', + 'REF_NOTEQUAL', 'REG_UNALLOCATED_ADDR_READ', + 'REG_UNALLOCATED_ADDR_WRITE', 'REG_VIRTUAL_READ', + 'REG_VIRTUAL_WRITE', 'RESERVED_60', 'RESERVED_61', 'RESERVED_62', + 'RESERVED_63', 'RESERVED_88', 'RESERVED_89', 'RESERVED_90', + 'RESERVED_91', 'RESERVED_ES', 'RESERVED_LS', 'RESERVED_RDPOLICY', + 'RESERVED_VS', 'RESET_TO_LOWEST_VGT', 'RESET_VTX_CNT', 'RE_Z', + 'RGB111110_FIX', 'RGB111110_FLOAT', 'RGB565', 'RGBA1010102', + 'RGBA16161616_10LSB', 'RGBA16161616_10MSB', 'RGBA16161616_12LSB', + 'RGBA16161616_12MSB', 'RGBA16161616_FLOAT', 'RGBA16161616_SNORM', + 'RGBA16161616_UNORM', 'RGBA4444', 'RGBA5551', 'RGBA8888', + 'RIGHT_EYE', 'RINGID0', 'RINGID1', 'RINGID2', 'RINGID3', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RMIPerfSel', 'RMI_CID', 'RMI_CID_CC', 'RMI_CID_CM', 'RMI_CID_DC', + 'RMI_CID_FC', 'RMI_CID_S', 'RMI_CID_TILE', 'RMI_CID_Z', + 'RMI_CID_ZPCPSD', 'RMI_PERF_SEL_BUSY', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3', + 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 'RMI_PERF_SEL_DYN_CLK_RB_VLD', 'RMI_PERF_SEL_EVENT_SEND', + 'RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ', + 'RMI_PERF_SEL_LAT_FIFO_FULL', + 'RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ', + 'RMI_PERF_SEL_LAT_FIFO_NUM_USED', + 'RMI_PERF_SEL_LEVEL_ADD_RMI_TO_UTC', + 'RMI_PERF_SEL_LEVEL_ADD_UTCL1_TO_UTCL2', 'RMI_PERF_SEL_NONE', + 'RMI_PERF_SEL_PERF_WINDOW', 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTR', + 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB', + 'RMI_PERF_SEL_POP_DEMUX_RTS_RTR', + 'RMI_PERF_SEL_POP_DEMUX_RTS_RTRB', + 'RMI_PERF_SEL_POP_XNACK_RTSB_RTR', + 'RMI_PERF_SEL_POP_XNACK_RTSB_RTRB', + 'RMI_PERF_SEL_POP_XNACK_RTS_RTR', + 'RMI_PERF_SEL_POP_XNACK_RTS_RTRB', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB', + 'RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_VMID_BYPASS', + 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB', + 'RMI_PERF_SEL_PRT_FIFO_BUSY', 'RMI_PERF_SEL_PRT_FIFO_NUM_USED', + 'RMI_PERF_SEL_PRT_FIFO_REQ', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 'RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY', + 'RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX', 'RMI_PERF_SEL_RB_RMI_RD_IDLE', + 'RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_STALL', 'RMI_PERF_SEL_RB_RMI_RD_STARVE', + 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 'RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY', + 'RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX', 'RMI_PERF_SEL_RB_RMI_WR_IDLE', + 'RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_STALL', 'RMI_PERF_SEL_RB_RMI_WR_STARVE', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB', + 'RMI_PERF_SEL_REG_CLK_VLD', 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID', + 'RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID', + 'RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND', + 'RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND', + 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 'RMI_PERF_SEL_RMI_TC_STALL_ALLREQ', + 'RMI_PERF_SEL_RMI_TC_STALL_RDREQ', + 'RMI_PERF_SEL_RMI_TC_STALL_WRREQ', + 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_RMI_UTC_BUSY', 'RMI_PERF_SEL_RMI_UTC_REQ', + 'RMI_PERF_SEL_SKID_FIFO_BUSY', 'RMI_PERF_SEL_SKID_FIFO_DEPTH', + 'RMI_PERF_SEL_SKID_FIFO_IN_RTS', 'RMI_PERF_SEL_SKID_FIFO_IN_RTSB', + 'RMI_PERF_SEL_SKID_FIFO_OUT_RTS', + 'RMI_PERF_SEL_SKID_FIFO_OUT_RTSB', 'RMI_PERF_SEL_SKID_FIFO_REQ', + 'RMI_PERF_SEL_TCIW_BUSY', 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 'RMI_PERF_SEL_TCIW_REQ', + 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', + 'RMI_PERF_SEL_UTCL1_BUSY', 'RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL', + 'RMI_PERF_SEL_UTCL1_LFIFO_FULL', + 'RMI_PERF_SEL_UTCL1_PERMISSION_MISS', + 'RMI_PERF_SEL_UTCL1_REQUEST', + 'RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 'RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 'RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 'RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 'RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS', + 'RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'RMI_PERF_SEL_UTCL1_TRANSLATION_HIT', + 'RMI_PERF_SEL_UTCL1_TRANSLATION_MISS', + 'RMI_PERF_SEL_UTCL1_UTCL2_REQ', 'RMI_PERF_SEL_UTC_POP_RTSB_RTR', + 'RMI_PERF_SEL_UTC_POP_RTSB_RTRB', 'RMI_PERF_SEL_UTC_POP_RTS_RTR', + 'RMI_PERF_SEL_UTC_POP_RTS_RTRB', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR', + 'RMI_PERF_SEL_XNACK_FIFO_BUSY', 'RMI_PERF_SEL_XNACK_FIFO_FULL', + 'RMI_PERF_SEL_XNACK_FIFO_NUM_USED', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB', 'ROM_SIGNATURE', + 'ROTATED_MICRO_TILING', 'ROTATE_0_DEGREES', 'ROTATE_180_DEGREES', + 'ROTATE_270_DEGREES', 'ROTATE_90_DEGREES', 'ROTATION_ANGLE', + 'ROUND_BY_HALF', 'ROUND_TRUNCATE', 'RRDPCS_PHY_DP_TX_PSTATE_HOLD', + 'RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF', + 'RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN', + 'RRDPCS_PHY_DP_TX_PSTATE_POWER_UP', 'RST_PIX_CNT', 'RSV_TAG_RAM', + 'RbMap', 'RbXsel', 'RbXsel2', 'RbYsel', 'ReadPolicy', 'ReadSize', + 'Reserved_0x00', 'RingCounterControl', 'RoundMode', 'RowSize', + 'RowTiling', 'SAMPLE_PIPELINESTAT', 'SAMPLE_STREAMOUTSTATS', + 'SAMPLE_STREAMOUTSTATS1', 'SAMPLE_STREAMOUTSTATS2', + 'SAMPLE_STREAMOUTSTATS3', 'SCL_2TAP_HARDCODE', 'SCL_ALPHA_COEF', + 'SCL_ALPHA_COEF_ALPHA', 'SCL_ALPHA_COEF_LUMA', 'SCL_AUTOCAL_MODE', + 'SCL_BOUNDARY', 'SCL_BOUNDARY_BLACK', 'SCL_BOUNDARY_EDGE', + 'SCL_CHROMA_COEF', 'SCL_CHROMA_COEF_CHROMA', + 'SCL_CHROMA_COEF_LUMA', 'SCL_COEF_2TAP_HARDCODE_OFF', + 'SCL_COEF_2TAP_HARDCODE_ON', 'SCL_COEF_ALPHA_HORZ_FILTER', + 'SCL_COEF_ALPHA_VERT_FILTER', 'SCL_COEF_CHROMA_HORZ_FILTER', + 'SCL_COEF_CHROMA_VERT_FILTER', 'SCL_COEF_FILTER_TYPE_SEL', + 'SCL_COEF_LUMA_HORZ_FILTER', 'SCL_COEF_LUMA_VERT_FILTER', + 'SCL_COEF_RAM_SEL', 'SCL_COEF_RAM_SEL_0', 'SCL_COEF_RAM_SEL_1', + 'SCL_SHARP_DISABLE', 'SCL_SHARP_EN', 'SCL_SHARP_ENABLE', + 'SC_BACKEND_BUSY', 'SC_BACKEND_PRIM_FIFO_FULL', 'SC_BB_DISCARD', + 'SC_BCI_CREDIT_AT_MAX', 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_BCI_SEND', + 'SC_BM_BUSY', 'SC_BUSY_CNT_NOT_ZERO', + 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'SC_DB0_TILE_INTERFACE_BUSY', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_SEND', 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 'SC_DB0_TILE_INTERFACE_SEND_SOP', + 'SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 'SC_DB1_TILE_INTERFACE_BUSY', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'SC_DB1_TILE_INTERFACE_SEND', 'SC_DB1_TILE_INTERFACE_SEND_EVENT', + 'SC_DB1_TILE_INTERFACE_SEND_SOP', + 'SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 'SC_EARLYZ_QUAD_COUNT', 'SC_EARLYZ_QUAD_WITH_1_PIX', + 'SC_EARLYZ_QUAD_WITH_2_PIX', 'SC_EARLYZ_QUAD_WITH_3_PIX', + 'SC_EARLYZ_QUAD_WITH_4_PIX', 'SC_EOP_SYNC_WINDOW', + 'SC_FULL_FULL_QUAD', 'SC_FULL_HALF_QUAD', 'SC_FULL_QTR_QUAD', + 'SC_GRP0_DYN_SCLK_BUSY', 'SC_GRP1_DYN_SCLK_BUSY', + 'SC_GRP2_DYN_SCLK_BUSY', 'SC_GRP3_DYN_SCLK_BUSY', + 'SC_GRP4_DYN_SCLK_BUSY', 'SC_GRP5_DYN_SCLK_BUSY', + 'SC_GRP6_DYN_SCLK_BUSY', 'SC_GRP7_DYN_SCLK_BUSY', + 'SC_GRP8_DYN_SCLK_BUSY', 'SC_GRP9_DYN_SCLK_BUSY', + 'SC_HALF_FULL_QUAD', 'SC_HALF_HALF_QUAD', 'SC_HALF_LSB', + 'SC_HALF_QTR_QUAD', 'SC_LSB_ONE_SIDED', 'SC_LSB_TWO_SIDED', + 'SC_MULTICYCLE_BUBBLE_FREEZE', 'SC_P0_DETAIL_QUAD_COUNT', + 'SC_P0_DETAIL_QUAD_WITH_1_PIX', 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 'SC_P0_DETAIL_QUAD_WITH_3_PIX', 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 'SC_P0_HIZ_QUAD_COUNT', 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 'SC_P0_HIZ_QUAD_PER_TILE_H1', 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 'SC_P0_HIZ_QUAD_PER_TILE_H11', 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 'SC_P0_HIZ_QUAD_PER_TILE_H13', 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 'SC_P0_HIZ_QUAD_PER_TILE_H15', 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 'SC_P0_HIZ_QUAD_PER_TILE_H2', 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 'SC_P0_HIZ_QUAD_PER_TILE_H4', 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 'SC_P0_HIZ_QUAD_PER_TILE_H6', 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 'SC_P0_HIZ_QUAD_PER_TILE_H8', 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 'SC_P0_HIZ_TILE_COUNT', 'SC_P1_DETAIL_QUAD_COUNT', + 'SC_P1_DETAIL_QUAD_WITH_1_PIX', 'SC_P1_DETAIL_QUAD_WITH_2_PIX', + 'SC_P1_DETAIL_QUAD_WITH_3_PIX', 'SC_P1_DETAIL_QUAD_WITH_4_PIX', + 'SC_P1_HIZ_QUAD_COUNT', 'SC_P1_HIZ_QUAD_PER_TILE_H0', + 'SC_P1_HIZ_QUAD_PER_TILE_H1', 'SC_P1_HIZ_QUAD_PER_TILE_H10', + 'SC_P1_HIZ_QUAD_PER_TILE_H11', 'SC_P1_HIZ_QUAD_PER_TILE_H12', + 'SC_P1_HIZ_QUAD_PER_TILE_H13', 'SC_P1_HIZ_QUAD_PER_TILE_H14', + 'SC_P1_HIZ_QUAD_PER_TILE_H15', 'SC_P1_HIZ_QUAD_PER_TILE_H16', + 'SC_P1_HIZ_QUAD_PER_TILE_H2', 'SC_P1_HIZ_QUAD_PER_TILE_H3', + 'SC_P1_HIZ_QUAD_PER_TILE_H4', 'SC_P1_HIZ_QUAD_PER_TILE_H5', + 'SC_P1_HIZ_QUAD_PER_TILE_H6', 'SC_P1_HIZ_QUAD_PER_TILE_H7', + 'SC_P1_HIZ_QUAD_PER_TILE_H8', 'SC_P1_HIZ_QUAD_PER_TILE_H9', + 'SC_P1_HIZ_TILE_COUNT', 'SC_P2_DETAIL_QUAD_COUNT', + 'SC_P2_DETAIL_QUAD_WITH_1_PIX', 'SC_P2_DETAIL_QUAD_WITH_2_PIX', + 'SC_P2_DETAIL_QUAD_WITH_3_PIX', 'SC_P2_DETAIL_QUAD_WITH_4_PIX', + 'SC_P2_HIZ_QUAD_COUNT', 'SC_P2_HIZ_QUAD_PER_TILE_H0', + 'SC_P2_HIZ_QUAD_PER_TILE_H1', 'SC_P2_HIZ_QUAD_PER_TILE_H10', + 'SC_P2_HIZ_QUAD_PER_TILE_H11', 'SC_P2_HIZ_QUAD_PER_TILE_H12', + 'SC_P2_HIZ_QUAD_PER_TILE_H13', 'SC_P2_HIZ_QUAD_PER_TILE_H14', + 'SC_P2_HIZ_QUAD_PER_TILE_H15', 'SC_P2_HIZ_QUAD_PER_TILE_H16', + 'SC_P2_HIZ_QUAD_PER_TILE_H2', 'SC_P2_HIZ_QUAD_PER_TILE_H3', + 'SC_P2_HIZ_QUAD_PER_TILE_H4', 'SC_P2_HIZ_QUAD_PER_TILE_H5', + 'SC_P2_HIZ_QUAD_PER_TILE_H6', 'SC_P2_HIZ_QUAD_PER_TILE_H7', + 'SC_P2_HIZ_QUAD_PER_TILE_H8', 'SC_P2_HIZ_QUAD_PER_TILE_H9', + 'SC_P2_HIZ_TILE_COUNT', 'SC_P3_DETAIL_QUAD_COUNT', + 'SC_P3_DETAIL_QUAD_WITH_1_PIX', 'SC_P3_DETAIL_QUAD_WITH_2_PIX', + 'SC_P3_DETAIL_QUAD_WITH_3_PIX', 'SC_P3_DETAIL_QUAD_WITH_4_PIX', + 'SC_P3_HIZ_QUAD_COUNT', 'SC_P3_HIZ_QUAD_PER_TILE_H0', + 'SC_P3_HIZ_QUAD_PER_TILE_H1', 'SC_P3_HIZ_QUAD_PER_TILE_H10', + 'SC_P3_HIZ_QUAD_PER_TILE_H11', 'SC_P3_HIZ_QUAD_PER_TILE_H12', + 'SC_P3_HIZ_QUAD_PER_TILE_H13', 'SC_P3_HIZ_QUAD_PER_TILE_H14', + 'SC_P3_HIZ_QUAD_PER_TILE_H15', 'SC_P3_HIZ_QUAD_PER_TILE_H16', + 'SC_P3_HIZ_QUAD_PER_TILE_H2', 'SC_P3_HIZ_QUAD_PER_TILE_H3', + 'SC_P3_HIZ_QUAD_PER_TILE_H4', 'SC_P3_HIZ_QUAD_PER_TILE_H5', + 'SC_P3_HIZ_QUAD_PER_TILE_H6', 'SC_P3_HIZ_QUAD_PER_TILE_H7', + 'SC_P3_HIZ_QUAD_PER_TILE_H8', 'SC_P3_HIZ_QUAD_PER_TILE_H9', + 'SC_P3_HIZ_TILE_COUNT', 'SC_PA0_SC_DATA_FIFO_EOPG_RD', + 'SC_PA0_SC_DATA_FIFO_EOP_RD', 'SC_PA0_SC_DATA_FIFO_RD', + 'SC_PA0_SC_DATA_FIFO_WE', 'SC_PA0_SC_DEALLOC_0_RD', + 'SC_PA0_SC_DEALLOC_1_RD', 'SC_PA0_SC_EOPG_WE', 'SC_PA0_SC_EOP_WE', + 'SC_PA0_SC_EVENT_WE', 'SC_PA0_SC_FPOV_WE', 'SC_PA0_SC_LPOV_WE', + 'SC_PA0_SC_NULL_DEALLOC_WE', 'SC_PA0_SC_NULL_WE', + 'SC_PA1_SC_DATA_FIFO_EOPG_RD', 'SC_PA1_SC_DATA_FIFO_EOP_RD', + 'SC_PA1_SC_DATA_FIFO_RD', 'SC_PA1_SC_DATA_FIFO_WE', + 'SC_PA1_SC_DEALLOC_0_RD', 'SC_PA1_SC_DEALLOC_1_RD', + 'SC_PA1_SC_EOPG_WE', 'SC_PA1_SC_EOP_WE', 'SC_PA1_SC_EVENT_WE', + 'SC_PA1_SC_FPOV_WE', 'SC_PA1_SC_LPOV_WE', + 'SC_PA1_SC_NULL_DEALLOC_WE', 'SC_PA1_SC_NULL_WE', + 'SC_PA2_SC_DATA_FIFO_EOPG_RD', 'SC_PA2_SC_DATA_FIFO_EOP_RD', + 'SC_PA2_SC_DATA_FIFO_RD', 'SC_PA2_SC_DATA_FIFO_WE', + 'SC_PA2_SC_DEALLOC_0_RD', 'SC_PA2_SC_DEALLOC_1_RD', + 'SC_PA2_SC_EOPG_WE', 'SC_PA2_SC_EOP_WE', 'SC_PA2_SC_EVENT_WE', + 'SC_PA2_SC_FPOV_WE', 'SC_PA2_SC_LPOV_WE', + 'SC_PA2_SC_NULL_DEALLOC_WE', 'SC_PA2_SC_NULL_WE', + 'SC_PA3_SC_DATA_FIFO_EOPG_RD', 'SC_PA3_SC_DATA_FIFO_EOP_RD', + 'SC_PA3_SC_DATA_FIFO_RD', 'SC_PA3_SC_DATA_FIFO_WE', + 'SC_PA3_SC_DEALLOC_0_RD', 'SC_PA3_SC_DEALLOC_1_RD', + 'SC_PA3_SC_EOPG_WE', 'SC_PA3_SC_EOP_WE', 'SC_PA3_SC_EVENT_WE', + 'SC_PA3_SC_FPOV_WE', 'SC_PA3_SC_LPOV_WE', + 'SC_PA3_SC_NULL_DEALLOC_WE', 'SC_PA3_SC_NULL_WE', + 'SC_PA_SC_DEALLOC_0_0_WE', 'SC_PA_SC_DEALLOC_0_1_WE', + 'SC_PA_SC_DEALLOC_1_0_WE', 'SC_PA_SC_DEALLOC_1_1_WE', + 'SC_PA_SC_DEALLOC_2_0_WE', 'SC_PA_SC_DEALLOC_2_1_WE', + 'SC_PA_SC_DEALLOC_3_0_WE', 'SC_PA_SC_DEALLOC_3_1_WE', + 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BIN_HIST_NUM_PRIMS', 'SC_PBB_BUSY', + 'SC_PBB_BUSY_AND_NO_SENDS', 'SC_PBB_END_OF_BATCH', + 'SC_PBB_END_OF_BIN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 'SC_PBB_NONBINNED_PRIM', 'SC_PBB_NUM_BINS', + 'SC_PBB_PRIMBIN_PROCESSED', 'SC_PBB_PRIM_ADDED_TO_BATCH', + 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', 'SC_PERFCNT_SEL', + 'SC_PKR_4X2_FILL_QUAD', 'SC_PKR_4X2_QUAD_SPLIT', + 'SC_PKR_CONTROL_XFER', 'SC_PKR_DBHANG_FORCE_EOV', + 'SC_PKR_END_OF_VECTOR', 'SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE', + 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP', + 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX', + 'SC_PKR_QUAD_PER_ROW_H1', 'SC_PKR_QUAD_PER_ROW_H2', 'SC_PK_BUSY', + 'SC_PK_DEALLOC_WAVE_BREAK', 'SC_PK_MAX_DEALLOC_FORCE_EOV', + 'SC_POPS_FORCE_EOV', 'SC_POPS_INTRA_WAVE_OVERLAPS', + 'SC_PSSW_WINDOW_VALID', 'SC_PSSW_WINDOW_VALID_BUSY', + 'SC_PS_ARB_EOP_POP_SYNC_POP', 'SC_PS_ARB_EVENT_SYNC_POP', + 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 'SC_PS_ARB_PA_SC_BUSY', 'SC_PS_ARB_SC_BUSY', + 'SC_PS_ARB_STALLED_FROM_BELOW', 'SC_PS_ARB_STARVED_FROM_ABOVE', + 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', 'SC_PS_CTX_DONE_FIFO_POP', + 'SC_PS_CTX_DONE_FIFO_PUSH', 'SC_PS_PA0_SC_FIFO_EMPTY', + 'SC_PS_PA0_SC_FIFO_FULL', 'SC_PS_PA1_SC_FIFO_EMPTY', + 'SC_PS_PA1_SC_FIFO_FULL', 'SC_PS_PA2_SC_FIFO_EMPTY', + 'SC_PS_PA2_SC_FIFO_FULL', 'SC_PS_PA3_SC_FIFO_EMPTY', + 'SC_PS_PA3_SC_FIFO_FULL', 'SC_PS_TO_BE_SCLK_GATE_STALL', + 'SC_PS_TS_EVENT_FIFO_POP', 'SC_PS_TS_EVENT_FIFO_PUSH', + 'SC_PW_BM_PASS_EMPTY_PRIM', 'SC_QTR_FULL_QUAD', + 'SC_QTR_HALF_QUAD', 'SC_QTR_QTR_QUAD', 'SC_QZ0_QUAD_COUNT', + 'SC_QZ0_QUAD_PER_TILE_H0', 'SC_QZ0_QUAD_PER_TILE_H1', + 'SC_QZ0_QUAD_PER_TILE_H10', 'SC_QZ0_QUAD_PER_TILE_H11', + 'SC_QZ0_QUAD_PER_TILE_H12', 'SC_QZ0_QUAD_PER_TILE_H13', + 'SC_QZ0_QUAD_PER_TILE_H14', 'SC_QZ0_QUAD_PER_TILE_H15', + 'SC_QZ0_QUAD_PER_TILE_H16', 'SC_QZ0_QUAD_PER_TILE_H2', + 'SC_QZ0_QUAD_PER_TILE_H3', 'SC_QZ0_QUAD_PER_TILE_H4', + 'SC_QZ0_QUAD_PER_TILE_H5', 'SC_QZ0_QUAD_PER_TILE_H6', + 'SC_QZ0_QUAD_PER_TILE_H7', 'SC_QZ0_QUAD_PER_TILE_H8', + 'SC_QZ0_QUAD_PER_TILE_H9', 'SC_QZ0_TILE_COUNT', + 'SC_QZ0_TILE_COVERED_COUNT', 'SC_QZ0_TILE_NOT_COVERED_COUNT', + 'SC_QZ1_QUAD_COUNT', 'SC_QZ1_QUAD_PER_TILE_H0', + 'SC_QZ1_QUAD_PER_TILE_H1', 'SC_QZ1_QUAD_PER_TILE_H10', + 'SC_QZ1_QUAD_PER_TILE_H11', 'SC_QZ1_QUAD_PER_TILE_H12', + 'SC_QZ1_QUAD_PER_TILE_H13', 'SC_QZ1_QUAD_PER_TILE_H14', + 'SC_QZ1_QUAD_PER_TILE_H15', 'SC_QZ1_QUAD_PER_TILE_H16', + 'SC_QZ1_QUAD_PER_TILE_H2', 'SC_QZ1_QUAD_PER_TILE_H3', + 'SC_QZ1_QUAD_PER_TILE_H4', 'SC_QZ1_QUAD_PER_TILE_H5', + 'SC_QZ1_QUAD_PER_TILE_H6', 'SC_QZ1_QUAD_PER_TILE_H7', + 'SC_QZ1_QUAD_PER_TILE_H8', 'SC_QZ1_QUAD_PER_TILE_H9', + 'SC_QZ1_TILE_COUNT', 'SC_QZ1_TILE_COVERED_COUNT', + 'SC_QZ1_TILE_NOT_COVERED_COUNT', 'SC_QZ2_QUAD_COUNT', + 'SC_QZ2_QUAD_PER_TILE_H0', 'SC_QZ2_QUAD_PER_TILE_H1', + 'SC_QZ2_QUAD_PER_TILE_H10', 'SC_QZ2_QUAD_PER_TILE_H11', + 'SC_QZ2_QUAD_PER_TILE_H12', 'SC_QZ2_QUAD_PER_TILE_H13', + 'SC_QZ2_QUAD_PER_TILE_H14', 'SC_QZ2_QUAD_PER_TILE_H15', + 'SC_QZ2_QUAD_PER_TILE_H16', 'SC_QZ2_QUAD_PER_TILE_H2', + 'SC_QZ2_QUAD_PER_TILE_H3', 'SC_QZ2_QUAD_PER_TILE_H4', + 'SC_QZ2_QUAD_PER_TILE_H5', 'SC_QZ2_QUAD_PER_TILE_H6', + 'SC_QZ2_QUAD_PER_TILE_H7', 'SC_QZ2_QUAD_PER_TILE_H8', + 'SC_QZ2_QUAD_PER_TILE_H9', 'SC_QZ2_TILE_COUNT', + 'SC_QZ2_TILE_COVERED_COUNT', 'SC_QZ2_TILE_NOT_COVERED_COUNT', + 'SC_QZ3_QUAD_COUNT', 'SC_QZ3_QUAD_PER_TILE_H0', + 'SC_QZ3_QUAD_PER_TILE_H1', 'SC_QZ3_QUAD_PER_TILE_H10', + 'SC_QZ3_QUAD_PER_TILE_H11', 'SC_QZ3_QUAD_PER_TILE_H12', + 'SC_QZ3_QUAD_PER_TILE_H13', 'SC_QZ3_QUAD_PER_TILE_H14', + 'SC_QZ3_QUAD_PER_TILE_H15', 'SC_QZ3_QUAD_PER_TILE_H16', + 'SC_QZ3_QUAD_PER_TILE_H2', 'SC_QZ3_QUAD_PER_TILE_H3', + 'SC_QZ3_QUAD_PER_TILE_H4', 'SC_QZ3_QUAD_PER_TILE_H5', + 'SC_QZ3_QUAD_PER_TILE_H6', 'SC_QZ3_QUAD_PER_TILE_H7', + 'SC_QZ3_QUAD_PER_TILE_H8', 'SC_QZ3_QUAD_PER_TILE_H9', + 'SC_QZ3_TILE_COUNT', 'SC_QZ3_TILE_COVERED_COUNT', + 'SC_QZ3_TILE_NOT_COVERED_COUNT', 'SC_QZQP_WINDOW_VALID', + 'SC_QZQP_WINDOW_VALID_BUSY', 'SC_REG_SCLK_BUSY', 'SC_RESERVED_0', + 'SC_RESERVED_1', 'SC_RESERVED_2', 'SC_RESERVED_3', 'SC_SCB_BUSY', + 'SC_SCF_SCB_INTERFACE_BUSY', 'SC_SCISSOR_DISCARD', + 'SC_SC_PS_ENG_MULTICYCLE_BUBBLE', 'SC_SC_SPI_DEALLOC_0_0', + 'SC_SC_SPI_DEALLOC_0_1', 'SC_SC_SPI_DEALLOC_0_2', + 'SC_SC_SPI_DEALLOC_1_0', 'SC_SC_SPI_DEALLOC_1_1', + 'SC_SC_SPI_DEALLOC_1_2', 'SC_SC_SPI_DEALLOC_2_0', + 'SC_SC_SPI_DEALLOC_2_1', 'SC_SC_SPI_DEALLOC_2_2', + 'SC_SC_SPI_DEALLOC_3_0', 'SC_SC_SPI_DEALLOC_3_1', + 'SC_SC_SPI_DEALLOC_3_2', 'SC_SC_SPI_EVENT', 'SC_SC_SPI_FPOV_0', + 'SC_SC_SPI_FPOV_1', 'SC_SC_SPI_FPOV_2', 'SC_SC_SPI_FPOV_3', + 'SC_SEND_DB_VPZ', 'SC_SPIBC_FULL_FREEZE', 'SC_SPI_CREDIT_AT_MAX', + 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_SPI_SEND', + 'SC_SRPS_WINDOW_VALID', 'SC_SRPS_WINDOW_VALID_BUSY', + 'SC_STALLED_BY_BCI', 'SC_STALLED_BY_DB_QUAD', + 'SC_STALLED_BY_DB_TILE', 'SC_STALLED_BY_PRIMFIFO', + 'SC_STALLED_BY_QUADFIFO', 'SC_STALLED_BY_SPI', + 'SC_STALLED_BY_TILEFIFO', 'SC_STALLED_BY_TILEORDERFIFO', + 'SC_STARVED_BY_DB_QUAD', 'SC_STARVED_BY_DB_TILE', + 'SC_STARVED_BY_PA', 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 'SC_SUPERTILE_COUNT', + 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 'SC_SUPERTILE_PER_PRIM_H0', 'SC_SUPERTILE_PER_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_H10', 'SC_SUPERTILE_PER_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_H12', 'SC_SUPERTILE_PER_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_H14', 'SC_SUPERTILE_PER_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_H16', 'SC_SUPERTILE_PER_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_H3', 'SC_SUPERTILE_PER_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_H5', 'SC_SUPERTILE_PER_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_H7', 'SC_SUPERTILE_PER_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_H9', 'SC_TILE_PER_PRIM_H0', + 'SC_TILE_PER_PRIM_H1', 'SC_TILE_PER_PRIM_H10', + 'SC_TILE_PER_PRIM_H11', 'SC_TILE_PER_PRIM_H12', + 'SC_TILE_PER_PRIM_H13', 'SC_TILE_PER_PRIM_H14', + 'SC_TILE_PER_PRIM_H15', 'SC_TILE_PER_PRIM_H16', + 'SC_TILE_PER_PRIM_H2', 'SC_TILE_PER_PRIM_H3', + 'SC_TILE_PER_PRIM_H4', 'SC_TILE_PER_PRIM_H5', + 'SC_TILE_PER_PRIM_H6', 'SC_TILE_PER_PRIM_H7', + 'SC_TILE_PER_PRIM_H8', 'SC_TILE_PER_PRIM_H9', + 'SC_TILE_PER_SUPERTILE_H0', 'SC_TILE_PER_SUPERTILE_H1', + 'SC_TILE_PER_SUPERTILE_H10', 'SC_TILE_PER_SUPERTILE_H11', + 'SC_TILE_PER_SUPERTILE_H12', 'SC_TILE_PER_SUPERTILE_H13', + 'SC_TILE_PER_SUPERTILE_H14', 'SC_TILE_PER_SUPERTILE_H15', + 'SC_TILE_PER_SUPERTILE_H16', 'SC_TILE_PER_SUPERTILE_H2', + 'SC_TILE_PER_SUPERTILE_H3', 'SC_TILE_PER_SUPERTILE_H4', + 'SC_TILE_PER_SUPERTILE_H5', 'SC_TILE_PER_SUPERTILE_H6', + 'SC_TILE_PER_SUPERTILE_H7', 'SC_TILE_PER_SUPERTILE_H8', + 'SC_TILE_PER_SUPERTILE_H9', 'SC_TILE_PICKED_H1', + 'SC_TILE_PICKED_H2', 'SC_TILE_PICKED_H3', 'SC_TILE_PICKED_H4', + 'SC_TPQZ_WINDOW_VALID', 'SC_TPQZ_WINDOW_VALID_BUSY', + 'SC_TRPK_WINDOW_VALID', 'SC_TRPK_WINDOW_VALID_BUSY', + 'SDMA_PERF_SEL', 'SDMA_PERF_SEL_CE_AFIFO_FULL', + 'SDMA_PERF_SEL_CE_DST_IDLE', 'SDMA_PERF_SEL_CE_INFO1_FULL', + 'SDMA_PERF_SEL_CE_INFO_FULL', 'SDMA_PERF_SEL_CE_IN_IDLE', + 'SDMA_PERF_SEL_CE_L1_WR_VLD', 'SDMA_PERF_SEL_CE_OUT_IDLE', + 'SDMA_PERF_SEL_CE_RD_STALL', 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 'SDMA_PERF_SEL_CE_SPLIT_IDLE', 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 'SDMA_PERF_SEL_CE_WR_IDLE', 'SDMA_PERF_SEL_CE_WR_STALL', + 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', 'SDMA_PERF_SEL_CTX_CHANGE', + 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERF_SEL_CYCLE', + 'SDMA_PERF_SEL_DMA_L1_RD_SEND', 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 'SDMA_PERF_SEL_DMA_MC_RD_SEND', 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 'SDMA_PERF_SEL_DOORBELL', 'SDMA_PERF_SEL_EX_IDLE', + 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERF_SEL_F32_L1_WR_VLD', 'SDMA_PERF_SEL_GCR_RTN', + 'SDMA_PERF_SEL_GCR_SEND', 'SDMA_PERF_SEL_GFX_SELECT', + 'SDMA_PERF_SEL_GPUVM_INVREQ_HIGH', + 'SDMA_PERF_SEL_GPUVM_INVREQ_LOW', 'SDMA_PERF_SEL_IB_CMD_FULL', + 'SDMA_PERF_SEL_IB_CMD_IDLE', 'SDMA_PERF_SEL_IDLE', + 'SDMA_PERF_SEL_INT_IDLE', 'SDMA_PERF_SEL_INT_REQ_COUNT', + 'SDMA_PERF_SEL_INT_REQ_STALL', 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 'SDMA_PERF_SEL_INT_RESP_RETRY', 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 'SDMA_PERF_SEL_L1_RDMC_IDLE', 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 'SDMA_PERF_SEL_L1_WRL2_IDLE', 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 'SDMA_PERF_SEL_L1_WR_INV_IDLE', 'SDMA_PERF_SEL_L2_META_RET_VLD', + 'SDMA_PERF_SEL_MC_RD_COUNT', 'SDMA_PERF_SEL_MC_RD_IDLE', + 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERF_SEL_MC_RD_RET_STALL', 'SDMA_PERF_SEL_MC_WR_COUNT', + 'SDMA_PERF_SEL_MC_WR_IDLE', 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 'SDMA_PERF_SEL_META_REQ_SEND', 'SDMA_PERF_SEL_META_RTN_VLD', + 'SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER', + 'SDMA_PERF_SEL_NUM_PACKET', 'SDMA_PERF_SEL_PAGE_SELECT', + 'SDMA_PERF_SEL_RB_CMD_FULL', 'SDMA_PERF_SEL_RB_CMD_IDLE', + 'SDMA_PERF_SEL_RB_EMPTY', 'SDMA_PERF_SEL_RB_FULL', + 'SDMA_PERF_SEL_RB_RPTR_WB', 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 'SDMA_PERF_SEL_RD_BA_RTR', 'SDMA_PERF_SEL_REG_IDLE', + 'SDMA_PERF_SEL_RLC0_SELECT', 'SDMA_PERF_SEL_RLC1_SELECT', + 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', 'SDMA_PERF_SEL_SEM_IDLE', + 'SDMA_PERF_SEL_SEM_REQ_COUNT', 'SDMA_PERF_SEL_SEM_REQ_STALL', + 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERF_SEL_SEM_RESP_PASS', 'SDMA_PERF_SEL_SRBM_REG_SEND', + 'SDMA_PERF_SEL_TLBI_RTN', 'SDMA_PERF_SEL_TLBI_SEND', + 'SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER', + 'SDMA_PERF_SEL_UTCL2_FREE', 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', 'SDMA_PERF_SEL_WR_BA_RTR', + 'SEC_GSP0_PRIORITY_HIGH', 'SEC_GSP0_PRIORITY_LOW', 'SEGMENTS_1', + 'SEGMENTS_128', 'SEGMENTS_16', 'SEGMENTS_2', 'SEGMENTS_32', + 'SEGMENTS_4', 'SEGMENTS_64', 'SEGMENTS_8', 'SEM_ECC_ERROR', + 'SEM_PERF_SEL', 'SEM_PERF_SEL_ACP_REQ_SIGNAL', + 'SEM_PERF_SEL_ACP_REQ_WAIT', 'SEM_PERF_SEL_ATC_INVALIDATION', + 'SEM_PERF_SEL_ATC_REQ', 'SEM_PERF_SEL_ATC_RET', + 'SEM_PERF_SEL_ATC_VM_INVALIDATION', 'SEM_PERF_SEL_ATC_XNACK', + 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 'SEM_PERF_SEL_CYCLE', 'SEM_PERF_SEL_IDLE', + 'SEM_PERF_SEL_ISP_REQ_SIGNAL', 'SEM_PERF_SEL_ISP_REQ_WAIT', + 'SEM_PERF_SEL_MC_RD_REQ', 'SEM_PERF_SEL_MC_RD_RET', + 'SEM_PERF_SEL_MC_WR_REQ', 'SEM_PERF_SEL_MC_WR_RET', + 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 'SEM_PERF_SEL_UVD_REQ_SIGNAL', 'SEM_PERF_SEL_UVD_REQ_WAIT', + 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 'SEM_PERF_SEL_VP8_REQ_SIGNAL', 'SEM_PERF_SEL_VP8_REQ_WAIT', + 'SEM_RESP_FAILED', 'SEM_RESP_PASSED', 'SEM_TRANS_ERROR', + 'SEND_AT_EARLIEST_TIME', 'SEND_AT_LINK_NUMBER', + 'SEND_NORMAL_PACKET', 'SEND_PPS_PACKET', 'SET_FE_ID', + 'SET_STATIC_SCREEN_SMU_INTR', 'SH_MEM_ADDRESS_MODE', + 'SH_MEM_ADDRESS_MODE_32', 'SH_MEM_ADDRESS_MODE_64', + 'SH_MEM_ALIGNMENT_MODE', 'SH_MEM_ALIGNMENT_MODE_DWORD', + 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 'SH_MEM_ALIGNMENT_MODE_STRICT', 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', + 'SH_MEM_RETRY_MODE', 'SH_MEM_RETRY_MODE_ALL', + 'SH_MEM_RETRY_MODE_NONE', 'SH_MEM_RETRY_MODE_WRITEATOMIC', + 'SIGNED', 'SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_SA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_START', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_START', + 'SIMM16_WAITCNT_EXP_CNT_SIZE', 'SIMM16_WAITCNT_EXP_CNT_START', + 'SIMM16_WAITCNT_LGKM_CNT_SIZE', 'SIMM16_WAITCNT_LGKM_CNT_START', + 'SIMM16_WAITCNT_VM_CNT_HI_SIZE', 'SIMM16_WAITCNT_VM_CNT_HI_START', + 'SIMM16_WAITCNT_VM_CNT_SIZE', 'SIMM16_WAITCNT_VM_CNT_START', + 'SIXTEEN_BANKS', 'SIXTEEN_PIPES', 'SIXTY_FOUR_PIPES', 'SIZE_16K', + 'SIZE_8K', 'SMU_INTR_STATUS_CLEAR', 'SMU_INTR_STATUS_NOOP', + 'SM_MODE_RESERVED', 'SOFT_RESET', 'SOFT_RESET_0', 'SOFT_RESET_1', + 'SO_VGTSTREAMOUT_FLUSH', 'SPI_FOG_EXP', 'SPI_FOG_EXP2', + 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', 'SPI_FOG_NONE', + 'SPI_LB_WAVES_RSVD', 'SPI_LB_WAVES_SELECT', 'SPI_PERFCNT_SEL', + 'SPI_PERF_CLKGATE_ACTIVE_STALL', 'SPI_PERF_CLKGATE_ALL_CLOCKS_ON', + 'SPI_PERF_CLKGATE_BUSY_STALL', 'SPI_PERF_CLKGATE_CGTT_DYN_ON', + 'SPI_PERF_CLKGATE_CGTT_REG_ON', 'SPI_PERF_CSG_BUSY', + 'SPI_PERF_CSG_CRAWLER_STALL', 'SPI_PERF_CSG_EVENT_WAVE', + 'SPI_PERF_CSG_NUM_THREADGROUPS', 'SPI_PERF_CSG_WAVE', + 'SPI_PERF_CSG_WINDOW_VALID', 'SPI_PERF_CSN_BUSY', + 'SPI_PERF_CSN_CRAWLER_STALL', 'SPI_PERF_CSN_EVENT_WAVE', + 'SPI_PERF_CSN_NUM_THREADGROUPS', 'SPI_PERF_CSN_WAVE', + 'SPI_PERF_CSN_WINDOW_VALID', 'SPI_PERF_ESC_VTX_BUSY', + 'SPI_PERF_ESC_VTX_CAC_BUSY', 'SPI_PERF_ESC_VTX_INPUT_STARVED', + 'SPI_PERF_ESC_VTX_VSR_FULL', 'SPI_PERF_ESC_VTX_VSR_STALL', + 'SPI_PERF_ES_BUSY', 'SPI_PERF_ES_CRAWLER_STALL', + 'SPI_PERF_ES_EVENT_WAVE', 'SPI_PERF_ES_FIRST_SUBGRP', + 'SPI_PERF_ES_FIRST_WAVE', 'SPI_PERF_ES_LAST_SUBGRP', + 'SPI_PERF_ES_LAST_WAVE', 'SPI_PERF_ES_LSHS_DEALLOC', + 'SPI_PERF_ES_PERS_UPD_FULL0', 'SPI_PERF_ES_PERS_UPD_FULL1', + 'SPI_PERF_ES_WAVE', 'SPI_PERF_ES_WINDOW_VALID', + 'SPI_PERF_EXP_ARB_COL_CNT', 'SPI_PERF_EXP_ARB_GDS_CNT', + 'SPI_PERF_EXP_ARB_PAR_CNT', 'SPI_PERF_EXP_ARB_POS_CNT', + 'SPI_PERF_GSC_VTX_BUSY', 'SPI_PERF_GSC_VTX_CAC_BUSY', + 'SPI_PERF_GSC_VTX_INPUT_STARVED', 'SPI_PERF_GSC_VTX_VSR_FULL', + 'SPI_PERF_GSC_VTX_VSR_STALL', 'SPI_PERF_GS_BUSY', + 'SPI_PERF_GS_CRAWLER_STALL', 'SPI_PERF_GS_EVENT_WAVE', + 'SPI_PERF_GS_FIRST_SUBGRP', 'SPI_PERF_GS_GRP_FIFO_FULL', + 'SPI_PERF_GS_HS_DEALLOC', 'SPI_PERF_GS_LAST_SUBGRP', + 'SPI_PERF_GS_NGG_GS_ALLOC_FIFO_EMPTY', 'SPI_PERF_GS_NGG_PC_FULL', + 'SPI_PERF_GS_NGG_SE_AT_SYNC_EVENT', + 'SPI_PERF_GS_NGG_SE_DEALLOC_PC_SPACE_CNT', + 'SPI_PERF_GS_NGG_SE_DOES_NOT_HAVE_BATON', + 'SPI_PERF_GS_NGG_SE_FORWARDED_BATON', + 'SPI_PERF_GS_NGG_SE_HAS_BATON', + 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 'SPI_PERF_GS_NGG_SE_SG_ALLOC_PC_SPACE_CNT', + 'SPI_PERF_GS_PERS_UPD_FULL0', 'SPI_PERF_GS_PERS_UPD_FULL1', + 'SPI_PERF_GS_WAVE', 'SPI_PERF_GS_WINDOW_VALID', + 'SPI_PERF_HS_BUSY', 'SPI_PERF_HS_CRAWLER_STALL', + 'SPI_PERF_HS_EVENT_WAVE', 'SPI_PERF_HS_FIRST_WAVE', + 'SPI_PERF_HS_LAST_WAVE', 'SPI_PERF_HS_OFFCHIP_LDS_STALL', + 'SPI_PERF_HS_PERS_UPD_FULL0', 'SPI_PERF_HS_PERS_UPD_FULL1', + 'SPI_PERF_HS_WAVE', 'SPI_PERF_HS_WINDOW_VALID', + 'SPI_PERF_LDS0_PC_VALID', 'SPI_PERF_LDS1_PC_VALID', + 'SPI_PERF_LS_BUSY', 'SPI_PERF_LS_CRAWLER_STALL', + 'SPI_PERF_LS_EVENT_WAVE', 'SPI_PERF_LS_FIRST_WAVE', + 'SPI_PERF_LS_LAST_WAVE', 'SPI_PERF_LS_OFFCHIP_LDS_STALL', + 'SPI_PERF_LS_PERS_UPD_FULL0', 'SPI_PERF_LS_PERS_UPD_FULL1', + 'SPI_PERF_LS_WAVE', 'SPI_PERF_LS_WINDOW_VALID', + 'SPI_PERF_NUM_EXPGRANT_EXPORTS', 'SPI_PERF_NUM_PS_COL_R0_EXPORTS', + 'SPI_PERF_NUM_PS_COL_R1_EXPORTS', + 'SPI_PERF_NUM_VS_GDS_R0_EXPORTS', + 'SPI_PERF_NUM_VS_GDS_R1_EXPORTS', + 'SPI_PERF_NUM_VS_PARAM_R0_EXPORTS', + 'SPI_PERF_NUM_VS_PARAM_R1_EXPORTS', + 'SPI_PERF_NUM_VS_POS_R0_EXPORTS', + 'SPI_PERF_NUM_VS_POS_R1_EXPORTS', 'SPI_PERF_PC_ALLOC_ACCUM', + 'SPI_PERF_PIX_ALLOC_DB0_STALL', 'SPI_PERF_PIX_ALLOC_DB1_STALL', + 'SPI_PERF_PIX_ALLOC_DB2_STALL', 'SPI_PERF_PIX_ALLOC_DB3_STALL', + 'SPI_PERF_PIX_ALLOC_DB4_STALL', 'SPI_PERF_PIX_ALLOC_DB5_STALL', + 'SPI_PERF_PIX_ALLOC_DB6_STALL', 'SPI_PERF_PIX_ALLOC_DB7_STALL', + 'SPI_PERF_PIX_ALLOC_PEND_CNT', 'SPI_PERF_PIX_ALLOC_SCB0_STALL', + 'SPI_PERF_PIX_ALLOC_SCB1_STALL', 'SPI_PERF_PIX_ALLOC_SCB2_STALL', + 'SPI_PERF_PIX_ALLOC_SCB3_STALL', 'SPI_PERF_PS0_ACTIVE', + 'SPI_PERF_PS0_BUSY', 'SPI_PERF_PS0_CNF_BIN2', + 'SPI_PERF_PS0_CNF_BIN3', 'SPI_PERF_PS0_CRAWLER_STALL', + 'SPI_PERF_PS0_DEALLOC_BIN0', 'SPI_PERF_PS0_EVENT_WAVE', + 'SPI_PERF_PS0_FPOS_BIN1_STALL', 'SPI_PERF_PS0_FPOS_BIN2', + 'SPI_PERF_PS0_LDS_RES_FULL', 'SPI_PERF_PS0_OPT_WAVE', + 'SPI_PERF_PS0_PASS_BIN0', 'SPI_PERF_PS0_PASS_BIN1', + 'SPI_PERF_PS0_POPS_WAVE_EXIT', 'SPI_PERF_PS0_POPS_WAVE_SENT', + 'SPI_PERF_PS0_PRIM_BIN0', 'SPI_PERF_PS0_PRIM_BIN1', + 'SPI_PERF_PS0_WAVE', 'SPI_PERF_PS0_WINDOW_VALID', + 'SPI_PERF_PS1_ACTIVE', 'SPI_PERF_PS1_BUSY', + 'SPI_PERF_PS1_CNF_BIN2', 'SPI_PERF_PS1_CNF_BIN3', + 'SPI_PERF_PS1_CRAWLER_STALL', 'SPI_PERF_PS1_DEALLOC_BIN0', + 'SPI_PERF_PS1_EVENT_WAVE', 'SPI_PERF_PS1_FPOS_BIN1_STALL', + 'SPI_PERF_PS1_FPOS_BIN2', 'SPI_PERF_PS1_LDS_RES_FULL', + 'SPI_PERF_PS1_OPT_WAVE', 'SPI_PERF_PS1_PASS_BIN0', + 'SPI_PERF_PS1_PASS_BIN1', 'SPI_PERF_PS1_POPS_WAVE_EXIT', + 'SPI_PERF_PS1_POPS_WAVE_SENT', 'SPI_PERF_PS1_PRIM_BIN0', + 'SPI_PERF_PS1_PRIM_BIN1', 'SPI_PERF_PS1_WAVE', + 'SPI_PERF_PS1_WINDOW_VALID', 'SPI_PERF_PS2_ACTIVE', + 'SPI_PERF_PS2_BUSY', 'SPI_PERF_PS2_CNF_BIN2', + 'SPI_PERF_PS2_CNF_BIN3', 'SPI_PERF_PS2_CRAWLER_STALL', + 'SPI_PERF_PS2_DEALLOC_BIN0', 'SPI_PERF_PS2_EVENT_WAVE', + 'SPI_PERF_PS2_FPOS_BIN1_STALL', 'SPI_PERF_PS2_FPOS_BIN2', + 'SPI_PERF_PS2_LDS_RES_FULL', 'SPI_PERF_PS2_OPT_WAVE', + 'SPI_PERF_PS2_PASS_BIN0', 'SPI_PERF_PS2_PASS_BIN1', + 'SPI_PERF_PS2_POPS_WAVE_EXIT', 'SPI_PERF_PS2_POPS_WAVE_SENT', + 'SPI_PERF_PS2_PRIM_BIN0', 'SPI_PERF_PS2_PRIM_BIN1', + 'SPI_PERF_PS2_WAVE', 'SPI_PERF_PS2_WINDOW_VALID', + 'SPI_PERF_PS3_ACTIVE', 'SPI_PERF_PS3_BUSY', + 'SPI_PERF_PS3_CNF_BIN2', 'SPI_PERF_PS3_CNF_BIN3', + 'SPI_PERF_PS3_CRAWLER_STALL', 'SPI_PERF_PS3_DEALLOC_BIN0', + 'SPI_PERF_PS3_EVENT_WAVE', 'SPI_PERF_PS3_FPOS_BIN1_STALL', + 'SPI_PERF_PS3_FPOS_BIN2', 'SPI_PERF_PS3_LDS_RES_FULL', + 'SPI_PERF_PS3_OPT_WAVE', 'SPI_PERF_PS3_PASS_BIN0', + 'SPI_PERF_PS3_PASS_BIN1', 'SPI_PERF_PS3_POPS_WAVE_EXIT', + 'SPI_PERF_PS3_POPS_WAVE_SENT', 'SPI_PERF_PS3_PRIM_BIN0', + 'SPI_PERF_PS3_PRIM_BIN1', 'SPI_PERF_PS3_WAVE', + 'SPI_PERF_PS3_WINDOW_VALID', 'SPI_PERF_PS_PERS_UPD_FULL0', + 'SPI_PERF_PS_PERS_UPD_FULL1', 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 'SPI_PERF_RA_BAR_CU_FULL_CSN', 'SPI_PERF_RA_BAR_CU_FULL_HS', + 'SPI_PERF_RA_BULKY_CU_FULL_CSG', 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 'SPI_PERF_RA_CSG_LOCK', 'SPI_PERF_RA_CSN_LOCK', + 'SPI_PERF_RA_GS_LOCK', 'SPI_PERF_RA_HS_LOCK', + 'SPI_PERF_RA_LDS_CU_FULL_CSG', 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 'SPI_PERF_RA_LDS_CU_FULL_ES', 'SPI_PERF_RA_LDS_CU_FULL_LS', + 'SPI_PERF_RA_LDS_CU_FULL_PS', 'SPI_PERF_RA_PIPE_REQ_BIN2', + 'SPI_PERF_RA_REQ_NO_ALLOC', 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 'SPI_PERF_RA_REQ_NO_ALLOC_HS', 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 'SPI_PERF_RA_REQ_NO_ALLOC_VS', 'SPI_PERF_RA_RES_STALL_CSG', + 'SPI_PERF_RA_RES_STALL_CSN', 'SPI_PERF_RA_RES_STALL_GS', + 'SPI_PERF_RA_RES_STALL_HS', 'SPI_PERF_RA_RES_STALL_PS', + 'SPI_PERF_RA_RES_STALL_VS', 'SPI_PERF_RA_RSV_UPD', + 'SPI_PERF_RA_SGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_SGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_SGPR_SIMD_FULL_GS', + 'SPI_PERF_RA_SGPR_SIMD_FULL_HS', 'SPI_PERF_RA_SGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_SGPR_SIMD_FULL_VS', 'SPI_PERF_RA_TASK_REQ_BIN3', + 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 'SPI_PERF_RA_TMP_STALL_CSG', 'SPI_PERF_RA_TMP_STALL_CSN', + 'SPI_PERF_RA_TMP_STALL_GS', 'SPI_PERF_RA_TMP_STALL_HS', + 'SPI_PERF_RA_TMP_STALL_PS', 'SPI_PERF_RA_TMP_STALL_VS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_VS', 'SPI_PERF_RA_VS_LOCK', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_VS', 'SPI_PERF_RA_WR_CTL_FULL', + 'SPI_PERF_RA_WVLIM_STALL_CSG', 'SPI_PERF_RA_WVLIM_STALL_CSN', + 'SPI_PERF_RA_WVLIM_STALL_GS', 'SPI_PERF_RA_WVLIM_STALL_HS', + 'SPI_PERF_RA_WVLIM_STALL_PS', 'SPI_PERF_RA_WVLIM_STALL_VS', + 'SPI_PERF_SWC_CSC_WR', 'SPI_PERF_SWC_CSG_WR', + 'SPI_PERF_SWC_GS_WR', 'SPI_PERF_SWC_HS_WR', 'SPI_PERF_SWC_PS_WR', + 'SPI_PERF_SWC_VS_WR', 'SPI_PERF_VS_ALLOC_CNT', 'SPI_PERF_VS_BUSY', + 'SPI_PERF_VS_CRAWLER_STALL', 'SPI_PERF_VS_EVENT_WAVE', + 'SPI_PERF_VS_FIRST_SUBGRP', 'SPI_PERF_VS_FIRST_WAVE', + 'SPI_PERF_VS_LAST_SUBGRP', 'SPI_PERF_VS_LAST_WAVE', + 'SPI_PERF_VS_LATE_ALLOC_ACCUM', 'SPI_PERF_VS_LATE_ALLOC_FULL', + 'SPI_PERF_VS_LSHS_DEALLOC', 'SPI_PERF_VS_PC_ALLOC_CNT', + 'SPI_PERF_VS_PC_STALL', 'SPI_PERF_VS_PERS_UPD_FULL0', + 'SPI_PERF_VS_PERS_UPD_FULL1', 'SPI_PERF_VS_POS0_STALL', + 'SPI_PERF_VS_POS1_STALL', 'SPI_PERF_VS_WAVE', + 'SPI_PERF_VS_WINDOW_VALID', 'SPI_PERF_VWC_CSC_WR', + 'SPI_PERF_VWC_CSG_WR', 'SPI_PERF_VWC_GS_WR', 'SPI_PERF_VWC_HS_WR', + 'SPI_PERF_VWC_PS_WR', 'SPI_PERF_VWC_VS_WR', + 'SPI_PNT_SPRITE_OVERRIDE', 'SPI_PNT_SPRITE_SEL_0', + 'SPI_PNT_SPRITE_SEL_1', 'SPI_PNT_SPRITE_SEL_NONE', + 'SPI_PNT_SPRITE_SEL_S', 'SPI_PNT_SPRITE_SEL_T', 'SPI_SAMPLE_CNTL', + 'SPI_SHADER_1COMP', 'SPI_SHADER_2COMP', 'SPI_SHADER_32_ABGR', + 'SPI_SHADER_32_AR', 'SPI_SHADER_32_GR', 'SPI_SHADER_32_R', + 'SPI_SHADER_4COMP', 'SPI_SHADER_4COMPRESS', + 'SPI_SHADER_EX_FORMAT', 'SPI_SHADER_FORMAT', + 'SPI_SHADER_FP16_ABGR', 'SPI_SHADER_NONE', + 'SPI_SHADER_SINT16_ABGR', 'SPI_SHADER_SNORM16_ABGR', + 'SPI_SHADER_UINT16_ABGR', 'SPI_SHADER_UNORM16_ABGR', + 'SPI_SHADER_ZERO', 'SPM_PERFMON_STATE', 'SPRITE_EN', + 'SP_PERF_SEL_DUMMY_BEGIN', 'SP_PERF_SEL_DUMMY_LAST', + 'SQC_PERF_SEL_DCACHE_ATOMIC', 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_NONZERO', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED', + 'SQC_PERF_SEL_DCACHE_FLAT_REQ', 'SQC_PERF_SEL_DCACHE_GCR', + 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', + 'SQC_PERF_SEL_DCACHE_GCR_WRITEBACK', 'SQC_PERF_SEL_DCACHE_HITS', + 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALIDB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READY', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_DCACHE_INVAL_INST', 'SQC_PERF_SEL_DCACHE_MISSES', + 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 'SQC_PERF_SEL_DCACHE_NONFLAT_REQ', 'SQC_PERF_SEL_DCACHE_REQ', + 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 'SQC_PERF_SEL_DCACHE_REQ_READ_8', 'SQC_PERF_SEL_DCACHE_REQ_TIME', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_1', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_2', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_4', + 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_UTCL0_ALL_REQ', + 'SQC_PERF_SEL_DCACHE_UTCL0_HIT_FIFO_FULL', + 'SQC_PERF_SEL_DCACHE_UTCL0_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_UTCL0_LFIFO_FULL', + 'SQC_PERF_SEL_DCACHE_UTCL0_PERMISSION_MISS', + 'SQC_PERF_SEL_DCACHE_UTCL0_REQUEST', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_LFIFO_NOT_RES', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_LRU_INFLIGHT', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_MISSFIFO_FULL', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_MULTI_MISS', + 'SQC_PERF_SEL_DCACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_HIT', + 'SQC_PERF_SEL_DCACHE_UTCL0_TRANSLATION_MISS', + 'SQC_PERF_SEL_DCACHE_UTCL0_UTCL1_INFLIGHT', + 'SQC_PERF_SEL_DCACHE_UTCL0_XNACK', + 'SQC_PERF_SEL_DCACHE_UTCL1_ALL_REQ', + 'SQC_PERF_SEL_DCACHE_UTCL1_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_WB_ASYNC', 'SQC_PERF_SEL_DCACHE_WB_INST', + 'SQC_PERF_SEL_DCACHE_WC_LRU_WRITE', + 'SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE', 'SQC_PERF_SEL_DUMMY_LAST', + 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF', + 'SQC_PERF_SEL_ICACHE_GCR', 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', 'SQC_PERF_SEL_ICACHE_HITS', + 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALIDB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READY', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_ICACHE_INVAL_INST', 'SQC_PERF_SEL_ICACHE_MISSES', + 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', 'SQC_PERF_SEL_ICACHE_REQ', + 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_UTCL0_ALL_REQ', + 'SQC_PERF_SEL_ICACHE_UTCL0_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_UTCL0_LFIFO_FULL', + 'SQC_PERF_SEL_ICACHE_UTCL0_PERMISSION_MISS', + 'SQC_PERF_SEL_ICACHE_UTCL0_REQUEST', + 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_LFIFO_NOT_RES', + 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_LRU_INFLIGHT', + 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_MISSFIFO_FULL', + 'SQC_PERF_SEL_ICACHE_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_HIT', + 'SQC_PERF_SEL_ICACHE_UTCL0_TRANSLATION_MISS', + 'SQC_PERF_SEL_ICACHE_UTCL0_UTCL1_INFLIGHT', + 'SQC_PERF_SEL_ICACHE_UTCL0_XNACK', + 'SQC_PERF_SEL_ICACHE_UTCL1_ALL_REQ', + 'SQC_PERF_SEL_ICACHE_UTCL1_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 'SQC_PERF_SEL_LDS_ADDR_STALL', 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 'SQC_PERF_SEL_LDS_CMD_FIFO_FULL', + 'SQC_PERF_SEL_LDS_DATA_FIFO_FULL', + 'SQC_PERF_SEL_LDS_DIRECT_FIFO_FULL_STALL', + 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', 'SQC_PERF_SEL_POWER_ALU_BUSY', + 'SQC_PERF_SEL_POWER_GPR_RD', 'SQC_PERF_SEL_POWER_GPR_WR', + 'SQC_PERF_SEL_POWER_LDS_BUSY', 'SQC_PERF_SEL_POWER_TEX_BUSY', + 'SQC_PERF_SEL_POWER_VALU', 'SQC_PERF_SEL_POWER_VALU0', + 'SQC_PERF_SEL_POWER_VALU1', 'SQC_PERF_SEL_POWER_VALU2', + 'SQC_PERF_SEL_PT_POWER_STALL', 'SQC_PERF_SEL_SQ_DCACHE_REQS', + 'SQC_PERF_SEL_TC_DATA_ATOMIC_REQ', + 'SQC_PERF_SEL_TC_DATA_READ_REQ', 'SQC_PERF_SEL_TC_DATA_WRITE_REQ', + 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', 'SQC_PERF_SEL_TC_INST_REQ', + 'SQC_PERF_SEL_TC_REQ', 'SQC_PERF_SEL_TC_STALL', + 'SQC_PERF_SEL_TC_STARVE', 'SQDEC_BEGIN', 'SQDEC_END', + 'SQGFXUDEC_BEGIN', 'SQGFXUDEC_END', 'SQG_PERF_SEL_DUMMY_LAST', + 'SQG_PERF_SEL_TLB_SHOOTDOWN', 'SQG_PERF_SEL_TLB_SHOOTDOWN_CYCLES', + 'SQG_PERF_SEL_TTRACE_INFLIGHT_REQS', + 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', 'SQG_PERF_SEL_TTRACE_REQS', + 'SQG_PERF_SEL_TTRACE_STALL', 'SQG_PERF_SEL_UTCL0_HIT_FIFO_FULL', + 'SQG_PERF_SEL_UTCL0_LFIFO_FULL', + 'SQG_PERF_SEL_UTCL0_PERMISSION_MISS', + 'SQG_PERF_SEL_UTCL0_REQUEST', + 'SQG_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 'SQG_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 'SQG_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 'SQG_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 'SQG_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'SQG_PERF_SEL_UTCL0_TRANSLATION_HIT', + 'SQG_PERF_SEL_UTCL0_TRANSLATION_MISS', + 'SQG_PERF_SEL_UTCL0_UTCL1_REQ', 'SQIND_GLOBAL_REGS_OFFSET', + 'SQIND_GLOBAL_REGS_SIZE', 'SQIND_LOCAL_REGS_OFFSET', + 'SQIND_LOCAL_REGS_SIZE', 'SQIND_WAVE_HWREGS_OFFSET', + 'SQIND_WAVE_HWREGS_SIZE', 'SQIND_WAVE_SGPRS_OFFSET', + 'SQIND_WAVE_SGPRS_SIZE', 'SQIND_WAVE_VGPRS_OFFSET', + 'SQIND_WAVE_VGPRS_SIZE', 'SQPERFDDEC_BEGIN', 'SQPERFDDEC_END', + 'SQPERFSDEC_BEGIN', 'SQPERFSDEC_END', 'SQPWRDEC_BEGIN', + 'SQPWRDEC_END', 'SQ_CAC_POWER_ALU_BUSY', 'SQ_CAC_POWER_GPR_RD', + 'SQ_CAC_POWER_GPR_WR', 'SQ_CAC_POWER_LDS_BUSY', + 'SQ_CAC_POWER_SEL', 'SQ_CAC_POWER_TEX_BUSY', 'SQ_CAC_POWER_VALU', + 'SQ_CAC_POWER_VALU0', 'SQ_CAC_POWER_VALU1', 'SQ_CAC_POWER_VALU2', + 'SQ_DISPATCHER_GFX_CNT_PER_RING', 'SQ_DISPATCHER_GFX_MIN', + 'SQ_EDC_FUE_CNTL_LDS', 'SQ_EDC_FUE_CNTL_SIMD0', + 'SQ_EDC_FUE_CNTL_SIMD1', 'SQ_EDC_FUE_CNTL_SIMD2', + 'SQ_EDC_FUE_CNTL_SIMD3', 'SQ_EDC_FUE_CNTL_SQ', + 'SQ_EDC_FUE_CNTL_TA', 'SQ_EDC_FUE_CNTL_TCP', 'SQ_EDC_FUE_CNTL_TD', + 'SQ_EDC_INFO_SOURCE', 'SQ_EDC_INFO_SOURCE_GDS', + 'SQ_EDC_INFO_SOURCE_INST', 'SQ_EDC_INFO_SOURCE_INVALID', + 'SQ_EDC_INFO_SOURCE_LDS', 'SQ_EDC_INFO_SOURCE_SGPR', + 'SQ_EDC_INFO_SOURCE_TA', 'SQ_EDC_INFO_SOURCE_VGPR', + 'SQ_EX_MODE_EXCP_ADDR_WATCH0', 'SQ_EX_MODE_EXCP_DIV0', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH1', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH2', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH3', 'SQ_EX_MODE_EXCP_INEXACT', + 'SQ_EX_MODE_EXCP_INPUT_DENORM', 'SQ_EX_MODE_EXCP_INT_DIV0', + 'SQ_EX_MODE_EXCP_INVALID', 'SQ_EX_MODE_EXCP_MEM_VIOL', + 'SQ_EX_MODE_EXCP_OVERFLOW', 'SQ_EX_MODE_EXCP_UNDERFLOW', + 'SQ_EX_MODE_EXCP_VALU_BASE', 'SQ_EX_MODE_EXCP_VALU_SIZE', + 'SQ_GFXDEC_BEGIN', 'SQ_GFXDEC_END', 'SQ_GFXDEC_STATE_ID_SHIFT', + 'SQ_IBUF_IB_DRET', 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 'SQ_IBUF_IB_EMPTY_WAIT_GNT', 'SQ_IBUF_IB_IDLE', + 'SQ_IBUF_IB_INI_WAIT_DRET', 'SQ_IBUF_IB_INI_WAIT_GNT', + 'SQ_IBUF_IB_LE_4DW', 'SQ_IBUF_IB_WAIT_DRET', 'SQ_IBUF_ST', + 'SQ_IMG_FILTER_MODE_BLEND', 'SQ_IMG_FILTER_MODE_MAX', + 'SQ_IMG_FILTER_MODE_MIN', 'SQ_IMG_FILTER_TYPE', 'SQ_IND_CMD_CMD', + 'SQ_IND_CMD_CMD_DEBUG', 'SQ_IND_CMD_CMD_KILL', + 'SQ_IND_CMD_CMD_NULL', 'SQ_IND_CMD_CMD_SAVECTX', + 'SQ_IND_CMD_CMD_SETFATALHALT', 'SQ_IND_CMD_CMD_SETHALT', + 'SQ_IND_CMD_CMD_SET_SPI_PRIO', 'SQ_IND_CMD_CMD_SINGLE_STEP', + 'SQ_IND_CMD_CMD_TRAP', 'SQ_IND_CMD_MODE', + 'SQ_IND_CMD_MODE_BROADCAST', 'SQ_IND_CMD_MODE_BROADCAST_ME', + 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', 'SQ_IND_CMD_MODE_SINGLE', + 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', 'SQ_INST_STR_IB_WAVE_NORML', + 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', + 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST0', + 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST1', 'SQ_INST_STR_ST', + 'SQ_INTERRUPT_WORD_ENCODING', 'SQ_INTERRUPT_WORD_ENCODING_AUTO', + 'SQ_INTERRUPT_WORD_ENCODING_ERROR', + 'SQ_INTERRUPT_WORD_ENCODING_INST', 'SQ_MAX_PGM_SGPRS', + 'SQ_MAX_PGM_VGPRS', 'SQ_NON_EVENT', 'SQ_OOB_COMPLETE', + 'SQ_OOB_INDEX_AND_OFFSET', 'SQ_OOB_INDEX_ONLY', + 'SQ_OOB_NUM_RECORDS_0', 'SQ_OOB_SELECT', 'SQ_PERF_SEL', + 'SQ_PERF_SEL_ACCUM_PREV', 'SQ_PERF_SEL_BUSY_CYCLES', + 'SQ_PERF_SEL_CYCLES', 'SQ_PERF_SEL_DUMMY_END', + 'SQ_PERF_SEL_DUMMY_LAST', 'SQ_PERF_SEL_EVENTS', + 'SQ_PERF_SEL_EXP_BUS0_BUSY', 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 'SQ_PERF_SEL_IFETCH_LEVEL', 'SQ_PERF_SEL_IFETCH_REQS', + 'SQ_PERF_SEL_IFETCH_XNACK', 'SQ_PERF_SEL_INSTS_ALL', + 'SQ_PERF_SEL_INSTS_BRANCH', 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', + 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS', 'SQ_PERF_SEL_INSTS_EXP', + 'SQ_PERF_SEL_INSTS_EXP_GDS', 'SQ_PERF_SEL_INSTS_FLAT', + 'SQ_PERF_SEL_INSTS_FLAT_REPLAY', 'SQ_PERF_SEL_INSTS_GDS', + 'SQ_PERF_SEL_INSTS_LDS', 'SQ_PERF_SEL_INSTS_SALU', + 'SQ_PERF_SEL_INSTS_SENDMSG', 'SQ_PERF_SEL_INSTS_SMEM', + 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 'SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY', + 'SQ_PERF_SEL_INSTS_SMEM_REPLAY', 'SQ_PERF_SEL_INSTS_TEX', + 'SQ_PERF_SEL_INSTS_TEX_LOAD', 'SQ_PERF_SEL_INSTS_TEX_REPLAY', + 'SQ_PERF_SEL_INSTS_TEX_STORE', 'SQ_PERF_SEL_INSTS_VALU', + 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 'SQ_PERF_SEL_INSTS_VALU_LDS_DIRECT_RD', + 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 'SQ_PERF_SEL_INSTS_VALU_VINTRP_OP', 'SQ_PERF_SEL_INSTS_WAVE32', + 'SQ_PERF_SEL_INSTS_WAVE32_FLAT', 'SQ_PERF_SEL_INSTS_WAVE32_LDS', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32', + 'SQ_PERF_SEL_INST_CACHE_REQS', 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', + 'SQ_PERF_SEL_INST_CYCLES_EXP_GDS', 'SQ_PERF_SEL_INST_CYCLES_FLAT', + 'SQ_PERF_SEL_INST_CYCLES_LDS', 'SQ_PERF_SEL_INST_CYCLES_TEX', + 'SQ_PERF_SEL_INST_CYCLES_VALU', + 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 'SQ_PERF_SEL_INST_LEVEL_EXP', 'SQ_PERF_SEL_INST_LEVEL_GDS', + 'SQ_PERF_SEL_INST_LEVEL_LDS', 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', 'SQ_PERF_SEL_ITEMS', + 'SQ_PERF_SEL_ITEM_CYCLES_VALU', + 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_LEVEL_WAVES', + 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_SALU', + 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VALU', + 'SQ_PERF_SEL_MIXED_SUBSEQUENT_ISSUES_VMEM', 'SQ_PERF_SEL_MSG', + 'SQ_PERF_SEL_MSG_BUS_BUSY', 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 'SQ_PERF_SEL_MSG_GSCNT', 'SQ_PERF_SEL_MSG_INTERRUPT', + 'SQ_PERF_SEL_NONE', 'SQ_PERF_SEL_QUADS', 'SQ_PERF_SEL_Reserved_1', + 'SQ_PERF_SEL_Reserved_10', 'SQ_PERF_SEL_Reserved_11', + 'SQ_PERF_SEL_Reserved_12', 'SQ_PERF_SEL_Reserved_13', + 'SQ_PERF_SEL_Reserved_14', 'SQ_PERF_SEL_Reserved_15', + 'SQ_PERF_SEL_Reserved_16', 'SQ_PERF_SEL_Reserved_17', + 'SQ_PERF_SEL_Reserved_18', 'SQ_PERF_SEL_Reserved_2', + 'SQ_PERF_SEL_Reserved_3', 'SQ_PERF_SEL_Reserved_4', + 'SQ_PERF_SEL_Reserved_5', 'SQ_PERF_SEL_Reserved_6', + 'SQ_PERF_SEL_Reserved_7', 'SQ_PERF_SEL_Reserved_8', + 'SQ_PERF_SEL_Reserved_9', 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 'SQ_PERF_SEL_SALU_PIPE_STALL', 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL', + 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_STALL', 'SQ_PERF_SEL_USER0', + 'SQ_PERF_SEL_USER1', 'SQ_PERF_SEL_USER10', 'SQ_PERF_SEL_USER11', + 'SQ_PERF_SEL_USER12', 'SQ_PERF_SEL_USER13', 'SQ_PERF_SEL_USER14', + 'SQ_PERF_SEL_USER15', 'SQ_PERF_SEL_USER2', 'SQ_PERF_SEL_USER3', + 'SQ_PERF_SEL_USER4', 'SQ_PERF_SEL_USER5', 'SQ_PERF_SEL_USER6', + 'SQ_PERF_SEL_USER7', 'SQ_PERF_SEL_USER8', 'SQ_PERF_SEL_USER9', + 'SQ_PERF_SEL_USER_LEVEL0', 'SQ_PERF_SEL_USER_LEVEL1', + 'SQ_PERF_SEL_USER_LEVEL10', 'SQ_PERF_SEL_USER_LEVEL11', + 'SQ_PERF_SEL_USER_LEVEL12', 'SQ_PERF_SEL_USER_LEVEL13', + 'SQ_PERF_SEL_USER_LEVEL14', 'SQ_PERF_SEL_USER_LEVEL15', + 'SQ_PERF_SEL_USER_LEVEL2', 'SQ_PERF_SEL_USER_LEVEL3', + 'SQ_PERF_SEL_USER_LEVEL4', 'SQ_PERF_SEL_USER_LEVEL5', + 'SQ_PERF_SEL_USER_LEVEL6', 'SQ_PERF_SEL_USER_LEVEL7', + 'SQ_PERF_SEL_USER_LEVEL8', 'SQ_PERF_SEL_USER_LEVEL9', + 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 'SQ_PERF_SEL_VALU_RETURN_SDST', + 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', + 'SQ_PERF_SEL_VMEM_BUS_STALL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_SECOND_TRY_STALL', + 'SQ_PERF_SEL_VMEM_SECOND_TRY_USED', + 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', 'SQ_PERF_SEL_WAIT_ANY', + 'SQ_PERF_SEL_WAIT_BARRIER', 'SQ_PERF_SEL_WAIT_CNT_ANY', + 'SQ_PERF_SEL_WAIT_CNT_EXP', 'SQ_PERF_SEL_WAIT_CNT_LGKM', + 'SQ_PERF_SEL_WAIT_CNT_VMVS', 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 'SQ_PERF_SEL_WAIT_IFETCH', 'SQ_PERF_SEL_WAIT_INST_ANY', + 'SQ_PERF_SEL_WAIT_INST_BR_MSG', 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', + 'SQ_PERF_SEL_WAIT_INST_FLAT', 'SQ_PERF_SEL_WAIT_INST_LDS', + 'SQ_PERF_SEL_WAIT_INST_SCA', 'SQ_PERF_SEL_WAIT_INST_TEX', + 'SQ_PERF_SEL_WAIT_INST_VALU', 'SQ_PERF_SEL_WAIT_INST_VMEM', + 'SQ_PERF_SEL_WAIT_OTHER', 'SQ_PERF_SEL_WAIT_SLEEP', + 'SQ_PERF_SEL_WAIT_SLEEP_XNACK', 'SQ_PERF_SEL_WAIT_TTRACE', + 'SQ_PERF_SEL_WAVE32_INSTS', 'SQ_PERF_SEL_WAVE32_ITEMS', + 'SQ_PERF_SEL_WAVE64_HALF_SKIP', 'SQ_PERF_SEL_WAVE64_INSTS', + 'SQ_PERF_SEL_WAVE64_ITEMS', 'SQ_PERF_SEL_WAVES', + 'SQ_PERF_SEL_WAVES_32', 'SQ_PERF_SEL_WAVES_64', + 'SQ_PERF_SEL_WAVES_EQ_64', 'SQ_PERF_SEL_WAVES_LT_16', + 'SQ_PERF_SEL_WAVES_LT_32', 'SQ_PERF_SEL_WAVES_LT_48', + 'SQ_PERF_SEL_WAVES_LT_64', 'SQ_PERF_SEL_WAVES_RESTORED', + 'SQ_PERF_SEL_WAVES_SAVED', 'SQ_PERF_SEL_WAVE_CYCLES', + 'SQ_PERF_SEL_WAVE_READY', 'SQ_PERF_SEL_XNACK_ALL', + 'SQ_PERF_SEL_XNACK_FIRST', 'SQ_ROUND_MINUS_INFINITY', + 'SQ_ROUND_MODE', 'SQ_ROUND_NEAREST_EVEN', + 'SQ_ROUND_PLUS_INFINITY', 'SQ_ROUND_TO_ZERO', 'SQ_RSRC_BUF', + 'SQ_RSRC_BUF_RSVD_1', 'SQ_RSRC_BUF_RSVD_2', 'SQ_RSRC_BUF_RSVD_3', + 'SQ_RSRC_BUF_TYPE', 'SQ_RSRC_FLAT', 'SQ_RSRC_FLAT_RSVD_0', + 'SQ_RSRC_FLAT_RSVD_2', 'SQ_RSRC_FLAT_RSVD_3', 'SQ_RSRC_FLAT_TYPE', + 'SQ_RSRC_IMG_1D', 'SQ_RSRC_IMG_1D_ARRAY', 'SQ_RSRC_IMG_2D', + 'SQ_RSRC_IMG_2D_ARRAY', 'SQ_RSRC_IMG_2D_MSAA', + 'SQ_RSRC_IMG_2D_MSAA_ARRAY', 'SQ_RSRC_IMG_3D', 'SQ_RSRC_IMG_CUBE', + 'SQ_RSRC_IMG_RSVD_0', 'SQ_RSRC_IMG_RSVD_1', 'SQ_RSRC_IMG_RSVD_2', + 'SQ_RSRC_IMG_RSVD_3', 'SQ_RSRC_IMG_RSVD_4', 'SQ_RSRC_IMG_RSVD_5', + 'SQ_RSRC_IMG_RSVD_6', 'SQ_RSRC_IMG_RSVD_7', 'SQ_RSRC_IMG_TYPE', + 'SQ_SEL_0', 'SQ_SEL_1', 'SQ_SEL_N_BC_1', 'SQ_SEL_RESERVED_1', + 'SQ_SEL_W', 'SQ_SEL_X', 'SQ_SEL_XYZW01', 'SQ_SEL_Y', 'SQ_SEL_Z', + 'SQ_TEX_ANISO_RATIO', 'SQ_TEX_ANISO_RATIO_1', + 'SQ_TEX_ANISO_RATIO_16', 'SQ_TEX_ANISO_RATIO_2', + 'SQ_TEX_ANISO_RATIO_4', 'SQ_TEX_ANISO_RATIO_8', + 'SQ_TEX_BORDER_COLOR', 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 'SQ_TEX_BORDER_COLOR_REGISTER', 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 'SQ_TEX_CLAMP', 'SQ_TEX_CLAMP_BORDER', 'SQ_TEX_CLAMP_HALF_BORDER', + 'SQ_TEX_CLAMP_LAST_TEXEL', 'SQ_TEX_DEPTH_COMPARE', + 'SQ_TEX_DEPTH_COMPARE_ALWAYS', 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 'SQ_TEX_DEPTH_COMPARE_GREATER', + 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', 'SQ_TEX_DEPTH_COMPARE_LESS', + 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', 'SQ_TEX_DEPTH_COMPARE_NEVER', + 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', 'SQ_TEX_MIP_FILTER', + 'SQ_TEX_MIP_FILTER_LINEAR', 'SQ_TEX_MIP_FILTER_NONE', + 'SQ_TEX_MIP_FILTER_POINT', 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', + 'SQ_TEX_MIRROR', 'SQ_TEX_MIRROR_ONCE_BORDER', + 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 'SQ_TEX_WRAP', 'SQ_TEX_XY_FILTER', + 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', 'SQ_TEX_XY_FILTER_ANISO_POINT', + 'SQ_TEX_XY_FILTER_BILINEAR', 'SQ_TEX_XY_FILTER_POINT', + 'SQ_TEX_Z_FILTER', 'SQ_TEX_Z_FILTER_LINEAR', + 'SQ_TEX_Z_FILTER_NONE', 'SQ_TEX_Z_FILTER_POINT', + 'SQ_TT_INST_EXCLUDE_EXPGNT234', + 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD', 'SQ_TT_MODE', + 'SQ_TT_MODE_DETAIL', 'SQ_TT_MODE_GLOBAL', 'SQ_TT_MODE_OFF', + 'SQ_TT_MODE_ON', 'SQ_TT_RT_FREQ', 'SQ_TT_RT_FREQ_1024_CLK', + 'SQ_TT_RT_FREQ_4096_CLK', 'SQ_TT_RT_FREQ_NEVER', + 'SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_IMMED1_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_INST_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT', 'SQ_TT_TOKEN_EXCLUDE_REG_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT', 'SQ_TT_TOKEN_MASK_COMP_BIT', + 'SQ_TT_TOKEN_MASK_COMP_SHIFT', 'SQ_TT_TOKEN_MASK_CONFIG_BIT', + 'SQ_TT_TOKEN_MASK_CONFIG_SHIFT', 'SQ_TT_TOKEN_MASK_CONTEXT_BIT', + 'SQ_TT_TOKEN_MASK_CONTEXT_SHIFT', 'SQ_TT_TOKEN_MASK_GFXUDEC_BIT', + 'SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT', 'SQ_TT_TOKEN_MASK_INST_EXCLUDE', + 'SQ_TT_TOKEN_MASK_OTHER_BIT', 'SQ_TT_TOKEN_MASK_OTHER_SHIFT', + 'SQ_TT_TOKEN_MASK_READS_BIT', 'SQ_TT_TOKEN_MASK_READS_SHIFT', + 'SQ_TT_TOKEN_MASK_REG_INCLUDE', + 'SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT', + 'SQ_TT_TOKEN_MASK_SHDEC_BIT', 'SQ_TT_TOKEN_MASK_SHDEC_SHIFT', + 'SQ_TT_TOKEN_MASK_SQDEC_BIT', 'SQ_TT_TOKEN_MASK_SQDEC_SHIFT', + 'SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT', 'SQ_TT_UTIL_TIMER', + 'SQ_TT_UTIL_TIMER_100_CLK', 'SQ_TT_UTIL_TIMER_250_CLK', + 'SQ_TT_WAVESTART_MODE', 'SQ_TT_WAVESTART_MODE_ALLOC', + 'SQ_TT_WAVESTART_MODE_PBB_ID', 'SQ_TT_WAVESTART_MODE_SHORT', + 'SQ_TT_WTYPE_INCLUDE', 'SQ_TT_WTYPE_INCLUDE_CS_BIT', + 'SQ_TT_WTYPE_INCLUDE_CS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_ES_BIT', + 'SQ_TT_WTYPE_INCLUDE_ES_SHIFT', 'SQ_TT_WTYPE_INCLUDE_GS_BIT', + 'SQ_TT_WTYPE_INCLUDE_GS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_HS_BIT', + 'SQ_TT_WTYPE_INCLUDE_HS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_LS_BIT', + 'SQ_TT_WTYPE_INCLUDE_LS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_PS_BIT', + 'SQ_TT_WTYPE_INCLUDE_PS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_SHIFT', + 'SQ_TT_WTYPE_INCLUDE_VS_BIT', 'SQ_TT_WTYPE_INCLUDE_VS_SHIFT', + 'SQ_WATCH_MODES', 'SQ_WATCH_MODE_ALL', 'SQ_WATCH_MODE_ATOMIC', + 'SQ_WATCH_MODE_NONREAD', 'SQ_WATCH_MODE_READ', + 'SQ_WAVE_IB_ECC_CLEAN', 'SQ_WAVE_IB_ECC_ERR_CONTINUE', + 'SQ_WAVE_IB_ECC_ERR_HALT', 'SQ_WAVE_IB_ECC_ST', + 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', 'SQ_WAVE_SCHED_MODES', + 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST', 'SQ_WAVE_SCHED_MODE_EXPERT', + 'SQ_WAVE_SCHED_MODE_NORMAL', 'SQ_WAVE_TYPE', 'SQ_WAVE_TYPE_CS', + 'SQ_WAVE_TYPE_ES', 'SQ_WAVE_TYPE_GS', 'SQ_WAVE_TYPE_HS', + 'SQ_WAVE_TYPE_LS', 'SQ_WAVE_TYPE_PS', 'SQ_WAVE_TYPE_PS0', + 'SQ_WAVE_TYPE_PS1', 'SQ_WAVE_TYPE_PS2', 'SQ_WAVE_TYPE_PS3', + 'SQ_WAVE_TYPE_VS', 'STALL', 'STATIC_SCREEN_SMU_INTR', + 'STATIC_SCREEN_SMU_INTR_NOOP', 'STENCIL_8', 'STENCIL_ADD_CLAMP', + 'STENCIL_ADD_WRAP', 'STENCIL_AND', 'STENCIL_INVALID', + 'STENCIL_INVERT', 'STENCIL_KEEP', 'STENCIL_NAND', 'STENCIL_NOR', + 'STENCIL_ONES', 'STENCIL_OR', 'STENCIL_REPLACE_OP', + 'STENCIL_REPLACE_TEST', 'STENCIL_SUB_CLAMP', 'STENCIL_SUB_WRAP', + 'STENCIL_XNOR', 'STENCIL_XOR', 'STENCIL_ZERO', 'STEREO_DISABLED', + 'STREAM_0_SYNCHRONIZATION', + 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_10_SYNCHRONIZATION', + 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION', + 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION', + 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION', + 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION', + 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION', + 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_1_SYNCHRONIZATION', + 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_2_SYNCHRONIZATION', + 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_3_SYNCHRONIZATION', + 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_4_SYNCHRONIZATION', + 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_5_SYNCHRONIZATION', + 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_6_SYNCHRONIZATION', + 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION', + 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION', + 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION', + 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'STRM_PERFMON_STATE_RESERVED_3', + 'STRM_PERFMON_STATE_START_COUNTING', + 'STRM_PERFMON_STATE_STOP_COUNTING', 'SURFACE_DCC', + 'SURFACE_DCC_IND_64B', 'SURFACE_DCC_IS_IND_64B', + 'SURFACE_DCC_IS_NOT_IND_64B', 'SURFACE_FLIP_AWAY_INT_LEVEL', + 'SURFACE_FLIP_AWAY_INT_PULSE', 'SURFACE_FLIP_AWAY_INT_TYPE', + 'SURFACE_FLIP_INT_LEVEL', 'SURFACE_FLIP_INT_PULSE', + 'SURFACE_FLIP_INT_TYPE', 'SURFACE_FLIP_IN_STEREOSYNC', + 'SURFACE_FLIP_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', + 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLED', + 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 'SURFACE_FLIP_TYPE', 'SURFACE_FLIP_VUPDATE_SKIP_NUM', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', 'SURFACE_INUSE_IS_LATCHED', + 'SURFACE_INUSE_IS_NOT_LATCHED', 'SURFACE_INUSE_RAED_NO_LATCH', + 'SURFACE_IS_DCC', 'SURFACE_IS_NOT_DCC', 'SURFACE_IS_NOT_TMZ', + 'SURFACE_IS_TMZ', 'SURFACE_I_FLIP', 'SURFACE_PIXEL_FORMAT', + 'SURFACE_TMZ', 'SURFACE_UPDATE_IS_LOCKED', + 'SURFACE_UPDATE_IS_UNLOCKED', 'SURFACE_UPDATE_LOCK', + 'SURFACE_V_FLIP', 'SURF_16_BANK', 'SURF_2_BANK', 'SURF_4_BANK', + 'SURF_8_BANK', 'SURF_BANK_HEIGHT_1', 'SURF_BANK_HEIGHT_2', + 'SURF_BANK_HEIGHT_4', 'SURF_BANK_HEIGHT_8', 'SURF_BANK_WIDTH_1', + 'SURF_BANK_WIDTH_2', 'SURF_BANK_WIDTH_4', 'SURF_BANK_WIDTH_8', + 'SURF_MACRO_ASPECT_1', 'SURF_MACRO_ASPECT_2', + 'SURF_MACRO_ASPECT_4', 'SURF_MACRO_ASPECT_8', + 'SURF_TILE_SPLIT_128B', 'SURF_TILE_SPLIT_1KB', + 'SURF_TILE_SPLIT_256B', 'SURF_TILE_SPLIT_2KB', + 'SURF_TILE_SPLIT_4KB', 'SURF_TILE_SPLIT_512B', + 'SURF_TILE_SPLIT_64B', 'SU_PERFCNT_SEL', 'SWAP_ALT', + 'SWAP_ALT_REV', 'SWAP_STD', 'SWAP_STD_REV', 'SWATH_HEIGHT', + 'SWATH_HEIGHT_16L', 'SWATH_HEIGHT_1L', 'SWATH_HEIGHT_2L', + 'SWATH_HEIGHT_4L', 'SWATH_HEIGHT_8L', 'SWIZZLE_4KB_D', + 'SWIZZLE_4KB_D_X', 'SWIZZLE_4KB_S', 'SWIZZLE_4KB_S_X', + 'SWIZZLE_64KB_D', 'SWIZZLE_64KB_D_T', 'SWIZZLE_64KB_D_X', + 'SWIZZLE_64KB_R_X', 'SWIZZLE_64KB_S', 'SWIZZLE_64KB_S_T', + 'SWIZZLE_64KB_S_X', 'SWIZZLE_LINEAR', 'SWIZZLE_MODE_ENUM', + 'SWIZZLE_TYPE_ENUM', 'SWIZZLE_VAR_D', 'SWIZZLE_VAR_D_X', + 'SWIZZLE_VAR_S', 'SWIZZLE_VAR_S_X', 'SW_256B_D', 'SW_256B_R', + 'SW_256B_S', 'SW_4KB_D', 'SW_4KB_D_X', 'SW_4KB_R', 'SW_4KB_R_X', + 'SW_4KB_S', 'SW_4KB_S_X', 'SW_4KB_Z', 'SW_4KB_Z_X', 'SW_64KB_D', + 'SW_64KB_D_T', 'SW_64KB_D_X', 'SW_64KB_R', 'SW_64KB_R_T', + 'SW_64KB_R_X', 'SW_64KB_S', 'SW_64KB_S_T', 'SW_64KB_S_X', + 'SW_64KB_Z', 'SW_64KB_Z_T', 'SW_64KB_Z_X', 'SW_D', 'SW_L', + 'SW_LINEAR', 'SW_MODE', 'SW_R', 'SW_S', 'SW_VAR_D', 'SW_VAR_D_X', + 'SW_VAR_R', 'SW_VAR_R_X', 'SW_VAR_S', 'SW_VAR_S_X', 'SW_VAR_Z', + 'SW_VAR_Z_X', 'SW_Z', 'SX_BLEND_OPT', 'SX_CB_RAT_ACK_REQUEST', + 'SX_DOWNCONVERT_FORMAT', 'SX_OPT_COMB_FCN', 'SX_PERFCOUNTER_VALS', + 'SX_PERF_SEL_CLOCK', 'SX_PERF_SEL_CLOCK_DROP_STALL', + 'SX_PERF_SEL_COL_BUSY', 'SX_PERF_SEL_COL_SCBD0_STALL', + 'SX_PERF_SEL_COL_SCBD1_STALL', 'SX_PERF_SEL_COL_SCBD_STALL', + 'SX_PERF_SEL_DB0_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB0_HALF_QUADS', + 'SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB0_PIXELS', + 'SX_PERF_SEL_DB0_PIXEL_IDLE', 'SX_PERF_SEL_DB0_PIXEL_STALL', + 'SX_PERF_SEL_DB0_PRED_PIXELS', 'SX_PERF_SEL_DB0_SIZE', + 'SX_PERF_SEL_DB1_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB1_HALF_QUADS', + 'SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB1_PIXELS', + 'SX_PERF_SEL_DB1_PIXEL_IDLE', 'SX_PERF_SEL_DB1_PIXEL_STALL', + 'SX_PERF_SEL_DB1_PRED_PIXELS', 'SX_PERF_SEL_DB1_SIZE', + 'SX_PERF_SEL_DB2_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB2_HALF_QUADS', + 'SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB2_PIXELS', + 'SX_PERF_SEL_DB2_PIXEL_IDLE', 'SX_PERF_SEL_DB2_PIXEL_STALL', + 'SX_PERF_SEL_DB2_PRED_PIXELS', 'SX_PERF_SEL_DB2_SIZE', + 'SX_PERF_SEL_DB3_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB3_HALF_QUADS', + 'SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB3_PIXELS', + 'SX_PERF_SEL_DB3_PIXEL_IDLE', 'SX_PERF_SEL_DB3_PIXEL_STALL', + 'SX_PERF_SEL_DB3_PRED_PIXELS', 'SX_PERF_SEL_DB3_SIZE', + 'SX_PERF_SEL_GATE_EN1', 'SX_PERF_SEL_GATE_EN2', + 'SX_PERF_SEL_GATE_EN3', 'SX_PERF_SEL_GATE_EN4', + 'SX_PERF_SEL_GATE_EN5', 'SX_PERF_SEL_GATE_EN6', + 'SX_PERF_SEL_GATE_EN7', 'SX_PERF_SEL_GATE_EN8', + 'SX_PERF_SEL_IDX_BUSY', 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 'SX_PERF_SEL_IDX_REQ', 'SX_PERF_SEL_IDX_REQ_LATENCY', + 'SX_PERF_SEL_IDX_RET', 'SX_PERF_SEL_IDX_SCBD_STALL', + 'SX_PERF_SEL_IDX_STALL_CYCLES', 'SX_PERF_SEL_PA_IDLE_CYCLES', + 'SX_PERF_SEL_PA_POS', 'SX_PERF_SEL_PA_REQ', + 'SX_PERF_SEL_PA_REQ_LATENCY', 'SX_PERF_SEL_POS_BUSY', + 'SX_PERF_SEL_POS_SCBD_STALL', 'SX_PERF_SEL_SH_COLOR_STALL', + 'SX_PERF_SEL_SH_COLOR_STARVE', 'SX_PERF_SEL_SH_IDX_STARVE', + 'SX_PERF_SEL_SH_POS_STALL', 'SX_PERF_SEL_SH_POS_STARVE', + 'SX_PERF_SEL_SPLITMODE', 'SX_RT_EXPORT_10_11_11', + 'SX_RT_EXPORT_16_16_AR', 'SX_RT_EXPORT_16_16_GR', + 'SX_RT_EXPORT_1_5_5_5', 'SX_RT_EXPORT_2_10_10_10', + 'SX_RT_EXPORT_32_A', 'SX_RT_EXPORT_32_R', 'SX_RT_EXPORT_4_4_4_4', + 'SX_RT_EXPORT_5_6_5', 'SX_RT_EXPORT_8_8_8_8', + 'SX_RT_EXPORT_NO_CONVERSION', 'SYMCLK_FE_FORCE_EN', + 'SYMCLK_FE_FORCE_EN_DISABLE', 'SYMCLK_FE_FORCE_EN_ENABLE', + 'SYMCLK_FE_FORCE_SRC', 'SYMCLK_FE_FORCE_SRC_RESERVED', + 'SYMCLK_FE_FORCE_SRC_UNIPHYA', 'SYMCLK_FE_FORCE_SRC_UNIPHYB', + 'SYMCLK_FE_FORCE_SRC_UNIPHYC', 'SYMCLK_FE_FORCE_SRC_UNIPHYD', + 'SYMCLK_FE_FORCE_SRC_UNIPHYE', 'SYMCLK_FE_FORCE_SRC_UNIPHYF', + 'SampleSplit', 'SampleSplitBytes', 'ScMap', + 'ScUncertaintyRegionMode', 'ScXsel', 'ScYsel', 'SeEnable', + 'SeMap', 'SePairMap', 'SePairXsel', 'SePairYsel', 'SeXsel', + 'SeYsel', 'ShaderEngineTileSize', 'SourceFormat', 'Spare_261', + 'Spare_285', 'Spare_286', 'StencilFormat', 'StencilOp', + 'SurfaceArray', 'SurfaceEndian', 'SurfaceFormat', 'SurfaceNumber', + 'SurfaceSwap', 'SurfaceTiling', 'TA_PERFCOUNT_SEL', + 'TA_PERF_SEL_NULL', 'TA_PERF_SEL_RESERVED_29', + 'TA_PERF_SEL_RESERVED_41', 'TA_PERF_SEL_RESERVED_42', + 'TA_PERF_SEL_RESERVED_43', + 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 'TA_PERF_SEL_addresser_busy', 'TA_PERF_SEL_addresser_fifo_busy', + 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 'TA_PERF_SEL_addresser_stalled_cycles', + 'TA_PERF_SEL_aligner_busy', 'TA_PERF_SEL_aligner_cycles', + 'TA_PERF_SEL_aniso_10_cycle_quads', + 'TA_PERF_SEL_aniso_12_cycle_quads', + 'TA_PERF_SEL_aniso_14_cycle_quads', + 'TA_PERF_SEL_aniso_16_cycle_quads', + 'TA_PERF_SEL_aniso_1_cycle_quads', + 'TA_PERF_SEL_aniso_2_cycle_quads', + 'TA_PERF_SEL_aniso_4_cycle_quads', + 'TA_PERF_SEL_aniso_6_cycle_quads', + 'TA_PERF_SEL_aniso_8_cycle_quads', + 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 'TA_PERF_SEL_aniso_stalled_cycles', + 'TA_PERF_SEL_bilin_point_1_cycle_pixels', + 'TA_PERF_SEL_buffer_atomic_wavefronts', + 'TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles', + 'TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles', + 'TA_PERF_SEL_buffer_coalescable_wavefronts', + 'TA_PERF_SEL_buffer_coalesced_read_cycles', + 'TA_PERF_SEL_buffer_coalesced_write_cycles', + 'TA_PERF_SEL_buffer_read_wavefronts', + 'TA_PERF_SEL_buffer_total_cycles', + 'TA_PERF_SEL_buffer_wavefronts', + 'TA_PERF_SEL_buffer_write_wavefronts', + 'TA_PERF_SEL_color_1_cycle_pixels', + 'TA_PERF_SEL_color_2_cycle_pixels', + 'TA_PERF_SEL_color_3_cycle_pixels', + 'TA_PERF_SEL_color_4_cycle_pixels', + 'TA_PERF_SEL_data_stalled_by_tc_cycles', + 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 'TA_PERF_SEL_deriv_stalled_cycles', + 'TA_PERF_SEL_first_xnack_on_phase0', + 'TA_PERF_SEL_first_xnack_on_phase1', + 'TA_PERF_SEL_first_xnack_on_phase2', + 'TA_PERF_SEL_first_xnack_on_phase3', + 'TA_PERF_SEL_flat_atomic_wavefronts', + 'TA_PERF_SEL_flat_coalesceable_wavefronts', + 'TA_PERF_SEL_flat_read_wavefronts', 'TA_PERF_SEL_flat_wavefronts', + 'TA_PERF_SEL_flat_write_wavefronts', 'TA_PERF_SEL_gradient_busy', + 'TA_PERF_SEL_gradient_cycles', 'TA_PERF_SEL_gradient_fifo_busy', + 'TA_PERF_SEL_image_atomic_wavefronts', + 'TA_PERF_SEL_image_read_wavefronts', + 'TA_PERF_SEL_image_total_cycles', 'TA_PERF_SEL_image_wavefronts', + 'TA_PERF_SEL_image_write_wavefronts', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp5_en', 'TA_PERF_SEL_lod_busy', + 'TA_PERF_SEL_lod_fifo_busy', 'TA_PERF_SEL_mip_1_cycle_pixels', + 'TA_PERF_SEL_mip_2_cycle_pixels', + 'TA_PERF_SEL_mipmap_invalid_samples', + 'TA_PERF_SEL_mipmap_lod_0_samples', + 'TA_PERF_SEL_mipmap_lod_10_samples', + 'TA_PERF_SEL_mipmap_lod_11_samples', + 'TA_PERF_SEL_mipmap_lod_12_samples', + 'TA_PERF_SEL_mipmap_lod_13_samples', + 'TA_PERF_SEL_mipmap_lod_14_samples', + 'TA_PERF_SEL_mipmap_lod_1_samples', + 'TA_PERF_SEL_mipmap_lod_2_samples', + 'TA_PERF_SEL_mipmap_lod_3_samples', + 'TA_PERF_SEL_mipmap_lod_4_samples', + 'TA_PERF_SEL_mipmap_lod_5_samples', + 'TA_PERF_SEL_mipmap_lod_6_samples', + 'TA_PERF_SEL_mipmap_lod_7_samples', + 'TA_PERF_SEL_mipmap_lod_8_samples', + 'TA_PERF_SEL_mipmap_lod_9_samples', 'TA_PERF_SEL_reg_sclk_vld', + 'TA_PERF_SEL_sh_fifo_addr_busy', + 'TA_PERF_SEL_sh_fifo_addr_cycles', + 'TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles', + 'TA_PERF_SEL_sh_fifo_busy', 'TA_PERF_SEL_sh_fifo_cmd_busy', + 'TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles', + 'TA_PERF_SEL_sh_fifo_data_busy', + 'TA_PERF_SEL_sh_fifo_data_cycles', + 'TA_PERF_SEL_sh_fifo_data_sfifo_busy', + 'TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles', + 'TA_PERF_SEL_sh_fifo_data_tfifo_busy', + 'TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles', + 'TA_PERF_SEL_sp_ta_addr_cycles', 'TA_PERF_SEL_sp_ta_data_cycles', + 'TA_PERF_SEL_sq_ta_cmd_cycles', 'TA_PERF_SEL_ta_busy', + 'TA_PERF_SEL_ta_fa_data_state_cycles', + 'TA_PERF_SEL_ta_sh_fifo_starved', 'TA_PERF_SEL_total_wavefronts', + 'TA_PERF_SEL_vol_1_cycle_pixels', + 'TA_PERF_SEL_vol_2_cycle_pixels', 'TA_PERF_SEL_walker_cycles', + 'TA_PERF_SEL_write_path_busy', + 'TA_PERF_SEL_write_path_input_cycles', + 'TA_PERF_SEL_write_path_output_cycles', + 'TA_PERF_SEL_xnack_on_phase0', 'TA_PERF_SEL_xnack_on_phase1', + 'TA_PERF_SEL_xnack_on_phase2', 'TA_PERF_SEL_xnack_on_phase3', + 'TA_TC_ADDR_MODES', 'TA_TC_ADDR_MODE_BORDER_COLOR', + 'TA_TC_ADDR_MODE_COMP0', 'TA_TC_ADDR_MODE_COMP1', + 'TA_TC_ADDR_MODE_COMP2', 'TA_TC_ADDR_MODE_COMP3', + 'TA_TC_ADDR_MODE_DEFAULT', 'TA_TC_ADDR_MODE_UNALIGNED', + 'TA_TC_REQ_MODES', 'TA_TC_REQ_MODE_BORDER', 'TA_TC_REQ_MODE_BYTE', + 'TA_TC_REQ_MODE_BYTE_NV', 'TA_TC_REQ_MODE_DWORD', + 'TA_TC_REQ_MODE_NORMAL', 'TA_TC_REQ_MODE_TEX0', + 'TA_TC_REQ_MODE_TEX1', 'TA_TC_REQ_MODE_TEX2', + 'TCC_CACHE_POLICIES', 'TCC_CACHE_POLICY_LRU', + 'TCC_CACHE_POLICY_STREAM', 'TCC_MTYPE', 'TCP_CACHE_POLICIES', + 'TCP_CACHE_POLICY_HIT_EVICT', 'TCP_CACHE_POLICY_HIT_LRU', + 'TCP_CACHE_POLICY_MISS_EVICT', 'TCP_CACHE_POLICY_MISS_LRU', + 'TCP_CACHE_STORE_POLICIES', 'TCP_CACHE_STORE_POLICY_WT_EVICT', + 'TCP_CACHE_STORE_POLICY_WT_LRU', 'TCP_DSM_DATA_SEL', + 'TCP_DSM_DISABLE', 'TCP_DSM_INJECT_SEL', 'TCP_DSM_INJECT_SEL0', + 'TCP_DSM_INJECT_SEL1', 'TCP_DSM_INJECT_SEL2', + 'TCP_DSM_INJECT_SEL3', 'TCP_DSM_SEL0', 'TCP_DSM_SEL1', + 'TCP_DSM_SEL_BOTH', 'TCP_DSM_SINGLE_WRITE', + 'TCP_DSM_SINGLE_WRITE_DIS', 'TCP_DSM_SINGLE_WRITE_EN', + 'TCP_OPCODE_ATOMIC', 'TCP_OPCODE_ATOMIC_CMPSWAP', + 'TCP_OPCODE_GATHERH', 'TCP_OPCODE_READ', 'TCP_OPCODE_TYPE', + 'TCP_OPCODE_WBINVL1', 'TCP_OPCODE_WRITE', 'TCP_PERFCOUNT_SELECT', + 'TCP_PERF_SEL_ALLOC_STALL_CYCLES', + 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 'TCP_PERF_SEL_CORE_REG_SCLK_VLD', + 'TCP_PERF_SEL_CP_TCP_INVALIDATE', 'TCP_PERF_SEL_GATE_EN1', + 'TCP_PERF_SEL_GATE_EN2', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_GL1_REQ_READ', 'TCP_PERF_SEL_GL1_REQ_READ_LATENCY', + 'TCP_PERF_SEL_GL1_REQ_WRITE', + 'TCP_PERF_SEL_GL1_REQ_WRITE_LATENCY', + 'TCP_PERF_SEL_HOLE_READ_STALL', 'TCP_PERF_SEL_LFIFO_STALL_CYCLES', + 'TCP_PERF_SEL_LOD_STALL_CYCLES', + 'TCP_PERF_SEL_PENDING_STALL_CYCLES', 'TCP_PERF_SEL_POWER_STALL', + 'TCP_PERF_SEL_READCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_READFIFO_STALL_CYCLES', + 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_REQ_MISS_TAGRAM0', 'TCP_PERF_SEL_REQ_MISS_TAGRAM1', + 'TCP_PERF_SEL_REQ_MISS_TAGRAM2', 'TCP_PERF_SEL_REQ_MISS_TAGRAM3', + 'TCP_PERF_SEL_RFIFO_STALL_CYCLES', 'TCP_PERF_SEL_SHOOTDOWN', + 'TCP_PERF_SEL_TAGRAM0_REQ', 'TCP_PERF_SEL_TAGRAM1_REQ', + 'TCP_PERF_SEL_TAGRAM2_REQ', 'TCP_PERF_SEL_TAGRAM3_REQ', + 'TCP_PERF_SEL_TA_REQ', 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', 'TCP_PERF_SEL_TA_REQ_READ', + 'TCP_PERF_SEL_TA_REQ_STATE_READ', 'TCP_PERF_SEL_TA_REQ_WRITE', + 'TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES', + 'TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES', + 'TCP_PERF_SEL_TA_TCP_STATE_READ', + 'TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ', + 'TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ', + 'TCP_PERF_SEL_TCC_CC_ATOMIC_REQ', 'TCP_PERF_SEL_TCC_CC_READ_REQ', + 'TCP_PERF_SEL_TCC_CC_WRITE_REQ', 'TCP_PERF_SEL_TCC_DCC_REQ', + 'TCP_PERF_SEL_TCC_LRU_REQ', 'TCP_PERF_SEL_TCC_NC_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_NC_READ_REQ', 'TCP_PERF_SEL_TCC_NC_WRITE_REQ', + 'TCP_PERF_SEL_TCC_READ_REQ', 'TCP_PERF_SEL_TCC_READ_REQ_LATENCY', + 'TCP_PERF_SEL_TCC_STREAM_REQ', 'TCP_PERF_SEL_TCC_UC_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_UC_READ_REQ', 'TCP_PERF_SEL_TCC_UC_WRITE_REQ', + 'TCP_PERF_SEL_TCC_WRITE_REQ', + 'TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY', + 'TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY', 'TCP_PERF_SEL_TCP_LATENCY', + 'TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES', + 'TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES', + 'TCP_PERF_SEL_TCP_TCR_STARVE_CYCLES', + 'TCP_PERF_SEL_TCR_RDRET_STALL', + 'TCP_PERF_SEL_TCR_TCP_STALL_CYCLES', + 'TCP_PERF_SEL_TC_TA_XNACK_STALL', + 'TCP_PERF_SEL_TD_TCP_STALL_CYCLES', 'TCP_PERF_SEL_TOTAL_ACCESSES', + 'TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_TOTAL_CACHE_ACCESSES', + 'TCP_PERF_SEL_TOTAL_HIT_LRU_READ', + 'TCP_PERF_SEL_TOTAL_MISS_EVICT_READ', + 'TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE', + 'TCP_PERF_SEL_TOTAL_MISS_LRU_READ', + 'TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE', + 'TCP_PERF_SEL_TOTAL_NON_READ', 'TCP_PERF_SEL_TOTAL_READ', + 'TCP_PERF_SEL_TOTAL_WBINVL1', 'TCP_PERF_SEL_TOTAL_WRITE', + 'TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES', + 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 'TCP_PERF_SEL_UTCL0_LFIFO_FULL', + 'TCP_PERF_SEL_UTCL0_PERMISSION_MISS', + 'TCP_PERF_SEL_UTCL0_REQUEST', + 'TCP_PERF_SEL_UTCL0_SERIALIZATION_STALL', + 'TCP_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 'TCP_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 'TCP_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 'TCP_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 'TCP_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 'TCP_PERF_SEL_UTCL0_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'TCP_PERF_SEL_UTCL0_TRANSLATION_HIT', + 'TCP_PERF_SEL_UTCL0_TRANSLATION_MISS', + 'TCP_PERF_SEL_UTCL0_UTCL2_INFLIGHT', + 'TCP_PERF_SEL_WRITE_CONFLICT_STALL', + 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES', 'TCP_WATCH_MODES', + 'TCP_WATCH_MODE_ALL', 'TCP_WATCH_MODE_ATOMIC', + 'TCP_WATCH_MODE_NONREAD', 'TCP_WATCH_MODE_READ', 'TC_EA_CID', + 'TC_EA_CID_CPF', 'TC_EA_CID_CPG', 'TC_EA_CID_DCC', + 'TC_EA_CID_FMASK', 'TC_EA_CID_HTILE', 'TC_EA_CID_IA', + 'TC_EA_CID_MISC', 'TC_EA_CID_PA', 'TC_EA_CID_RT', 'TC_EA_CID_SQC', + 'TC_EA_CID_STENCIL', 'TC_EA_CID_TCP', 'TC_EA_CID_TCPMETA', + 'TC_EA_CID_UTCL2_TPI', 'TC_EA_CID_WD', 'TC_EA_CID_Z', + 'TC_MICRO_TILE_MODE', 'TC_NACKS', 'TC_NACK_DATA_ERROR', + 'TC_NACK_NO_FAULT', 'TC_NACK_PAGE_FAULT', + 'TC_NACK_PROTECTION_FAULT', 'TC_ONLY', 'TC_OP', + 'TC_OP_ATOMIC_ADD_32', 'TC_OP_ATOMIC_ADD_64', + 'TC_OP_ATOMIC_ADD_RTN_32', 'TC_OP_ATOMIC_ADD_RTN_64', + 'TC_OP_ATOMIC_AND_32', 'TC_OP_ATOMIC_AND_64', + 'TC_OP_ATOMIC_AND_RTN_32', 'TC_OP_ATOMIC_AND_RTN_64', + 'TC_OP_ATOMIC_CMPSWAP_32', 'TC_OP_ATOMIC_CMPSWAP_64', + 'TC_OP_ATOMIC_CMPSWAP_RTN_32', 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 'TC_OP_ATOMIC_DEC_32', 'TC_OP_ATOMIC_DEC_64', + 'TC_OP_ATOMIC_DEC_RTN_32', 'TC_OP_ATOMIC_DEC_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_32', 'TC_OP_ATOMIC_FCMPSWAP_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 'TC_OP_ATOMIC_FMAX_32', 'TC_OP_ATOMIC_FMAX_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMAX_RTN_32', 'TC_OP_ATOMIC_FMAX_RTN_64', + 'TC_OP_ATOMIC_FMIN_32', 'TC_OP_ATOMIC_FMIN_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMIN_RTN_32', 'TC_OP_ATOMIC_FMIN_RTN_64', + 'TC_OP_ATOMIC_INC_32', 'TC_OP_ATOMIC_INC_64', + 'TC_OP_ATOMIC_INC_RTN_32', 'TC_OP_ATOMIC_INC_RTN_64', + 'TC_OP_ATOMIC_OR_32', 'TC_OP_ATOMIC_OR_64', + 'TC_OP_ATOMIC_OR_RTN_32', 'TC_OP_ATOMIC_OR_RTN_64', + 'TC_OP_ATOMIC_SMAX_32', 'TC_OP_ATOMIC_SMAX_64', + 'TC_OP_ATOMIC_SMAX_RTN_32', 'TC_OP_ATOMIC_SMAX_RTN_64', + 'TC_OP_ATOMIC_SMIN_32', 'TC_OP_ATOMIC_SMIN_64', + 'TC_OP_ATOMIC_SMIN_RTN_32', 'TC_OP_ATOMIC_SMIN_RTN_64', + 'TC_OP_ATOMIC_SUB_32', 'TC_OP_ATOMIC_SUB_64', + 'TC_OP_ATOMIC_SUB_RTN_32', 'TC_OP_ATOMIC_SUB_RTN_64', + 'TC_OP_ATOMIC_SWAP_32', 'TC_OP_ATOMIC_SWAP_64', + 'TC_OP_ATOMIC_SWAP_RTN_32', 'TC_OP_ATOMIC_SWAP_RTN_64', + 'TC_OP_ATOMIC_UMAX_32', 'TC_OP_ATOMIC_UMAX_64', + 'TC_OP_ATOMIC_UMAX_RTN_32', 'TC_OP_ATOMIC_UMAX_RTN_64', + 'TC_OP_ATOMIC_UMIN_32', 'TC_OP_ATOMIC_UMIN_64', + 'TC_OP_ATOMIC_UMIN_RTN_32', 'TC_OP_ATOMIC_UMIN_RTN_64', + 'TC_OP_ATOMIC_XOR_32', 'TC_OP_ATOMIC_XOR_64', + 'TC_OP_ATOMIC_XOR_RTN_32', 'TC_OP_ATOMIC_XOR_RTN_64', + 'TC_OP_INVL2_NC', 'TC_OP_INV_METADATA', 'TC_OP_MASKS', + 'TC_OP_MASK_64', 'TC_OP_MASK_FLUSH_DENROM', 'TC_OP_MASK_NO_RTN', + 'TC_OP_NOP_ACK', 'TC_OP_NOP_RTN0', 'TC_OP_PROBE_FILTER', + 'TC_OP_READ', 'TC_OP_RESERVED_FOP_32_0', + 'TC_OP_RESERVED_FOP_32_1', 'TC_OP_RESERVED_FOP_32_2', + 'TC_OP_RESERVED_FOP_64_0', 'TC_OP_RESERVED_FOP_64_1', + 'TC_OP_RESERVED_FOP_64_2', 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_32_0', 'TC_OP_RESERVED_FOP_RTN_32_1', + 'TC_OP_RESERVED_FOP_RTN_32_2', 'TC_OP_RESERVED_FOP_RTN_64_0', + 'TC_OP_RESERVED_FOP_RTN_64_1', 'TC_OP_RESERVED_FOP_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_32_1', 'TC_OP_RESERVED_NON_FLOAT_32_2', + 'TC_OP_RESERVED_NON_FLOAT_32_3', 'TC_OP_RESERVED_NON_FLOAT_32_4', + 'TC_OP_RESERVED_NON_FLOAT_64_1', 'TC_OP_RESERVED_NON_FLOAT_64_2', + 'TC_OP_RESERVED_NON_FLOAT_64_3', 'TC_OP_RESERVED_NON_FLOAT_64_4', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', 'TC_OP_WBINVL1', + 'TC_OP_WBINVL1_SD', 'TC_OP_WBINVL1_VOL', 'TC_OP_WBINVL2', + 'TC_OP_WBINVL2_NC', 'TC_OP_WBINVL2_SD', 'TC_OP_WBL2_NC', + 'TC_OP_WBL2_WC', 'TC_OP_WRITE', 'TD_PERFCOUNT_SEL', + 'TD_PERF_SEL_RESERVED_21', 'TD_PERF_SEL_RESERVED_8', + 'TD_PERF_SEL_address_cmd_poison', + 'TD_PERF_SEL_bypassLerp_wavefront', + 'TD_PERF_SEL_core_state_rams_read', + 'TD_PERF_SEL_d16_en_wavefront', 'TD_PERF_SEL_data_poison', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 'TD_PERF_SEL_done_scoreboard_is_full', + 'TD_PERF_SEL_done_scoreboard_not_empty', + 'TD_PERF_SEL_four_comp_wavefront', + 'TD_PERF_SEL_gather4_wavefront', + 'TD_PERF_SEL_gather4h_packed_wavefront', + 'TD_PERF_SEL_gather4h_wavefront', + 'TD_PERF_SEL_gather8h_packed_wavefront', 'TD_PERF_SEL_input_busy', + 'TD_PERF_SEL_input_state_fifo_full', + 'TD_PERF_SEL_ldfptr_wavefront', 'TD_PERF_SEL_lds_stall', + 'TD_PERF_SEL_load_wavefront', 'TD_PERF_SEL_lod_warn_from_ta', + 'TD_PERF_SEL_min_max_filter_wavefront', + 'TD_PERF_SEL_mixmode_instruction', 'TD_PERF_SEL_mixmode_resource', + 'TD_PERF_SEL_nofilter_busy', + 'TD_PERF_SEL_nofilter_formatters_turned_off', + 'TD_PERF_SEL_nofilter_pkr_full', + 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 'TD_PERF_SEL_none', 'TD_PERF_SEL_one_comp_wavefront', + 'TD_PERF_SEL_opaque_black_border', + 'TD_PERF_SEL_out_of_order_instr', + 'TD_PERF_SEL_reference_data_rams_read', + 'TD_PERF_SEL_sample_c_wavefront', 'TD_PERF_SEL_sampler_lerp_busy', + 'TD_PERF_SEL_sampler_out_busy', 'TD_PERF_SEL_sampler_pkr_full', + 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 'TD_PERF_SEL_status_packet', 'TD_PERF_SEL_store_wavefront', + 'TD_PERF_SEL_ta_data_stall', + 'TD_PERF_SEL_tc_cycling_of_nofilter_instr', + 'TD_PERF_SEL_tc_data_stall', 'TD_PERF_SEL_tc_ram_stall', + 'TD_PERF_SEL_tc_td_data_fifo_full', + 'TD_PERF_SEL_tc_td_ram_fifo_full', 'TD_PERF_SEL_td_busy', + 'TD_PERF_SEL_td_cycling_of_nofilter_instr', + 'TD_PERF_SEL_three_comp_wavefront', 'TD_PERF_SEL_total_num_instr', + 'TD_PERF_SEL_two_comp_wavefront', + 'TD_PERF_SEL_user_defined_border', + 'TD_PERF_SEL_wavefront_dest_is_lds', + 'TD_PERF_SEL_weight_data_rams_read', 'TD_PERF_SEL_white_border', + 'TD_PERF_SEL_write_ack_wavefront', 'TESS_ISOLINE', 'TESS_QUAD', + 'TESS_TRIANGLE', 'TEST_CLK_DIV_SEL', 'TEST_CLK_SEL', + 'TEST_CLK_SEL_0', 'TEST_CLK_SEL_1', 'TEST_CLK_SEL_2', + 'TEST_CLK_SEL_3', 'TEST_CLK_SEL_4', 'TEST_CLK_SEL_5', + 'TEST_CLK_SEL_6', 'TEST_CLK_SEL_7', 'TEST_CLK_SEL_8', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', 'TEST_CLOCK_MUX_SELECT_ENUM', + 'TEX_BC_SWIZZLE', 'TEX_BC_Swizzle_WXYZ', 'TEX_BC_Swizzle_WZYX', + 'TEX_BC_Swizzle_XWYZ', 'TEX_BC_Swizzle_XYZW', + 'TEX_BC_Swizzle_YXWZ', 'TEX_BC_Swizzle_ZYXW', + 'TEX_BORDER_COLOR_TYPE', 'TEX_BorderColor_OpaqueBlack', + 'TEX_BorderColor_OpaqueWhite', 'TEX_BorderColor_Register', + 'TEX_BorderColor_TransparentBlack', 'TEX_CHROMA_KEY', 'TEX_CLAMP', + 'TEX_COORD_TYPE', 'TEX_ChromaKey_Blend', 'TEX_ChromaKey_Disabled', + 'TEX_ChromaKey_Kill', 'TEX_ChromaKey_RESERVED_3', + 'TEX_Clamp_ClampHalfToBorder', 'TEX_Clamp_ClampToBorder', + 'TEX_Clamp_ClampToLast', 'TEX_Clamp_Mirror', + 'TEX_Clamp_MirrorOnceHalfToBorder', + 'TEX_Clamp_MirrorOnceToBorder', 'TEX_Clamp_MirrorOnceToLast', + 'TEX_Clamp_Repeat', 'TEX_CoordType_Normalized', + 'TEX_CoordType_Unnormalized', 'TEX_DEPTH_COMPARE_FUNCTION', + 'TEX_DIM', 'TEX_DepthCompareFunction_Always', + 'TEX_DepthCompareFunction_Equal', + 'TEX_DepthCompareFunction_Greater', + 'TEX_DepthCompareFunction_GreaterEqual', + 'TEX_DepthCompareFunction_Less', + 'TEX_DepthCompareFunction_LessEqual', + 'TEX_DepthCompareFunction_Never', + 'TEX_DepthCompareFunction_NotEqual', 'TEX_Dim_1D', + 'TEX_Dim_1DArray', 'TEX_Dim_2D', 'TEX_Dim_2DArray', + 'TEX_Dim_2DArray_MSAA', 'TEX_Dim_2D_MSAA', 'TEX_Dim_3D', + 'TEX_Dim_CubeMap', 'TEX_FORMAT_COMP', 'TEX_FormatComp_RESERVED_3', + 'TEX_FormatComp_Signed', 'TEX_FormatComp_Unsigned', + 'TEX_FormatComp_UnsignedBiased', 'TEX_MAX_ANISO_RATIO', + 'TEX_MIP_FILTER', 'TEX_MaxAnisoRatio_16to1', + 'TEX_MaxAnisoRatio_1to1', 'TEX_MaxAnisoRatio_2to1', + 'TEX_MaxAnisoRatio_4to1', 'TEX_MaxAnisoRatio_8to1', + 'TEX_MaxAnisoRatio_RESERVED_5', 'TEX_MaxAnisoRatio_RESERVED_6', + 'TEX_MaxAnisoRatio_RESERVED_7', 'TEX_MipFilter_Linear', + 'TEX_MipFilter_None', 'TEX_MipFilter_Point', + 'TEX_MipFilter_Point_Aniso_Adj', 'TEX_REQUEST_SIZE', + 'TEX_RequestSize_128B', 'TEX_RequestSize_2X64B', + 'TEX_RequestSize_32B', 'TEX_RequestSize_64B', 'TEX_SAMPLER_TYPE', + 'TEX_SamplerType_Invalid', 'TEX_SamplerType_Valid', + 'TEX_XYFilter_AnisoLinear', 'TEX_XYFilter_AnisoPoint', + 'TEX_XYFilter_Linear', 'TEX_XYFilter_Point', 'TEX_XY_FILTER', + 'TEX_ZFilter_Linear', 'TEX_ZFilter_None', 'TEX_ZFilter_Point', + 'TEX_ZFilter_RESERVED_3', 'TEX_Z_FILTER', 'TGID_ROLLOVER', + 'THICK_MICRO_TILING', 'THIN_MICRO_TILING', 'THIRTY_TWO_PIPES', + 'THREAD_TRACE_DRAW', 'THREAD_TRACE_FINISH', 'THREAD_TRACE_MARKER', + 'THREAD_TRACE_START', 'THREAD_TRACE_STOP', 'TILE_SPLIT', + 'TMDS_COLOR_FORMAT', 'TMDS_COLOR_FORMAT_DUAL30BPP', + 'TMDS_COLOR_FORMAT_RESERVED', 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 'TMDS_CTL0_DATA_INVERT', 'TMDS_CTL0_DATA_INVERT_EN', + 'TMDS_CTL0_DATA_MODULATION', 'TMDS_CTL0_DATA_MODULATION_BIT0', + 'TMDS_CTL0_DATA_MODULATION_BIT1', + 'TMDS_CTL0_DATA_MODULATION_BIT2', + 'TMDS_CTL0_DATA_MODULATION_DISABLE', 'TMDS_CTL0_DATA_NORMAL', + 'TMDS_CTL0_DATA_SEL', 'TMDS_CTL0_DATA_SEL0_RESERVED', + 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL0_DATA_SEL2_VSYNC', + 'TMDS_CTL0_DATA_SEL3_RESERVED', 'TMDS_CTL0_DATA_SEL4_HSYNC', + 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', + 'TMDS_CTL0_PATTERN_OUT_DISABLE', 'TMDS_CTL0_PATTERN_OUT_EN', + 'TMDS_CTL0_PATTERN_OUT_ENABLE', 'TMDS_CTL1_DATA_INVERT', + 'TMDS_CTL1_DATA_INVERT_EN', 'TMDS_CTL1_DATA_MODULATION', + 'TMDS_CTL1_DATA_MODULATION_BIT0', + 'TMDS_CTL1_DATA_MODULATION_BIT1', + 'TMDS_CTL1_DATA_MODULATION_BIT2', + 'TMDS_CTL1_DATA_MODULATION_DISABLE', 'TMDS_CTL1_DATA_NORMAL', + 'TMDS_CTL1_DATA_SEL', 'TMDS_CTL1_DATA_SEL0_RESERVED', + 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL1_DATA_SEL2_VSYNC', + 'TMDS_CTL1_DATA_SEL3_RESERVED', 'TMDS_CTL1_DATA_SEL4_HSYNC', + 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL1_PATTERN_OUT_DISABLE', 'TMDS_CTL1_PATTERN_OUT_EN', + 'TMDS_CTL1_PATTERN_OUT_ENABLE', 'TMDS_CTL2_DATA_INVERT', + 'TMDS_CTL2_DATA_INVERT_EN', 'TMDS_CTL2_DATA_MODULATION', + 'TMDS_CTL2_DATA_MODULATION_BIT0', + 'TMDS_CTL2_DATA_MODULATION_BIT1', + 'TMDS_CTL2_DATA_MODULATION_BIT2', + 'TMDS_CTL2_DATA_MODULATION_DISABLE', 'TMDS_CTL2_DATA_NORMAL', + 'TMDS_CTL2_DATA_SEL', 'TMDS_CTL2_DATA_SEL0_RESERVED', + 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL2_DATA_SEL2_VSYNC', + 'TMDS_CTL2_DATA_SEL3_RESERVED', 'TMDS_CTL2_DATA_SEL4_HSYNC', + 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL2_PATTERN_OUT_DISABLE', 'TMDS_CTL2_PATTERN_OUT_EN', + 'TMDS_CTL2_PATTERN_OUT_ENABLE', 'TMDS_CTL3_DATA_INVERT', + 'TMDS_CTL3_DATA_INVERT_EN', 'TMDS_CTL3_DATA_MODULATION', + 'TMDS_CTL3_DATA_MODULATION_BIT0', + 'TMDS_CTL3_DATA_MODULATION_BIT1', + 'TMDS_CTL3_DATA_MODULATION_BIT2', + 'TMDS_CTL3_DATA_MODULATION_DISABLE', 'TMDS_CTL3_DATA_NORMAL', + 'TMDS_CTL3_DATA_SEL', 'TMDS_CTL3_DATA_SEL0_RESERVED', + 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL3_DATA_SEL2_VSYNC', + 'TMDS_CTL3_DATA_SEL3_RESERVED', 'TMDS_CTL3_DATA_SEL4_HSYNC', + 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL3_PATTERN_OUT_DISABLE', 'TMDS_CTL3_PATTERN_OUT_EN', + 'TMDS_CTL3_PATTERN_OUT_ENABLE', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', 'TMDS_MUX_SELECT', + 'TMDS_MUX_SELECT_B', 'TMDS_MUX_SELECT_G', 'TMDS_MUX_SELECT_R', + 'TMDS_MUX_SELECT_RESERVED', 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 'TMDS_PIXEL_ENCODING', 'TMDS_PIXEL_ENCODING_422', + 'TMDS_PIXEL_ENCODING_444_OR_420', 'TMDS_REG_TEST_OUTPUTA_CNTLA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 'TMDS_REG_TEST_OUTPUTB_CNTLB', 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', 'TMDS_STEREOSYNC_CTL0', + 'TMDS_STEREOSYNC_CTL1', 'TMDS_STEREOSYNC_CTL2', + 'TMDS_STEREOSYNC_CTL3', 'TMDS_STEREOSYNC_CTL_SEL_REG', + 'TMDS_SYNC_PHASE', 'TMDS_SYNC_PHASE_ON_FRAME_START', + 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB', + 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK', + 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', + 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', + 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', + 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 'TRANSFERRED_1024_BYTES', 'TRANSFERRED_128_BYTES', + 'TRANSFERRED_2048_BYTES', 'TRANSFERRED_256_BYTES', + 'TRANSFERRED_4096_BYTES', 'TRANSFERRED_512_BYTES', + 'TRANSFERRED_64_BYTES', 'TRANSFERRED_8192_BYTES', 'TRAPEZOIDS', + 'TRISTRIP', 'TVX_DATA_FORMAT', 'TVX_DST_SEL', 'TVX_DstSel_0f', + 'TVX_DstSel_1f', 'TVX_DstSel_Mask', 'TVX_DstSel_RESERVED_6', + 'TVX_DstSel_W', 'TVX_DstSel_X', 'TVX_DstSel_Y', 'TVX_DstSel_Z', + 'TVX_ENDIAN_SWAP', 'TVX_EndianSwap_8in16', 'TVX_EndianSwap_8in32', + 'TVX_EndianSwap_8in64', 'TVX_EndianSwap_None', 'TVX_FMT_1', + 'TVX_FMT_10_10_10_2', 'TVX_FMT_10_11_11', + 'TVX_FMT_10_11_11_FLOAT', 'TVX_FMT_11_11_10', + 'TVX_FMT_11_11_10_FLOAT', 'TVX_FMT_16', 'TVX_FMT_16_16', + 'TVX_FMT_16_16_16', 'TVX_FMT_16_16_16_16', + 'TVX_FMT_16_16_16_16_FLOAT', 'TVX_FMT_16_16_16_FLOAT', + 'TVX_FMT_16_16_FLOAT', 'TVX_FMT_16_FLOAT', 'TVX_FMT_1_5_5_5', + 'TVX_FMT_1_REVERSED', 'TVX_FMT_24_8', 'TVX_FMT_24_8_FLOAT', + 'TVX_FMT_2_10_10_10', 'TVX_FMT_32', 'TVX_FMT_32_32', + 'TVX_FMT_32_32_32', 'TVX_FMT_32_32_32_32', + 'TVX_FMT_32_32_32_32_FLOAT', 'TVX_FMT_32_32_32_FLOAT', + 'TVX_FMT_32_32_FLOAT', 'TVX_FMT_32_AS_8', 'TVX_FMT_32_AS_8_8', + 'TVX_FMT_32_FLOAT', 'TVX_FMT_3_3_2', 'TVX_FMT_4_4', + 'TVX_FMT_4_4_4_4', 'TVX_FMT_5_5_5_1', 'TVX_FMT_5_6_5', + 'TVX_FMT_5_9_9_9_SHAREDEXP', 'TVX_FMT_6_5_5', 'TVX_FMT_8', + 'TVX_FMT_8_24', 'TVX_FMT_8_24_FLOAT', 'TVX_FMT_8_8', + 'TVX_FMT_8_8_8', 'TVX_FMT_8_8_8_8', 'TVX_FMT_APC0', + 'TVX_FMT_APC1', 'TVX_FMT_APC2', 'TVX_FMT_APC3', 'TVX_FMT_APC4', + 'TVX_FMT_APC5', 'TVX_FMT_APC6', 'TVX_FMT_APC7', 'TVX_FMT_BC1', + 'TVX_FMT_BC2', 'TVX_FMT_BC3', 'TVX_FMT_BC4', 'TVX_FMT_BC5', + 'TVX_FMT_BG_RG', 'TVX_FMT_CTX1', 'TVX_FMT_GB_GR', + 'TVX_FMT_INVALID', 'TVX_FMT_RESERVED_33', 'TVX_FMT_RESERVED_36', + 'TVX_FMT_RESERVED_4', 'TVX_FMT_RESERVED_63', + 'TVX_FMT_X24_8_32_FLOAT', 'TVX_INST', 'TVX_Inst_Gather4', + 'TVX_Inst_Gather4_C', 'TVX_Inst_Gather4_C_O', + 'TVX_Inst_Gather4_O', 'TVX_Inst_GetBufferResInfo', + 'TVX_Inst_GetGradientsH', 'TVX_Inst_GetGradientsV', + 'TVX_Inst_GetLOD', 'TVX_Inst_GetNumberOfSamples', + 'TVX_Inst_GetTextureResInfo', 'TVX_Inst_KeepGradients', + 'TVX_Inst_LD', 'TVX_Inst_NormalVertexFetch', 'TVX_Inst_Pass', + 'TVX_Inst_RESERVED_15', 'TVX_Inst_RESERVED_2', 'TVX_Inst_Sample', + 'TVX_Inst_Sample_C', 'TVX_Inst_Sample_C_G', + 'TVX_Inst_Sample_C_G_LB', 'TVX_Inst_Sample_C_L', + 'TVX_Inst_Sample_C_LB', 'TVX_Inst_Sample_C_LZ', + 'TVX_Inst_Sample_G', 'TVX_Inst_Sample_G_LB', 'TVX_Inst_Sample_L', + 'TVX_Inst_Sample_LB', 'TVX_Inst_Sample_LZ', + 'TVX_Inst_SemanticVertexFetch', 'TVX_Inst_SetGradientsH', + 'TVX_Inst_SetGradientsV', 'TVX_Inst_SetTextureOffsets', + 'TVX_NUM_FORMAT_ALL', 'TVX_NumFormatAll_Int', + 'TVX_NumFormatAll_Norm', 'TVX_NumFormatAll_RESERVED_3', + 'TVX_NumFormatAll_Scaled', 'TVX_SRC_SEL', 'TVX_SRFModeAll_NZ', + 'TVX_SRFModeAll_ZCMO', 'TVX_SRF_MODE_ALL', 'TVX_SrcSel_0f', + 'TVX_SrcSel_1f', 'TVX_SrcSel_W', 'TVX_SrcSel_X', 'TVX_SrcSel_Y', + 'TVX_SrcSel_Z', 'TVX_TYPE', 'TVX_Type_InvalidTextureResource', + 'TVX_Type_InvalidVertexBuffer', 'TVX_Type_ValidTextureResource', + 'TVX_Type_ValidVertexBuffer', 'TWO_BANKS', 'TWO_FRAGMENTS', + 'TWO_PIPES', 'TWO_RB_PER_SE', 'TWO_SHADER_ENGINS', 'TileSplit', + 'TileType', 'UCONFIG_SPACE_END', 'UCONFIG_SPACE_START', + 'UNCACHED_RD', 'UNCACHED_WR', 'UNDEF', 'UNSIGNED', + 'UTCL0FaultType', 'UTCL0RequestType', 'UTCL0_TYPE_BYPASS', + 'UTCL0_TYPE_NORMAL', 'UTCL0_TYPE_SHOOTDOWN', + 'UTCL0_XNACK_NO_RETRY', 'UTCL0_XNACK_PRT', 'UTCL0_XNACK_RETRY', + 'UTCL0_XNACK_SUCCESS', 'UTCL1FaultType', 'UTCL1PerfSel', + 'UTCL1RequestType', 'UTCL1_PERF_SEL_BYPASS_REQS', + 'UTCL1_PERF_SEL_HITS', 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 'UTCL1_PERF_SEL_MISSES', 'UTCL1_PERF_SEL_NONE', + 'UTCL1_PERF_SEL_NONRANGE_INV_REQS', + 'UTCL1_PERF_SEL_NUM_BIGK_PAGES', + 'UTCL1_PERF_SEL_NUM_SMALLK_PAGES', + 'UTCL1_PERF_SEL_OUTSTANDING_UTCL2_REQS_ACCUM', + 'UTCL1_PERF_SEL_RANGE_INV_REQS', 'UTCL1_PERF_SEL_REQS', + 'UTCL1_PERF_SEL_STALL_MH_CAM_FULL', + 'UTCL1_PERF_SEL_STALL_MH_OFIFO_FULL', + 'UTCL1_PERF_SEL_STALL_ON_UTCL2_CREDITS', + 'UTCL1_PERF_SEL_TOTAL_UTCL2_REQS', 'UTCL1_TYPE_BYPASS', + 'UTCL1_TYPE_NORMAL', 'UTCL1_TYPE_SHOOTDOWN', + 'UTCL1_XNACK_NO_RETRY', 'UTCL1_XNACK_PRT', 'UTCL1_XNACK_RETRY', + 'UTCL1_XNACK_SUCCESS', 'UVDFC_BITSTREAM_ADDR', + 'UVDFC_BITSTREAM_SIZE', 'UVDFC_DECODED_ADDR', + 'UVDFC_DISPLAY_ADDR', 'UVDFC_DISPLAY_PITCH', + 'UVDFC_DISPLAY_TILING', 'UVDFC_EOD', 'UVDFC_FENCE', + 'UVDFC_ITBUF_ADDR', 'UVDFC_MBLOCK_ADDR', 'UVDFC_TRAP', + 'UVDFirmwareCommand', 'VC_AND_TC', 'VC_ONLY', + 'VGT_CACHE_INVALID_MODE', 'VGT_DETECT_ONE', 'VGT_DETECT_ZERO', + 'VGT_DIST_MODE', 'VGT_DI_INDEX_SIZE', 'VGT_DI_MAJOR_MODE_SELECT', + 'VGT_DI_PRIM_TYPE', 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', + 'VGT_DMA_BUF_RING', 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', + 'VGT_DMA_PTR_UPDATE', 'VGT_DMA_SWAP_16_BIT', + 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', 'VGT_DMA_SWAP_NONE', + 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', 'VGT_FLUSH', + 'VGT_GROUP_CONV_SEL', 'VGT_GRP_2D_COPY_RECT_V0', + 'VGT_GRP_2D_COPY_RECT_V1', 'VGT_GRP_2D_COPY_RECT_V2', + 'VGT_GRP_2D_COPY_RECT_V3', 'VGT_GRP_2D_FILL_RECT', + 'VGT_GRP_2D_LINE', 'VGT_GRP_2D_RECT', 'VGT_GRP_2D_TRI', + 'VGT_GRP_3D_LINE', 'VGT_GRP_3D_LINE_ADJ', 'VGT_GRP_3D_PATCH', + 'VGT_GRP_3D_POINT', 'VGT_GRP_3D_QUAD', 'VGT_GRP_3D_RECT', + 'VGT_GRP_3D_TRI', 'VGT_GRP_3D_TRI_ADJ', 'VGT_GRP_AUTO_PRIM', + 'VGT_GRP_FAN', 'VGT_GRP_FIX_1_23_TO_FLOAT', 'VGT_GRP_FLOAT_32', + 'VGT_GRP_INDEX_16', 'VGT_GRP_INDEX_32', 'VGT_GRP_LIST', + 'VGT_GRP_LOOP', 'VGT_GRP_POLYGON', 'VGT_GRP_PRIM_INDEX_LINE', + 'VGT_GRP_PRIM_INDEX_QUAD', 'VGT_GRP_PRIM_INDEX_TRI', + 'VGT_GRP_PRIM_ORDER', 'VGT_GRP_PRIM_TYPE', 'VGT_GRP_SINT_16', + 'VGT_GRP_SINT_32', 'VGT_GRP_STRIP', 'VGT_GRP_UINT_16', + 'VGT_GRP_UINT_32', 'VGT_GS_CUT_MODE', 'VGT_GS_MODE_TYPE', + 'VGT_GS_OUTPRIM_TYPE', 'VGT_INDEX_16', 'VGT_INDEX_32', + 'VGT_INDEX_8', 'VGT_INDEX_TYPE_MODE', 'VGT_OUTPATH_GS_BLOCK', + 'VGT_OUTPATH_HS_BLOCK', 'VGT_OUTPATH_PRIM_GEN', + 'VGT_OUTPATH_SELECT', 'VGT_OUTPATH_TE_GS_BLOCK', + 'VGT_OUTPATH_TE_OUTPUT', 'VGT_OUTPATH_TE_PRIM_GEN', + 'VGT_OUTPATH_VTX_REUSE', 'VGT_OUT_2D_RECT', 'VGT_OUT_LINE', + 'VGT_OUT_LINE_ADJ', 'VGT_OUT_PATCH', 'VGT_OUT_POINT', + 'VGT_OUT_PRIM_TYPE', 'VGT_OUT_RECT_V0', 'VGT_OUT_RECT_V1', + 'VGT_OUT_RECT_V2', 'VGT_OUT_RECT_V3', 'VGT_OUT_TRI', + 'VGT_OUT_TRI_ADJ', 'VGT_POLICY_BYPASS', 'VGT_POLICY_LRU', + 'VGT_POLICY_STREAM', 'VGT_RDREQ_POLICY', 'VGT_STAGES_ES_EN', + 'VGT_STAGES_GS_EN', 'VGT_STAGES_HS_EN', 'VGT_STAGES_LS_EN', + 'VGT_STAGES_VS_EN', 'VGT_STREAMOUT_RESET', 'VGT_STREAMOUT_SYNC', + 'VGT_TESS_PARTITION', 'VGT_TESS_TOPOLOGY', 'VGT_TESS_TYPE', + 'VGT_TE_PRIM_INDEX_LINE', 'VGT_TE_PRIM_INDEX_QUAD', + 'VGT_TE_PRIM_INDEX_TRI', 'VGT_TE_QUAD', 'VID_ENHANCED_MODE', + 'VID_NORMAL_FRAME_MODE', 'VID_STREAM_DISABLE_MASKED', + 'VID_STREAM_DISABLE_UNMASK', 'VMEMCMD_RETURN_IN_ORDER', + 'VMEMCMD_RETURN_IN_ORDER_READ', 'VMEMCMD_RETURN_ORDER', + 'VMEMCMD_RETURN_OUT_OF_ORDER', 'VMID_SZ', 'VMPG_SIZE', + 'VMPG_SIZE_4KB', 'VMPG_SIZE_64KB', 'VREADY_AT_OR_AFTER_VSYNC', + 'VREADY_BEFORE_VSYNC', 'VSYNC_CNT_LATCH_MASK', + 'VSYNC_CNT_LATCH_MASK_0', 'VSYNC_CNT_LATCH_MASK_1', + 'VSYNC_CNT_REFCLK_SEL', 'VSYNC_CNT_REFCLK_SEL_0', + 'VSYNC_CNT_REFCLK_SEL_1', 'VSYNC_CNT_RESET_SEL', + 'VSYNC_CNT_RESET_SEL_0', 'VSYNC_CNT_RESET_SEL_1', + 'VS_PARTIAL_FLUSH', 'VS_PS', 'VS_STAGE_COPY_SHADER', + 'VS_STAGE_DS', 'VS_STAGE_REAL', 'VTG_SEL_0', 'VTG_SEL_1', + 'VTG_SEL_2', 'VTG_SEL_3', 'VTG_SEL_4', 'VTG_SEL_5', 'VTX_CLAMP', + 'VTX_Clamp_ClampToNAN', 'VTX_Clamp_ClampToZero', 'VTX_FETCH_TYPE', + 'VTX_FORMAT_COMP_ALL', 'VTX_FetchType_InstanceData', + 'VTX_FetchType_NoIndexOffset', 'VTX_FetchType_RESERVED_3', + 'VTX_FetchType_VertexData', 'VTX_FormatCompAll_Signed', + 'VTX_FormatCompAll_Unsigned', 'VTX_MEM_REQUEST_SIZE', + 'VTX_MemRequestSize_32B', 'VTX_MemRequestSize_64B', + 'WBSCL_BACKPRESSURE_CNT_DISABLE', 'WBSCL_BACKPRESSURE_CNT_ENABLE', + 'WBSCL_BACKPRESSURE_CNT_EN_ENUM', 'WBSCL_COEF_CHROMA_HORZ_FILTER', + 'WBSCL_COEF_CHROMA_VERT_FILTER', 'WBSCL_COEF_FILTER_TYPE_SEL', + 'WBSCL_COEF_LUMA_HORZ_FILTER', 'WBSCL_COEF_LUMA_VERT_FILTER', + 'WBSCL_COEF_RAM_FILTER_TYPE_ENUM', + 'WBSCL_COEF_RAM_FILTER_TYPE_HC', 'WBSCL_COEF_RAM_FILTER_TYPE_HL', + 'WBSCL_COEF_RAM_FILTER_TYPE_VC', 'WBSCL_COEF_RAM_FILTER_TYPE_VL', + 'WBSCL_COEF_RAM_PHASE0', 'WBSCL_COEF_RAM_PHASE1', + 'WBSCL_COEF_RAM_PHASE2', 'WBSCL_COEF_RAM_PHASE3', + 'WBSCL_COEF_RAM_PHASE4', 'WBSCL_COEF_RAM_PHASE5', + 'WBSCL_COEF_RAM_PHASE6', 'WBSCL_COEF_RAM_PHASE7', + 'WBSCL_COEF_RAM_PHASE8', 'WBSCL_COEF_RAM_PHASE_ENUM', + 'WBSCL_COEF_RAM_RD_SEL_0', 'WBSCL_COEF_RAM_RD_SEL_1', + 'WBSCL_COEF_RAM_RD_SEL_ENUM', 'WBSCL_COEF_RAM_SEL_0', + 'WBSCL_COEF_RAM_SEL_1', 'WBSCL_COEF_RAM_SEL_ENUM', + 'WBSCL_COEF_RAM_TAP_COEF_DISABLE', + 'WBSCL_COEF_RAM_TAP_COEF_ENABLE', + 'WBSCL_COEF_RAM_TAP_COEF_EN_ENUM', 'WBSCL_COEF_RAM_TAP_PAIR_IDX0', + 'WBSCL_COEF_RAM_TAP_PAIR_IDX1', 'WBSCL_COEF_RAM_TAP_PAIR_IDX2', + 'WBSCL_COEF_RAM_TAP_PAIR_IDX3', 'WBSCL_COEF_RAM_TAP_PAIR_IDX4', + 'WBSCL_COEF_RAM_TAP_PAIR_IDX5', + 'WBSCL_COEF_RAM_TAP_PAIR_IDX_ENUM', + 'WBSCL_DATA_OVERFLOW_INT_TYPE_ENUM', + 'WBSCL_DATA_OVERFLOW_INT_TYPE_HW', + 'WBSCL_DATA_OVERFLOW_INT_TYPE_REG', + 'WBSCL_HOST_CONFLICT_INT_TYPE_ENUM', + 'WBSCL_HOST_CONFLICT_INT_TYPE_HW', + 'WBSCL_HOST_CONFLICT_INT_TYPE_REG', 'WBSCL_LB_MEM_PWR_FORCE_DS', + 'WBSCL_LB_MEM_PWR_FORCE_ENUM', 'WBSCL_LB_MEM_PWR_FORCE_LS', + 'WBSCL_LB_MEM_PWR_FORCE_NO', 'WBSCL_LB_MEM_PWR_FORCE_SD', + 'WBSCL_LB_MEM_PWR_MODE_SEL_DS', 'WBSCL_LB_MEM_PWR_MODE_SEL_ENUM', + 'WBSCL_LB_MEM_PWR_MODE_SEL_LS', 'WBSCL_LB_MEM_PWR_MODE_SEL_ON', + 'WBSCL_LB_MEM_PWR_MODE_SEL_SD', 'WBSCL_LUT_MEM_PWR_STATE_ENUM', + 'WBSCL_LUT_MEM_PWR_STATE_LS', 'WBSCL_LUT_MEM_PWR_STATE_ON', + 'WBSCL_LUT_MEM_PWR_STATE_RESERVED2', + 'WBSCL_LUT_MEM_PWR_STATE_RESERVED3', 'WBSCL_MEM_PWR_STATE_DS', + 'WBSCL_MEM_PWR_STATE_ENUM', 'WBSCL_MEM_PWR_STATE_LS', + 'WBSCL_MEM_PWR_STATE_ON', 'WBSCL_MEM_PWR_STATE_SD', + 'WBSCL_MODE_SCALING_444_BYPASS', + 'WBSCL_MODE_SCALING_444_RGB_ENABLE', + 'WBSCL_MODE_SCALING_444_YCBCR_ENABLE', + 'WBSCL_MODE_SCALING_YCBCR_ENABLE', 'WBSCL_MODE_SEL', + 'WBSCL_NUM_OF_TAPS0', 'WBSCL_NUM_OF_TAPS1', 'WBSCL_NUM_OF_TAPS10', + 'WBSCL_NUM_OF_TAPS11', 'WBSCL_NUM_OF_TAPS2', 'WBSCL_NUM_OF_TAPS3', + 'WBSCL_NUM_OF_TAPS4', 'WBSCL_NUM_OF_TAPS5', 'WBSCL_NUM_OF_TAPS6', + 'WBSCL_NUM_OF_TAPS7', 'WBSCL_NUM_OF_TAPS8', 'WBSCL_NUM_OF_TAPS9', + 'WBSCL_NUM_OF_TAPS_ENUM', 'WBSCL_OUTSIDE_PIX_STRATEGY_BLACK', + 'WBSCL_OUTSIDE_PIX_STRATEGY_EDGE', + 'WBSCL_OUTSIDE_PIX_STRATEGY_ENUM', 'WBSCL_PIXEL_DEPTH', + 'WBSCL_STATUS_ACK_CLR', 'WBSCL_STATUS_ACK_ENUM', + 'WBSCL_STATUS_ACK_NCLR', 'WBSCL_STATUS_MASK_DISABLE', + 'WBSCL_STATUS_MASK_ENABLE', 'WBSCL_STATUS_MASK_ENUM', + 'WBSCL_TEST_CRC_CONT_DISABLE', 'WBSCL_TEST_CRC_CONT_ENABLE', + 'WBSCL_TEST_CRC_CONT_EN_ENUM', 'WBSCL_TEST_CRC_DISABLE', + 'WBSCL_TEST_CRC_ENABLE', 'WBSCL_TEST_CRC_EN_ENUM', + 'WBSCL_TEST_CRC_MASKED', 'WBSCL_TEST_CRC_MASK_ENUM', + 'WBSCL_TEST_CRC_UNMASKED', 'WB_CLK_GATE_DISABLE', + 'WB_CLK_GATE_DIS_ENUM', 'WB_CLK_GATE_ENABLE', 'WB_ENABLE_ENUM', + 'WB_EN_DISABLE', 'WB_EN_ENABLE', 'WB_MEM_PWR_DISABLE', + 'WB_MEM_PWR_DIS_ENUM', 'WB_MEM_PWR_ENABLE', + 'WB_RAM_PW_SAVE_MODE_ENUM', 'WB_RAM_PW_SAVE_MODE_LS', + 'WB_RAM_PW_SAVE_MODE_SD', 'WB_SOFT_RESET_ENUM', + 'WB_SOFT_RESET_NEG', 'WB_SOFT_RESET_POS', 'WB_TEST_CLK_SEL_ENUM', + 'WB_TEST_CLK_SEL_PERM', 'WB_TEST_CLK_SEL_REG', + 'WB_TEST_CLK_SEL_WB', 'WB_TEST_CLK_SEL_WBSCL', + 'WD_IA_DRAW_REG_XFER', 'WD_IA_DRAW_REG_XFER_GE_CNTL', + 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 'WD_IA_DRAW_SOURCE', 'WD_IA_DRAW_SOURCE_AUTO', + 'WD_IA_DRAW_SOURCE_DMA', 'WD_IA_DRAW_SOURCE_IMMD', + 'WD_IA_DRAW_SOURCE_OPAQ', 'WD_IA_DRAW_TYPE', + 'WD_IA_DRAW_TYPE_DI_MM0', 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 'WD_IA_DRAW_TYPE_EVENT_INIT', 'WD_IA_DRAW_TYPE_IMM_DATA', + 'WD_IA_DRAW_TYPE_INDX_OFF', 'WD_IA_DRAW_TYPE_MAX_INDX', + 'WD_IA_DRAW_TYPE_MIN_INDX', 'WD_IA_DRAW_TYPE_REG_XFER', + 'WRITE_BASE_ONLY', 'WRITE_BOTH', 'WritePolicy', 'XNORM', + 'XNORM_A', 'XNORM_B', 'XTAL_REF_CLOCK_SOURCE_SEL', + 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', + 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', 'XTAL_REF_SEL', + 'XTAL_REF_SEL_1X', 'XTAL_REF_SEL_2X', 'Y10_CbCr1010_420_PLANAR', + 'Y10_CrCb1010_420_PLANAR', 'Y12_CbCr1212_420_PLANAR', + 'Y12_CrCb1212_420_PLANAR', 'Y8_CbCr88_420_PLANAR', + 'Y8_CrCb88_420_PLANAR', 'YCbYCr10101010_422_PACKED', + 'YCbYCr12121212_422_PACKED', 'YCbYCr8888_422_PACKED', + 'YCrCbA16161616_10LSB', 'YCrCbA16161616_10MSB', + 'YCrCbA16161616_12LSB', 'YCrCbA16161616_12MSB', 'YCrCbA8888', + 'YCrYCb10101010_422_PACKED', 'YCrYCb12121212_422_PACKED', + 'YCrYCb8888_422_PACKED', 'Y_G_DATA_ON_ALPHA_PORT', + 'Y_G_DATA_ON_CB_B_PORT', 'Y_G_DATA_ON_CR_R_PORT', + 'Y_G_DATA_ON_Y_G_PORT', 'ZFormat', 'ZLimitSumm', 'ZModeForce', + 'ZOrder', 'ZPASS_DISABLE', 'ZPASS_DONE', 'ZPASS_PIXELS', + 'ZPASS_SAMPLES', 'ZSamplePosition', 'Z_16', 'Z_24', 'Z_32_FLOAT', + 'Z_INVALID', 'Z_SAMPLE_CENTER', 'Z_SAMPLE_CENTROID', + 'ZpassControl', '_navi10_ENUM_HEADER', 'ge_assembler_busy', + 'ge_assembler_stalled', 'ge_cm_reading_stalled', + 'ge_cm_stalled_by_gog', 'ge_cm_stalled_by_gsfetch_done', + 'ge_dma_busy', 'ge_dma_lat_bin_0', 'ge_dma_lat_bin_1', + 'ge_dma_lat_bin_2', 'ge_dma_lat_bin_3', 'ge_dma_lat_bin_4', + 'ge_dma_lat_bin_5', 'ge_dma_lat_bin_6', 'ge_dma_lat_bin_7', + 'ge_dma_return', 'ge_dma_utcl1_consecutive_retry_event', + 'ge_dma_utcl1_request_event', 'ge_dma_utcl1_retry_event', + 'ge_dma_utcl1_stall_event', 'ge_dma_utcl1_stall_utcl2_event', + 'ge_dma_utcl1_translation_hit_event', + 'ge_dma_utcl1_translation_miss_event', + 'ge_dma_utcl2_stall_on_trans', 'ge_dma_utcl2_trans_ack', + 'ge_dma_utcl2_trans_xnack', 'ge_ds_cache_hits', 'ge_ds_prims', + 'ge_es_done', 'ge_es_done_latency', 'ge_es_flush', + 'ge_es_ring_high_water_mark', 'ge_es_thread_groups', + 'ge_esthread_stalled_es_rb_full', 'ge_esthread_stalled_spi_bp', + 'ge_esvert_stalled_es_tbl', 'ge_esvert_stalled_gs_event', + 'ge_esvert_stalled_gs_tbl', 'ge_esvert_stalled_gsprim', + 'ge_gea_dma_starved', 'ge_gog_busy', 'ge_gog_out_indx_stalled', + 'ge_gog_out_prim_stalled', 'ge_gog_vs_tbl_stalled', + 'ge_gs_cache_hits', 'ge_gs_counters_avail_stalled', 'ge_gs_done', + 'ge_gs_done_latency', 'ge_gs_event_stall', + 'ge_gs_issue_rtr_stalled', 'ge_gs_rb_space_avail_stalled', + 'ge_gs_ring_high_water_mark', 'ge_gsprim_stalled_es_tbl', + 'ge_gsprim_stalled_esvert', 'ge_gsprim_stalled_gs_event', + 'ge_gsprim_stalled_gs_tbl', 'ge_gsthread_stalled', 'ge_hs_done', + 'ge_hs_done_latency', 'ge_hs_done_se0', 'ge_hs_done_se1', + 'ge_hs_done_se2_reserved', 'ge_hs_done_se3_reserved', + 'ge_hs_tfm_stall', 'ge_hs_tgs_active_high_water_mark', + 'ge_hs_thread_groups', 'ge_inside_tf_bin_0', 'ge_inside_tf_bin_1', + 'ge_inside_tf_bin_2', 'ge_inside_tf_bin_3', 'ge_inside_tf_bin_4', + 'ge_inside_tf_bin_5', 'ge_inside_tf_bin_6', 'ge_inside_tf_bin_7', + 'ge_inside_tf_bin_8', 'ge_ls_done', 'ge_ls_done_latency', + 'ge_null_patch', 'ge_pa_clipp_eop', 'ge_pa_clipp_is_event', + 'ge_pa_clipp_new_vtx_vect', 'ge_pa_clipp_null_prim', + 'ge_pa_clipp_send', 'ge_pa_clipp_send_not_event', + 'ge_pa_clipp_stalled', 'ge_pa_clipp_starved_busy', + 'ge_pa_clipp_starved_idle', 'ge_pa_clipp_valid_prim', + 'ge_pa_clips_send', 'ge_pa_clips_stalled', 'ge_pa_clipv_send', + 'ge_pa_clipv_stalled', 'ge_rbiu_di_fifo_stalled', + 'ge_rbiu_di_fifo_starved', 'ge_rbiu_dr_fifo_stalled', + 'ge_rbiu_dr_fifo_starved', 'ge_reused_es_indices', + 'ge_reused_vs_indices', 'ge_sclk_core_vld', 'ge_sclk_gs_vld', + 'ge_sclk_input_vld', 'ge_sclk_leg_gs_arb_vld', 'ge_sclk_ngg_vld', + 'ge_sclk_reg_vld', 'ge_sclk_te11_vld', 'ge_sclk_vr_vld', + 'ge_sclk_wd_te11_vld', 'ge_spi_esvert_eov', + 'ge_spi_esvert_stalled', 'ge_spi_esvert_starved_busy', + 'ge_spi_esvert_valid', 'ge_spi_eswave_is_event', + 'ge_spi_eswave_send', 'ge_spi_gsprim_cont', 'ge_spi_gsprim_eov', + 'ge_spi_gsprim_stalled', 'ge_spi_gsprim_starved_busy', + 'ge_spi_gsprim_starved_idle', 'ge_spi_gsprim_valid', + 'ge_spi_gssubgrp_is_event', 'ge_spi_gssubgrp_send', + 'ge_spi_gswave_is_event', 'ge_spi_gswave_send', + 'ge_spi_hsvert_eov', 'ge_spi_hsvert_stalled', + 'ge_spi_hsvert_starved_busy', 'ge_spi_hsvert_valid', + 'ge_spi_hswave_is_event', 'ge_spi_hswave_send', + 'ge_spi_lsvert_eov', 'ge_spi_lsvert_stalled', + 'ge_spi_lsvert_starved_busy', 'ge_spi_lsvert_starved_idle', + 'ge_spi_lsvert_valid', 'ge_spi_lswave_is_event', + 'ge_spi_lswave_send', 'ge_spi_vsvert_eov', 'ge_spi_vsvert_send', + 'ge_spi_vsvert_stalled', 'ge_spi_vsvert_starved_busy', + 'ge_spi_vsvert_starved_idle', 'ge_spi_vswave_is_event', + 'ge_spi_vswave_send', 'ge_starved_on_hs_done', 'ge_stat_busy', + 'ge_stat_combined_busy', 'ge_stat_no_dma_busy', + 'ge_strmout_stalled', 'ge_te11_busy', 'ge_te11_starved', + 'ge_tfreq_lat_bin_0', 'ge_tfreq_lat_bin_1', 'ge_tfreq_lat_bin_2', + 'ge_tfreq_lat_bin_3', 'ge_tfreq_lat_bin_4', 'ge_tfreq_lat_bin_5', + 'ge_tfreq_lat_bin_6', 'ge_tfreq_lat_bin_7', + 'ge_tfreq_utcl1_consecutive_retry_event', + 'ge_tfreq_utcl1_request_event', 'ge_tfreq_utcl1_retry_event', + 'ge_tfreq_utcl1_stall_event', 'ge_tfreq_utcl1_stall_utcl2_event', + 'ge_tfreq_utcl1_translation_hit_event', + 'ge_tfreq_utcl1_translation_miss_event', + 'ge_tfreq_utcl2_stall_on_trans', 'ge_tfreq_utcl2_trans_ack', + 'ge_tfreq_utcl2_trans_xnack', 'ge_vs_cache_hits', 'ge_vs_done', + 'ge_vs_pc_stall', 'ge_vs_table_high_water_mark', + 'ge_vs_thread_groups', 'ge_vsvert_api_send', 'ge_vsvert_ds_send', + 'ge_wait_for_es_done_stalled', 'ge_waveid_stalled'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_nv.py b/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_nv.py new file mode 100644 index 0000000000..c21fbfb2bc --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_nv.py @@ -0,0 +1,962 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +F32_MES_PM4_PACKETS_H = True # macro +uint32_t = True # macro +int32_t = True # macro +PM4_MES_HEADER_DEFINED = True # macro +PM4_MEC_RELEASE_MEM_DEFINED = True # macro +PM4_MEC_WRITE_DATA_DEFINED = True # macro +class union_PM4_MES_TYPE_3_HEADER(Union): + pass + +class struct_PM4_MES_TYPE_3_HEADER_0(Structure): + pass + +struct_PM4_MES_TYPE_3_HEADER_0._pack_ = 1 # source:False +struct_PM4_MES_TYPE_3_HEADER_0._fields_ = [ + ('reserved1', ctypes.c_uint32, 8), + ('opcode', ctypes.c_uint32, 8), + ('count', ctypes.c_uint32, 14), + ('type', ctypes.c_uint32, 2), +] + +union_PM4_MES_TYPE_3_HEADER._pack_ = 1 # source:False +union_PM4_MES_TYPE_3_HEADER._anonymous_ = ('_0',) +union_PM4_MES_TYPE_3_HEADER._fields_ = [ + ('_0', struct_PM4_MES_TYPE_3_HEADER_0), + ('u32All', ctypes.c_uint32), +] + + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 5: 'event_index__mec_release_mem__end_of_pipe', + 6: 'event_index__mec_release_mem__shader_done', +} +event_index__mec_release_mem__end_of_pipe = 5 +event_index__mec_release_mem__shader_done = 6 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'cache_policy__mec_release_mem__lru', + 1: 'cache_policy__mec_release_mem__stream', +} +cache_policy__mec_release_mem__lru = 0 +cache_policy__mec_release_mem__stream = 1 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'pq_exe_status__mec_release_mem__default', + 1: 'pq_exe_status__mec_release_mem__phase_update', +} +pq_exe_status__mec_release_mem__default = 0 +pq_exe_status__mec_release_mem__phase_update = 1 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'dst_sel__mec_release_mem__memory_controller', + 1: 'dst_sel__mec_release_mem__tc_l2', + 2: 'dst_sel__mec_release_mem__queue_write_pointer_register', + 3: 'dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit', +} +dst_sel__mec_release_mem__memory_controller = 0 +dst_sel__mec_release_mem__tc_l2 = 1 +dst_sel__mec_release_mem__queue_write_pointer_register = 2 +dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit = 3 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'int_sel__mec_release_mem__none', + 1: 'int_sel__mec_release_mem__send_interrupt_only', + 2: 'int_sel__mec_release_mem__send_interrupt_after_write_confirm', + 3: 'int_sel__mec_release_mem__send_data_after_write_confirm', + 4: 'int_sel__mec_release_mem__unconditionally_send_int_ctxid', + 5: 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare', + 6: 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare', +} +int_sel__mec_release_mem__none = 0 +int_sel__mec_release_mem__send_interrupt_only = 1 +int_sel__mec_release_mem__send_interrupt_after_write_confirm = 2 +int_sel__mec_release_mem__send_data_after_write_confirm = 3 +int_sel__mec_release_mem__unconditionally_send_int_ctxid = 4 +int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare = 5 +int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare = 6 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'data_sel__mec_release_mem__none', + 1: 'data_sel__mec_release_mem__send_32_bit_low', + 2: 'data_sel__mec_release_mem__send_64_bit_data', + 3: 'data_sel__mec_release_mem__send_gpu_clock_counter', + 4: 'data_sel__mec_release_mem__send_cp_perfcounter_hi_lo', + 5: 'data_sel__mec_release_mem__store_gds_data_to_memory', +} +data_sel__mec_release_mem__none = 0 +data_sel__mec_release_mem__send_32_bit_low = 1 +data_sel__mec_release_mem__send_64_bit_data = 2 +data_sel__mec_release_mem__send_gpu_clock_counter = 3 +data_sel__mec_release_mem__send_cp_perfcounter_hi_lo = 4 +data_sel__mec_release_mem__store_gds_data_to_memory = 5 +c_uint32 = ctypes.c_uint32 # enum +class struct_pm4_mec_release_mem(Structure): + pass + +class union_pm4_mec_release_mem_0(Union): + pass + +union_pm4_mec_release_mem_0._pack_ = 1 # source:False +union_pm4_mec_release_mem_0._fields_ = [ + ('header', union_PM4_MES_TYPE_3_HEADER), + ('ordinal1', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_1(Union): + pass + +class struct_pm4_mec_release_mem_1_bitfields2(Structure): + pass + +struct_pm4_mec_release_mem_1_bitfields2._pack_ = 1 # source:False +struct_pm4_mec_release_mem_1_bitfields2._fields_ = [ + ('event_type', ctypes.c_uint32, 6), + ('reserved1', ctypes.c_uint32, 2), + ('event_index', c_uint32, 4), + ('tcl1_vol_action_ena', ctypes.c_uint32, 1), + ('tc_vol_action_ena', ctypes.c_uint32, 1), + ('reserved2', ctypes.c_uint32, 1), + ('tc_wb_action_ena', ctypes.c_uint32, 1), + ('tcl1_action_ena', ctypes.c_uint32, 1), + ('tc_action_ena', ctypes.c_uint32, 1), + ('reserved3', ctypes.c_uint32, 1), + ('tc_nc_action_ena', ctypes.c_uint32, 1), + ('tc_wc_action_ena', ctypes.c_uint32, 1), + ('tc_md_action_ena', ctypes.c_uint32, 1), + ('reserved4', ctypes.c_uint32, 3), + ('cache_policy', c_uint32, 2), + ('reserved5', ctypes.c_uint32, 2), + ('pq_exe_status', c_uint32, 1), + ('reserved6', ctypes.c_uint32, 2), +] + +union_pm4_mec_release_mem_1._pack_ = 1 # source:False +union_pm4_mec_release_mem_1._fields_ = [ + ('bitfields2', struct_pm4_mec_release_mem_1_bitfields2), + ('ordinal2', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_2(Union): + pass + +class struct_pm4_mec_release_mem_2_bitfields3(Structure): + pass + +struct_pm4_mec_release_mem_2_bitfields3._pack_ = 1 # source:False +struct_pm4_mec_release_mem_2_bitfields3._fields_ = [ + ('reserved7', ctypes.c_uint32, 16), + ('dst_sel', c_uint32, 2), + ('reserved8', ctypes.c_uint32, 6), + ('int_sel', c_uint32, 3), + ('reserved9', ctypes.c_uint32, 2), + ('data_sel', c_uint32, 3), +] + +union_pm4_mec_release_mem_2._pack_ = 1 # source:False +union_pm4_mec_release_mem_2._fields_ = [ + ('bitfields3', struct_pm4_mec_release_mem_2_bitfields3), + ('ordinal3', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_3(Union): + pass + +class struct_pm4_mec_release_mem_3_bitfields4(Structure): + pass + +struct_pm4_mec_release_mem_3_bitfields4._pack_ = 1 # source:False +struct_pm4_mec_release_mem_3_bitfields4._fields_ = [ + ('reserved10', ctypes.c_uint32, 2), + ('address_lo_32b', ctypes.c_uint32, 30), +] + +class struct_pm4_mec_release_mem_3_bitfields4b(Structure): + pass + +struct_pm4_mec_release_mem_3_bitfields4b._pack_ = 1 # source:False +struct_pm4_mec_release_mem_3_bitfields4b._fields_ = [ + ('reserved11', ctypes.c_uint32, 3), + ('address_lo_64b', ctypes.c_uint32, 29), +] + +union_pm4_mec_release_mem_3._pack_ = 1 # source:False +union_pm4_mec_release_mem_3._fields_ = [ + ('bitfields4', struct_pm4_mec_release_mem_3_bitfields4), + ('bitfields4b', struct_pm4_mec_release_mem_3_bitfields4b), + ('reserved12', ctypes.c_uint32), + ('ordinal4', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_4(Union): + pass + +union_pm4_mec_release_mem_4._pack_ = 1 # source:False +union_pm4_mec_release_mem_4._fields_ = [ + ('address_hi', ctypes.c_uint32), + ('reserved13', ctypes.c_uint32), + ('ordinal5', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_5(Union): + pass + +class struct_pm4_mec_release_mem_5_bitfields6c(Structure): + pass + +struct_pm4_mec_release_mem_5_bitfields6c._pack_ = 1 # source:False +struct_pm4_mec_release_mem_5_bitfields6c._fields_ = [ + ('dw_offset', ctypes.c_uint32, 16), + ('num_dwords', ctypes.c_uint32, 16), +] + +union_pm4_mec_release_mem_5._pack_ = 1 # source:False +union_pm4_mec_release_mem_5._fields_ = [ + ('data_lo', ctypes.c_uint32), + ('cmp_data_lo', ctypes.c_uint32), + ('bitfields6c', struct_pm4_mec_release_mem_5_bitfields6c), + ('reserved14', ctypes.c_uint32), + ('ordinal6', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_6(Union): + pass + +union_pm4_mec_release_mem_6._pack_ = 1 # source:False +union_pm4_mec_release_mem_6._fields_ = [ + ('data_hi', ctypes.c_uint32), + ('cmp_data_hi', ctypes.c_uint32), + ('reserved15', ctypes.c_uint32), + ('reserved16', ctypes.c_uint32), + ('ordinal7', ctypes.c_uint32), +] + +struct_pm4_mec_release_mem._pack_ = 1 # source:False +struct_pm4_mec_release_mem._anonymous_ = ('_0', '_1', '_2', '_3', '_4', '_5', '_6',) +struct_pm4_mec_release_mem._fields_ = [ + ('_0', union_pm4_mec_release_mem_0), + ('_1', union_pm4_mec_release_mem_1), + ('_2', union_pm4_mec_release_mem_2), + ('_3', union_pm4_mec_release_mem_3), + ('_4', union_pm4_mec_release_mem_4), + ('_5', union_pm4_mec_release_mem_5), + ('_6', union_pm4_mec_release_mem_6), + ('int_ctxid', ctypes.c_uint32), +] + + +# values for enumeration 'WRITE_DATA_dst_sel_enum' +WRITE_DATA_dst_sel_enum__enumvalues = { + 0: 'dst_sel___write_data__mem_mapped_register', + 2: 'dst_sel___write_data__tc_l2', + 3: 'dst_sel___write_data__gds', + 5: 'dst_sel___write_data__memory', + 6: 'dst_sel___write_data__memory_mapped_adc_persistent_state', +} +dst_sel___write_data__mem_mapped_register = 0 +dst_sel___write_data__tc_l2 = 2 +dst_sel___write_data__gds = 3 +dst_sel___write_data__memory = 5 +dst_sel___write_data__memory_mapped_adc_persistent_state = 6 +WRITE_DATA_dst_sel_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_addr_incr_enum' +WRITE_DATA_addr_incr_enum__enumvalues = { + 0: 'addr_incr___write_data__increment_address', + 1: 'addr_incr___write_data__do_not_increment_address', +} +addr_incr___write_data__increment_address = 0 +addr_incr___write_data__do_not_increment_address = 1 +WRITE_DATA_addr_incr_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_wr_confirm_enum' +WRITE_DATA_wr_confirm_enum__enumvalues = { + 0: 'wr_confirm___write_data__do_not_wait_for_write_confirmation', + 1: 'wr_confirm___write_data__wait_for_write_confirmation', +} +wr_confirm___write_data__do_not_wait_for_write_confirmation = 0 +wr_confirm___write_data__wait_for_write_confirmation = 1 +WRITE_DATA_wr_confirm_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_cache_policy_enum' +WRITE_DATA_cache_policy_enum__enumvalues = { + 0: 'cache_policy___write_data__lru', + 1: 'cache_policy___write_data__stream', +} +cache_policy___write_data__lru = 0 +cache_policy___write_data__stream = 1 +WRITE_DATA_cache_policy_enum = ctypes.c_uint32 # enum +class struct_pm4_mec_write_data_mmio(Structure): + pass + +class union_pm4_mec_write_data_mmio_0(Union): + pass + +union_pm4_mec_write_data_mmio_0._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_0._fields_ = [ + ('header', union_PM4_MES_TYPE_3_HEADER), + ('ordinal1', ctypes.c_uint32), +] + +class union_pm4_mec_write_data_mmio_1(Union): + pass + +class struct_pm4_mec_write_data_mmio_1_bitfields2(Structure): + pass + +struct_pm4_mec_write_data_mmio_1_bitfields2._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio_1_bitfields2._fields_ = [ + ('reserved1', ctypes.c_uint32, 8), + ('dst_sel', ctypes.c_uint32, 4), + ('reserved2', ctypes.c_uint32, 4), + ('addr_incr', ctypes.c_uint32, 1), + ('reserved3', ctypes.c_uint32, 2), + ('resume_vf', ctypes.c_uint32, 1), + ('wr_confirm', ctypes.c_uint32, 1), + ('reserved4', ctypes.c_uint32, 4), + ('cache_policy', ctypes.c_uint32, 2), + ('reserved5', ctypes.c_uint32, 5), +] + +union_pm4_mec_write_data_mmio_1._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_1._fields_ = [ + ('bitfields2', struct_pm4_mec_write_data_mmio_1_bitfields2), + ('ordinal2', ctypes.c_uint32), +] + +class union_pm4_mec_write_data_mmio_2(Union): + pass + +class struct_pm4_mec_write_data_mmio_2_bitfields3(Structure): + pass + +struct_pm4_mec_write_data_mmio_2_bitfields3._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio_2_bitfields3._fields_ = [ + ('dst_mmreg_addr', ctypes.c_uint32, 18), + ('reserved6', ctypes.c_uint32, 14), +] + +union_pm4_mec_write_data_mmio_2._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_2._fields_ = [ + ('bitfields3', struct_pm4_mec_write_data_mmio_2_bitfields3), + ('ordinal3', ctypes.c_uint32), +] + +struct_pm4_mec_write_data_mmio._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio._anonymous_ = ('_0', '_1', '_2',) +struct_pm4_mec_write_data_mmio._fields_ = [ + ('_0', union_pm4_mec_write_data_mmio_0), + ('_1', union_pm4_mec_write_data_mmio_1), + ('_2', union_pm4_mec_write_data_mmio_2), + ('reserved7', ctypes.c_uint32), + ('data', ctypes.c_uint32), +] + + +# values for enumeration 'c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT' +c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT__enumvalues = { + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', +} +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT = ctypes.c_uint32 # enum +NVD_H = True # macro +PACKET_TYPE0 = 0 # macro +PACKET_TYPE1 = 1 # macro +PACKET_TYPE2 = 2 # macro +PACKET_TYPE3 = 3 # macro +def CP_PACKET_GET_TYPE(h): # macro + return (((h)>>30)&3) +def CP_PACKET_GET_COUNT(h): # macro + return (((h)>>16)&0x3FFF) +def CP_PACKET0_GET_REG(h): # macro + return ((h)&0xFFFF) +def CP_PACKET3_GET_OPCODE(h): # macro + return (((h)>>8)&0xFF) +def PACKET0(reg, n): # macro + return ((0<<30)|((reg)&0xFFFF)|((n)&0x3FFF)<<16) +CP_PACKET2 = 0x80000000 # macro +PACKET2_PAD_SHIFT = 0 # macro +PACKET2_PAD_MASK = (0x3fffffff<<0) # macro +# def PACKET2(v): # macro +# return (0x80000000|REG_SET(PACKET2_PAD,(v))) +def PACKET3(op, n): # macro + return ((3<<30)|(((op)&0xFF)<<8)|((n)&0x3FFF)<<16) +def PACKET3_COMPUTE(op, n): # macro + return (PACKET3(op,n)|1<<1) +PACKET3_NOP = 0x10 # macro +PACKET3_SET_BASE = 0x11 # macro +def PACKET3_BASE_INDEX(x): # macro + return ((x)<<0) +CE_PARTITION_BASE = 3 # macro +PACKET3_CLEAR_STATE = 0x12 # macro +PACKET3_INDEX_BUFFER_SIZE = 0x13 # macro +PACKET3_DISPATCH_DIRECT = 0x15 # macro +PACKET3_DISPATCH_INDIRECT = 0x16 # macro +PACKET3_INDIRECT_BUFFER_END = 0x17 # macro +PACKET3_INDIRECT_BUFFER_CNST_END = 0x19 # macro +PACKET3_ATOMIC_GDS = 0x1D # macro +PACKET3_ATOMIC_MEM = 0x1E # macro +PACKET3_OCCLUSION_QUERY = 0x1F # macro +PACKET3_SET_PREDICATION = 0x20 # macro +PACKET3_REG_RMW = 0x21 # macro +PACKET3_COND_EXEC = 0x22 # macro +PACKET3_PRED_EXEC = 0x23 # macro +PACKET3_DRAW_INDIRECT = 0x24 # macro +PACKET3_DRAW_INDEX_INDIRECT = 0x25 # macro +PACKET3_INDEX_BASE = 0x26 # macro +PACKET3_DRAW_INDEX_2 = 0x27 # macro +PACKET3_CONTEXT_CONTROL = 0x28 # macro +PACKET3_INDEX_TYPE = 0x2A # macro +PACKET3_DRAW_INDIRECT_MULTI = 0x2C # macro +PACKET3_DRAW_INDEX_AUTO = 0x2D # macro +PACKET3_NUM_INSTANCES = 0x2F # macro +PACKET3_DRAW_INDEX_MULTI_AUTO = 0x30 # macro +PACKET3_INDIRECT_BUFFER_PRIV = 0x32 # macro +PACKET3_INDIRECT_BUFFER_CNST = 0x33 # macro +PACKET3_COND_INDIRECT_BUFFER_CNST = 0x33 # macro +PACKET3_STRMOUT_BUFFER_UPDATE = 0x34 # macro +PACKET3_DRAW_INDEX_OFFSET_2 = 0x35 # macro +PACKET3_DRAW_PREAMBLE = 0x36 # macro +PACKET3_WRITE_DATA = 0x37 # macro +def WRITE_DATA_DST_SEL(x): # macro + return ((x)<<8) +WR_ONE_ADDR = (1<<16) # macro +WR_CONFIRM = (1<<20) # macro +def WRITE_DATA_CACHE_POLICY(x): # macro + return ((x)<<25) +def WRITE_DATA_ENGINE_SEL(x): # macro + return ((x)<<30) +PACKET3_DRAW_INDEX_INDIRECT_MULTI = 0x38 # macro +PACKET3_MEM_SEMAPHORE = 0x39 # macro +PACKET3_SEM_USE_MAILBOX = (0x1<<16) # macro +PACKET3_SEM_SEL_SIGNAL_TYPE = (0x1<<20) # macro +PACKET3_SEM_SEL_SIGNAL = (0x6<<29) # macro +PACKET3_SEM_SEL_WAIT = (0x7<<29) # macro +PACKET3_DRAW_INDEX_MULTI_INST = 0x3A # macro +PACKET3_COPY_DW = 0x3B # macro +PACKET3_WAIT_REG_MEM = 0x3C # macro +def WAIT_REG_MEM_FUNCTION(x): # macro + return ((x)<<0) +def WAIT_REG_MEM_MEM_SPACE(x): # macro + return ((x)<<4) +def WAIT_REG_MEM_OPERATION(x): # macro + return ((x)<<6) +def WAIT_REG_MEM_ENGINE(x): # macro + return ((x)<<8) +PACKET3_INDIRECT_BUFFER = 0x3F # macro +INDIRECT_BUFFER_VALID = (1<<23) # macro +def INDIRECT_BUFFER_CACHE_POLICY(x): # macro + return ((x)<<28) +def INDIRECT_BUFFER_PRE_ENB(x): # macro + return ((x)<<21) +def INDIRECT_BUFFER_PRE_RESUME(x): # macro + return ((x)<<30) +PACKET3_COND_INDIRECT_BUFFER = 0x3F # macro +PACKET3_COPY_DATA = 0x40 # macro +PACKET3_CP_DMA = 0x41 # macro +PACKET3_PFP_SYNC_ME = 0x42 # macro +PACKET3_SURFACE_SYNC = 0x43 # macro +PACKET3_ME_INITIALIZE = 0x44 # macro +PACKET3_COND_WRITE = 0x45 # macro +PACKET3_EVENT_WRITE = 0x46 # macro +def EVENT_TYPE(x): # macro + return ((x)<<0) +def EVENT_INDEX(x): # macro + return ((x)<<8) +PACKET3_EVENT_WRITE_EOP = 0x47 # macro +PACKET3_EVENT_WRITE_EOS = 0x48 # macro +PACKET3_RELEASE_MEM = 0x49 # macro +def PACKET3_RELEASE_MEM_EVENT_TYPE(x): # macro + return ((x)<<0) +def PACKET3_RELEASE_MEM_EVENT_INDEX(x): # macro + return ((x)<<8) +PACKET3_RELEASE_MEM_GCR_GLM_WB = (1<<12) # macro +PACKET3_RELEASE_MEM_GCR_GLM_INV = (1<<13) # macro +PACKET3_RELEASE_MEM_GCR_GLV_INV = (1<<14) # macro +PACKET3_RELEASE_MEM_GCR_GL1_INV = (1<<15) # macro +PACKET3_RELEASE_MEM_GCR_GL2_US = (1<<16) # macro +PACKET3_RELEASE_MEM_GCR_GL2_RANGE = (1<<17) # macro +PACKET3_RELEASE_MEM_GCR_GL2_DISCARD = (1<<19) # macro +PACKET3_RELEASE_MEM_GCR_GL2_INV = (1<<20) # macro +PACKET3_RELEASE_MEM_GCR_GL2_WB = (1<<21) # macro +PACKET3_RELEASE_MEM_GCR_SEQ = (1<<22) # macro +def PACKET3_RELEASE_MEM_CACHE_POLICY(x): # macro + return ((x)<<25) +PACKET3_RELEASE_MEM_EXECUTE = (1<<28) # macro +def PACKET3_RELEASE_MEM_DATA_SEL(x): # macro + return ((x)<<29) +def PACKET3_RELEASE_MEM_INT_SEL(x): # macro + return ((x)<<24) +def PACKET3_RELEASE_MEM_DST_SEL(x): # macro + return ((x)<<16) +PACKET3_PREAMBLE_CNTL = 0x4A # macro +PACKET3_PREAMBLE_BEGIN_CLEAR_STATE = (2<<28) # macro +PACKET3_PREAMBLE_END_CLEAR_STATE = (3<<28) # macro +PACKET3_DMA_DATA = 0x50 # macro +def PACKET3_DMA_DATA_ENGINE(x): # macro + return ((x)<<0) +def PACKET3_DMA_DATA_SRC_CACHE_POLICY(x): # macro + return ((x)<<13) +def PACKET3_DMA_DATA_DST_SEL(x): # macro + return ((x)<<20) +def PACKET3_DMA_DATA_DST_CACHE_POLICY(x): # macro + return ((x)<<25) +def PACKET3_DMA_DATA_SRC_SEL(x): # macro + return ((x)<<29) +PACKET3_DMA_DATA_CP_SYNC = (1<<31) # macro +PACKET3_DMA_DATA_CMD_SAS = (1<<26) # macro +PACKET3_DMA_DATA_CMD_DAS = (1<<27) # macro +PACKET3_DMA_DATA_CMD_SAIC = (1<<28) # macro +PACKET3_DMA_DATA_CMD_DAIC = (1<<29) # macro +PACKET3_DMA_DATA_CMD_RAW_WAIT = (1<<30) # macro +PACKET3_CONTEXT_REG_RMW = 0x51 # macro +PACKET3_GFX_CNTX_UPDATE = 0x52 # macro +PACKET3_BLK_CNTX_UPDATE = 0x53 # macro +PACKET3_INCR_UPDT_STATE = 0x55 # macro +PACKET3_ACQUIRE_MEM = 0x58 # macro +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLI_INV(x): # macro + return ((x)<<0) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL1_RANGE(x): # macro + return ((x)<<2) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_WB(x): # macro + return ((x)<<4) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_INV(x): # macro + return ((x)<<5) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_WB(x): # macro + return ((x)<<6) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_INV(x): # macro + return ((x)<<7) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GLV_INV(x): # macro + return ((x)<<8) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL1_INV(x): # macro + return ((x)<<9) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_US(x): # macro + return ((x)<<10) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_RANGE(x): # macro + return ((x)<<11) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_DISCARD(x): # macro + return ((x)<<13) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_INV(x): # macro + return ((x)<<14) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_WB(x): # macro + return ((x)<<15) +def PACKET3_ACQUIRE_MEM_GCR_CNTL_SEQ(x): # macro + return ((x)<<16) +PACKET3_ACQUIRE_MEM_GCR_RANGE_IS_PA = (1<<18) # macro +PACKET3_REWIND = 0x59 # macro +PACKET3_INTERRUPT = 0x5A # macro +PACKET3_GEN_PDEPTE = 0x5B # macro +PACKET3_INDIRECT_BUFFER_PASID = 0x5C # macro +PACKET3_PRIME_UTCL2 = 0x5D # macro +PACKET3_LOAD_UCONFIG_REG = 0x5E # macro +PACKET3_LOAD_SH_REG = 0x5F # macro +PACKET3_LOAD_CONFIG_REG = 0x60 # macro +PACKET3_LOAD_CONTEXT_REG = 0x61 # macro +PACKET3_LOAD_COMPUTE_STATE = 0x62 # macro +PACKET3_LOAD_SH_REG_INDEX = 0x63 # macro +PACKET3_SET_CONFIG_REG = 0x68 # macro +PACKET3_SET_CONFIG_REG_START = 0x00002000 # macro +PACKET3_SET_CONFIG_REG_END = 0x00002c00 # macro +PACKET3_SET_CONTEXT_REG = 0x69 # macro +PACKET3_SET_CONTEXT_REG_START = 0x0000a000 # macro +PACKET3_SET_CONTEXT_REG_END = 0x0000a400 # macro +PACKET3_SET_CONTEXT_REG_INDEX = 0x6A # macro +PACKET3_SET_VGPR_REG_DI_MULTI = 0x71 # macro +PACKET3_SET_SH_REG_DI = 0x72 # macro +PACKET3_SET_CONTEXT_REG_INDIRECT = 0x73 # macro +PACKET3_SET_SH_REG_DI_MULTI = 0x74 # macro +PACKET3_GFX_PIPE_LOCK = 0x75 # macro +PACKET3_SET_SH_REG = 0x76 # macro +PACKET3_SET_SH_REG_START = 0x00002c00 # macro +PACKET3_SET_SH_REG_END = 0x00003000 # macro +PACKET3_SET_SH_REG_OFFSET = 0x77 # macro +PACKET3_SET_QUEUE_REG = 0x78 # macro +PACKET3_SET_UCONFIG_REG = 0x79 # macro +PACKET3_SET_UCONFIG_REG_START = 0x0000c000 # macro +PACKET3_SET_UCONFIG_REG_END = 0x0000c400 # macro +PACKET3_SET_UCONFIG_REG_INDEX = 0x7A # macro +PACKET3_FORWARD_HEADER = 0x7C # macro +PACKET3_SCRATCH_RAM_WRITE = 0x7D # macro +PACKET3_SCRATCH_RAM_READ = 0x7E # macro +PACKET3_LOAD_CONST_RAM = 0x80 # macro +PACKET3_WRITE_CONST_RAM = 0x81 # macro +PACKET3_DUMP_CONST_RAM = 0x83 # macro +PACKET3_INCREMENT_CE_COUNTER = 0x84 # macro +PACKET3_INCREMENT_DE_COUNTER = 0x85 # macro +PACKET3_WAIT_ON_CE_COUNTER = 0x86 # macro +PACKET3_WAIT_ON_DE_COUNTER_DIFF = 0x88 # macro +PACKET3_SWITCH_BUFFER = 0x8B # macro +PACKET3_DISPATCH_DRAW_PREAMBLE = 0x8C # macro +PACKET3_DISPATCH_DRAW_PREAMBLE_ACE = 0x8C # macro +PACKET3_DISPATCH_DRAW = 0x8D # macro +PACKET3_DISPATCH_DRAW_ACE = 0x8D # macro +PACKET3_GET_LOD_STATS = 0x8E # macro +PACKET3_DRAW_MULTI_PREAMBLE = 0x8F # macro +PACKET3_FRAME_CONTROL = 0x90 # macro +FRAME_TMZ = (1<<0) # macro +def FRAME_CMD(x): # macro + return ((x)<<28) +PACKET3_INDEX_ATTRIBUTES_INDIRECT = 0x91 # macro +PACKET3_WAIT_REG_MEM64 = 0x93 # macro +PACKET3_COND_PREEMPT = 0x94 # macro +PACKET3_HDP_FLUSH = 0x95 # macro +PACKET3_COPY_DATA_RB = 0x96 # macro +PACKET3_INVALIDATE_TLBS = 0x98 # macro +def PACKET3_INVALIDATE_TLBS_DST_SEL(x): # macro + return ((x)<<0) +def PACKET3_INVALIDATE_TLBS_ALL_HUB(x): # macro + return ((x)<<4) +def PACKET3_INVALIDATE_TLBS_PASID(x): # macro + return ((x)<<5) +PACKET3_AQL_PACKET = 0x99 # macro +PACKET3_DMA_DATA_FILL_MULTI = 0x9A # macro +PACKET3_SET_SH_REG_INDEX = 0x9B # macro +PACKET3_DRAW_INDIRECT_COUNT_MULTI = 0x9C # macro +PACKET3_DRAW_INDEX_INDIRECT_COUNT_MULTI = 0x9D # macro +PACKET3_DUMP_CONST_RAM_OFFSET = 0x9E # macro +PACKET3_LOAD_CONTEXT_REG_INDEX = 0x9F # macro +PACKET3_SET_RESOURCES = 0xA0 # macro +def PACKET3_SET_RESOURCES_VMID_MASK(x): # macro + return ((x)<<0) +def PACKET3_SET_RESOURCES_UNMAP_LATENTY(x): # macro + return ((x)<<16) +def PACKET3_SET_RESOURCES_QUEUE_TYPE(x): # macro + return ((x)<<29) +PACKET3_MAP_PROCESS = 0xA1 # macro +PACKET3_MAP_QUEUES = 0xA2 # macro +def PACKET3_MAP_QUEUES_QUEUE_SEL(x): # macro + return ((x)<<4) +def PACKET3_MAP_QUEUES_VMID(x): # macro + return ((x)<<8) +def PACKET3_MAP_QUEUES_QUEUE(x): # macro + return ((x)<<13) +def PACKET3_MAP_QUEUES_PIPE(x): # macro + return ((x)<<16) +def PACKET3_MAP_QUEUES_ME(x): # macro + return ((x)<<18) +def PACKET3_MAP_QUEUES_QUEUE_TYPE(x): # macro + return ((x)<<21) +def PACKET3_MAP_QUEUES_ALLOC_FORMAT(x): # macro + return ((x)<<24) +def PACKET3_MAP_QUEUES_ENGINE_SEL(x): # macro + return ((x)<<26) +def PACKET3_MAP_QUEUES_NUM_QUEUES(x): # macro + return ((x)<<29) +def PACKET3_MAP_QUEUES_CHECK_DISABLE(x): # macro + return ((x)<<1) +def PACKET3_MAP_QUEUES_DOORBELL_OFFSET(x): # macro + return ((x)<<2) +PACKET3_UNMAP_QUEUES = 0xA3 # macro +def PACKET3_UNMAP_QUEUES_ACTION(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_QUEUE_SEL(x): # macro + return ((x)<<4) +def PACKET3_UNMAP_QUEUES_ENGINE_SEL(x): # macro + return ((x)<<26) +def PACKET3_UNMAP_QUEUES_NUM_QUEUES(x): # macro + return ((x)<<29) +def PACKET3_UNMAP_QUEUES_PASID(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET0(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET1(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_RB_WPTR(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET2(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET3(x): # macro + return ((x)<<2) +PACKET3_QUERY_STATUS = 0xA4 # macro +def PACKET3_QUERY_STATUS_CONTEXT_ID(x): # macro + return ((x)<<0) +def PACKET3_QUERY_STATUS_INTERRUPT_SEL(x): # macro + return ((x)<<28) +def PACKET3_QUERY_STATUS_COMMAND(x): # macro + return ((x)<<30) +def PACKET3_QUERY_STATUS_PASID(x): # macro + return ((x)<<0) +def PACKET3_QUERY_STATUS_DOORBELL_OFFSET(x): # macro + return ((x)<<2) +def PACKET3_QUERY_STATUS_ENG_SEL(x): # macro + return ((x)<<25) +PACKET3_RUN_LIST = 0xA5 # macro +PACKET3_MAP_PROCESS_VM = 0xA6 # macro +PACKET3_SET_Q_PREEMPTION_MODE = 0xF0 # macro +def PACKET3_SET_Q_PREEMPTION_MODE_IB_VMID(x): # macro + return ((x)<<0) +PACKET3_SET_Q_PREEMPTION_MODE_INIT_SHADOW_MEM = (1<<0) # macro +__all__ = \ + ['CACHE_FLUSH_AND_INV_TS_EVENT', 'CE_PARTITION_BASE', + 'CP_PACKET2', 'F32_MES_PM4_PACKETS_H', 'FRAME_TMZ', + 'INDIRECT_BUFFER_VALID', 'NVD_H', 'PACKET2_PAD_MASK', + 'PACKET2_PAD_SHIFT', 'PACKET3_ACQUIRE_MEM', + 'PACKET3_ACQUIRE_MEM_GCR_RANGE_IS_PA', 'PACKET3_AQL_PACKET', + 'PACKET3_ATOMIC_GDS', 'PACKET3_ATOMIC_MEM', + 'PACKET3_BLK_CNTX_UPDATE', 'PACKET3_CLEAR_STATE', + 'PACKET3_COND_EXEC', 'PACKET3_COND_INDIRECT_BUFFER', + 'PACKET3_COND_INDIRECT_BUFFER_CNST', 'PACKET3_COND_PREEMPT', + 'PACKET3_COND_WRITE', 'PACKET3_CONTEXT_CONTROL', + 'PACKET3_CONTEXT_REG_RMW', 'PACKET3_COPY_DATA', + 'PACKET3_COPY_DATA_RB', 'PACKET3_COPY_DW', 'PACKET3_CP_DMA', + 'PACKET3_DISPATCH_DIRECT', 'PACKET3_DISPATCH_DRAW', + 'PACKET3_DISPATCH_DRAW_ACE', 'PACKET3_DISPATCH_DRAW_PREAMBLE', + 'PACKET3_DISPATCH_DRAW_PREAMBLE_ACE', 'PACKET3_DISPATCH_INDIRECT', + 'PACKET3_DMA_DATA', 'PACKET3_DMA_DATA_CMD_DAIC', + 'PACKET3_DMA_DATA_CMD_DAS', 'PACKET3_DMA_DATA_CMD_RAW_WAIT', + 'PACKET3_DMA_DATA_CMD_SAIC', 'PACKET3_DMA_DATA_CMD_SAS', + 'PACKET3_DMA_DATA_CP_SYNC', 'PACKET3_DMA_DATA_FILL_MULTI', + 'PACKET3_DRAW_INDEX_2', 'PACKET3_DRAW_INDEX_AUTO', + 'PACKET3_DRAW_INDEX_INDIRECT', + 'PACKET3_DRAW_INDEX_INDIRECT_COUNT_MULTI', + 'PACKET3_DRAW_INDEX_INDIRECT_MULTI', + 'PACKET3_DRAW_INDEX_MULTI_AUTO', 'PACKET3_DRAW_INDEX_MULTI_INST', + 'PACKET3_DRAW_INDEX_OFFSET_2', 'PACKET3_DRAW_INDIRECT', + 'PACKET3_DRAW_INDIRECT_COUNT_MULTI', + 'PACKET3_DRAW_INDIRECT_MULTI', 'PACKET3_DRAW_MULTI_PREAMBLE', + 'PACKET3_DRAW_PREAMBLE', 'PACKET3_DUMP_CONST_RAM', + 'PACKET3_DUMP_CONST_RAM_OFFSET', 'PACKET3_EVENT_WRITE', + 'PACKET3_EVENT_WRITE_EOP', 'PACKET3_EVENT_WRITE_EOS', + 'PACKET3_FORWARD_HEADER', 'PACKET3_FRAME_CONTROL', + 'PACKET3_GEN_PDEPTE', 'PACKET3_GET_LOD_STATS', + 'PACKET3_GFX_CNTX_UPDATE', 'PACKET3_GFX_PIPE_LOCK', + 'PACKET3_HDP_FLUSH', 'PACKET3_INCREMENT_CE_COUNTER', + 'PACKET3_INCREMENT_DE_COUNTER', 'PACKET3_INCR_UPDT_STATE', + 'PACKET3_INDEX_ATTRIBUTES_INDIRECT', 'PACKET3_INDEX_BASE', + 'PACKET3_INDEX_BUFFER_SIZE', 'PACKET3_INDEX_TYPE', + 'PACKET3_INDIRECT_BUFFER', 'PACKET3_INDIRECT_BUFFER_CNST', + 'PACKET3_INDIRECT_BUFFER_CNST_END', 'PACKET3_INDIRECT_BUFFER_END', + 'PACKET3_INDIRECT_BUFFER_PASID', 'PACKET3_INDIRECT_BUFFER_PRIV', + 'PACKET3_INTERRUPT', 'PACKET3_INVALIDATE_TLBS', + 'PACKET3_LOAD_COMPUTE_STATE', 'PACKET3_LOAD_CONFIG_REG', + 'PACKET3_LOAD_CONST_RAM', 'PACKET3_LOAD_CONTEXT_REG', + 'PACKET3_LOAD_CONTEXT_REG_INDEX', 'PACKET3_LOAD_SH_REG', + 'PACKET3_LOAD_SH_REG_INDEX', 'PACKET3_LOAD_UCONFIG_REG', + 'PACKET3_MAP_PROCESS', 'PACKET3_MAP_PROCESS_VM', + 'PACKET3_MAP_QUEUES', 'PACKET3_MEM_SEMAPHORE', + 'PACKET3_ME_INITIALIZE', 'PACKET3_NOP', 'PACKET3_NUM_INSTANCES', + 'PACKET3_OCCLUSION_QUERY', 'PACKET3_PFP_SYNC_ME', + 'PACKET3_PREAMBLE_BEGIN_CLEAR_STATE', 'PACKET3_PREAMBLE_CNTL', + 'PACKET3_PREAMBLE_END_CLEAR_STATE', 'PACKET3_PRED_EXEC', + 'PACKET3_PRIME_UTCL2', 'PACKET3_QUERY_STATUS', 'PACKET3_REG_RMW', + 'PACKET3_RELEASE_MEM', 'PACKET3_RELEASE_MEM_EXECUTE', + 'PACKET3_RELEASE_MEM_GCR_GL1_INV', + 'PACKET3_RELEASE_MEM_GCR_GL2_DISCARD', + 'PACKET3_RELEASE_MEM_GCR_GL2_INV', + 'PACKET3_RELEASE_MEM_GCR_GL2_RANGE', + 'PACKET3_RELEASE_MEM_GCR_GL2_US', + 'PACKET3_RELEASE_MEM_GCR_GL2_WB', + 'PACKET3_RELEASE_MEM_GCR_GLM_INV', + 'PACKET3_RELEASE_MEM_GCR_GLM_WB', + 'PACKET3_RELEASE_MEM_GCR_GLV_INV', 'PACKET3_RELEASE_MEM_GCR_SEQ', + 'PACKET3_REWIND', 'PACKET3_RUN_LIST', 'PACKET3_SCRATCH_RAM_READ', + 'PACKET3_SCRATCH_RAM_WRITE', 'PACKET3_SEM_SEL_SIGNAL', + 'PACKET3_SEM_SEL_SIGNAL_TYPE', 'PACKET3_SEM_SEL_WAIT', + 'PACKET3_SEM_USE_MAILBOX', 'PACKET3_SET_BASE', + 'PACKET3_SET_CONFIG_REG', 'PACKET3_SET_CONFIG_REG_END', + 'PACKET3_SET_CONFIG_REG_START', 'PACKET3_SET_CONTEXT_REG', + 'PACKET3_SET_CONTEXT_REG_END', 'PACKET3_SET_CONTEXT_REG_INDEX', + 'PACKET3_SET_CONTEXT_REG_INDIRECT', + 'PACKET3_SET_CONTEXT_REG_START', 'PACKET3_SET_PREDICATION', + 'PACKET3_SET_QUEUE_REG', 'PACKET3_SET_Q_PREEMPTION_MODE', + 'PACKET3_SET_Q_PREEMPTION_MODE_INIT_SHADOW_MEM', + 'PACKET3_SET_RESOURCES', 'PACKET3_SET_SH_REG', + 'PACKET3_SET_SH_REG_DI', 'PACKET3_SET_SH_REG_DI_MULTI', + 'PACKET3_SET_SH_REG_END', 'PACKET3_SET_SH_REG_INDEX', + 'PACKET3_SET_SH_REG_OFFSET', 'PACKET3_SET_SH_REG_START', + 'PACKET3_SET_UCONFIG_REG', 'PACKET3_SET_UCONFIG_REG_END', + 'PACKET3_SET_UCONFIG_REG_INDEX', 'PACKET3_SET_UCONFIG_REG_START', + 'PACKET3_SET_VGPR_REG_DI_MULTI', 'PACKET3_STRMOUT_BUFFER_UPDATE', + 'PACKET3_SURFACE_SYNC', 'PACKET3_SWITCH_BUFFER', + 'PACKET3_UNMAP_QUEUES', 'PACKET3_WAIT_ON_CE_COUNTER', + 'PACKET3_WAIT_ON_DE_COUNTER_DIFF', 'PACKET3_WAIT_REG_MEM', + 'PACKET3_WAIT_REG_MEM64', 'PACKET3_WRITE_CONST_RAM', + 'PACKET3_WRITE_DATA', 'PACKET_TYPE0', 'PACKET_TYPE1', + 'PACKET_TYPE2', 'PACKET_TYPE3', 'PM4_MEC_RELEASE_MEM_DEFINED', + 'PM4_MEC_WRITE_DATA_DEFINED', 'PM4_MES_HEADER_DEFINED', + 'WRITE_DATA_addr_incr_enum', 'WRITE_DATA_cache_policy_enum', + 'WRITE_DATA_dst_sel_enum', 'WRITE_DATA_wr_confirm_enum', + 'WR_CONFIRM', 'WR_ONE_ADDR', + 'addr_incr___write_data__do_not_increment_address', + 'addr_incr___write_data__increment_address', + 'c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT', 'c_uint32', 'c_uint32', + 'c_uint32', 'c_uint32', 'c_uint32', 'c_uint32', + 'cache_policy___write_data__lru', + 'cache_policy___write_data__stream', + 'cache_policy__mec_release_mem__lru', + 'cache_policy__mec_release_mem__stream', + 'data_sel__mec_release_mem__none', + 'data_sel__mec_release_mem__send_32_bit_low', + 'data_sel__mec_release_mem__send_64_bit_data', + 'data_sel__mec_release_mem__send_cp_perfcounter_hi_lo', + 'data_sel__mec_release_mem__send_gpu_clock_counter', + 'data_sel__mec_release_mem__store_gds_data_to_memory', + 'dst_sel___write_data__gds', + 'dst_sel___write_data__mem_mapped_register', + 'dst_sel___write_data__memory', + 'dst_sel___write_data__memory_mapped_adc_persistent_state', + 'dst_sel___write_data__tc_l2', + 'dst_sel__mec_release_mem__memory_controller', + 'dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit', + 'dst_sel__mec_release_mem__queue_write_pointer_register', + 'dst_sel__mec_release_mem__tc_l2', + 'event_index__mec_release_mem__end_of_pipe', + 'event_index__mec_release_mem__shader_done', 'int32_t', + 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare', + 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare', + 'int_sel__mec_release_mem__none', + 'int_sel__mec_release_mem__send_data_after_write_confirm', + 'int_sel__mec_release_mem__send_interrupt_after_write_confirm', + 'int_sel__mec_release_mem__send_interrupt_only', + 'int_sel__mec_release_mem__unconditionally_send_int_ctxid', + 'pq_exe_status__mec_release_mem__default', + 'pq_exe_status__mec_release_mem__phase_update', + 'struct_PM4_MES_TYPE_3_HEADER_0', 'struct_pm4_mec_release_mem', + 'struct_pm4_mec_release_mem_1_bitfields2', + 'struct_pm4_mec_release_mem_2_bitfields3', + 'struct_pm4_mec_release_mem_3_bitfields4', + 'struct_pm4_mec_release_mem_3_bitfields4b', + 'struct_pm4_mec_release_mem_5_bitfields6c', + 'struct_pm4_mec_write_data_mmio', + 'struct_pm4_mec_write_data_mmio_1_bitfields2', + 'struct_pm4_mec_write_data_mmio_2_bitfields3', 'uint32_t', + 'union_PM4_MES_TYPE_3_HEADER', 'union_pm4_mec_release_mem_0', + 'union_pm4_mec_release_mem_1', 'union_pm4_mec_release_mem_2', + 'union_pm4_mec_release_mem_3', 'union_pm4_mec_release_mem_4', + 'union_pm4_mec_release_mem_5', 'union_pm4_mec_release_mem_6', + 'union_pm4_mec_write_data_mmio_0', + 'union_pm4_mec_write_data_mmio_1', + 'union_pm4_mec_write_data_mmio_2', + 'wr_confirm___write_data__do_not_wait_for_write_confirmation', + 'wr_confirm___write_data__wait_for_write_confirmation'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_soc15.py b/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_soc15.py new file mode 100644 index 0000000000..16e9ee3d5e --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/pm4_soc15.py @@ -0,0 +1,931 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +F32_MES_PM4_PACKETS_H = True # macro +uint32_t = True # macro +int32_t = True # macro +PM4_MES_HEADER_DEFINED = True # macro +PM4_MEC_RELEASE_MEM_DEFINED = True # macro +PM4_MEC_WRITE_DATA_DEFINED = True # macro +class union_PM4_MES_TYPE_3_HEADER(Union): + pass + +class struct_PM4_MES_TYPE_3_HEADER_0(Structure): + pass + +struct_PM4_MES_TYPE_3_HEADER_0._pack_ = 1 # source:False +struct_PM4_MES_TYPE_3_HEADER_0._fields_ = [ + ('reserved1', ctypes.c_uint32, 8), + ('opcode', ctypes.c_uint32, 8), + ('count', ctypes.c_uint32, 14), + ('type', ctypes.c_uint32, 2), +] + +union_PM4_MES_TYPE_3_HEADER._pack_ = 1 # source:False +union_PM4_MES_TYPE_3_HEADER._anonymous_ = ('_0',) +union_PM4_MES_TYPE_3_HEADER._fields_ = [ + ('_0', struct_PM4_MES_TYPE_3_HEADER_0), + ('u32All', ctypes.c_uint32), +] + + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 5: 'event_index__mec_release_mem__end_of_pipe', + 6: 'event_index__mec_release_mem__shader_done', +} +event_index__mec_release_mem__end_of_pipe = 5 +event_index__mec_release_mem__shader_done = 6 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'cache_policy__mec_release_mem__lru', + 1: 'cache_policy__mec_release_mem__stream', +} +cache_policy__mec_release_mem__lru = 0 +cache_policy__mec_release_mem__stream = 1 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'pq_exe_status__mec_release_mem__default', + 1: 'pq_exe_status__mec_release_mem__phase_update', +} +pq_exe_status__mec_release_mem__default = 0 +pq_exe_status__mec_release_mem__phase_update = 1 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'dst_sel__mec_release_mem__memory_controller', + 1: 'dst_sel__mec_release_mem__tc_l2', + 2: 'dst_sel__mec_release_mem__queue_write_pointer_register', + 3: 'dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit', +} +dst_sel__mec_release_mem__memory_controller = 0 +dst_sel__mec_release_mem__tc_l2 = 1 +dst_sel__mec_release_mem__queue_write_pointer_register = 2 +dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit = 3 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'int_sel__mec_release_mem__none', + 1: 'int_sel__mec_release_mem__send_interrupt_only', + 2: 'int_sel__mec_release_mem__send_interrupt_after_write_confirm', + 3: 'int_sel__mec_release_mem__send_data_after_write_confirm', + 4: 'int_sel__mec_release_mem__unconditionally_send_int_ctxid', + 5: 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare', + 6: 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare', +} +int_sel__mec_release_mem__none = 0 +int_sel__mec_release_mem__send_interrupt_only = 1 +int_sel__mec_release_mem__send_interrupt_after_write_confirm = 2 +int_sel__mec_release_mem__send_data_after_write_confirm = 3 +int_sel__mec_release_mem__unconditionally_send_int_ctxid = 4 +int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare = 5 +int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare = 6 +c_uint32 = ctypes.c_uint32 # enum + +# values for enumeration 'c_uint32' +c_uint32__enumvalues = { + 0: 'data_sel__mec_release_mem__none', + 1: 'data_sel__mec_release_mem__send_32_bit_low', + 2: 'data_sel__mec_release_mem__send_64_bit_data', + 3: 'data_sel__mec_release_mem__send_gpu_clock_counter', + 4: 'data_sel__mec_release_mem__send_cp_perfcounter_hi_lo', + 5: 'data_sel__mec_release_mem__store_gds_data_to_memory', +} +data_sel__mec_release_mem__none = 0 +data_sel__mec_release_mem__send_32_bit_low = 1 +data_sel__mec_release_mem__send_64_bit_data = 2 +data_sel__mec_release_mem__send_gpu_clock_counter = 3 +data_sel__mec_release_mem__send_cp_perfcounter_hi_lo = 4 +data_sel__mec_release_mem__store_gds_data_to_memory = 5 +c_uint32 = ctypes.c_uint32 # enum +class struct_pm4_mec_release_mem(Structure): + pass + +class union_pm4_mec_release_mem_0(Union): + pass + +union_pm4_mec_release_mem_0._pack_ = 1 # source:False +union_pm4_mec_release_mem_0._fields_ = [ + ('header', union_PM4_MES_TYPE_3_HEADER), + ('ordinal1', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_1(Union): + pass + +class struct_pm4_mec_release_mem_1_bitfields2(Structure): + pass + +struct_pm4_mec_release_mem_1_bitfields2._pack_ = 1 # source:False +struct_pm4_mec_release_mem_1_bitfields2._fields_ = [ + ('event_type', ctypes.c_uint32, 6), + ('reserved1', ctypes.c_uint32, 2), + ('event_index', c_uint32, 4), + ('tcl1_vol_action_ena', ctypes.c_uint32, 1), + ('tc_vol_action_ena', ctypes.c_uint32, 1), + ('reserved2', ctypes.c_uint32, 1), + ('tc_wb_action_ena', ctypes.c_uint32, 1), + ('tcl1_action_ena', ctypes.c_uint32, 1), + ('tc_action_ena', ctypes.c_uint32, 1), + ('reserved3', ctypes.c_uint32, 1), + ('tc_nc_action_ena', ctypes.c_uint32, 1), + ('tc_wc_action_ena', ctypes.c_uint32, 1), + ('tc_md_action_ena', ctypes.c_uint32, 1), + ('reserved4', ctypes.c_uint32, 3), + ('cache_policy', c_uint32, 2), + ('reserved5', ctypes.c_uint32, 2), + ('pq_exe_status', c_uint32, 1), + ('reserved6', ctypes.c_uint32, 2), +] + +union_pm4_mec_release_mem_1._pack_ = 1 # source:False +union_pm4_mec_release_mem_1._fields_ = [ + ('bitfields2', struct_pm4_mec_release_mem_1_bitfields2), + ('ordinal2', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_2(Union): + pass + +class struct_pm4_mec_release_mem_2_bitfields3(Structure): + pass + +struct_pm4_mec_release_mem_2_bitfields3._pack_ = 1 # source:False +struct_pm4_mec_release_mem_2_bitfields3._fields_ = [ + ('reserved7', ctypes.c_uint32, 16), + ('dst_sel', c_uint32, 2), + ('reserved8', ctypes.c_uint32, 6), + ('int_sel', c_uint32, 3), + ('reserved9', ctypes.c_uint32, 2), + ('data_sel', c_uint32, 3), +] + +union_pm4_mec_release_mem_2._pack_ = 1 # source:False +union_pm4_mec_release_mem_2._fields_ = [ + ('bitfields3', struct_pm4_mec_release_mem_2_bitfields3), + ('ordinal3', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_3(Union): + pass + +class struct_pm4_mec_release_mem_3_bitfields4(Structure): + pass + +struct_pm4_mec_release_mem_3_bitfields4._pack_ = 1 # source:False +struct_pm4_mec_release_mem_3_bitfields4._fields_ = [ + ('reserved10', ctypes.c_uint32, 2), + ('address_lo_32b', ctypes.c_uint32, 30), +] + +class struct_pm4_mec_release_mem_3_bitfields4b(Structure): + pass + +struct_pm4_mec_release_mem_3_bitfields4b._pack_ = 1 # source:False +struct_pm4_mec_release_mem_3_bitfields4b._fields_ = [ + ('reserved11', ctypes.c_uint32, 3), + ('address_lo_64b', ctypes.c_uint32, 29), +] + +union_pm4_mec_release_mem_3._pack_ = 1 # source:False +union_pm4_mec_release_mem_3._fields_ = [ + ('bitfields4', struct_pm4_mec_release_mem_3_bitfields4), + ('bitfields4b', struct_pm4_mec_release_mem_3_bitfields4b), + ('reserved12', ctypes.c_uint32), + ('ordinal4', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_4(Union): + pass + +union_pm4_mec_release_mem_4._pack_ = 1 # source:False +union_pm4_mec_release_mem_4._fields_ = [ + ('address_hi', ctypes.c_uint32), + ('reserved13', ctypes.c_uint32), + ('ordinal5', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_5(Union): + pass + +class struct_pm4_mec_release_mem_5_bitfields6c(Structure): + pass + +struct_pm4_mec_release_mem_5_bitfields6c._pack_ = 1 # source:False +struct_pm4_mec_release_mem_5_bitfields6c._fields_ = [ + ('dw_offset', ctypes.c_uint32, 16), + ('num_dwords', ctypes.c_uint32, 16), +] + +union_pm4_mec_release_mem_5._pack_ = 1 # source:False +union_pm4_mec_release_mem_5._fields_ = [ + ('data_lo', ctypes.c_uint32), + ('cmp_data_lo', ctypes.c_uint32), + ('bitfields6c', struct_pm4_mec_release_mem_5_bitfields6c), + ('reserved14', ctypes.c_uint32), + ('ordinal6', ctypes.c_uint32), +] + +class union_pm4_mec_release_mem_6(Union): + pass + +union_pm4_mec_release_mem_6._pack_ = 1 # source:False +union_pm4_mec_release_mem_6._fields_ = [ + ('data_hi', ctypes.c_uint32), + ('cmp_data_hi', ctypes.c_uint32), + ('reserved15', ctypes.c_uint32), + ('reserved16', ctypes.c_uint32), + ('ordinal7', ctypes.c_uint32), +] + +struct_pm4_mec_release_mem._pack_ = 1 # source:False +struct_pm4_mec_release_mem._anonymous_ = ('_0', '_1', '_2', '_3', '_4', '_5', '_6',) +struct_pm4_mec_release_mem._fields_ = [ + ('_0', union_pm4_mec_release_mem_0), + ('_1', union_pm4_mec_release_mem_1), + ('_2', union_pm4_mec_release_mem_2), + ('_3', union_pm4_mec_release_mem_3), + ('_4', union_pm4_mec_release_mem_4), + ('_5', union_pm4_mec_release_mem_5), + ('_6', union_pm4_mec_release_mem_6), + ('int_ctxid', ctypes.c_uint32), +] + + +# values for enumeration 'WRITE_DATA_dst_sel_enum' +WRITE_DATA_dst_sel_enum__enumvalues = { + 0: 'dst_sel___write_data__mem_mapped_register', + 2: 'dst_sel___write_data__tc_l2', + 3: 'dst_sel___write_data__gds', + 5: 'dst_sel___write_data__memory', + 6: 'dst_sel___write_data__memory_mapped_adc_persistent_state', +} +dst_sel___write_data__mem_mapped_register = 0 +dst_sel___write_data__tc_l2 = 2 +dst_sel___write_data__gds = 3 +dst_sel___write_data__memory = 5 +dst_sel___write_data__memory_mapped_adc_persistent_state = 6 +WRITE_DATA_dst_sel_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_addr_incr_enum' +WRITE_DATA_addr_incr_enum__enumvalues = { + 0: 'addr_incr___write_data__increment_address', + 1: 'addr_incr___write_data__do_not_increment_address', +} +addr_incr___write_data__increment_address = 0 +addr_incr___write_data__do_not_increment_address = 1 +WRITE_DATA_addr_incr_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_wr_confirm_enum' +WRITE_DATA_wr_confirm_enum__enumvalues = { + 0: 'wr_confirm___write_data__do_not_wait_for_write_confirmation', + 1: 'wr_confirm___write_data__wait_for_write_confirmation', +} +wr_confirm___write_data__do_not_wait_for_write_confirmation = 0 +wr_confirm___write_data__wait_for_write_confirmation = 1 +WRITE_DATA_wr_confirm_enum = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_DATA_cache_policy_enum' +WRITE_DATA_cache_policy_enum__enumvalues = { + 0: 'cache_policy___write_data__lru', + 1: 'cache_policy___write_data__stream', +} +cache_policy___write_data__lru = 0 +cache_policy___write_data__stream = 1 +WRITE_DATA_cache_policy_enum = ctypes.c_uint32 # enum +class struct_pm4_mec_write_data_mmio(Structure): + pass + +class union_pm4_mec_write_data_mmio_0(Union): + pass + +union_pm4_mec_write_data_mmio_0._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_0._fields_ = [ + ('header', union_PM4_MES_TYPE_3_HEADER), + ('ordinal1', ctypes.c_uint32), +] + +class union_pm4_mec_write_data_mmio_1(Union): + pass + +class struct_pm4_mec_write_data_mmio_1_bitfields2(Structure): + pass + +struct_pm4_mec_write_data_mmio_1_bitfields2._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio_1_bitfields2._fields_ = [ + ('reserved1', ctypes.c_uint32, 8), + ('dst_sel', ctypes.c_uint32, 4), + ('reserved2', ctypes.c_uint32, 4), + ('addr_incr', ctypes.c_uint32, 1), + ('reserved3', ctypes.c_uint32, 2), + ('resume_vf', ctypes.c_uint32, 1), + ('wr_confirm', ctypes.c_uint32, 1), + ('reserved4', ctypes.c_uint32, 4), + ('cache_policy', ctypes.c_uint32, 2), + ('reserved5', ctypes.c_uint32, 5), +] + +union_pm4_mec_write_data_mmio_1._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_1._fields_ = [ + ('bitfields2', struct_pm4_mec_write_data_mmio_1_bitfields2), + ('ordinal2', ctypes.c_uint32), +] + +class union_pm4_mec_write_data_mmio_2(Union): + pass + +class struct_pm4_mec_write_data_mmio_2_bitfields3(Structure): + pass + +struct_pm4_mec_write_data_mmio_2_bitfields3._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio_2_bitfields3._fields_ = [ + ('dst_mmreg_addr', ctypes.c_uint32, 18), + ('reserved6', ctypes.c_uint32, 14), +] + +union_pm4_mec_write_data_mmio_2._pack_ = 1 # source:False +union_pm4_mec_write_data_mmio_2._fields_ = [ + ('bitfields3', struct_pm4_mec_write_data_mmio_2_bitfields3), + ('ordinal3', ctypes.c_uint32), +] + +struct_pm4_mec_write_data_mmio._pack_ = 1 # source:False +struct_pm4_mec_write_data_mmio._anonymous_ = ('_0', '_1', '_2',) +struct_pm4_mec_write_data_mmio._fields_ = [ + ('_0', union_pm4_mec_write_data_mmio_0), + ('_1', union_pm4_mec_write_data_mmio_1), + ('_2', union_pm4_mec_write_data_mmio_2), + ('reserved7', ctypes.c_uint32), + ('data', ctypes.c_uint32), +] + + +# values for enumeration 'c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT' +c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT__enumvalues = { + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', +} +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT = ctypes.c_uint32 # enum +SOC15_H = True # macro +GFX9_NUM_GFX_RINGS = 1 # macro +GFX9_NUM_COMPUTE_RINGS = 8 # macro +PACKET_TYPE0 = 0 # macro +PACKET_TYPE1 = 1 # macro +PACKET_TYPE2 = 2 # macro +PACKET_TYPE3 = 3 # macro +def CP_PACKET_GET_TYPE(h): # macro + return (((h)>>30)&3) +def CP_PACKET_GET_COUNT(h): # macro + return (((h)>>16)&0x3FFF) +def CP_PACKET0_GET_REG(h): # macro + return ((h)&0xFFFF) +def CP_PACKET3_GET_OPCODE(h): # macro + return (((h)>>8)&0xFF) +def PACKET0(reg, n): # macro + return ((0<<30)|((reg)&0xFFFF)|((n)&0x3FFF)<<16) +CP_PACKET2 = 0x80000000 # macro +PACKET2_PAD_SHIFT = 0 # macro +PACKET2_PAD_MASK = (0x3fffffff<<0) # macro +# def PACKET2(v): # macro +# return (0x80000000|REG_SET(PACKET2_PAD,(v))) +def PACKET3(op, n): # macro + return ((3<<30)|(((op)&0xFF)<<8)|((n)&0x3FFF)<<16) +def PACKET3_COMPUTE(op, n): # macro + return (PACKET3(op,n)|1<<1) +PACKETJ_CONDITION_CHECK0 = 0 # macro +PACKETJ_CONDITION_CHECK1 = 1 # macro +PACKETJ_CONDITION_CHECK2 = 2 # macro +PACKETJ_CONDITION_CHECK3 = 3 # macro +PACKETJ_CONDITION_CHECK4 = 4 # macro +PACKETJ_CONDITION_CHECK5 = 5 # macro +PACKETJ_CONDITION_CHECK6 = 6 # macro +PACKETJ_CONDITION_CHECK7 = 7 # macro +PACKETJ_TYPE0 = 0 # macro +PACKETJ_TYPE1 = 1 # macro +PACKETJ_TYPE2 = 2 # macro +PACKETJ_TYPE3 = 3 # macro +PACKETJ_TYPE4 = 4 # macro +PACKETJ_TYPE5 = 5 # macro +PACKETJ_TYPE6 = 6 # macro +PACKETJ_TYPE7 = 7 # macro +def PACKETJ(reg, r, cond, type): # macro + return ((reg&0x3FFFF)|((r&0x3F)<<18)|((cond&0xF)<<24)|((type&0xF)<<28)) +CP_PACKETJ_NOP = 0x60000000 # macro +def CP_PACKETJ_GET_REG(x): # macro + return ((x)&0x3FFFF) +def CP_PACKETJ_GET_RES(x): # macro + return (((x)>>18)&0x3F) +def CP_PACKETJ_GET_COND(x): # macro + return (((x)>>24)&0xF) +def CP_PACKETJ_GET_TYPE(x): # macro + return (((x)>>28)&0xF) +PACKET3_NOP = 0x10 # macro +PACKET3_SET_BASE = 0x11 # macro +def PACKET3_BASE_INDEX(x): # macro + return ((x)<<0) +CE_PARTITION_BASE = 3 # macro +PACKET3_CLEAR_STATE = 0x12 # macro +PACKET3_INDEX_BUFFER_SIZE = 0x13 # macro +PACKET3_DISPATCH_DIRECT = 0x15 # macro +PACKET3_DISPATCH_INDIRECT = 0x16 # macro +PACKET3_ATOMIC_GDS = 0x1D # macro +PACKET3_ATOMIC_MEM = 0x1E # macro +PACKET3_OCCLUSION_QUERY = 0x1F # macro +PACKET3_SET_PREDICATION = 0x20 # macro +PACKET3_REG_RMW = 0x21 # macro +PACKET3_COND_EXEC = 0x22 # macro +PACKET3_PRED_EXEC = 0x23 # macro +PACKET3_DRAW_INDIRECT = 0x24 # macro +PACKET3_DRAW_INDEX_INDIRECT = 0x25 # macro +PACKET3_INDEX_BASE = 0x26 # macro +PACKET3_DRAW_INDEX_2 = 0x27 # macro +PACKET3_CONTEXT_CONTROL = 0x28 # macro +PACKET3_INDEX_TYPE = 0x2A # macro +PACKET3_DRAW_INDIRECT_MULTI = 0x2C # macro +PACKET3_DRAW_INDEX_AUTO = 0x2D # macro +PACKET3_NUM_INSTANCES = 0x2F # macro +PACKET3_DRAW_INDEX_MULTI_AUTO = 0x30 # macro +PACKET3_INDIRECT_BUFFER_CONST = 0x33 # macro +PACKET3_STRMOUT_BUFFER_UPDATE = 0x34 # macro +PACKET3_DRAW_INDEX_OFFSET_2 = 0x35 # macro +PACKET3_DRAW_PREAMBLE = 0x36 # macro +PACKET3_WRITE_DATA = 0x37 # macro +def WRITE_DATA_DST_SEL(x): # macro + return ((x)<<8) +WR_ONE_ADDR = (1<<16) # macro +WR_CONFIRM = (1<<20) # macro +def WRITE_DATA_CACHE_POLICY(x): # macro + return ((x)<<25) +def WRITE_DATA_ENGINE_SEL(x): # macro + return ((x)<<30) +PACKET3_DRAW_INDEX_INDIRECT_MULTI = 0x38 # macro +PACKET3_MEM_SEMAPHORE = 0x39 # macro +PACKET3_SEM_USE_MAILBOX = (0x1<<16) # macro +PACKET3_SEM_SEL_SIGNAL_TYPE = (0x1<<20) # macro +PACKET3_SEM_SEL_SIGNAL = (0x6<<29) # macro +PACKET3_SEM_SEL_WAIT = (0x7<<29) # macro +PACKET3_WAIT_REG_MEM = 0x3C # macro +def WAIT_REG_MEM_FUNCTION(x): # macro + return ((x)<<0) +def WAIT_REG_MEM_MEM_SPACE(x): # macro + return ((x)<<4) +def WAIT_REG_MEM_OPERATION(x): # macro + return ((x)<<6) +def WAIT_REG_MEM_ENGINE(x): # macro + return ((x)<<8) +PACKET3_INDIRECT_BUFFER = 0x3F # macro +INDIRECT_BUFFER_VALID = (1<<23) # macro +def INDIRECT_BUFFER_CACHE_POLICY(x): # macro + return ((x)<<28) +def INDIRECT_BUFFER_PRE_ENB(x): # macro + return ((x)<<21) +def INDIRECT_BUFFER_PRE_RESUME(x): # macro + return ((x)<<30) +PACKET3_COPY_DATA = 0x40 # macro +PACKET3_PFP_SYNC_ME = 0x42 # macro +PACKET3_COND_WRITE = 0x45 # macro +PACKET3_EVENT_WRITE = 0x46 # macro +def EVENT_TYPE(x): # macro + return ((x)<<0) +def EVENT_INDEX(x): # macro + return ((x)<<8) +PACKET3_RELEASE_MEM = 0x49 # macro +EOP_TCL1_VOL_ACTION_EN = (1<<12) # macro +EOP_TC_VOL_ACTION_EN = (1<<13) # macro +EOP_TC_WB_ACTION_EN = (1<<15) # macro +EOP_TCL1_ACTION_EN = (1<<16) # macro +EOP_TC_ACTION_EN = (1<<17) # macro +EOP_TC_NC_ACTION_EN = (1<<19) # macro +EOP_TC_MD_ACTION_EN = (1<<21) # macro +EOP_EXEC = (1<<28) # macro +def DATA_SEL(x): # macro + return ((x)<<29) +def INT_SEL(x): # macro + return ((x)<<24) +def DST_SEL(x): # macro + return ((x)<<16) +PACKET3_PREAMBLE_CNTL = 0x4A # macro +PACKET3_PREAMBLE_BEGIN_CLEAR_STATE = (2<<28) # macro +PACKET3_PREAMBLE_END_CLEAR_STATE = (3<<28) # macro +PACKET3_DMA_DATA = 0x50 # macro +def PACKET3_DMA_DATA_ENGINE(x): # macro + return ((x)<<0) +def PACKET3_DMA_DATA_SRC_CACHE_POLICY(x): # macro + return ((x)<<13) +def PACKET3_DMA_DATA_DST_SEL(x): # macro + return ((x)<<20) +def PACKET3_DMA_DATA_DST_CACHE_POLICY(x): # macro + return ((x)<<25) +def PACKET3_DMA_DATA_SRC_SEL(x): # macro + return ((x)<<29) +PACKET3_DMA_DATA_CP_SYNC = (1<<31) # macro +PACKET3_DMA_DATA_CMD_SAS = (1<<26) # macro +PACKET3_DMA_DATA_CMD_DAS = (1<<27) # macro +PACKET3_DMA_DATA_CMD_SAIC = (1<<28) # macro +PACKET3_DMA_DATA_CMD_DAIC = (1<<29) # macro +PACKET3_DMA_DATA_CMD_RAW_WAIT = (1<<30) # macro +PACKET3_ACQUIRE_MEM = 0x58 # macro +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_NC_ACTION_ENA(x): # macro + return ((x)<<3) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_WC_ACTION_ENA(x): # macro + return ((x)<<4) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_INV_METADATA_ACTION_ENA(x): # macro + return ((x)<<5) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TCL1_VOL_ACTION_ENA(x): # macro + return ((x)<<15) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_WB_ACTION_ENA(x): # macro + return ((x)<<18) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TCL1_ACTION_ENA(x): # macro + return ((x)<<22) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_ACTION_ENA(x): # macro + return ((x)<<23) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_CB_ACTION_ENA(x): # macro + return ((x)<<25) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_DB_ACTION_ENA(x): # macro + return ((x)<<26) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_KCACHE_ACTION_ENA(x): # macro + return ((x)<<27) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_KCACHE_VOL_ACTION_ENA(x): # macro + return ((x)<<28) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_ICACHE_ACTION_ENA(x): # macro + return ((x)<<29) +def PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_KCACHE_WB_ACTION_ENA(x): # macro + return ((x)<<30) +PACKET3_REWIND = 0x59 # macro +PACKET3_LOAD_UCONFIG_REG = 0x5E # macro +PACKET3_LOAD_SH_REG = 0x5F # macro +PACKET3_LOAD_CONFIG_REG = 0x60 # macro +PACKET3_LOAD_CONTEXT_REG = 0x61 # macro +PACKET3_SET_CONFIG_REG = 0x68 # macro +PACKET3_SET_CONFIG_REG_START = 0x00002000 # macro +PACKET3_SET_CONFIG_REG_END = 0x00002c00 # macro +PACKET3_SET_CONTEXT_REG = 0x69 # macro +PACKET3_SET_CONTEXT_REG_START = 0x0000a000 # macro +PACKET3_SET_CONTEXT_REG_END = 0x0000a400 # macro +PACKET3_SET_CONTEXT_REG_INDIRECT = 0x73 # macro +PACKET3_SET_SH_REG = 0x76 # macro +PACKET3_SET_SH_REG_START = 0x00002c00 # macro +PACKET3_SET_SH_REG_END = 0x00003000 # macro +PACKET3_SET_SH_REG_OFFSET = 0x77 # macro +PACKET3_SET_QUEUE_REG = 0x78 # macro +PACKET3_SET_UCONFIG_REG = 0x79 # macro +PACKET3_SET_UCONFIG_REG_START = 0x0000c000 # macro +PACKET3_SET_UCONFIG_REG_END = 0x0000c400 # macro +PACKET3_SET_UCONFIG_REG_INDEX_TYPE = (2<<28) # macro +PACKET3_SCRATCH_RAM_WRITE = 0x7D # macro +PACKET3_SCRATCH_RAM_READ = 0x7E # macro +PACKET3_LOAD_CONST_RAM = 0x80 # macro +PACKET3_WRITE_CONST_RAM = 0x81 # macro +PACKET3_DUMP_CONST_RAM = 0x83 # macro +PACKET3_INCREMENT_CE_COUNTER = 0x84 # macro +PACKET3_INCREMENT_DE_COUNTER = 0x85 # macro +PACKET3_WAIT_ON_CE_COUNTER = 0x86 # macro +PACKET3_WAIT_ON_DE_COUNTER_DIFF = 0x88 # macro +PACKET3_SWITCH_BUFFER = 0x8B # macro +PACKET3_FRAME_CONTROL = 0x90 # macro +FRAME_TMZ = (1<<0) # macro +def FRAME_CMD(x): # macro + return ((x)<<28) +PACKET3_INVALIDATE_TLBS = 0x98 # macro +def PACKET3_INVALIDATE_TLBS_DST_SEL(x): # macro + return ((x)<<0) +def PACKET3_INVALIDATE_TLBS_ALL_HUB(x): # macro + return ((x)<<4) +def PACKET3_INVALIDATE_TLBS_PASID(x): # macro + return ((x)<<5) +def PACKET3_INVALIDATE_TLBS_FLUSH_TYPE(x): # macro + return ((x)<<29) +PACKET3_SET_RESOURCES = 0xA0 # macro +def PACKET3_SET_RESOURCES_VMID_MASK(x): # macro + return ((x)<<0) +def PACKET3_SET_RESOURCES_UNMAP_LATENTY(x): # macro + return ((x)<<16) +def PACKET3_SET_RESOURCES_QUEUE_TYPE(x): # macro + return ((x)<<29) +PACKET3_MAP_QUEUES = 0xA2 # macro +def PACKET3_MAP_QUEUES_QUEUE_SEL(x): # macro + return ((x)<<4) +def PACKET3_MAP_QUEUES_VMID(x): # macro + return ((x)<<8) +def PACKET3_MAP_QUEUES_QUEUE(x): # macro + return ((x)<<13) +def PACKET3_MAP_QUEUES_PIPE(x): # macro + return ((x)<<16) +def PACKET3_MAP_QUEUES_ME(x): # macro + return ((x)<<18) +def PACKET3_MAP_QUEUES_QUEUE_TYPE(x): # macro + return ((x)<<21) +def PACKET3_MAP_QUEUES_ALLOC_FORMAT(x): # macro + return ((x)<<24) +def PACKET3_MAP_QUEUES_ENGINE_SEL(x): # macro + return ((x)<<26) +def PACKET3_MAP_QUEUES_NUM_QUEUES(x): # macro + return ((x)<<29) +def PACKET3_MAP_QUEUES_CHECK_DISABLE(x): # macro + return ((x)<<1) +def PACKET3_MAP_QUEUES_DOORBELL_OFFSET(x): # macro + return ((x)<<2) +PACKET3_UNMAP_QUEUES = 0xA3 # macro +def PACKET3_UNMAP_QUEUES_ACTION(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_QUEUE_SEL(x): # macro + return ((x)<<4) +def PACKET3_UNMAP_QUEUES_ENGINE_SEL(x): # macro + return ((x)<<26) +def PACKET3_UNMAP_QUEUES_NUM_QUEUES(x): # macro + return ((x)<<29) +def PACKET3_UNMAP_QUEUES_PASID(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET0(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET1(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_RB_WPTR(x): # macro + return ((x)<<0) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET2(x): # macro + return ((x)<<2) +def PACKET3_UNMAP_QUEUES_DOORBELL_OFFSET3(x): # macro + return ((x)<<2) +PACKET3_QUERY_STATUS = 0xA4 # macro +def PACKET3_QUERY_STATUS_CONTEXT_ID(x): # macro + return ((x)<<0) +def PACKET3_QUERY_STATUS_INTERRUPT_SEL(x): # macro + return ((x)<<28) +def PACKET3_QUERY_STATUS_COMMAND(x): # macro + return ((x)<<30) +def PACKET3_QUERY_STATUS_PASID(x): # macro + return ((x)<<0) +def PACKET3_QUERY_STATUS_DOORBELL_OFFSET(x): # macro + return ((x)<<2) +def PACKET3_QUERY_STATUS_ENG_SEL(x): # macro + return ((x)<<25) +PACKET3_RUN_CLEANER_SHADER = 0xD2 # macro +VCE_CMD_NO_OP = 0x00000000 # macro +VCE_CMD_END = 0x00000001 # macro +VCE_CMD_IB = 0x00000002 # macro +VCE_CMD_FENCE = 0x00000003 # macro +VCE_CMD_TRAP = 0x00000004 # macro +VCE_CMD_IB_AUTO = 0x00000005 # macro +VCE_CMD_SEMAPHORE = 0x00000006 # macro +VCE_CMD_IB_VM = 0x00000102 # macro +VCE_CMD_WAIT_GE = 0x00000106 # macro +VCE_CMD_UPDATE_PTB = 0x00000107 # macro +VCE_CMD_FLUSH_TLB = 0x00000108 # macro +VCE_CMD_REG_WRITE = 0x00000109 # macro +VCE_CMD_REG_WAIT = 0x0000010a # macro +HEVC_ENC_CMD_NO_OP = 0x00000000 # macro +HEVC_ENC_CMD_END = 0x00000001 # macro +HEVC_ENC_CMD_FENCE = 0x00000003 # macro +HEVC_ENC_CMD_TRAP = 0x00000004 # macro +HEVC_ENC_CMD_IB_VM = 0x00000102 # macro +HEVC_ENC_CMD_REG_WRITE = 0x00000109 # macro +HEVC_ENC_CMD_REG_WAIT = 0x0000010a # macro +__all__ = \ + ['CACHE_FLUSH_AND_INV_TS_EVENT', 'CE_PARTITION_BASE', + 'CP_PACKET2', 'CP_PACKETJ_NOP', 'EOP_EXEC', 'EOP_TCL1_ACTION_EN', + 'EOP_TCL1_VOL_ACTION_EN', 'EOP_TC_ACTION_EN', + 'EOP_TC_MD_ACTION_EN', 'EOP_TC_NC_ACTION_EN', + 'EOP_TC_VOL_ACTION_EN', 'EOP_TC_WB_ACTION_EN', + 'F32_MES_PM4_PACKETS_H', 'FRAME_TMZ', 'GFX9_NUM_COMPUTE_RINGS', + 'GFX9_NUM_GFX_RINGS', 'HEVC_ENC_CMD_END', 'HEVC_ENC_CMD_FENCE', + 'HEVC_ENC_CMD_IB_VM', 'HEVC_ENC_CMD_NO_OP', + 'HEVC_ENC_CMD_REG_WAIT', 'HEVC_ENC_CMD_REG_WRITE', + 'HEVC_ENC_CMD_TRAP', 'INDIRECT_BUFFER_VALID', 'PACKET2_PAD_MASK', + 'PACKET2_PAD_SHIFT', 'PACKET3_ACQUIRE_MEM', 'PACKET3_ATOMIC_GDS', + 'PACKET3_ATOMIC_MEM', 'PACKET3_CLEAR_STATE', 'PACKET3_COND_EXEC', + 'PACKET3_COND_WRITE', 'PACKET3_CONTEXT_CONTROL', + 'PACKET3_COPY_DATA', 'PACKET3_DISPATCH_DIRECT', + 'PACKET3_DISPATCH_INDIRECT', 'PACKET3_DMA_DATA', + 'PACKET3_DMA_DATA_CMD_DAIC', 'PACKET3_DMA_DATA_CMD_DAS', + 'PACKET3_DMA_DATA_CMD_RAW_WAIT', 'PACKET3_DMA_DATA_CMD_SAIC', + 'PACKET3_DMA_DATA_CMD_SAS', 'PACKET3_DMA_DATA_CP_SYNC', + 'PACKET3_DRAW_INDEX_2', 'PACKET3_DRAW_INDEX_AUTO', + 'PACKET3_DRAW_INDEX_INDIRECT', + 'PACKET3_DRAW_INDEX_INDIRECT_MULTI', + 'PACKET3_DRAW_INDEX_MULTI_AUTO', 'PACKET3_DRAW_INDEX_OFFSET_2', + 'PACKET3_DRAW_INDIRECT', 'PACKET3_DRAW_INDIRECT_MULTI', + 'PACKET3_DRAW_PREAMBLE', 'PACKET3_DUMP_CONST_RAM', + 'PACKET3_EVENT_WRITE', 'PACKET3_FRAME_CONTROL', + 'PACKET3_INCREMENT_CE_COUNTER', 'PACKET3_INCREMENT_DE_COUNTER', + 'PACKET3_INDEX_BASE', 'PACKET3_INDEX_BUFFER_SIZE', + 'PACKET3_INDEX_TYPE', 'PACKET3_INDIRECT_BUFFER', + 'PACKET3_INDIRECT_BUFFER_CONST', 'PACKET3_INVALIDATE_TLBS', + 'PACKET3_LOAD_CONFIG_REG', 'PACKET3_LOAD_CONST_RAM', + 'PACKET3_LOAD_CONTEXT_REG', 'PACKET3_LOAD_SH_REG', + 'PACKET3_LOAD_UCONFIG_REG', 'PACKET3_MAP_QUEUES', + 'PACKET3_MEM_SEMAPHORE', 'PACKET3_NOP', 'PACKET3_NUM_INSTANCES', + 'PACKET3_OCCLUSION_QUERY', 'PACKET3_PFP_SYNC_ME', + 'PACKET3_PREAMBLE_BEGIN_CLEAR_STATE', 'PACKET3_PREAMBLE_CNTL', + 'PACKET3_PREAMBLE_END_CLEAR_STATE', 'PACKET3_PRED_EXEC', + 'PACKET3_QUERY_STATUS', 'PACKET3_REG_RMW', 'PACKET3_RELEASE_MEM', + 'PACKET3_REWIND', 'PACKET3_RUN_CLEANER_SHADER', + 'PACKET3_SCRATCH_RAM_READ', 'PACKET3_SCRATCH_RAM_WRITE', + 'PACKET3_SEM_SEL_SIGNAL', 'PACKET3_SEM_SEL_SIGNAL_TYPE', + 'PACKET3_SEM_SEL_WAIT', 'PACKET3_SEM_USE_MAILBOX', + 'PACKET3_SET_BASE', 'PACKET3_SET_CONFIG_REG', + 'PACKET3_SET_CONFIG_REG_END', 'PACKET3_SET_CONFIG_REG_START', + 'PACKET3_SET_CONTEXT_REG', 'PACKET3_SET_CONTEXT_REG_END', + 'PACKET3_SET_CONTEXT_REG_INDIRECT', + 'PACKET3_SET_CONTEXT_REG_START', 'PACKET3_SET_PREDICATION', + 'PACKET3_SET_QUEUE_REG', 'PACKET3_SET_RESOURCES', + 'PACKET3_SET_SH_REG', 'PACKET3_SET_SH_REG_END', + 'PACKET3_SET_SH_REG_OFFSET', 'PACKET3_SET_SH_REG_START', + 'PACKET3_SET_UCONFIG_REG', 'PACKET3_SET_UCONFIG_REG_END', + 'PACKET3_SET_UCONFIG_REG_INDEX_TYPE', + 'PACKET3_SET_UCONFIG_REG_START', 'PACKET3_STRMOUT_BUFFER_UPDATE', + 'PACKET3_SWITCH_BUFFER', 'PACKET3_UNMAP_QUEUES', + 'PACKET3_WAIT_ON_CE_COUNTER', 'PACKET3_WAIT_ON_DE_COUNTER_DIFF', + 'PACKET3_WAIT_REG_MEM', 'PACKET3_WRITE_CONST_RAM', + 'PACKET3_WRITE_DATA', 'PACKETJ_CONDITION_CHECK0', + 'PACKETJ_CONDITION_CHECK1', 'PACKETJ_CONDITION_CHECK2', + 'PACKETJ_CONDITION_CHECK3', 'PACKETJ_CONDITION_CHECK4', + 'PACKETJ_CONDITION_CHECK5', 'PACKETJ_CONDITION_CHECK6', + 'PACKETJ_CONDITION_CHECK7', 'PACKETJ_TYPE0', 'PACKETJ_TYPE1', + 'PACKETJ_TYPE2', 'PACKETJ_TYPE3', 'PACKETJ_TYPE4', + 'PACKETJ_TYPE5', 'PACKETJ_TYPE6', 'PACKETJ_TYPE7', 'PACKET_TYPE0', + 'PACKET_TYPE1', 'PACKET_TYPE2', 'PACKET_TYPE3', + 'PM4_MEC_RELEASE_MEM_DEFINED', 'PM4_MEC_WRITE_DATA_DEFINED', + 'PM4_MES_HEADER_DEFINED', 'SOC15_H', 'VCE_CMD_END', + 'VCE_CMD_FENCE', 'VCE_CMD_FLUSH_TLB', 'VCE_CMD_IB', + 'VCE_CMD_IB_AUTO', 'VCE_CMD_IB_VM', 'VCE_CMD_NO_OP', + 'VCE_CMD_REG_WAIT', 'VCE_CMD_REG_WRITE', 'VCE_CMD_SEMAPHORE', + 'VCE_CMD_TRAP', 'VCE_CMD_UPDATE_PTB', 'VCE_CMD_WAIT_GE', + 'WRITE_DATA_addr_incr_enum', 'WRITE_DATA_cache_policy_enum', + 'WRITE_DATA_dst_sel_enum', 'WRITE_DATA_wr_confirm_enum', + 'WR_CONFIRM', 'WR_ONE_ADDR', + 'addr_incr___write_data__do_not_increment_address', + 'addr_incr___write_data__increment_address', + 'c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT', 'c_uint32', 'c_uint32', + 'c_uint32', 'c_uint32', 'c_uint32', 'c_uint32', + 'cache_policy___write_data__lru', + 'cache_policy___write_data__stream', + 'cache_policy__mec_release_mem__lru', + 'cache_policy__mec_release_mem__stream', + 'data_sel__mec_release_mem__none', + 'data_sel__mec_release_mem__send_32_bit_low', + 'data_sel__mec_release_mem__send_64_bit_data', + 'data_sel__mec_release_mem__send_cp_perfcounter_hi_lo', + 'data_sel__mec_release_mem__send_gpu_clock_counter', + 'data_sel__mec_release_mem__store_gds_data_to_memory', + 'dst_sel___write_data__gds', + 'dst_sel___write_data__mem_mapped_register', + 'dst_sel___write_data__memory', + 'dst_sel___write_data__memory_mapped_adc_persistent_state', + 'dst_sel___write_data__tc_l2', + 'dst_sel__mec_release_mem__memory_controller', + 'dst_sel__mec_release_mem__queue_write_pointer_poll_mask_bit', + 'dst_sel__mec_release_mem__queue_write_pointer_register', + 'dst_sel__mec_release_mem__tc_l2', + 'event_index__mec_release_mem__end_of_pipe', + 'event_index__mec_release_mem__shader_done', 'int32_t', + 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_32_bit_compare', + 'int_sel__mec_release_mem__conditionally_send_int_ctxid_based_on_64_bit_compare', + 'int_sel__mec_release_mem__none', + 'int_sel__mec_release_mem__send_data_after_write_confirm', + 'int_sel__mec_release_mem__send_interrupt_after_write_confirm', + 'int_sel__mec_release_mem__send_interrupt_only', + 'int_sel__mec_release_mem__unconditionally_send_int_ctxid', + 'pq_exe_status__mec_release_mem__default', + 'pq_exe_status__mec_release_mem__phase_update', + 'struct_PM4_MES_TYPE_3_HEADER_0', 'struct_pm4_mec_release_mem', + 'struct_pm4_mec_release_mem_1_bitfields2', + 'struct_pm4_mec_release_mem_2_bitfields3', + 'struct_pm4_mec_release_mem_3_bitfields4', + 'struct_pm4_mec_release_mem_3_bitfields4b', + 'struct_pm4_mec_release_mem_5_bitfields6c', + 'struct_pm4_mec_write_data_mmio', + 'struct_pm4_mec_write_data_mmio_1_bitfields2', + 'struct_pm4_mec_write_data_mmio_2_bitfields3', 'uint32_t', + 'union_PM4_MES_TYPE_3_HEADER', 'union_pm4_mec_release_mem_0', + 'union_pm4_mec_release_mem_1', 'union_pm4_mec_release_mem_2', + 'union_pm4_mec_release_mem_3', 'union_pm4_mec_release_mem_4', + 'union_pm4_mec_release_mem_5', 'union_pm4_mec_release_mem_6', + 'union_pm4_mec_write_data_mmio_0', + 'union_pm4_mec_write_data_mmio_1', + 'union_pm4_mec_write_data_mmio_2', + 'wr_confirm___write_data__do_not_wait_for_write_confirmation', + 'wr_confirm___write_data__wait_for_write_confirmation'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_0_0.py b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_0_0.py new file mode 100644 index 0000000000..a48adeed78 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_0_0.py @@ -0,0 +1,5209 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/opt/rocm/include', '-x', 'c++'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_ = True # macro +SDMA_OP_COPY = 1 # macro +SDMA_OP_FENCE = 5 # macro +SDMA_OP_TRAP = 6 # macro +SDMA_OP_POLL_REGMEM = 8 # macro +SDMA_OP_ATOMIC = 10 # macro +SDMA_OP_CONST_FILL = 11 # macro +SDMA_OP_TIMESTAMP = 13 # macro +SDMA_OP_GCR = 17 # Variable ctypes.c_uint32 +SDMA_SUBOP_COPY_LINEAR = 0 # macro +SDMA_SUBOP_COPY_LINEAR_RECT = 4 # Variable ctypes.c_uint32 +SDMA_SUBOP_TIMESTAMP_GET_GLOBAL = 2 # macro +SDMA_SUBOP_USER_GCR = 1 # Variable ctypes.c_uint32 +SDMA_ATOMIC_ADD64 = 47 # Variable ctypes.c_uint32 +class struct_SDMA_PKT_COPY_LINEAR_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('extra_info', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._fields_ = [ + ('reserved_0', ctypes.c_uint32, 16), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_1', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION), + ('COUNT_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION), + ('PARAMETER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION), +] + +SDMA_PKT_COPY_LINEAR = struct_SDMA_PKT_COPY_LINEAR_TAG +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved', ctypes.c_uint32, 13), + ('element', ctypes.c_uint32, 3), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._fields_ = [ + ('src_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('src_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._fields_ = [ + ('src_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('src_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._fields_ = [ + ('src_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._fields_ = [ + ('dst_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0), + ('DW_8_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._fields_ = [ + ('dst_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0), + ('DW_9_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._fields_ = [ + ('dst_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0), + ('DW_10_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._fields_ = [ + ('rect_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('rect_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0), + ('DW_11_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._fields_ = [ + ('rect_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 5), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_3', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0), + ('DW_12_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION), + ('SRC_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION), + ('SRC_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION), + ('SRC_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION), + ('DST_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION), + ('DST_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION), + ('DST_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION), + ('RECT_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION), + ('RECT_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION), +] + +SDMA_PKT_COPY_LINEAR_RECT = struct_SDMA_PKT_COPY_LINEAR_RECT_TAG +class struct_SDMA_PKT_CONSTANT_FILL_TAG(Structure): + pass + +class union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('sw', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 12), + ('fillsize', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_CONSTANT_FILL_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION), + ('COUNT_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION), +] + +SDMA_PKT_CONSTANT_FILL = struct_SDMA_PKT_CONSTANT_FILL_TAG +class struct_SDMA_PKT_FENCE_TAG(Structure): + pass + +class union_SDMA_PKT_FENCE_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('mtype', ctypes.c_uint32, 3), + ('gcc', ctypes.c_uint32, 1), + ('sys', ctypes.c_uint32, 1), + ('pad1', ctypes.c_uint32, 1), + ('snp', ctypes.c_uint32, 1), + ('gpa', ctypes.c_uint32, 1), + ('l2_policy', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_3_0._fields_ = [ + ('data', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_FENCE_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_FENCE_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_FENCE_TAG_DATA_UNION), +] + +SDMA_PKT_FENCE = struct_SDMA_PKT_FENCE_TAG +class struct_SDMA_PKT_POLL_REGMEM_TAG(Structure): + pass + +class union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 10), + ('hdp_flush', ctypes.c_uint32, 1), + ('reserved_1', ctypes.c_uint32, 1), + ('func', ctypes.c_uint32, 3), + ('mem_poll', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._fields_ = [ + ('value', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._fields_ = [ + ('mask', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._fields_ = [ + ('interval', ctypes.c_uint32, 16), + ('retry_count', ctypes.c_uint32, 12), + ('reserved_0', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_POLL_REGMEM_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION), + ('VALUE_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION), + ('MASK_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION), + ('DW5_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION), +] + +SDMA_PKT_POLL_REGMEM = struct_SDMA_PKT_POLL_REGMEM_TAG +class struct_SDMA_PKT_ATOMIC_TAG(Structure): + pass + +class union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('l', ctypes.c_uint32, 1), + ('reserved_0', ctypes.c_uint32, 8), + ('operation', ctypes.c_uint32, 7), +] + +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_4_0._fields_ = [ + ('src_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_5_0._fields_ = [ + ('cmp_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_6_0._fields_ = [ + ('cmp_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_7_0._fields_ = [ + ('loop_interval', ctypes.c_uint32, 13), + ('reserved_0', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_ATOMIC_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION), + ('SRC_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION), + ('SRC_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION), + ('CMP_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION), + ('CMP_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION), + ('LOOP_UNION', union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION), +] + +SDMA_PKT_ATOMIC = struct_SDMA_PKT_ATOMIC_TAG +class struct_SDMA_PKT_TIMESTAMP_TAG(Structure): + pass + +class union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TIMESTAMP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION), +] + +SDMA_PKT_TIMESTAMP = struct_SDMA_PKT_TIMESTAMP_TAG +class struct_SDMA_PKT_TRAP_TAG(Structure): + pass + +class union_SDMA_PKT_TRAP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_1_0._fields_ = [ + ('int_ctx', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TRAP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TRAP_TAG_HEADER_UNION), + ('INT_CONTEXT_UNION', union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION), +] + +SDMA_PKT_TRAP = struct_SDMA_PKT_TRAP_TAG +class struct_SDMA_PKT_HDP_FLUSH_TAG(Structure): + pass + +struct_SDMA_PKT_HDP_FLUSH_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_HDP_FLUSH_TAG._fields_ = [ + ('DW_0_DATA', ctypes.c_uint32), + ('DW_1_DATA', ctypes.c_uint32), + ('DW_2_DATA', ctypes.c_uint32), + ('DW_3_DATA', ctypes.c_uint32), + ('DW_4_DATA', ctypes.c_uint32), + ('DW_5_DATA', ctypes.c_uint32), +] + +SDMA_PKT_HDP_FLUSH = struct_SDMA_PKT_HDP_FLUSH_TAG +hdp_flush_cmd = struct_SDMA_PKT_HDP_FLUSH_TAG # Variable struct_SDMA_PKT_HDP_FLUSH_TAG +class struct_SDMA_PKT_GCR_TAG(Structure): + pass + +class union_SDMA_PKT_GCR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('_2', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_GCR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD1_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_1_0._fields_ = [ + ('_0', ctypes.c_uint32, 7), + ('BaseVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD2_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_2_0._fields_ = [ + ('BaseVA_HI', ctypes.c_uint32, 16), + ('GCR_CONTROL_GLI_INV', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL1_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GLM_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLM_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLV_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL1_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_US', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL2_DISCARD', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_WB', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_GCR_TAG_WORD2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD3_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_3_0._fields_ = [ + ('GCR_CONTROL_RANGE_IS_PA', ctypes.c_uint32, 1), + ('GCR_CONTROL_SEQ', ctypes.c_uint32, 2), + ('_2', ctypes.c_uint32, 4), + ('LimitVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD4_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_4_0._fields_ = [ + ('LimitVA_HI', ctypes.c_uint32, 16), + ('_1', ctypes.c_uint32, 8), + ('VMID', ctypes.c_uint32, 4), + ('_3', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_GCR_TAG_WORD4_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD4_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD4_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_GCR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_GCR_TAG_HEADER_UNION), + ('WORD1_UNION', union_SDMA_PKT_GCR_TAG_WORD1_UNION), + ('WORD2_UNION', union_SDMA_PKT_GCR_TAG_WORD2_UNION), + ('WORD3_UNION', union_SDMA_PKT_GCR_TAG_WORD3_UNION), + ('WORD4_UNION', union_SDMA_PKT_GCR_TAG_WORD4_UNION), +] + +SDMA_PKT_GCR = struct_SDMA_PKT_GCR_TAG +__VEGA10_SDMA_PKT_OPEN_H_ = True # macro +SDMA_OP_NOP = 0 # macro +SDMA_OP_WRITE = 2 # macro +SDMA_OP_INDIRECT = 4 # macro +SDMA_OP_SEM = 7 # macro +SDMA_OP_COND_EXE = 9 # macro +SDMA_OP_PTEPDE = 12 # macro +SDMA_OP_SRBM_WRITE = 14 # macro +SDMA_OP_PRE_EXE = 15 # macro +SDMA_OP_DUMMY_TRAP = 16 # macro +SDMA_SUBOP_TIMESTAMP_SET = 0 # macro +SDMA_SUBOP_TIMESTAMP_GET = 1 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND = 4 # macro +SDMA_SUBOP_COPY_TILED = 1 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND = 5 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND = 6 # macro +SDMA_SUBOP_COPY_SOA = 3 # macro +SDMA_SUBOP_COPY_DIRTY_PAGE = 7 # macro +SDMA_SUBOP_COPY_LINEAR_PHY = 8 # macro +SDMA_SUBOP_WRITE_LINEAR = 0 # macro +SDMA_SUBOP_WRITE_TILED = 1 # macro +SDMA_SUBOP_PTEPDE_GEN = 0 # macro +SDMA_SUBOP_PTEPDE_COPY = 1 # macro +SDMA_SUBOP_PTEPDE_RMW = 2 # macro +SDMA_SUBOP_PTEPDE_COPY_BACKWARDS = 3 # macro +SDMA_SUBOP_DATA_FILL_MULTI = 1 # macro +SDMA_SUBOP_POLL_REG_WRITE_MEM = 1 # macro +SDMA_SUBOP_POLL_DBIT_WRITE_MEM = 2 # macro +SDMA_SUBOP_POLL_MEM_VERIFY = 3 # macro +HEADER_AGENT_DISPATCH = 4 # macro +HEADER_BARRIER = 5 # macro +SDMA_OP_AQL_COPY = 0 # macro +SDMA_OP_AQL_BARRIER_OR = 0 # macro +SDMA_PKT_HEADER_op_offset = 0 # macro +SDMA_PKT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_op_shift = 0 # macro +def SDMA_PKT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_ALL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift = 21 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_LOG(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift = 27 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GCC(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST1_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_DST1_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_DST1_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_DST2_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_DST2_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_TILED_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_DW_5_epitch_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_TILED_DW_5_epitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_5_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_COUNT_count_offset = 12 # macro +SDMA_PKT_COPY_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift = 26 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_VIDEOCOPY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset = 1 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_TILED_ADDR0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset = 2 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_TILED_ADDR0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset = 3 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_TILED_ADDR1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset = 4 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_TILED_ADDR1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset = 5 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_5_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift = 9 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset = 9 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_9_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset = 11 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset = 12 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset = 13 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 14 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset = 15 # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_COPY_T2T_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_T2T_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_T2T_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_T2T_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_6_src_epitch_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_T2T_DW_6_src_epitch_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_T2T_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_14_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_MIP_ID(x): # macro + return (((x)&0x0000000F)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_TILED_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_STRUCT_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_SB_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_SB_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset = 3 # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_START_INDEX_START_INDEX(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_COUNT_count_offset = 4 # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_COUNT_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_stride_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_mask = 0x000007FF # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRIDE(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift = 24 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRUCT_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_count_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift = 24 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset = 4 # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_TILED_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_WRITE_TILED_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_WRITE_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_WRITE_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_WRITE_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_WRITE_TILED_DW_5_epitch_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_WRITE_TILED_DW_5_epitch_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_5_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_WRITE_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_WRITE_TILED_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_TILED_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_COUNT_count_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift = 28 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTE_SIZE(x): # macro + return (((x)&0x00000003)<<28) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift = 30 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_DIRECTION(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_FIRST_XFER(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_LAST_XFER(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask = 0x0001FFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_COUNT(x): # macro + return (((x)&0x0001FFFF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift = 20 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift = 22 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_LO_MASK_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_HI_MASK_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset = 5 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_LO_VALUE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset = 6 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_HI_VALUE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_INCR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset = 3 # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset = 4 # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset = 5 # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW0_INIT_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset = 6 # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW1_INIT_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset = 7 # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW0_INCR_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset = 8 # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW1_INCR_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_COUNT_count_offset = 9 # macro +SDMA_PKT_WRITE_INCR_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_WRITE_INCR_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_INDIRECT_HEADER_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_op_shift = 0 # macro +def SDMA_PKT_INDIRECT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_INDIRECT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_INDIRECT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_INDIRECT_HEADER_vmid_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_vmid_mask = 0x0000000F # macro +SDMA_PKT_INDIRECT_HEADER_vmid_shift = 16 # macro +def SDMA_PKT_INDIRECT_HEADER_VMID(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset = 1 # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_LO_IB_BASE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset = 2 # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_HI_IB_BASE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset = 3 # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask = 0x000FFFFF # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift = 0 # macro +def SDMA_PKT_INDIRECT_IB_SIZE_IB_SIZE(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset = 4 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_LO_CSA_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset = 5 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_HI_CSA_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SEMAPHORE_HEADER_write_one_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_shift = 29 # macro +def SDMA_PKT_SEMAPHORE_HEADER_WRITE_ONE(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_SEMAPHORE_HEADER_signal_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_shift = 30 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SIGNAL(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift = 31 # macro +def SDMA_PKT_SEMAPHORE_HEADER_MAILBOX(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_HEADER_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_op_shift = 0 # macro +def SDMA_PKT_FENCE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_FENCE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_FENCE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_DATA_data_offset = 3 # macro +SDMA_PKT_FENCE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_DATA_data_shift = 0 # macro +def SDMA_PKT_FENCE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask = 0x0000000F # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift = 28 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_BYTE_EN(x): # macro + return (((x)&0x0000000F)<<28) +SDMA_PKT_SRBM_WRITE_ADDR_addr_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_mask = 0x0003FFFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_ADDR(x): # macro + return (((x)&0x0003FFFF)<<0) +SDMA_PKT_SRBM_WRITE_DATA_data_offset = 2 # macro +SDMA_PKT_SRBM_WRITE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_SRBM_WRITE_DATA_data_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PRE_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_PRE_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PRE_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PRE_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift = 16 # macro +def SDMA_PKT_PRE_EXE_HEADER_DEV_SEL(x): # macro + return (((x)&0x000000FF)<<16) +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset = 1 # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_PRE_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COND_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COND_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COND_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COND_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_REFERENCE_reference_offset = 3 # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_shift = 0 # macro +def SDMA_PKT_COND_EXE_REFERENCE_REFERENCE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset = 4 # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_COND_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift = 16 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift = 30 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_FILLSIZE(x): # macro + return (((x)&0x00000003)<<30) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset = 3 # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DATA_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_COUNT_count_offset = 4 # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask = 0x00000001 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift = 31 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_MEMLOG_CLR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset = 1 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_BYTE_STRIDE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset = 2 # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_DMA_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset = 5 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask = 0x03FFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_COUNT(x): # macro + return (((x)&0x03FFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift = 26 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_HDP_FLUSH(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_POLL_REGMEM_HEADER_func_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_mask = 0x00000007 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_shift = 28 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_FUNC(x): # macro + return (((x)&0x00000007)<<28) +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift = 31 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_VALUE_value_offset = 3 # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_VALUE_VALUE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_MASK_mask_offset = 4 # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_MASK_MASK(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_interval_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_mask = 0x0000FFFF # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask = 0x00000FFF # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift = 16 # macro +def SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset = 1 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask = 0x3FFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift = 2 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_ADDR_31_2(x): # macro + return (((x)&0x3FFFFFFF)<<2) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 2 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 3 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask = 0x00000003 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift = 16 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_EA(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset = 3 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask = 0x0FFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift = 4 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_ADDR_31_4(x): # macro + return (((x)&0x0FFFFFFF)<<4) +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset = 4 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_PAGE_NUM_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask = 0x00000001 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift = 31 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_MODE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset = 1 # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_PATTERN_PATTERN(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset = 2 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_CMP0_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset = 3 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_CMP0_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset = 4 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset = 5 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset = 6 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_CMP1_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset = 7 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_CMP1_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset = 8 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset = 9 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset = 10 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_REC_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset = 11 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_REC_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset = 12 # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_RESERVED_RESERVED(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_HEADER_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_ATOMIC_HEADER_op_shift = 0 # macro +def SDMA_PKT_ATOMIC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_ATOMIC_HEADER_loop_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_loop_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_loop_shift = 16 # macro +def SDMA_PKT_ATOMIC_HEADER_LOOP(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_ATOMIC_HEADER_tmz_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_ATOMIC_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_ATOMIC_HEADER_atomic_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_mask = 0x0000007F # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_shift = 25 # macro +def SDMA_PKT_ATOMIC_HEADER_ATOMIC_OP(x): # macro + return (((x)&0x0000007F)<<25) +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset = 3 # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_LO_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset = 4 # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_HI_SRC_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset = 5 # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_LO_CMP_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset = 6 # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_HI_CMP_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset = 7 # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask = 0x00001FFF # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift = 0 # macro +def SDMA_PKT_ATOMIC_LOOP_INTERVAL_LOOP_INTERVAL(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset = 1 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_INIT_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_INIT_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_NOP_HEADER_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_op_shift = 0 # macro +def SDMA_PKT_NOP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_NOP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_NOP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_NOP_HEADER_count_offset = 0 # macro +SDMA_PKT_NOP_HEADER_count_mask = 0x00003FFF # macro +SDMA_PKT_NOP_HEADER_count_shift = 16 # macro +def SDMA_PKT_NOP_HEADER_COUNT(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_NOP_DATA0_data0_offset = 1 # macro +SDMA_PKT_NOP_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_NOP_DATA0_data0_shift = 0 # macro +def SDMA_PKT_NOP_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_HEADER_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_HEADER_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_HEADER_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_HEADER_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_HEADER_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_HEADER_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_HEADER_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_HEADER_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_HEADER_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_HEADER_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset = 2 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_RETURN_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset = 3 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_RETURN_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset = 4 # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 6 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 7 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 8 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 9 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset = 10 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_RESERVED_DW10(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset = 11 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_RESERVED_DW11(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset = 2 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_DEPENDENT_ADDR_0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset = 3 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_DEPENDENT_ADDR_0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset = 4 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_DEPENDENT_ADDR_1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset = 5 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_DEPENDENT_ADDR_1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset = 6 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_DEPENDENT_ADDR_2_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset = 7 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_DEPENDENT_ADDR_2_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset = 8 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_DEPENDENT_ADDR_3_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset = 9 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_DEPENDENT_ADDR_3_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset = 10 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_DEPENDENT_ADDR_4_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset = 11 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_DEPENDENT_ADDR_4_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +__all__ = \ + ['HEADER_AGENT_DISPATCH', 'HEADER_BARRIER', + 'HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_format_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_format_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_format_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_op_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_op_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_op_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_shift', 'SDMA_ATOMIC_ADD64', + 'SDMA_OP_AQL_BARRIER_OR', 'SDMA_OP_AQL_COPY', 'SDMA_OP_ATOMIC', + 'SDMA_OP_COND_EXE', 'SDMA_OP_CONST_FILL', 'SDMA_OP_COPY', + 'SDMA_OP_DUMMY_TRAP', 'SDMA_OP_FENCE', 'SDMA_OP_GCR', + 'SDMA_OP_INDIRECT', 'SDMA_OP_NOP', 'SDMA_OP_POLL_REGMEM', + 'SDMA_OP_PRE_EXE', 'SDMA_OP_PTEPDE', 'SDMA_OP_SEM', + 'SDMA_OP_SRBM_WRITE', 'SDMA_OP_TIMESTAMP', 'SDMA_OP_TRAP', + 'SDMA_OP_WRITE', 'SDMA_PKT_ATOMIC', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_loop_mask', + 'SDMA_PKT_ATOMIC_HEADER_loop_offset', + 'SDMA_PKT_ATOMIC_HEADER_loop_shift', + 'SDMA_PKT_ATOMIC_HEADER_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_tmz_mask', + 'SDMA_PKT_ATOMIC_HEADER_tmz_offset', + 'SDMA_PKT_ATOMIC_HEADER_tmz_shift', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_COND_EXE_HEADER_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_op_shift', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_mask', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_offset', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_shift', + 'SDMA_PKT_CONSTANT_FILL', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_mask', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_offset', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_shift', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift', + 'SDMA_PKT_COPY_LINEAR', 'SDMA_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_RECT', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_mask', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_offset', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_T2T_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_mask', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_offset', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_mask', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_offset', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_shift', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_mask', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_offset', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_shift', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_TILED_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_FENCE', 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_FENCE_DATA_data_mask', + 'SDMA_PKT_FENCE_DATA_data_offset', + 'SDMA_PKT_FENCE_DATA_data_shift', 'SDMA_PKT_FENCE_HEADER_op_mask', + 'SDMA_PKT_FENCE_HEADER_op_offset', + 'SDMA_PKT_FENCE_HEADER_op_shift', + 'SDMA_PKT_FENCE_HEADER_sub_op_mask', + 'SDMA_PKT_FENCE_HEADER_sub_op_offset', + 'SDMA_PKT_FENCE_HEADER_sub_op_shift', 'SDMA_PKT_GCR', + 'SDMA_PKT_HDP_FLUSH', 'SDMA_PKT_HEADER_op_mask', + 'SDMA_PKT_HEADER_op_offset', 'SDMA_PKT_HEADER_op_shift', + 'SDMA_PKT_HEADER_sub_op_mask', 'SDMA_PKT_HEADER_sub_op_offset', + 'SDMA_PKT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift', + 'SDMA_PKT_INDIRECT_HEADER_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_vmid_mask', + 'SDMA_PKT_INDIRECT_HEADER_vmid_offset', + 'SDMA_PKT_INDIRECT_HEADER_vmid_shift', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift', + 'SDMA_PKT_NOP_DATA0_data0_mask', + 'SDMA_PKT_NOP_DATA0_data0_offset', + 'SDMA_PKT_NOP_DATA0_data0_shift', + 'SDMA_PKT_NOP_HEADER_count_mask', + 'SDMA_PKT_NOP_HEADER_count_offset', + 'SDMA_PKT_NOP_HEADER_count_shift', 'SDMA_PKT_NOP_HEADER_op_mask', + 'SDMA_PKT_NOP_HEADER_op_offset', 'SDMA_PKT_NOP_HEADER_op_shift', + 'SDMA_PKT_NOP_HEADER_sub_op_mask', + 'SDMA_PKT_NOP_HEADER_sub_op_offset', + 'SDMA_PKT_NOP_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift', + 'SDMA_PKT_POLL_REGMEM', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_mask', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_offset', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_shift', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_mask', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_offset', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift', + 'SDMA_PKT_PRE_EXE_HEADER_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_op_shift', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_shift', + 'SDMA_PKT_SRBM_WRITE_DATA_data_mask', + 'SDMA_PKT_SRBM_WRITE_DATA_data_offset', + 'SDMA_PKT_SRBM_WRITE_DATA_data_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift', 'SDMA_PKT_TIMESTAMP', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift', + 'SDMA_PKT_TRAP', 'SDMA_PKT_TRAP_HEADER_op_mask', + 'SDMA_PKT_TRAP_HEADER_op_offset', 'SDMA_PKT_TRAP_HEADER_op_shift', + 'SDMA_PKT_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_WRITE_INCR_COUNT_count_mask', + 'SDMA_PKT_WRITE_INCR_COUNT_count_offset', + 'SDMA_PKT_WRITE_INCR_COUNT_count_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_op_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_WRITE_TILED_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_shift', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift', + 'SDMA_SUBOP_COPY_DIRTY_PAGE', 'SDMA_SUBOP_COPY_LINEAR', + 'SDMA_SUBOP_COPY_LINEAR_PHY', 'SDMA_SUBOP_COPY_LINEAR_RECT', + 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND', 'SDMA_SUBOP_COPY_SOA', + 'SDMA_SUBOP_COPY_T2T_SUB_WIND', 'SDMA_SUBOP_COPY_TILED', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND', 'SDMA_SUBOP_DATA_FILL_MULTI', + 'SDMA_SUBOP_POLL_DBIT_WRITE_MEM', 'SDMA_SUBOP_POLL_MEM_VERIFY', + 'SDMA_SUBOP_POLL_REG_WRITE_MEM', 'SDMA_SUBOP_PTEPDE_COPY', + 'SDMA_SUBOP_PTEPDE_COPY_BACKWARDS', 'SDMA_SUBOP_PTEPDE_GEN', + 'SDMA_SUBOP_PTEPDE_RMW', 'SDMA_SUBOP_TIMESTAMP_GET', + 'SDMA_SUBOP_TIMESTAMP_GET_GLOBAL', 'SDMA_SUBOP_TIMESTAMP_SET', + 'SDMA_SUBOP_USER_GCR', 'SDMA_SUBOP_WRITE_LINEAR', + 'SDMA_SUBOP_WRITE_TILED', '__VEGA10_SDMA_PKT_OPEN_H_', + 'hdp_flush_cmd', 'struct_SDMA_PKT_ATOMIC_TAG', + 'struct_SDMA_PKT_ATOMIC_TAG_0_0', + 'struct_SDMA_PKT_ATOMIC_TAG_1_0', + 'struct_SDMA_PKT_ATOMIC_TAG_2_0', + 'struct_SDMA_PKT_ATOMIC_TAG_3_0', + 'struct_SDMA_PKT_ATOMIC_TAG_4_0', + 'struct_SDMA_PKT_ATOMIC_TAG_5_0', + 'struct_SDMA_PKT_ATOMIC_TAG_6_0', + 'struct_SDMA_PKT_ATOMIC_TAG_7_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_6_0', + 'struct_SDMA_PKT_FENCE_TAG', 'struct_SDMA_PKT_FENCE_TAG_0_0', + 'struct_SDMA_PKT_FENCE_TAG_1_0', 'struct_SDMA_PKT_FENCE_TAG_2_0', + 'struct_SDMA_PKT_FENCE_TAG_3_0', 'struct_SDMA_PKT_GCR_TAG', + 'struct_SDMA_PKT_GCR_TAG_0_0', 'struct_SDMA_PKT_GCR_TAG_1_0', + 'struct_SDMA_PKT_GCR_TAG_2_0', 'struct_SDMA_PKT_GCR_TAG_3_0', + 'struct_SDMA_PKT_GCR_TAG_4_0', 'struct_SDMA_PKT_HDP_FLUSH_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_0_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_1_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_2_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_3_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_4_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_5_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG', + 'struct_SDMA_PKT_TIMESTAMP_TAG_0_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_1_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_2_0', 'struct_SDMA_PKT_TRAP_TAG', + 'struct_SDMA_PKT_TRAP_TAG_0_0', 'struct_SDMA_PKT_TRAP_TAG_1_0', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_DATA_UNION', + 'union_SDMA_PKT_FENCE_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD1_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD2_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD3_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD4_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_4_2.py b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_4_2.py new file mode 100644 index 0000000000..a48adeed78 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_4_4_2.py @@ -0,0 +1,5209 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/opt/rocm/include', '-x', 'c++'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_ = True # macro +SDMA_OP_COPY = 1 # macro +SDMA_OP_FENCE = 5 # macro +SDMA_OP_TRAP = 6 # macro +SDMA_OP_POLL_REGMEM = 8 # macro +SDMA_OP_ATOMIC = 10 # macro +SDMA_OP_CONST_FILL = 11 # macro +SDMA_OP_TIMESTAMP = 13 # macro +SDMA_OP_GCR = 17 # Variable ctypes.c_uint32 +SDMA_SUBOP_COPY_LINEAR = 0 # macro +SDMA_SUBOP_COPY_LINEAR_RECT = 4 # Variable ctypes.c_uint32 +SDMA_SUBOP_TIMESTAMP_GET_GLOBAL = 2 # macro +SDMA_SUBOP_USER_GCR = 1 # Variable ctypes.c_uint32 +SDMA_ATOMIC_ADD64 = 47 # Variable ctypes.c_uint32 +class struct_SDMA_PKT_COPY_LINEAR_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('extra_info', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._fields_ = [ + ('reserved_0', ctypes.c_uint32, 16), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_1', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION), + ('COUNT_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION), + ('PARAMETER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION), +] + +SDMA_PKT_COPY_LINEAR = struct_SDMA_PKT_COPY_LINEAR_TAG +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved', ctypes.c_uint32, 13), + ('element', ctypes.c_uint32, 3), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._fields_ = [ + ('src_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('src_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._fields_ = [ + ('src_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('src_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._fields_ = [ + ('src_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._fields_ = [ + ('dst_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0), + ('DW_8_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._fields_ = [ + ('dst_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0), + ('DW_9_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._fields_ = [ + ('dst_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0), + ('DW_10_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._fields_ = [ + ('rect_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('rect_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0), + ('DW_11_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._fields_ = [ + ('rect_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 5), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_3', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0), + ('DW_12_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION), + ('SRC_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION), + ('SRC_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION), + ('SRC_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION), + ('DST_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION), + ('DST_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION), + ('DST_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION), + ('RECT_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION), + ('RECT_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION), +] + +SDMA_PKT_COPY_LINEAR_RECT = struct_SDMA_PKT_COPY_LINEAR_RECT_TAG +class struct_SDMA_PKT_CONSTANT_FILL_TAG(Structure): + pass + +class union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('sw', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 12), + ('fillsize', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_CONSTANT_FILL_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION), + ('COUNT_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION), +] + +SDMA_PKT_CONSTANT_FILL = struct_SDMA_PKT_CONSTANT_FILL_TAG +class struct_SDMA_PKT_FENCE_TAG(Structure): + pass + +class union_SDMA_PKT_FENCE_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('mtype', ctypes.c_uint32, 3), + ('gcc', ctypes.c_uint32, 1), + ('sys', ctypes.c_uint32, 1), + ('pad1', ctypes.c_uint32, 1), + ('snp', ctypes.c_uint32, 1), + ('gpa', ctypes.c_uint32, 1), + ('l2_policy', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_3_0._fields_ = [ + ('data', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_FENCE_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_FENCE_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_FENCE_TAG_DATA_UNION), +] + +SDMA_PKT_FENCE = struct_SDMA_PKT_FENCE_TAG +class struct_SDMA_PKT_POLL_REGMEM_TAG(Structure): + pass + +class union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 10), + ('hdp_flush', ctypes.c_uint32, 1), + ('reserved_1', ctypes.c_uint32, 1), + ('func', ctypes.c_uint32, 3), + ('mem_poll', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._fields_ = [ + ('value', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._fields_ = [ + ('mask', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._fields_ = [ + ('interval', ctypes.c_uint32, 16), + ('retry_count', ctypes.c_uint32, 12), + ('reserved_0', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_POLL_REGMEM_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION), + ('VALUE_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION), + ('MASK_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION), + ('DW5_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION), +] + +SDMA_PKT_POLL_REGMEM = struct_SDMA_PKT_POLL_REGMEM_TAG +class struct_SDMA_PKT_ATOMIC_TAG(Structure): + pass + +class union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('l', ctypes.c_uint32, 1), + ('reserved_0', ctypes.c_uint32, 8), + ('operation', ctypes.c_uint32, 7), +] + +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_4_0._fields_ = [ + ('src_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_5_0._fields_ = [ + ('cmp_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_6_0._fields_ = [ + ('cmp_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_7_0._fields_ = [ + ('loop_interval', ctypes.c_uint32, 13), + ('reserved_0', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_ATOMIC_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION), + ('SRC_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION), + ('SRC_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION), + ('CMP_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION), + ('CMP_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION), + ('LOOP_UNION', union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION), +] + +SDMA_PKT_ATOMIC = struct_SDMA_PKT_ATOMIC_TAG +class struct_SDMA_PKT_TIMESTAMP_TAG(Structure): + pass + +class union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TIMESTAMP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION), +] + +SDMA_PKT_TIMESTAMP = struct_SDMA_PKT_TIMESTAMP_TAG +class struct_SDMA_PKT_TRAP_TAG(Structure): + pass + +class union_SDMA_PKT_TRAP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_1_0._fields_ = [ + ('int_ctx', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TRAP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TRAP_TAG_HEADER_UNION), + ('INT_CONTEXT_UNION', union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION), +] + +SDMA_PKT_TRAP = struct_SDMA_PKT_TRAP_TAG +class struct_SDMA_PKT_HDP_FLUSH_TAG(Structure): + pass + +struct_SDMA_PKT_HDP_FLUSH_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_HDP_FLUSH_TAG._fields_ = [ + ('DW_0_DATA', ctypes.c_uint32), + ('DW_1_DATA', ctypes.c_uint32), + ('DW_2_DATA', ctypes.c_uint32), + ('DW_3_DATA', ctypes.c_uint32), + ('DW_4_DATA', ctypes.c_uint32), + ('DW_5_DATA', ctypes.c_uint32), +] + +SDMA_PKT_HDP_FLUSH = struct_SDMA_PKT_HDP_FLUSH_TAG +hdp_flush_cmd = struct_SDMA_PKT_HDP_FLUSH_TAG # Variable struct_SDMA_PKT_HDP_FLUSH_TAG +class struct_SDMA_PKT_GCR_TAG(Structure): + pass + +class union_SDMA_PKT_GCR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('_2', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_GCR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD1_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_1_0._fields_ = [ + ('_0', ctypes.c_uint32, 7), + ('BaseVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD2_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_2_0._fields_ = [ + ('BaseVA_HI', ctypes.c_uint32, 16), + ('GCR_CONTROL_GLI_INV', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL1_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GLM_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLM_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLV_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL1_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_US', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL2_DISCARD', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_WB', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_GCR_TAG_WORD2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD3_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_3_0._fields_ = [ + ('GCR_CONTROL_RANGE_IS_PA', ctypes.c_uint32, 1), + ('GCR_CONTROL_SEQ', ctypes.c_uint32, 2), + ('_2', ctypes.c_uint32, 4), + ('LimitVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD4_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_4_0._fields_ = [ + ('LimitVA_HI', ctypes.c_uint32, 16), + ('_1', ctypes.c_uint32, 8), + ('VMID', ctypes.c_uint32, 4), + ('_3', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_GCR_TAG_WORD4_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD4_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD4_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_GCR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_GCR_TAG_HEADER_UNION), + ('WORD1_UNION', union_SDMA_PKT_GCR_TAG_WORD1_UNION), + ('WORD2_UNION', union_SDMA_PKT_GCR_TAG_WORD2_UNION), + ('WORD3_UNION', union_SDMA_PKT_GCR_TAG_WORD3_UNION), + ('WORD4_UNION', union_SDMA_PKT_GCR_TAG_WORD4_UNION), +] + +SDMA_PKT_GCR = struct_SDMA_PKT_GCR_TAG +__VEGA10_SDMA_PKT_OPEN_H_ = True # macro +SDMA_OP_NOP = 0 # macro +SDMA_OP_WRITE = 2 # macro +SDMA_OP_INDIRECT = 4 # macro +SDMA_OP_SEM = 7 # macro +SDMA_OP_COND_EXE = 9 # macro +SDMA_OP_PTEPDE = 12 # macro +SDMA_OP_SRBM_WRITE = 14 # macro +SDMA_OP_PRE_EXE = 15 # macro +SDMA_OP_DUMMY_TRAP = 16 # macro +SDMA_SUBOP_TIMESTAMP_SET = 0 # macro +SDMA_SUBOP_TIMESTAMP_GET = 1 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND = 4 # macro +SDMA_SUBOP_COPY_TILED = 1 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND = 5 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND = 6 # macro +SDMA_SUBOP_COPY_SOA = 3 # macro +SDMA_SUBOP_COPY_DIRTY_PAGE = 7 # macro +SDMA_SUBOP_COPY_LINEAR_PHY = 8 # macro +SDMA_SUBOP_WRITE_LINEAR = 0 # macro +SDMA_SUBOP_WRITE_TILED = 1 # macro +SDMA_SUBOP_PTEPDE_GEN = 0 # macro +SDMA_SUBOP_PTEPDE_COPY = 1 # macro +SDMA_SUBOP_PTEPDE_RMW = 2 # macro +SDMA_SUBOP_PTEPDE_COPY_BACKWARDS = 3 # macro +SDMA_SUBOP_DATA_FILL_MULTI = 1 # macro +SDMA_SUBOP_POLL_REG_WRITE_MEM = 1 # macro +SDMA_SUBOP_POLL_DBIT_WRITE_MEM = 2 # macro +SDMA_SUBOP_POLL_MEM_VERIFY = 3 # macro +HEADER_AGENT_DISPATCH = 4 # macro +HEADER_BARRIER = 5 # macro +SDMA_OP_AQL_COPY = 0 # macro +SDMA_OP_AQL_BARRIER_OR = 0 # macro +SDMA_PKT_HEADER_op_offset = 0 # macro +SDMA_PKT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_op_shift = 0 # macro +def SDMA_PKT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_ALL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift = 21 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_LOG(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift = 27 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GCC(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST1_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_DST1_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_DST1_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_DST2_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_DST2_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_TILED_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_DW_5_epitch_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_TILED_DW_5_epitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_5_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_COUNT_count_offset = 12 # macro +SDMA_PKT_COPY_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift = 26 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_VIDEOCOPY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset = 1 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_TILED_ADDR0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset = 2 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_TILED_ADDR0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset = 3 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_TILED_ADDR1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset = 4 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_TILED_ADDR1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset = 5 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_5_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift = 9 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset = 9 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_9_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset = 11 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset = 12 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset = 13 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 14 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset = 15 # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_COPY_T2T_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_T2T_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_T2T_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_T2T_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_6_src_epitch_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_T2T_DW_6_src_epitch_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_T2T_DW_12_dst_epitch_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_T2T_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_14_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_MIP_ID(x): # macro + return (((x)&0x0000000F)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_TILED_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_STRUCT_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_SB_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_SB_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset = 3 # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_START_INDEX_START_INDEX(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_COUNT_count_offset = 4 # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_COUNT_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_stride_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_mask = 0x000007FF # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRIDE(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift = 24 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRUCT_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_count_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift = 24 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset = 4 # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_TILED_HEADER_mip_max_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_mip_max_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_HEADER_mip_max_shift = 20 # macro +def SDMA_PKT_WRITE_TILED_HEADER_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_WRITE_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_WRITE_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_WRITE_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_WRITE_TILED_DW_5_epitch_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_epitch_mask = 0x0000FFFF # macro +SDMA_PKT_WRITE_TILED_DW_5_epitch_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_5_EPITCH(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_WRITE_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_WRITE_TILED_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_TILED_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_COUNT_count_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift = 28 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTE_SIZE(x): # macro + return (((x)&0x00000003)<<28) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift = 30 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_DIRECTION(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_FIRST_XFER(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_LAST_XFER(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask = 0x0001FFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_COUNT(x): # macro + return (((x)&0x0001FFFF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift = 20 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift = 22 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_LO_MASK_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_HI_MASK_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset = 5 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_LO_VALUE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset = 6 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_HI_VALUE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_INCR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset = 3 # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset = 4 # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset = 5 # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW0_INIT_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset = 6 # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW1_INIT_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset = 7 # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW0_INCR_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset = 8 # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW1_INCR_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_COUNT_count_offset = 9 # macro +SDMA_PKT_WRITE_INCR_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_WRITE_INCR_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_INDIRECT_HEADER_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_op_shift = 0 # macro +def SDMA_PKT_INDIRECT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_INDIRECT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_INDIRECT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_INDIRECT_HEADER_vmid_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_vmid_mask = 0x0000000F # macro +SDMA_PKT_INDIRECT_HEADER_vmid_shift = 16 # macro +def SDMA_PKT_INDIRECT_HEADER_VMID(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset = 1 # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_LO_IB_BASE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset = 2 # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_HI_IB_BASE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset = 3 # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask = 0x000FFFFF # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift = 0 # macro +def SDMA_PKT_INDIRECT_IB_SIZE_IB_SIZE(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset = 4 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_LO_CSA_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset = 5 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_HI_CSA_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SEMAPHORE_HEADER_write_one_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_shift = 29 # macro +def SDMA_PKT_SEMAPHORE_HEADER_WRITE_ONE(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_SEMAPHORE_HEADER_signal_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_shift = 30 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SIGNAL(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift = 31 # macro +def SDMA_PKT_SEMAPHORE_HEADER_MAILBOX(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_HEADER_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_op_shift = 0 # macro +def SDMA_PKT_FENCE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_FENCE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_FENCE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_DATA_data_offset = 3 # macro +SDMA_PKT_FENCE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_DATA_data_shift = 0 # macro +def SDMA_PKT_FENCE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask = 0x0000000F # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift = 28 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_BYTE_EN(x): # macro + return (((x)&0x0000000F)<<28) +SDMA_PKT_SRBM_WRITE_ADDR_addr_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_mask = 0x0003FFFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_ADDR(x): # macro + return (((x)&0x0003FFFF)<<0) +SDMA_PKT_SRBM_WRITE_DATA_data_offset = 2 # macro +SDMA_PKT_SRBM_WRITE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_SRBM_WRITE_DATA_data_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PRE_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_PRE_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PRE_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PRE_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift = 16 # macro +def SDMA_PKT_PRE_EXE_HEADER_DEV_SEL(x): # macro + return (((x)&0x000000FF)<<16) +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset = 1 # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_PRE_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COND_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COND_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COND_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COND_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_REFERENCE_reference_offset = 3 # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_shift = 0 # macro +def SDMA_PKT_COND_EXE_REFERENCE_REFERENCE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset = 4 # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_COND_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift = 16 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift = 30 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_FILLSIZE(x): # macro + return (((x)&0x00000003)<<30) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset = 3 # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DATA_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_COUNT_count_offset = 4 # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask = 0x00000001 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift = 31 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_MEMLOG_CLR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset = 1 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_BYTE_STRIDE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset = 2 # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_DMA_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset = 5 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask = 0x03FFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_COUNT(x): # macro + return (((x)&0x03FFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift = 26 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_HDP_FLUSH(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_POLL_REGMEM_HEADER_func_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_mask = 0x00000007 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_shift = 28 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_FUNC(x): # macro + return (((x)&0x00000007)<<28) +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift = 31 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_VALUE_value_offset = 3 # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_VALUE_VALUE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_MASK_mask_offset = 4 # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_MASK_MASK(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_interval_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_mask = 0x0000FFFF # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask = 0x00000FFF # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift = 16 # macro +def SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset = 1 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask = 0x3FFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift = 2 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_ADDR_31_2(x): # macro + return (((x)&0x3FFFFFFF)<<2) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 2 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 3 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask = 0x00000003 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift = 16 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_EA(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset = 3 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask = 0x0FFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift = 4 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_ADDR_31_4(x): # macro + return (((x)&0x0FFFFFFF)<<4) +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset = 4 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_PAGE_NUM_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask = 0x00000001 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift = 31 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_MODE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset = 1 # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_PATTERN_PATTERN(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset = 2 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_CMP0_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset = 3 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_CMP0_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset = 4 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset = 5 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset = 6 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_CMP1_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset = 7 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_CMP1_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset = 8 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset = 9 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset = 10 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_REC_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset = 11 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_REC_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset = 12 # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_RESERVED_RESERVED(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_HEADER_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_ATOMIC_HEADER_op_shift = 0 # macro +def SDMA_PKT_ATOMIC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_ATOMIC_HEADER_loop_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_loop_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_loop_shift = 16 # macro +def SDMA_PKT_ATOMIC_HEADER_LOOP(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_ATOMIC_HEADER_tmz_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_ATOMIC_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_ATOMIC_HEADER_atomic_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_mask = 0x0000007F # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_shift = 25 # macro +def SDMA_PKT_ATOMIC_HEADER_ATOMIC_OP(x): # macro + return (((x)&0x0000007F)<<25) +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset = 3 # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_LO_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset = 4 # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_HI_SRC_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset = 5 # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_LO_CMP_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset = 6 # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_HI_CMP_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset = 7 # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask = 0x00001FFF # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift = 0 # macro +def SDMA_PKT_ATOMIC_LOOP_INTERVAL_LOOP_INTERVAL(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset = 1 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_INIT_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_INIT_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_NOP_HEADER_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_op_shift = 0 # macro +def SDMA_PKT_NOP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_NOP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_NOP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_NOP_HEADER_count_offset = 0 # macro +SDMA_PKT_NOP_HEADER_count_mask = 0x00003FFF # macro +SDMA_PKT_NOP_HEADER_count_shift = 16 # macro +def SDMA_PKT_NOP_HEADER_COUNT(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_NOP_DATA0_data0_offset = 1 # macro +SDMA_PKT_NOP_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_NOP_DATA0_data0_shift = 0 # macro +def SDMA_PKT_NOP_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_HEADER_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_HEADER_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_HEADER_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_HEADER_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_HEADER_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_HEADER_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_HEADER_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_HEADER_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_HEADER_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_HEADER_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset = 2 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_RETURN_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset = 3 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_RETURN_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset = 4 # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 6 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 7 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 8 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 9 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset = 10 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_RESERVED_DW10(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset = 11 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_RESERVED_DW11(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset = 2 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_DEPENDENT_ADDR_0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset = 3 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_DEPENDENT_ADDR_0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset = 4 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_DEPENDENT_ADDR_1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset = 5 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_DEPENDENT_ADDR_1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset = 6 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_DEPENDENT_ADDR_2_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset = 7 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_DEPENDENT_ADDR_2_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset = 8 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_DEPENDENT_ADDR_3_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset = 9 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_DEPENDENT_ADDR_3_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset = 10 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_DEPENDENT_ADDR_4_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset = 11 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_DEPENDENT_ADDR_4_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +__all__ = \ + ['HEADER_AGENT_DISPATCH', 'HEADER_BARRIER', + 'HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_format_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_format_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_format_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_op_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_op_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_op_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_shift', 'SDMA_ATOMIC_ADD64', + 'SDMA_OP_AQL_BARRIER_OR', 'SDMA_OP_AQL_COPY', 'SDMA_OP_ATOMIC', + 'SDMA_OP_COND_EXE', 'SDMA_OP_CONST_FILL', 'SDMA_OP_COPY', + 'SDMA_OP_DUMMY_TRAP', 'SDMA_OP_FENCE', 'SDMA_OP_GCR', + 'SDMA_OP_INDIRECT', 'SDMA_OP_NOP', 'SDMA_OP_POLL_REGMEM', + 'SDMA_OP_PRE_EXE', 'SDMA_OP_PTEPDE', 'SDMA_OP_SEM', + 'SDMA_OP_SRBM_WRITE', 'SDMA_OP_TIMESTAMP', 'SDMA_OP_TRAP', + 'SDMA_OP_WRITE', 'SDMA_PKT_ATOMIC', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_loop_mask', + 'SDMA_PKT_ATOMIC_HEADER_loop_offset', + 'SDMA_PKT_ATOMIC_HEADER_loop_shift', + 'SDMA_PKT_ATOMIC_HEADER_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_tmz_mask', + 'SDMA_PKT_ATOMIC_HEADER_tmz_offset', + 'SDMA_PKT_ATOMIC_HEADER_tmz_shift', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_COND_EXE_HEADER_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_op_shift', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_mask', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_offset', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_shift', + 'SDMA_PKT_CONSTANT_FILL', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_mask', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_offset', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_shift', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_epitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift', + 'SDMA_PKT_COPY_LINEAR', 'SDMA_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_RECT', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_mask', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_offset', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_epitch_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_epitch_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_T2T_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_T2T_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_mask', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_offset', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_mask', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_offset', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_shift', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_mask', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_offset', + 'SDMA_PKT_COPY_TILED_DW_5_epitch_shift', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_TILED_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_TILED_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_epitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_id_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_mip_max_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_FENCE', 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_FENCE_DATA_data_mask', + 'SDMA_PKT_FENCE_DATA_data_offset', + 'SDMA_PKT_FENCE_DATA_data_shift', 'SDMA_PKT_FENCE_HEADER_op_mask', + 'SDMA_PKT_FENCE_HEADER_op_offset', + 'SDMA_PKT_FENCE_HEADER_op_shift', + 'SDMA_PKT_FENCE_HEADER_sub_op_mask', + 'SDMA_PKT_FENCE_HEADER_sub_op_offset', + 'SDMA_PKT_FENCE_HEADER_sub_op_shift', 'SDMA_PKT_GCR', + 'SDMA_PKT_HDP_FLUSH', 'SDMA_PKT_HEADER_op_mask', + 'SDMA_PKT_HEADER_op_offset', 'SDMA_PKT_HEADER_op_shift', + 'SDMA_PKT_HEADER_sub_op_mask', 'SDMA_PKT_HEADER_sub_op_offset', + 'SDMA_PKT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift', + 'SDMA_PKT_INDIRECT_HEADER_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_vmid_mask', + 'SDMA_PKT_INDIRECT_HEADER_vmid_offset', + 'SDMA_PKT_INDIRECT_HEADER_vmid_shift', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift', + 'SDMA_PKT_NOP_DATA0_data0_mask', + 'SDMA_PKT_NOP_DATA0_data0_offset', + 'SDMA_PKT_NOP_DATA0_data0_shift', + 'SDMA_PKT_NOP_HEADER_count_mask', + 'SDMA_PKT_NOP_HEADER_count_offset', + 'SDMA_PKT_NOP_HEADER_count_shift', 'SDMA_PKT_NOP_HEADER_op_mask', + 'SDMA_PKT_NOP_HEADER_op_offset', 'SDMA_PKT_NOP_HEADER_op_shift', + 'SDMA_PKT_NOP_HEADER_sub_op_mask', + 'SDMA_PKT_NOP_HEADER_sub_op_offset', + 'SDMA_PKT_NOP_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift', + 'SDMA_PKT_POLL_REGMEM', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_mask', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_offset', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_shift', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_mask', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_offset', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift', + 'SDMA_PKT_PRE_EXE_HEADER_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_op_shift', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_shift', + 'SDMA_PKT_SRBM_WRITE_DATA_data_mask', + 'SDMA_PKT_SRBM_WRITE_DATA_data_offset', + 'SDMA_PKT_SRBM_WRITE_DATA_data_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift', 'SDMA_PKT_TIMESTAMP', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift', + 'SDMA_PKT_TRAP', 'SDMA_PKT_TRAP_HEADER_op_mask', + 'SDMA_PKT_TRAP_HEADER_op_offset', 'SDMA_PKT_TRAP_HEADER_op_shift', + 'SDMA_PKT_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_WRITE_INCR_COUNT_count_mask', + 'SDMA_PKT_WRITE_INCR_COUNT_count_offset', + 'SDMA_PKT_WRITE_INCR_COUNT_count_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_op_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_WRITE_TILED_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_epitch_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_mip_max_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_shift', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift', + 'SDMA_SUBOP_COPY_DIRTY_PAGE', 'SDMA_SUBOP_COPY_LINEAR', + 'SDMA_SUBOP_COPY_LINEAR_PHY', 'SDMA_SUBOP_COPY_LINEAR_RECT', + 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND', 'SDMA_SUBOP_COPY_SOA', + 'SDMA_SUBOP_COPY_T2T_SUB_WIND', 'SDMA_SUBOP_COPY_TILED', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND', 'SDMA_SUBOP_DATA_FILL_MULTI', + 'SDMA_SUBOP_POLL_DBIT_WRITE_MEM', 'SDMA_SUBOP_POLL_MEM_VERIFY', + 'SDMA_SUBOP_POLL_REG_WRITE_MEM', 'SDMA_SUBOP_PTEPDE_COPY', + 'SDMA_SUBOP_PTEPDE_COPY_BACKWARDS', 'SDMA_SUBOP_PTEPDE_GEN', + 'SDMA_SUBOP_PTEPDE_RMW', 'SDMA_SUBOP_TIMESTAMP_GET', + 'SDMA_SUBOP_TIMESTAMP_GET_GLOBAL', 'SDMA_SUBOP_TIMESTAMP_SET', + 'SDMA_SUBOP_USER_GCR', 'SDMA_SUBOP_WRITE_LINEAR', + 'SDMA_SUBOP_WRITE_TILED', '__VEGA10_SDMA_PKT_OPEN_H_', + 'hdp_flush_cmd', 'struct_SDMA_PKT_ATOMIC_TAG', + 'struct_SDMA_PKT_ATOMIC_TAG_0_0', + 'struct_SDMA_PKT_ATOMIC_TAG_1_0', + 'struct_SDMA_PKT_ATOMIC_TAG_2_0', + 'struct_SDMA_PKT_ATOMIC_TAG_3_0', + 'struct_SDMA_PKT_ATOMIC_TAG_4_0', + 'struct_SDMA_PKT_ATOMIC_TAG_5_0', + 'struct_SDMA_PKT_ATOMIC_TAG_6_0', + 'struct_SDMA_PKT_ATOMIC_TAG_7_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_6_0', + 'struct_SDMA_PKT_FENCE_TAG', 'struct_SDMA_PKT_FENCE_TAG_0_0', + 'struct_SDMA_PKT_FENCE_TAG_1_0', 'struct_SDMA_PKT_FENCE_TAG_2_0', + 'struct_SDMA_PKT_FENCE_TAG_3_0', 'struct_SDMA_PKT_GCR_TAG', + 'struct_SDMA_PKT_GCR_TAG_0_0', 'struct_SDMA_PKT_GCR_TAG_1_0', + 'struct_SDMA_PKT_GCR_TAG_2_0', 'struct_SDMA_PKT_GCR_TAG_3_0', + 'struct_SDMA_PKT_GCR_TAG_4_0', 'struct_SDMA_PKT_HDP_FLUSH_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_0_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_1_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_2_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_3_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_4_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_5_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG', + 'struct_SDMA_PKT_TIMESTAMP_TAG_0_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_1_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_2_0', 'struct_SDMA_PKT_TRAP_TAG', + 'struct_SDMA_PKT_TRAP_TAG_0_0', 'struct_SDMA_PKT_TRAP_TAG_1_0', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_DATA_UNION', + 'union_SDMA_PKT_FENCE_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD1_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD2_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD3_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD4_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_5_0_0.py b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_5_0_0.py new file mode 100644 index 0000000000..1eb64252ca --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_5_0_0.py @@ -0,0 +1,7103 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/opt/rocm/include', '-x', 'c++'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_ = True # macro +SDMA_OP_COPY = 1 # macro +SDMA_OP_FENCE = 5 # macro +SDMA_OP_TRAP = 6 # macro +SDMA_OP_POLL_REGMEM = 8 # macro +SDMA_OP_ATOMIC = 10 # macro +SDMA_OP_CONST_FILL = 11 # macro +SDMA_OP_TIMESTAMP = 13 # macro +SDMA_OP_GCR = 17 # Variable ctypes.c_uint32 +SDMA_SUBOP_COPY_LINEAR = 0 # macro +SDMA_SUBOP_COPY_LINEAR_RECT = 4 # Variable ctypes.c_uint32 +SDMA_SUBOP_TIMESTAMP_GET_GLOBAL = 2 # macro +SDMA_SUBOP_USER_GCR = 1 # Variable ctypes.c_uint32 +SDMA_ATOMIC_ADD64 = 47 # Variable ctypes.c_uint32 +class struct_SDMA_PKT_COPY_LINEAR_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('extra_info', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._fields_ = [ + ('reserved_0', ctypes.c_uint32, 16), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_1', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION), + ('COUNT_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION), + ('PARAMETER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION), +] + +SDMA_PKT_COPY_LINEAR = struct_SDMA_PKT_COPY_LINEAR_TAG +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved', ctypes.c_uint32, 13), + ('element', ctypes.c_uint32, 3), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._fields_ = [ + ('src_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('src_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._fields_ = [ + ('src_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('src_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._fields_ = [ + ('src_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._fields_ = [ + ('dst_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0), + ('DW_8_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._fields_ = [ + ('dst_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0), + ('DW_9_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._fields_ = [ + ('dst_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0), + ('DW_10_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._fields_ = [ + ('rect_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('rect_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0), + ('DW_11_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._fields_ = [ + ('rect_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 5), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_3', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0), + ('DW_12_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION), + ('SRC_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION), + ('SRC_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION), + ('SRC_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION), + ('DST_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION), + ('DST_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION), + ('DST_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION), + ('RECT_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION), + ('RECT_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION), +] + +SDMA_PKT_COPY_LINEAR_RECT = struct_SDMA_PKT_COPY_LINEAR_RECT_TAG +class struct_SDMA_PKT_CONSTANT_FILL_TAG(Structure): + pass + +class union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('sw', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 12), + ('fillsize', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_CONSTANT_FILL_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION), + ('COUNT_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION), +] + +SDMA_PKT_CONSTANT_FILL = struct_SDMA_PKT_CONSTANT_FILL_TAG +class struct_SDMA_PKT_FENCE_TAG(Structure): + pass + +class union_SDMA_PKT_FENCE_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('mtype', ctypes.c_uint32, 3), + ('gcc', ctypes.c_uint32, 1), + ('sys', ctypes.c_uint32, 1), + ('pad1', ctypes.c_uint32, 1), + ('snp', ctypes.c_uint32, 1), + ('gpa', ctypes.c_uint32, 1), + ('l2_policy', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_3_0._fields_ = [ + ('data', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_FENCE_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_FENCE_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_FENCE_TAG_DATA_UNION), +] + +SDMA_PKT_FENCE = struct_SDMA_PKT_FENCE_TAG +class struct_SDMA_PKT_POLL_REGMEM_TAG(Structure): + pass + +class union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 10), + ('hdp_flush', ctypes.c_uint32, 1), + ('reserved_1', ctypes.c_uint32, 1), + ('func', ctypes.c_uint32, 3), + ('mem_poll', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._fields_ = [ + ('value', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._fields_ = [ + ('mask', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._fields_ = [ + ('interval', ctypes.c_uint32, 16), + ('retry_count', ctypes.c_uint32, 12), + ('reserved_0', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_POLL_REGMEM_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION), + ('VALUE_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION), + ('MASK_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION), + ('DW5_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION), +] + +SDMA_PKT_POLL_REGMEM = struct_SDMA_PKT_POLL_REGMEM_TAG +class struct_SDMA_PKT_ATOMIC_TAG(Structure): + pass + +class union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('l', ctypes.c_uint32, 1), + ('reserved_0', ctypes.c_uint32, 8), + ('operation', ctypes.c_uint32, 7), +] + +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_4_0._fields_ = [ + ('src_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_5_0._fields_ = [ + ('cmp_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_6_0._fields_ = [ + ('cmp_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_7_0._fields_ = [ + ('loop_interval', ctypes.c_uint32, 13), + ('reserved_0', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_ATOMIC_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION), + ('SRC_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION), + ('SRC_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION), + ('CMP_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION), + ('CMP_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION), + ('LOOP_UNION', union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION), +] + +SDMA_PKT_ATOMIC = struct_SDMA_PKT_ATOMIC_TAG +class struct_SDMA_PKT_TIMESTAMP_TAG(Structure): + pass + +class union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TIMESTAMP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION), +] + +SDMA_PKT_TIMESTAMP = struct_SDMA_PKT_TIMESTAMP_TAG +class struct_SDMA_PKT_TRAP_TAG(Structure): + pass + +class union_SDMA_PKT_TRAP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_1_0._fields_ = [ + ('int_ctx', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TRAP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TRAP_TAG_HEADER_UNION), + ('INT_CONTEXT_UNION', union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION), +] + +SDMA_PKT_TRAP = struct_SDMA_PKT_TRAP_TAG +class struct_SDMA_PKT_HDP_FLUSH_TAG(Structure): + pass + +struct_SDMA_PKT_HDP_FLUSH_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_HDP_FLUSH_TAG._fields_ = [ + ('DW_0_DATA', ctypes.c_uint32), + ('DW_1_DATA', ctypes.c_uint32), + ('DW_2_DATA', ctypes.c_uint32), + ('DW_3_DATA', ctypes.c_uint32), + ('DW_4_DATA', ctypes.c_uint32), + ('DW_5_DATA', ctypes.c_uint32), +] + +SDMA_PKT_HDP_FLUSH = struct_SDMA_PKT_HDP_FLUSH_TAG +hdp_flush_cmd = struct_SDMA_PKT_HDP_FLUSH_TAG # Variable struct_SDMA_PKT_HDP_FLUSH_TAG +class struct_SDMA_PKT_GCR_TAG(Structure): + pass + +class union_SDMA_PKT_GCR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('_2', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_GCR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD1_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_1_0._fields_ = [ + ('_0', ctypes.c_uint32, 7), + ('BaseVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD2_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_2_0._fields_ = [ + ('BaseVA_HI', ctypes.c_uint32, 16), + ('GCR_CONTROL_GLI_INV', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL1_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GLM_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLM_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLV_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL1_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_US', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL2_DISCARD', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_WB', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_GCR_TAG_WORD2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD3_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_3_0._fields_ = [ + ('GCR_CONTROL_RANGE_IS_PA', ctypes.c_uint32, 1), + ('GCR_CONTROL_SEQ', ctypes.c_uint32, 2), + ('_2', ctypes.c_uint32, 4), + ('LimitVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD4_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_4_0._fields_ = [ + ('LimitVA_HI', ctypes.c_uint32, 16), + ('_1', ctypes.c_uint32, 8), + ('VMID', ctypes.c_uint32, 4), + ('_3', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_GCR_TAG_WORD4_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD4_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD4_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_GCR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_GCR_TAG_HEADER_UNION), + ('WORD1_UNION', union_SDMA_PKT_GCR_TAG_WORD1_UNION), + ('WORD2_UNION', union_SDMA_PKT_GCR_TAG_WORD2_UNION), + ('WORD3_UNION', union_SDMA_PKT_GCR_TAG_WORD3_UNION), + ('WORD4_UNION', union_SDMA_PKT_GCR_TAG_WORD4_UNION), +] + +SDMA_PKT_GCR = struct_SDMA_PKT_GCR_TAG +__NAVI10_SDMA_PKT_OPEN_H_ = True # macro +SDMA_OP_NOP = 0 # macro +SDMA_OP_WRITE = 2 # macro +SDMA_OP_INDIRECT = 4 # macro +SDMA_OP_SEM = 7 # macro +SDMA_OP_COND_EXE = 9 # macro +SDMA_OP_PTEPDE = 12 # macro +SDMA_OP_SRBM_WRITE = 14 # macro +SDMA_OP_PRE_EXE = 15 # macro +SDMA_OP_GPUVM_INV = 16 # macro +SDMA_OP_GCR_REQ = 17 # macro +SDMA_OP_DUMMY_TRAP = 32 # macro +SDMA_SUBOP_TIMESTAMP_SET = 0 # macro +SDMA_SUBOP_TIMESTAMP_GET = 1 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND = 4 # macro +SDMA_SUBOP_COPY_TILED = 1 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND = 5 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND = 6 # macro +SDMA_SUBOP_COPY_SOA = 3 # macro +SDMA_SUBOP_COPY_DIRTY_PAGE = 7 # macro +SDMA_SUBOP_COPY_LINEAR_PHY = 8 # macro +SDMA_SUBOP_COPY_LINEAR_BC = 16 # macro +SDMA_SUBOP_COPY_TILED_BC = 17 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND_BC = 20 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND_BC = 21 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND_BC = 22 # macro +SDMA_SUBOP_WRITE_LINEAR = 0 # macro +SDMA_SUBOP_WRITE_TILED = 1 # macro +SDMA_SUBOP_WRITE_TILED_BC = 17 # macro +SDMA_SUBOP_PTEPDE_GEN = 0 # macro +SDMA_SUBOP_PTEPDE_COPY = 1 # macro +SDMA_SUBOP_PTEPDE_RMW = 2 # macro +SDMA_SUBOP_PTEPDE_COPY_BACKWARDS = 3 # macro +SDMA_SUBOP_DATA_FILL_MULTI = 1 # macro +SDMA_SUBOP_POLL_REG_WRITE_MEM = 1 # macro +SDMA_SUBOP_POLL_DBIT_WRITE_MEM = 2 # macro +SDMA_SUBOP_POLL_MEM_VERIFY = 3 # macro +SDMA_SUBOP_VM_INVALIDATION = 4 # macro +HEADER_AGENT_DISPATCH = 4 # macro +HEADER_BARRIER = 5 # macro +SDMA_OP_AQL_COPY = 0 # macro +SDMA_OP_AQL_BARRIER_OR = 0 # macro +SDMA_GCR_RANGE_IS_PA = (1<<18) # macro +def SDMA_GCR_SEQ(x): # macro + return (((x)&0x3)<<16) +SDMA_GCR_GL2_WB = (1<<15) # macro +SDMA_GCR_GL2_INV = (1<<14) # macro +SDMA_GCR_GL2_DISCARD = (1<<13) # macro +def SDMA_GCR_GL2_RANGE(x): # macro + return (((x)&0x3)<<11) +SDMA_GCR_GL2_US = (1<<10) # macro +SDMA_GCR_GL1_INV = (1<<9) # macro +SDMA_GCR_GLV_INV = (1<<8) # macro +SDMA_GCR_GLK_INV = (1<<7) # macro +SDMA_GCR_GLK_WB = (1<<6) # macro +SDMA_GCR_GLM_INV = (1<<5) # macro +SDMA_GCR_GLM_WB = (1<<4) # macro +def SDMA_GCR_GL1_RANGE(x): # macro + return (((x)&0x3)<<2) +def SDMA_GCR_GLI_INV(x): # macro + return (((x)&0x3)<<0) +SDMA_PKT_HEADER_op_offset = 0 # macro +SDMA_PKT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_op_shift = 0 # macro +def SDMA_PKT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_HEADER_backwards_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_backwards_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_backwards_shift = 25 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BACKWARDS(x): # macro + return (((x)&0x00000001)<<25) +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_shift = 22 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_DST_HA(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_shift = 30 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_SRC_HA(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_ALL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_shift = 3 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_MTYPE(x): # macro + return (((x)&0x00000007)<<3) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_shift = 6 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_L2_POLICY(x): # macro + return (((x)&0x00000003)<<6) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_shift = 11 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_MTYPE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_shift = 14 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_L2_POLICY(x): # macro + return (((x)&0x00000003)<<14) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_shift = 3 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_MTYPE(x): # macro + return (((x)&0x00000007)<<3) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_shift = 6 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_L2_POLICY(x): # macro + return (((x)&0x00000003)<<6) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_shift = 11 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_MTYPE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_shift = 14 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_L2_POLICY(x): # macro + return (((x)&0x00000003)<<14) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift = 21 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_LOG(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift = 27 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GCC(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST1_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_DST1_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_DST1_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_DST2_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_DST2_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_SRC_PITCH(x): # macro + return (((x)&0x00003FFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_DST_PITCH(x): # macro + return (((x)&0x00003FFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_shift = 22 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_DST_HA(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_shift = 30 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_SRC_HA(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_DW_5_mip_max_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_DW_5_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_5_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_7_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_DW_7_linear_cc_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_cc_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_cc_shift = 20 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_CC(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_COUNT_count_offset = 12 # macro +SDMA_PKT_COPY_TILED_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_TILED_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_BC_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_BC_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_BC_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_BC_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_BC_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_TILED_BC_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_BC_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_BC_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_BC_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_BC_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_BC_COUNT_count_offset = 11 # macro +SDMA_PKT_COPY_TILED_BC_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_TILED_BC_COUNT_count_shift = 2 # macro +def SDMA_PKT_COPY_TILED_BC_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<2) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift = 26 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_VIDEOCOPY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset = 1 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_TILED_ADDR0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset = 2 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_TILED_ADDR0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset = 3 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_TILED_ADDR1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset = 4 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_TILED_ADDR1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset = 5 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_5_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift = 9 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset = 9 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_9_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset = 11 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset = 12 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset = 13 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 14 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset = 15 # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_T2T_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_T2T_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_T2T_HEADER_dcc_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_shift = 19 # macro +def SDMA_PKT_COPY_T2T_HEADER_DCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_shift = 31 # macro +def SDMA_PKT_COPY_T2T_HEADER_DCC_DIR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_14_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_offset = 15 # macro +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_ADDR_LO_META_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_offset = 16 # macro +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_ADDR_HI_META_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_mask = 0x0000007F # macro +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_DATA_FORMAT(x): # macro + return (((x)&0x0000007F)<<0) +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_shift = 7 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_COLOR_TRANSFORM_DISABLE(x): # macro + return (((x)&0x00000001)<<7) +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_shift = 8 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_ALPHA_IS_ON_MSB(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_shift = 9 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_NUMBER_TYPE(x): # macro + return (((x)&0x00000007)<<9) +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_shift = 12 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_SURFACE_TYPE(x): # macro + return (((x)&0x00000003)<<12) +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_shift = 24 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_MAX_COMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_shift = 26 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_MAX_UNCOMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<26) +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_shift = 28 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_WRITE_COMPRESS_ENABLE(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_shift = 29 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_META_TMZ(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_COPY_T2T_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_10_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_mask = 0x00000FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_11_DST_DEPTH(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_shift = 19 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_TILED_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_offset = 14 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_META_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_offset = 15 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_META_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_mask = 0x0000007F # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_DATA_FORMAT(x): # macro + return (((x)&0x0000007F)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_shift = 7 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_COLOR_TRANSFORM_DISABLE(x): # macro + return (((x)&0x00000001)<<7) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_ALPHA_IS_ON_MSB(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_NUMBER_TYPE(x): # macro + return (((x)&0x00000007)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_shift = 12 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_SURFACE_TYPE(x): # macro + return (((x)&0x00000003)<<12) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_MAX_COMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_shift = 26 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_MAX_UNCOMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<26) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_shift = 28 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_WRITE_COMPRESS_ENABLE(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_shift = 29 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_META_TMZ(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_TILED_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_MAT_ASPT(x): # macro + return ((x&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_LINEAR_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_STRUCT_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_SB_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_SB_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset = 3 # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_START_INDEX_START_INDEX(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_COUNT_count_offset = 4 # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_COUNT_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_stride_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_mask = 0x000007FF # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRIDE(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift = 24 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRUCT_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_count_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift = 24 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset = 4 # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_mask = 0x00001FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_WRITE_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_WRITE_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_WRITE_TILED_DW_5_mip_max_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_mip_max_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_DW_5_mip_max_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_5_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_WRITE_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_z_mask = 0x00001FFF # macro +SDMA_PKT_WRITE_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_7_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_TILED_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_BC_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_shift = 11 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_shift = 15 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_shift = 21 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_shift = 26 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_WRITE_TILED_BC_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_BC_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_BC_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_BC_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_BC_COUNT_count_shift = 2 # macro +def SDMA_PKT_WRITE_TILED_BC_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<2) +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_COUNT_count_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift = 28 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTE_SIZE(x): # macro + return (((x)&0x00000003)<<28) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift = 30 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_DIRECTION(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_FIRST_XFER(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_LAST_XFER(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask = 0x0001FFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_COUNT(x): # macro + return (((x)&0x0001FFFF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_mask = 0x00000007 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_shift = 16 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_MTYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift = 20 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift = 22 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_LO_MASK_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_HI_MASK_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset = 5 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_LO_VALUE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset = 6 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_HI_VALUE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_INCR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset = 3 # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset = 4 # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset = 5 # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW0_INIT_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset = 6 # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW1_INIT_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset = 7 # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW0_INCR_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset = 8 # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW1_INCR_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_COUNT_count_offset = 9 # macro +SDMA_PKT_WRITE_INCR_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_WRITE_INCR_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_INDIRECT_HEADER_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_op_shift = 0 # macro +def SDMA_PKT_INDIRECT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_INDIRECT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_INDIRECT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_INDIRECT_HEADER_vmid_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_vmid_mask = 0x0000000F # macro +SDMA_PKT_INDIRECT_HEADER_vmid_shift = 16 # macro +def SDMA_PKT_INDIRECT_HEADER_VMID(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_INDIRECT_HEADER_priv_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_priv_mask = 0x00000001 # macro +SDMA_PKT_INDIRECT_HEADER_priv_shift = 31 # macro +def SDMA_PKT_INDIRECT_HEADER_PRIV(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset = 1 # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_LO_IB_BASE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset = 2 # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_HI_IB_BASE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset = 3 # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask = 0x000FFFFF # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift = 0 # macro +def SDMA_PKT_INDIRECT_IB_SIZE_IB_SIZE(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset = 4 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_LO_CSA_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset = 5 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_HI_CSA_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SEMAPHORE_HEADER_write_one_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_shift = 29 # macro +def SDMA_PKT_SEMAPHORE_HEADER_WRITE_ONE(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_SEMAPHORE_HEADER_signal_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_shift = 30 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SIGNAL(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift = 31 # macro +def SDMA_PKT_SEMAPHORE_HEADER_MAILBOX(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_HEADER_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_op_shift = 0 # macro +def SDMA_PKT_FENCE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_FENCE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_FENCE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_FENCE_HEADER_mtype_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_mtype_mask = 0x00000007 # macro +SDMA_PKT_FENCE_HEADER_mtype_shift = 16 # macro +def SDMA_PKT_FENCE_HEADER_MTYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_FENCE_HEADER_gcc_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_FENCE_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_FENCE_HEADER_sys_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_sys_shift = 20 # macro +def SDMA_PKT_FENCE_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_FENCE_HEADER_snp_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_snp_shift = 22 # macro +def SDMA_PKT_FENCE_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_FENCE_HEADER_gpa_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_FENCE_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_FENCE_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_FENCE_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_FENCE_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_DATA_data_offset = 3 # macro +SDMA_PKT_FENCE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_DATA_data_shift = 0 # macro +def SDMA_PKT_FENCE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask = 0x0000000F # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift = 28 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_BYTE_EN(x): # macro + return (((x)&0x0000000F)<<28) +SDMA_PKT_SRBM_WRITE_ADDR_addr_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_mask = 0x0003FFFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_ADDR(x): # macro + return (((x)&0x0003FFFF)<<0) +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_mask = 0x00000FFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_shift = 20 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_APERTUREID(x): # macro + return (((x)&0x00000FFF)<<20) +SDMA_PKT_SRBM_WRITE_DATA_data_offset = 2 # macro +SDMA_PKT_SRBM_WRITE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_SRBM_WRITE_DATA_data_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PRE_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_PRE_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PRE_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PRE_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift = 16 # macro +def SDMA_PKT_PRE_EXE_HEADER_DEV_SEL(x): # macro + return (((x)&0x000000FF)<<16) +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset = 1 # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_PRE_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COND_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COND_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COND_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COND_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_REFERENCE_reference_offset = 3 # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_shift = 0 # macro +def SDMA_PKT_COND_EXE_REFERENCE_REFERENCE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset = 4 # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_COND_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift = 16 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift = 30 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_FILLSIZE(x): # macro + return (((x)&0x00000003)<<30) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset = 3 # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DATA_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_COUNT_count_offset = 4 # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask = 0x00000001 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift = 31 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_MEMLOG_CLR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset = 1 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_BYTE_STRIDE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset = 2 # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_DMA_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset = 5 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask = 0x03FFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_COUNT(x): # macro + return (((x)&0x03FFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift = 26 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_HDP_FLUSH(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_POLL_REGMEM_HEADER_func_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_mask = 0x00000007 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_shift = 28 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_FUNC(x): # macro + return (((x)&0x00000007)<<28) +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift = 31 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_VALUE_value_offset = 3 # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_VALUE_VALUE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_MASK_mask_offset = 4 # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_MASK_MASK(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_interval_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_mask = 0x0000FFFF # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask = 0x00000FFF # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift = 16 # macro +def SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset = 1 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask = 0x3FFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift = 2 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_ADDR_31_2(x): # macro + return (((x)&0x3FFFFFFF)<<2) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 2 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 3 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask = 0x00000003 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift = 16 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_EA(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset = 3 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask = 0x0FFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift = 4 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_ADDR_31_4(x): # macro + return (((x)&0x0FFFFFFF)<<4) +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset = 4 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_PAGE_NUM_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask = 0x00000001 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift = 31 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_MODE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset = 1 # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_PATTERN_PATTERN(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset = 2 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_CMP0_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset = 3 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_CMP0_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset = 4 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset = 5 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset = 6 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_CMP1_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset = 7 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_CMP1_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset = 8 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset = 9 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset = 10 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_REC_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset = 11 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_REC_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset = 12 # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_RESERVED_RESERVED(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_HEADER_op_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_VM_INVALIDATION_HEADER_op_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_shift = 16 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_GFX_ENG_ID(x): # macro + return (((x)&0x0000001F)<<16) +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_shift = 24 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_MM_ENG_ID(x): # macro + return (((x)&0x0000001F)<<24) +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_offset = 1 # macro +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_mask = 0xFFFFFFFF # macro +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_INVALIDATEREQ(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_offset = 2 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_mask = 0xFFFFFFFF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_ADDRESSRANGELO(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_mask = 0x0000FFFF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_INVALIDATEACK(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_shift = 16 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_ADDRESSRANGEHI(x): # macro + return (((x)&0x0000001F)<<16) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_mask = 0x000001FF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_shift = 23 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_RESERVED(x): # macro + return (((x)&0x000001FF)<<23) +SDMA_PKT_ATOMIC_HEADER_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_ATOMIC_HEADER_op_shift = 0 # macro +def SDMA_PKT_ATOMIC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_ATOMIC_HEADER_loop_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_loop_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_loop_shift = 16 # macro +def SDMA_PKT_ATOMIC_HEADER_LOOP(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_ATOMIC_HEADER_tmz_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_ATOMIC_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_ATOMIC_HEADER_atomic_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_mask = 0x0000007F # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_shift = 25 # macro +def SDMA_PKT_ATOMIC_HEADER_ATOMIC_OP(x): # macro + return (((x)&0x0000007F)<<25) +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset = 3 # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_LO_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset = 4 # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_HI_SRC_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset = 5 # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_LO_CMP_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset = 6 # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_HI_CMP_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset = 7 # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask = 0x00001FFF # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift = 0 # macro +def SDMA_PKT_ATOMIC_LOOP_INTERVAL_LOOP_INTERVAL(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset = 1 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_INIT_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_INIT_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_GPUVM_INV_HEADER_op_offset = 0 # macro +SDMA_PKT_GPUVM_INV_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_GPUVM_INV_HEADER_op_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_GPUVM_INV_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_GPUVM_INV_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_GPUVM_INV_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_GPUVM_INV_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_mask = 0x0000FFFF # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_PER_VMID_INV_REQ(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_mask = 0x00000007 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_shift = 16 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_FLUSH_TYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_shift = 19 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PTES(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_shift = 20 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE0(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_shift = 21 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE1(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_shift = 22 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE2(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_shift = 23 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L1_PTES(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_shift = 24 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_CLR_PROTECTION_FAULT_STATUS_ADDR(x): # macro + return (((x)&0x00000001)<<24) +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_shift = 25 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_LOG_REQUEST(x): # macro + return (((x)&0x00000001)<<25) +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_shift = 26 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_FOUR_KILOBYTES(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_offset = 2 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD2_S(x): # macro + return (((x)&0x00000001)<<0) +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_offset = 2 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_mask = 0x7FFFFFFF # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_shift = 1 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD2_PAGE_VA_42_12(x): # macro + return (((x)&0x7FFFFFFF)<<1) +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_offset = 3 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_mask = 0x0000003F # macro +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD3_PAGE_VA_47_43(x): # macro + return (((x)&0x0000003F)<<0) +SDMA_PKT_GCR_REQ_HEADER_op_offset = 0 # macro +SDMA_PKT_GCR_REQ_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_GCR_REQ_HEADER_op_shift = 0 # macro +def SDMA_PKT_GCR_REQ_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_GCR_REQ_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_GCR_REQ_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_GCR_REQ_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_GCR_REQ_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_offset = 1 # macro +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_mask = 0x01FFFFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_shift = 7 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD1_BASE_VA_31_7(x): # macro + return (((x)&0x01FFFFFF)<<7) +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_offset = 2 # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD2_BASE_VA_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_offset = 2 # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_shift = 16 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD2_GCR_CONTROL_15_0(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_offset = 3 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_mask = 0x00000007 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD3_GCR_CONTROL_18_16(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_offset = 3 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_mask = 0x01FFFFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_shift = 7 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD3_LIMIT_VA_31_7(x): # macro + return (((x)&0x01FFFFFF)<<7) +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_offset = 4 # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD4_LIMIT_VA_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_offset = 4 # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_mask = 0x0000000F # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_shift = 24 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD4_VMID(x): # macro + return (((x)&0x0000000F)<<24) +SDMA_PKT_NOP_HEADER_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_op_shift = 0 # macro +def SDMA_PKT_NOP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_NOP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_NOP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_NOP_HEADER_count_offset = 0 # macro +SDMA_PKT_NOP_HEADER_count_mask = 0x00003FFF # macro +SDMA_PKT_NOP_HEADER_count_shift = 16 # macro +def SDMA_PKT_NOP_HEADER_COUNT(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_NOP_DATA0_data0_offset = 1 # macro +SDMA_PKT_NOP_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_NOP_DATA0_data0_shift = 0 # macro +def SDMA_PKT_NOP_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_HEADER_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_HEADER_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_HEADER_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_HEADER_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_HEADER_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_HEADER_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_HEADER_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_HEADER_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_HEADER_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_HEADER_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset = 2 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_RETURN_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset = 3 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_RETURN_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset = 4 # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 6 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 7 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 8 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 9 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset = 10 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_RESERVED_DW10(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset = 11 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_RESERVED_DW11(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset = 2 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_DEPENDENT_ADDR_0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset = 3 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_DEPENDENT_ADDR_0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset = 4 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_DEPENDENT_ADDR_1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset = 5 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_DEPENDENT_ADDR_1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset = 6 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_DEPENDENT_ADDR_2_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset = 7 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_DEPENDENT_ADDR_2_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset = 8 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_DEPENDENT_ADDR_3_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset = 9 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_DEPENDENT_ADDR_3_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset = 10 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_DEPENDENT_ADDR_4_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset = 11 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_DEPENDENT_ADDR_4_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +__all__ = \ + ['HEADER_AGENT_DISPATCH', 'HEADER_BARRIER', + 'HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_format_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_format_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_format_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_op_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_op_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_op_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_shift', 'SDMA_ATOMIC_ADD64', + 'SDMA_GCR_GL1_INV', 'SDMA_GCR_GL2_DISCARD', 'SDMA_GCR_GL2_INV', + 'SDMA_GCR_GL2_US', 'SDMA_GCR_GL2_WB', 'SDMA_GCR_GLK_INV', + 'SDMA_GCR_GLK_WB', 'SDMA_GCR_GLM_INV', 'SDMA_GCR_GLM_WB', + 'SDMA_GCR_GLV_INV', 'SDMA_GCR_RANGE_IS_PA', + 'SDMA_OP_AQL_BARRIER_OR', 'SDMA_OP_AQL_COPY', 'SDMA_OP_ATOMIC', + 'SDMA_OP_COND_EXE', 'SDMA_OP_CONST_FILL', 'SDMA_OP_COPY', + 'SDMA_OP_DUMMY_TRAP', 'SDMA_OP_FENCE', 'SDMA_OP_GCR', + 'SDMA_OP_GCR_REQ', 'SDMA_OP_GPUVM_INV', 'SDMA_OP_INDIRECT', + 'SDMA_OP_NOP', 'SDMA_OP_POLL_REGMEM', 'SDMA_OP_PRE_EXE', + 'SDMA_OP_PTEPDE', 'SDMA_OP_SEM', 'SDMA_OP_SRBM_WRITE', + 'SDMA_OP_TIMESTAMP', 'SDMA_OP_TRAP', 'SDMA_OP_WRITE', + 'SDMA_PKT_ATOMIC', 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_loop_mask', + 'SDMA_PKT_ATOMIC_HEADER_loop_offset', + 'SDMA_PKT_ATOMIC_HEADER_loop_shift', + 'SDMA_PKT_ATOMIC_HEADER_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_tmz_mask', + 'SDMA_PKT_ATOMIC_HEADER_tmz_offset', + 'SDMA_PKT_ATOMIC_HEADER_tmz_shift', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_COND_EXE_HEADER_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_op_shift', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_mask', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_offset', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_shift', + 'SDMA_PKT_CONSTANT_FILL', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_mask', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_offset', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_shift', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift', + 'SDMA_PKT_COPY_LINEAR', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_RECT', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_mask', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_offset', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_mask', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_offset', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_shift', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_mask', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_offset', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_shift', + 'SDMA_PKT_COPY_T2T_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_mask', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_offset', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_shift', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_mask', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_offset', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_shift', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_mask', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_offset', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_shift', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cc_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cc_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cc_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_TILED_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_FENCE', 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_FENCE_DATA_data_mask', + 'SDMA_PKT_FENCE_DATA_data_offset', + 'SDMA_PKT_FENCE_DATA_data_shift', + 'SDMA_PKT_FENCE_HEADER_gcc_mask', + 'SDMA_PKT_FENCE_HEADER_gcc_offset', + 'SDMA_PKT_FENCE_HEADER_gcc_shift', + 'SDMA_PKT_FENCE_HEADER_gpa_mask', + 'SDMA_PKT_FENCE_HEADER_gpa_offset', + 'SDMA_PKT_FENCE_HEADER_gpa_shift', + 'SDMA_PKT_FENCE_HEADER_l2_policy_mask', + 'SDMA_PKT_FENCE_HEADER_l2_policy_offset', + 'SDMA_PKT_FENCE_HEADER_l2_policy_shift', + 'SDMA_PKT_FENCE_HEADER_mtype_mask', + 'SDMA_PKT_FENCE_HEADER_mtype_offset', + 'SDMA_PKT_FENCE_HEADER_mtype_shift', + 'SDMA_PKT_FENCE_HEADER_op_mask', + 'SDMA_PKT_FENCE_HEADER_op_offset', + 'SDMA_PKT_FENCE_HEADER_op_shift', + 'SDMA_PKT_FENCE_HEADER_snp_mask', + 'SDMA_PKT_FENCE_HEADER_snp_offset', + 'SDMA_PKT_FENCE_HEADER_snp_shift', + 'SDMA_PKT_FENCE_HEADER_sub_op_mask', + 'SDMA_PKT_FENCE_HEADER_sub_op_offset', + 'SDMA_PKT_FENCE_HEADER_sub_op_shift', + 'SDMA_PKT_FENCE_HEADER_sys_mask', + 'SDMA_PKT_FENCE_HEADER_sys_offset', + 'SDMA_PKT_FENCE_HEADER_sys_shift', 'SDMA_PKT_GCR', + 'SDMA_PKT_GCR_REQ_HEADER_op_mask', + 'SDMA_PKT_GCR_REQ_HEADER_op_offset', + 'SDMA_PKT_GCR_REQ_HEADER_op_shift', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_mask', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_offset', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_shift', + 'SDMA_PKT_GPUVM_INV_HEADER_op_mask', + 'SDMA_PKT_GPUVM_INV_HEADER_op_offset', + 'SDMA_PKT_GPUVM_INV_HEADER_op_shift', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_mask', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_offset', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_shift', + 'SDMA_PKT_HDP_FLUSH', 'SDMA_PKT_HEADER_op_mask', + 'SDMA_PKT_HEADER_op_offset', 'SDMA_PKT_HEADER_op_shift', + 'SDMA_PKT_HEADER_sub_op_mask', 'SDMA_PKT_HEADER_sub_op_offset', + 'SDMA_PKT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift', + 'SDMA_PKT_INDIRECT_HEADER_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_priv_mask', + 'SDMA_PKT_INDIRECT_HEADER_priv_offset', + 'SDMA_PKT_INDIRECT_HEADER_priv_shift', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_vmid_mask', + 'SDMA_PKT_INDIRECT_HEADER_vmid_offset', + 'SDMA_PKT_INDIRECT_HEADER_vmid_shift', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift', + 'SDMA_PKT_NOP_DATA0_data0_mask', + 'SDMA_PKT_NOP_DATA0_data0_offset', + 'SDMA_PKT_NOP_DATA0_data0_shift', + 'SDMA_PKT_NOP_HEADER_count_mask', + 'SDMA_PKT_NOP_HEADER_count_offset', + 'SDMA_PKT_NOP_HEADER_count_shift', 'SDMA_PKT_NOP_HEADER_op_mask', + 'SDMA_PKT_NOP_HEADER_op_offset', 'SDMA_PKT_NOP_HEADER_op_shift', + 'SDMA_PKT_NOP_HEADER_sub_op_mask', + 'SDMA_PKT_NOP_HEADER_sub_op_offset', + 'SDMA_PKT_NOP_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift', + 'SDMA_PKT_POLL_REGMEM', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_mask', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_offset', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_shift', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_mask', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_offset', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift', + 'SDMA_PKT_PRE_EXE_HEADER_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_op_shift', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_shift', + 'SDMA_PKT_SRBM_WRITE_DATA_data_mask', + 'SDMA_PKT_SRBM_WRITE_DATA_data_offset', + 'SDMA_PKT_SRBM_WRITE_DATA_data_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift', 'SDMA_PKT_TIMESTAMP', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift', + 'SDMA_PKT_TRAP', 'SDMA_PKT_TRAP_HEADER_op_mask', + 'SDMA_PKT_TRAP_HEADER_op_offset', 'SDMA_PKT_TRAP_HEADER_op_shift', + 'SDMA_PKT_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_shift', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_mask', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_offset', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_shift', + 'SDMA_PKT_WRITE_INCR_COUNT_count_mask', + 'SDMA_PKT_WRITE_INCR_COUNT_count_offset', + 'SDMA_PKT_WRITE_INCR_COUNT_count_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_op_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_shift', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift', + 'SDMA_SUBOP_COPY_DIRTY_PAGE', 'SDMA_SUBOP_COPY_LINEAR', + 'SDMA_SUBOP_COPY_LINEAR_BC', 'SDMA_SUBOP_COPY_LINEAR_PHY', + 'SDMA_SUBOP_COPY_LINEAR_RECT', 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND', + 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND_BC', 'SDMA_SUBOP_COPY_SOA', + 'SDMA_SUBOP_COPY_T2T_SUB_WIND', 'SDMA_SUBOP_COPY_T2T_SUB_WIND_BC', + 'SDMA_SUBOP_COPY_TILED', 'SDMA_SUBOP_COPY_TILED_BC', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND_BC', 'SDMA_SUBOP_DATA_FILL_MULTI', + 'SDMA_SUBOP_POLL_DBIT_WRITE_MEM', 'SDMA_SUBOP_POLL_MEM_VERIFY', + 'SDMA_SUBOP_POLL_REG_WRITE_MEM', 'SDMA_SUBOP_PTEPDE_COPY', + 'SDMA_SUBOP_PTEPDE_COPY_BACKWARDS', 'SDMA_SUBOP_PTEPDE_GEN', + 'SDMA_SUBOP_PTEPDE_RMW', 'SDMA_SUBOP_TIMESTAMP_GET', + 'SDMA_SUBOP_TIMESTAMP_GET_GLOBAL', 'SDMA_SUBOP_TIMESTAMP_SET', + 'SDMA_SUBOP_USER_GCR', 'SDMA_SUBOP_VM_INVALIDATION', + 'SDMA_SUBOP_WRITE_LINEAR', 'SDMA_SUBOP_WRITE_TILED', + 'SDMA_SUBOP_WRITE_TILED_BC', '__NAVI10_SDMA_PKT_OPEN_H_', + 'hdp_flush_cmd', 'struct_SDMA_PKT_ATOMIC_TAG', + 'struct_SDMA_PKT_ATOMIC_TAG_0_0', + 'struct_SDMA_PKT_ATOMIC_TAG_1_0', + 'struct_SDMA_PKT_ATOMIC_TAG_2_0', + 'struct_SDMA_PKT_ATOMIC_TAG_3_0', + 'struct_SDMA_PKT_ATOMIC_TAG_4_0', + 'struct_SDMA_PKT_ATOMIC_TAG_5_0', + 'struct_SDMA_PKT_ATOMIC_TAG_6_0', + 'struct_SDMA_PKT_ATOMIC_TAG_7_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_6_0', + 'struct_SDMA_PKT_FENCE_TAG', 'struct_SDMA_PKT_FENCE_TAG_0_0', + 'struct_SDMA_PKT_FENCE_TAG_1_0', 'struct_SDMA_PKT_FENCE_TAG_2_0', + 'struct_SDMA_PKT_FENCE_TAG_3_0', 'struct_SDMA_PKT_GCR_TAG', + 'struct_SDMA_PKT_GCR_TAG_0_0', 'struct_SDMA_PKT_GCR_TAG_1_0', + 'struct_SDMA_PKT_GCR_TAG_2_0', 'struct_SDMA_PKT_GCR_TAG_3_0', + 'struct_SDMA_PKT_GCR_TAG_4_0', 'struct_SDMA_PKT_HDP_FLUSH_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_0_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_1_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_2_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_3_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_4_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_5_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG', + 'struct_SDMA_PKT_TIMESTAMP_TAG_0_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_1_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_2_0', 'struct_SDMA_PKT_TRAP_TAG', + 'struct_SDMA_PKT_TRAP_TAG_0_0', 'struct_SDMA_PKT_TRAP_TAG_1_0', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_DATA_UNION', + 'union_SDMA_PKT_FENCE_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD1_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD2_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD3_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD4_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_6_0_0.py b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_6_0_0.py new file mode 100644 index 0000000000..b8934de798 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/sdma_6_0_0.py @@ -0,0 +1,8085 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/opt/rocm/include', '-x', 'c++'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_ = True # macro +SDMA_OP_COPY = 1 # macro +SDMA_OP_FENCE = 5 # macro +SDMA_OP_TRAP = 6 # macro +SDMA_OP_POLL_REGMEM = 8 # macro +SDMA_OP_ATOMIC = 10 # macro +SDMA_OP_CONST_FILL = 11 # macro +SDMA_OP_TIMESTAMP = 13 # macro +SDMA_OP_GCR = 17 # Variable ctypes.c_uint32 +SDMA_SUBOP_COPY_LINEAR = 0 # macro +SDMA_SUBOP_COPY_LINEAR_RECT = 4 # Variable ctypes.c_uint32 +SDMA_SUBOP_TIMESTAMP_GET_GLOBAL = 2 # macro +SDMA_SUBOP_USER_GCR = 1 # Variable ctypes.c_uint32 +SDMA_ATOMIC_ADD64 = 47 # Variable ctypes.c_uint32 +class struct_SDMA_PKT_COPY_LINEAR_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('extra_info', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_1_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_2_0._fields_ = [ + ('reserved_0', ctypes.c_uint32, 16), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_1', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_3_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_4_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_5_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG_6_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION), + ('COUNT_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION), + ('PARAMETER_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION), +] + +SDMA_PKT_COPY_LINEAR = struct_SDMA_PKT_COPY_LINEAR_TAG +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG(Structure): + pass + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved', ctypes.c_uint32, 13), + ('element', ctypes.c_uint32, 3), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0._fields_ = [ + ('src_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0._fields_ = [ + ('src_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0._fields_ = [ + ('src_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('src_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0._fields_ = [ + ('src_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('src_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0._fields_ = [ + ('src_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0._fields_ = [ + ('dst_offset_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_offset_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0), + ('DW_8_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0._fields_ = [ + ('dst_offset_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 2), + ('dst_pitch', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0), + ('DW_9_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0._fields_ = [ + ('dst_slice_pitch', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0), + ('DW_10_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0._fields_ = [ + ('rect_x', ctypes.c_uint32, 14), + ('reserved_1', ctypes.c_uint32, 2), + ('rect_y', ctypes.c_uint32, 14), + ('reserved_2', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0), + ('DW_11_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION(Union): + pass + +class struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0(Structure): + pass + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0._fields_ = [ + ('rect_z', ctypes.c_uint32, 11), + ('reserved_1', ctypes.c_uint32, 5), + ('dst_swap', ctypes.c_uint32, 2), + ('reserved_2', ctypes.c_uint32, 6), + ('src_swap', ctypes.c_uint32, 2), + ('reserved_3', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0), + ('DW_12_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_COPY_LINEAR_RECT_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION), + ('SRC_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION), + ('SRC_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION), + ('SRC_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION), + ('SRC_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION), + ('SRC_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION), + ('DST_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION), + ('DST_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION), + ('DST_PARAMETER_3_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION), + ('RECT_PARAMETER_1_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION), + ('RECT_PARAMETER_2_UNION', union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION), +] + +SDMA_PKT_COPY_LINEAR_RECT = struct_SDMA_PKT_COPY_LINEAR_RECT_TAG +class struct_SDMA_PKT_CONSTANT_FILL_TAG(Structure): + pass + +class union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('sw', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 12), + ('fillsize', ctypes.c_uint32, 2), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0._fields_ = [ + ('dst_addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0._fields_ = [ + ('dst_addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION(Union): + pass + +class struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0._fields_ = [ + ('count', ctypes.c_uint32, 22), + ('reserved_0', ctypes.c_uint32, 10), +] + +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_CONSTANT_FILL_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_CONSTANT_FILL_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION), + ('DST_ADDR_LO_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION), + ('DST_ADDR_HI_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION), + ('COUNT_UNION', union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION), +] + +SDMA_PKT_CONSTANT_FILL = struct_SDMA_PKT_CONSTANT_FILL_TAG +class struct_SDMA_PKT_FENCE_TAG(Structure): + pass + +class union_SDMA_PKT_FENCE_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('mtype', ctypes.c_uint32, 3), + ('gcc', ctypes.c_uint32, 1), + ('sys', ctypes.c_uint32, 1), + ('pad1', ctypes.c_uint32, 1), + ('snp', ctypes.c_uint32, 1), + ('gpa', ctypes.c_uint32, 1), + ('l2_policy', ctypes.c_uint32, 2), + ('reserved_0', ctypes.c_uint32, 6), +] + +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_FENCE_TAG_DATA_UNION(Union): + pass + +class struct_SDMA_PKT_FENCE_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_FENCE_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG_3_0._fields_ = [ + ('data', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_FENCE_TAG_DATA_UNION._pack_ = 1 # source:False +union_SDMA_PKT_FENCE_TAG_DATA_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_FENCE_TAG_DATA_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_FENCE_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_FENCE_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_FENCE_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_FENCE_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION), + ('DATA_UNION', union_SDMA_PKT_FENCE_TAG_DATA_UNION), +] + +SDMA_PKT_FENCE = struct_SDMA_PKT_FENCE_TAG +class struct_SDMA_PKT_POLL_REGMEM_TAG(Structure): + pass + +class union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 10), + ('hdp_flush', ctypes.c_uint32, 1), + ('reserved_1', ctypes.c_uint32, 1), + ('func', ctypes.c_uint32, 3), + ('mem_poll', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_3_0._fields_ = [ + ('value', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_4_0._fields_ = [ + ('mask', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION(Union): + pass + +class struct_SDMA_PKT_POLL_REGMEM_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG_5_0._fields_ = [ + ('interval', ctypes.c_uint32, 16), + ('retry_count', ctypes.c_uint32, 12), + ('reserved_0', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._pack_ = 1 # source:False +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_POLL_REGMEM_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_POLL_REGMEM_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_POLL_REGMEM_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION), + ('VALUE_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION), + ('MASK_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION), + ('DW5_UNION', union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION), +] + +SDMA_PKT_POLL_REGMEM = struct_SDMA_PKT_POLL_REGMEM_TAG +class struct_SDMA_PKT_ATOMIC_TAG(Structure): + pass + +class union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('l', ctypes.c_uint32, 1), + ('reserved_0', ctypes.c_uint32, 8), + ('operation', ctypes.c_uint32, 7), +] + +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_3_0._fields_ = [ + ('src_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_4_0._fields_ = [ + ('src_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_5_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_5_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_5_0._fields_ = [ + ('cmp_data_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_5_0), + ('DW_5_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_6_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_6_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_6_0._fields_ = [ + ('cmp_data_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_6_0), + ('DW_6_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION(Union): + pass + +class struct_SDMA_PKT_ATOMIC_TAG_7_0(Structure): + pass + +struct_SDMA_PKT_ATOMIC_TAG_7_0._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG_7_0._fields_ = [ + ('loop_interval', ctypes.c_uint32, 13), + ('reserved_0', ctypes.c_uint32, 19), +] + +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._pack_ = 1 # source:False +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_ATOMIC_TAG_7_0), + ('DW_7_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_ATOMIC_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_ATOMIC_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION), + ('SRC_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION), + ('SRC_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION), + ('CMP_DATA_LO_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION), + ('CMP_DATA_HI_UNION', union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION), + ('LOOP_UNION', union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION), +] + +SDMA_PKT_ATOMIC = struct_SDMA_PKT_ATOMIC_TAG +class struct_SDMA_PKT_TIMESTAMP_TAG(Structure): + pass + +class union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_1_0._fields_ = [ + ('addr_31_0', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION(Union): + pass + +class struct_SDMA_PKT_TIMESTAMP_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG_2_0._fields_ = [ + ('addr_63_32', ctypes.c_uint32, 32), +] + +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TIMESTAMP_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TIMESTAMP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TIMESTAMP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION), + ('ADDR_LO_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION), + ('ADDR_HI_UNION', union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION), +] + +SDMA_PKT_TIMESTAMP = struct_SDMA_PKT_TIMESTAMP_TAG +class struct_SDMA_PKT_TRAP_TAG(Structure): + pass + +class union_SDMA_PKT_TRAP_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('reserved_0', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION(Union): + pass + +class struct_SDMA_PKT_TRAP_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_TRAP_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG_1_0._fields_ = [ + ('int_ctx', ctypes.c_uint32, 28), + ('reserved_1', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._pack_ = 1 # source:False +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_TRAP_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_TRAP_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_TRAP_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_TRAP_TAG_HEADER_UNION), + ('INT_CONTEXT_UNION', union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION), +] + +SDMA_PKT_TRAP = struct_SDMA_PKT_TRAP_TAG +class struct_SDMA_PKT_HDP_FLUSH_TAG(Structure): + pass + +struct_SDMA_PKT_HDP_FLUSH_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_HDP_FLUSH_TAG._fields_ = [ + ('DW_0_DATA', ctypes.c_uint32), + ('DW_1_DATA', ctypes.c_uint32), + ('DW_2_DATA', ctypes.c_uint32), + ('DW_3_DATA', ctypes.c_uint32), + ('DW_4_DATA', ctypes.c_uint32), + ('DW_5_DATA', ctypes.c_uint32), +] + +SDMA_PKT_HDP_FLUSH = struct_SDMA_PKT_HDP_FLUSH_TAG +hdp_flush_cmd = struct_SDMA_PKT_HDP_FLUSH_TAG # Variable struct_SDMA_PKT_HDP_FLUSH_TAG +class struct_SDMA_PKT_GCR_TAG(Structure): + pass + +class union_SDMA_PKT_GCR_TAG_HEADER_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_0_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_0_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_0_0._fields_ = [ + ('op', ctypes.c_uint32, 8), + ('sub_op', ctypes.c_uint32, 8), + ('_2', ctypes.c_uint32, 16), +] + +union_SDMA_PKT_GCR_TAG_HEADER_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_HEADER_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_HEADER_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_0_0), + ('DW_0_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD1_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_1_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_1_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_1_0._fields_ = [ + ('_0', ctypes.c_uint32, 7), + ('BaseVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD1_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD1_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD1_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_1_0), + ('DW_1_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD2_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_2_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_2_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_2_0._fields_ = [ + ('BaseVA_HI', ctypes.c_uint32, 16), + ('GCR_CONTROL_GLI_INV', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL1_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GLM_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLM_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_WB', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLK_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GLV_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL1_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_US', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_RANGE', ctypes.c_uint32, 2), + ('GCR_CONTROL_GL2_DISCARD', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_INV', ctypes.c_uint32, 1), + ('GCR_CONTROL_GL2_WB', ctypes.c_uint32, 1), +] + +union_SDMA_PKT_GCR_TAG_WORD2_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD2_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD2_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_2_0), + ('DW_2_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD3_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_3_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_3_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_3_0._fields_ = [ + ('GCR_CONTROL_RANGE_IS_PA', ctypes.c_uint32, 1), + ('GCR_CONTROL_SEQ', ctypes.c_uint32, 2), + ('_2', ctypes.c_uint32, 4), + ('LimitVA_LO', ctypes.c_uint32, 25), +] + +union_SDMA_PKT_GCR_TAG_WORD3_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD3_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD3_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_3_0), + ('DW_3_DATA', ctypes.c_uint32), +] + +class union_SDMA_PKT_GCR_TAG_WORD4_UNION(Union): + pass + +class struct_SDMA_PKT_GCR_TAG_4_0(Structure): + pass + +struct_SDMA_PKT_GCR_TAG_4_0._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG_4_0._fields_ = [ + ('LimitVA_HI', ctypes.c_uint32, 16), + ('_1', ctypes.c_uint32, 8), + ('VMID', ctypes.c_uint32, 4), + ('_3', ctypes.c_uint32, 4), +] + +union_SDMA_PKT_GCR_TAG_WORD4_UNION._pack_ = 1 # source:False +union_SDMA_PKT_GCR_TAG_WORD4_UNION._anonymous_ = ('_0',) +union_SDMA_PKT_GCR_TAG_WORD4_UNION._fields_ = [ + ('_0', struct_SDMA_PKT_GCR_TAG_4_0), + ('DW_4_DATA', ctypes.c_uint32), +] + +struct_SDMA_PKT_GCR_TAG._pack_ = 1 # source:False +struct_SDMA_PKT_GCR_TAG._fields_ = [ + ('HEADER_UNION', union_SDMA_PKT_GCR_TAG_HEADER_UNION), + ('WORD1_UNION', union_SDMA_PKT_GCR_TAG_WORD1_UNION), + ('WORD2_UNION', union_SDMA_PKT_GCR_TAG_WORD2_UNION), + ('WORD3_UNION', union_SDMA_PKT_GCR_TAG_WORD3_UNION), + ('WORD4_UNION', union_SDMA_PKT_GCR_TAG_WORD4_UNION), +] + +SDMA_PKT_GCR = struct_SDMA_PKT_GCR_TAG +__SDMA_V6_0_0_PKT_OPEN_H_ = True # macro +SDMA_OP_NOP = 0 # macro +SDMA_OP_WRITE = 2 # macro +SDMA_OP_INDIRECT = 4 # macro +SDMA_OP_SEM = 7 # macro +SDMA_OP_COND_EXE = 9 # macro +SDMA_OP_PTEPDE = 12 # macro +SDMA_OP_SRBM_WRITE = 14 # macro +SDMA_OP_PRE_EXE = 15 # macro +SDMA_OP_GPUVM_INV = 16 # macro +SDMA_OP_GCR_REQ = 17 # macro +SDMA_OP_DUMMY_TRAP = 32 # macro +SDMA_SUBOP_TIMESTAMP_SET = 0 # macro +SDMA_SUBOP_TIMESTAMP_GET = 1 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND = 4 # macro +SDMA_SUBOP_COPY_TILED = 1 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND = 5 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND = 6 # macro +SDMA_SUBOP_COPY_SOA = 3 # macro +SDMA_SUBOP_COPY_DIRTY_PAGE = 7 # macro +SDMA_SUBOP_COPY_LINEAR_PHY = 8 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND_LARGE = 36 # macro +SDMA_SUBOP_COPY_LINEAR_BC = 16 # macro +SDMA_SUBOP_COPY_TILED_BC = 17 # macro +SDMA_SUBOP_COPY_LINEAR_SUB_WIND_BC = 20 # macro +SDMA_SUBOP_COPY_TILED_SUB_WIND_BC = 21 # macro +SDMA_SUBOP_COPY_T2T_SUB_WIND_BC = 22 # macro +SDMA_SUBOP_WRITE_LINEAR = 0 # macro +SDMA_SUBOP_WRITE_TILED = 1 # macro +SDMA_SUBOP_WRITE_TILED_BC = 17 # macro +SDMA_SUBOP_PTEPDE_GEN = 0 # macro +SDMA_SUBOP_PTEPDE_COPY = 1 # macro +SDMA_SUBOP_PTEPDE_RMW = 2 # macro +SDMA_SUBOP_PTEPDE_COPY_BACKWARDS = 3 # macro +SDMA_SUBOP_MEM_INCR = 1 # macro +SDMA_SUBOP_DATA_FILL_MULTI = 1 # macro +SDMA_SUBOP_POLL_REG_WRITE_MEM = 1 # macro +SDMA_SUBOP_POLL_DBIT_WRITE_MEM = 2 # macro +SDMA_SUBOP_POLL_MEM_VERIFY = 3 # macro +SDMA_SUBOP_VM_INVALIDATION = 4 # macro +HEADER_AGENT_DISPATCH = 4 # macro +HEADER_BARRIER = 5 # macro +SDMA_OP_AQL_COPY = 0 # macro +SDMA_OP_AQL_BARRIER_OR = 0 # macro +SDMA_GCR_RANGE_IS_PA = (1<<18) # macro +def SDMA_GCR_SEQ(x): # macro + return (((x)&0x3)<<16) +SDMA_GCR_GL2_WB = (1<<15) # macro +SDMA_GCR_GL2_INV = (1<<14) # macro +SDMA_GCR_GL2_DISCARD = (1<<13) # macro +def SDMA_GCR_GL2_RANGE(x): # macro + return (((x)&0x3)<<11) +SDMA_GCR_GL2_US = (1<<10) # macro +SDMA_GCR_GL1_INV = (1<<9) # macro +SDMA_GCR_GLV_INV = (1<<8) # macro +SDMA_GCR_GLK_INV = (1<<7) # macro +SDMA_GCR_GLK_WB = (1<<6) # macro +SDMA_GCR_GLM_INV = (1<<5) # macro +SDMA_GCR_GLM_WB = (1<<4) # macro +def SDMA_GCR_GL1_RANGE(x): # macro + return (((x)&0x3)<<2) +def SDMA_GCR_GLI_INV(x): # macro + return (((x)&0x3)<<0) +SDMA_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_LINEAR_HEADER_backwards_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_backwards_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_backwards_shift = 25 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BACKWARDS(x): # macro + return (((x)&0x00000001)<<25) +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_mask = 0x3FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x3FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_DST_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_LINEAR_PARAMETER_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_shift = 19 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_DST_HA(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_BC_PARAMETER_SRC_HA(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset = 0 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_HEADER_ALL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_shift = 3 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_MTYPE(x): # macro + return (((x)&0x00000007)<<3) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_shift = 6 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_L2_POLICY(x): # macro + return (((x)&0x00000003)<<6) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_shift = 8 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_LLC(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_shift = 11 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_MTYPE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_shift = 14 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_L2_POLICY(x): # macro + return (((x)&0x00000003)<<14) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_shift = 16 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_LLC(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift = 17 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<17) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_offset = 1 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_mask = 0x000000FF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_shift = 24 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_ADDR_PAIR_NUM(x): # macro + return (((x)&0x000000FF)<<24) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_shift = 3 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_MTYPE(x): # macro + return (((x)&0x00000007)<<3) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_shift = 6 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_L2_POLICY(x): # macro + return (((x)&0x00000003)<<6) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_shift = 8 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_LLC(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_mask = 0x00000007 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_shift = 11 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_MTYPE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_shift = 14 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_L2_POLICY(x): # macro + return (((x)&0x00000003)<<14) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_shift = 16 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_LLC(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift = 17 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<17) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift = 19 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift = 20 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift = 21 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_LOG(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift = 22 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_SNOOP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift = 23 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_DST_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift = 27 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GCC(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift = 28 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SYS(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift = 30 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_SNOOP(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset = 2 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask = 0x00000001 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift = 31 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_SRC_GPA(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset = 1 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask = 0x3FFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x3FFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_shift = 10 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST2_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<10) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift = 16 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST1_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_DST1_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_offset = 2 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 3 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 4 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset = 5 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_DST1_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset = 6 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_DST1_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_DST2_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_DST2_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_SRC_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_DST_PITCH(x): # macro + return (((x)&0x0007FFFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_DST_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_SRC_X(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_SRC_Y(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_SRC_Z(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_SRC_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_SRC_SLICE_PITCH_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_SRC_SLICE_PITCH_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_DST_X(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_DST_Y(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_offset = 13 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_DST_Z(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_offset = 14 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_DST_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_offset = 15 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_DST_SLICE_PITCH_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_offset = 16 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_DST_SLICE_PITCH_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_offset = 16 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_offset = 16 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_shift = 18 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_DST_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_offset = 16 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_offset = 16 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_shift = 26 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_SRC_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_offset = 17 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_RECT_X(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_offset = 18 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_RECT_Y(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_offset = 19 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_RECT_Z(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_offset = 0 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_mask = 0x00000007 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_shift = 29 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_ELEMENTSIZE(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_offset = 4 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_SRC_PITCH(x): # macro + return (((x)&0x00003FFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_offset = 5 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_SRC_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_offset = 8 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_offset = 9 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_shift = 13 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_DST_PITCH(x): # macro + return (((x)&0x00003FFF)<<13) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_offset = 10 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_DST_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_offset = 11 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_shift = 19 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_DST_HA(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_offset = 12 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_mask = 0x00000001 # macro +SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_shift = 27 # macro +def SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_SRC_HA(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_TILED_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_TILED_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_DW_4_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_DW_5_mip_max_offset = 5 # macro +SDMA_PKT_COPY_TILED_DW_5_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_DW_5_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_5_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_DW_7_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_TILED_DW_7_LINEAR_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_offset = 7 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_TILED_DW_7_TILE_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_COUNT_count_offset = 12 # macro +SDMA_PKT_COPY_TILED_COUNT_count_mask = 0x3FFFFFFF # macro +SDMA_PKT_COPY_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_TILED_COUNT_COUNT(x): # macro + return (((x)&0x3FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_BC_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_BC_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_BC_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_3_width_offset = 3 # macro +SDMA_PKT_COPY_TILED_BC_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_3_width_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_4_height_offset = 4 # macro +SDMA_PKT_COPY_TILED_BC_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_4_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_4_depth_offset = 4 # macro +SDMA_PKT_COPY_TILED_BC_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_BC_DW_4_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_offset = 5 # macro +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_TILED_BC_DW_5_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_TILED_BC_DW_6_x_offset = 6 # macro +SDMA_PKT_COPY_TILED_BC_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_6_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_6_y_offset = 6 # macro +SDMA_PKT_COPY_TILED_BC_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_BC_DW_6_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_BC_DW_7_z_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_BC_DW_7_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_offset = 7 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_BC_DW_7_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset = 8 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset = 9 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_BC_COUNT_count_offset = 12 # macro +SDMA_PKT_COPY_TILED_BC_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_COPY_TILED_BC_COUNT_count_shift = 2 # macro +def SDMA_PKT_COPY_TILED_BC_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<2) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_shift = 19 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift = 26 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_VIDEOCOPY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset = 0 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask = 0x00000001 # macro +SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift = 27 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_HEADER_BROADCAST(x): # macro + return (((x)&0x00000001)<<27) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset = 1 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_TILED_ADDR0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset = 2 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_TILED_ADDR0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset = 3 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_TILED_ADDR1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset = 4 # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_TILED_ADDR1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset = 5 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_5_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset = 6 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_6_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift = 9 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_offset = 7 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_7_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset = 8 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_8_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset = 9 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_9_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift = 8 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_DST2_SW(x): # macro + return (((x)&0x00000003)<<8) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_shift = 10 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_DST2_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<10) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_LINEAR_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_offset = 10 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_DW_10_TILE_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset = 11 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset = 12 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset = 13 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask = 0x0007FFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_LINEAR_PITCH(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset = 14 # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset = 15 # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask = 0x3FFFFFFF # macro +SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_L2T_BROADCAST_COUNT_COUNT(x): # macro + return (((x)&0x3FFFFFFF)<<0) +SDMA_PKT_COPY_T2T_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_T2T_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_T2T_HEADER_dcc_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_shift = 19 # macro +def SDMA_PKT_COPY_T2T_HEADER_DCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_T2T_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_COPY_T2T_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_offset = 0 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_HEADER_dcc_dir_shift = 31 # macro +def SDMA_PKT_COPY_T2T_HEADER_DCC_DIR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_offset = 6 # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_6_src_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_T2T_DW_6_SRC_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_11_DST_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift = 9 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_offset = 12 # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_T2T_DW_12_DST_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_T2T_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_T2T_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_DW_14_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_T2T_DW_14_DST_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_T2T_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_offset = 14 # macro +SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_T2T_DW_14_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_offset = 15 # macro +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_ADDR_LO_META_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_offset = 16 # macro +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_ADDR_HI_META_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_mask = 0x0000007F # macro +SDMA_PKT_COPY_T2T_META_CONFIG_data_format_shift = 0 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_DATA_FORMAT(x): # macro + return (((x)&0x0000007F)<<0) +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_shift = 7 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_COLOR_TRANSFORM_DISABLE(x): # macro + return (((x)&0x00000001)<<7) +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_shift = 8 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_ALPHA_IS_ON_MSB(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_number_type_shift = 9 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_NUMBER_TYPE(x): # macro + return (((x)&0x00000007)<<9) +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_shift = 12 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_SURFACE_TYPE(x): # macro + return (((x)&0x00000003)<<12) +SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_shift = 14 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_META_LLC(x): # macro + return (((x)&0x00000001)<<14) +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_shift = 24 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_MAX_COMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_shift = 26 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_MAX_UNCOMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<26) +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_shift = 28 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_WRITE_COMPRESS_ENABLE(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_shift = 29 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_META_TMZ(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_offset = 17 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_mask = 0x00000001 # macro +SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_shift = 31 # macro +def SDMA_PKT_COPY_T2T_META_CONFIG_PIPE_ALIGNED(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_T2T_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_offset = 3 # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_3_SRC_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_offset = 3 # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_3_src_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_3_SRC_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_offset = 4 # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_4_SRC_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_offset = 4 # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_4_src_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_4_SRC_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_offset = 5 # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_5_SRC_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_offset = 5 # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_5_SRC_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_offset = 6 # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_T2T_BC_DW_6_SRC_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_offset = 9 # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_9_DST_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_offset = 9 # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_9_DST_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_offset = 10 # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_10_DST_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_offset = 10 # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_10_DST_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_offset = 11 # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_11_DST_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_offset = 11 # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_mask = 0x00000FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_11_DST_DEPTH(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_offset = 12 # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_T2T_BC_DW_12_DST_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_offset = 13 # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_13_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_offset = 13 # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_13_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_shift = 16 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_offset = 14 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_shift = 24 # macro +def SDMA_PKT_COPY_T2T_BC_DW_14_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_shift = 19 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_TILED_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_5_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_shift = 20 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_6_MIP_ID(x): # macro + return (((x)&0x0000000F)<<20) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask = 0x00001FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_RECT_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_LINEAR_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_DW_13_TILE_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_offset = 14 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_META_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_offset = 15 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_META_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_mask = 0x0000007F # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_DATA_FORMAT(x): # macro + return (((x)&0x0000007F)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_shift = 7 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_COLOR_TRANSFORM_DISABLE(x): # macro + return (((x)&0x00000001)<<7) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_ALPHA_IS_ON_MSB(x): # macro + return (((x)&0x00000001)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_shift = 9 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_NUMBER_TYPE(x): # macro + return (((x)&0x00000007)<<9) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_shift = 12 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_SURFACE_TYPE(x): # macro + return (((x)&0x00000003)<<12) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_shift = 14 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_META_LLC(x): # macro + return (((x)&0x00000001)<<14) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_MAX_COMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_shift = 26 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_MAX_UNCOMP_BLOCK_SIZE(x): # macro + return (((x)&0x00000003)<<26) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_shift = 28 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_WRITE_COMPRESS_ENABLE(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_shift = 29 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_META_TMZ(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_offset = 16 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_PIPE_ALIGNED(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_TILED_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_TILED_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_TILED_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_offset = 3 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_TILED_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_TILED_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_offset = 4 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_WIDTH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_offset = 5 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_mask = 0x0000000F # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_shift = 3 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_shift = 8 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_shift = 11 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_shift = 15 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_shift = 18 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_shift = 21 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_offset = 6 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_shift = 26 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset = 7 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset = 8 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_LINEAR_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_offset = 9 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_LINEAR_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_LINEAR_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_offset = 10 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_LINEAR_PITCH(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_offset = 11 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_mask = 0x0FFFFFFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_LINEAR_SLICE_PITCH(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_RECT_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_offset = 12 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_mask = 0x00003FFF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_RECT_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_mask = 0x000007FF # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_shift = 0 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_RECT_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_offset = 13 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_shift = 24 # macro +def SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_TILE_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_HEADER_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_op_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_COPY_STRUCT_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COPY_STRUCT_HEADER_detile_offset = 0 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_mask = 0x00000001 # macro +SDMA_PKT_COPY_STRUCT_HEADER_detile_shift = 31 # macro +def SDMA_PKT_COPY_STRUCT_HEADER_DETILE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset = 1 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_SB_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset = 2 # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_SB_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset = 3 # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_START_INDEX_START_INDEX(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_COUNT_count_offset = 4 # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_COUNT_count_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_COUNT_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_stride_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_mask = 0x000007FF # macro +SDMA_PKT_COPY_STRUCT_DW_5_stride_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRIDE(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift = 16 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_LINEAR_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_shift = 18 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_LINEAR_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask = 0x00000003 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift = 24 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRUCT_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_offset = 5 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_shift = 26 # macro +def SDMA_PKT_COPY_STRUCT_DW_5_STRUCT_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset = 6 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_LINEAR_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset = 7 # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift = 0 # macro +def SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_LINEAR_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_UNTILED_HEADER_cpv_offset = 0 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_WRITE_UNTILED_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_WRITE_UNTILED_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_count_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_UNTILED_DW_3_count_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift = 24 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_offset = 3 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_shift = 26 # macro +def SDMA_PKT_WRITE_UNTILED_DW_3_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset = 4 # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_UNTILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_HEADER_ENCRYPT(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_WRITE_TILED_HEADER_tmz_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_WRITE_TILED_HEADER_cpv_offset = 0 # macro +SDMA_PKT_WRITE_TILED_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_WRITE_TILED_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_WRITE_TILED_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_mask = 0x00001FFF # macro +SDMA_PKT_WRITE_TILED_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_4_DEPTH(x): # macro + return (((x)&0x00001FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_DW_5_SWIZZLE_MODE(x): # macro + return (((x)&0x0000001F)<<3) +SDMA_PKT_WRITE_TILED_DW_5_dimension_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_5_dimension_shift = 9 # macro +def SDMA_PKT_WRITE_TILED_DW_5_DIMENSION(x): # macro + return (((x)&0x00000003)<<9) +SDMA_PKT_WRITE_TILED_DW_5_mip_max_offset = 5 # macro +SDMA_PKT_WRITE_TILED_DW_5_mip_max_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_DW_5_mip_max_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_5_MIP_MAX(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_WRITE_TILED_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_z_mask = 0x00001FFF # macro +SDMA_PKT_WRITE_TILED_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DW_7_Z(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_WRITE_TILED_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_DW_7_cache_policy_offset = 7 # macro +SDMA_PKT_WRITE_TILED_DW_7_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_DW_7_cache_policy_shift = 26 # macro +def SDMA_PKT_WRITE_TILED_DW_7_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_PKT_WRITE_TILED_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_WRITE_TILED_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_BC_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_3_width_offset = 3 # macro +SDMA_PKT_WRITE_TILED_BC_DW_3_width_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_3_width_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_3_WIDTH(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_4_height_offset = 4 # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_height_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_height_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_4_HEIGHT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_offset = 4 # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_BC_DW_4_depth_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_4_DEPTH(x): # macro + return (((x)&0x000007FF)<<16) +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_ELEMENT_SIZE(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_mask = 0x0000000F # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_shift = 3 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_ARRAY_MODE(x): # macro + return (((x)&0x0000000F)<<3) +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_shift = 8 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_MIT_MODE(x): # macro + return (((x)&0x00000007)<<8) +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_mask = 0x00000007 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_shift = 11 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_TILESPLIT_SIZE(x): # macro + return (((x)&0x00000007)<<11) +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_shift = 15 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_BANK_W(x): # macro + return (((x)&0x00000003)<<15) +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_shift = 18 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_BANK_H(x): # macro + return (((x)&0x00000003)<<18) +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_shift = 21 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_NUM_BANK(x): # macro + return (((x)&0x00000003)<<21) +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_MAT_ASPT(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_offset = 5 # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_mask = 0x0000001F # macro +SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_shift = 26 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_5_PIPE_CONFIG(x): # macro + return (((x)&0x0000001F)<<26) +SDMA_PKT_WRITE_TILED_BC_DW_6_x_offset = 6 # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_x_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_x_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_6_X(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_6_y_offset = 6 # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_y_mask = 0x00003FFF # macro +SDMA_PKT_WRITE_TILED_BC_DW_6_y_shift = 16 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_6_Y(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_WRITE_TILED_BC_DW_7_z_offset = 7 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_z_mask = 0x000007FF # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_z_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_7_Z(x): # macro + return (((x)&0x000007FF)<<0) +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_offset = 7 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_mask = 0x00000003 # macro +SDMA_PKT_WRITE_TILED_BC_DW_7_sw_shift = 24 # macro +def SDMA_PKT_WRITE_TILED_BC_DW_7_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_WRITE_TILED_BC_COUNT_count_offset = 8 # macro +SDMA_PKT_WRITE_TILED_BC_COUNT_count_mask = 0x000FFFFF # macro +SDMA_PKT_WRITE_TILED_BC_COUNT_count_shift = 2 # macro +def SDMA_PKT_WRITE_TILED_BC_COUNT_COUNT(x): # macro + return (((x)&0x000FFFFF)<<2) +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_offset = 9 # macro +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_TILED_BC_DATA0_data0_shift = 0 # macro +def SDMA_PKT_WRITE_TILED_BC_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_PTEPDE_COPY_HEADER_cpv_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_COUNT_count_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_PTEPDE_COPY_COUNT_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_shift = 22 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_DST_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<22) +SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_offset = 7 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_shift = 29 # macro +def SDMA_PKT_PTEPDE_COPY_COUNT_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<29) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift = 28 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTE_SIZE(x): # macro + return (((x)&0x00000003)<<28) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift = 30 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_DIRECTION(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset = 0 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift = 31 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_PTEPDE_OP(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_FIRST_XFER(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset = 5 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift = 8 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_MASK_LAST_XFER(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset = 6 # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask = 0x0001FFFF # macro +SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift = 0 # macro +def SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_COUNT(x): # macro + return (((x)&0x0001FFFF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_op_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_mask = 0x00000007 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_mtype_shift = 16 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_MTYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift = 20 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift = 22 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_shift = 26 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_LLC_POLICY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_PTEPDE_RMW_HEADER_cpv_offset = 0 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_PTEPDE_RMW_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_PTEPDE_RMW_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset = 3 # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_LO_MASK_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset = 4 # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_MASK_HI_MASK_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset = 5 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_LO_VALUE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset = 6 # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_VALUE_HI_VALUE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_offset = 7 # macro +SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_mask = 0xFFFFFFFF # macro +SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_shift = 0 # macro +def SDMA_PKT_PTEPDE_RMW_COUNT_NUM_OF_PTE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_REGISTER_RMW_HEADER_op_offset = 0 # macro +SDMA_PKT_REGISTER_RMW_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_REGISTER_RMW_HEADER_op_shift = 0 # macro +def SDMA_PKT_REGISTER_RMW_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_REGISTER_RMW_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_REGISTER_RMW_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_REGISTER_RMW_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_REGISTER_RMW_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_REGISTER_RMW_ADDR_addr_offset = 1 # macro +SDMA_PKT_REGISTER_RMW_ADDR_addr_mask = 0x000FFFFF # macro +SDMA_PKT_REGISTER_RMW_ADDR_addr_shift = 0 # macro +def SDMA_PKT_REGISTER_RMW_ADDR_ADDR(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_offset = 1 # macro +SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_mask = 0x00000FFF # macro +SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_shift = 20 # macro +def SDMA_PKT_REGISTER_RMW_ADDR_APERTURE_ID(x): # macro + return (((x)&0x00000FFF)<<20) +SDMA_PKT_REGISTER_RMW_MASK_mask_offset = 2 # macro +SDMA_PKT_REGISTER_RMW_MASK_mask_mask = 0xFFFFFFFF # macro +SDMA_PKT_REGISTER_RMW_MASK_mask_shift = 0 # macro +def SDMA_PKT_REGISTER_RMW_MASK_MASK(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_REGISTER_RMW_VALUE_value_offset = 3 # macro +SDMA_PKT_REGISTER_RMW_VALUE_value_mask = 0xFFFFFFFF # macro +SDMA_PKT_REGISTER_RMW_VALUE_value_shift = 0 # macro +def SDMA_PKT_REGISTER_RMW_VALUE_VALUE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_REGISTER_RMW_MISC_stride_offset = 4 # macro +SDMA_PKT_REGISTER_RMW_MISC_stride_mask = 0x000FFFFF # macro +SDMA_PKT_REGISTER_RMW_MISC_stride_shift = 0 # macro +def SDMA_PKT_REGISTER_RMW_MISC_STRIDE(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_offset = 4 # macro +SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_mask = 0x00000FFF # macro +SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_shift = 20 # macro +def SDMA_PKT_REGISTER_RMW_MISC_NUM_OF_REG(x): # macro + return (((x)&0x00000FFF)<<20) +SDMA_PKT_WRITE_INCR_HEADER_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_op_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_WRITE_INCR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_WRITE_INCR_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_WRITE_INCR_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_WRITE_INCR_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_WRITE_INCR_HEADER_cpv_offset = 0 # macro +SDMA_PKT_WRITE_INCR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_WRITE_INCR_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_WRITE_INCR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset = 3 # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW0_MASK_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset = 4 # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_MASK_DW1_MASK_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset = 5 # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW0_INIT_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset = 6 # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INIT_DW1_INIT_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset = 7 # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW0_INCR_DW0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset = 8 # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask = 0xFFFFFFFF # macro +SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_INCR_DW1_INCR_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_WRITE_INCR_COUNT_count_offset = 9 # macro +SDMA_PKT_WRITE_INCR_COUNT_count_mask = 0x0007FFFF # macro +SDMA_PKT_WRITE_INCR_COUNT_count_shift = 0 # macro +def SDMA_PKT_WRITE_INCR_COUNT_COUNT(x): # macro + return (((x)&0x0007FFFF)<<0) +SDMA_PKT_INDIRECT_HEADER_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_op_shift = 0 # macro +def SDMA_PKT_INDIRECT_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_INDIRECT_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_INDIRECT_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_INDIRECT_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_INDIRECT_HEADER_vmid_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_vmid_mask = 0x0000000F # macro +SDMA_PKT_INDIRECT_HEADER_vmid_shift = 16 # macro +def SDMA_PKT_INDIRECT_HEADER_VMID(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_PKT_INDIRECT_HEADER_priv_offset = 0 # macro +SDMA_PKT_INDIRECT_HEADER_priv_mask = 0x00000001 # macro +SDMA_PKT_INDIRECT_HEADER_priv_shift = 31 # macro +def SDMA_PKT_INDIRECT_HEADER_PRIV(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset = 1 # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_LO_IB_BASE_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset = 2 # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_BASE_HI_IB_BASE_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset = 3 # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask = 0x000FFFFF # macro +SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift = 0 # macro +def SDMA_PKT_INDIRECT_IB_SIZE_IB_SIZE(x): # macro + return (((x)&0x000FFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset = 4 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_LO_CSA_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset = 5 # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift = 0 # macro +def SDMA_PKT_INDIRECT_CSA_ADDR_HI_CSA_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SEMAPHORE_HEADER_write_one_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_write_one_shift = 29 # macro +def SDMA_PKT_SEMAPHORE_HEADER_WRITE_ONE(x): # macro + return (((x)&0x00000001)<<29) +SDMA_PKT_SEMAPHORE_HEADER_signal_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_signal_shift = 30 # macro +def SDMA_PKT_SEMAPHORE_HEADER_SIGNAL(x): # macro + return (((x)&0x00000001)<<30) +SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset = 0 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask = 0x00000001 # macro +SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift = 31 # macro +def SDMA_PKT_SEMAPHORE_HEADER_MAILBOX(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_SEMAPHORE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_MEM_INCR_HEADER_op_offset = 0 # macro +SDMA_PKT_MEM_INCR_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_MEM_INCR_HEADER_op_shift = 0 # macro +def SDMA_PKT_MEM_INCR_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_MEM_INCR_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_MEM_INCR_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_MEM_INCR_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_MEM_INCR_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_MEM_INCR_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_MEM_INCR_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_MEM_INCR_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_MEM_INCR_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_MEM_INCR_HEADER_llc_policy_offset = 0 # macro +SDMA_PKT_MEM_INCR_HEADER_llc_policy_mask = 0x00000001 # macro +SDMA_PKT_MEM_INCR_HEADER_llc_policy_shift = 26 # macro +def SDMA_PKT_MEM_INCR_HEADER_LLC_POLICY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_MEM_INCR_HEADER_cpv_offset = 0 # macro +SDMA_PKT_MEM_INCR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_MEM_INCR_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_MEM_INCR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_MEM_INCR_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_MEM_INCR_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_HEADER_op_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_VM_INVALIDATION_HEADER_op_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_shift = 16 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_GFX_ENG_ID(x): # macro + return (((x)&0x0000001F)<<16) +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_offset = 0 # macro +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_shift = 24 # macro +def SDMA_PKT_VM_INVALIDATION_HEADER_MM_ENG_ID(x): # macro + return (((x)&0x0000001F)<<24) +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_offset = 1 # macro +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_mask = 0xFFFFFFFF # macro +SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_INVALIDATEREQ(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_offset = 2 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_mask = 0xFFFFFFFF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_ADDRESSRANGELO(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_mask = 0x0000FFFF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_shift = 0 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_INVALIDATEACK(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_mask = 0x0000001F # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_shift = 16 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_ADDRESSRANGEHI(x): # macro + return (((x)&0x0000001F)<<16) +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_offset = 3 # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_mask = 0x000001FF # macro +SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_shift = 23 # macro +def SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_RESERVED(x): # macro + return (((x)&0x000001FF)<<23) +SDMA_PKT_FENCE_HEADER_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_op_shift = 0 # macro +def SDMA_PKT_FENCE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_FENCE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_FENCE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_FENCE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_FENCE_HEADER_mtype_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_mtype_mask = 0x00000007 # macro +SDMA_PKT_FENCE_HEADER_mtype_shift = 16 # macro +def SDMA_PKT_FENCE_HEADER_MTYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_FENCE_HEADER_gcc_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_gcc_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_gcc_shift = 19 # macro +def SDMA_PKT_FENCE_HEADER_GCC(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_FENCE_HEADER_sys_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_sys_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_sys_shift = 20 # macro +def SDMA_PKT_FENCE_HEADER_SYS(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_FENCE_HEADER_snp_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_snp_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_snp_shift = 22 # macro +def SDMA_PKT_FENCE_HEADER_SNP(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_FENCE_HEADER_gpa_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_gpa_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_gpa_shift = 23 # macro +def SDMA_PKT_FENCE_HEADER_GPA(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_FENCE_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_FENCE_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_FENCE_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_FENCE_HEADER_llc_policy_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_llc_policy_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_llc_policy_shift = 26 # macro +def SDMA_PKT_FENCE_HEADER_LLC_POLICY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_FENCE_HEADER_cpv_offset = 0 # macro +SDMA_PKT_FENCE_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_FENCE_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_FENCE_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_FENCE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_FENCE_DATA_data_offset = 3 # macro +SDMA_PKT_FENCE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_FENCE_DATA_data_shift = 0 # macro +def SDMA_PKT_FENCE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_op_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset = 0 # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask = 0x0000000F # macro +SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift = 28 # macro +def SDMA_PKT_SRBM_WRITE_HEADER_BYTE_EN(x): # macro + return (((x)&0x0000000F)<<28) +SDMA_PKT_SRBM_WRITE_ADDR_addr_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_mask = 0x0003FFFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_addr_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_ADDR(x): # macro + return (((x)&0x0003FFFF)<<0) +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_offset = 1 # macro +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_mask = 0x00000FFF # macro +SDMA_PKT_SRBM_WRITE_ADDR_apertureid_shift = 20 # macro +def SDMA_PKT_SRBM_WRITE_ADDR_APERTUREID(x): # macro + return (((x)&0x00000FFF)<<20) +SDMA_PKT_SRBM_WRITE_DATA_data_offset = 2 # macro +SDMA_PKT_SRBM_WRITE_DATA_data_mask = 0xFFFFFFFF # macro +SDMA_PKT_SRBM_WRITE_DATA_data_shift = 0 # macro +def SDMA_PKT_SRBM_WRITE_DATA_DATA(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_PRE_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_PRE_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_PRE_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_PRE_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset = 0 # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask = 0x000000FF # macro +SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift = 16 # macro +def SDMA_PKT_PRE_EXE_HEADER_DEV_SEL(x): # macro + return (((x)&0x000000FF)<<16) +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset = 1 # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_PRE_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_COND_EXE_HEADER_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_op_shift = 0 # macro +def SDMA_PKT_COND_EXE_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_COND_EXE_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_COND_EXE_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_COND_EXE_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_COND_EXE_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_COND_EXE_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_COND_EXE_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_COND_EXE_HEADER_cpv_offset = 0 # macro +SDMA_PKT_COND_EXE_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_COND_EXE_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_COND_EXE_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_COND_EXE_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_REFERENCE_reference_offset = 3 # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_mask = 0xFFFFFFFF # macro +SDMA_PKT_COND_EXE_REFERENCE_reference_shift = 0 # macro +def SDMA_PKT_COND_EXE_REFERENCE_REFERENCE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset = 4 # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask = 0x00003FFF # macro +SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift = 0 # macro +def SDMA_PKT_COND_EXE_EXEC_COUNT_EXEC_COUNT(x): # macro + return (((x)&0x00003FFF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_op_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift = 16 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_CONSTANT_FILL_HEADER_cpv_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset = 0 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask = 0x00000003 # macro +SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift = 30 # macro +def SDMA_PKT_CONSTANT_FILL_HEADER_FILLSIZE(x): # macro + return (((x)&0x00000003)<<30) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset = 1 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset = 2 # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset = 3 # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_DATA_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_CONSTANT_FILL_COUNT_count_offset = 4 # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_mask = 0x3FFFFFFF # macro +SDMA_PKT_CONSTANT_FILL_COUNT_count_shift = 0 # macro +def SDMA_PKT_CONSTANT_FILL_COUNT_COUNT(x): # macro + return (((x)&0x3FFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset = 0 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask = 0x00000001 # macro +SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift = 31 # macro +def SDMA_PKT_DATA_FILL_MULTI_HEADER_MEMLOG_CLR(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset = 1 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_BYTE_STRIDE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset = 2 # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_DMA_COUNT(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset = 3 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset = 4 # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset = 5 # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask = 0x03FFFFFF # macro +SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift = 0 # macro +def SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_COUNT(x): # macro + return (((x)&0x03FFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_shift = 20 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<20) +SDMA_PKT_POLL_REGMEM_HEADER_cpv_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_cpv_shift = 24 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<24) +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift = 26 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_HDP_FLUSH(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_POLL_REGMEM_HEADER_func_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_mask = 0x00000007 # macro +SDMA_PKT_POLL_REGMEM_HEADER_func_shift = 28 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_FUNC(x): # macro + return (((x)&0x00000007)<<28) +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset = 0 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask = 0x00000001 # macro +SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift = 31 # macro +def SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_VALUE_value_offset = 3 # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_VALUE_value_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_VALUE_VALUE(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_MASK_mask_offset = 4 # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REGMEM_MASK_mask_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_MASK_MASK(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_interval_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_mask = 0x0000FFFF # macro +SDMA_PKT_POLL_REGMEM_DW5_interval_shift = 0 # macro +def SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset = 5 # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask = 0x00000FFF # macro +SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift = 16 # macro +def SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(x): # macro + return (((x)&0x00000FFF)<<16) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_offset = 0 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset = 1 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask = 0x3FFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift = 2 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_ADDR_31_2(x): # macro + return (((x)&0x3FFFFFFF)<<2) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 2 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 3 # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask = 0x00000003 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift = 16 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_EA(x): # macro + return (((x)&0x00000003)<<16) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_offset = 0 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset = 3 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask = 0x0FFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift = 4 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_ADDR_31_4(x): # macro + return (((x)&0x0FFFFFFF)<<4) +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset = 4 # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift = 0 # macro +def SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_PAGE_NUM_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_shift = 24 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<24) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset = 0 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask = 0x00000001 # macro +SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift = 31 # macro +def SDMA_PKT_POLL_MEM_VERIFY_HEADER_MODE(x): # macro + return (((x)&0x00000001)<<31) +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset = 1 # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_PATTERN_PATTERN(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset = 2 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_CMP0_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset = 3 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_CMP0_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_offset = 4 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_CMP0_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_offset = 5 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_CMP0_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset = 6 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_CMP1_START_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset = 7 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_CMP1_START_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset = 8 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_CMP1_END_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset = 9 # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_CMP1_END_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset = 10 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_REC_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset = 11 # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_REC_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset = 12 # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask = 0xFFFFFFFF # macro +SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift = 0 # macro +def SDMA_PKT_POLL_MEM_VERIFY_RESERVED_RESERVED(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_HEADER_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_ATOMIC_HEADER_op_shift = 0 # macro +def SDMA_PKT_ATOMIC_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_ATOMIC_HEADER_loop_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_loop_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_loop_shift = 16 # macro +def SDMA_PKT_ATOMIC_HEADER_LOOP(x): # macro + return (((x)&0x00000001)<<16) +SDMA_PKT_ATOMIC_HEADER_tmz_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_tmz_shift = 18 # macro +def SDMA_PKT_ATOMIC_HEADER_TMZ(x): # macro + return (((x)&0x00000001)<<18) +SDMA_PKT_ATOMIC_HEADER_cache_policy_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_cache_policy_mask = 0x00000007 # macro +SDMA_PKT_ATOMIC_HEADER_cache_policy_shift = 20 # macro +def SDMA_PKT_ATOMIC_HEADER_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<20) +SDMA_PKT_ATOMIC_HEADER_cpv_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_ATOMIC_HEADER_cpv_shift = 24 # macro +def SDMA_PKT_ATOMIC_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<24) +SDMA_PKT_ATOMIC_HEADER_atomic_op_offset = 0 # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_mask = 0x0000007F # macro +SDMA_PKT_ATOMIC_HEADER_atomic_op_shift = 25 # macro +def SDMA_PKT_ATOMIC_HEADER_ATOMIC_OP(x): # macro + return (((x)&0x0000007F)<<25) +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset = 1 # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_LO_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset = 2 # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_ADDR_HI_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset = 3 # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_LO_SRC_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset = 4 # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_SRC_DATA_HI_SRC_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset = 5 # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_LO_CMP_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset = 6 # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift = 0 # macro +def SDMA_PKT_ATOMIC_CMP_DATA_HI_CMP_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset = 7 # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask = 0x00001FFF # macro +SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift = 0 # macro +def SDMA_PKT_ATOMIC_LOOP_INTERVAL_LOOP_INTERVAL(x): # macro + return (((x)&0x00001FFF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_SET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset = 1 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_INIT_DATA_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_INIT_DATA_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_mask = 0x00000001 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_shift = 26 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_LLC_POLICY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_TIMESTAMP_GET_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_mask = 0x00000003 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_shift = 24 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_L2_POLICY(x): # macro + return (((x)&0x00000003)<<24) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_mask = 0x00000001 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_shift = 26 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_LLC_POLICY(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_offset = 0 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_mask = 0x00000001 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_shift = 28 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset = 1 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask = 0x1FFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift = 3 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_WRITE_ADDR_31_3(x): # macro + return (((x)&0x1FFFFFFF)<<3) +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset = 2 # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift = 0 # macro +def SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_WRITE_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_PKT_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_op_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_DUMMY_TRAP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset = 1 # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask = 0x0FFFFFFF # macro +SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift = 0 # macro +def SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_INT_CONTEXT(x): # macro + return (((x)&0x0FFFFFFF)<<0) +SDMA_PKT_GPUVM_INV_HEADER_op_offset = 0 # macro +SDMA_PKT_GPUVM_INV_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_GPUVM_INV_HEADER_op_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_GPUVM_INV_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_GPUVM_INV_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_GPUVM_INV_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_GPUVM_INV_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_mask = 0x0000FFFF # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_PER_VMID_INV_REQ(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_mask = 0x00000007 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_shift = 16 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_FLUSH_TYPE(x): # macro + return (((x)&0x00000007)<<16) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_shift = 19 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PTES(x): # macro + return (((x)&0x00000001)<<19) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_shift = 20 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE0(x): # macro + return (((x)&0x00000001)<<20) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_shift = 21 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE1(x): # macro + return (((x)&0x00000001)<<21) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_shift = 22 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L2_PDE2(x): # macro + return (((x)&0x00000001)<<22) +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_shift = 23 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_L1_PTES(x): # macro + return (((x)&0x00000001)<<23) +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_shift = 24 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_CLR_PROTECTION_FAULT_STATUS_ADDR(x): # macro + return (((x)&0x00000001)<<24) +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_shift = 25 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_LOG_REQUEST(x): # macro + return (((x)&0x00000001)<<25) +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_offset = 1 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_shift = 26 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD1_FOUR_KILOBYTES(x): # macro + return (((x)&0x00000001)<<26) +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_offset = 2 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_mask = 0x00000001 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_s_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD2_S(x): # macro + return (((x)&0x00000001)<<0) +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_offset = 2 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_mask = 0x7FFFFFFF # macro +SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_shift = 1 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD2_PAGE_VA_42_12(x): # macro + return (((x)&0x7FFFFFFF)<<1) +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_offset = 3 # macro +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_mask = 0x0000003F # macro +SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_shift = 0 # macro +def SDMA_PKT_GPUVM_INV_PAYLOAD3_PAGE_VA_47_43(x): # macro + return (((x)&0x0000003F)<<0) +SDMA_PKT_GCR_REQ_HEADER_op_offset = 0 # macro +SDMA_PKT_GCR_REQ_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_GCR_REQ_HEADER_op_shift = 0 # macro +def SDMA_PKT_GCR_REQ_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_GCR_REQ_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_GCR_REQ_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_GCR_REQ_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_GCR_REQ_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_offset = 1 # macro +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_mask = 0x01FFFFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_shift = 7 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD1_BASE_VA_31_7(x): # macro + return (((x)&0x01FFFFFF)<<7) +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_offset = 2 # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD2_BASE_VA_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_offset = 2 # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_shift = 16 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD2_GCR_CONTROL_15_0(x): # macro + return (((x)&0x0000FFFF)<<16) +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_offset = 3 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_mask = 0x00000007 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD3_GCR_CONTROL_18_16(x): # macro + return (((x)&0x00000007)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_offset = 3 # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_mask = 0x01FFFFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_shift = 7 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD3_LIMIT_VA_31_7(x): # macro + return (((x)&0x01FFFFFF)<<7) +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_offset = 4 # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_mask = 0x0000FFFF # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_shift = 0 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD4_LIMIT_VA_47_32(x): # macro + return (((x)&0x0000FFFF)<<0) +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_offset = 4 # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_mask = 0x0000000F # macro +SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_shift = 24 # macro +def SDMA_PKT_GCR_REQ_PAYLOAD4_VMID(x): # macro + return (((x)&0x0000000F)<<24) +SDMA_PKT_NOP_HEADER_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_op_shift = 0 # macro +def SDMA_PKT_NOP_HEADER_OP(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_PKT_NOP_HEADER_sub_op_offset = 0 # macro +SDMA_PKT_NOP_HEADER_sub_op_mask = 0x000000FF # macro +SDMA_PKT_NOP_HEADER_sub_op_shift = 8 # macro +def SDMA_PKT_NOP_HEADER_SUB_OP(x): # macro + return (((x)&0x000000FF)<<8) +SDMA_PKT_NOP_HEADER_count_offset = 0 # macro +SDMA_PKT_NOP_HEADER_count_mask = 0x00003FFF # macro +SDMA_PKT_NOP_HEADER_count_shift = 16 # macro +def SDMA_PKT_NOP_HEADER_COUNT(x): # macro + return (((x)&0x00003FFF)<<16) +SDMA_PKT_NOP_DATA0_data0_offset = 1 # macro +SDMA_PKT_NOP_DATA0_data0_mask = 0xFFFFFFFF # macro +SDMA_PKT_NOP_DATA0_data0_shift = 0 # macro +def SDMA_PKT_NOP_DATA0_DATA0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_HEADER_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_HEADER_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_HEADER_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_HEADER_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_HEADER_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_HEADER_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_HEADER_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_HEADER_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_HEADER_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_HEADER_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_HEADER_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_HEADER_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_HEADER_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_HEADER_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_HEADER_HEADER_cpv_offset = 0 # macro +SDMA_AQL_PKT_HEADER_HEADER_cpv_mask = 0x00000001 # macro +SDMA_AQL_PKT_HEADER_HEADER_cpv_shift = 28 # macro +def SDMA_AQL_PKT_HEADER_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_offset = 0 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_shift = 28 # macro +def SDMA_AQL_PKT_COPY_LINEAR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset = 2 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_RETURN_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset = 3 # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_RETURN_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset = 4 # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask = 0x003FFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COUNT_COUNT(x): # macro + return (((x)&0x003FFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift = 16 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_DST_SW(x): # macro + return (((x)&0x00000003)<<16) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_shift = 18 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_DST_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<18) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask = 0x00000003 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift = 24 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_SRC_SW(x): # macro + return (((x)&0x00000003)<<24) +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_offset = 5 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_mask = 0x00000007 # macro +SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_shift = 26 # macro +def SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_SRC_CACHE_POLICY(x): # macro + return (((x)&0x00000007)<<26) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset = 6 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_SRC_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset = 7 # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_SRC_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset = 8 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_DST_ADDR_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset = 9 # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_DST_ADDR_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset = 10 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_RESERVED_DW10(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset = 11 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_RESERVED_DW11(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset = 12 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_RESERVED_DW12(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask = 0x000000FF # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_FORMAT(x): # macro + return (((x)&0x000000FF)<<0) +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask = 0x00000001 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift = 8 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_BARRIER(x): # macro + return (((x)&0x00000001)<<8) +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift = 9 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_ACQUIRE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<9) +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask = 0x00000003 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift = 11 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RELEASE_FENCE_SCOPE(x): # macro + return (((x)&0x00000003)<<11) +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift = 13 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_RESERVED(x): # macro + return (((x)&0x00000007)<<13) +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask = 0x0000000F # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift = 16 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_OP(x): # macro + return (((x)&0x0000000F)<<16) +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift = 20 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_SUBOP(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_offset = 0 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_mask = 0x00000001 # macro +SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_shift = 28 # macro +def SDMA_AQL_PKT_BARRIER_OR_HEADER_CPV(x): # macro + return (((x)&0x00000001)<<28) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset = 1 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_RESERVED_DW1(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset = 2 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_DEPENDENT_ADDR_0_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset = 3 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_DEPENDENT_ADDR_0_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset = 4 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_DEPENDENT_ADDR_1_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset = 5 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_DEPENDENT_ADDR_1_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset = 6 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_DEPENDENT_ADDR_2_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset = 7 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_DEPENDENT_ADDR_2_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset = 8 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_DEPENDENT_ADDR_3_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset = 9 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_DEPENDENT_ADDR_3_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset = 10 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_DEPENDENT_ADDR_4_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset = 11 # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_DEPENDENT_ADDR_4_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_CACHE_POLICY0(x): # macro + return (((x)&0x00000007)<<0) +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_shift = 5 # macro +def SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_CACHE_POLICY1(x): # macro + return (((x)&0x00000007)<<5) +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_shift = 10 # macro +def SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_CACHE_POLICY2(x): # macro + return (((x)&0x00000007)<<10) +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_shift = 15 # macro +def SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_CACHE_POLICY3(x): # macro + return (((x)&0x00000007)<<15) +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_offset = 12 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_mask = 0x00000007 # macro +SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_shift = 20 # macro +def SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_CACHE_POLICY4(x): # macro + return (((x)&0x00000007)<<20) +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset = 13 # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_RESERVED_DW13(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset = 14 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_COMPLETION_SIGNAL_31_0(x): # macro + return (((x)&0xFFFFFFFF)<<0) +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset = 15 # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask = 0xFFFFFFFF # macro +SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift = 0 # macro +def SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_COMPLETION_SIGNAL_63_32(x): # macro + return (((x)&0xFFFFFFFF)<<0) +__all__ = \ + ['HEADER_AGENT_DISPATCH', 'HEADER_BARRIER', + 'HSA_RUNTIME_CORE_INC_SDMA_REGISTERS_H_', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_mask', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_offset', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy1_shift', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_mask', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_offset', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy2_shift', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_mask', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_offset', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy3_shift', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_mask', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_offset', + 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy4_shift', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_HI_dependent_addr_0_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_0_LO_dependent_addr_0_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_HI_dependent_addr_1_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_1_LO_dependent_addr_1_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_HI_dependent_addr_2_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_2_LO_dependent_addr_2_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_HI_dependent_addr_3_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_3_LO_dependent_addr_3_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_HI_dependent_addr_4_63_32_shift', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_mask', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_offset', + 'SDMA_AQL_PKT_BARRIER_OR_DEPENDENT_ADDR_4_LO_dependent_addr_4_31_0_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_cpv_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_format_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_op_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_mask', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_offset', + 'SDMA_AQL_PKT_BARRIER_OR_HEADER_subop_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_BARRIER_OR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_HI_completion_signal_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COMPLETION_SIGNAL_LO_completion_signal_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_barrier_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_cpv_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_format_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_reserved_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_HEADER_subop_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW10_reserved_dw10_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW11_reserved_dw11_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW12_reserved_dw12_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW13_reserved_dw13_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RESERVED_DW1_reserved_dw1_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_HI_return_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_RETURN_ADDR_LO_return_addr_31_0_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_AQL_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_acquire_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_barrier_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_cpv_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_cpv_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_cpv_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_format_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_format_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_format_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_op_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_op_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_op_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_release_fence_scope_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_reserved_shift', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_mask', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_offset', + 'SDMA_AQL_PKT_HEADER_HEADER_subop_shift', 'SDMA_ATOMIC_ADD64', + 'SDMA_GCR_GL1_INV', 'SDMA_GCR_GL2_DISCARD', 'SDMA_GCR_GL2_INV', + 'SDMA_GCR_GL2_US', 'SDMA_GCR_GL2_WB', 'SDMA_GCR_GLK_INV', + 'SDMA_GCR_GLK_WB', 'SDMA_GCR_GLM_INV', 'SDMA_GCR_GLM_WB', + 'SDMA_GCR_GLV_INV', 'SDMA_GCR_RANGE_IS_PA', + 'SDMA_OP_AQL_BARRIER_OR', 'SDMA_OP_AQL_COPY', 'SDMA_OP_ATOMIC', + 'SDMA_OP_COND_EXE', 'SDMA_OP_CONST_FILL', 'SDMA_OP_COPY', + 'SDMA_OP_DUMMY_TRAP', 'SDMA_OP_FENCE', 'SDMA_OP_GCR', + 'SDMA_OP_GCR_REQ', 'SDMA_OP_GPUVM_INV', 'SDMA_OP_INDIRECT', + 'SDMA_OP_NOP', 'SDMA_OP_POLL_REGMEM', 'SDMA_OP_PRE_EXE', + 'SDMA_OP_PTEPDE', 'SDMA_OP_SEM', 'SDMA_OP_SRBM_WRITE', + 'SDMA_OP_TIMESTAMP', 'SDMA_OP_TRAP', 'SDMA_OP_WRITE', + 'SDMA_PKT_ATOMIC', 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_ATOMIC_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_ATOMIC_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_HI_cmp_data_63_32_shift', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_mask', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_offset', + 'SDMA_PKT_ATOMIC_CMP_DATA_LO_cmp_data_31_0_shift', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_atomic_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_cache_policy_mask', + 'SDMA_PKT_ATOMIC_HEADER_cache_policy_offset', + 'SDMA_PKT_ATOMIC_HEADER_cache_policy_shift', + 'SDMA_PKT_ATOMIC_HEADER_cpv_mask', + 'SDMA_PKT_ATOMIC_HEADER_cpv_offset', + 'SDMA_PKT_ATOMIC_HEADER_cpv_shift', + 'SDMA_PKT_ATOMIC_HEADER_loop_mask', + 'SDMA_PKT_ATOMIC_HEADER_loop_offset', + 'SDMA_PKT_ATOMIC_HEADER_loop_shift', + 'SDMA_PKT_ATOMIC_HEADER_op_mask', + 'SDMA_PKT_ATOMIC_HEADER_op_offset', + 'SDMA_PKT_ATOMIC_HEADER_op_shift', + 'SDMA_PKT_ATOMIC_HEADER_tmz_mask', + 'SDMA_PKT_ATOMIC_HEADER_tmz_offset', + 'SDMA_PKT_ATOMIC_HEADER_tmz_shift', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_mask', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_offset', + 'SDMA_PKT_ATOMIC_LOOP_INTERVAL_loop_interval_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_HI_src_data_63_32_shift', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_mask', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_offset', + 'SDMA_PKT_ATOMIC_SRC_DATA_LO_src_data_31_0_shift', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_COND_EXE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_COND_EXE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_COND_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_COND_EXE_HEADER_cache_policy_mask', + 'SDMA_PKT_COND_EXE_HEADER_cache_policy_offset', + 'SDMA_PKT_COND_EXE_HEADER_cache_policy_shift', + 'SDMA_PKT_COND_EXE_HEADER_cpv_mask', + 'SDMA_PKT_COND_EXE_HEADER_cpv_offset', + 'SDMA_PKT_COND_EXE_HEADER_cpv_shift', + 'SDMA_PKT_COND_EXE_HEADER_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_op_shift', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_COND_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_mask', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_offset', + 'SDMA_PKT_COND_EXE_REFERENCE_reference_shift', + 'SDMA_PKT_CONSTANT_FILL', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_mask', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_offset', + 'SDMA_PKT_CONSTANT_FILL_COUNT_count_shift', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DATA_src_data_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_CONSTANT_FILL_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cache_policy_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cpv_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cpv_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_cpv_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_fillsize_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sub_op_shift', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_mask', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_offset', + 'SDMA_PKT_CONSTANT_FILL_HEADER_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_HI_dst1_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST1_ADDR_LO_dst1_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_HI_dst2_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_DST2_ADDR_LO_dst2_addr_31_0_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_cpv_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_cache_policy_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst1_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_cache_policy_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_dst2_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_cache_policy_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_BROADCAST_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_COUNT_count_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_all_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_cpv_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_HEADER_tmz_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_l2_policy_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_llc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_mtype_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_l2_policy_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_llc_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_mtype_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_DIRTY_PAGE_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_COUNT_count_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_cache_policy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_dst2_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_cache_policy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_linear_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_cache_policy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_10_tile_sw_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_5_width_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_depth_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_6_height_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_dimension_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_element_size_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_mip_max_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_7_swizzle_mode_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_x_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_8_y_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_DW_9_z_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_cpv_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_tmz_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_HEADER_videocopy_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_0_tiled_addr0_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_HI_1_tiled_addr1_63_32_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_0_tiled_addr0_31_0_shift', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_mask', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_offset', + 'SDMA_PKT_COPY_L2T_BROADCAST_TILED_ADDR_LO_1_tiled_addr1_31_0_shift', + 'SDMA_PKT_COPY_LINEAR', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_BC_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_ha_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_ha_shift', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_BC_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_backwards_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_broadcast_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_cpv_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_cpv_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_cpv_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_cache_policy_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_cache_policy_shift', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_RECT', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_ha_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_ha_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_10_dst_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_11_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_cache_policy_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_cache_policy_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_12_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_3_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_4_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_5_src_slice_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_8_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_DW_9_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_cpv_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_elementsize_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_11_dst_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_12_dst_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_13_dst_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_14_dst_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_15_dst_slice_pitch_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_policy_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_slice_pitch_47_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_dst_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_policy_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_16_src_sw_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_17_rect_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_18_rect_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_19_rect_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_3_src_x_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_4_src_y_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_5_src_z_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_6_src_pitch_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_7_src_slice_pitch_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_DW_8_src_slice_pitch_47_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_cpv_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_HEADER_tmz_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_LARGE_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_LINEAR_SUBWIN_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_addr_pair_num_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_COUNT_count_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_cpv_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_HEADER_tmz_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_l2_policy_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_llc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_log_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_mtype_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_dst_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gcc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_gpa_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_l2_policy_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_llc_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_mtype_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_snoop_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sw_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_PARAMETER_src_sys_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_PHYSICAL_LINEAR_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_mask', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_offset', + 'SDMA_PKT_COPY_STRUCT_COUNT_count_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_cache_policy_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_linear_sw_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_stride_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_cache_policy_shift', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_mask', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_offset', + 'SDMA_PKT_COPY_STRUCT_DW_5_struct_sw_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_cpv_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_cpv_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_cpv_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_detile_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_mask', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_offset', + 'SDMA_PKT_COPY_STRUCT_HEADER_tmz_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_HI_sb_addr_63_32_shift', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_mask', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_offset', + 'SDMA_PKT_COPY_STRUCT_SB_ADDR_LO_sb_addr_31_0_shift', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_mask', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_offset', + 'SDMA_PKT_COPY_STRUCT_START_INDEX_start_index_shift', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_array_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_h_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_bank_w_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mat_aspt_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_mit_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_num_bank_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_pipe_config_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_12_dst_tilesplit_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_array_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_h_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_bank_w_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mat_aspt_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_mit_mode_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_num_bank_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_pipe_config_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_6_src_tilesplit_size_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_BC_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_BC_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_width_shift', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_mask', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_offset', + 'SDMA_PKT_COPY_T2T_DW_10_dst_z_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_mask', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_offset', + 'SDMA_PKT_COPY_T2T_DW_11_dst_height_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_id_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_mip_max_shift', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_12_dst_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_x_shift', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_mask', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_offset', + 'SDMA_PKT_COPY_T2T_DW_13_rect_y_shift', + 'SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_mask', + 'SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_offset', + 'SDMA_PKT_COPY_T2T_DW_14_dst_cache_policy_shift', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_dst_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_mask', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_offset', + 'SDMA_PKT_COPY_T2T_DW_14_rect_z_shift', + 'SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_mask', + 'SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_offset', + 'SDMA_PKT_COPY_T2T_DW_14_src_cache_policy_shift', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_mask', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_offset', + 'SDMA_PKT_COPY_T2T_DW_14_src_sw_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_x_shift', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_mask', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_offset', + 'SDMA_PKT_COPY_T2T_DW_3_src_y_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_width_shift', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_mask', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_offset', + 'SDMA_PKT_COPY_T2T_DW_4_src_z_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_depth_shift', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_mask', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_offset', + 'SDMA_PKT_COPY_T2T_DW_5_src_height_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_dimension_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_element_size_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_id_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_mip_max_shift', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_mask', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_offset', + 'SDMA_PKT_COPY_T2T_DW_6_src_swizzle_mode_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_x_shift', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_mask', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_offset', + 'SDMA_PKT_COPY_T2T_DW_9_dst_y_shift', + 'SDMA_PKT_COPY_T2T_HEADER_cpv_mask', + 'SDMA_PKT_COPY_T2T_HEADER_cpv_offset', + 'SDMA_PKT_COPY_T2T_HEADER_cpv_shift', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_mask', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_offset', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_dir_shift', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_mask', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_offset', + 'SDMA_PKT_COPY_T2T_HEADER_dcc_shift', + 'SDMA_PKT_COPY_T2T_HEADER_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_T2T_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_mask', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_offset', + 'SDMA_PKT_COPY_T2T_HEADER_tmz_shift', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_META_ADDR_HI_meta_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_META_ADDR_LO_meta_addr_31_0_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_alpha_is_on_msb_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_color_transform_disable_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_data_format_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_comp_block_size_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_max_uncomp_block_size_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_llc_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_meta_tmz_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_number_type_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_pipe_aligned_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_surface_type_shift', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_mask', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_offset', + 'SDMA_PKT_COPY_T2T_META_CONFIG_write_compress_enable_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_COPY_T2T_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_BC_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_array_mode_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_h_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_bank_w_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mat_aspt_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_mit_mode_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_num_bank_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_pipe_config_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_5_tilesplit_size_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_BC_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_BC_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_BC_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_COUNT_count_mask', + 'SDMA_PKT_COPY_TILED_COUNT_count_offset', + 'SDMA_PKT_COPY_TILED_COUNT_count_shift', + 'SDMA_PKT_COPY_TILED_DW_3_width_mask', + 'SDMA_PKT_COPY_TILED_DW_3_width_offset', + 'SDMA_PKT_COPY_TILED_DW_3_width_shift', + 'SDMA_PKT_COPY_TILED_DW_4_depth_mask', + 'SDMA_PKT_COPY_TILED_DW_4_depth_offset', + 'SDMA_PKT_COPY_TILED_DW_4_depth_shift', + 'SDMA_PKT_COPY_TILED_DW_4_height_mask', + 'SDMA_PKT_COPY_TILED_DW_4_height_offset', + 'SDMA_PKT_COPY_TILED_DW_4_height_shift', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_mask', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_offset', + 'SDMA_PKT_COPY_TILED_DW_5_dimension_shift', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_mask', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_offset', + 'SDMA_PKT_COPY_TILED_DW_5_element_size_shift', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_mask', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_offset', + 'SDMA_PKT_COPY_TILED_DW_5_mip_max_shift', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_DW_6_x_mask', + 'SDMA_PKT_COPY_TILED_DW_6_x_offset', + 'SDMA_PKT_COPY_TILED_DW_6_x_shift', + 'SDMA_PKT_COPY_TILED_DW_6_y_mask', + 'SDMA_PKT_COPY_TILED_DW_6_y_offset', + 'SDMA_PKT_COPY_TILED_DW_6_y_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_cache_policy_shift', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_mask', + 'SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_offset', + 'SDMA_PKT_COPY_TILED_DW_7_tile_cache_policy_shift', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_DW_7_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_DW_7_z_mask', + 'SDMA_PKT_COPY_TILED_DW_7_z_offset', + 'SDMA_PKT_COPY_TILED_DW_7_z_shift', + 'SDMA_PKT_COPY_TILED_HEADER_cpv_mask', + 'SDMA_PKT_COPY_TILED_HEADER_cpv_offset', + 'SDMA_PKT_COPY_TILED_HEADER_cpv_shift', + 'SDMA_PKT_COPY_TILED_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_COPY_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_COPY_TILED_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_PITCH_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_LINEAR_SLICE_PITCH_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_array_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_h_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_bank_w_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mat_aspt_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_mit_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_num_bank_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_pipe_config_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_6_tilesplit_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_BC_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_10_linear_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_11_linear_slice_pitch_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_12_rect_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_cache_policy_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_linear_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_rect_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_cache_policy_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_13_tile_sw_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_3_tiled_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_tiled_z_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_4_width_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_depth_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_5_height_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_dimension_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_element_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_id_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_mip_max_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_6_swizzle_mode_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_x_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_DW_9_linear_y_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_cpv_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_dcc_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_detile_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_sub_op_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_HEADER_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_HI_linear_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_LINEAR_ADDR_LO_linear_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_HI_meta_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_ADDR_LO_meta_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_alpha_is_on_msb_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_color_transform_disable_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_data_format_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_comp_block_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_max_uncomp_block_size_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_llc_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_meta_tmz_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_number_type_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_pipe_aligned_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_surface_type_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_META_CONFIG_write_compress_enable_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_SUBWIN_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_HI_tiled_addr_63_32_shift', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_mask', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_offset', + 'SDMA_PKT_COPY_TILED_TILED_ADDR_LO_tiled_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_COUNT_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_mask', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_offset', + 'SDMA_PKT_DATA_FILL_MULTI_BYTE_STRIDE_byte_stride_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DMA_COUNT_dma_count_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_DATA_FILL_MULTI_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cache_policy_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_cpv_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_memlog_clr_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_op_shift', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_mask', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_offset', + 'SDMA_PKT_DATA_FILL_MULTI_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_op_shift', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_DUMMY_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_DUMMY_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_FENCE', 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_FENCE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_FENCE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_FENCE_DATA_data_mask', + 'SDMA_PKT_FENCE_DATA_data_offset', + 'SDMA_PKT_FENCE_DATA_data_shift', + 'SDMA_PKT_FENCE_HEADER_cpv_mask', + 'SDMA_PKT_FENCE_HEADER_cpv_offset', + 'SDMA_PKT_FENCE_HEADER_cpv_shift', + 'SDMA_PKT_FENCE_HEADER_gcc_mask', + 'SDMA_PKT_FENCE_HEADER_gcc_offset', + 'SDMA_PKT_FENCE_HEADER_gcc_shift', + 'SDMA_PKT_FENCE_HEADER_gpa_mask', + 'SDMA_PKT_FENCE_HEADER_gpa_offset', + 'SDMA_PKT_FENCE_HEADER_gpa_shift', + 'SDMA_PKT_FENCE_HEADER_l2_policy_mask', + 'SDMA_PKT_FENCE_HEADER_l2_policy_offset', + 'SDMA_PKT_FENCE_HEADER_l2_policy_shift', + 'SDMA_PKT_FENCE_HEADER_llc_policy_mask', + 'SDMA_PKT_FENCE_HEADER_llc_policy_offset', + 'SDMA_PKT_FENCE_HEADER_llc_policy_shift', + 'SDMA_PKT_FENCE_HEADER_mtype_mask', + 'SDMA_PKT_FENCE_HEADER_mtype_offset', + 'SDMA_PKT_FENCE_HEADER_mtype_shift', + 'SDMA_PKT_FENCE_HEADER_op_mask', + 'SDMA_PKT_FENCE_HEADER_op_offset', + 'SDMA_PKT_FENCE_HEADER_op_shift', + 'SDMA_PKT_FENCE_HEADER_snp_mask', + 'SDMA_PKT_FENCE_HEADER_snp_offset', + 'SDMA_PKT_FENCE_HEADER_snp_shift', + 'SDMA_PKT_FENCE_HEADER_sub_op_mask', + 'SDMA_PKT_FENCE_HEADER_sub_op_offset', + 'SDMA_PKT_FENCE_HEADER_sub_op_shift', + 'SDMA_PKT_FENCE_HEADER_sys_mask', + 'SDMA_PKT_FENCE_HEADER_sys_offset', + 'SDMA_PKT_FENCE_HEADER_sys_shift', 'SDMA_PKT_GCR', + 'SDMA_PKT_GCR_REQ_HEADER_op_mask', + 'SDMA_PKT_GCR_REQ_HEADER_op_offset', + 'SDMA_PKT_GCR_REQ_HEADER_op_shift', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_mask', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_offset', + 'SDMA_PKT_GCR_REQ_HEADER_sub_op_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD1_base_va_31_7_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_base_va_47_32_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD2_gcr_control_15_0_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_gcr_control_18_16_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD3_limit_va_31_7_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_limit_va_47_32_shift', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_mask', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_offset', + 'SDMA_PKT_GCR_REQ_PAYLOAD4_vmid_shift', + 'SDMA_PKT_GPUVM_INV_HEADER_op_mask', + 'SDMA_PKT_GPUVM_INV_HEADER_op_offset', + 'SDMA_PKT_GPUVM_INV_HEADER_op_shift', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_mask', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_offset', + 'SDMA_PKT_GPUVM_INV_HEADER_sub_op_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_clr_protection_fault_status_addr_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_flush_type_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_four_kilobytes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l1_ptes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde0_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde1_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_pde2_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_l2_ptes_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_log_request_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD1_per_vmid_inv_req_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_page_va_42_12_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD2_s_shift', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_mask', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_offset', + 'SDMA_PKT_GPUVM_INV_PAYLOAD3_page_va_47_43_shift', + 'SDMA_PKT_HDP_FLUSH', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_mask', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_offset', + 'SDMA_PKT_INDIRECT_BASE_HI_ib_base_63_32_shift', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_mask', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_offset', + 'SDMA_PKT_INDIRECT_BASE_LO_ib_base_31_0_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_HI_csa_addr_63_32_shift', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_mask', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_offset', + 'SDMA_PKT_INDIRECT_CSA_ADDR_LO_csa_addr_31_0_shift', + 'SDMA_PKT_INDIRECT_HEADER_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_priv_mask', + 'SDMA_PKT_INDIRECT_HEADER_priv_offset', + 'SDMA_PKT_INDIRECT_HEADER_priv_shift', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_mask', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_offset', + 'SDMA_PKT_INDIRECT_HEADER_sub_op_shift', + 'SDMA_PKT_INDIRECT_HEADER_vmid_mask', + 'SDMA_PKT_INDIRECT_HEADER_vmid_offset', + 'SDMA_PKT_INDIRECT_HEADER_vmid_shift', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_mask', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_offset', + 'SDMA_PKT_INDIRECT_IB_SIZE_ib_size_shift', + 'SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_MEM_INCR_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_MEM_INCR_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_MEM_INCR_HEADER_cpv_mask', + 'SDMA_PKT_MEM_INCR_HEADER_cpv_offset', + 'SDMA_PKT_MEM_INCR_HEADER_cpv_shift', + 'SDMA_PKT_MEM_INCR_HEADER_l2_policy_mask', + 'SDMA_PKT_MEM_INCR_HEADER_l2_policy_offset', + 'SDMA_PKT_MEM_INCR_HEADER_l2_policy_shift', + 'SDMA_PKT_MEM_INCR_HEADER_llc_policy_mask', + 'SDMA_PKT_MEM_INCR_HEADER_llc_policy_offset', + 'SDMA_PKT_MEM_INCR_HEADER_llc_policy_shift', + 'SDMA_PKT_MEM_INCR_HEADER_op_mask', + 'SDMA_PKT_MEM_INCR_HEADER_op_offset', + 'SDMA_PKT_MEM_INCR_HEADER_op_shift', + 'SDMA_PKT_MEM_INCR_HEADER_sub_op_mask', + 'SDMA_PKT_MEM_INCR_HEADER_sub_op_offset', + 'SDMA_PKT_MEM_INCR_HEADER_sub_op_shift', + 'SDMA_PKT_NOP_DATA0_data0_mask', + 'SDMA_PKT_NOP_DATA0_data0_offset', + 'SDMA_PKT_NOP_DATA0_data0_shift', + 'SDMA_PKT_NOP_HEADER_count_mask', + 'SDMA_PKT_NOP_HEADER_count_offset', + 'SDMA_PKT_NOP_HEADER_count_shift', 'SDMA_PKT_NOP_HEADER_op_mask', + 'SDMA_PKT_NOP_HEADER_op_offset', 'SDMA_PKT_NOP_HEADER_op_shift', + 'SDMA_PKT_NOP_HEADER_sub_op_mask', + 'SDMA_PKT_NOP_HEADER_sub_op_offset', + 'SDMA_PKT_NOP_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cache_policy_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_cpv_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_ea_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_PAGE_NUM_page_num_31_0_shift', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_mask', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_offset', + 'SDMA_PKT_POLL_DBIT_WRITE_MEM_START_PAGE_addr_31_4_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_HI_cmp0_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_END_LO_cmp0_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_HI_cmp0_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP0_ADDR_START_LO_cmp0_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_HI_cmp1_end_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_END_LO_cmp1_end_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_HI_cmp1_start_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_CMP1_ADDR_START_LO_cmp1_start_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cache_policy_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_cpv_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_mode_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_PATTERN_pattern_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_HI_rec_63_32_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_REC_ADDR_LO_rec_31_0_shift', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_mask', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_offset', + 'SDMA_PKT_POLL_MEM_VERIFY_RESERVED_reserved_shift', + 'SDMA_PKT_POLL_REGMEM', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REGMEM_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_interval_shift', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_mask', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_offset', + 'SDMA_PKT_POLL_REGMEM_DW5_retry_count_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_cache_policy_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_cpv_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_cpv_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_cpv_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_func_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_hdp_flush_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_mem_poll_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REGMEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_mask', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_offset', + 'SDMA_PKT_POLL_REGMEM_MASK_mask_shift', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_mask', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_offset', + 'SDMA_PKT_POLL_REGMEM_VALUE_value_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_DST_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cache_policy_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_cpv_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_HEADER_sub_op_shift', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_mask', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_offset', + 'SDMA_PKT_POLL_REG_WRITE_MEM_SRC_ADDR_addr_31_2_shift', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_mask', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_offset', + 'SDMA_PKT_PRE_EXE_EXEC_COUNT_exec_count_shift', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_mask', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_offset', + 'SDMA_PKT_PRE_EXE_HEADER_dev_sel_shift', + 'SDMA_PKT_PRE_EXE_HEADER_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_op_shift', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_mask', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_offset', + 'SDMA_PKT_PRE_EXE_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_COUNT_IN_32B_XFER_count_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_direction_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_pte_size_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_first_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_MASK_BIT_FOR_DW_mask_last_xfer_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_BACKWARDS_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_count_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_dst_cache_policy_shift', + 'SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_mask', + 'SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_offset', + 'SDMA_PKT_PTEPDE_COPY_COUNT_src_cache_policy_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_cpv_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_cpv_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_cpv_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_ptepde_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_mask', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_offset', + 'SDMA_PKT_PTEPDE_COPY_HEADER_tmz_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_PTEPDE_COPY_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_HI_src_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_COPY_SRC_ADDR_LO_src_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_mask', + 'SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_offset', + 'SDMA_PKT_PTEPDE_RMW_COUNT_num_of_pte_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_cpv_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_cpv_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_cpv_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gcc_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_gpa_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_l2_policy_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_llc_policy_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_mtype_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_snp_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sub_op_shift', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_mask', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_offset', + 'SDMA_PKT_PTEPDE_RMW_HEADER_sys_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_HI_mask_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_MASK_LO_mask_31_0_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_HI_value_63_32_shift', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_mask', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_offset', + 'SDMA_PKT_PTEPDE_RMW_VALUE_LO_value_31_0_shift', + 'SDMA_PKT_REGISTER_RMW_ADDR_addr_mask', + 'SDMA_PKT_REGISTER_RMW_ADDR_addr_offset', + 'SDMA_PKT_REGISTER_RMW_ADDR_addr_shift', + 'SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_mask', + 'SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_offset', + 'SDMA_PKT_REGISTER_RMW_ADDR_aperture_id_shift', + 'SDMA_PKT_REGISTER_RMW_HEADER_op_mask', + 'SDMA_PKT_REGISTER_RMW_HEADER_op_offset', + 'SDMA_PKT_REGISTER_RMW_HEADER_op_shift', + 'SDMA_PKT_REGISTER_RMW_HEADER_sub_op_mask', + 'SDMA_PKT_REGISTER_RMW_HEADER_sub_op_offset', + 'SDMA_PKT_REGISTER_RMW_HEADER_sub_op_shift', + 'SDMA_PKT_REGISTER_RMW_MASK_mask_mask', + 'SDMA_PKT_REGISTER_RMW_MASK_mask_offset', + 'SDMA_PKT_REGISTER_RMW_MASK_mask_shift', + 'SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_mask', + 'SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_offset', + 'SDMA_PKT_REGISTER_RMW_MISC_num_of_reg_shift', + 'SDMA_PKT_REGISTER_RMW_MISC_stride_mask', + 'SDMA_PKT_REGISTER_RMW_MISC_stride_offset', + 'SDMA_PKT_REGISTER_RMW_MISC_stride_shift', + 'SDMA_PKT_REGISTER_RMW_VALUE_value_mask', + 'SDMA_PKT_REGISTER_RMW_VALUE_value_offset', + 'SDMA_PKT_REGISTER_RMW_VALUE_value_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_HI_addr_63_32_shift', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_mask', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_offset', + 'SDMA_PKT_SEMAPHORE_ADDR_LO_addr_31_0_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_mailbox_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_signal_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_sub_op_shift', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_mask', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_offset', + 'SDMA_PKT_SEMAPHORE_HEADER_write_one_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_addr_shift', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_mask', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_offset', + 'SDMA_PKT_SRBM_WRITE_ADDR_apertureid_shift', + 'SDMA_PKT_SRBM_WRITE_DATA_data_mask', + 'SDMA_PKT_SRBM_WRITE_DATA_data_offset', + 'SDMA_PKT_SRBM_WRITE_DATA_data_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_byte_en_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_op_shift', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_mask', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_offset', + 'SDMA_PKT_SRBM_WRITE_HEADER_sub_op_shift', 'SDMA_PKT_TIMESTAMP', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_cpv_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_l2_policy_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_llc_policy_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_GLOBAL_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_cpv_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_l2_policy_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_llc_policy_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_GET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_HI_write_addr_63_32_shift', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_mask', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_offset', + 'SDMA_PKT_TIMESTAMP_GET_WRITE_ADDR_LO_write_addr_31_3_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_mask', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_offset', + 'SDMA_PKT_TIMESTAMP_SET_HEADER_sub_op_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_HI_init_data_63_32_shift', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_mask', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_offset', + 'SDMA_PKT_TIMESTAMP_SET_INIT_DATA_LO_init_data_31_0_shift', + 'SDMA_PKT_TRAP', 'SDMA_PKT_TRAP_HEADER_op_mask', + 'SDMA_PKT_TRAP_HEADER_op_offset', 'SDMA_PKT_TRAP_HEADER_op_shift', + 'SDMA_PKT_TRAP_HEADER_sub_op_mask', + 'SDMA_PKT_TRAP_HEADER_sub_op_offset', + 'SDMA_PKT_TRAP_HEADER_sub_op_shift', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_mask', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_offset', + 'SDMA_PKT_TRAP_INT_CONTEXT_int_context_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_addressrangehi_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_invalidateack_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGEHI_reserved_shift', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_mask', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_offset', + 'SDMA_PKT_VM_INVALIDATION_ADDRESSRANGELO_addressrangelo_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_gfx_eng_id_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_mm_eng_id_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_op_shift', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_mask', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_offset', + 'SDMA_PKT_VM_INVALIDATION_HEADER_sub_op_shift', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_mask', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_offset', + 'SDMA_PKT_VM_INVALIDATION_INVALIDATEREQ_invalidatereq_shift', + 'SDMA_PKT_WRITE_INCR_COUNT_count_mask', + 'SDMA_PKT_WRITE_INCR_COUNT_count_offset', + 'SDMA_PKT_WRITE_INCR_COUNT_count_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_INCR_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_cache_policy_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_cache_policy_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_cache_policy_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_cpv_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_cpv_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_cpv_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_op_shift', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_INCR_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW0_incr_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INCR_DW1_incr_dw1_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW0_init_dw0_shift', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_mask', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_offset', + 'SDMA_PKT_WRITE_INCR_INIT_DW1_init_dw1_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW0_mask_dw0_shift', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_mask', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_offset', + 'SDMA_PKT_WRITE_INCR_MASK_DW1_mask_dw1_shift', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_BC_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_BC_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_BC_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_array_mode_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_h_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_bank_w_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mat_aspt_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_mit_mode_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_num_bank_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_pipe_config_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_5_tilesplit_size_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_BC_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_BC_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_COUNT_count_mask', + 'SDMA_PKT_WRITE_TILED_COUNT_count_offset', + 'SDMA_PKT_WRITE_TILED_COUNT_count_shift', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_TILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_TILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_TILED_DW_3_width_mask', + 'SDMA_PKT_WRITE_TILED_DW_3_width_offset', + 'SDMA_PKT_WRITE_TILED_DW_3_width_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_depth_shift', + 'SDMA_PKT_WRITE_TILED_DW_4_height_mask', + 'SDMA_PKT_WRITE_TILED_DW_4_height_offset', + 'SDMA_PKT_WRITE_TILED_DW_4_height_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_dimension_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_element_size_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_mip_max_shift', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_mask', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_offset', + 'SDMA_PKT_WRITE_TILED_DW_5_swizzle_mode_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_x_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_x_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_x_shift', + 'SDMA_PKT_WRITE_TILED_DW_6_y_mask', + 'SDMA_PKT_WRITE_TILED_DW_6_y_offset', + 'SDMA_PKT_WRITE_TILED_DW_6_y_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_cache_policy_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_cache_policy_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_cache_policy_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_sw_shift', + 'SDMA_PKT_WRITE_TILED_DW_7_z_mask', + 'SDMA_PKT_WRITE_TILED_DW_7_z_offset', + 'SDMA_PKT_WRITE_TILED_DW_7_z_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_cpv_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_cpv_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_cpv_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_TILED_HEADER_tmz_shift', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_mask', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_offset', + 'SDMA_PKT_WRITE_UNTILED_DATA0_data0_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_HI_dst_addr_63_32_shift', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_mask', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_offset', + 'SDMA_PKT_WRITE_UNTILED_DST_ADDR_LO_dst_addr_31_0_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_cache_policy_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_count_shift', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_mask', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_offset', + 'SDMA_PKT_WRITE_UNTILED_DW_3_sw_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_cpv_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_cpv_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_cpv_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_encrypt_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_sub_op_shift', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_mask', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_offset', + 'SDMA_PKT_WRITE_UNTILED_HEADER_tmz_shift', + 'SDMA_SUBOP_COPY_DIRTY_PAGE', 'SDMA_SUBOP_COPY_LINEAR', + 'SDMA_SUBOP_COPY_LINEAR_BC', 'SDMA_SUBOP_COPY_LINEAR_PHY', + 'SDMA_SUBOP_COPY_LINEAR_RECT', 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND', + 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND_BC', + 'SDMA_SUBOP_COPY_LINEAR_SUB_WIND_LARGE', 'SDMA_SUBOP_COPY_SOA', + 'SDMA_SUBOP_COPY_T2T_SUB_WIND', 'SDMA_SUBOP_COPY_T2T_SUB_WIND_BC', + 'SDMA_SUBOP_COPY_TILED', 'SDMA_SUBOP_COPY_TILED_BC', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND', + 'SDMA_SUBOP_COPY_TILED_SUB_WIND_BC', 'SDMA_SUBOP_DATA_FILL_MULTI', + 'SDMA_SUBOP_MEM_INCR', 'SDMA_SUBOP_POLL_DBIT_WRITE_MEM', + 'SDMA_SUBOP_POLL_MEM_VERIFY', 'SDMA_SUBOP_POLL_REG_WRITE_MEM', + 'SDMA_SUBOP_PTEPDE_COPY', 'SDMA_SUBOP_PTEPDE_COPY_BACKWARDS', + 'SDMA_SUBOP_PTEPDE_GEN', 'SDMA_SUBOP_PTEPDE_RMW', + 'SDMA_SUBOP_TIMESTAMP_GET', 'SDMA_SUBOP_TIMESTAMP_GET_GLOBAL', + 'SDMA_SUBOP_TIMESTAMP_SET', 'SDMA_SUBOP_USER_GCR', + 'SDMA_SUBOP_VM_INVALIDATION', 'SDMA_SUBOP_WRITE_LINEAR', + 'SDMA_SUBOP_WRITE_TILED', 'SDMA_SUBOP_WRITE_TILED_BC', + '__SDMA_V6_0_0_PKT_OPEN_H_', 'hdp_flush_cmd', + 'struct_SDMA_PKT_ATOMIC_TAG', 'struct_SDMA_PKT_ATOMIC_TAG_0_0', + 'struct_SDMA_PKT_ATOMIC_TAG_1_0', + 'struct_SDMA_PKT_ATOMIC_TAG_2_0', + 'struct_SDMA_PKT_ATOMIC_TAG_3_0', + 'struct_SDMA_PKT_ATOMIC_TAG_4_0', + 'struct_SDMA_PKT_ATOMIC_TAG_5_0', + 'struct_SDMA_PKT_ATOMIC_TAG_6_0', + 'struct_SDMA_PKT_ATOMIC_TAG_7_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_0_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_1_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_2_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_3_0', + 'struct_SDMA_PKT_CONSTANT_FILL_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_10_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_11_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_12_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_6_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_7_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_8_0', + 'struct_SDMA_PKT_COPY_LINEAR_RECT_TAG_9_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_0_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_1_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_2_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_3_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_4_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_5_0', + 'struct_SDMA_PKT_COPY_LINEAR_TAG_6_0', + 'struct_SDMA_PKT_FENCE_TAG', 'struct_SDMA_PKT_FENCE_TAG_0_0', + 'struct_SDMA_PKT_FENCE_TAG_1_0', 'struct_SDMA_PKT_FENCE_TAG_2_0', + 'struct_SDMA_PKT_FENCE_TAG_3_0', 'struct_SDMA_PKT_GCR_TAG', + 'struct_SDMA_PKT_GCR_TAG_0_0', 'struct_SDMA_PKT_GCR_TAG_1_0', + 'struct_SDMA_PKT_GCR_TAG_2_0', 'struct_SDMA_PKT_GCR_TAG_3_0', + 'struct_SDMA_PKT_GCR_TAG_4_0', 'struct_SDMA_PKT_HDP_FLUSH_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_0_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_1_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_2_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_3_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_4_0', + 'struct_SDMA_PKT_POLL_REGMEM_TAG_5_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG', + 'struct_SDMA_PKT_TIMESTAMP_TAG_0_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_1_0', + 'struct_SDMA_PKT_TIMESTAMP_TAG_2_0', 'struct_SDMA_PKT_TRAP_TAG', + 'struct_SDMA_PKT_TRAP_TAG_0_0', 'struct_SDMA_PKT_TRAP_TAG_1_0', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_CMP_DATA_LO_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_HEADER_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_LOOP_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_HI_UNION', + 'union_SDMA_PKT_ATOMIC_TAG_SRC_DATA_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_COUNT_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DATA_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_CONSTANT_FILL_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_DST_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_RECT_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_1_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_2_UNION', + 'union_SDMA_PKT_COPY_LINEAR_RECT_TAG_SRC_PARAMETER_3_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_COUNT_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_DST_ADDR_LO_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_HEADER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_PARAMETER_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_HI_UNION', + 'union_SDMA_PKT_COPY_LINEAR_TAG_SRC_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_FENCE_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_FENCE_TAG_DATA_UNION', + 'union_SDMA_PKT_FENCE_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_HEADER_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD1_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD2_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD3_UNION', + 'union_SDMA_PKT_GCR_TAG_WORD4_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_DW5_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_HEADER_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_MASK_UNION', + 'union_SDMA_PKT_POLL_REGMEM_TAG_VALUE_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_HI_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_ADDR_LO_UNION', + 'union_SDMA_PKT_TIMESTAMP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_HEADER_UNION', + 'union_SDMA_PKT_TRAP_TAG_INT_CONTEXT_UNION'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v13_0_0.py b/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v13_0_0.py new file mode 100644 index 0000000000..b67f1ce734 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v13_0_0.py @@ -0,0 +1,3068 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +SMU_V13_0_0_PPSMC_H = True # macro +PPSMC_VERSION = 0x1 # macro +DEBUGSMC_VERSION = 0x1 # macro +PPSMC_Result_OK = 0x1 # macro +PPSMC_Result_Failed = 0xFF # macro +PPSMC_Result_UnknownCmd = 0xFE # macro +PPSMC_Result_CmdRejectedPrereq = 0xFD # macro +PPSMC_Result_CmdRejectedBusy = 0xFC # macro +PPSMC_MSG_TestMessage = 0x1 # macro +PPSMC_MSG_GetSmuVersion = 0x2 # macro +PPSMC_MSG_GetDriverIfVersion = 0x3 # macro +PPSMC_MSG_SetAllowedFeaturesMaskLow = 0x4 # macro +PPSMC_MSG_SetAllowedFeaturesMaskHigh = 0x5 # macro +PPSMC_MSG_EnableAllSmuFeatures = 0x6 # macro +PPSMC_MSG_DisableAllSmuFeatures = 0x7 # macro +PPSMC_MSG_EnableSmuFeaturesLow = 0x8 # macro +PPSMC_MSG_EnableSmuFeaturesHigh = 0x9 # macro +PPSMC_MSG_DisableSmuFeaturesLow = 0xA # macro +PPSMC_MSG_DisableSmuFeaturesHigh = 0xB # macro +PPSMC_MSG_GetRunningSmuFeaturesLow = 0xC # macro +PPSMC_MSG_GetRunningSmuFeaturesHigh = 0xD # macro +PPSMC_MSG_SetDriverDramAddrHigh = 0xE # macro +PPSMC_MSG_SetDriverDramAddrLow = 0xF # macro +PPSMC_MSG_SetToolsDramAddrHigh = 0x10 # macro +PPSMC_MSG_SetToolsDramAddrLow = 0x11 # macro +PPSMC_MSG_TransferTableSmu2Dram = 0x12 # macro +PPSMC_MSG_TransferTableDram2Smu = 0x13 # macro +PPSMC_MSG_UseDefaultPPTable = 0x14 # macro +PPSMC_MSG_EnterBaco = 0x15 # macro +PPSMC_MSG_ExitBaco = 0x16 # macro +PPSMC_MSG_ArmD3 = 0x17 # macro +PPSMC_MSG_BacoAudioD3PME = 0x18 # macro +PPSMC_MSG_SetSoftMinByFreq = 0x19 # macro +PPSMC_MSG_SetSoftMaxByFreq = 0x1A # macro +PPSMC_MSG_SetHardMinByFreq = 0x1B # macro +PPSMC_MSG_SetHardMaxByFreq = 0x1C # macro +PPSMC_MSG_GetMinDpmFreq = 0x1D # macro +PPSMC_MSG_GetMaxDpmFreq = 0x1E # macro +PPSMC_MSG_GetDpmFreqByIndex = 0x1F # macro +PPSMC_MSG_OverridePcieParameters = 0x20 # macro +PPSMC_MSG_DramLogSetDramAddrHigh = 0x21 # macro +PPSMC_MSG_DramLogSetDramAddrLow = 0x22 # macro +PPSMC_MSG_DramLogSetDramSize = 0x23 # macro +PPSMC_MSG_SetWorkloadMask = 0x24 # macro +PPSMC_MSG_GetVoltageByDpm = 0x25 # macro +PPSMC_MSG_SetVideoFps = 0x26 # macro +PPSMC_MSG_GetDcModeMaxDpmFreq = 0x27 # macro +PPSMC_MSG_AllowGfxOff = 0x28 # macro +PPSMC_MSG_DisallowGfxOff = 0x29 # macro +PPSMC_MSG_PowerUpVcn = 0x2A # macro +PPSMC_MSG_PowerDownVcn = 0x2B # macro +PPSMC_MSG_PowerUpJpeg = 0x2C # macro +PPSMC_MSG_PowerDownJpeg = 0x2D # macro +PPSMC_MSG_PrepareMp1ForUnload = 0x2E # macro +PPSMC_MSG_Mode1Reset = 0x2F # macro +PPSMC_MSG_Mode2Reset = 0x4F # macro +PPSMC_MSG_SetSystemVirtualDramAddrHigh = 0x30 # macro +PPSMC_MSG_SetSystemVirtualDramAddrLow = 0x31 # macro +PPSMC_MSG_SetPptLimit = 0x32 # macro +PPSMC_MSG_GetPptLimit = 0x33 # macro +PPSMC_MSG_ReenableAcDcInterrupt = 0x34 # macro +PPSMC_MSG_NotifyPowerSource = 0x35 # macro +PPSMC_MSG_RunDcBtc = 0x36 # macro +PPSMC_MSG_GetDebugData = 0x37 # macro +PPSMC_MSG_SetTemperatureInputSelect = 0x38 # macro +PPSMC_MSG_SetFwDstatesMask = 0x39 # macro +PPSMC_MSG_SetThrottlerMask = 0x3A # macro +PPSMC_MSG_SetExternalClientDfCstateAllow = 0x3B # macro +PPSMC_MSG_SetMGpuFanBoostLimitRpm = 0x3C # macro +PPSMC_MSG_DumpSTBtoDram = 0x3D # macro +PPSMC_MSG_STBtoDramLogSetDramAddrHigh = 0x3E # macro +PPSMC_MSG_STBtoDramLogSetDramAddrLow = 0x3F # macro +PPSMC_MSG_STBtoDramLogSetDramSize = 0x40 # macro +PPSMC_MSG_SetGpoAllow = 0x41 # macro +PPSMC_MSG_AllowGfxDcs = 0x42 # macro +PPSMC_MSG_DisallowGfxDcs = 0x43 # macro +PPSMC_MSG_EnableAudioStutterWA = 0x44 # macro +PPSMC_MSG_PowerUpUmsch = 0x45 # macro +PPSMC_MSG_PowerDownUmsch = 0x46 # macro +PPSMC_MSG_SetDcsArch = 0x47 # macro +PPSMC_MSG_TriggerVFFLR = 0x48 # macro +PPSMC_MSG_SetNumBadMemoryPagesRetired = 0x49 # macro +PPSMC_MSG_SetBadMemoryPagesRetiredFlagsPerChannel = 0x4A # macro +PPSMC_MSG_SetPriorityDeltaGain = 0x4B # macro +PPSMC_MSG_AllowIHHostInterrupt = 0x4C # macro +PPSMC_MSG_DALNotPresent = 0x4E # macro +PPSMC_MSG_EnableUCLKShadow = 0x51 # macro +PPSMC_Message_Count = 0x52 # macro +DEBUGSMC_MSG_TestMessage = 0x1 # macro +DEBUGSMC_MSG_GetDebugData = 0x2 # macro +DEBUGSMC_MSG_DebugDumpExit = 0x3 # macro +DEBUGSMC_Message_Count = 0x4 # macro +SMU13_DRIVER_IF_V13_0_0_H = True # macro +int32_t = True # macro +uint32_t = True # macro +int8_t = True # macro +uint8_t = True # macro +uint16_t = True # macro +int16_t = True # macro +uint64_t = True # macro +bool = True # macro +SMU13_0_0_DRIVER_IF_VERSION = 0x3D # macro +PPTABLE_VERSION = 0x2B # macro +NUM_GFXCLK_DPM_LEVELS = 16 # macro +NUM_SOCCLK_DPM_LEVELS = 8 # macro +NUM_MP0CLK_DPM_LEVELS = 2 # macro +NUM_DCLK_DPM_LEVELS = 8 # macro +NUM_VCLK_DPM_LEVELS = 8 # macro +NUM_DISPCLK_DPM_LEVELS = 8 # macro +NUM_DPPCLK_DPM_LEVELS = 8 # macro +NUM_DPREFCLK_DPM_LEVELS = 8 # macro +NUM_DCFCLK_DPM_LEVELS = 8 # macro +NUM_DTBCLK_DPM_LEVELS = 8 # macro +NUM_UCLK_DPM_LEVELS = 4 # macro +NUM_LINK_LEVELS = 3 # macro +NUM_FCLK_DPM_LEVELS = 8 # macro +NUM_OD_FAN_MAX_POINTS = 6 # macro +FEATURE_FW_DATA_READ_BIT = 0 # macro +FEATURE_DPM_GFXCLK_BIT = 1 # macro +FEATURE_DPM_GFX_POWER_OPTIMIZER_BIT = 2 # macro +FEATURE_DPM_UCLK_BIT = 3 # macro +FEATURE_DPM_FCLK_BIT = 4 # macro +FEATURE_DPM_SOCCLK_BIT = 5 # macro +FEATURE_DPM_MP0CLK_BIT = 6 # macro +FEATURE_DPM_LINK_BIT = 7 # macro +FEATURE_DPM_DCN_BIT = 8 # macro +FEATURE_VMEMP_SCALING_BIT = 9 # macro +FEATURE_VDDIO_MEM_SCALING_BIT = 10 # macro +FEATURE_DS_GFXCLK_BIT = 11 # macro +FEATURE_DS_SOCCLK_BIT = 12 # macro +FEATURE_DS_FCLK_BIT = 13 # macro +FEATURE_DS_LCLK_BIT = 14 # macro +FEATURE_DS_DCFCLK_BIT = 15 # macro +FEATURE_DS_UCLK_BIT = 16 # macro +FEATURE_GFX_ULV_BIT = 17 # macro +FEATURE_FW_DSTATE_BIT = 18 # macro +FEATURE_GFXOFF_BIT = 19 # macro +FEATURE_BACO_BIT = 20 # macro +FEATURE_MM_DPM_BIT = 21 # macro +FEATURE_SOC_MPCLK_DS_BIT = 22 # macro +FEATURE_BACO_MPCLK_DS_BIT = 23 # macro +FEATURE_THROTTLERS_BIT = 24 # macro +FEATURE_SMARTSHIFT_BIT = 25 # macro +FEATURE_GTHR_BIT = 26 # macro +FEATURE_ACDC_BIT = 27 # macro +FEATURE_VR0HOT_BIT = 28 # macro +FEATURE_FW_CTF_BIT = 29 # macro +FEATURE_FAN_CONTROL_BIT = 30 # macro +FEATURE_GFX_DCS_BIT = 31 # macro +FEATURE_GFX_READ_MARGIN_BIT = 32 # macro +FEATURE_LED_DISPLAY_BIT = 33 # macro +FEATURE_GFXCLK_SPREAD_SPECTRUM_BIT = 34 # macro +FEATURE_OUT_OF_BAND_MONITOR_BIT = 35 # macro +FEATURE_OPTIMIZED_VMIN_BIT = 36 # macro +FEATURE_GFX_IMU_BIT = 37 # macro +FEATURE_BOOT_TIME_CAL_BIT = 38 # macro +FEATURE_GFX_PCC_DFLL_BIT = 39 # macro +FEATURE_SOC_CG_BIT = 40 # macro +FEATURE_DF_CSTATE_BIT = 41 # macro +FEATURE_GFX_EDC_BIT = 42 # macro +FEATURE_BOOT_POWER_OPT_BIT = 43 # macro +FEATURE_CLOCK_POWER_DOWN_BYPASS_BIT = 44 # macro +FEATURE_DS_VCN_BIT = 45 # macro +FEATURE_BACO_CG_BIT = 46 # macro +FEATURE_MEM_TEMP_READ_BIT = 47 # macro +FEATURE_ATHUB_MMHUB_PG_BIT = 48 # macro +FEATURE_SOC_PCC_BIT = 49 # macro +FEATURE_EDC_PWRBRK_BIT = 50 # macro +FEATURE_BOMXCO_SVI3_PROG_BIT = 51 # macro +FEATURE_SPARE_52_BIT = 52 # macro +FEATURE_SPARE_53_BIT = 53 # macro +FEATURE_SPARE_54_BIT = 54 # macro +FEATURE_SPARE_55_BIT = 55 # macro +FEATURE_SPARE_56_BIT = 56 # macro +FEATURE_SPARE_57_BIT = 57 # macro +FEATURE_SPARE_58_BIT = 58 # macro +FEATURE_SPARE_59_BIT = 59 # macro +FEATURE_SPARE_60_BIT = 60 # macro +FEATURE_SPARE_61_BIT = 61 # macro +FEATURE_SPARE_62_BIT = 62 # macro +FEATURE_SPARE_63_BIT = 63 # macro +NUM_FEATURES = 64 # macro +ALLOWED_FEATURE_CTRL_DEFAULT = 0xFFFFFFFFFFFFFFFF # macro +ALLOWED_FEATURE_CTRL_SCPM = ((1<<1)|(1<<2)|(1<<3)|(1<<4)|(1<<5)|(1<<6)|(1<<7)|(1<<8)|(1<<11)|(1<<12)|(1<<13)|(1<<14)|(1<<15)|(1<<16)|(1<<45)) # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_FCLK = 0x00000001 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_DCN_FCLK = 0x00000002 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_MP0_FCLK = 0x00000004 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_DCFCLK = 0x00000008 # macro +DEBUG_OVERRIDE_DISABLE_FAST_FCLK_TIMER = 0x00000010 # macro +DEBUG_OVERRIDE_DISABLE_VCN_PG = 0x00000020 # macro +DEBUG_OVERRIDE_DISABLE_FMAX_VMAX = 0x00000040 # macro +DEBUG_OVERRIDE_DISABLE_IMU_FW_CHECKS = 0x00000080 # macro +DEBUG_OVERRIDE_DISABLE_D0i2_REENTRY_HSR_TIMER_CHECK = 0x00000100 # macro +DEBUG_OVERRIDE_DISABLE_DFLL = 0x00000200 # macro +DEBUG_OVERRIDE_ENABLE_RLC_VF_BRINGUP_MODE = 0x00000400 # macro +DEBUG_OVERRIDE_DFLL_MASTER_MODE = 0x00000800 # macro +DEBUG_OVERRIDE_ENABLE_PROFILING_MODE = 0x00001000 # macro +VR_MAPPING_VR_SELECT_MASK = 0x01 # macro +VR_MAPPING_VR_SELECT_SHIFT = 0x00 # macro +VR_MAPPING_PLANE_SELECT_MASK = 0x02 # macro +VR_MAPPING_PLANE_SELECT_SHIFT = 0x01 # macro +PSI_SEL_VR0_PLANE0_PSI0 = 0x01 # macro +PSI_SEL_VR0_PLANE0_PSI1 = 0x02 # macro +PSI_SEL_VR0_PLANE1_PSI0 = 0x04 # macro +PSI_SEL_VR0_PLANE1_PSI1 = 0x08 # macro +PSI_SEL_VR1_PLANE0_PSI0 = 0x10 # macro +PSI_SEL_VR1_PLANE0_PSI1 = 0x20 # macro +PSI_SEL_VR1_PLANE1_PSI0 = 0x40 # macro +PSI_SEL_VR1_PLANE1_PSI1 = 0x80 # macro +THROTTLER_TEMP_EDGE_BIT = 0 # macro +THROTTLER_TEMP_HOTSPOT_BIT = 1 # macro +THROTTLER_TEMP_HOTSPOT_G_BIT = 2 # macro +THROTTLER_TEMP_HOTSPOT_M_BIT = 3 # macro +THROTTLER_TEMP_MEM_BIT = 4 # macro +THROTTLER_TEMP_VR_GFX_BIT = 5 # macro +THROTTLER_TEMP_VR_MEM0_BIT = 6 # macro +THROTTLER_TEMP_VR_MEM1_BIT = 7 # macro +THROTTLER_TEMP_VR_SOC_BIT = 8 # macro +THROTTLER_TEMP_VR_U_BIT = 9 # macro +THROTTLER_TEMP_LIQUID0_BIT = 10 # macro +THROTTLER_TEMP_LIQUID1_BIT = 11 # macro +THROTTLER_TEMP_PLX_BIT = 12 # macro +THROTTLER_TDC_GFX_BIT = 13 # macro +THROTTLER_TDC_SOC_BIT = 14 # macro +THROTTLER_TDC_U_BIT = 15 # macro +THROTTLER_PPT0_BIT = 16 # macro +THROTTLER_PPT1_BIT = 17 # macro +THROTTLER_PPT2_BIT = 18 # macro +THROTTLER_PPT3_BIT = 19 # macro +THROTTLER_FIT_BIT = 20 # macro +THROTTLER_GFX_APCC_PLUS_BIT = 21 # macro +THROTTLER_COUNT = 22 # macro +FW_DSTATE_SOC_ULV_BIT = 0 # macro +FW_DSTATE_G6_HSR_BIT = 1 # macro +FW_DSTATE_G6_PHY_VMEMP_OFF_BIT = 2 # macro +FW_DSTATE_SMN_DS_BIT = 3 # macro +FW_DSTATE_MP1_WHISPER_MODE_BIT = 4 # macro +FW_DSTATE_SOC_LIV_MIN_BIT = 5 # macro +FW_DSTATE_SOC_PLL_PWRDN_BIT = 6 # macro +FW_DSTATE_MEM_PLL_PWRDN_BIT = 7 # macro +FW_DSTATE_MALL_ALLOC_BIT = 8 # macro +FW_DSTATE_MEM_PSI_BIT = 9 # macro +FW_DSTATE_HSR_NON_STROBE_BIT = 10 # macro +FW_DSTATE_MP0_ENTER_WFI_BIT = 11 # macro +FW_DSTATE_U_ULV_BIT = 12 # macro +FW_DSTATE_MALL_FLUSH_BIT = 13 # macro +FW_DSTATE_SOC_PSI_BIT = 14 # macro +FW_DSTATE_U_PSI_BIT = 15 # macro +FW_DSTATE_UCP_DS_BIT = 16 # macro +FW_DSTATE_CSRCLK_DS_BIT = 17 # macro +FW_DSTATE_MMHUB_INTERLOCK_BIT = 18 # macro +FW_DSTATE_D0i3_2_QUIET_FW_BIT = 19 # macro +FW_DSTATE_CLDO_PRG_BIT = 20 # macro +FW_DSTATE_DF_PLL_PWRDN_BIT = 21 # macro +FW_DSTATE_U_LOW_PWR_MODE_EN_BIT = 22 # macro +FW_DSTATE_GFX_PSI6_BIT = 23 # macro +FW_DSTATE_GFX_VR_PWR_STAGE_BIT = 24 # macro +LED_DISPLAY_GFX_DPM_BIT = 0 # macro +LED_DISPLAY_PCIE_BIT = 1 # macro +LED_DISPLAY_ERROR_BIT = 2 # macro +MEM_TEMP_READ_OUT_OF_BAND_BIT = 0 # macro +MEM_TEMP_READ_IN_BAND_REFRESH_BIT = 1 # macro +MEM_TEMP_READ_IN_BAND_DUMMY_PSTATE_BIT = 2 # macro +NUM_I2C_CONTROLLERS = 8 # macro +I2C_CONTROLLER_ENABLED = 1 # macro +I2C_CONTROLLER_DISABLED = 0 # macro +MAX_SW_I2C_COMMANDS = 24 # macro +CMDCONFIG_STOP_BIT = 0 # macro +CMDCONFIG_RESTART_BIT = 1 # macro +CMDCONFIG_READWRITE_BIT = 2 # macro +CMDCONFIG_STOP_MASK = (1<<0) # macro +CMDCONFIG_RESTART_MASK = (1<<1) # macro +CMDCONFIG_READWRITE_MASK = (1<<2) # macro +PP_NUM_RTAVFS_PWL_ZONES = 5 # macro +PP_OD_FEATURE_GFX_VF_CURVE_BIT = 0 # macro +PP_OD_FEATURE_PPT_BIT = 2 # macro +PP_OD_FEATURE_FAN_CURVE_BIT = 3 # macro +PP_OD_FEATURE_GFXCLK_BIT = 7 # macro +PP_OD_FEATURE_UCLK_BIT = 8 # macro +PP_OD_FEATURE_ZERO_FAN_BIT = 9 # macro +PP_OD_FEATURE_TEMPERATURE_BIT = 10 # macro +PP_OD_FEATURE_COUNT = 13 # macro +PP_NUM_OD_VF_CURVE_POINTS = 5 + 1 # macro +INVALID_BOARD_GPIO = 0xFF # macro +MARKETING_BASE_CLOCKS = 0 # macro +MARKETING_GAME_CLOCKS = 1 # macro +MARKETING_BOOST_CLOCKS = 2 # macro +NUM_WM_RANGES = 4 # macro +WORKLOAD_PPLIB_DEFAULT_BIT = 0 # macro +WORKLOAD_PPLIB_FULL_SCREEN_3D_BIT = 1 # macro +WORKLOAD_PPLIB_POWER_SAVING_BIT = 2 # macro +WORKLOAD_PPLIB_VIDEO_BIT = 3 # macro +WORKLOAD_PPLIB_VR_BIT = 4 # macro +WORKLOAD_PPLIB_COMPUTE_BIT = 5 # macro +WORKLOAD_PPLIB_CUSTOM_BIT = 6 # macro +WORKLOAD_PPLIB_WINDOW_3D_BIT = 7 # macro +WORKLOAD_PPLIB_COUNT = 8 # macro +TABLE_TRANSFER_OK = 0x0 # macro +TABLE_TRANSFER_FAILED = 0xFF # macro +TABLE_TRANSFER_PENDING = 0xAB # macro +TABLE_PPTABLE = 0 # macro +TABLE_COMBO_PPTABLE = 1 # macro +TABLE_WATERMARKS = 2 # macro +TABLE_AVFS_PSM_DEBUG = 3 # macro +TABLE_PMSTATUSLOG = 4 # macro +TABLE_SMU_METRICS = 5 # macro +TABLE_DRIVER_SMU_CONFIG = 6 # macro +TABLE_ACTIVITY_MONITOR_COEFF = 7 # macro +TABLE_OVERDRIVE = 8 # macro +TABLE_I2C_COMMANDS = 9 # macro +TABLE_DRIVER_INFO = 10 # macro +TABLE_ECCINFO = 11 # macro +TABLE_WIFIBAND = 12 # macro +TABLE_COUNT = 13 # macro +IH_INTERRUPT_ID_TO_DRIVER = 0xFE # macro +IH_INTERRUPT_CONTEXT_ID_BACO = 0x2 # macro +IH_INTERRUPT_CONTEXT_ID_AC = 0x3 # macro +IH_INTERRUPT_CONTEXT_ID_DC = 0x4 # macro +IH_INTERRUPT_CONTEXT_ID_AUDIO_D0 = 0x5 # macro +IH_INTERRUPT_CONTEXT_ID_AUDIO_D3 = 0x6 # macro +IH_INTERRUPT_CONTEXT_ID_THERMAL_THROTTLING = 0x7 # macro +IH_INTERRUPT_CONTEXT_ID_FAN_ABNORMAL = 0x8 # macro +IH_INTERRUPT_CONTEXT_ID_FAN_RECOVERY = 0x9 # macro + +# values for enumeration 'c__EA_FEATURE_PWR_DOMAIN_e' +c__EA_FEATURE_PWR_DOMAIN_e__enumvalues = { + 0: 'FEATURE_PWR_ALL', + 1: 'FEATURE_PWR_S5', + 2: 'FEATURE_PWR_BACO', + 3: 'FEATURE_PWR_SOC', + 4: 'FEATURE_PWR_GFX', + 5: 'FEATURE_PWR_DOMAIN_COUNT', +} +FEATURE_PWR_ALL = 0 +FEATURE_PWR_S5 = 1 +FEATURE_PWR_BACO = 2 +FEATURE_PWR_SOC = 3 +FEATURE_PWR_GFX = 4 +FEATURE_PWR_DOMAIN_COUNT = 5 +c__EA_FEATURE_PWR_DOMAIN_e = ctypes.c_uint32 # enum +FEATURE_PWR_DOMAIN_e = c__EA_FEATURE_PWR_DOMAIN_e +FEATURE_PWR_DOMAIN_e__enumvalues = c__EA_FEATURE_PWR_DOMAIN_e__enumvalues + +# values for enumeration 'c__EA_SVI_PSI_e' +c__EA_SVI_PSI_e__enumvalues = { + 0: 'SVI_PSI_0', + 1: 'SVI_PSI_1', + 2: 'SVI_PSI_2', + 3: 'SVI_PSI_3', + 4: 'SVI_PSI_4', + 5: 'SVI_PSI_5', + 6: 'SVI_PSI_6', + 7: 'SVI_PSI_7', +} +SVI_PSI_0 = 0 +SVI_PSI_1 = 1 +SVI_PSI_2 = 2 +SVI_PSI_3 = 3 +SVI_PSI_4 = 4 +SVI_PSI_5 = 5 +SVI_PSI_6 = 6 +SVI_PSI_7 = 7 +c__EA_SVI_PSI_e = ctypes.c_uint32 # enum +SVI_PSI_e = c__EA_SVI_PSI_e +SVI_PSI_e__enumvalues = c__EA_SVI_PSI_e__enumvalues + +# values for enumeration 'c__EA_SMARTSHIFT_VERSION_e' +c__EA_SMARTSHIFT_VERSION_e__enumvalues = { + 0: 'SMARTSHIFT_VERSION_1', + 1: 'SMARTSHIFT_VERSION_2', + 2: 'SMARTSHIFT_VERSION_3', +} +SMARTSHIFT_VERSION_1 = 0 +SMARTSHIFT_VERSION_2 = 1 +SMARTSHIFT_VERSION_3 = 2 +c__EA_SMARTSHIFT_VERSION_e = ctypes.c_uint32 # enum +SMARTSHIFT_VERSION_e = c__EA_SMARTSHIFT_VERSION_e +SMARTSHIFT_VERSION_e__enumvalues = c__EA_SMARTSHIFT_VERSION_e__enumvalues + +# values for enumeration 'c__EA_FOPT_CALC_e' +c__EA_FOPT_CALC_e__enumvalues = { + 0: 'FOPT_CALC_AC_CALC_DC', + 1: 'FOPT_PPTABLE_AC_CALC_DC', + 2: 'FOPT_CALC_AC_PPTABLE_DC', + 3: 'FOPT_PPTABLE_AC_PPTABLE_DC', +} +FOPT_CALC_AC_CALC_DC = 0 +FOPT_PPTABLE_AC_CALC_DC = 1 +FOPT_CALC_AC_PPTABLE_DC = 2 +FOPT_PPTABLE_AC_PPTABLE_DC = 3 +c__EA_FOPT_CALC_e = ctypes.c_uint32 # enum +FOPT_CALC_e = c__EA_FOPT_CALC_e +FOPT_CALC_e__enumvalues = c__EA_FOPT_CALC_e__enumvalues + +# values for enumeration 'c__EA_DRAM_BIT_WIDTH_TYPE_e' +c__EA_DRAM_BIT_WIDTH_TYPE_e__enumvalues = { + 0: 'DRAM_BIT_WIDTH_DISABLED', + 8: 'DRAM_BIT_WIDTH_X_8', + 16: 'DRAM_BIT_WIDTH_X_16', + 32: 'DRAM_BIT_WIDTH_X_32', + 64: 'DRAM_BIT_WIDTH_X_64', + 128: 'DRAM_BIT_WIDTH_X_128', + 129: 'DRAM_BIT_WIDTH_COUNT', +} +DRAM_BIT_WIDTH_DISABLED = 0 +DRAM_BIT_WIDTH_X_8 = 8 +DRAM_BIT_WIDTH_X_16 = 16 +DRAM_BIT_WIDTH_X_32 = 32 +DRAM_BIT_WIDTH_X_64 = 64 +DRAM_BIT_WIDTH_X_128 = 128 +DRAM_BIT_WIDTH_COUNT = 129 +c__EA_DRAM_BIT_WIDTH_TYPE_e = ctypes.c_uint32 # enum +DRAM_BIT_WIDTH_TYPE_e = c__EA_DRAM_BIT_WIDTH_TYPE_e +DRAM_BIT_WIDTH_TYPE_e__enumvalues = c__EA_DRAM_BIT_WIDTH_TYPE_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerPort_e' +c__EA_I2cControllerPort_e__enumvalues = { + 0: 'I2C_CONTROLLER_PORT_0', + 1: 'I2C_CONTROLLER_PORT_1', + 2: 'I2C_CONTROLLER_PORT_COUNT', +} +I2C_CONTROLLER_PORT_0 = 0 +I2C_CONTROLLER_PORT_1 = 1 +I2C_CONTROLLER_PORT_COUNT = 2 +c__EA_I2cControllerPort_e = ctypes.c_uint32 # enum +I2cControllerPort_e = c__EA_I2cControllerPort_e +I2cControllerPort_e__enumvalues = c__EA_I2cControllerPort_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerName_e' +c__EA_I2cControllerName_e__enumvalues = { + 0: 'I2C_CONTROLLER_NAME_VR_GFX', + 1: 'I2C_CONTROLLER_NAME_VR_SOC', + 2: 'I2C_CONTROLLER_NAME_VR_VMEMP', + 3: 'I2C_CONTROLLER_NAME_VR_VDDIO', + 4: 'I2C_CONTROLLER_NAME_LIQUID0', + 5: 'I2C_CONTROLLER_NAME_LIQUID1', + 6: 'I2C_CONTROLLER_NAME_PLX', + 7: 'I2C_CONTROLLER_NAME_FAN_INTAKE', + 8: 'I2C_CONTROLLER_NAME_COUNT', +} +I2C_CONTROLLER_NAME_VR_GFX = 0 +I2C_CONTROLLER_NAME_VR_SOC = 1 +I2C_CONTROLLER_NAME_VR_VMEMP = 2 +I2C_CONTROLLER_NAME_VR_VDDIO = 3 +I2C_CONTROLLER_NAME_LIQUID0 = 4 +I2C_CONTROLLER_NAME_LIQUID1 = 5 +I2C_CONTROLLER_NAME_PLX = 6 +I2C_CONTROLLER_NAME_FAN_INTAKE = 7 +I2C_CONTROLLER_NAME_COUNT = 8 +c__EA_I2cControllerName_e = ctypes.c_uint32 # enum +I2cControllerName_e = c__EA_I2cControllerName_e +I2cControllerName_e__enumvalues = c__EA_I2cControllerName_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerThrottler_e' +c__EA_I2cControllerThrottler_e__enumvalues = { + 0: 'I2C_CONTROLLER_THROTTLER_TYPE_NONE', + 1: 'I2C_CONTROLLER_THROTTLER_VR_GFX', + 2: 'I2C_CONTROLLER_THROTTLER_VR_SOC', + 3: 'I2C_CONTROLLER_THROTTLER_VR_VMEMP', + 4: 'I2C_CONTROLLER_THROTTLER_VR_VDDIO', + 5: 'I2C_CONTROLLER_THROTTLER_LIQUID0', + 6: 'I2C_CONTROLLER_THROTTLER_LIQUID1', + 7: 'I2C_CONTROLLER_THROTTLER_PLX', + 8: 'I2C_CONTROLLER_THROTTLER_FAN_INTAKE', + 9: 'I2C_CONTROLLER_THROTTLER_INA3221', + 10: 'I2C_CONTROLLER_THROTTLER_COUNT', +} +I2C_CONTROLLER_THROTTLER_TYPE_NONE = 0 +I2C_CONTROLLER_THROTTLER_VR_GFX = 1 +I2C_CONTROLLER_THROTTLER_VR_SOC = 2 +I2C_CONTROLLER_THROTTLER_VR_VMEMP = 3 +I2C_CONTROLLER_THROTTLER_VR_VDDIO = 4 +I2C_CONTROLLER_THROTTLER_LIQUID0 = 5 +I2C_CONTROLLER_THROTTLER_LIQUID1 = 6 +I2C_CONTROLLER_THROTTLER_PLX = 7 +I2C_CONTROLLER_THROTTLER_FAN_INTAKE = 8 +I2C_CONTROLLER_THROTTLER_INA3221 = 9 +I2C_CONTROLLER_THROTTLER_COUNT = 10 +c__EA_I2cControllerThrottler_e = ctypes.c_uint32 # enum +I2cControllerThrottler_e = c__EA_I2cControllerThrottler_e +I2cControllerThrottler_e__enumvalues = c__EA_I2cControllerThrottler_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerProtocol_e' +c__EA_I2cControllerProtocol_e__enumvalues = { + 0: 'I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5', + 1: 'I2C_CONTROLLER_PROTOCOL_VR_IR35217', + 2: 'I2C_CONTROLLER_PROTOCOL_TMP_MAX31875', + 3: 'I2C_CONTROLLER_PROTOCOL_INA3221', + 4: 'I2C_CONTROLLER_PROTOCOL_TMP_MAX6604', + 5: 'I2C_CONTROLLER_PROTOCOL_COUNT', +} +I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5 = 0 +I2C_CONTROLLER_PROTOCOL_VR_IR35217 = 1 +I2C_CONTROLLER_PROTOCOL_TMP_MAX31875 = 2 +I2C_CONTROLLER_PROTOCOL_INA3221 = 3 +I2C_CONTROLLER_PROTOCOL_TMP_MAX6604 = 4 +I2C_CONTROLLER_PROTOCOL_COUNT = 5 +c__EA_I2cControllerProtocol_e = ctypes.c_uint32 # enum +I2cControllerProtocol_e = c__EA_I2cControllerProtocol_e +I2cControllerProtocol_e__enumvalues = c__EA_I2cControllerProtocol_e__enumvalues +class struct_c__SA_I2cControllerConfig_t(Structure): + pass + +struct_c__SA_I2cControllerConfig_t._pack_ = 1 # source:False +struct_c__SA_I2cControllerConfig_t._fields_ = [ + ('Enabled', ctypes.c_ubyte), + ('Speed', ctypes.c_ubyte), + ('SlaveAddress', ctypes.c_ubyte), + ('ControllerPort', ctypes.c_ubyte), + ('ControllerName', ctypes.c_ubyte), + ('ThermalThrotter', ctypes.c_ubyte), + ('I2cProtocol', ctypes.c_ubyte), + ('PaddingConfig', ctypes.c_ubyte), +] + +I2cControllerConfig_t = struct_c__SA_I2cControllerConfig_t + +# values for enumeration 'c__EA_I2cPort_e' +c__EA_I2cPort_e__enumvalues = { + 0: 'I2C_PORT_SVD_SCL', + 1: 'I2C_PORT_GPIO', +} +I2C_PORT_SVD_SCL = 0 +I2C_PORT_GPIO = 1 +c__EA_I2cPort_e = ctypes.c_uint32 # enum +I2cPort_e = c__EA_I2cPort_e +I2cPort_e__enumvalues = c__EA_I2cPort_e__enumvalues + +# values for enumeration 'c__EA_I2cSpeed_e' +c__EA_I2cSpeed_e__enumvalues = { + 0: 'I2C_SPEED_FAST_50K', + 1: 'I2C_SPEED_FAST_100K', + 2: 'I2C_SPEED_FAST_400K', + 3: 'I2C_SPEED_FAST_PLUS_1M', + 4: 'I2C_SPEED_HIGH_1M', + 5: 'I2C_SPEED_HIGH_2M', + 6: 'I2C_SPEED_COUNT', +} +I2C_SPEED_FAST_50K = 0 +I2C_SPEED_FAST_100K = 1 +I2C_SPEED_FAST_400K = 2 +I2C_SPEED_FAST_PLUS_1M = 3 +I2C_SPEED_HIGH_1M = 4 +I2C_SPEED_HIGH_2M = 5 +I2C_SPEED_COUNT = 6 +c__EA_I2cSpeed_e = ctypes.c_uint32 # enum +I2cSpeed_e = c__EA_I2cSpeed_e +I2cSpeed_e__enumvalues = c__EA_I2cSpeed_e__enumvalues + +# values for enumeration 'c__EA_I2cCmdType_e' +c__EA_I2cCmdType_e__enumvalues = { + 0: 'I2C_CMD_READ', + 1: 'I2C_CMD_WRITE', + 2: 'I2C_CMD_COUNT', +} +I2C_CMD_READ = 0 +I2C_CMD_WRITE = 1 +I2C_CMD_COUNT = 2 +c__EA_I2cCmdType_e = ctypes.c_uint32 # enum +I2cCmdType_e = c__EA_I2cCmdType_e +I2cCmdType_e__enumvalues = c__EA_I2cCmdType_e__enumvalues +class struct_c__SA_SwI2cCmd_t(Structure): + pass + +struct_c__SA_SwI2cCmd_t._pack_ = 1 # source:False +struct_c__SA_SwI2cCmd_t._fields_ = [ + ('ReadWriteData', ctypes.c_ubyte), + ('CmdConfig', ctypes.c_ubyte), +] + +SwI2cCmd_t = struct_c__SA_SwI2cCmd_t +class struct_c__SA_SwI2cRequest_t(Structure): + pass + +struct_c__SA_SwI2cRequest_t._pack_ = 1 # source:False +struct_c__SA_SwI2cRequest_t._fields_ = [ + ('I2CcontrollerPort', ctypes.c_ubyte), + ('I2CSpeed', ctypes.c_ubyte), + ('SlaveAddress', ctypes.c_ubyte), + ('NumCmds', ctypes.c_ubyte), + ('SwI2cCmds', struct_c__SA_SwI2cCmd_t * 24), +] + +SwI2cRequest_t = struct_c__SA_SwI2cRequest_t +class struct_c__SA_SwI2cRequestExternal_t(Structure): + pass + +struct_c__SA_SwI2cRequestExternal_t._pack_ = 1 # source:False +struct_c__SA_SwI2cRequestExternal_t._fields_ = [ + ('SwI2cRequest', SwI2cRequest_t), + ('Spare', ctypes.c_uint32 * 8), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SwI2cRequestExternal_t = struct_c__SA_SwI2cRequestExternal_t +class struct_c__SA_EccInfo_t(Structure): + pass + +struct_c__SA_EccInfo_t._pack_ = 1 # source:False +struct_c__SA_EccInfo_t._fields_ = [ + ('mca_umc_status', ctypes.c_uint64), + ('mca_umc_addr', ctypes.c_uint64), + ('ce_count_lo_chip', ctypes.c_uint16), + ('ce_count_hi_chip', ctypes.c_uint16), + ('eccPadding', ctypes.c_uint32), +] + +EccInfo_t = struct_c__SA_EccInfo_t +class struct_c__SA_EccInfoTable_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('EccInfo', struct_c__SA_EccInfo_t * 24), + ] + +EccInfoTable_t = struct_c__SA_EccInfoTable_t + +# values for enumeration 'c__EA_D3HOTSequence_e' +c__EA_D3HOTSequence_e__enumvalues = { + 0: 'BACO_SEQUENCE', + 1: 'MSR_SEQUENCE', + 2: 'BAMACO_SEQUENCE', + 3: 'ULPS_SEQUENCE', + 4: 'D3HOT_SEQUENCE_COUNT', +} +BACO_SEQUENCE = 0 +MSR_SEQUENCE = 1 +BAMACO_SEQUENCE = 2 +ULPS_SEQUENCE = 3 +D3HOT_SEQUENCE_COUNT = 4 +c__EA_D3HOTSequence_e = ctypes.c_uint32 # enum +D3HOTSequence_e = c__EA_D3HOTSequence_e +D3HOTSequence_e__enumvalues = c__EA_D3HOTSequence_e__enumvalues + +# values for enumeration 'c__EA_PowerGatingMode_e' +c__EA_PowerGatingMode_e__enumvalues = { + 0: 'PG_DYNAMIC_MODE', + 1: 'PG_STATIC_MODE', +} +PG_DYNAMIC_MODE = 0 +PG_STATIC_MODE = 1 +c__EA_PowerGatingMode_e = ctypes.c_uint32 # enum +PowerGatingMode_e = c__EA_PowerGatingMode_e +PowerGatingMode_e__enumvalues = c__EA_PowerGatingMode_e__enumvalues + +# values for enumeration 'c__EA_PowerGatingSettings_e' +c__EA_PowerGatingSettings_e__enumvalues = { + 0: 'PG_POWER_DOWN', + 1: 'PG_POWER_UP', +} +PG_POWER_DOWN = 0 +PG_POWER_UP = 1 +c__EA_PowerGatingSettings_e = ctypes.c_uint32 # enum +PowerGatingSettings_e = c__EA_PowerGatingSettings_e +PowerGatingSettings_e__enumvalues = c__EA_PowerGatingSettings_e__enumvalues +class struct_c__SA_QuadraticInt_t(Structure): + pass + +struct_c__SA_QuadraticInt_t._pack_ = 1 # source:False +struct_c__SA_QuadraticInt_t._fields_ = [ + ('a', ctypes.c_uint32), + ('b', ctypes.c_uint32), + ('c', ctypes.c_uint32), +] + +QuadraticInt_t = struct_c__SA_QuadraticInt_t +class struct_c__SA_LinearInt_t(Structure): + pass + +struct_c__SA_LinearInt_t._pack_ = 1 # source:False +struct_c__SA_LinearInt_t._fields_ = [ + ('m', ctypes.c_uint32), + ('b', ctypes.c_uint32), +] + +LinearInt_t = struct_c__SA_LinearInt_t +class struct_c__SA_DroopInt_t(Structure): + pass + +struct_c__SA_DroopInt_t._pack_ = 1 # source:False +struct_c__SA_DroopInt_t._fields_ = [ + ('a', ctypes.c_uint32), + ('b', ctypes.c_uint32), + ('c', ctypes.c_uint32), +] + +DroopInt_t = struct_c__SA_DroopInt_t + +# values for enumeration 'c__EA_DCS_ARCH_e' +c__EA_DCS_ARCH_e__enumvalues = { + 0: 'DCS_ARCH_DISABLED', + 1: 'DCS_ARCH_FADCS', + 2: 'DCS_ARCH_ASYNC', +} +DCS_ARCH_DISABLED = 0 +DCS_ARCH_FADCS = 1 +DCS_ARCH_ASYNC = 2 +c__EA_DCS_ARCH_e = ctypes.c_uint32 # enum +DCS_ARCH_e = c__EA_DCS_ARCH_e +DCS_ARCH_e__enumvalues = c__EA_DCS_ARCH_e__enumvalues + +# values for enumeration 'c__EA_PPCLK_e' +c__EA_PPCLK_e__enumvalues = { + 0: 'PPCLK_GFXCLK', + 1: 'PPCLK_SOCCLK', + 2: 'PPCLK_UCLK', + 3: 'PPCLK_FCLK', + 4: 'PPCLK_DCLK_0', + 5: 'PPCLK_VCLK_0', + 6: 'PPCLK_DCLK_1', + 7: 'PPCLK_VCLK_1', + 8: 'PPCLK_DISPCLK', + 9: 'PPCLK_DPPCLK', + 10: 'PPCLK_DPREFCLK', + 11: 'PPCLK_DCFCLK', + 12: 'PPCLK_DTBCLK', + 13: 'PPCLK_COUNT', +} +PPCLK_GFXCLK = 0 +PPCLK_SOCCLK = 1 +PPCLK_UCLK = 2 +PPCLK_FCLK = 3 +PPCLK_DCLK_0 = 4 +PPCLK_VCLK_0 = 5 +PPCLK_DCLK_1 = 6 +PPCLK_VCLK_1 = 7 +PPCLK_DISPCLK = 8 +PPCLK_DPPCLK = 9 +PPCLK_DPREFCLK = 10 +PPCLK_DCFCLK = 11 +PPCLK_DTBCLK = 12 +PPCLK_COUNT = 13 +c__EA_PPCLK_e = ctypes.c_uint32 # enum +PPCLK_e = c__EA_PPCLK_e +PPCLK_e__enumvalues = c__EA_PPCLK_e__enumvalues + +# values for enumeration 'c__EA_VOLTAGE_MODE_e' +c__EA_VOLTAGE_MODE_e__enumvalues = { + 0: 'VOLTAGE_MODE_PPTABLE', + 1: 'VOLTAGE_MODE_FUSES', + 2: 'VOLTAGE_MODE_COUNT', +} +VOLTAGE_MODE_PPTABLE = 0 +VOLTAGE_MODE_FUSES = 1 +VOLTAGE_MODE_COUNT = 2 +c__EA_VOLTAGE_MODE_e = ctypes.c_uint32 # enum +VOLTAGE_MODE_e = c__EA_VOLTAGE_MODE_e +VOLTAGE_MODE_e__enumvalues = c__EA_VOLTAGE_MODE_e__enumvalues + +# values for enumeration 'c__EA_AVFS_VOLTAGE_TYPE_e' +c__EA_AVFS_VOLTAGE_TYPE_e__enumvalues = { + 0: 'AVFS_VOLTAGE_GFX', + 1: 'AVFS_VOLTAGE_SOC', + 2: 'AVFS_VOLTAGE_COUNT', +} +AVFS_VOLTAGE_GFX = 0 +AVFS_VOLTAGE_SOC = 1 +AVFS_VOLTAGE_COUNT = 2 +c__EA_AVFS_VOLTAGE_TYPE_e = ctypes.c_uint32 # enum +AVFS_VOLTAGE_TYPE_e = c__EA_AVFS_VOLTAGE_TYPE_e +AVFS_VOLTAGE_TYPE_e__enumvalues = c__EA_AVFS_VOLTAGE_TYPE_e__enumvalues + +# values for enumeration 'c__EA_AVFS_TEMP_e' +c__EA_AVFS_TEMP_e__enumvalues = { + 0: 'AVFS_TEMP_COLD', + 1: 'AVFS_TEMP_HOT', + 2: 'AVFS_TEMP_COUNT', +} +AVFS_TEMP_COLD = 0 +AVFS_TEMP_HOT = 1 +AVFS_TEMP_COUNT = 2 +c__EA_AVFS_TEMP_e = ctypes.c_uint32 # enum +AVFS_TEMP_e = c__EA_AVFS_TEMP_e +AVFS_TEMP_e__enumvalues = c__EA_AVFS_TEMP_e__enumvalues + +# values for enumeration 'c__EA_AVFS_D_e' +c__EA_AVFS_D_e__enumvalues = { + 0: 'AVFS_D_G', + 1: 'AVFS_D_M_B', + 2: 'AVFS_D_M_S', + 3: 'AVFS_D_COUNT', +} +AVFS_D_G = 0 +AVFS_D_M_B = 1 +AVFS_D_M_S = 2 +AVFS_D_COUNT = 3 +c__EA_AVFS_D_e = ctypes.c_uint32 # enum +AVFS_D_e = c__EA_AVFS_D_e +AVFS_D_e__enumvalues = c__EA_AVFS_D_e__enumvalues + +# values for enumeration 'c__EA_UCLK_DIV_e' +c__EA_UCLK_DIV_e__enumvalues = { + 0: 'UCLK_DIV_BY_1', + 1: 'UCLK_DIV_BY_2', + 2: 'UCLK_DIV_BY_4', + 3: 'UCLK_DIV_BY_8', +} +UCLK_DIV_BY_1 = 0 +UCLK_DIV_BY_2 = 1 +UCLK_DIV_BY_4 = 2 +UCLK_DIV_BY_8 = 3 +c__EA_UCLK_DIV_e = ctypes.c_uint32 # enum +UCLK_DIV_e = c__EA_UCLK_DIV_e +UCLK_DIV_e__enumvalues = c__EA_UCLK_DIV_e__enumvalues + +# values for enumeration 'c__EA_GpioIntPolarity_e' +c__EA_GpioIntPolarity_e__enumvalues = { + 0: 'GPIO_INT_POLARITY_ACTIVE_LOW', + 1: 'GPIO_INT_POLARITY_ACTIVE_HIGH', +} +GPIO_INT_POLARITY_ACTIVE_LOW = 0 +GPIO_INT_POLARITY_ACTIVE_HIGH = 1 +c__EA_GpioIntPolarity_e = ctypes.c_uint32 # enum +GpioIntPolarity_e = c__EA_GpioIntPolarity_e +GpioIntPolarity_e__enumvalues = c__EA_GpioIntPolarity_e__enumvalues + +# values for enumeration 'c__EA_PwrConfig_e' +c__EA_PwrConfig_e__enumvalues = { + 0: 'PWR_CONFIG_TDP', + 1: 'PWR_CONFIG_TGP', + 2: 'PWR_CONFIG_TCP_ESTIMATED', + 3: 'PWR_CONFIG_TCP_MEASURED', +} +PWR_CONFIG_TDP = 0 +PWR_CONFIG_TGP = 1 +PWR_CONFIG_TCP_ESTIMATED = 2 +PWR_CONFIG_TCP_MEASURED = 3 +c__EA_PwrConfig_e = ctypes.c_uint32 # enum +PwrConfig_e = c__EA_PwrConfig_e +PwrConfig_e__enumvalues = c__EA_PwrConfig_e__enumvalues +class struct_c__SA_DpmDescriptor_t(Structure): + pass + +struct_c__SA_DpmDescriptor_t._pack_ = 1 # source:False +struct_c__SA_DpmDescriptor_t._fields_ = [ + ('Padding', ctypes.c_ubyte), + ('SnapToDiscrete', ctypes.c_ubyte), + ('NumDiscreteLevels', ctypes.c_ubyte), + ('CalculateFopt', ctypes.c_ubyte), + ('ConversionToAvfsClk', LinearInt_t), + ('Padding3', ctypes.c_uint32 * 3), + ('Padding4', ctypes.c_uint16), + ('FoptimalDc', ctypes.c_uint16), + ('FoptimalAc', ctypes.c_uint16), + ('Padding2', ctypes.c_uint16), +] + +DpmDescriptor_t = struct_c__SA_DpmDescriptor_t + +# values for enumeration 'c__EA_PPT_THROTTLER_e' +c__EA_PPT_THROTTLER_e__enumvalues = { + 0: 'PPT_THROTTLER_PPT0', + 1: 'PPT_THROTTLER_PPT1', + 2: 'PPT_THROTTLER_PPT2', + 3: 'PPT_THROTTLER_PPT3', + 4: 'PPT_THROTTLER_COUNT', +} +PPT_THROTTLER_PPT0 = 0 +PPT_THROTTLER_PPT1 = 1 +PPT_THROTTLER_PPT2 = 2 +PPT_THROTTLER_PPT3 = 3 +PPT_THROTTLER_COUNT = 4 +c__EA_PPT_THROTTLER_e = ctypes.c_uint32 # enum +PPT_THROTTLER_e = c__EA_PPT_THROTTLER_e +PPT_THROTTLER_e__enumvalues = c__EA_PPT_THROTTLER_e__enumvalues + +# values for enumeration 'c__EA_TEMP_e' +c__EA_TEMP_e__enumvalues = { + 0: 'TEMP_EDGE', + 1: 'TEMP_HOTSPOT', + 2: 'TEMP_HOTSPOT_G', + 3: 'TEMP_HOTSPOT_M', + 4: 'TEMP_MEM', + 5: 'TEMP_VR_GFX', + 6: 'TEMP_VR_MEM0', + 7: 'TEMP_VR_MEM1', + 8: 'TEMP_VR_SOC', + 9: 'TEMP_VR_U', + 10: 'TEMP_LIQUID0', + 11: 'TEMP_LIQUID1', + 12: 'TEMP_PLX', + 13: 'TEMP_COUNT', +} +TEMP_EDGE = 0 +TEMP_HOTSPOT = 1 +TEMP_HOTSPOT_G = 2 +TEMP_HOTSPOT_M = 3 +TEMP_MEM = 4 +TEMP_VR_GFX = 5 +TEMP_VR_MEM0 = 6 +TEMP_VR_MEM1 = 7 +TEMP_VR_SOC = 8 +TEMP_VR_U = 9 +TEMP_LIQUID0 = 10 +TEMP_LIQUID1 = 11 +TEMP_PLX = 12 +TEMP_COUNT = 13 +c__EA_TEMP_e = ctypes.c_uint32 # enum +TEMP_e = c__EA_TEMP_e +TEMP_e__enumvalues = c__EA_TEMP_e__enumvalues + +# values for enumeration 'c__EA_TDC_THROTTLER_e' +c__EA_TDC_THROTTLER_e__enumvalues = { + 0: 'TDC_THROTTLER_GFX', + 1: 'TDC_THROTTLER_SOC', + 2: 'TDC_THROTTLER_U', + 3: 'TDC_THROTTLER_COUNT', +} +TDC_THROTTLER_GFX = 0 +TDC_THROTTLER_SOC = 1 +TDC_THROTTLER_U = 2 +TDC_THROTTLER_COUNT = 3 +c__EA_TDC_THROTTLER_e = ctypes.c_uint32 # enum +TDC_THROTTLER_e = c__EA_TDC_THROTTLER_e +TDC_THROTTLER_e__enumvalues = c__EA_TDC_THROTTLER_e__enumvalues + +# values for enumeration 'c__EA_SVI_PLANE_e' +c__EA_SVI_PLANE_e__enumvalues = { + 0: 'SVI_PLANE_GFX', + 1: 'SVI_PLANE_SOC', + 2: 'SVI_PLANE_VMEMP', + 3: 'SVI_PLANE_VDDIO_MEM', + 4: 'SVI_PLANE_U', + 5: 'SVI_PLANE_COUNT', +} +SVI_PLANE_GFX = 0 +SVI_PLANE_SOC = 1 +SVI_PLANE_VMEMP = 2 +SVI_PLANE_VDDIO_MEM = 3 +SVI_PLANE_U = 4 +SVI_PLANE_COUNT = 5 +c__EA_SVI_PLANE_e = ctypes.c_uint32 # enum +SVI_PLANE_e = c__EA_SVI_PLANE_e +SVI_PLANE_e__enumvalues = c__EA_SVI_PLANE_e__enumvalues + +# values for enumeration 'c__EA_PMFW_VOLT_PLANE_e' +c__EA_PMFW_VOLT_PLANE_e__enumvalues = { + 0: 'PMFW_VOLT_PLANE_GFX', + 1: 'PMFW_VOLT_PLANE_SOC', + 2: 'PMFW_VOLT_PLANE_COUNT', +} +PMFW_VOLT_PLANE_GFX = 0 +PMFW_VOLT_PLANE_SOC = 1 +PMFW_VOLT_PLANE_COUNT = 2 +c__EA_PMFW_VOLT_PLANE_e = ctypes.c_uint32 # enum +PMFW_VOLT_PLANE_e = c__EA_PMFW_VOLT_PLANE_e +PMFW_VOLT_PLANE_e__enumvalues = c__EA_PMFW_VOLT_PLANE_e__enumvalues + +# values for enumeration 'c__EA_CUSTOMER_VARIANT_e' +c__EA_CUSTOMER_VARIANT_e__enumvalues = { + 0: 'CUSTOMER_VARIANT_ROW', + 1: 'CUSTOMER_VARIANT_FALCON', + 2: 'CUSTOMER_VARIANT_COUNT', +} +CUSTOMER_VARIANT_ROW = 0 +CUSTOMER_VARIANT_FALCON = 1 +CUSTOMER_VARIANT_COUNT = 2 +c__EA_CUSTOMER_VARIANT_e = ctypes.c_uint32 # enum +CUSTOMER_VARIANT_e = c__EA_CUSTOMER_VARIANT_e +CUSTOMER_VARIANT_e__enumvalues = c__EA_CUSTOMER_VARIANT_e__enumvalues + +# values for enumeration 'c__EA_POWER_SOURCE_e' +c__EA_POWER_SOURCE_e__enumvalues = { + 0: 'POWER_SOURCE_AC', + 1: 'POWER_SOURCE_DC', + 2: 'POWER_SOURCE_COUNT', +} +POWER_SOURCE_AC = 0 +POWER_SOURCE_DC = 1 +POWER_SOURCE_COUNT = 2 +c__EA_POWER_SOURCE_e = ctypes.c_uint32 # enum +POWER_SOURCE_e = c__EA_POWER_SOURCE_e +POWER_SOURCE_e__enumvalues = c__EA_POWER_SOURCE_e__enumvalues + +# values for enumeration 'c__EA_MEM_VENDOR_e' +c__EA_MEM_VENDOR_e__enumvalues = { + 0: 'MEM_VENDOR_PLACEHOLDER0', + 1: 'MEM_VENDOR_SAMSUNG', + 2: 'MEM_VENDOR_INFINEON', + 3: 'MEM_VENDOR_ELPIDA', + 4: 'MEM_VENDOR_ETRON', + 5: 'MEM_VENDOR_NANYA', + 6: 'MEM_VENDOR_HYNIX', + 7: 'MEM_VENDOR_MOSEL', + 8: 'MEM_VENDOR_WINBOND', + 9: 'MEM_VENDOR_ESMT', + 10: 'MEM_VENDOR_PLACEHOLDER1', + 11: 'MEM_VENDOR_PLACEHOLDER2', + 12: 'MEM_VENDOR_PLACEHOLDER3', + 13: 'MEM_VENDOR_PLACEHOLDER4', + 14: 'MEM_VENDOR_PLACEHOLDER5', + 15: 'MEM_VENDOR_MICRON', + 16: 'MEM_VENDOR_COUNT', +} +MEM_VENDOR_PLACEHOLDER0 = 0 +MEM_VENDOR_SAMSUNG = 1 +MEM_VENDOR_INFINEON = 2 +MEM_VENDOR_ELPIDA = 3 +MEM_VENDOR_ETRON = 4 +MEM_VENDOR_NANYA = 5 +MEM_VENDOR_HYNIX = 6 +MEM_VENDOR_MOSEL = 7 +MEM_VENDOR_WINBOND = 8 +MEM_VENDOR_ESMT = 9 +MEM_VENDOR_PLACEHOLDER1 = 10 +MEM_VENDOR_PLACEHOLDER2 = 11 +MEM_VENDOR_PLACEHOLDER3 = 12 +MEM_VENDOR_PLACEHOLDER4 = 13 +MEM_VENDOR_PLACEHOLDER5 = 14 +MEM_VENDOR_MICRON = 15 +MEM_VENDOR_COUNT = 16 +c__EA_MEM_VENDOR_e = ctypes.c_uint32 # enum +MEM_VENDOR_e = c__EA_MEM_VENDOR_e +MEM_VENDOR_e__enumvalues = c__EA_MEM_VENDOR_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_HW_FUSE_e' +c__EA_PP_GRTAVFS_HW_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_HW_CPO_CTL_ZONE0', + 1: 'PP_GRTAVFS_HW_CPO_CTL_ZONE1', + 2: 'PP_GRTAVFS_HW_CPO_CTL_ZONE2', + 3: 'PP_GRTAVFS_HW_CPO_CTL_ZONE3', + 4: 'PP_GRTAVFS_HW_CPO_CTL_ZONE4', + 5: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0', + 6: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0', + 7: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1', + 8: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1', + 9: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2', + 10: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2', + 11: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3', + 12: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3', + 13: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4', + 14: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4', + 15: 'PP_GRTAVFS_HW_ZONE0_VF', + 16: 'PP_GRTAVFS_HW_ZONE1_VF1', + 17: 'PP_GRTAVFS_HW_ZONE2_VF2', + 18: 'PP_GRTAVFS_HW_ZONE3_VF3', + 19: 'PP_GRTAVFS_HW_VOLTAGE_GB', + 20: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0', + 21: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1', + 22: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2', + 23: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3', + 24: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4', + 25: 'PP_GRTAVFS_HW_RESERVED_0', + 26: 'PP_GRTAVFS_HW_RESERVED_1', + 27: 'PP_GRTAVFS_HW_RESERVED_2', + 28: 'PP_GRTAVFS_HW_RESERVED_3', + 29: 'PP_GRTAVFS_HW_RESERVED_4', + 30: 'PP_GRTAVFS_HW_RESERVED_5', + 31: 'PP_GRTAVFS_HW_RESERVED_6', + 32: 'PP_GRTAVFS_HW_FUSE_COUNT', +} +PP_GRTAVFS_HW_CPO_CTL_ZONE0 = 0 +PP_GRTAVFS_HW_CPO_CTL_ZONE1 = 1 +PP_GRTAVFS_HW_CPO_CTL_ZONE2 = 2 +PP_GRTAVFS_HW_CPO_CTL_ZONE3 = 3 +PP_GRTAVFS_HW_CPO_CTL_ZONE4 = 4 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0 = 5 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0 = 6 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1 = 7 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1 = 8 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2 = 9 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2 = 10 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3 = 11 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3 = 12 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4 = 13 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4 = 14 +PP_GRTAVFS_HW_ZONE0_VF = 15 +PP_GRTAVFS_HW_ZONE1_VF1 = 16 +PP_GRTAVFS_HW_ZONE2_VF2 = 17 +PP_GRTAVFS_HW_ZONE3_VF3 = 18 +PP_GRTAVFS_HW_VOLTAGE_GB = 19 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0 = 20 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1 = 21 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2 = 22 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3 = 23 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4 = 24 +PP_GRTAVFS_HW_RESERVED_0 = 25 +PP_GRTAVFS_HW_RESERVED_1 = 26 +PP_GRTAVFS_HW_RESERVED_2 = 27 +PP_GRTAVFS_HW_RESERVED_3 = 28 +PP_GRTAVFS_HW_RESERVED_4 = 29 +PP_GRTAVFS_HW_RESERVED_5 = 30 +PP_GRTAVFS_HW_RESERVED_6 = 31 +PP_GRTAVFS_HW_FUSE_COUNT = 32 +c__EA_PP_GRTAVFS_HW_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_HW_FUSE_e = c__EA_PP_GRTAVFS_HW_FUSE_e +PP_GRTAVFS_HW_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_HW_FUSE_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e' +c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0', + 1: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0', + 2: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0', + 3: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0', + 4: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0', + 5: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0', + 6: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0', + 7: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0', + 8: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0', + 9: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1', + 10: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2', + 11: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3', + 12: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4', + 13: 'PP_GRTAVFS_FW_COMMON_FUSE_COUNT', +} +PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0 = 0 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0 = 1 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0 = 2 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0 = 3 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0 = 4 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0 = 5 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0 = 6 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0 = 7 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0 = 8 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1 = 9 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2 = 10 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3 = 11 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4 = 12 +PP_GRTAVFS_FW_COMMON_FUSE_COUNT = 13 +c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_FW_COMMON_FUSE_e = c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e +PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_FW_SEP_FUSE_e' +c__EA_PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1', + 1: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0', + 2: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1', + 3: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2', + 4: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3', + 5: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4', + 6: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1', + 7: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0', + 8: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1', + 9: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2', + 10: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3', + 11: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4', + 12: 'PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY', + 13: 'PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY', + 14: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0', + 15: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1', + 16: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2', + 17: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3', + 18: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4', + 19: 'PP_GRTAVFS_FW_SEP_FUSE_COUNT', +} +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1 = 0 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0 = 1 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1 = 2 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2 = 3 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3 = 4 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4 = 5 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1 = 6 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0 = 7 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1 = 8 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2 = 9 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3 = 10 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4 = 11 +PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY = 12 +PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY = 13 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0 = 14 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1 = 15 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2 = 16 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3 = 17 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4 = 18 +PP_GRTAVFS_FW_SEP_FUSE_COUNT = 19 +c__EA_PP_GRTAVFS_FW_SEP_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_FW_SEP_FUSE_e = c__EA_PP_GRTAVFS_FW_SEP_FUSE_e +PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues +class struct_c__SA_SviTelemetryScale_t(Structure): + pass + +struct_c__SA_SviTelemetryScale_t._pack_ = 1 # source:False +struct_c__SA_SviTelemetryScale_t._fields_ = [ + ('Offset', ctypes.c_byte), + ('Padding', ctypes.c_ubyte), + ('MaxCurrent', ctypes.c_uint16), +] + +SviTelemetryScale_t = struct_c__SA_SviTelemetryScale_t + +# values for enumeration 'c__EA_FanMode_e' +c__EA_FanMode_e__enumvalues = { + 0: 'FAN_MODE_AUTO', + 1: 'FAN_MODE_MANUAL_LINEAR', +} +FAN_MODE_AUTO = 0 +FAN_MODE_MANUAL_LINEAR = 1 +c__EA_FanMode_e = ctypes.c_uint32 # enum +FanMode_e = c__EA_FanMode_e +FanMode_e__enumvalues = c__EA_FanMode_e__enumvalues +class struct_c__SA_OverDriveTable_t(Structure): + pass + +struct_c__SA_OverDriveTable_t._pack_ = 1 # source:False +struct_c__SA_OverDriveTable_t._fields_ = [ + ('FeatureCtrlMask', ctypes.c_uint32), + ('VoltageOffsetPerZoneBoundary', ctypes.c_int16 * 6), + ('Reserved', ctypes.c_uint32), + ('GfxclkFmin', ctypes.c_int16), + ('GfxclkFmax', ctypes.c_int16), + ('UclkFmin', ctypes.c_uint16), + ('UclkFmax', ctypes.c_uint16), + ('Ppt', ctypes.c_int16), + ('Tdc', ctypes.c_int16), + ('FanLinearPwmPoints', ctypes.c_ubyte * 6), + ('FanLinearTempPoints', ctypes.c_ubyte * 6), + ('FanMinimumPwm', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetTemperature', ctypes.c_uint16), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('FanZeroRpmStopTemp', ctypes.c_ubyte), + ('FanMode', ctypes.c_ubyte), + ('MaxOpTemp', ctypes.c_ubyte), + ('Spare', ctypes.c_uint32 * 13), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +OverDriveTable_t = struct_c__SA_OverDriveTable_t +class struct_c__SA_OverDriveTableExternal_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('OverDriveTable', OverDriveTable_t), + ] + +OverDriveTableExternal_t = struct_c__SA_OverDriveTableExternal_t +class struct_c__SA_OverDriveLimits_t(Structure): + pass + +struct_c__SA_OverDriveLimits_t._pack_ = 1 # source:False +struct_c__SA_OverDriveLimits_t._fields_ = [ + ('FeatureCtrlMask', ctypes.c_uint32), + ('VoltageOffsetPerZoneBoundary', ctypes.c_int16), + ('Reserved1', ctypes.c_uint16), + ('Reserved2', ctypes.c_uint16), + ('GfxclkFmin', ctypes.c_int16), + ('GfxclkFmax', ctypes.c_int16), + ('UclkFmin', ctypes.c_uint16), + ('UclkFmax', ctypes.c_uint16), + ('Ppt', ctypes.c_int16), + ('Tdc', ctypes.c_int16), + ('FanLinearPwmPoints', ctypes.c_ubyte), + ('FanLinearTempPoints', ctypes.c_ubyte), + ('FanMinimumPwm', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetTemperature', ctypes.c_uint16), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('FanZeroRpmStopTemp', ctypes.c_ubyte), + ('FanMode', ctypes.c_ubyte), + ('MaxOpTemp', ctypes.c_ubyte), + ('Spare', ctypes.c_uint32 * 13), +] + +OverDriveLimits_t = struct_c__SA_OverDriveLimits_t + +# values for enumeration 'c__EA_BOARD_GPIO_TYPE_e' +c__EA_BOARD_GPIO_TYPE_e__enumvalues = { + 0: 'BOARD_GPIO_SMUIO_0', + 1: 'BOARD_GPIO_SMUIO_1', + 2: 'BOARD_GPIO_SMUIO_2', + 3: 'BOARD_GPIO_SMUIO_3', + 4: 'BOARD_GPIO_SMUIO_4', + 5: 'BOARD_GPIO_SMUIO_5', + 6: 'BOARD_GPIO_SMUIO_6', + 7: 'BOARD_GPIO_SMUIO_7', + 8: 'BOARD_GPIO_SMUIO_8', + 9: 'BOARD_GPIO_SMUIO_9', + 10: 'BOARD_GPIO_SMUIO_10', + 11: 'BOARD_GPIO_SMUIO_11', + 12: 'BOARD_GPIO_SMUIO_12', + 13: 'BOARD_GPIO_SMUIO_13', + 14: 'BOARD_GPIO_SMUIO_14', + 15: 'BOARD_GPIO_SMUIO_15', + 16: 'BOARD_GPIO_SMUIO_16', + 17: 'BOARD_GPIO_SMUIO_17', + 18: 'BOARD_GPIO_SMUIO_18', + 19: 'BOARD_GPIO_SMUIO_19', + 20: 'BOARD_GPIO_SMUIO_20', + 21: 'BOARD_GPIO_SMUIO_21', + 22: 'BOARD_GPIO_SMUIO_22', + 23: 'BOARD_GPIO_SMUIO_23', + 24: 'BOARD_GPIO_SMUIO_24', + 25: 'BOARD_GPIO_SMUIO_25', + 26: 'BOARD_GPIO_SMUIO_26', + 27: 'BOARD_GPIO_SMUIO_27', + 28: 'BOARD_GPIO_SMUIO_28', + 29: 'BOARD_GPIO_SMUIO_29', + 30: 'BOARD_GPIO_SMUIO_30', + 31: 'BOARD_GPIO_SMUIO_31', + 32: 'MAX_BOARD_GPIO_SMUIO_NUM', + 33: 'BOARD_GPIO_DC_GEN_A', + 34: 'BOARD_GPIO_DC_GEN_B', + 35: 'BOARD_GPIO_DC_GEN_C', + 36: 'BOARD_GPIO_DC_GEN_D', + 37: 'BOARD_GPIO_DC_GEN_E', + 38: 'BOARD_GPIO_DC_GEN_F', + 39: 'BOARD_GPIO_DC_GEN_G', + 40: 'BOARD_GPIO_DC_GENLK_CLK', + 41: 'BOARD_GPIO_DC_GENLK_VSYNC', + 42: 'BOARD_GPIO_DC_SWAPLOCK_A', + 43: 'BOARD_GPIO_DC_SWAPLOCK_B', +} +BOARD_GPIO_SMUIO_0 = 0 +BOARD_GPIO_SMUIO_1 = 1 +BOARD_GPIO_SMUIO_2 = 2 +BOARD_GPIO_SMUIO_3 = 3 +BOARD_GPIO_SMUIO_4 = 4 +BOARD_GPIO_SMUIO_5 = 5 +BOARD_GPIO_SMUIO_6 = 6 +BOARD_GPIO_SMUIO_7 = 7 +BOARD_GPIO_SMUIO_8 = 8 +BOARD_GPIO_SMUIO_9 = 9 +BOARD_GPIO_SMUIO_10 = 10 +BOARD_GPIO_SMUIO_11 = 11 +BOARD_GPIO_SMUIO_12 = 12 +BOARD_GPIO_SMUIO_13 = 13 +BOARD_GPIO_SMUIO_14 = 14 +BOARD_GPIO_SMUIO_15 = 15 +BOARD_GPIO_SMUIO_16 = 16 +BOARD_GPIO_SMUIO_17 = 17 +BOARD_GPIO_SMUIO_18 = 18 +BOARD_GPIO_SMUIO_19 = 19 +BOARD_GPIO_SMUIO_20 = 20 +BOARD_GPIO_SMUIO_21 = 21 +BOARD_GPIO_SMUIO_22 = 22 +BOARD_GPIO_SMUIO_23 = 23 +BOARD_GPIO_SMUIO_24 = 24 +BOARD_GPIO_SMUIO_25 = 25 +BOARD_GPIO_SMUIO_26 = 26 +BOARD_GPIO_SMUIO_27 = 27 +BOARD_GPIO_SMUIO_28 = 28 +BOARD_GPIO_SMUIO_29 = 29 +BOARD_GPIO_SMUIO_30 = 30 +BOARD_GPIO_SMUIO_31 = 31 +MAX_BOARD_GPIO_SMUIO_NUM = 32 +BOARD_GPIO_DC_GEN_A = 33 +BOARD_GPIO_DC_GEN_B = 34 +BOARD_GPIO_DC_GEN_C = 35 +BOARD_GPIO_DC_GEN_D = 36 +BOARD_GPIO_DC_GEN_E = 37 +BOARD_GPIO_DC_GEN_F = 38 +BOARD_GPIO_DC_GEN_G = 39 +BOARD_GPIO_DC_GENLK_CLK = 40 +BOARD_GPIO_DC_GENLK_VSYNC = 41 +BOARD_GPIO_DC_SWAPLOCK_A = 42 +BOARD_GPIO_DC_SWAPLOCK_B = 43 +c__EA_BOARD_GPIO_TYPE_e = ctypes.c_uint32 # enum +BOARD_GPIO_TYPE_e = c__EA_BOARD_GPIO_TYPE_e +BOARD_GPIO_TYPE_e__enumvalues = c__EA_BOARD_GPIO_TYPE_e__enumvalues +class struct_c__SA_BootValues_t(Structure): + pass + +struct_c__SA_BootValues_t._pack_ = 1 # source:False +struct_c__SA_BootValues_t._fields_ = [ + ('InitGfxclk_bypass', ctypes.c_uint16), + ('InitSocclk', ctypes.c_uint16), + ('InitMp0clk', ctypes.c_uint16), + ('InitMpioclk', ctypes.c_uint16), + ('InitSmnclk', ctypes.c_uint16), + ('InitUcpclk', ctypes.c_uint16), + ('InitCsrclk', ctypes.c_uint16), + ('InitDprefclk', ctypes.c_uint16), + ('InitDcfclk', ctypes.c_uint16), + ('InitDtbclk', ctypes.c_uint16), + ('InitDclk', ctypes.c_uint16), + ('InitVclk', ctypes.c_uint16), + ('InitUsbdfsclk', ctypes.c_uint16), + ('InitMp1clk', ctypes.c_uint16), + ('InitLclk', ctypes.c_uint16), + ('InitBaco400clk_bypass', ctypes.c_uint16), + ('InitBaco1200clk_bypass', ctypes.c_uint16), + ('InitBaco700clk_bypass', ctypes.c_uint16), + ('InitFclk', ctypes.c_uint16), + ('InitGfxclk_clkb', ctypes.c_uint16), + ('InitUclkDPMState', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 3), + ('InitVcoFreqPll0', ctypes.c_uint32), + ('InitVcoFreqPll1', ctypes.c_uint32), + ('InitVcoFreqPll2', ctypes.c_uint32), + ('InitVcoFreqPll3', ctypes.c_uint32), + ('InitVcoFreqPll4', ctypes.c_uint32), + ('InitVcoFreqPll5', ctypes.c_uint32), + ('InitVcoFreqPll6', ctypes.c_uint32), + ('InitGfx', ctypes.c_uint16), + ('InitSoc', ctypes.c_uint16), + ('InitU', ctypes.c_uint16), + ('Padding2', ctypes.c_uint16), + ('Spare', ctypes.c_uint32 * 8), +] + +BootValues_t = struct_c__SA_BootValues_t +class struct_c__SA_MsgLimits_t(Structure): + pass + +struct_c__SA_MsgLimits_t._pack_ = 1 # source:False +struct_c__SA_MsgLimits_t._fields_ = [ + ('Power', ctypes.c_uint16 * 2 * 4), + ('Tdc', ctypes.c_uint16 * 3), + ('Temperature', ctypes.c_uint16 * 13), + ('PwmLimitMin', ctypes.c_ubyte), + ('PwmLimitMax', ctypes.c_ubyte), + ('FanTargetTemperature', ctypes.c_ubyte), + ('Spare1', ctypes.c_ubyte * 1), + ('AcousticTargetRpmThresholdMin', ctypes.c_uint16), + ('AcousticTargetRpmThresholdMax', ctypes.c_uint16), + ('AcousticLimitRpmThresholdMin', ctypes.c_uint16), + ('AcousticLimitRpmThresholdMax', ctypes.c_uint16), + ('PccLimitMin', ctypes.c_uint16), + ('PccLimitMax', ctypes.c_uint16), + ('FanStopTempMin', ctypes.c_uint16), + ('FanStopTempMax', ctypes.c_uint16), + ('FanStartTempMin', ctypes.c_uint16), + ('FanStartTempMax', ctypes.c_uint16), + ('PowerMinPpt0', ctypes.c_uint16 * 2), + ('Spare', ctypes.c_uint32 * 11), +] + +MsgLimits_t = struct_c__SA_MsgLimits_t +class struct_c__SA_DriverReportedClocks_t(Structure): + pass + +struct_c__SA_DriverReportedClocks_t._pack_ = 1 # source:False +struct_c__SA_DriverReportedClocks_t._fields_ = [ + ('BaseClockAc', ctypes.c_uint16), + ('GameClockAc', ctypes.c_uint16), + ('BoostClockAc', ctypes.c_uint16), + ('BaseClockDc', ctypes.c_uint16), + ('GameClockDc', ctypes.c_uint16), + ('BoostClockDc', ctypes.c_uint16), + ('Reserved', ctypes.c_uint32 * 4), +] + +DriverReportedClocks_t = struct_c__SA_DriverReportedClocks_t +class struct_c__SA_AvfsDcBtcParams_t(Structure): + pass + +struct_c__SA_AvfsDcBtcParams_t._pack_ = 1 # source:False +struct_c__SA_AvfsDcBtcParams_t._fields_ = [ + ('DcBtcEnabled', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 3), + ('DcTol', ctypes.c_uint16), + ('DcBtcGb', ctypes.c_uint16), + ('DcBtcMin', ctypes.c_uint16), + ('DcBtcMax', ctypes.c_uint16), + ('DcBtcGbScalar', LinearInt_t), +] + +AvfsDcBtcParams_t = struct_c__SA_AvfsDcBtcParams_t +class struct_c__SA_AvfsFuseOverride_t(Structure): + pass + +struct_c__SA_AvfsFuseOverride_t._pack_ = 1 # source:False +struct_c__SA_AvfsFuseOverride_t._fields_ = [ + ('AvfsTemp', ctypes.c_uint16 * 2), + ('VftFMin', ctypes.c_uint16), + ('VInversion', ctypes.c_uint16), + ('qVft', struct_c__SA_QuadraticInt_t * 2), + ('qAvfsGb', QuadraticInt_t), + ('qAvfsGb2', QuadraticInt_t), +] + +AvfsFuseOverride_t = struct_c__SA_AvfsFuseOverride_t +class struct_c__SA_SkuTable_t(Structure): + pass + +struct_c__SA_SkuTable_t._pack_ = 1 # source:False +struct_c__SA_SkuTable_t._fields_ = [ + ('Version', ctypes.c_uint32), + ('FeaturesToRun', ctypes.c_uint32 * 2), + ('TotalPowerConfig', ctypes.c_ubyte), + ('CustomerVariant', ctypes.c_ubyte), + ('MemoryTemperatureTypeMask', ctypes.c_ubyte), + ('SmartShiftVersion', ctypes.c_ubyte), + ('SocketPowerLimitAc', ctypes.c_uint16 * 4), + ('SocketPowerLimitDc', ctypes.c_uint16 * 4), + ('SocketPowerLimitSmartShift2', ctypes.c_uint16), + ('EnableLegacyPptLimit', ctypes.c_ubyte), + ('UseInputTelemetry', ctypes.c_ubyte), + ('SmartShiftMinReportedPptinDcs', ctypes.c_ubyte), + ('PaddingPpt', ctypes.c_ubyte * 1), + ('VrTdcLimit', ctypes.c_uint16 * 3), + ('PlatformTdcLimit', ctypes.c_uint16 * 3), + ('TemperatureLimit', ctypes.c_uint16 * 13), + ('HwCtfTempLimit', ctypes.c_uint16), + ('PaddingInfra', ctypes.c_uint16), + ('FitControllerFailureRateLimit', ctypes.c_uint32), + ('FitControllerGfxDutyCycle', ctypes.c_uint32), + ('FitControllerSocDutyCycle', ctypes.c_uint32), + ('FitControllerSocOffset', ctypes.c_uint32), + ('GfxApccPlusResidencyLimit', ctypes.c_uint32), + ('ThrottlerControlMask', ctypes.c_uint32), + ('FwDStateMask', ctypes.c_uint32), + ('UlvVoltageOffset', ctypes.c_uint16 * 2), + ('UlvVoltageOffsetU', ctypes.c_uint16), + ('DeepUlvVoltageOffsetSoc', ctypes.c_uint16), + ('DefaultMaxVoltage', ctypes.c_uint16 * 2), + ('BoostMaxVoltage', ctypes.c_uint16 * 2), + ('VminTempHystersis', ctypes.c_int16 * 2), + ('VminTempThreshold', ctypes.c_int16 * 2), + ('Vmin_Hot_T0', ctypes.c_uint16 * 2), + ('Vmin_Cold_T0', ctypes.c_uint16 * 2), + ('Vmin_Hot_Eol', ctypes.c_uint16 * 2), + ('Vmin_Cold_Eol', ctypes.c_uint16 * 2), + ('Vmin_Aging_Offset', ctypes.c_uint16 * 2), + ('Spare_Vmin_Plat_Offset_Hot', ctypes.c_uint16 * 2), + ('Spare_Vmin_Plat_Offset_Cold', ctypes.c_uint16 * 2), + ('VcBtcFixedVminAgingOffset', ctypes.c_uint16 * 2), + ('VcBtcVmin2PsmDegrationGb', ctypes.c_uint16 * 2), + ('VcBtcPsmA', ctypes.c_uint32 * 2), + ('VcBtcPsmB', ctypes.c_uint32 * 2), + ('VcBtcVminA', ctypes.c_uint32 * 2), + ('VcBtcVminB', ctypes.c_uint32 * 2), + ('PerPartVminEnabled', ctypes.c_ubyte * 2), + ('VcBtcEnabled', ctypes.c_ubyte * 2), + ('SocketPowerLimitAcTau', ctypes.c_uint16 * 4), + ('SocketPowerLimitDcTau', ctypes.c_uint16 * 4), + ('Vmin_droop', QuadraticInt_t), + ('SpareVmin', ctypes.c_uint32 * 9), + ('DpmDescriptor', struct_c__SA_DpmDescriptor_t * 13), + ('FreqTableGfx', ctypes.c_uint16 * 16), + ('FreqTableVclk', ctypes.c_uint16 * 8), + ('FreqTableDclk', ctypes.c_uint16 * 8), + ('FreqTableSocclk', ctypes.c_uint16 * 8), + ('FreqTableUclk', ctypes.c_uint16 * 4), + ('FreqTableDispclk', ctypes.c_uint16 * 8), + ('FreqTableDppClk', ctypes.c_uint16 * 8), + ('FreqTableDprefclk', ctypes.c_uint16 * 8), + ('FreqTableDcfclk', ctypes.c_uint16 * 8), + ('FreqTableDtbclk', ctypes.c_uint16 * 8), + ('FreqTableFclk', ctypes.c_uint16 * 8), + ('DcModeMaxFreq', ctypes.c_uint32 * 13), + ('Mp0clkFreq', ctypes.c_uint16 * 2), + ('Mp0DpmVoltage', ctypes.c_uint16 * 2), + ('GfxclkSpare', ctypes.c_ubyte * 2), + ('GfxclkFreqCap', ctypes.c_uint16), + ('GfxclkFgfxoffEntry', ctypes.c_uint16), + ('GfxclkFgfxoffExitImu', ctypes.c_uint16), + ('GfxclkFgfxoffExitRlc', ctypes.c_uint16), + ('GfxclkThrottleClock', ctypes.c_uint16), + ('EnableGfxPowerStagesGpio', ctypes.c_ubyte), + ('GfxIdlePadding', ctypes.c_ubyte), + ('SmsRepairWRCKClkDivEn', ctypes.c_ubyte), + ('SmsRepairWRCKClkDivVal', ctypes.c_ubyte), + ('GfxOffEntryEarlyMGCGEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGDelayEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGDelayVal', ctypes.c_ubyte), + ('GfxclkFreqGfxUlv', ctypes.c_uint16), + ('GfxIdlePadding2', ctypes.c_ubyte * 2), + ('GfxOffEntryHysteresis', ctypes.c_uint32), + ('GfxoffSpare', ctypes.c_uint32 * 15), + ('DfllBtcMasterScalerM', ctypes.c_uint32), + ('DfllBtcMasterScalerB', ctypes.c_int32), + ('DfllBtcSlaveScalerM', ctypes.c_uint32), + ('DfllBtcSlaveScalerB', ctypes.c_int32), + ('DfllPccAsWaitCtrl', ctypes.c_uint32), + ('DfllPccAsStepCtrl', ctypes.c_uint32), + ('DfllL2FrequencyBoostM', ctypes.c_uint32), + ('DfllL2FrequencyBoostB', ctypes.c_uint32), + ('GfxGpoSpare', ctypes.c_uint32 * 8), + ('DcsGfxOffVoltage', ctypes.c_uint16), + ('PaddingDcs', ctypes.c_uint16), + ('DcsMinGfxOffTime', ctypes.c_uint16), + ('DcsMaxGfxOffTime', ctypes.c_uint16), + ('DcsMinCreditAccum', ctypes.c_uint32), + ('DcsExitHysteresis', ctypes.c_uint16), + ('DcsTimeout', ctypes.c_uint16), + ('FoptEnabled', ctypes.c_ubyte), + ('DcsSpare2', ctypes.c_ubyte * 3), + ('DcsFoptM', ctypes.c_uint32), + ('DcsFoptB', ctypes.c_uint32), + ('DcsSpare', ctypes.c_uint32 * 11), + ('ShadowFreqTableUclk', ctypes.c_uint16 * 4), + ('UseStrobeModeOptimizations', ctypes.c_ubyte), + ('PaddingMem', ctypes.c_ubyte * 3), + ('UclkDpmPstates', ctypes.c_ubyte * 4), + ('FreqTableUclkDiv', ctypes.c_ubyte * 4), + ('MemVmempVoltage', ctypes.c_uint16 * 4), + ('MemVddioVoltage', ctypes.c_uint16 * 4), + ('FclkDpmUPstates', ctypes.c_ubyte * 8), + ('FclkDpmVddU', ctypes.c_uint16 * 8), + ('FclkDpmUSpeed', ctypes.c_uint16 * 8), + ('FclkDpmDisallowPstateFreq', ctypes.c_uint16), + ('PaddingFclk', ctypes.c_uint16), + ('PcieGenSpeed', ctypes.c_ubyte * 3), + ('PcieLaneCount', ctypes.c_ubyte * 3), + ('LclkFreq', ctypes.c_uint16 * 3), + ('FanStopTemp', ctypes.c_uint16 * 13), + ('FanStartTemp', ctypes.c_uint16 * 13), + ('FanGain', ctypes.c_uint16 * 13), + ('FanGainPadding', ctypes.c_uint16), + ('FanPwmMin', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanMaximumRpm', ctypes.c_uint16), + ('MGpuAcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetGfxclk', ctypes.c_uint16), + ('TempInputSelectMask', ctypes.c_uint32), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('FanTachEdgePerRev', ctypes.c_ubyte), + ('FanTargetTemperature', ctypes.c_uint16 * 13), + ('FuzzyFan_ErrorSetDelta', ctypes.c_int16), + ('FuzzyFan_ErrorRateSetDelta', ctypes.c_int16), + ('FuzzyFan_PwmSetDelta', ctypes.c_int16), + ('FuzzyFan_Reserved', ctypes.c_uint16), + ('FwCtfLimit', ctypes.c_uint16 * 13), + ('IntakeTempEnableRPM', ctypes.c_uint16), + ('IntakeTempOffsetTemp', ctypes.c_int16), + ('IntakeTempReleaseTemp', ctypes.c_uint16), + ('IntakeTempHighIntakeAcousticLimit', ctypes.c_uint16), + ('IntakeTempAcouticLimitReleaseRate', ctypes.c_uint16), + ('FanAbnormalTempLimitOffset', ctypes.c_int16), + ('FanStalledTriggerRpm', ctypes.c_uint16), + ('FanAbnormalTriggerRpmCoeff', ctypes.c_uint16), + ('FanAbnormalDetectionEnable', ctypes.c_uint16), + ('FanIntakeSensorSupport', ctypes.c_ubyte), + ('FanIntakePadding', ctypes.c_ubyte * 3), + ('FanSpare', ctypes.c_uint32 * 13), + ('OverrideGfxAvfsFuses', ctypes.c_ubyte), + ('GfxAvfsPadding', ctypes.c_ubyte * 3), + ('L2HwRtAvfsFuses', ctypes.c_uint32 * 32), + ('SeHwRtAvfsFuses', ctypes.c_uint32 * 32), + ('CommonRtAvfs', ctypes.c_uint32 * 13), + ('L2FwRtAvfsFuses', ctypes.c_uint32 * 19), + ('SeFwRtAvfsFuses', ctypes.c_uint32 * 19), + ('Droop_PWL_F', ctypes.c_uint32 * 5), + ('Droop_PWL_a', ctypes.c_uint32 * 5), + ('Droop_PWL_b', ctypes.c_uint32 * 5), + ('Droop_PWL_c', ctypes.c_uint32 * 5), + ('Static_PWL_Offset', ctypes.c_uint32 * 5), + ('dGbV_dT_vmin', ctypes.c_uint32), + ('dGbV_dT_vmax', ctypes.c_uint32), + ('V2F_vmin_range_low', ctypes.c_uint32), + ('V2F_vmin_range_high', ctypes.c_uint32), + ('V2F_vmax_range_low', ctypes.c_uint32), + ('V2F_vmax_range_high', ctypes.c_uint32), + ('DcBtcGfxParams', AvfsDcBtcParams_t), + ('GfxAvfsSpare', ctypes.c_uint32 * 32), + ('OverrideSocAvfsFuses', ctypes.c_ubyte), + ('MinSocAvfsRevision', ctypes.c_ubyte), + ('SocAvfsPadding', ctypes.c_ubyte * 2), + ('SocAvfsFuseOverride', struct_c__SA_AvfsFuseOverride_t * 3), + ('dBtcGbSoc', struct_c__SA_DroopInt_t * 3), + ('qAgingGb', struct_c__SA_LinearInt_t * 3), + ('qStaticVoltageOffset', struct_c__SA_QuadraticInt_t * 3), + ('DcBtcSocParams', struct_c__SA_AvfsDcBtcParams_t * 3), + ('SocAvfsSpare', ctypes.c_uint32 * 32), + ('BootValues', BootValues_t), + ('DriverReportedClocks', DriverReportedClocks_t), + ('MsgLimits', MsgLimits_t), + ('OverDriveLimitsMin', OverDriveLimits_t), + ('OverDriveLimitsBasicMax', OverDriveLimits_t), + ('reserved', ctypes.c_uint32 * 22), + ('DebugOverrides', ctypes.c_uint32), + ('TotalBoardPowerSupport', ctypes.c_ubyte), + ('TotalBoardPowerPadding', ctypes.c_ubyte * 3), + ('TotalIdleBoardPowerM', ctypes.c_int16), + ('TotalIdleBoardPowerB', ctypes.c_int16), + ('TotalBoardPowerM', ctypes.c_int16), + ('TotalBoardPowerB', ctypes.c_int16), + ('qFeffCoeffGameClock', struct_c__SA_QuadraticInt_t * 2), + ('qFeffCoeffBaseClock', struct_c__SA_QuadraticInt_t * 2), + ('qFeffCoeffBoostClock', struct_c__SA_QuadraticInt_t * 2), + ('TemperatureLimit_Hynix', ctypes.c_uint16), + ('TemperatureLimit_Micron', ctypes.c_uint16), + ('TemperatureFwCtfLimit_Hynix', ctypes.c_uint16), + ('TemperatureFwCtfLimit_Micron', ctypes.c_uint16), + ('Spare', ctypes.c_uint32 * 41), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SkuTable_t = struct_c__SA_SkuTable_t +class struct_c__SA_BoardTable_t(Structure): + pass + +struct_c__SA_BoardTable_t._pack_ = 1 # source:False +struct_c__SA_BoardTable_t._fields_ = [ + ('Version', ctypes.c_uint32), + ('I2cControllers', struct_c__SA_I2cControllerConfig_t * 8), + ('VddGfxVrMapping', ctypes.c_ubyte), + ('VddSocVrMapping', ctypes.c_ubyte), + ('VddMem0VrMapping', ctypes.c_ubyte), + ('VddMem1VrMapping', ctypes.c_ubyte), + ('GfxUlvPhaseSheddingMask', ctypes.c_ubyte), + ('SocUlvPhaseSheddingMask', ctypes.c_ubyte), + ('VmempUlvPhaseSheddingMask', ctypes.c_ubyte), + ('VddioUlvPhaseSheddingMask', ctypes.c_ubyte), + ('SlaveAddrMapping', ctypes.c_ubyte * 5), + ('VrPsiSupport', ctypes.c_ubyte * 5), + ('PaddingPsi', ctypes.c_ubyte * 5), + ('EnablePsi6', ctypes.c_ubyte * 5), + ('SviTelemetryScale', struct_c__SA_SviTelemetryScale_t * 5), + ('VoltageTelemetryRatio', ctypes.c_uint32 * 5), + ('DownSlewRateVr', ctypes.c_ubyte * 5), + ('LedOffGpio', ctypes.c_ubyte), + ('FanOffGpio', ctypes.c_ubyte), + ('GfxVrPowerStageOffGpio', ctypes.c_ubyte), + ('AcDcGpio', ctypes.c_ubyte), + ('AcDcPolarity', ctypes.c_ubyte), + ('VR0HotGpio', ctypes.c_ubyte), + ('VR0HotPolarity', ctypes.c_ubyte), + ('GthrGpio', ctypes.c_ubyte), + ('GthrPolarity', ctypes.c_ubyte), + ('LedPin0', ctypes.c_ubyte), + ('LedPin1', ctypes.c_ubyte), + ('LedPin2', ctypes.c_ubyte), + ('LedEnableMask', ctypes.c_ubyte), + ('LedPcie', ctypes.c_ubyte), + ('LedError', ctypes.c_ubyte), + ('UclkTrainingModeSpreadPercent', ctypes.c_ubyte), + ('UclkSpreadPadding', ctypes.c_ubyte), + ('UclkSpreadFreq', ctypes.c_uint16), + ('UclkSpreadPercent', ctypes.c_ubyte * 16), + ('GfxclkSpreadEnable', ctypes.c_ubyte), + ('FclkSpreadPercent', ctypes.c_ubyte), + ('FclkSpreadFreq', ctypes.c_uint16), + ('DramWidth', ctypes.c_ubyte), + ('PaddingMem1', ctypes.c_ubyte * 7), + ('HsrEnabled', ctypes.c_ubyte), + ('VddqOffEnabled', ctypes.c_ubyte), + ('PaddingUmcFlags', ctypes.c_ubyte * 2), + ('PostVoltageSetBacoDelay', ctypes.c_uint32), + ('BacoEntryDelay', ctypes.c_uint32), + ('FuseWritePowerMuxPresent', ctypes.c_ubyte), + ('FuseWritePadding', ctypes.c_ubyte * 3), + ('BoardSpare', ctypes.c_uint32 * 63), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +BoardTable_t = struct_c__SA_BoardTable_t +class struct_c__SA_PPTable_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('SkuTable', SkuTable_t), + ('BoardTable', BoardTable_t), + ] + +PPTable_t = struct_c__SA_PPTable_t +class struct_c__SA_DriverSmuConfig_t(Structure): + pass + +struct_c__SA_DriverSmuConfig_t._pack_ = 1 # source:False +struct_c__SA_DriverSmuConfig_t._fields_ = [ + ('GfxclkAverageLpfTau', ctypes.c_uint16), + ('FclkAverageLpfTau', ctypes.c_uint16), + ('UclkAverageLpfTau', ctypes.c_uint16), + ('GfxActivityLpfTau', ctypes.c_uint16), + ('UclkActivityLpfTau', ctypes.c_uint16), + ('SocketPowerLpfTau', ctypes.c_uint16), + ('VcnClkAverageLpfTau', ctypes.c_uint16), + ('VcnUsageAverageLpfTau', ctypes.c_uint16), +] + +DriverSmuConfig_t = struct_c__SA_DriverSmuConfig_t +class struct_c__SA_DriverSmuConfigExternal_t(Structure): + pass + +struct_c__SA_DriverSmuConfigExternal_t._pack_ = 1 # source:False +struct_c__SA_DriverSmuConfigExternal_t._fields_ = [ + ('DriverSmuConfig', DriverSmuConfig_t), + ('Spare', ctypes.c_uint32 * 8), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DriverSmuConfigExternal_t = struct_c__SA_DriverSmuConfigExternal_t +class struct_c__SA_DriverInfoTable_t(Structure): + pass + +struct_c__SA_DriverInfoTable_t._pack_ = 1 # source:False +struct_c__SA_DriverInfoTable_t._fields_ = [ + ('FreqTableGfx', ctypes.c_uint16 * 16), + ('FreqTableVclk', ctypes.c_uint16 * 8), + ('FreqTableDclk', ctypes.c_uint16 * 8), + ('FreqTableSocclk', ctypes.c_uint16 * 8), + ('FreqTableUclk', ctypes.c_uint16 * 4), + ('FreqTableDispclk', ctypes.c_uint16 * 8), + ('FreqTableDppClk', ctypes.c_uint16 * 8), + ('FreqTableDprefclk', ctypes.c_uint16 * 8), + ('FreqTableDcfclk', ctypes.c_uint16 * 8), + ('FreqTableDtbclk', ctypes.c_uint16 * 8), + ('FreqTableFclk', ctypes.c_uint16 * 8), + ('DcModeMaxFreq', ctypes.c_uint16 * 13), + ('Padding', ctypes.c_uint16), + ('Spare', ctypes.c_uint32 * 32), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DriverInfoTable_t = struct_c__SA_DriverInfoTable_t +class struct_c__SA_SmuMetrics_t(Structure): + pass + +struct_c__SA_SmuMetrics_t._pack_ = 1 # source:False +struct_c__SA_SmuMetrics_t._fields_ = [ + ('CurrClock', ctypes.c_uint32 * 13), + ('AverageGfxclkFrequencyTarget', ctypes.c_uint16), + ('AverageGfxclkFrequencyPreDs', ctypes.c_uint16), + ('AverageGfxclkFrequencyPostDs', ctypes.c_uint16), + ('AverageFclkFrequencyPreDs', ctypes.c_uint16), + ('AverageFclkFrequencyPostDs', ctypes.c_uint16), + ('AverageMemclkFrequencyPreDs', ctypes.c_uint16), + ('AverageMemclkFrequencyPostDs', ctypes.c_uint16), + ('AverageVclk0Frequency', ctypes.c_uint16), + ('AverageDclk0Frequency', ctypes.c_uint16), + ('AverageVclk1Frequency', ctypes.c_uint16), + ('AverageDclk1Frequency', ctypes.c_uint16), + ('PCIeBusy', ctypes.c_uint16), + ('dGPU_W_MAX', ctypes.c_uint16), + ('padding', ctypes.c_uint16), + ('MetricsCounter', ctypes.c_uint32), + ('AvgVoltage', ctypes.c_uint16 * 5), + ('AvgCurrent', ctypes.c_uint16 * 5), + ('AverageGfxActivity', ctypes.c_uint16), + ('AverageUclkActivity', ctypes.c_uint16), + ('Vcn0ActivityPercentage', ctypes.c_uint16), + ('Vcn1ActivityPercentage', ctypes.c_uint16), + ('EnergyAccumulator', ctypes.c_uint32), + ('AverageSocketPower', ctypes.c_uint16), + ('AverageTotalBoardPower', ctypes.c_uint16), + ('AvgTemperature', ctypes.c_uint16 * 13), + ('AvgTemperatureFanIntake', ctypes.c_uint16), + ('PcieRate', ctypes.c_ubyte), + ('PcieWidth', ctypes.c_ubyte), + ('AvgFanPwm', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 1), + ('AvgFanRpm', ctypes.c_uint16), + ('ThrottlingPercentage', ctypes.c_ubyte * 22), + ('VmaxThrottlingPercentage', ctypes.c_ubyte), + ('Padding1', ctypes.c_ubyte * 3), + ('D3HotEntryCountPerMode', ctypes.c_uint32 * 4), + ('D3HotExitCountPerMode', ctypes.c_uint32 * 4), + ('ArmMsgReceivedCountPerMode', ctypes.c_uint32 * 4), + ('ApuSTAPMSmartShiftLimit', ctypes.c_uint16), + ('ApuSTAPMLimit', ctypes.c_uint16), + ('AvgApuSocketPower', ctypes.c_uint16), + ('AverageUclkActivity_MAX', ctypes.c_uint16), + ('PublicSerialNumberLower', ctypes.c_uint32), + ('PublicSerialNumberUpper', ctypes.c_uint32), +] + +SmuMetrics_t = struct_c__SA_SmuMetrics_t +class struct_c__SA_SmuMetricsExternal_t(Structure): + pass + +struct_c__SA_SmuMetricsExternal_t._pack_ = 1 # source:False +struct_c__SA_SmuMetricsExternal_t._fields_ = [ + ('SmuMetrics', SmuMetrics_t), + ('Spare', ctypes.c_uint32 * 29), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SmuMetricsExternal_t = struct_c__SA_SmuMetricsExternal_t +class struct_c__SA_WatermarkRowGeneric_t(Structure): + pass + +struct_c__SA_WatermarkRowGeneric_t._pack_ = 1 # source:False +struct_c__SA_WatermarkRowGeneric_t._fields_ = [ + ('WmSetting', ctypes.c_ubyte), + ('Flags', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 2), +] + +WatermarkRowGeneric_t = struct_c__SA_WatermarkRowGeneric_t + +# values for enumeration 'c__EA_WATERMARKS_FLAGS_e' +c__EA_WATERMARKS_FLAGS_e__enumvalues = { + 0: 'WATERMARKS_CLOCK_RANGE', + 1: 'WATERMARKS_DUMMY_PSTATE', + 2: 'WATERMARKS_MALL', + 3: 'WATERMARKS_COUNT', +} +WATERMARKS_CLOCK_RANGE = 0 +WATERMARKS_DUMMY_PSTATE = 1 +WATERMARKS_MALL = 2 +WATERMARKS_COUNT = 3 +c__EA_WATERMARKS_FLAGS_e = ctypes.c_uint32 # enum +WATERMARKS_FLAGS_e = c__EA_WATERMARKS_FLAGS_e +WATERMARKS_FLAGS_e__enumvalues = c__EA_WATERMARKS_FLAGS_e__enumvalues +class struct_c__SA_Watermarks_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('WatermarkRow', struct_c__SA_WatermarkRowGeneric_t * 4), + ] + +Watermarks_t = struct_c__SA_Watermarks_t +class struct_c__SA_WatermarksExternal_t(Structure): + pass + +struct_c__SA_WatermarksExternal_t._pack_ = 1 # source:False +struct_c__SA_WatermarksExternal_t._fields_ = [ + ('Watermarks', Watermarks_t), + ('Spare', ctypes.c_uint32 * 16), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +WatermarksExternal_t = struct_c__SA_WatermarksExternal_t +class struct_c__SA_AvfsDebugTable_t(Structure): + pass + +struct_c__SA_AvfsDebugTable_t._pack_ = 1 # source:False +struct_c__SA_AvfsDebugTable_t._fields_ = [ + ('avgPsmCount', ctypes.c_uint16 * 214), + ('minPsmCount', ctypes.c_uint16 * 214), + ('avgPsmVoltage', ctypes.c_float * 214), + ('minPsmVoltage', ctypes.c_float * 214), +] + +AvfsDebugTable_t = struct_c__SA_AvfsDebugTable_t +class struct_c__SA_AvfsDebugTableExternal_t(Structure): + pass + +struct_c__SA_AvfsDebugTableExternal_t._pack_ = 1 # source:False +struct_c__SA_AvfsDebugTableExternal_t._fields_ = [ + ('AvfsDebugTable', AvfsDebugTable_t), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +AvfsDebugTableExternal_t = struct_c__SA_AvfsDebugTableExternal_t +class struct_c__SA_DpmActivityMonitorCoeffInt_t(Structure): + pass + +struct_c__SA_DpmActivityMonitorCoeffInt_t._pack_ = 1 # source:False +struct_c__SA_DpmActivityMonitorCoeffInt_t._fields_ = [ + ('Gfx_ActiveHystLimit', ctypes.c_ubyte), + ('Gfx_IdleHystLimit', ctypes.c_ubyte), + ('Gfx_FPS', ctypes.c_ubyte), + ('Gfx_MinActiveFreqType', ctypes.c_ubyte), + ('Gfx_BoosterFreqType', ctypes.c_ubyte), + ('PaddingGfx', ctypes.c_ubyte), + ('Gfx_MinActiveFreq', ctypes.c_uint16), + ('Gfx_BoosterFreq', ctypes.c_uint16), + ('Gfx_PD_Data_time_constant', ctypes.c_uint16), + ('Gfx_PD_Data_limit_a', ctypes.c_uint32), + ('Gfx_PD_Data_limit_b', ctypes.c_uint32), + ('Gfx_PD_Data_limit_c', ctypes.c_uint32), + ('Gfx_PD_Data_error_coeff', ctypes.c_uint32), + ('Gfx_PD_Data_error_rate_coeff', ctypes.c_uint32), + ('Fclk_ActiveHystLimit', ctypes.c_ubyte), + ('Fclk_IdleHystLimit', ctypes.c_ubyte), + ('Fclk_FPS', ctypes.c_ubyte), + ('Fclk_MinActiveFreqType', ctypes.c_ubyte), + ('Fclk_BoosterFreqType', ctypes.c_ubyte), + ('PaddingFclk', ctypes.c_ubyte), + ('Fclk_MinActiveFreq', ctypes.c_uint16), + ('Fclk_BoosterFreq', ctypes.c_uint16), + ('Fclk_PD_Data_time_constant', ctypes.c_uint16), + ('Fclk_PD_Data_limit_a', ctypes.c_uint32), + ('Fclk_PD_Data_limit_b', ctypes.c_uint32), + ('Fclk_PD_Data_limit_c', ctypes.c_uint32), + ('Fclk_PD_Data_error_coeff', ctypes.c_uint32), + ('Fclk_PD_Data_error_rate_coeff', ctypes.c_uint32), + ('Mem_UpThreshold_Limit', ctypes.c_uint32 * 4), + ('Mem_UpHystLimit', ctypes.c_ubyte * 4), + ('Mem_DownHystLimit', ctypes.c_ubyte * 4), + ('Mem_Fps', ctypes.c_uint16), + ('padding', ctypes.c_ubyte * 2), +] + +DpmActivityMonitorCoeffInt_t = struct_c__SA_DpmActivityMonitorCoeffInt_t +class struct_c__SA_DpmActivityMonitorCoeffIntExternal_t(Structure): + pass + +struct_c__SA_DpmActivityMonitorCoeffIntExternal_t._pack_ = 1 # source:False +struct_c__SA_DpmActivityMonitorCoeffIntExternal_t._fields_ = [ + ('DpmActivityMonitorCoeffInt', DpmActivityMonitorCoeffInt_t), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DpmActivityMonitorCoeffIntExternal_t = struct_c__SA_DpmActivityMonitorCoeffIntExternal_t +__AMDGPU_SMU_H__ = True # macro +u32 = True # macro +SMU_THERMAL_MINIMUM_ALERT_TEMP = 0 # macro +SMU_THERMAL_MAXIMUM_ALERT_TEMP = 255 # macro +SMU_TEMPERATURE_UNITS_PER_CENTIGRADES = 1000 # macro +SMU_FW_NAME_LEN = 0x24 # macro +SMU_DPM_USER_PROFILE_RESTORE = (1<<0) # macro +SMU_CUSTOM_FAN_SPEED_RPM = (1<<1) # macro +SMU_CUSTOM_FAN_SPEED_PWM = (1<<2) # macro +SMU_THROTTLER_PPT0_BIT = 0 # macro +SMU_THROTTLER_PPT1_BIT = 1 # macro +SMU_THROTTLER_PPT2_BIT = 2 # macro +SMU_THROTTLER_PPT3_BIT = 3 # macro +SMU_THROTTLER_SPL_BIT = 4 # macro +SMU_THROTTLER_FPPT_BIT = 5 # macro +SMU_THROTTLER_SPPT_BIT = 6 # macro +SMU_THROTTLER_SPPT_APU_BIT = 7 # macro +SMU_THROTTLER_TDC_GFX_BIT = 16 # macro +SMU_THROTTLER_TDC_SOC_BIT = 17 # macro +SMU_THROTTLER_TDC_MEM_BIT = 18 # macro +SMU_THROTTLER_TDC_VDD_BIT = 19 # macro +SMU_THROTTLER_TDC_CVIP_BIT = 20 # macro +SMU_THROTTLER_EDC_CPU_BIT = 21 # macro +SMU_THROTTLER_EDC_GFX_BIT = 22 # macro +SMU_THROTTLER_APCC_BIT = 23 # macro +SMU_THROTTLER_TEMP_GPU_BIT = 32 # macro +SMU_THROTTLER_TEMP_CORE_BIT = 33 # macro +SMU_THROTTLER_TEMP_MEM_BIT = 34 # macro +SMU_THROTTLER_TEMP_EDGE_BIT = 35 # macro +SMU_THROTTLER_TEMP_HOTSPOT_BIT = 36 # macro +SMU_THROTTLER_TEMP_SOC_BIT = 37 # macro +SMU_THROTTLER_TEMP_VR_GFX_BIT = 38 # macro +SMU_THROTTLER_TEMP_VR_SOC_BIT = 39 # macro +SMU_THROTTLER_TEMP_VR_MEM0_BIT = 40 # macro +SMU_THROTTLER_TEMP_VR_MEM1_BIT = 41 # macro +SMU_THROTTLER_TEMP_LIQUID0_BIT = 42 # macro +SMU_THROTTLER_TEMP_LIQUID1_BIT = 43 # macro +SMU_THROTTLER_VRHOT0_BIT = 44 # macro +SMU_THROTTLER_VRHOT1_BIT = 45 # macro +SMU_THROTTLER_PROCHOT_CPU_BIT = 46 # macro +SMU_THROTTLER_PROCHOT_GFX_BIT = 47 # macro +SMU_THROTTLER_PPM_BIT = 56 # macro +SMU_THROTTLER_FIT_BIT = 57 # macro +# def SMU_TABLE_INIT(tables, table_id, s, a, d): # macro +# return {tables[table_id].size=s;tables[table_id].align=a;tables[table_id].domain=d;}(0) +class struct_smu_hw_power_state(Structure): + pass + +struct_smu_hw_power_state._pack_ = 1 # source:False +struct_smu_hw_power_state._fields_ = [ + ('magic', ctypes.c_uint32), +] + +class struct_smu_power_state(Structure): + pass + + +# values for enumeration 'smu_state_ui_label' +smu_state_ui_label__enumvalues = { + 0: 'SMU_STATE_UI_LABEL_NONE', + 1: 'SMU_STATE_UI_LABEL_BATTERY', + 2: 'SMU_STATE_UI_TABEL_MIDDLE_LOW', + 3: 'SMU_STATE_UI_LABEL_BALLANCED', + 4: 'SMU_STATE_UI_LABEL_MIDDLE_HIGHT', + 5: 'SMU_STATE_UI_LABEL_PERFORMANCE', + 6: 'SMU_STATE_UI_LABEL_BACO', +} +SMU_STATE_UI_LABEL_NONE = 0 +SMU_STATE_UI_LABEL_BATTERY = 1 +SMU_STATE_UI_TABEL_MIDDLE_LOW = 2 +SMU_STATE_UI_LABEL_BALLANCED = 3 +SMU_STATE_UI_LABEL_MIDDLE_HIGHT = 4 +SMU_STATE_UI_LABEL_PERFORMANCE = 5 +SMU_STATE_UI_LABEL_BACO = 6 +smu_state_ui_label = ctypes.c_uint32 # enum + +# values for enumeration 'smu_state_classification_flag' +smu_state_classification_flag__enumvalues = { + 1: 'SMU_STATE_CLASSIFICATION_FLAG_BOOT', + 2: 'SMU_STATE_CLASSIFICATION_FLAG_THERMAL', + 4: 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE', + 8: 'SMU_STATE_CLASSIFICATION_FLAG_RESET', + 16: 'SMU_STATE_CLASSIFICATION_FLAG_FORCED', + 32: 'SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE', + 64: 'SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE', + 128: 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE', + 256: 'SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE', + 512: 'SMU_STATE_CLASSIFICATION_FLAG_UVD', + 1024: 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW', + 2048: 'SMU_STATE_CLASSIFICATION_FLAG_ACPI', + 4096: 'SMU_STATE_CLASSIFICATION_FLAG_HD2', + 8192: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_HD', + 16384: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_SD', + 32768: 'SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE', + 65536: 'SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE', + 131072: 'SMU_STATE_CLASSIFICATION_FLAG_BACO', + 262144: 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2', + 524288: 'SMU_STATE_CLASSIFICATION_FLAG_ULV', + 1048576: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC', +} +SMU_STATE_CLASSIFICATION_FLAG_BOOT = 1 +SMU_STATE_CLASSIFICATION_FLAG_THERMAL = 2 +SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE = 4 +SMU_STATE_CLASSIFICATION_FLAG_RESET = 8 +SMU_STATE_CLASSIFICATION_FLAG_FORCED = 16 +SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE = 32 +SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE = 64 +SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE = 128 +SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE = 256 +SMU_STATE_CLASSIFICATION_FLAG_UVD = 512 +SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW = 1024 +SMU_STATE_CLASSIFICATION_FLAG_ACPI = 2048 +SMU_STATE_CLASSIFICATION_FLAG_HD2 = 4096 +SMU_STATE_CLASSIFICATION_FLAG_UVD_HD = 8192 +SMU_STATE_CLASSIFICATION_FLAG_UVD_SD = 16384 +SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE = 32768 +SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE = 65536 +SMU_STATE_CLASSIFICATION_FLAG_BACO = 131072 +SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2 = 262144 +SMU_STATE_CLASSIFICATION_FLAG_ULV = 524288 +SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC = 1048576 +smu_state_classification_flag = ctypes.c_uint32 # enum +class struct_smu_state_classification_block(Structure): + pass + +struct_smu_state_classification_block._pack_ = 1 # source:False +struct_smu_state_classification_block._fields_ = [ + ('ui_label', smu_state_ui_label), + ('flags', smu_state_classification_flag), + ('bios_index', ctypes.c_int32), + ('temporary_state', ctypes.c_bool), + ('to_be_deleted', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 2), +] + +class struct_smu_state_pcie_block(Structure): + pass + +struct_smu_state_pcie_block._pack_ = 1 # source:False +struct_smu_state_pcie_block._fields_ = [ + ('lanes', ctypes.c_uint32), +] + + +# values for enumeration 'smu_refreshrate_source' +smu_refreshrate_source__enumvalues = { + 0: 'SMU_REFRESHRATE_SOURCE_EDID', + 1: 'SMU_REFRESHRATE_SOURCE_EXPLICIT', +} +SMU_REFRESHRATE_SOURCE_EDID = 0 +SMU_REFRESHRATE_SOURCE_EXPLICIT = 1 +smu_refreshrate_source = ctypes.c_uint32 # enum +class struct_smu_state_display_block(Structure): + pass + +struct_smu_state_display_block._pack_ = 1 # source:False +struct_smu_state_display_block._fields_ = [ + ('disable_frame_modulation', ctypes.c_bool), + ('limit_refreshrate', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 2), + ('refreshrate_source', smu_refreshrate_source), + ('explicit_refreshrate', ctypes.c_int32), + ('edid_refreshrate_index', ctypes.c_int32), + ('enable_vari_bright', ctypes.c_bool), + ('PADDING_1', ctypes.c_ubyte * 3), +] + +class struct_smu_state_memory_block(Structure): + pass + +struct_smu_state_memory_block._pack_ = 1 # source:False +struct_smu_state_memory_block._fields_ = [ + ('dll_off', ctypes.c_bool), + ('m3arb', ctypes.c_ubyte), + ('unused', ctypes.c_ubyte * 3), +] + +class struct_smu_state_software_algorithm_block(Structure): + pass + +struct_smu_state_software_algorithm_block._pack_ = 1 # source:False +struct_smu_state_software_algorithm_block._fields_ = [ + ('disable_load_balancing', ctypes.c_bool), + ('enable_sleep_for_timestamps', ctypes.c_bool), +] + +class struct_smu_temperature_range(Structure): + pass + +struct_smu_temperature_range._pack_ = 1 # source:False +struct_smu_temperature_range._fields_ = [ + ('min', ctypes.c_int32), + ('max', ctypes.c_int32), + ('edge_emergency_max', ctypes.c_int32), + ('hotspot_min', ctypes.c_int32), + ('hotspot_crit_max', ctypes.c_int32), + ('hotspot_emergency_max', ctypes.c_int32), + ('mem_min', ctypes.c_int32), + ('mem_crit_max', ctypes.c_int32), + ('mem_emergency_max', ctypes.c_int32), + ('software_shutdown_temp', ctypes.c_int32), + ('software_shutdown_temp_offset', ctypes.c_int32), +] + +class struct_smu_state_validation_block(Structure): + pass + +struct_smu_state_validation_block._pack_ = 1 # source:False +struct_smu_state_validation_block._fields_ = [ + ('single_display_only', ctypes.c_bool), + ('disallow_on_dc', ctypes.c_bool), + ('supported_power_levels', ctypes.c_ubyte), +] + +class struct_smu_uvd_clocks(Structure): + pass + +struct_smu_uvd_clocks._pack_ = 1 # source:False +struct_smu_uvd_clocks._fields_ = [ + ('vclk', ctypes.c_uint32), + ('dclk', ctypes.c_uint32), +] + + +# values for enumeration 'smu_power_src_type' +smu_power_src_type__enumvalues = { + 0: 'SMU_POWER_SOURCE_AC', + 1: 'SMU_POWER_SOURCE_DC', + 2: 'SMU_POWER_SOURCE_COUNT', +} +SMU_POWER_SOURCE_AC = 0 +SMU_POWER_SOURCE_DC = 1 +SMU_POWER_SOURCE_COUNT = 2 +smu_power_src_type = ctypes.c_uint32 # enum + +# values for enumeration 'smu_ppt_limit_type' +smu_ppt_limit_type__enumvalues = { + 0: 'SMU_DEFAULT_PPT_LIMIT', + 1: 'SMU_FAST_PPT_LIMIT', +} +SMU_DEFAULT_PPT_LIMIT = 0 +SMU_FAST_PPT_LIMIT = 1 +smu_ppt_limit_type = ctypes.c_uint32 # enum + +# values for enumeration 'smu_ppt_limit_level' +smu_ppt_limit_level__enumvalues = { + -1: 'SMU_PPT_LIMIT_MIN', + 0: 'SMU_PPT_LIMIT_CURRENT', + 1: 'SMU_PPT_LIMIT_DEFAULT', + 2: 'SMU_PPT_LIMIT_MAX', +} +SMU_PPT_LIMIT_MIN = -1 +SMU_PPT_LIMIT_CURRENT = 0 +SMU_PPT_LIMIT_DEFAULT = 1 +SMU_PPT_LIMIT_MAX = 2 +smu_ppt_limit_level = ctypes.c_int32 # enum + +# values for enumeration 'smu_memory_pool_size' +smu_memory_pool_size__enumvalues = { + 0: 'SMU_MEMORY_POOL_SIZE_ZERO', + 268435456: 'SMU_MEMORY_POOL_SIZE_256_MB', + 536870912: 'SMU_MEMORY_POOL_SIZE_512_MB', + 1073741824: 'SMU_MEMORY_POOL_SIZE_1_GB', + 2147483648: 'SMU_MEMORY_POOL_SIZE_2_GB', +} +SMU_MEMORY_POOL_SIZE_ZERO = 0 +SMU_MEMORY_POOL_SIZE_256_MB = 268435456 +SMU_MEMORY_POOL_SIZE_512_MB = 536870912 +SMU_MEMORY_POOL_SIZE_1_GB = 1073741824 +SMU_MEMORY_POOL_SIZE_2_GB = 2147483648 +smu_memory_pool_size = ctypes.c_uint32 # enum + +# values for enumeration 'smu_clk_type' +smu_clk_type__enumvalues = { + 0: 'SMU_GFXCLK', + 1: 'SMU_VCLK', + 2: 'SMU_DCLK', + 3: 'SMU_VCLK1', + 4: 'SMU_DCLK1', + 5: 'SMU_ECLK', + 6: 'SMU_SOCCLK', + 7: 'SMU_UCLK', + 8: 'SMU_DCEFCLK', + 9: 'SMU_DISPCLK', + 10: 'SMU_PIXCLK', + 11: 'SMU_PHYCLK', + 12: 'SMU_FCLK', + 13: 'SMU_SCLK', + 14: 'SMU_MCLK', + 15: 'SMU_PCIE', + 16: 'SMU_LCLK', + 17: 'SMU_OD_CCLK', + 18: 'SMU_OD_SCLK', + 19: 'SMU_OD_MCLK', + 20: 'SMU_OD_VDDC_CURVE', + 21: 'SMU_OD_RANGE', + 22: 'SMU_OD_VDDGFX_OFFSET', + 23: 'SMU_OD_FAN_CURVE', + 24: 'SMU_OD_ACOUSTIC_LIMIT', + 25: 'SMU_OD_ACOUSTIC_TARGET', + 26: 'SMU_OD_FAN_TARGET_TEMPERATURE', + 27: 'SMU_OD_FAN_MINIMUM_PWM', + 28: 'SMU_CLK_COUNT', +} +SMU_GFXCLK = 0 +SMU_VCLK = 1 +SMU_DCLK = 2 +SMU_VCLK1 = 3 +SMU_DCLK1 = 4 +SMU_ECLK = 5 +SMU_SOCCLK = 6 +SMU_UCLK = 7 +SMU_DCEFCLK = 8 +SMU_DISPCLK = 9 +SMU_PIXCLK = 10 +SMU_PHYCLK = 11 +SMU_FCLK = 12 +SMU_SCLK = 13 +SMU_MCLK = 14 +SMU_PCIE = 15 +SMU_LCLK = 16 +SMU_OD_CCLK = 17 +SMU_OD_SCLK = 18 +SMU_OD_MCLK = 19 +SMU_OD_VDDC_CURVE = 20 +SMU_OD_RANGE = 21 +SMU_OD_VDDGFX_OFFSET = 22 +SMU_OD_FAN_CURVE = 23 +SMU_OD_ACOUSTIC_LIMIT = 24 +SMU_OD_ACOUSTIC_TARGET = 25 +SMU_OD_FAN_TARGET_TEMPERATURE = 26 +SMU_OD_FAN_MINIMUM_PWM = 27 +SMU_CLK_COUNT = 28 +smu_clk_type = ctypes.c_uint32 # enum +class struct_smu_user_dpm_profile(Structure): + pass + +struct_smu_user_dpm_profile._pack_ = 1 # source:False +struct_smu_user_dpm_profile._fields_ = [ + ('fan_mode', ctypes.c_uint32), + ('power_limit', ctypes.c_uint32), + ('fan_speed_pwm', ctypes.c_uint32), + ('fan_speed_rpm', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('user_od', ctypes.c_uint32), + ('clk_mask', ctypes.c_uint32 * 28), + ('clk_dependency', ctypes.c_uint32), +] + +class struct_smu_table(Structure): + pass + +class struct_amdgpu_bo(Structure): + pass + +struct_smu_table._pack_ = 1 # source:False +struct_smu_table._fields_ = [ + ('size', ctypes.c_uint64), + ('align', ctypes.c_uint32), + ('domain', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 3), + ('mc_address', ctypes.c_uint64), + ('cpu_addr', ctypes.POINTER(None)), + ('bo', ctypes.POINTER(struct_amdgpu_bo)), + ('version', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + + +# values for enumeration 'smu_perf_level_designation' +smu_perf_level_designation__enumvalues = { + 0: 'PERF_LEVEL_ACTIVITY', + 1: 'PERF_LEVEL_POWER_CONTAINMENT', +} +PERF_LEVEL_ACTIVITY = 0 +PERF_LEVEL_POWER_CONTAINMENT = 1 +smu_perf_level_designation = ctypes.c_uint32 # enum +class struct_smu_performance_level(Structure): + pass + +struct_smu_performance_level._pack_ = 1 # source:False +struct_smu_performance_level._fields_ = [ + ('core_clock', ctypes.c_uint32), + ('memory_clock', ctypes.c_uint32), + ('vddc', ctypes.c_uint32), + ('vddci', ctypes.c_uint32), + ('non_local_mem_freq', ctypes.c_uint32), + ('non_local_mem_width', ctypes.c_uint32), +] + +class struct_smu_clock_info(Structure): + pass + +struct_smu_clock_info._pack_ = 1 # source:False +struct_smu_clock_info._fields_ = [ + ('min_mem_clk', ctypes.c_uint32), + ('max_mem_clk', ctypes.c_uint32), + ('min_eng_clk', ctypes.c_uint32), + ('max_eng_clk', ctypes.c_uint32), + ('min_bus_bandwidth', ctypes.c_uint32), + ('max_bus_bandwidth', ctypes.c_uint32), +] + +class struct_smu_bios_boot_up_values(Structure): + pass + +struct_smu_bios_boot_up_values._pack_ = 1 # source:False +struct_smu_bios_boot_up_values._fields_ = [ + ('revision', ctypes.c_uint32), + ('gfxclk', ctypes.c_uint32), + ('uclk', ctypes.c_uint32), + ('socclk', ctypes.c_uint32), + ('dcefclk', ctypes.c_uint32), + ('eclk', ctypes.c_uint32), + ('vclk', ctypes.c_uint32), + ('dclk', ctypes.c_uint32), + ('vddc', ctypes.c_uint16), + ('vddci', ctypes.c_uint16), + ('mvddc', ctypes.c_uint16), + ('vdd_gfx', ctypes.c_uint16), + ('cooling_id', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 3), + ('pp_table_id', ctypes.c_uint32), + ('format_revision', ctypes.c_uint32), + ('content_revision', ctypes.c_uint32), + ('fclk', ctypes.c_uint32), + ('lclk', ctypes.c_uint32), + ('firmware_caps', ctypes.c_uint32), +] + + +# values for enumeration 'smu_table_id' +smu_table_id__enumvalues = { + 0: 'SMU_TABLE_PPTABLE', + 1: 'SMU_TABLE_WATERMARKS', + 2: 'SMU_TABLE_CUSTOM_DPM', + 3: 'SMU_TABLE_DPMCLOCKS', + 4: 'SMU_TABLE_AVFS', + 5: 'SMU_TABLE_AVFS_PSM_DEBUG', + 6: 'SMU_TABLE_AVFS_FUSE_OVERRIDE', + 7: 'SMU_TABLE_PMSTATUSLOG', + 8: 'SMU_TABLE_SMU_METRICS', + 9: 'SMU_TABLE_DRIVER_SMU_CONFIG', + 10: 'SMU_TABLE_ACTIVITY_MONITOR_COEFF', + 11: 'SMU_TABLE_OVERDRIVE', + 12: 'SMU_TABLE_I2C_COMMANDS', + 13: 'SMU_TABLE_PACE', + 14: 'SMU_TABLE_ECCINFO', + 15: 'SMU_TABLE_COMBO_PPTABLE', + 16: 'SMU_TABLE_WIFIBAND', + 17: 'SMU_TABLE_COUNT', +} +SMU_TABLE_PPTABLE = 0 +SMU_TABLE_WATERMARKS = 1 +SMU_TABLE_CUSTOM_DPM = 2 +SMU_TABLE_DPMCLOCKS = 3 +SMU_TABLE_AVFS = 4 +SMU_TABLE_AVFS_PSM_DEBUG = 5 +SMU_TABLE_AVFS_FUSE_OVERRIDE = 6 +SMU_TABLE_PMSTATUSLOG = 7 +SMU_TABLE_SMU_METRICS = 8 +SMU_TABLE_DRIVER_SMU_CONFIG = 9 +SMU_TABLE_ACTIVITY_MONITOR_COEFF = 10 +SMU_TABLE_OVERDRIVE = 11 +SMU_TABLE_I2C_COMMANDS = 12 +SMU_TABLE_PACE = 13 +SMU_TABLE_ECCINFO = 14 +SMU_TABLE_COMBO_PPTABLE = 15 +SMU_TABLE_WIFIBAND = 16 +SMU_TABLE_COUNT = 17 +smu_table_id = ctypes.c_uint32 # enum +__all__ = \ + ['ALLOWED_FEATURE_CTRL_DEFAULT', 'ALLOWED_FEATURE_CTRL_SCPM', + 'AVFS_D_COUNT', 'AVFS_D_G', 'AVFS_D_M_B', 'AVFS_D_M_S', + 'AVFS_D_e', 'AVFS_D_e__enumvalues', 'AVFS_TEMP_COLD', + 'AVFS_TEMP_COUNT', 'AVFS_TEMP_HOT', 'AVFS_TEMP_e', + 'AVFS_TEMP_e__enumvalues', 'AVFS_VOLTAGE_COUNT', + 'AVFS_VOLTAGE_GFX', 'AVFS_VOLTAGE_SOC', 'AVFS_VOLTAGE_TYPE_e', + 'AVFS_VOLTAGE_TYPE_e__enumvalues', 'AvfsDcBtcParams_t', + 'AvfsDebugTableExternal_t', 'AvfsDebugTable_t', + 'AvfsFuseOverride_t', 'BACO_SEQUENCE', 'BAMACO_SEQUENCE', + 'BOARD_GPIO_DC_GENLK_CLK', 'BOARD_GPIO_DC_GENLK_VSYNC', + 'BOARD_GPIO_DC_GEN_A', 'BOARD_GPIO_DC_GEN_B', + 'BOARD_GPIO_DC_GEN_C', 'BOARD_GPIO_DC_GEN_D', + 'BOARD_GPIO_DC_GEN_E', 'BOARD_GPIO_DC_GEN_F', + 'BOARD_GPIO_DC_GEN_G', 'BOARD_GPIO_DC_SWAPLOCK_A', + 'BOARD_GPIO_DC_SWAPLOCK_B', 'BOARD_GPIO_SMUIO_0', + 'BOARD_GPIO_SMUIO_1', 'BOARD_GPIO_SMUIO_10', + 'BOARD_GPIO_SMUIO_11', 'BOARD_GPIO_SMUIO_12', + 'BOARD_GPIO_SMUIO_13', 'BOARD_GPIO_SMUIO_14', + 'BOARD_GPIO_SMUIO_15', 'BOARD_GPIO_SMUIO_16', + 'BOARD_GPIO_SMUIO_17', 'BOARD_GPIO_SMUIO_18', + 'BOARD_GPIO_SMUIO_19', 'BOARD_GPIO_SMUIO_2', + 'BOARD_GPIO_SMUIO_20', 'BOARD_GPIO_SMUIO_21', + 'BOARD_GPIO_SMUIO_22', 'BOARD_GPIO_SMUIO_23', + 'BOARD_GPIO_SMUIO_24', 'BOARD_GPIO_SMUIO_25', + 'BOARD_GPIO_SMUIO_26', 'BOARD_GPIO_SMUIO_27', + 'BOARD_GPIO_SMUIO_28', 'BOARD_GPIO_SMUIO_29', + 'BOARD_GPIO_SMUIO_3', 'BOARD_GPIO_SMUIO_30', + 'BOARD_GPIO_SMUIO_31', 'BOARD_GPIO_SMUIO_4', 'BOARD_GPIO_SMUIO_5', + 'BOARD_GPIO_SMUIO_6', 'BOARD_GPIO_SMUIO_7', 'BOARD_GPIO_SMUIO_8', + 'BOARD_GPIO_SMUIO_9', 'BOARD_GPIO_TYPE_e', + 'BOARD_GPIO_TYPE_e__enumvalues', 'BoardTable_t', 'BootValues_t', + 'CMDCONFIG_READWRITE_BIT', 'CMDCONFIG_READWRITE_MASK', + 'CMDCONFIG_RESTART_BIT', 'CMDCONFIG_RESTART_MASK', + 'CMDCONFIG_STOP_BIT', 'CMDCONFIG_STOP_MASK', + 'CUSTOMER_VARIANT_COUNT', 'CUSTOMER_VARIANT_FALCON', + 'CUSTOMER_VARIANT_ROW', 'CUSTOMER_VARIANT_e', + 'CUSTOMER_VARIANT_e__enumvalues', 'D3HOTSequence_e', + 'D3HOTSequence_e__enumvalues', 'D3HOT_SEQUENCE_COUNT', + 'DCS_ARCH_ASYNC', 'DCS_ARCH_DISABLED', 'DCS_ARCH_FADCS', + 'DCS_ARCH_e', 'DCS_ARCH_e__enumvalues', + 'DEBUGSMC_MSG_DebugDumpExit', 'DEBUGSMC_MSG_GetDebugData', + 'DEBUGSMC_MSG_TestMessage', 'DEBUGSMC_Message_Count', + 'DEBUGSMC_VERSION', 'DEBUG_OVERRIDE_DFLL_MASTER_MODE', + 'DEBUG_OVERRIDE_DISABLE_D0i2_REENTRY_HSR_TIMER_CHECK', + 'DEBUG_OVERRIDE_DISABLE_DFLL', + 'DEBUG_OVERRIDE_DISABLE_FAST_FCLK_TIMER', + 'DEBUG_OVERRIDE_DISABLE_FMAX_VMAX', + 'DEBUG_OVERRIDE_DISABLE_IMU_FW_CHECKS', + 'DEBUG_OVERRIDE_DISABLE_VCN_PG', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_DCN_FCLK', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_MP0_FCLK', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_DCFCLK', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_FCLK', + 'DEBUG_OVERRIDE_ENABLE_PROFILING_MODE', + 'DEBUG_OVERRIDE_ENABLE_RLC_VF_BRINGUP_MODE', + 'DRAM_BIT_WIDTH_COUNT', 'DRAM_BIT_WIDTH_DISABLED', + 'DRAM_BIT_WIDTH_TYPE_e', 'DRAM_BIT_WIDTH_TYPE_e__enumvalues', + 'DRAM_BIT_WIDTH_X_128', 'DRAM_BIT_WIDTH_X_16', + 'DRAM_BIT_WIDTH_X_32', 'DRAM_BIT_WIDTH_X_64', + 'DRAM_BIT_WIDTH_X_8', 'DpmActivityMonitorCoeffIntExternal_t', + 'DpmActivityMonitorCoeffInt_t', 'DpmDescriptor_t', + 'DriverInfoTable_t', 'DriverReportedClocks_t', + 'DriverSmuConfigExternal_t', 'DriverSmuConfig_t', 'DroopInt_t', + 'EccInfoTable_t', 'EccInfo_t', 'FAN_MODE_AUTO', + 'FAN_MODE_MANUAL_LINEAR', 'FEATURE_ACDC_BIT', + 'FEATURE_ATHUB_MMHUB_PG_BIT', 'FEATURE_BACO_BIT', + 'FEATURE_BACO_CG_BIT', 'FEATURE_BACO_MPCLK_DS_BIT', + 'FEATURE_BOMXCO_SVI3_PROG_BIT', 'FEATURE_BOOT_POWER_OPT_BIT', + 'FEATURE_BOOT_TIME_CAL_BIT', + 'FEATURE_CLOCK_POWER_DOWN_BYPASS_BIT', 'FEATURE_DF_CSTATE_BIT', + 'FEATURE_DPM_DCN_BIT', 'FEATURE_DPM_FCLK_BIT', + 'FEATURE_DPM_GFXCLK_BIT', 'FEATURE_DPM_GFX_POWER_OPTIMIZER_BIT', + 'FEATURE_DPM_LINK_BIT', 'FEATURE_DPM_MP0CLK_BIT', + 'FEATURE_DPM_SOCCLK_BIT', 'FEATURE_DPM_UCLK_BIT', + 'FEATURE_DS_DCFCLK_BIT', 'FEATURE_DS_FCLK_BIT', + 'FEATURE_DS_GFXCLK_BIT', 'FEATURE_DS_LCLK_BIT', + 'FEATURE_DS_SOCCLK_BIT', 'FEATURE_DS_UCLK_BIT', + 'FEATURE_DS_VCN_BIT', 'FEATURE_EDC_PWRBRK_BIT', + 'FEATURE_FAN_CONTROL_BIT', 'FEATURE_FW_CTF_BIT', + 'FEATURE_FW_DATA_READ_BIT', 'FEATURE_FW_DSTATE_BIT', + 'FEATURE_GFXCLK_SPREAD_SPECTRUM_BIT', 'FEATURE_GFXOFF_BIT', + 'FEATURE_GFX_DCS_BIT', 'FEATURE_GFX_EDC_BIT', + 'FEATURE_GFX_IMU_BIT', 'FEATURE_GFX_PCC_DFLL_BIT', + 'FEATURE_GFX_READ_MARGIN_BIT', 'FEATURE_GFX_ULV_BIT', + 'FEATURE_GTHR_BIT', 'FEATURE_LED_DISPLAY_BIT', + 'FEATURE_MEM_TEMP_READ_BIT', 'FEATURE_MM_DPM_BIT', + 'FEATURE_OPTIMIZED_VMIN_BIT', 'FEATURE_OUT_OF_BAND_MONITOR_BIT', + 'FEATURE_PWR_ALL', 'FEATURE_PWR_BACO', 'FEATURE_PWR_DOMAIN_COUNT', + 'FEATURE_PWR_DOMAIN_e', 'FEATURE_PWR_DOMAIN_e__enumvalues', + 'FEATURE_PWR_GFX', 'FEATURE_PWR_S5', 'FEATURE_PWR_SOC', + 'FEATURE_SMARTSHIFT_BIT', 'FEATURE_SOC_CG_BIT', + 'FEATURE_SOC_MPCLK_DS_BIT', 'FEATURE_SOC_PCC_BIT', + 'FEATURE_SPARE_52_BIT', 'FEATURE_SPARE_53_BIT', + 'FEATURE_SPARE_54_BIT', 'FEATURE_SPARE_55_BIT', + 'FEATURE_SPARE_56_BIT', 'FEATURE_SPARE_57_BIT', + 'FEATURE_SPARE_58_BIT', 'FEATURE_SPARE_59_BIT', + 'FEATURE_SPARE_60_BIT', 'FEATURE_SPARE_61_BIT', + 'FEATURE_SPARE_62_BIT', 'FEATURE_SPARE_63_BIT', + 'FEATURE_THROTTLERS_BIT', 'FEATURE_VDDIO_MEM_SCALING_BIT', + 'FEATURE_VMEMP_SCALING_BIT', 'FEATURE_VR0HOT_BIT', + 'FOPT_CALC_AC_CALC_DC', 'FOPT_CALC_AC_PPTABLE_DC', 'FOPT_CALC_e', + 'FOPT_CALC_e__enumvalues', 'FOPT_PPTABLE_AC_CALC_DC', + 'FOPT_PPTABLE_AC_PPTABLE_DC', 'FW_DSTATE_CLDO_PRG_BIT', + 'FW_DSTATE_CSRCLK_DS_BIT', 'FW_DSTATE_D0i3_2_QUIET_FW_BIT', + 'FW_DSTATE_DF_PLL_PWRDN_BIT', 'FW_DSTATE_G6_HSR_BIT', + 'FW_DSTATE_G6_PHY_VMEMP_OFF_BIT', 'FW_DSTATE_GFX_PSI6_BIT', + 'FW_DSTATE_GFX_VR_PWR_STAGE_BIT', 'FW_DSTATE_HSR_NON_STROBE_BIT', + 'FW_DSTATE_MALL_ALLOC_BIT', 'FW_DSTATE_MALL_FLUSH_BIT', + 'FW_DSTATE_MEM_PLL_PWRDN_BIT', 'FW_DSTATE_MEM_PSI_BIT', + 'FW_DSTATE_MMHUB_INTERLOCK_BIT', 'FW_DSTATE_MP0_ENTER_WFI_BIT', + 'FW_DSTATE_MP1_WHISPER_MODE_BIT', 'FW_DSTATE_SMN_DS_BIT', + 'FW_DSTATE_SOC_LIV_MIN_BIT', 'FW_DSTATE_SOC_PLL_PWRDN_BIT', + 'FW_DSTATE_SOC_PSI_BIT', 'FW_DSTATE_SOC_ULV_BIT', + 'FW_DSTATE_UCP_DS_BIT', 'FW_DSTATE_U_LOW_PWR_MODE_EN_BIT', + 'FW_DSTATE_U_PSI_BIT', 'FW_DSTATE_U_ULV_BIT', 'FanMode_e', + 'FanMode_e__enumvalues', 'GPIO_INT_POLARITY_ACTIVE_HIGH', + 'GPIO_INT_POLARITY_ACTIVE_LOW', 'GpioIntPolarity_e', + 'GpioIntPolarity_e__enumvalues', 'I2C_CMD_COUNT', 'I2C_CMD_READ', + 'I2C_CMD_WRITE', 'I2C_CONTROLLER_DISABLED', + 'I2C_CONTROLLER_ENABLED', 'I2C_CONTROLLER_NAME_COUNT', + 'I2C_CONTROLLER_NAME_FAN_INTAKE', 'I2C_CONTROLLER_NAME_LIQUID0', + 'I2C_CONTROLLER_NAME_LIQUID1', 'I2C_CONTROLLER_NAME_PLX', + 'I2C_CONTROLLER_NAME_VR_GFX', 'I2C_CONTROLLER_NAME_VR_SOC', + 'I2C_CONTROLLER_NAME_VR_VDDIO', 'I2C_CONTROLLER_NAME_VR_VMEMP', + 'I2C_CONTROLLER_PORT_0', 'I2C_CONTROLLER_PORT_1', + 'I2C_CONTROLLER_PORT_COUNT', 'I2C_CONTROLLER_PROTOCOL_COUNT', + 'I2C_CONTROLLER_PROTOCOL_INA3221', + 'I2C_CONTROLLER_PROTOCOL_TMP_MAX31875', + 'I2C_CONTROLLER_PROTOCOL_TMP_MAX6604', + 'I2C_CONTROLLER_PROTOCOL_VR_IR35217', + 'I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5', + 'I2C_CONTROLLER_THROTTLER_COUNT', + 'I2C_CONTROLLER_THROTTLER_FAN_INTAKE', + 'I2C_CONTROLLER_THROTTLER_INA3221', + 'I2C_CONTROLLER_THROTTLER_LIQUID0', + 'I2C_CONTROLLER_THROTTLER_LIQUID1', + 'I2C_CONTROLLER_THROTTLER_PLX', + 'I2C_CONTROLLER_THROTTLER_TYPE_NONE', + 'I2C_CONTROLLER_THROTTLER_VR_GFX', + 'I2C_CONTROLLER_THROTTLER_VR_SOC', + 'I2C_CONTROLLER_THROTTLER_VR_VDDIO', + 'I2C_CONTROLLER_THROTTLER_VR_VMEMP', 'I2C_PORT_GPIO', + 'I2C_PORT_SVD_SCL', 'I2C_SPEED_COUNT', 'I2C_SPEED_FAST_100K', + 'I2C_SPEED_FAST_400K', 'I2C_SPEED_FAST_50K', + 'I2C_SPEED_FAST_PLUS_1M', 'I2C_SPEED_HIGH_1M', + 'I2C_SPEED_HIGH_2M', 'I2cCmdType_e', 'I2cCmdType_e__enumvalues', + 'I2cControllerConfig_t', 'I2cControllerName_e', + 'I2cControllerName_e__enumvalues', 'I2cControllerPort_e', + 'I2cControllerPort_e__enumvalues', 'I2cControllerProtocol_e', + 'I2cControllerProtocol_e__enumvalues', 'I2cControllerThrottler_e', + 'I2cControllerThrottler_e__enumvalues', 'I2cPort_e', + 'I2cPort_e__enumvalues', 'I2cSpeed_e', 'I2cSpeed_e__enumvalues', + 'IH_INTERRUPT_CONTEXT_ID_AC', 'IH_INTERRUPT_CONTEXT_ID_AUDIO_D0', + 'IH_INTERRUPT_CONTEXT_ID_AUDIO_D3', + 'IH_INTERRUPT_CONTEXT_ID_BACO', 'IH_INTERRUPT_CONTEXT_ID_DC', + 'IH_INTERRUPT_CONTEXT_ID_FAN_ABNORMAL', + 'IH_INTERRUPT_CONTEXT_ID_FAN_RECOVERY', + 'IH_INTERRUPT_CONTEXT_ID_THERMAL_THROTTLING', + 'IH_INTERRUPT_ID_TO_DRIVER', 'INVALID_BOARD_GPIO', + 'LED_DISPLAY_ERROR_BIT', 'LED_DISPLAY_GFX_DPM_BIT', + 'LED_DISPLAY_PCIE_BIT', 'LinearInt_t', 'MARKETING_BASE_CLOCKS', + 'MARKETING_BOOST_CLOCKS', 'MARKETING_GAME_CLOCKS', + 'MAX_BOARD_GPIO_SMUIO_NUM', 'MAX_SW_I2C_COMMANDS', + 'MEM_TEMP_READ_IN_BAND_DUMMY_PSTATE_BIT', + 'MEM_TEMP_READ_IN_BAND_REFRESH_BIT', + 'MEM_TEMP_READ_OUT_OF_BAND_BIT', 'MEM_VENDOR_COUNT', + 'MEM_VENDOR_ELPIDA', 'MEM_VENDOR_ESMT', 'MEM_VENDOR_ETRON', + 'MEM_VENDOR_HYNIX', 'MEM_VENDOR_INFINEON', 'MEM_VENDOR_MICRON', + 'MEM_VENDOR_MOSEL', 'MEM_VENDOR_NANYA', 'MEM_VENDOR_PLACEHOLDER0', + 'MEM_VENDOR_PLACEHOLDER1', 'MEM_VENDOR_PLACEHOLDER2', + 'MEM_VENDOR_PLACEHOLDER3', 'MEM_VENDOR_PLACEHOLDER4', + 'MEM_VENDOR_PLACEHOLDER5', 'MEM_VENDOR_SAMSUNG', + 'MEM_VENDOR_WINBOND', 'MEM_VENDOR_e', 'MEM_VENDOR_e__enumvalues', + 'MSR_SEQUENCE', 'MsgLimits_t', 'NUM_DCFCLK_DPM_LEVELS', + 'NUM_DCLK_DPM_LEVELS', 'NUM_DISPCLK_DPM_LEVELS', + 'NUM_DPPCLK_DPM_LEVELS', 'NUM_DPREFCLK_DPM_LEVELS', + 'NUM_DTBCLK_DPM_LEVELS', 'NUM_FCLK_DPM_LEVELS', 'NUM_FEATURES', + 'NUM_GFXCLK_DPM_LEVELS', 'NUM_I2C_CONTROLLERS', 'NUM_LINK_LEVELS', + 'NUM_MP0CLK_DPM_LEVELS', 'NUM_OD_FAN_MAX_POINTS', + 'NUM_SOCCLK_DPM_LEVELS', 'NUM_UCLK_DPM_LEVELS', + 'NUM_VCLK_DPM_LEVELS', 'NUM_WM_RANGES', 'OverDriveLimits_t', + 'OverDriveTableExternal_t', 'OverDriveTable_t', + 'PERF_LEVEL_ACTIVITY', 'PERF_LEVEL_POWER_CONTAINMENT', + 'PG_DYNAMIC_MODE', 'PG_POWER_DOWN', 'PG_POWER_UP', + 'PG_STATIC_MODE', 'PMFW_VOLT_PLANE_COUNT', 'PMFW_VOLT_PLANE_GFX', + 'PMFW_VOLT_PLANE_SOC', 'PMFW_VOLT_PLANE_e', + 'PMFW_VOLT_PLANE_e__enumvalues', 'POWER_SOURCE_AC', + 'POWER_SOURCE_COUNT', 'POWER_SOURCE_DC', 'POWER_SOURCE_e', + 'POWER_SOURCE_e__enumvalues', 'PPCLK_COUNT', 'PPCLK_DCFCLK', + 'PPCLK_DCLK_0', 'PPCLK_DCLK_1', 'PPCLK_DISPCLK', 'PPCLK_DPPCLK', + 'PPCLK_DPREFCLK', 'PPCLK_DTBCLK', 'PPCLK_FCLK', 'PPCLK_GFXCLK', + 'PPCLK_SOCCLK', 'PPCLK_UCLK', 'PPCLK_VCLK_0', 'PPCLK_VCLK_1', + 'PPCLK_e', 'PPCLK_e__enumvalues', 'PPSMC_MSG_AllowGfxDcs', + 'PPSMC_MSG_AllowGfxOff', 'PPSMC_MSG_AllowIHHostInterrupt', + 'PPSMC_MSG_ArmD3', 'PPSMC_MSG_BacoAudioD3PME', + 'PPSMC_MSG_DALNotPresent', 'PPSMC_MSG_DisableAllSmuFeatures', + 'PPSMC_MSG_DisableSmuFeaturesHigh', + 'PPSMC_MSG_DisableSmuFeaturesLow', 'PPSMC_MSG_DisallowGfxDcs', + 'PPSMC_MSG_DisallowGfxOff', 'PPSMC_MSG_DramLogSetDramAddrHigh', + 'PPSMC_MSG_DramLogSetDramAddrLow', 'PPSMC_MSG_DramLogSetDramSize', + 'PPSMC_MSG_DumpSTBtoDram', 'PPSMC_MSG_EnableAllSmuFeatures', + 'PPSMC_MSG_EnableAudioStutterWA', + 'PPSMC_MSG_EnableSmuFeaturesHigh', + 'PPSMC_MSG_EnableSmuFeaturesLow', 'PPSMC_MSG_EnableUCLKShadow', + 'PPSMC_MSG_EnterBaco', 'PPSMC_MSG_ExitBaco', + 'PPSMC_MSG_GetDcModeMaxDpmFreq', 'PPSMC_MSG_GetDebugData', + 'PPSMC_MSG_GetDpmFreqByIndex', 'PPSMC_MSG_GetDriverIfVersion', + 'PPSMC_MSG_GetMaxDpmFreq', 'PPSMC_MSG_GetMinDpmFreq', + 'PPSMC_MSG_GetPptLimit', 'PPSMC_MSG_GetRunningSmuFeaturesHigh', + 'PPSMC_MSG_GetRunningSmuFeaturesLow', 'PPSMC_MSG_GetSmuVersion', + 'PPSMC_MSG_GetVoltageByDpm', 'PPSMC_MSG_Mode1Reset', + 'PPSMC_MSG_Mode2Reset', 'PPSMC_MSG_NotifyPowerSource', + 'PPSMC_MSG_OverridePcieParameters', 'PPSMC_MSG_PowerDownJpeg', + 'PPSMC_MSG_PowerDownUmsch', 'PPSMC_MSG_PowerDownVcn', + 'PPSMC_MSG_PowerUpJpeg', 'PPSMC_MSG_PowerUpUmsch', + 'PPSMC_MSG_PowerUpVcn', 'PPSMC_MSG_PrepareMp1ForUnload', + 'PPSMC_MSG_ReenableAcDcInterrupt', 'PPSMC_MSG_RunDcBtc', + 'PPSMC_MSG_STBtoDramLogSetDramAddrHigh', + 'PPSMC_MSG_STBtoDramLogSetDramAddrLow', + 'PPSMC_MSG_STBtoDramLogSetDramSize', + 'PPSMC_MSG_SetAllowedFeaturesMaskHigh', + 'PPSMC_MSG_SetAllowedFeaturesMaskLow', + 'PPSMC_MSG_SetBadMemoryPagesRetiredFlagsPerChannel', + 'PPSMC_MSG_SetDcsArch', 'PPSMC_MSG_SetDriverDramAddrHigh', + 'PPSMC_MSG_SetDriverDramAddrLow', + 'PPSMC_MSG_SetExternalClientDfCstateAllow', + 'PPSMC_MSG_SetFwDstatesMask', 'PPSMC_MSG_SetGpoAllow', + 'PPSMC_MSG_SetHardMaxByFreq', 'PPSMC_MSG_SetHardMinByFreq', + 'PPSMC_MSG_SetMGpuFanBoostLimitRpm', + 'PPSMC_MSG_SetNumBadMemoryPagesRetired', 'PPSMC_MSG_SetPptLimit', + 'PPSMC_MSG_SetPriorityDeltaGain', 'PPSMC_MSG_SetSoftMaxByFreq', + 'PPSMC_MSG_SetSoftMinByFreq', + 'PPSMC_MSG_SetSystemVirtualDramAddrHigh', + 'PPSMC_MSG_SetSystemVirtualDramAddrLow', + 'PPSMC_MSG_SetTemperatureInputSelect', + 'PPSMC_MSG_SetThrottlerMask', 'PPSMC_MSG_SetToolsDramAddrHigh', + 'PPSMC_MSG_SetToolsDramAddrLow', 'PPSMC_MSG_SetVideoFps', + 'PPSMC_MSG_SetWorkloadMask', 'PPSMC_MSG_TestMessage', + 'PPSMC_MSG_TransferTableDram2Smu', + 'PPSMC_MSG_TransferTableSmu2Dram', 'PPSMC_MSG_TriggerVFFLR', + 'PPSMC_MSG_UseDefaultPPTable', 'PPSMC_Message_Count', + 'PPSMC_Result_CmdRejectedBusy', 'PPSMC_Result_CmdRejectedPrereq', + 'PPSMC_Result_Failed', 'PPSMC_Result_OK', + 'PPSMC_Result_UnknownCmd', 'PPSMC_VERSION', 'PPTABLE_VERSION', + 'PPT_THROTTLER_COUNT', 'PPT_THROTTLER_PPT0', 'PPT_THROTTLER_PPT1', + 'PPT_THROTTLER_PPT2', 'PPT_THROTTLER_PPT3', 'PPT_THROTTLER_e', + 'PPT_THROTTLER_e__enumvalues', 'PPTable_t', + 'PP_GRTAVFS_FW_COMMON_FUSE_COUNT', 'PP_GRTAVFS_FW_COMMON_FUSE_e', + 'PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4', 'PP_GRTAVFS_FW_SEP_FUSE_COUNT', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1', + 'PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY', + 'PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY', + 'PP_GRTAVFS_FW_SEP_FUSE_e', + 'PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE0', 'PP_GRTAVFS_HW_CPO_CTL_ZONE1', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE2', 'PP_GRTAVFS_HW_CPO_CTL_ZONE3', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE4', 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4', 'PP_GRTAVFS_HW_FUSE_COUNT', + 'PP_GRTAVFS_HW_FUSE_e', 'PP_GRTAVFS_HW_FUSE_e__enumvalues', + 'PP_GRTAVFS_HW_RESERVED_0', 'PP_GRTAVFS_HW_RESERVED_1', + 'PP_GRTAVFS_HW_RESERVED_2', 'PP_GRTAVFS_HW_RESERVED_3', + 'PP_GRTAVFS_HW_RESERVED_4', 'PP_GRTAVFS_HW_RESERVED_5', + 'PP_GRTAVFS_HW_RESERVED_6', 'PP_GRTAVFS_HW_VOLTAGE_GB', + 'PP_GRTAVFS_HW_ZONE0_VF', 'PP_GRTAVFS_HW_ZONE1_VF1', + 'PP_GRTAVFS_HW_ZONE2_VF2', 'PP_GRTAVFS_HW_ZONE3_VF3', + 'PP_NUM_OD_VF_CURVE_POINTS', 'PP_NUM_RTAVFS_PWL_ZONES', + 'PP_OD_FEATURE_COUNT', 'PP_OD_FEATURE_FAN_CURVE_BIT', + 'PP_OD_FEATURE_GFXCLK_BIT', 'PP_OD_FEATURE_GFX_VF_CURVE_BIT', + 'PP_OD_FEATURE_PPT_BIT', 'PP_OD_FEATURE_TEMPERATURE_BIT', + 'PP_OD_FEATURE_UCLK_BIT', 'PP_OD_FEATURE_ZERO_FAN_BIT', + 'PSI_SEL_VR0_PLANE0_PSI0', 'PSI_SEL_VR0_PLANE0_PSI1', + 'PSI_SEL_VR0_PLANE1_PSI0', 'PSI_SEL_VR0_PLANE1_PSI1', + 'PSI_SEL_VR1_PLANE0_PSI0', 'PSI_SEL_VR1_PLANE0_PSI1', + 'PSI_SEL_VR1_PLANE1_PSI0', 'PSI_SEL_VR1_PLANE1_PSI1', + 'PWR_CONFIG_TCP_ESTIMATED', 'PWR_CONFIG_TCP_MEASURED', + 'PWR_CONFIG_TDP', 'PWR_CONFIG_TGP', 'PowerGatingMode_e', + 'PowerGatingMode_e__enumvalues', 'PowerGatingSettings_e', + 'PowerGatingSettings_e__enumvalues', 'PwrConfig_e', + 'PwrConfig_e__enumvalues', 'QuadraticInt_t', + 'SMARTSHIFT_VERSION_1', 'SMARTSHIFT_VERSION_2', + 'SMARTSHIFT_VERSION_3', 'SMARTSHIFT_VERSION_e', + 'SMARTSHIFT_VERSION_e__enumvalues', 'SMU13_0_0_DRIVER_IF_VERSION', + 'SMU13_DRIVER_IF_V13_0_0_H', 'SMU_CLK_COUNT', + 'SMU_CUSTOM_FAN_SPEED_PWM', 'SMU_CUSTOM_FAN_SPEED_RPM', + 'SMU_DCEFCLK', 'SMU_DCLK', 'SMU_DCLK1', 'SMU_DEFAULT_PPT_LIMIT', + 'SMU_DISPCLK', 'SMU_DPM_USER_PROFILE_RESTORE', 'SMU_ECLK', + 'SMU_FAST_PPT_LIMIT', 'SMU_FCLK', 'SMU_FW_NAME_LEN', 'SMU_GFXCLK', + 'SMU_LCLK', 'SMU_MCLK', 'SMU_MEMORY_POOL_SIZE_1_GB', + 'SMU_MEMORY_POOL_SIZE_256_MB', 'SMU_MEMORY_POOL_SIZE_2_GB', + 'SMU_MEMORY_POOL_SIZE_512_MB', 'SMU_MEMORY_POOL_SIZE_ZERO', + 'SMU_OD_ACOUSTIC_LIMIT', 'SMU_OD_ACOUSTIC_TARGET', 'SMU_OD_CCLK', + 'SMU_OD_FAN_CURVE', 'SMU_OD_FAN_MINIMUM_PWM', + 'SMU_OD_FAN_TARGET_TEMPERATURE', 'SMU_OD_MCLK', 'SMU_OD_RANGE', + 'SMU_OD_SCLK', 'SMU_OD_VDDC_CURVE', 'SMU_OD_VDDGFX_OFFSET', + 'SMU_PCIE', 'SMU_PHYCLK', 'SMU_PIXCLK', 'SMU_POWER_SOURCE_AC', + 'SMU_POWER_SOURCE_COUNT', 'SMU_POWER_SOURCE_DC', + 'SMU_PPT_LIMIT_CURRENT', 'SMU_PPT_LIMIT_DEFAULT', + 'SMU_PPT_LIMIT_MAX', 'SMU_PPT_LIMIT_MIN', + 'SMU_REFRESHRATE_SOURCE_EDID', 'SMU_REFRESHRATE_SOURCE_EXPLICIT', + 'SMU_SCLK', 'SMU_SOCCLK', + 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE', + 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2', + 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW', + 'SMU_STATE_CLASSIFICATION_FLAG_ACPI', + 'SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE', + 'SMU_STATE_CLASSIFICATION_FLAG_BACO', + 'SMU_STATE_CLASSIFICATION_FLAG_BOOT', + 'SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE', + 'SMU_STATE_CLASSIFICATION_FLAG_FORCED', + 'SMU_STATE_CLASSIFICATION_FLAG_HD2', + 'SMU_STATE_CLASSIFICATION_FLAG_RESET', + 'SMU_STATE_CLASSIFICATION_FLAG_THERMAL', + 'SMU_STATE_CLASSIFICATION_FLAG_ULV', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_HD', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_SD', 'SMU_STATE_UI_LABEL_BACO', + 'SMU_STATE_UI_LABEL_BALLANCED', 'SMU_STATE_UI_LABEL_BATTERY', + 'SMU_STATE_UI_LABEL_MIDDLE_HIGHT', 'SMU_STATE_UI_LABEL_NONE', + 'SMU_STATE_UI_LABEL_PERFORMANCE', 'SMU_STATE_UI_TABEL_MIDDLE_LOW', + 'SMU_TABLE_ACTIVITY_MONITOR_COEFF', 'SMU_TABLE_AVFS', + 'SMU_TABLE_AVFS_FUSE_OVERRIDE', 'SMU_TABLE_AVFS_PSM_DEBUG', + 'SMU_TABLE_COMBO_PPTABLE', 'SMU_TABLE_COUNT', + 'SMU_TABLE_CUSTOM_DPM', 'SMU_TABLE_DPMCLOCKS', + 'SMU_TABLE_DRIVER_SMU_CONFIG', 'SMU_TABLE_ECCINFO', + 'SMU_TABLE_I2C_COMMANDS', 'SMU_TABLE_OVERDRIVE', 'SMU_TABLE_PACE', + 'SMU_TABLE_PMSTATUSLOG', 'SMU_TABLE_PPTABLE', + 'SMU_TABLE_SMU_METRICS', 'SMU_TABLE_WATERMARKS', + 'SMU_TABLE_WIFIBAND', 'SMU_TEMPERATURE_UNITS_PER_CENTIGRADES', + 'SMU_THERMAL_MAXIMUM_ALERT_TEMP', + 'SMU_THERMAL_MINIMUM_ALERT_TEMP', 'SMU_THROTTLER_APCC_BIT', + 'SMU_THROTTLER_EDC_CPU_BIT', 'SMU_THROTTLER_EDC_GFX_BIT', + 'SMU_THROTTLER_FIT_BIT', 'SMU_THROTTLER_FPPT_BIT', + 'SMU_THROTTLER_PPM_BIT', 'SMU_THROTTLER_PPT0_BIT', + 'SMU_THROTTLER_PPT1_BIT', 'SMU_THROTTLER_PPT2_BIT', + 'SMU_THROTTLER_PPT3_BIT', 'SMU_THROTTLER_PROCHOT_CPU_BIT', + 'SMU_THROTTLER_PROCHOT_GFX_BIT', 'SMU_THROTTLER_SPL_BIT', + 'SMU_THROTTLER_SPPT_APU_BIT', 'SMU_THROTTLER_SPPT_BIT', + 'SMU_THROTTLER_TDC_CVIP_BIT', 'SMU_THROTTLER_TDC_GFX_BIT', + 'SMU_THROTTLER_TDC_MEM_BIT', 'SMU_THROTTLER_TDC_SOC_BIT', + 'SMU_THROTTLER_TDC_VDD_BIT', 'SMU_THROTTLER_TEMP_CORE_BIT', + 'SMU_THROTTLER_TEMP_EDGE_BIT', 'SMU_THROTTLER_TEMP_GPU_BIT', + 'SMU_THROTTLER_TEMP_HOTSPOT_BIT', + 'SMU_THROTTLER_TEMP_LIQUID0_BIT', + 'SMU_THROTTLER_TEMP_LIQUID1_BIT', 'SMU_THROTTLER_TEMP_MEM_BIT', + 'SMU_THROTTLER_TEMP_SOC_BIT', 'SMU_THROTTLER_TEMP_VR_GFX_BIT', + 'SMU_THROTTLER_TEMP_VR_MEM0_BIT', + 'SMU_THROTTLER_TEMP_VR_MEM1_BIT', 'SMU_THROTTLER_TEMP_VR_SOC_BIT', + 'SMU_THROTTLER_VRHOT0_BIT', 'SMU_THROTTLER_VRHOT1_BIT', + 'SMU_UCLK', 'SMU_V13_0_0_PPSMC_H', 'SMU_VCLK', 'SMU_VCLK1', + 'SVI_PLANE_COUNT', 'SVI_PLANE_GFX', 'SVI_PLANE_SOC', + 'SVI_PLANE_U', 'SVI_PLANE_VDDIO_MEM', 'SVI_PLANE_VMEMP', + 'SVI_PLANE_e', 'SVI_PLANE_e__enumvalues', 'SVI_PSI_0', + 'SVI_PSI_1', 'SVI_PSI_2', 'SVI_PSI_3', 'SVI_PSI_4', 'SVI_PSI_5', + 'SVI_PSI_6', 'SVI_PSI_7', 'SVI_PSI_e', 'SVI_PSI_e__enumvalues', + 'SkuTable_t', 'SmuMetricsExternal_t', 'SmuMetrics_t', + 'SviTelemetryScale_t', 'SwI2cCmd_t', 'SwI2cRequestExternal_t', + 'SwI2cRequest_t', 'TABLE_ACTIVITY_MONITOR_COEFF', + 'TABLE_AVFS_PSM_DEBUG', 'TABLE_COMBO_PPTABLE', 'TABLE_COUNT', + 'TABLE_DRIVER_INFO', 'TABLE_DRIVER_SMU_CONFIG', 'TABLE_ECCINFO', + 'TABLE_I2C_COMMANDS', 'TABLE_OVERDRIVE', 'TABLE_PMSTATUSLOG', + 'TABLE_PPTABLE', 'TABLE_SMU_METRICS', 'TABLE_TRANSFER_FAILED', + 'TABLE_TRANSFER_OK', 'TABLE_TRANSFER_PENDING', 'TABLE_WATERMARKS', + 'TABLE_WIFIBAND', 'TDC_THROTTLER_COUNT', 'TDC_THROTTLER_GFX', + 'TDC_THROTTLER_SOC', 'TDC_THROTTLER_U', 'TDC_THROTTLER_e', + 'TDC_THROTTLER_e__enumvalues', 'TEMP_COUNT', 'TEMP_EDGE', + 'TEMP_HOTSPOT', 'TEMP_HOTSPOT_G', 'TEMP_HOTSPOT_M', + 'TEMP_LIQUID0', 'TEMP_LIQUID1', 'TEMP_MEM', 'TEMP_PLX', + 'TEMP_VR_GFX', 'TEMP_VR_MEM0', 'TEMP_VR_MEM1', 'TEMP_VR_SOC', + 'TEMP_VR_U', 'TEMP_e', 'TEMP_e__enumvalues', 'THROTTLER_COUNT', + 'THROTTLER_FIT_BIT', 'THROTTLER_GFX_APCC_PLUS_BIT', + 'THROTTLER_PPT0_BIT', 'THROTTLER_PPT1_BIT', 'THROTTLER_PPT2_BIT', + 'THROTTLER_PPT3_BIT', 'THROTTLER_TDC_GFX_BIT', + 'THROTTLER_TDC_SOC_BIT', 'THROTTLER_TDC_U_BIT', + 'THROTTLER_TEMP_EDGE_BIT', 'THROTTLER_TEMP_HOTSPOT_BIT', + 'THROTTLER_TEMP_HOTSPOT_G_BIT', 'THROTTLER_TEMP_HOTSPOT_M_BIT', + 'THROTTLER_TEMP_LIQUID0_BIT', 'THROTTLER_TEMP_LIQUID1_BIT', + 'THROTTLER_TEMP_MEM_BIT', 'THROTTLER_TEMP_PLX_BIT', + 'THROTTLER_TEMP_VR_GFX_BIT', 'THROTTLER_TEMP_VR_MEM0_BIT', + 'THROTTLER_TEMP_VR_MEM1_BIT', 'THROTTLER_TEMP_VR_SOC_BIT', + 'THROTTLER_TEMP_VR_U_BIT', 'UCLK_DIV_BY_1', 'UCLK_DIV_BY_2', + 'UCLK_DIV_BY_4', 'UCLK_DIV_BY_8', 'UCLK_DIV_e', + 'UCLK_DIV_e__enumvalues', 'ULPS_SEQUENCE', 'VOLTAGE_MODE_COUNT', + 'VOLTAGE_MODE_FUSES', 'VOLTAGE_MODE_PPTABLE', 'VOLTAGE_MODE_e', + 'VOLTAGE_MODE_e__enumvalues', 'VR_MAPPING_PLANE_SELECT_MASK', + 'VR_MAPPING_PLANE_SELECT_SHIFT', 'VR_MAPPING_VR_SELECT_MASK', + 'VR_MAPPING_VR_SELECT_SHIFT', 'WATERMARKS_CLOCK_RANGE', + 'WATERMARKS_COUNT', 'WATERMARKS_DUMMY_PSTATE', + 'WATERMARKS_FLAGS_e', 'WATERMARKS_FLAGS_e__enumvalues', + 'WATERMARKS_MALL', 'WORKLOAD_PPLIB_COMPUTE_BIT', + 'WORKLOAD_PPLIB_COUNT', 'WORKLOAD_PPLIB_CUSTOM_BIT', + 'WORKLOAD_PPLIB_DEFAULT_BIT', 'WORKLOAD_PPLIB_FULL_SCREEN_3D_BIT', + 'WORKLOAD_PPLIB_POWER_SAVING_BIT', 'WORKLOAD_PPLIB_VIDEO_BIT', + 'WORKLOAD_PPLIB_VR_BIT', 'WORKLOAD_PPLIB_WINDOW_3D_BIT', + 'WatermarkRowGeneric_t', 'WatermarksExternal_t', 'Watermarks_t', + '__AMDGPU_SMU_H__', 'bool', 'c__EA_AVFS_D_e', 'c__EA_AVFS_TEMP_e', + 'c__EA_AVFS_VOLTAGE_TYPE_e', 'c__EA_BOARD_GPIO_TYPE_e', + 'c__EA_CUSTOMER_VARIANT_e', 'c__EA_D3HOTSequence_e', + 'c__EA_DCS_ARCH_e', 'c__EA_DRAM_BIT_WIDTH_TYPE_e', + 'c__EA_FEATURE_PWR_DOMAIN_e', 'c__EA_FOPT_CALC_e', + 'c__EA_FanMode_e', 'c__EA_GpioIntPolarity_e', + 'c__EA_I2cCmdType_e', 'c__EA_I2cControllerName_e', + 'c__EA_I2cControllerPort_e', 'c__EA_I2cControllerProtocol_e', + 'c__EA_I2cControllerThrottler_e', 'c__EA_I2cPort_e', + 'c__EA_I2cSpeed_e', 'c__EA_MEM_VENDOR_e', + 'c__EA_PMFW_VOLT_PLANE_e', 'c__EA_POWER_SOURCE_e', + 'c__EA_PPCLK_e', 'c__EA_PPT_THROTTLER_e', + 'c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e', + 'c__EA_PP_GRTAVFS_FW_SEP_FUSE_e', 'c__EA_PP_GRTAVFS_HW_FUSE_e', + 'c__EA_PowerGatingMode_e', 'c__EA_PowerGatingSettings_e', + 'c__EA_PwrConfig_e', 'c__EA_SMARTSHIFT_VERSION_e', + 'c__EA_SVI_PLANE_e', 'c__EA_SVI_PSI_e', 'c__EA_TDC_THROTTLER_e', + 'c__EA_TEMP_e', 'c__EA_UCLK_DIV_e', 'c__EA_VOLTAGE_MODE_e', + 'c__EA_WATERMARKS_FLAGS_e', 'int16_t', 'int32_t', 'int8_t', + 'smu_clk_type', 'smu_memory_pool_size', + 'smu_perf_level_designation', 'smu_power_src_type', + 'smu_ppt_limit_level', 'smu_ppt_limit_type', + 'smu_refreshrate_source', 'smu_state_classification_flag', + 'smu_state_ui_label', 'smu_table_id', 'struct_amdgpu_bo', + 'struct_c__SA_AvfsDcBtcParams_t', + 'struct_c__SA_AvfsDebugTableExternal_t', + 'struct_c__SA_AvfsDebugTable_t', + 'struct_c__SA_AvfsFuseOverride_t', 'struct_c__SA_BoardTable_t', + 'struct_c__SA_BootValues_t', + 'struct_c__SA_DpmActivityMonitorCoeffIntExternal_t', + 'struct_c__SA_DpmActivityMonitorCoeffInt_t', + 'struct_c__SA_DpmDescriptor_t', 'struct_c__SA_DriverInfoTable_t', + 'struct_c__SA_DriverReportedClocks_t', + 'struct_c__SA_DriverSmuConfigExternal_t', + 'struct_c__SA_DriverSmuConfig_t', 'struct_c__SA_DroopInt_t', + 'struct_c__SA_EccInfoTable_t', 'struct_c__SA_EccInfo_t', + 'struct_c__SA_I2cControllerConfig_t', 'struct_c__SA_LinearInt_t', + 'struct_c__SA_MsgLimits_t', 'struct_c__SA_OverDriveLimits_t', + 'struct_c__SA_OverDriveTableExternal_t', + 'struct_c__SA_OverDriveTable_t', 'struct_c__SA_PPTable_t', + 'struct_c__SA_QuadraticInt_t', 'struct_c__SA_SkuTable_t', + 'struct_c__SA_SmuMetricsExternal_t', 'struct_c__SA_SmuMetrics_t', + 'struct_c__SA_SviTelemetryScale_t', 'struct_c__SA_SwI2cCmd_t', + 'struct_c__SA_SwI2cRequestExternal_t', + 'struct_c__SA_SwI2cRequest_t', + 'struct_c__SA_WatermarkRowGeneric_t', + 'struct_c__SA_WatermarksExternal_t', 'struct_c__SA_Watermarks_t', + 'struct_smu_bios_boot_up_values', 'struct_smu_clock_info', + 'struct_smu_hw_power_state', 'struct_smu_performance_level', + 'struct_smu_power_state', 'struct_smu_state_classification_block', + 'struct_smu_state_display_block', 'struct_smu_state_memory_block', + 'struct_smu_state_pcie_block', + 'struct_smu_state_software_algorithm_block', + 'struct_smu_state_validation_block', 'struct_smu_table', + 'struct_smu_temperature_range', 'struct_smu_user_dpm_profile', + 'struct_smu_uvd_clocks', 'u32', 'uint16_t', 'uint32_t', + 'uint64_t', 'uint8_t'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v14_0_3.py b/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v14_0_3.py new file mode 100644 index 0000000000..46cc1dc94d --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/smu_v14_0_3.py @@ -0,0 +1,3605 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-include', 'stdint.h'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +__SMU_V14_0_0_PMFW_H__ = True # macro +ENABLE_DEBUG_FEATURES = True # macro +FEATURE_CCLK_DPM_BIT = 0 # macro +FEATURE_FAN_CONTROLLER_BIT = 1 # macro +FEATURE_DATA_CALCULATION_BIT = 2 # macro +FEATURE_PPT_BIT = 3 # macro +FEATURE_TDC_BIT = 4 # macro +FEATURE_THERMAL_BIT = 5 # macro +FEATURE_FIT_BIT = 6 # macro +FEATURE_EDC_BIT = 7 # macro +FEATURE_PLL_POWER_DOWN_BIT = 8 # macro +FEATURE_VDDOFF_BIT = 9 # macro +FEATURE_VCN_DPM_BIT = 10 # macro +FEATURE_DS_MPM_BIT = 11 # macro +FEATURE_FCLK_DPM_BIT = 12 # macro +FEATURE_SOCCLK_DPM_BIT = 13 # macro +FEATURE_DS_MPIO_BIT = 14 # macro +FEATURE_LCLK_DPM_BIT = 15 # macro +FEATURE_SHUBCLK_DPM_BIT = 16 # macro +FEATURE_DCFCLK_DPM_BIT = 17 # macro +FEATURE_ISP_DPM_BIT = 18 # macro +FEATURE_IPU_DPM_BIT = 19 # macro +FEATURE_GFX_DPM_BIT = 20 # macro +FEATURE_DS_GFXCLK_BIT = 10 # macro +FEATURE_DS_SOCCLK_BIT = 11 # macro +FEATURE_DS_LCLK_BIT = 13 # macro +FEATURE_LOW_POWER_DCNCLKS_BIT = 24 # macro +FEATURE_DS_SHUBCLK_BIT = 25 # macro +FEATURE_RESERVED0_BIT = 26 # macro +FEATURE_ZSTATES_BIT = 27 # macro +FEATURE_IOMMUL2_PG_BIT = 28 # macro +FEATURE_DS_FCLK_BIT = 12 # macro +FEATURE_DS_SMNCLK_BIT = 30 # macro +FEATURE_DS_MP1CLK_BIT = 31 # macro +FEATURE_WHISPER_MODE_BIT = 32 # macro +FEATURE_SMU_LOW_POWER_BIT = 33 # macro +FEATURE_RESERVED1_BIT = 34 # macro +FEATURE_GFX_DEM_BIT = 35 # macro +FEATURE_PSI_BIT = 36 # macro +FEATURE_PROCHOT_BIT = 37 # macro +FEATURE_CPUOFF_BIT = 38 # macro +FEATURE_STAPM_BIT = 39 # macro +FEATURE_S0I3_BIT = 40 # macro +FEATURE_DF_LIGHT_CSTATE = 41 # macro +FEATURE_PERF_LIMIT_BIT = 42 # macro +FEATURE_CORE_DLDO_BIT = 43 # macro +FEATURE_DVO_BIT = 44 # macro +FEATURE_DS_VCN_BIT = 44 # macro +FEATURE_CPPC_BIT = 46 # macro +FEATURE_CPPC_PREFERRED_CORES = 47 # macro +FEATURE_DF_CSTATES_BIT = 48 # macro +FEATURE_FAST_PSTATE_CLDO_BIT = 49 # macro +FEATURE_ATHUB_PG_BIT = 50 # macro +FEATURE_VDDOFF_ECO_BIT = 51 # macro +FEATURE_ZSTATES_ECO_BIT = 52 # macro +FEATURE_CC6_BIT = 53 # macro +FEATURE_DS_UMCCLK_BIT = 54 # macro +FEATURE_DS_ISPCLK_BIT = 55 # macro +FEATURE_DS_HSPCLK_BIT = 56 # macro +FEATURE_P3T_BIT = 57 # macro +FEATURE_DS_IPUCLK_BIT = 58 # macro +FEATURE_DS_VPECLK_BIT = 59 # macro +FEATURE_VPE_DPM_BIT = 60 # macro +FEATURE_SMART_L3_RINSER_BIT = 61 # macro +FEATURE_PCC_BIT = 62 # macro +NUM_FEATURES = 64 # macro +class struct_SMU14_Firmware_Footer(Structure): + pass + +struct_SMU14_Firmware_Footer._pack_ = 1 # source:False +struct_SMU14_Firmware_Footer._fields_ = [ + ('Signature', ctypes.c_uint32), +] + +SMU14_Firmware_Footer = struct_SMU14_Firmware_Footer +class struct_c__SA_SMU_Firmware_Header(Structure): + pass + +struct_c__SA_SMU_Firmware_Header._pack_ = 1 # source:False +struct_c__SA_SMU_Firmware_Header._fields_ = [ + ('ImageVersion', ctypes.c_uint32), + ('ImageVersion2', ctypes.c_uint32), + ('Padding0', ctypes.c_uint32 * 3), + ('SizeFWSigned', ctypes.c_uint32), + ('Padding1', ctypes.c_uint32 * 25), + ('FirmwareType', ctypes.c_uint32), + ('Filler', ctypes.c_uint32 * 32), +] + +SMU_Firmware_Header = struct_c__SA_SMU_Firmware_Header +class struct_c__SA_FwStatus_t(Structure): + pass + +struct_c__SA_FwStatus_t._pack_ = 1 # source:False +struct_c__SA_FwStatus_t._fields_ = [ + ('DpmHandlerID', ctypes.c_uint64, 8), + ('ActivityMonitorID', ctypes.c_uint64, 8), + ('DpmTimerID', ctypes.c_uint64, 8), + ('DpmHubID', ctypes.c_uint64, 4), + ('DpmHubTask', ctypes.c_uint64, 4), + ('CclkSyncStatus', ctypes.c_uint64, 8), + ('Ccx0CpuOff', ctypes.c_uint64, 2), + ('Ccx1CpuOff', ctypes.c_uint64, 2), + ('GfxOffStatus', ctypes.c_uint64, 2), + ('VddOff', ctypes.c_uint64, 1), + ('InWhisperMode', ctypes.c_uint64, 1), + ('ZstateStatus', ctypes.c_uint64, 4), + ('spare0', ctypes.c_uint64, 4), + ('DstateFun', ctypes.c_uint64, 4), + ('DstateDev', ctypes.c_uint64, 4), + ('P2JobHandler', ctypes.c_uint64, 24), + ('RsmuPmiP2PendingCnt', ctypes.c_uint64, 8), + ('PostCode', ctypes.c_uint64, 32), + ('MsgPortBusy', ctypes.c_uint64, 24), + ('RsmuPmiP1Pending', ctypes.c_uint64, 1), + ('DfCstateExitPending', ctypes.c_uint64, 1), + ('Ccx0Pc6ExitPending', ctypes.c_uint64, 1), + ('Ccx1Pc6ExitPending', ctypes.c_uint64, 1), + ('WarmResetPending', ctypes.c_uint64, 1), + ('spare1', ctypes.c_uint64, 3), + ('IdleMask', ctypes.c_uint64, 32), +] + +FwStatus_t = struct_c__SA_FwStatus_t +class struct_c__SA_FwStatus_t_v14_0_1(Structure): + pass + +struct_c__SA_FwStatus_t_v14_0_1._pack_ = 1 # source:False +struct_c__SA_FwStatus_t_v14_0_1._fields_ = [ + ('DpmHandlerID', ctypes.c_uint64, 8), + ('ActivityMonitorID', ctypes.c_uint64, 8), + ('DpmTimerID', ctypes.c_uint64, 8), + ('DpmHubID', ctypes.c_uint64, 4), + ('DpmHubTask', ctypes.c_uint64, 4), + ('CclkSyncStatus', ctypes.c_uint64, 8), + ('ZstateStatus', ctypes.c_uint64, 4), + ('Cpu1VddOff', ctypes.c_uint64, 4), + ('DstateFun', ctypes.c_uint64, 4), + ('DstateDev', ctypes.c_uint64, 4), + ('GfxOffStatus', ctypes.c_uint64, 2), + ('Cpu0Off', ctypes.c_uint64, 2), + ('Cpu1Off', ctypes.c_uint64, 2), + ('Cpu0VddOff', ctypes.c_uint64, 2), + ('P2JobHandler', ctypes.c_uint64, 32), + ('PostCode', ctypes.c_uint64, 32), + ('MsgPortBusy', ctypes.c_uint64, 15), + ('RsmuPmiP1Pending', ctypes.c_uint64, 1), + ('RsmuPmiP2PendingCnt', ctypes.c_uint64, 8), + ('DfCstateExitPending', ctypes.c_uint64, 1), + ('Pc6EntryPending', ctypes.c_uint64, 1), + ('Pc6ExitPending', ctypes.c_uint64, 1), + ('WarmResetPending', ctypes.c_uint64, 1), + ('Mp0ClkPending', ctypes.c_uint64, 1), + ('InWhisperMode', ctypes.c_uint64, 1), + ('spare2', ctypes.c_uint64, 2), + ('IdleMask', ctypes.c_uint64, 32), +] + +FwStatus_t_v14_0_1 = struct_c__SA_FwStatus_t_v14_0_1 +SMU_V14_0_2_PPSMC_H = True # macro +PPSMC_VERSION = 0x1 # macro +PPSMC_Result_OK = 0x1 # macro +PPSMC_Result_Failed = 0xFF # macro +PPSMC_Result_UnknownCmd = 0xFE # macro +PPSMC_Result_CmdRejectedPrereq = 0xFD # macro +PPSMC_Result_CmdRejectedBusy = 0xFC # macro +PPSMC_MSG_TestMessage = 0x1 # macro +PPSMC_MSG_GetSmuVersion = 0x2 # macro +PPSMC_MSG_GetDriverIfVersion = 0x3 # macro +PPSMC_MSG_SetAllowedFeaturesMaskLow = 0x4 # macro +PPSMC_MSG_SetAllowedFeaturesMaskHigh = 0x5 # macro +PPSMC_MSG_EnableAllSmuFeatures = 0x6 # macro +PPSMC_MSG_DisableAllSmuFeatures = 0x7 # macro +PPSMC_MSG_EnableSmuFeaturesLow = 0x8 # macro +PPSMC_MSG_EnableSmuFeaturesHigh = 0x9 # macro +PPSMC_MSG_DisableSmuFeaturesLow = 0xA # macro +PPSMC_MSG_DisableSmuFeaturesHigh = 0xB # macro +PPSMC_MSG_GetRunningSmuFeaturesLow = 0xC # macro +PPSMC_MSG_GetRunningSmuFeaturesHigh = 0xD # macro +PPSMC_MSG_SetDriverDramAddrHigh = 0xE # macro +PPSMC_MSG_SetDriverDramAddrLow = 0xF # macro +PPSMC_MSG_SetToolsDramAddrHigh = 0x10 # macro +PPSMC_MSG_SetToolsDramAddrLow = 0x11 # macro +PPSMC_MSG_TransferTableSmu2Dram = 0x12 # macro +PPSMC_MSG_TransferTableDram2Smu = 0x13 # macro +PPSMC_MSG_UseDefaultPPTable = 0x14 # macro +PPSMC_MSG_EnterBaco = 0x15 # macro +PPSMC_MSG_ExitBaco = 0x16 # macro +PPSMC_MSG_ArmD3 = 0x17 # macro +PPSMC_MSG_BacoAudioD3PME = 0x18 # macro +PPSMC_MSG_SetSoftMinByFreq = 0x19 # macro +PPSMC_MSG_SetSoftMaxByFreq = 0x1A # macro +PPSMC_MSG_SetHardMinByFreq = 0x1B # macro +PPSMC_MSG_SetHardMaxByFreq = 0x1C # macro +PPSMC_MSG_GetMinDpmFreq = 0x1D # macro +PPSMC_MSG_GetMaxDpmFreq = 0x1E # macro +PPSMC_MSG_GetDpmFreqByIndex = 0x1F # macro +PPSMC_MSG_OverridePcieParameters = 0x20 # macro +PPSMC_MSG_DramLogSetDramAddrHigh = 0x21 # macro +PPSMC_MSG_DramLogSetDramAddrLow = 0x22 # macro +PPSMC_MSG_DramLogSetDramSize = 0x23 # macro +PPSMC_MSG_SetWorkloadMask = 0x24 # macro +PPSMC_MSG_GetVoltageByDpm = 0x25 # macro +PPSMC_MSG_SetVideoFps = 0x26 # macro +PPSMC_MSG_GetDcModeMaxDpmFreq = 0x27 # macro +PPSMC_MSG_AllowGfxOff = 0x28 # macro +PPSMC_MSG_DisallowGfxOff = 0x29 # macro +PPSMC_MSG_PowerUpVcn = 0x2A # macro +PPSMC_MSG_PowerDownVcn = 0x2B # macro +PPSMC_MSG_PowerUpJpeg = 0x2C # macro +PPSMC_MSG_PowerDownJpeg = 0x2D # macro +PPSMC_MSG_PrepareMp1ForUnload = 0x2E # macro +PPSMC_MSG_SetSystemVirtualDramAddrHigh = 0x30 # macro +PPSMC_MSG_SetSystemVirtualDramAddrLow = 0x31 # macro +PPSMC_MSG_SetPptLimit = 0x32 # macro +PPSMC_MSG_GetPptLimit = 0x33 # macro +PPSMC_MSG_ReenableAcDcInterrupt = 0x34 # macro +PPSMC_MSG_NotifyPowerSource = 0x35 # macro +PPSMC_MSG_RunDcBtc = 0x36 # macro +PPSMC_MSG_SetTemperatureInputSelect = 0x38 # macro +PPSMC_MSG_SetFwDstatesMask = 0x39 # macro +PPSMC_MSG_SetThrottlerMask = 0x3A # macro +PPSMC_MSG_SetExternalClientDfCstateAllow = 0x3B # macro +PPSMC_MSG_SetMGpuFanBoostLimitRpm = 0x3C # macro +PPSMC_MSG_DumpSTBtoDram = 0x3D # macro +PPSMC_MSG_STBtoDramLogSetDramAddress = 0x3E # macro +PPSMC_MSG_DummyUndefined = 0x3F # macro +PPSMC_MSG_STBtoDramLogSetDramSize = 0x40 # macro +PPSMC_MSG_SetOBMTraceBufferLogging = 0x41 # macro +PPSMC_MSG_UseProfilingMode = 0x42 # macro +PPSMC_MSG_AllowGfxDcs = 0x43 # macro +PPSMC_MSG_DisallowGfxDcs = 0x44 # macro +PPSMC_MSG_EnableAudioStutterWA = 0x45 # macro +PPSMC_MSG_PowerUpUmsch = 0x46 # macro +PPSMC_MSG_PowerDownUmsch = 0x47 # macro +PPSMC_MSG_SetDcsArch = 0x48 # macro +PPSMC_MSG_TriggerVFFLR = 0x49 # macro +PPSMC_MSG_SetNumBadMemoryPagesRetired = 0x4A # macro +PPSMC_MSG_SetBadMemoryPagesRetiredFlagsPerChannel = 0x4B # macro +PPSMC_MSG_SetPriorityDeltaGain = 0x4C # macro +PPSMC_MSG_AllowIHHostInterrupt = 0x4D # macro +PPSMC_MSG_EnableShadowDpm = 0x4E # macro +PPSMC_MSG_Mode3Reset = 0x4F # macro +PPSMC_MSG_SetDriverDramAddr = 0x50 # macro +PPSMC_MSG_SetToolsDramAddr = 0x51 # macro +PPSMC_MSG_TransferTableSmu2DramWithAddr = 0x52 # macro +PPSMC_MSG_TransferTableDram2SmuWithAddr = 0x53 # macro +PPSMC_MSG_GetAllRunningSmuFeatures = 0x54 # macro +PPSMC_MSG_GetSvi3Voltage = 0x55 # macro +PPSMC_MSG_UpdatePolicy = 0x56 # macro +PPSMC_MSG_ExtPwrConnSupport = 0x57 # macro +PPSMC_MSG_PreloadSwPstateForUclkOverDrive = 0x58 # macro +PPSMC_Message_Count = 0x59 # macro +SMU14_DRIVER_IF_V14_0_H = True # macro +PPTABLE_VERSION = 0x1B # macro +NUM_GFXCLK_DPM_LEVELS = 16 # macro +NUM_SOCCLK_DPM_LEVELS = 8 # macro +NUM_MP0CLK_DPM_LEVELS = 2 # macro +NUM_DCLK_DPM_LEVELS = 8 # macro +NUM_VCLK_DPM_LEVELS = 8 # macro +NUM_DISPCLK_DPM_LEVELS = 8 # macro +NUM_DPPCLK_DPM_LEVELS = 8 # macro +NUM_DPREFCLK_DPM_LEVELS = 8 # macro +NUM_DCFCLK_DPM_LEVELS = 8 # macro +NUM_DTBCLK_DPM_LEVELS = 8 # macro +NUM_UCLK_DPM_LEVELS = 6 # macro +NUM_LINK_LEVELS = 3 # macro +NUM_FCLK_DPM_LEVELS = 8 # macro +NUM_OD_FAN_MAX_POINTS = 6 # macro +FEATURE_FW_DATA_READ_BIT = 0 # macro +FEATURE_DPM_GFXCLK_BIT = 1 # macro +FEATURE_DPM_GFX_POWER_OPTIMIZER_BIT = 2 # macro +FEATURE_DPM_UCLK_BIT = 3 # macro +FEATURE_DPM_FCLK_BIT = 4 # macro +FEATURE_DPM_SOCCLK_BIT = 5 # macro +FEATURE_DPM_LINK_BIT = 6 # macro +FEATURE_DPM_DCN_BIT = 7 # macro +FEATURE_VMEMP_SCALING_BIT = 8 # macro +FEATURE_VDDIO_MEM_SCALING_BIT = 9 # macro +FEATURE_DS_DCFCLK_BIT = 14 # macro +FEATURE_DS_UCLK_BIT = 15 # macro +FEATURE_GFX_ULV_BIT = 16 # macro +FEATURE_FW_DSTATE_BIT = 17 # macro +FEATURE_GFXOFF_BIT = 18 # macro +FEATURE_BACO_BIT = 19 # macro +FEATURE_MM_DPM_BIT = 20 # macro +FEATURE_SOC_MPCLK_DS_BIT = 21 # macro +FEATURE_BACO_MPCLK_DS_BIT = 22 # macro +FEATURE_THROTTLERS_BIT = 23 # macro +FEATURE_SMARTSHIFT_BIT = 24 # macro +FEATURE_GTHR_BIT = 25 # macro +FEATURE_ACDC_BIT = 26 # macro +FEATURE_VR0HOT_BIT = 27 # macro +FEATURE_FW_CTF_BIT = 28 # macro +FEATURE_FAN_CONTROL_BIT = 29 # macro +FEATURE_GFX_DCS_BIT = 30 # macro +FEATURE_GFX_READ_MARGIN_BIT = 31 # macro +FEATURE_LED_DISPLAY_BIT = 32 # macro +FEATURE_GFXCLK_SPREAD_SPECTRUM_BIT = 33 # macro +FEATURE_OUT_OF_BAND_MONITOR_BIT = 34 # macro +FEATURE_OPTIMIZED_VMIN_BIT = 35 # macro +FEATURE_GFX_IMU_BIT = 36 # macro +FEATURE_BOOT_TIME_CAL_BIT = 37 # macro +FEATURE_GFX_PCC_DFLL_BIT = 38 # macro +FEATURE_SOC_CG_BIT = 39 # macro +FEATURE_DF_CSTATE_BIT = 40 # macro +FEATURE_GFX_EDC_BIT = 41 # macro +FEATURE_BOOT_POWER_OPT_BIT = 42 # macro +FEATURE_CLOCK_POWER_DOWN_BYPASS_BIT = 43 # macro +FEATURE_BACO_CG_BIT = 45 # macro +FEATURE_MEM_TEMP_READ_BIT = 46 # macro +FEATURE_ATHUB_MMHUB_PG_BIT = 47 # macro +FEATURE_SOC_PCC_BIT = 48 # macro +FEATURE_EDC_PWRBRK_BIT = 49 # macro +FEATURE_SOC_EDC_XVMIN_BIT = 50 # macro +FEATURE_GFX_PSM_DIDT_BIT = 51 # macro +FEATURE_APT_ALL_ENABLE_BIT = 52 # macro +FEATURE_APT_SQ_THROTTLE_BIT = 53 # macro +FEATURE_APT_PF_DCS_BIT = 54 # macro +FEATURE_GFX_EDC_XVMIN_BIT = 55 # macro +FEATURE_GFX_DIDT_XVMIN_BIT = 56 # macro +FEATURE_FAN_ABNORMAL_BIT = 57 # macro +FEATURE_CLOCK_STRETCH_COMPENSATOR = 58 # macro +FEATURE_SPARE_59_BIT = 59 # macro +FEATURE_SPARE_60_BIT = 60 # macro +FEATURE_SPARE_61_BIT = 61 # macro +FEATURE_SPARE_62_BIT = 62 # macro +FEATURE_SPARE_63_BIT = 63 # macro +ALLOWED_FEATURE_CTRL_DEFAULT = 0xFFFFFFFFFFFFFFFF # macro +ALLOWED_FEATURE_CTRL_SCPM = (1<<1) # macro +DEBUG_OVERRIDE_NOT_USE = 0x00000001 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_DCN_FCLK = 0x00000002 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_MP0_FCLK = 0x00000004 # macro +DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_DCFCLK = 0x00000008 # macro +DEBUG_OVERRIDE_DISABLE_FAST_FCLK_TIMER = 0x00000010 # macro +DEBUG_OVERRIDE_DISABLE_VCN_PG = 0x00000020 # macro +DEBUG_OVERRIDE_DISABLE_FMAX_VMAX = 0x00000040 # macro +DEBUG_OVERRIDE_DISABLE_IMU_FW_CHECKS = 0x00000080 # macro +DEBUG_OVERRIDE_DISABLE_D0i2_REENTRY_HSR_TIMER_CHECK = 0x00000100 # macro +DEBUG_OVERRIDE_DISABLE_DFLL = 0x00000200 # macro +DEBUG_OVERRIDE_ENABLE_RLC_VF_BRINGUP_MODE = 0x00000400 # macro +DEBUG_OVERRIDE_DFLL_MASTER_MODE = 0x00000800 # macro +DEBUG_OVERRIDE_ENABLE_PROFILING_MODE = 0x00001000 # macro +DEBUG_OVERRIDE_ENABLE_SOC_VF_BRINGUP_MODE = 0x00002000 # macro +DEBUG_OVERRIDE_ENABLE_PER_WGP_RESIENCY = 0x00004000 # macro +DEBUG_OVERRIDE_DISABLE_MEMORY_VOLTAGE_SCALING = 0x00008000 # macro +DEBUG_OVERRIDE_DFLL_BTC_FCW_LOG = 0x00010000 # macro +VR_MAPPING_VR_SELECT_MASK = 0x01 # macro +VR_MAPPING_VR_SELECT_SHIFT = 0x00 # macro +VR_MAPPING_PLANE_SELECT_MASK = 0x02 # macro +VR_MAPPING_PLANE_SELECT_SHIFT = 0x01 # macro +PSI_SEL_VR0_PLANE0_PSI0 = 0x01 # macro +PSI_SEL_VR0_PLANE0_PSI1 = 0x02 # macro +PSI_SEL_VR0_PLANE1_PSI0 = 0x04 # macro +PSI_SEL_VR0_PLANE1_PSI1 = 0x08 # macro +PSI_SEL_VR1_PLANE0_PSI0 = 0x10 # macro +PSI_SEL_VR1_PLANE0_PSI1 = 0x20 # macro +PSI_SEL_VR1_PLANE1_PSI0 = 0x40 # macro +PSI_SEL_VR1_PLANE1_PSI1 = 0x80 # macro +THROTTLER_TEMP_EDGE_BIT = 0 # macro +THROTTLER_TEMP_HOTSPOT_BIT = 1 # macro +THROTTLER_TEMP_HOTSPOT_GFX_BIT = 2 # macro +THROTTLER_TEMP_HOTSPOT_SOC_BIT = 3 # macro +THROTTLER_TEMP_MEM_BIT = 4 # macro +THROTTLER_TEMP_VR_GFX_BIT = 5 # macro +THROTTLER_TEMP_VR_SOC_BIT = 6 # macro +THROTTLER_TEMP_VR_MEM0_BIT = 7 # macro +THROTTLER_TEMP_VR_MEM1_BIT = 8 # macro +THROTTLER_TEMP_LIQUID0_BIT = 9 # macro +THROTTLER_TEMP_LIQUID1_BIT = 10 # macro +THROTTLER_TEMP_PLX_BIT = 11 # macro +THROTTLER_TDC_GFX_BIT = 12 # macro +THROTTLER_TDC_SOC_BIT = 13 # macro +THROTTLER_PPT0_BIT = 14 # macro +THROTTLER_PPT1_BIT = 15 # macro +THROTTLER_PPT2_BIT = 16 # macro +THROTTLER_PPT3_BIT = 17 # macro +THROTTLER_FIT_BIT = 18 # macro +THROTTLER_GFX_APCC_PLUS_BIT = 19 # macro +THROTTLER_GFX_DVO_BIT = 20 # macro +THROTTLER_COUNT = 21 # macro +FW_DSTATE_SOC_ULV_BIT = 0 # macro +FW_DSTATE_G6_HSR_BIT = 1 # macro +FW_DSTATE_G6_PHY_VMEMP_OFF_BIT = 2 # macro +FW_DSTATE_SMN_DS_BIT = 3 # macro +FW_DSTATE_MP1_WHISPER_MODE_BIT = 4 # macro +FW_DSTATE_SOC_LIV_MIN_BIT = 5 # macro +FW_DSTATE_SOC_PLL_PWRDN_BIT = 6 # macro +FW_DSTATE_MEM_PLL_PWRDN_BIT = 7 # macro +FW_DSTATE_MALL_ALLOC_BIT = 8 # macro +FW_DSTATE_MEM_PSI_BIT = 9 # macro +FW_DSTATE_HSR_NON_STROBE_BIT = 10 # macro +FW_DSTATE_MP0_ENTER_WFI_BIT = 11 # macro +FW_DSTATE_MALL_FLUSH_BIT = 12 # macro +FW_DSTATE_SOC_PSI_BIT = 13 # macro +FW_DSTATE_MMHUB_INTERLOCK_BIT = 14 # macro +FW_DSTATE_D0i3_2_QUIET_FW_BIT = 15 # macro +FW_DSTATE_CLDO_PRG_BIT = 16 # macro +FW_DSTATE_DF_PLL_PWRDN_BIT = 17 # macro +LED_DISPLAY_GFX_DPM_BIT = 0 # macro +LED_DISPLAY_PCIE_BIT = 1 # macro +LED_DISPLAY_ERROR_BIT = 2 # macro +MEM_TEMP_READ_OUT_OF_BAND_BIT = 0 # macro +MEM_TEMP_READ_IN_BAND_REFRESH_BIT = 1 # macro +MEM_TEMP_READ_IN_BAND_DUMMY_PSTATE_BIT = 2 # macro +NUM_I2C_CONTROLLERS = 8 # macro +I2C_CONTROLLER_ENABLED = 1 # macro +I2C_CONTROLLER_DISABLED = 0 # macro +MAX_SW_I2C_COMMANDS = 24 # macro +CMDCONFIG_STOP_BIT = 0 # macro +CMDCONFIG_RESTART_BIT = 1 # macro +CMDCONFIG_READWRITE_BIT = 2 # macro +CMDCONFIG_STOP_MASK = (1<<0) # macro +CMDCONFIG_RESTART_MASK = (1<<1) # macro +CMDCONFIG_READWRITE_MASK = (1<<2) # macro +EPCS_HIGH_POWER = 600 # macro +EPCS_NORMAL_POWER = 450 # macro +EPCS_LOW_POWER = 300 # macro +EPCS_SHORTED_POWER = 150 # macro +EPCS_NO_BOOTUP = 0 # macro +PP_NUM_RTAVFS_PWL_ZONES = 5 # macro +PP_NUM_PSM_DIDT_PWL_ZONES = 3 # macro +PP_NUM_OD_VF_CURVE_POINTS = 5 + 1 # macro +PP_OD_FEATURE_GFX_VF_CURVE_BIT = 0 # macro +PP_OD_FEATURE_GFX_VMAX_BIT = 1 # macro +PP_OD_FEATURE_SOC_VMAX_BIT = 2 # macro +PP_OD_FEATURE_PPT_BIT = 3 # macro +PP_OD_FEATURE_FAN_CURVE_BIT = 4 # macro +PP_OD_FEATURE_FAN_LEGACY_BIT = 5 # macro +PP_OD_FEATURE_FULL_CTRL_BIT = 6 # macro +PP_OD_FEATURE_TDC_BIT = 7 # macro +PP_OD_FEATURE_GFXCLK_BIT = 8 # macro +PP_OD_FEATURE_UCLK_BIT = 9 # macro +PP_OD_FEATURE_FCLK_BIT = 10 # macro +PP_OD_FEATURE_ZERO_FAN_BIT = 11 # macro +PP_OD_FEATURE_TEMPERATURE_BIT = 12 # macro +PP_OD_FEATURE_EDC_BIT = 13 # macro +PP_OD_FEATURE_COUNT = 14 # macro +INVALID_BOARD_GPIO = 0xFF # macro +NUM_WM_RANGES = 4 # macro +WORKLOAD_PPLIB_DEFAULT_BIT = 0 # macro +WORKLOAD_PPLIB_FULL_SCREEN_3D_BIT = 1 # macro +WORKLOAD_PPLIB_POWER_SAVING_BIT = 2 # macro +WORKLOAD_PPLIB_VIDEO_BIT = 3 # macro +WORKLOAD_PPLIB_VR_BIT = 4 # macro +WORKLOAD_PPLIB_COMPUTE_BIT = 5 # macro +WORKLOAD_PPLIB_CUSTOM_BIT = 6 # macro +WORKLOAD_PPLIB_WINDOW_3D_BIT = 7 # macro +WORKLOAD_PPLIB_DIRECT_ML_BIT = 8 # macro +WORKLOAD_PPLIB_CGVDI_BIT = 9 # macro +WORKLOAD_PPLIB_COUNT = 10 # macro +TABLE_TRANSFER_OK = 0x0 # macro +TABLE_TRANSFER_FAILED = 0xFF # macro +TABLE_TRANSFER_PENDING = 0xAB # macro +TABLE_PPT_FAILED = 0x100 # macro +TABLE_TDC_FAILED = 0x200 # macro +TABLE_TEMP_FAILED = 0x400 # macro +TABLE_FAN_TARGET_TEMP_FAILED = 0x800 # macro +TABLE_FAN_STOP_TEMP_FAILED = 0x1000 # macro +TABLE_FAN_START_TEMP_FAILED = 0x2000 # macro +TABLE_FAN_PWM_MIN_FAILED = 0x4000 # macro +TABLE_ACOUSTIC_TARGET_RPM_FAILED = 0x8000 # macro +TABLE_ACOUSTIC_LIMIT_RPM_FAILED = 0x10000 # macro +TABLE_MGPU_ACOUSTIC_TARGET_RPM_FAILED = 0x20000 # macro +TABLE_PPTABLE = 0 # macro +TABLE_COMBO_PPTABLE = 1 # macro +TABLE_WATERMARKS = 2 # macro +TABLE_AVFS_PSM_DEBUG = 3 # macro +TABLE_PMSTATUSLOG = 4 # macro +TABLE_SMU_METRICS = 5 # macro +TABLE_DRIVER_SMU_CONFIG = 6 # macro +TABLE_ACTIVITY_MONITOR_COEFF = 7 # macro +TABLE_OVERDRIVE = 8 # macro +TABLE_I2C_COMMANDS = 9 # macro +TABLE_DRIVER_INFO = 10 # macro +TABLE_ECCINFO = 11 # macro +TABLE_CUSTOM_SKUTABLE = 12 # macro +TABLE_COUNT = 13 # macro +IH_INTERRUPT_ID_TO_DRIVER = 0xFE # macro +IH_INTERRUPT_CONTEXT_ID_BACO = 0x2 # macro +IH_INTERRUPT_CONTEXT_ID_AC = 0x3 # macro +IH_INTERRUPT_CONTEXT_ID_DC = 0x4 # macro +IH_INTERRUPT_CONTEXT_ID_AUDIO_D0 = 0x5 # macro +IH_INTERRUPT_CONTEXT_ID_AUDIO_D3 = 0x6 # macro +IH_INTERRUPT_CONTEXT_ID_THERMAL_THROTTLING = 0x7 # macro +IH_INTERRUPT_CONTEXT_ID_FAN_ABNORMAL = 0x8 # macro +IH_INTERRUPT_CONTEXT_ID_FAN_RECOVERY = 0x9 # macro +IH_INTERRUPT_CONTEXT_ID_DYNAMIC_TABLE = 0xA # macro + +# values for enumeration 'c__EA_FEATURE_PWR_DOMAIN_e' +c__EA_FEATURE_PWR_DOMAIN_e__enumvalues = { + 0: 'FEATURE_PWR_ALL', + 1: 'FEATURE_PWR_S5', + 2: 'FEATURE_PWR_BACO', + 3: 'FEATURE_PWR_SOC', + 4: 'FEATURE_PWR_GFX', + 5: 'FEATURE_PWR_DOMAIN_COUNT', +} +FEATURE_PWR_ALL = 0 +FEATURE_PWR_S5 = 1 +FEATURE_PWR_BACO = 2 +FEATURE_PWR_SOC = 3 +FEATURE_PWR_GFX = 4 +FEATURE_PWR_DOMAIN_COUNT = 5 +c__EA_FEATURE_PWR_DOMAIN_e = ctypes.c_uint32 # enum +FEATURE_PWR_DOMAIN_e = c__EA_FEATURE_PWR_DOMAIN_e +FEATURE_PWR_DOMAIN_e__enumvalues = c__EA_FEATURE_PWR_DOMAIN_e__enumvalues + +# values for enumeration 'c__EA_FEATURE_BTC_e' +c__EA_FEATURE_BTC_e__enumvalues = { + 0: 'FEATURE_BTC_NOP', + 1: 'FEATURE_BTC_SAVE', + 2: 'FEATURE_BTC_RESTORE', + 3: 'FEATURE_BTC_COUNT', +} +FEATURE_BTC_NOP = 0 +FEATURE_BTC_SAVE = 1 +FEATURE_BTC_RESTORE = 2 +FEATURE_BTC_COUNT = 3 +c__EA_FEATURE_BTC_e = ctypes.c_uint32 # enum +FEATURE_BTC_e = c__EA_FEATURE_BTC_e +FEATURE_BTC_e__enumvalues = c__EA_FEATURE_BTC_e__enumvalues + +# values for enumeration 'c__EA_SVI_PSI_e' +c__EA_SVI_PSI_e__enumvalues = { + 0: 'SVI_PSI_0', + 1: 'SVI_PSI_1', + 2: 'SVI_PSI_2', + 3: 'SVI_PSI_3', + 4: 'SVI_PSI_4', + 5: 'SVI_PSI_5', + 6: 'SVI_PSI_6', + 7: 'SVI_PSI_7', +} +SVI_PSI_0 = 0 +SVI_PSI_1 = 1 +SVI_PSI_2 = 2 +SVI_PSI_3 = 3 +SVI_PSI_4 = 4 +SVI_PSI_5 = 5 +SVI_PSI_6 = 6 +SVI_PSI_7 = 7 +c__EA_SVI_PSI_e = ctypes.c_uint32 # enum +SVI_PSI_e = c__EA_SVI_PSI_e +SVI_PSI_e__enumvalues = c__EA_SVI_PSI_e__enumvalues + +# values for enumeration 'c__EA_SMARTSHIFT_VERSION_e' +c__EA_SMARTSHIFT_VERSION_e__enumvalues = { + 0: 'SMARTSHIFT_VERSION_1', + 1: 'SMARTSHIFT_VERSION_2', + 2: 'SMARTSHIFT_VERSION_3', +} +SMARTSHIFT_VERSION_1 = 0 +SMARTSHIFT_VERSION_2 = 1 +SMARTSHIFT_VERSION_3 = 2 +c__EA_SMARTSHIFT_VERSION_e = ctypes.c_uint32 # enum +SMARTSHIFT_VERSION_e = c__EA_SMARTSHIFT_VERSION_e +SMARTSHIFT_VERSION_e__enumvalues = c__EA_SMARTSHIFT_VERSION_e__enumvalues + +# values for enumeration 'c__EA_FOPT_CALC_e' +c__EA_FOPT_CALC_e__enumvalues = { + 0: 'FOPT_CALC_AC_CALC_DC', + 1: 'FOPT_PPTABLE_AC_CALC_DC', + 2: 'FOPT_CALC_AC_PPTABLE_DC', + 3: 'FOPT_PPTABLE_AC_PPTABLE_DC', +} +FOPT_CALC_AC_CALC_DC = 0 +FOPT_PPTABLE_AC_CALC_DC = 1 +FOPT_CALC_AC_PPTABLE_DC = 2 +FOPT_PPTABLE_AC_PPTABLE_DC = 3 +c__EA_FOPT_CALC_e = ctypes.c_uint32 # enum +FOPT_CALC_e = c__EA_FOPT_CALC_e +FOPT_CALC_e__enumvalues = c__EA_FOPT_CALC_e__enumvalues + +# values for enumeration 'c__EA_DRAM_BIT_WIDTH_TYPE_e' +c__EA_DRAM_BIT_WIDTH_TYPE_e__enumvalues = { + 0: 'DRAM_BIT_WIDTH_DISABLED', + 8: 'DRAM_BIT_WIDTH_X_8', + 16: 'DRAM_BIT_WIDTH_X_16', + 32: 'DRAM_BIT_WIDTH_X_32', + 64: 'DRAM_BIT_WIDTH_X_64', + 128: 'DRAM_BIT_WIDTH_X_128', + 129: 'DRAM_BIT_WIDTH_COUNT', +} +DRAM_BIT_WIDTH_DISABLED = 0 +DRAM_BIT_WIDTH_X_8 = 8 +DRAM_BIT_WIDTH_X_16 = 16 +DRAM_BIT_WIDTH_X_32 = 32 +DRAM_BIT_WIDTH_X_64 = 64 +DRAM_BIT_WIDTH_X_128 = 128 +DRAM_BIT_WIDTH_COUNT = 129 +c__EA_DRAM_BIT_WIDTH_TYPE_e = ctypes.c_uint32 # enum +DRAM_BIT_WIDTH_TYPE_e = c__EA_DRAM_BIT_WIDTH_TYPE_e +DRAM_BIT_WIDTH_TYPE_e__enumvalues = c__EA_DRAM_BIT_WIDTH_TYPE_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerPort_e' +c__EA_I2cControllerPort_e__enumvalues = { + 0: 'I2C_CONTROLLER_PORT_0', + 1: 'I2C_CONTROLLER_PORT_1', + 2: 'I2C_CONTROLLER_PORT_COUNT', +} +I2C_CONTROLLER_PORT_0 = 0 +I2C_CONTROLLER_PORT_1 = 1 +I2C_CONTROLLER_PORT_COUNT = 2 +c__EA_I2cControllerPort_e = ctypes.c_uint32 # enum +I2cControllerPort_e = c__EA_I2cControllerPort_e +I2cControllerPort_e__enumvalues = c__EA_I2cControllerPort_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerName_e' +c__EA_I2cControllerName_e__enumvalues = { + 0: 'I2C_CONTROLLER_NAME_VR_GFX', + 1: 'I2C_CONTROLLER_NAME_VR_SOC', + 2: 'I2C_CONTROLLER_NAME_VR_VMEMP', + 3: 'I2C_CONTROLLER_NAME_VR_VDDIO', + 4: 'I2C_CONTROLLER_NAME_LIQUID0', + 5: 'I2C_CONTROLLER_NAME_LIQUID1', + 6: 'I2C_CONTROLLER_NAME_PLX', + 7: 'I2C_CONTROLLER_NAME_FAN_INTAKE', + 8: 'I2C_CONTROLLER_NAME_COUNT', +} +I2C_CONTROLLER_NAME_VR_GFX = 0 +I2C_CONTROLLER_NAME_VR_SOC = 1 +I2C_CONTROLLER_NAME_VR_VMEMP = 2 +I2C_CONTROLLER_NAME_VR_VDDIO = 3 +I2C_CONTROLLER_NAME_LIQUID0 = 4 +I2C_CONTROLLER_NAME_LIQUID1 = 5 +I2C_CONTROLLER_NAME_PLX = 6 +I2C_CONTROLLER_NAME_FAN_INTAKE = 7 +I2C_CONTROLLER_NAME_COUNT = 8 +c__EA_I2cControllerName_e = ctypes.c_uint32 # enum +I2cControllerName_e = c__EA_I2cControllerName_e +I2cControllerName_e__enumvalues = c__EA_I2cControllerName_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerThrottler_e' +c__EA_I2cControllerThrottler_e__enumvalues = { + 0: 'I2C_CONTROLLER_THROTTLER_TYPE_NONE', + 1: 'I2C_CONTROLLER_THROTTLER_VR_GFX', + 2: 'I2C_CONTROLLER_THROTTLER_VR_SOC', + 3: 'I2C_CONTROLLER_THROTTLER_VR_VMEMP', + 4: 'I2C_CONTROLLER_THROTTLER_VR_VDDIO', + 5: 'I2C_CONTROLLER_THROTTLER_LIQUID0', + 6: 'I2C_CONTROLLER_THROTTLER_LIQUID1', + 7: 'I2C_CONTROLLER_THROTTLER_PLX', + 8: 'I2C_CONTROLLER_THROTTLER_FAN_INTAKE', + 9: 'I2C_CONTROLLER_THROTTLER_INA3221', + 10: 'I2C_CONTROLLER_THROTTLER_COUNT', +} +I2C_CONTROLLER_THROTTLER_TYPE_NONE = 0 +I2C_CONTROLLER_THROTTLER_VR_GFX = 1 +I2C_CONTROLLER_THROTTLER_VR_SOC = 2 +I2C_CONTROLLER_THROTTLER_VR_VMEMP = 3 +I2C_CONTROLLER_THROTTLER_VR_VDDIO = 4 +I2C_CONTROLLER_THROTTLER_LIQUID0 = 5 +I2C_CONTROLLER_THROTTLER_LIQUID1 = 6 +I2C_CONTROLLER_THROTTLER_PLX = 7 +I2C_CONTROLLER_THROTTLER_FAN_INTAKE = 8 +I2C_CONTROLLER_THROTTLER_INA3221 = 9 +I2C_CONTROLLER_THROTTLER_COUNT = 10 +c__EA_I2cControllerThrottler_e = ctypes.c_uint32 # enum +I2cControllerThrottler_e = c__EA_I2cControllerThrottler_e +I2cControllerThrottler_e__enumvalues = c__EA_I2cControllerThrottler_e__enumvalues + +# values for enumeration 'c__EA_I2cControllerProtocol_e' +c__EA_I2cControllerProtocol_e__enumvalues = { + 0: 'I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5', + 1: 'I2C_CONTROLLER_PROTOCOL_VR_IR35217', + 2: 'I2C_CONTROLLER_PROTOCOL_TMP_MAX31875', + 3: 'I2C_CONTROLLER_PROTOCOL_INA3221', + 4: 'I2C_CONTROLLER_PROTOCOL_TMP_MAX6604', + 5: 'I2C_CONTROLLER_PROTOCOL_COUNT', +} +I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5 = 0 +I2C_CONTROLLER_PROTOCOL_VR_IR35217 = 1 +I2C_CONTROLLER_PROTOCOL_TMP_MAX31875 = 2 +I2C_CONTROLLER_PROTOCOL_INA3221 = 3 +I2C_CONTROLLER_PROTOCOL_TMP_MAX6604 = 4 +I2C_CONTROLLER_PROTOCOL_COUNT = 5 +c__EA_I2cControllerProtocol_e = ctypes.c_uint32 # enum +I2cControllerProtocol_e = c__EA_I2cControllerProtocol_e +I2cControllerProtocol_e__enumvalues = c__EA_I2cControllerProtocol_e__enumvalues +class struct_c__SA_I2cControllerConfig_t(Structure): + pass + +struct_c__SA_I2cControllerConfig_t._pack_ = 1 # source:False +struct_c__SA_I2cControllerConfig_t._fields_ = [ + ('Enabled', ctypes.c_ubyte), + ('Speed', ctypes.c_ubyte), + ('SlaveAddress', ctypes.c_ubyte), + ('ControllerPort', ctypes.c_ubyte), + ('ControllerName', ctypes.c_ubyte), + ('ThermalThrotter', ctypes.c_ubyte), + ('I2cProtocol', ctypes.c_ubyte), + ('PaddingConfig', ctypes.c_ubyte), +] + +I2cControllerConfig_t = struct_c__SA_I2cControllerConfig_t + +# values for enumeration 'c__EA_I2cPort_e' +c__EA_I2cPort_e__enumvalues = { + 0: 'I2C_PORT_SVD_SCL', + 1: 'I2C_PORT_GPIO', +} +I2C_PORT_SVD_SCL = 0 +I2C_PORT_GPIO = 1 +c__EA_I2cPort_e = ctypes.c_uint32 # enum +I2cPort_e = c__EA_I2cPort_e +I2cPort_e__enumvalues = c__EA_I2cPort_e__enumvalues + +# values for enumeration 'c__EA_I2cSpeed_e' +c__EA_I2cSpeed_e__enumvalues = { + 0: 'I2C_SPEED_FAST_50K', + 1: 'I2C_SPEED_FAST_100K', + 2: 'I2C_SPEED_FAST_400K', + 3: 'I2C_SPEED_FAST_PLUS_1M', + 4: 'I2C_SPEED_HIGH_1M', + 5: 'I2C_SPEED_HIGH_2M', + 6: 'I2C_SPEED_COUNT', +} +I2C_SPEED_FAST_50K = 0 +I2C_SPEED_FAST_100K = 1 +I2C_SPEED_FAST_400K = 2 +I2C_SPEED_FAST_PLUS_1M = 3 +I2C_SPEED_HIGH_1M = 4 +I2C_SPEED_HIGH_2M = 5 +I2C_SPEED_COUNT = 6 +c__EA_I2cSpeed_e = ctypes.c_uint32 # enum +I2cSpeed_e = c__EA_I2cSpeed_e +I2cSpeed_e__enumvalues = c__EA_I2cSpeed_e__enumvalues + +# values for enumeration 'c__EA_I2cCmdType_e' +c__EA_I2cCmdType_e__enumvalues = { + 0: 'I2C_CMD_READ', + 1: 'I2C_CMD_WRITE', + 2: 'I2C_CMD_COUNT', +} +I2C_CMD_READ = 0 +I2C_CMD_WRITE = 1 +I2C_CMD_COUNT = 2 +c__EA_I2cCmdType_e = ctypes.c_uint32 # enum +I2cCmdType_e = c__EA_I2cCmdType_e +I2cCmdType_e__enumvalues = c__EA_I2cCmdType_e__enumvalues +class struct_c__SA_SwI2cCmd_t(Structure): + pass + +struct_c__SA_SwI2cCmd_t._pack_ = 1 # source:False +struct_c__SA_SwI2cCmd_t._fields_ = [ + ('ReadWriteData', ctypes.c_ubyte), + ('CmdConfig', ctypes.c_ubyte), +] + +SwI2cCmd_t = struct_c__SA_SwI2cCmd_t +class struct_c__SA_SwI2cRequest_t(Structure): + pass + +struct_c__SA_SwI2cRequest_t._pack_ = 1 # source:False +struct_c__SA_SwI2cRequest_t._fields_ = [ + ('I2CcontrollerPort', ctypes.c_ubyte), + ('I2CSpeed', ctypes.c_ubyte), + ('SlaveAddress', ctypes.c_ubyte), + ('NumCmds', ctypes.c_ubyte), + ('SwI2cCmds', struct_c__SA_SwI2cCmd_t * 24), +] + +SwI2cRequest_t = struct_c__SA_SwI2cRequest_t +class struct_c__SA_SwI2cRequestExternal_t(Structure): + pass + +struct_c__SA_SwI2cRequestExternal_t._pack_ = 1 # source:False +struct_c__SA_SwI2cRequestExternal_t._fields_ = [ + ('SwI2cRequest', SwI2cRequest_t), + ('Spare', ctypes.c_uint32 * 8), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SwI2cRequestExternal_t = struct_c__SA_SwI2cRequestExternal_t +class struct_c__SA_EccInfo_t(Structure): + pass + +struct_c__SA_EccInfo_t._pack_ = 1 # source:False +struct_c__SA_EccInfo_t._fields_ = [ + ('mca_umc_status', ctypes.c_uint64), + ('mca_umc_addr', ctypes.c_uint64), + ('ce_count_lo_chip', ctypes.c_uint16), + ('ce_count_hi_chip', ctypes.c_uint16), + ('eccPadding', ctypes.c_uint32), +] + +EccInfo_t = struct_c__SA_EccInfo_t +class struct_c__SA_EccInfoTable_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('EccInfo', struct_c__SA_EccInfo_t * 24), + ] + +EccInfoTable_t = struct_c__SA_EccInfoTable_t + +# values for enumeration 'c__EA_EPCS_STATUS_e' +c__EA_EPCS_STATUS_e__enumvalues = { + 0: 'EPCS_SHORTED_LIMIT', + 1: 'EPCS_LOW_POWER_LIMIT', + 2: 'EPCS_NORMAL_POWER_LIMIT', + 3: 'EPCS_HIGH_POWER_LIMIT', + 4: 'EPCS_NOT_CONFIGURED', + 5: 'EPCS_STATUS_COUNT', +} +EPCS_SHORTED_LIMIT = 0 +EPCS_LOW_POWER_LIMIT = 1 +EPCS_NORMAL_POWER_LIMIT = 2 +EPCS_HIGH_POWER_LIMIT = 3 +EPCS_NOT_CONFIGURED = 4 +EPCS_STATUS_COUNT = 5 +c__EA_EPCS_STATUS_e = ctypes.c_uint32 # enum +EPCS_STATUS_e = c__EA_EPCS_STATUS_e +EPCS_STATUS_e__enumvalues = c__EA_EPCS_STATUS_e__enumvalues + +# values for enumeration 'c__EA_D3HOTSequence_e' +c__EA_D3HOTSequence_e__enumvalues = { + 0: 'BACO_SEQUENCE', + 1: 'MSR_SEQUENCE', + 2: 'BAMACO_SEQUENCE', + 3: 'ULPS_SEQUENCE', + 4: 'D3HOT_SEQUENCE_COUNT', +} +BACO_SEQUENCE = 0 +MSR_SEQUENCE = 1 +BAMACO_SEQUENCE = 2 +ULPS_SEQUENCE = 3 +D3HOT_SEQUENCE_COUNT = 4 +c__EA_D3HOTSequence_e = ctypes.c_uint32 # enum +D3HOTSequence_e = c__EA_D3HOTSequence_e +D3HOTSequence_e__enumvalues = c__EA_D3HOTSequence_e__enumvalues + +# values for enumeration 'c__EA_PowerGatingMode_e' +c__EA_PowerGatingMode_e__enumvalues = { + 0: 'PG_DYNAMIC_MODE', + 1: 'PG_STATIC_MODE', +} +PG_DYNAMIC_MODE = 0 +PG_STATIC_MODE = 1 +c__EA_PowerGatingMode_e = ctypes.c_uint32 # enum +PowerGatingMode_e = c__EA_PowerGatingMode_e +PowerGatingMode_e__enumvalues = c__EA_PowerGatingMode_e__enumvalues + +# values for enumeration 'c__EA_PowerGatingSettings_e' +c__EA_PowerGatingSettings_e__enumvalues = { + 0: 'PG_POWER_DOWN', + 1: 'PG_POWER_UP', +} +PG_POWER_DOWN = 0 +PG_POWER_UP = 1 +c__EA_PowerGatingSettings_e = ctypes.c_uint32 # enum +PowerGatingSettings_e = c__EA_PowerGatingSettings_e +PowerGatingSettings_e__enumvalues = c__EA_PowerGatingSettings_e__enumvalues +class struct_c__SA_QuadraticInt_t(Structure): + pass + +struct_c__SA_QuadraticInt_t._pack_ = 1 # source:False +struct_c__SA_QuadraticInt_t._fields_ = [ + ('a', ctypes.c_uint32), + ('b', ctypes.c_uint32), + ('c', ctypes.c_uint32), +] + +QuadraticInt_t = struct_c__SA_QuadraticInt_t +class struct_c__SA_LinearInt_t(Structure): + pass + +struct_c__SA_LinearInt_t._pack_ = 1 # source:False +struct_c__SA_LinearInt_t._fields_ = [ + ('m', ctypes.c_uint32), + ('b', ctypes.c_uint32), +] + +LinearInt_t = struct_c__SA_LinearInt_t +class struct_c__SA_DroopInt_t(Structure): + pass + +struct_c__SA_DroopInt_t._pack_ = 1 # source:False +struct_c__SA_DroopInt_t._fields_ = [ + ('a', ctypes.c_uint32), + ('b', ctypes.c_uint32), + ('c', ctypes.c_uint32), +] + +DroopInt_t = struct_c__SA_DroopInt_t + +# values for enumeration 'c__EA_DCS_ARCH_e' +c__EA_DCS_ARCH_e__enumvalues = { + 0: 'DCS_ARCH_DISABLED', + 1: 'DCS_ARCH_FADCS', + 2: 'DCS_ARCH_ASYNC', +} +DCS_ARCH_DISABLED = 0 +DCS_ARCH_FADCS = 1 +DCS_ARCH_ASYNC = 2 +c__EA_DCS_ARCH_e = ctypes.c_uint32 # enum +DCS_ARCH_e = c__EA_DCS_ARCH_e +DCS_ARCH_e__enumvalues = c__EA_DCS_ARCH_e__enumvalues + +# values for enumeration 'c__EA_PPCLK_e' +c__EA_PPCLK_e__enumvalues = { + 0: 'PPCLK_GFXCLK', + 1: 'PPCLK_SOCCLK', + 2: 'PPCLK_UCLK', + 3: 'PPCLK_FCLK', + 4: 'PPCLK_DCLK_0', + 5: 'PPCLK_VCLK_0', + 6: 'PPCLK_DISPCLK', + 7: 'PPCLK_DPPCLK', + 8: 'PPCLK_DPREFCLK', + 9: 'PPCLK_DCFCLK', + 10: 'PPCLK_DTBCLK', + 11: 'PPCLK_COUNT', +} +PPCLK_GFXCLK = 0 +PPCLK_SOCCLK = 1 +PPCLK_UCLK = 2 +PPCLK_FCLK = 3 +PPCLK_DCLK_0 = 4 +PPCLK_VCLK_0 = 5 +PPCLK_DISPCLK = 6 +PPCLK_DPPCLK = 7 +PPCLK_DPREFCLK = 8 +PPCLK_DCFCLK = 9 +PPCLK_DTBCLK = 10 +PPCLK_COUNT = 11 +c__EA_PPCLK_e = ctypes.c_uint32 # enum +PPCLK_e = c__EA_PPCLK_e +PPCLK_e__enumvalues = c__EA_PPCLK_e__enumvalues + +# values for enumeration 'c__EA_VOLTAGE_MODE_e' +c__EA_VOLTAGE_MODE_e__enumvalues = { + 0: 'VOLTAGE_MODE_PPTABLE', + 1: 'VOLTAGE_MODE_FUSES', + 2: 'VOLTAGE_MODE_COUNT', +} +VOLTAGE_MODE_PPTABLE = 0 +VOLTAGE_MODE_FUSES = 1 +VOLTAGE_MODE_COUNT = 2 +c__EA_VOLTAGE_MODE_e = ctypes.c_uint32 # enum +VOLTAGE_MODE_e = c__EA_VOLTAGE_MODE_e +VOLTAGE_MODE_e__enumvalues = c__EA_VOLTAGE_MODE_e__enumvalues + +# values for enumeration 'c__EA_AVFS_VOLTAGE_TYPE_e' +c__EA_AVFS_VOLTAGE_TYPE_e__enumvalues = { + 0: 'AVFS_VOLTAGE_GFX', + 1: 'AVFS_VOLTAGE_SOC', + 2: 'AVFS_VOLTAGE_COUNT', +} +AVFS_VOLTAGE_GFX = 0 +AVFS_VOLTAGE_SOC = 1 +AVFS_VOLTAGE_COUNT = 2 +c__EA_AVFS_VOLTAGE_TYPE_e = ctypes.c_uint32 # enum +AVFS_VOLTAGE_TYPE_e = c__EA_AVFS_VOLTAGE_TYPE_e +AVFS_VOLTAGE_TYPE_e__enumvalues = c__EA_AVFS_VOLTAGE_TYPE_e__enumvalues + +# values for enumeration 'c__EA_AVFS_TEMP_e' +c__EA_AVFS_TEMP_e__enumvalues = { + 0: 'AVFS_TEMP_COLD', + 1: 'AVFS_TEMP_HOT', + 2: 'AVFS_TEMP_COUNT', +} +AVFS_TEMP_COLD = 0 +AVFS_TEMP_HOT = 1 +AVFS_TEMP_COUNT = 2 +c__EA_AVFS_TEMP_e = ctypes.c_uint32 # enum +AVFS_TEMP_e = c__EA_AVFS_TEMP_e +AVFS_TEMP_e__enumvalues = c__EA_AVFS_TEMP_e__enumvalues + +# values for enumeration 'c__EA_AVFS_D_e' +c__EA_AVFS_D_e__enumvalues = { + 0: 'AVFS_D_G', + 1: 'AVFS_D_COUNT', +} +AVFS_D_G = 0 +AVFS_D_COUNT = 1 +c__EA_AVFS_D_e = ctypes.c_uint32 # enum +AVFS_D_e = c__EA_AVFS_D_e +AVFS_D_e__enumvalues = c__EA_AVFS_D_e__enumvalues + +# values for enumeration 'c__EA_UCLK_DIV_e' +c__EA_UCLK_DIV_e__enumvalues = { + 0: 'UCLK_DIV_BY_1', + 1: 'UCLK_DIV_BY_2', + 2: 'UCLK_DIV_BY_4', + 3: 'UCLK_DIV_BY_8', +} +UCLK_DIV_BY_1 = 0 +UCLK_DIV_BY_2 = 1 +UCLK_DIV_BY_4 = 2 +UCLK_DIV_BY_8 = 3 +c__EA_UCLK_DIV_e = ctypes.c_uint32 # enum +UCLK_DIV_e = c__EA_UCLK_DIV_e +UCLK_DIV_e__enumvalues = c__EA_UCLK_DIV_e__enumvalues + +# values for enumeration 'c__EA_GpioIntPolarity_e' +c__EA_GpioIntPolarity_e__enumvalues = { + 0: 'GPIO_INT_POLARITY_ACTIVE_LOW', + 1: 'GPIO_INT_POLARITY_ACTIVE_HIGH', +} +GPIO_INT_POLARITY_ACTIVE_LOW = 0 +GPIO_INT_POLARITY_ACTIVE_HIGH = 1 +c__EA_GpioIntPolarity_e = ctypes.c_uint32 # enum +GpioIntPolarity_e = c__EA_GpioIntPolarity_e +GpioIntPolarity_e__enumvalues = c__EA_GpioIntPolarity_e__enumvalues + +# values for enumeration 'c__EA_PwrConfig_e' +c__EA_PwrConfig_e__enumvalues = { + 0: 'PWR_CONFIG_TDP', + 1: 'PWR_CONFIG_TGP', + 2: 'PWR_CONFIG_TCP_ESTIMATED', + 3: 'PWR_CONFIG_TCP_MEASURED', + 4: 'PWR_CONFIG_TBP_DESKTOP', + 5: 'PWR_CONFIG_TBP_MOBILE', +} +PWR_CONFIG_TDP = 0 +PWR_CONFIG_TGP = 1 +PWR_CONFIG_TCP_ESTIMATED = 2 +PWR_CONFIG_TCP_MEASURED = 3 +PWR_CONFIG_TBP_DESKTOP = 4 +PWR_CONFIG_TBP_MOBILE = 5 +c__EA_PwrConfig_e = ctypes.c_uint32 # enum +PwrConfig_e = c__EA_PwrConfig_e +PwrConfig_e__enumvalues = c__EA_PwrConfig_e__enumvalues +class struct_c__SA_DpmDescriptor_t(Structure): + pass + +struct_c__SA_DpmDescriptor_t._pack_ = 1 # source:False +struct_c__SA_DpmDescriptor_t._fields_ = [ + ('Padding', ctypes.c_ubyte), + ('SnapToDiscrete', ctypes.c_ubyte), + ('NumDiscreteLevels', ctypes.c_ubyte), + ('CalculateFopt', ctypes.c_ubyte), + ('ConversionToAvfsClk', LinearInt_t), + ('Padding3', ctypes.c_uint32 * 3), + ('Padding4', ctypes.c_uint16), + ('FoptimalDc', ctypes.c_uint16), + ('FoptimalAc', ctypes.c_uint16), + ('Padding2', ctypes.c_uint16), +] + +DpmDescriptor_t = struct_c__SA_DpmDescriptor_t + +# values for enumeration 'c__EA_PPT_THROTTLER_e' +c__EA_PPT_THROTTLER_e__enumvalues = { + 0: 'PPT_THROTTLER_PPT0', + 1: 'PPT_THROTTLER_PPT1', + 2: 'PPT_THROTTLER_PPT2', + 3: 'PPT_THROTTLER_PPT3', + 4: 'PPT_THROTTLER_COUNT', +} +PPT_THROTTLER_PPT0 = 0 +PPT_THROTTLER_PPT1 = 1 +PPT_THROTTLER_PPT2 = 2 +PPT_THROTTLER_PPT3 = 3 +PPT_THROTTLER_COUNT = 4 +c__EA_PPT_THROTTLER_e = ctypes.c_uint32 # enum +PPT_THROTTLER_e = c__EA_PPT_THROTTLER_e +PPT_THROTTLER_e__enumvalues = c__EA_PPT_THROTTLER_e__enumvalues + +# values for enumeration 'c__EA_TEMP_e' +c__EA_TEMP_e__enumvalues = { + 0: 'TEMP_EDGE', + 1: 'TEMP_HOTSPOT', + 2: 'TEMP_HOTSPOT_GFX', + 3: 'TEMP_HOTSPOT_SOC', + 4: 'TEMP_MEM', + 5: 'TEMP_VR_GFX', + 6: 'TEMP_VR_SOC', + 7: 'TEMP_VR_MEM0', + 8: 'TEMP_VR_MEM1', + 9: 'TEMP_LIQUID0', + 10: 'TEMP_LIQUID1', + 11: 'TEMP_PLX', + 12: 'TEMP_COUNT', +} +TEMP_EDGE = 0 +TEMP_HOTSPOT = 1 +TEMP_HOTSPOT_GFX = 2 +TEMP_HOTSPOT_SOC = 3 +TEMP_MEM = 4 +TEMP_VR_GFX = 5 +TEMP_VR_SOC = 6 +TEMP_VR_MEM0 = 7 +TEMP_VR_MEM1 = 8 +TEMP_LIQUID0 = 9 +TEMP_LIQUID1 = 10 +TEMP_PLX = 11 +TEMP_COUNT = 12 +c__EA_TEMP_e = ctypes.c_uint32 # enum +TEMP_e = c__EA_TEMP_e +TEMP_e__enumvalues = c__EA_TEMP_e__enumvalues + +# values for enumeration 'c__EA_TDC_THROTTLER_e' +c__EA_TDC_THROTTLER_e__enumvalues = { + 0: 'TDC_THROTTLER_GFX', + 1: 'TDC_THROTTLER_SOC', + 2: 'TDC_THROTTLER_COUNT', +} +TDC_THROTTLER_GFX = 0 +TDC_THROTTLER_SOC = 1 +TDC_THROTTLER_COUNT = 2 +c__EA_TDC_THROTTLER_e = ctypes.c_uint32 # enum +TDC_THROTTLER_e = c__EA_TDC_THROTTLER_e +TDC_THROTTLER_e__enumvalues = c__EA_TDC_THROTTLER_e__enumvalues + +# values for enumeration 'c__EA_SVI_PLANE_e' +c__EA_SVI_PLANE_e__enumvalues = { + 0: 'SVI_PLANE_VDD_GFX', + 1: 'SVI_PLANE_VDD_SOC', + 2: 'SVI_PLANE_VDDCI_MEM', + 3: 'SVI_PLANE_VDDIO_MEM', + 4: 'SVI_PLANE_COUNT', +} +SVI_PLANE_VDD_GFX = 0 +SVI_PLANE_VDD_SOC = 1 +SVI_PLANE_VDDCI_MEM = 2 +SVI_PLANE_VDDIO_MEM = 3 +SVI_PLANE_COUNT = 4 +c__EA_SVI_PLANE_e = ctypes.c_uint32 # enum +SVI_PLANE_e = c__EA_SVI_PLANE_e +SVI_PLANE_e__enumvalues = c__EA_SVI_PLANE_e__enumvalues + +# values for enumeration 'c__EA_PMFW_VOLT_PLANE_e' +c__EA_PMFW_VOLT_PLANE_e__enumvalues = { + 0: 'PMFW_VOLT_PLANE_GFX', + 1: 'PMFW_VOLT_PLANE_SOC', + 2: 'PMFW_VOLT_PLANE_COUNT', +} +PMFW_VOLT_PLANE_GFX = 0 +PMFW_VOLT_PLANE_SOC = 1 +PMFW_VOLT_PLANE_COUNT = 2 +c__EA_PMFW_VOLT_PLANE_e = ctypes.c_uint32 # enum +PMFW_VOLT_PLANE_e = c__EA_PMFW_VOLT_PLANE_e +PMFW_VOLT_PLANE_e__enumvalues = c__EA_PMFW_VOLT_PLANE_e__enumvalues + +# values for enumeration 'c__EA_CUSTOMER_VARIANT_e' +c__EA_CUSTOMER_VARIANT_e__enumvalues = { + 0: 'CUSTOMER_VARIANT_ROW', + 1: 'CUSTOMER_VARIANT_FALCON', + 2: 'CUSTOMER_VARIANT_COUNT', +} +CUSTOMER_VARIANT_ROW = 0 +CUSTOMER_VARIANT_FALCON = 1 +CUSTOMER_VARIANT_COUNT = 2 +c__EA_CUSTOMER_VARIANT_e = ctypes.c_uint32 # enum +CUSTOMER_VARIANT_e = c__EA_CUSTOMER_VARIANT_e +CUSTOMER_VARIANT_e__enumvalues = c__EA_CUSTOMER_VARIANT_e__enumvalues + +# values for enumeration 'c__EA_POWER_SOURCE_e' +c__EA_POWER_SOURCE_e__enumvalues = { + 0: 'POWER_SOURCE_AC', + 1: 'POWER_SOURCE_DC', + 2: 'POWER_SOURCE_COUNT', +} +POWER_SOURCE_AC = 0 +POWER_SOURCE_DC = 1 +POWER_SOURCE_COUNT = 2 +c__EA_POWER_SOURCE_e = ctypes.c_uint32 # enum +POWER_SOURCE_e = c__EA_POWER_SOURCE_e +POWER_SOURCE_e__enumvalues = c__EA_POWER_SOURCE_e__enumvalues + +# values for enumeration 'c__EA_MEM_VENDOR_e' +c__EA_MEM_VENDOR_e__enumvalues = { + 0: 'MEM_VENDOR_PLACEHOLDER0', + 1: 'MEM_VENDOR_SAMSUNG', + 2: 'MEM_VENDOR_INFINEON', + 3: 'MEM_VENDOR_ELPIDA', + 4: 'MEM_VENDOR_ETRON', + 5: 'MEM_VENDOR_NANYA', + 6: 'MEM_VENDOR_HYNIX', + 7: 'MEM_VENDOR_MOSEL', + 8: 'MEM_VENDOR_WINBOND', + 9: 'MEM_VENDOR_ESMT', + 10: 'MEM_VENDOR_PLACEHOLDER1', + 11: 'MEM_VENDOR_PLACEHOLDER2', + 12: 'MEM_VENDOR_PLACEHOLDER3', + 13: 'MEM_VENDOR_PLACEHOLDER4', + 14: 'MEM_VENDOR_PLACEHOLDER5', + 15: 'MEM_VENDOR_MICRON', + 16: 'MEM_VENDOR_COUNT', +} +MEM_VENDOR_PLACEHOLDER0 = 0 +MEM_VENDOR_SAMSUNG = 1 +MEM_VENDOR_INFINEON = 2 +MEM_VENDOR_ELPIDA = 3 +MEM_VENDOR_ETRON = 4 +MEM_VENDOR_NANYA = 5 +MEM_VENDOR_HYNIX = 6 +MEM_VENDOR_MOSEL = 7 +MEM_VENDOR_WINBOND = 8 +MEM_VENDOR_ESMT = 9 +MEM_VENDOR_PLACEHOLDER1 = 10 +MEM_VENDOR_PLACEHOLDER2 = 11 +MEM_VENDOR_PLACEHOLDER3 = 12 +MEM_VENDOR_PLACEHOLDER4 = 13 +MEM_VENDOR_PLACEHOLDER5 = 14 +MEM_VENDOR_MICRON = 15 +MEM_VENDOR_COUNT = 16 +c__EA_MEM_VENDOR_e = ctypes.c_uint32 # enum +MEM_VENDOR_e = c__EA_MEM_VENDOR_e +MEM_VENDOR_e__enumvalues = c__EA_MEM_VENDOR_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_HW_FUSE_e' +c__EA_PP_GRTAVFS_HW_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_HW_CPO_CTL_ZONE0', + 1: 'PP_GRTAVFS_HW_CPO_CTL_ZONE1', + 2: 'PP_GRTAVFS_HW_CPO_CTL_ZONE2', + 3: 'PP_GRTAVFS_HW_CPO_CTL_ZONE3', + 4: 'PP_GRTAVFS_HW_CPO_CTL_ZONE4', + 5: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0', + 6: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0', + 7: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1', + 8: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1', + 9: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2', + 10: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2', + 11: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3', + 12: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3', + 13: 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4', + 14: 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4', + 15: 'PP_GRTAVFS_HW_ZONE0_VF', + 16: 'PP_GRTAVFS_HW_ZONE1_VF1', + 17: 'PP_GRTAVFS_HW_ZONE2_VF2', + 18: 'PP_GRTAVFS_HW_ZONE3_VF3', + 19: 'PP_GRTAVFS_HW_VOLTAGE_GB', + 20: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0', + 21: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1', + 22: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2', + 23: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3', + 24: 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4', + 25: 'PP_GRTAVFS_HW_RESERVED_0', + 26: 'PP_GRTAVFS_HW_RESERVED_1', + 27: 'PP_GRTAVFS_HW_RESERVED_2', + 28: 'PP_GRTAVFS_HW_RESERVED_3', + 29: 'PP_GRTAVFS_HW_RESERVED_4', + 30: 'PP_GRTAVFS_HW_RESERVED_5', + 31: 'PP_GRTAVFS_HW_RESERVED_6', + 32: 'PP_GRTAVFS_HW_FUSE_COUNT', +} +PP_GRTAVFS_HW_CPO_CTL_ZONE0 = 0 +PP_GRTAVFS_HW_CPO_CTL_ZONE1 = 1 +PP_GRTAVFS_HW_CPO_CTL_ZONE2 = 2 +PP_GRTAVFS_HW_CPO_CTL_ZONE3 = 3 +PP_GRTAVFS_HW_CPO_CTL_ZONE4 = 4 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0 = 5 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0 = 6 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1 = 7 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1 = 8 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2 = 9 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2 = 10 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3 = 11 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3 = 12 +PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4 = 13 +PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4 = 14 +PP_GRTAVFS_HW_ZONE0_VF = 15 +PP_GRTAVFS_HW_ZONE1_VF1 = 16 +PP_GRTAVFS_HW_ZONE2_VF2 = 17 +PP_GRTAVFS_HW_ZONE3_VF3 = 18 +PP_GRTAVFS_HW_VOLTAGE_GB = 19 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0 = 20 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1 = 21 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2 = 22 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3 = 23 +PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4 = 24 +PP_GRTAVFS_HW_RESERVED_0 = 25 +PP_GRTAVFS_HW_RESERVED_1 = 26 +PP_GRTAVFS_HW_RESERVED_2 = 27 +PP_GRTAVFS_HW_RESERVED_3 = 28 +PP_GRTAVFS_HW_RESERVED_4 = 29 +PP_GRTAVFS_HW_RESERVED_5 = 30 +PP_GRTAVFS_HW_RESERVED_6 = 31 +PP_GRTAVFS_HW_FUSE_COUNT = 32 +c__EA_PP_GRTAVFS_HW_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_HW_FUSE_e = c__EA_PP_GRTAVFS_HW_FUSE_e +PP_GRTAVFS_HW_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_HW_FUSE_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e' +c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0', + 1: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0', + 2: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0', + 3: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0', + 4: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0', + 5: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0', + 6: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0', + 7: 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0', + 8: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0', + 9: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1', + 10: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2', + 11: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3', + 12: 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4', + 13: 'PP_GRTAVFS_FW_COMMON_FUSE_COUNT', +} +PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0 = 0 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0 = 1 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0 = 2 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0 = 3 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0 = 4 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0 = 5 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0 = 6 +PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0 = 7 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0 = 8 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1 = 9 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2 = 10 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3 = 11 +PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4 = 12 +PP_GRTAVFS_FW_COMMON_FUSE_COUNT = 13 +c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_FW_COMMON_FUSE_e = c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e +PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues + +# values for enumeration 'c__EA_PP_GRTAVFS_FW_SEP_FUSE_e' +c__EA_PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues = { + 0: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1', + 1: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0', + 2: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1', + 3: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2', + 4: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3', + 5: 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4', + 6: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1', + 7: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0', + 8: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1', + 9: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2', + 10: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3', + 11: 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4', + 12: 'PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY', + 13: 'PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY', + 14: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0', + 15: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1', + 16: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2', + 17: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3', + 18: 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4', + 19: 'PP_GRTAVFS_FW_SEP_FUSE_COUNT', +} +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1 = 0 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0 = 1 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1 = 2 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2 = 3 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3 = 4 +PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4 = 5 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1 = 6 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0 = 7 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1 = 8 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2 = 9 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3 = 10 +PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4 = 11 +PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY = 12 +PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY = 13 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0 = 14 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1 = 15 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2 = 16 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3 = 17 +PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4 = 18 +PP_GRTAVFS_FW_SEP_FUSE_COUNT = 19 +c__EA_PP_GRTAVFS_FW_SEP_FUSE_e = ctypes.c_uint32 # enum +PP_GRTAVFS_FW_SEP_FUSE_e = c__EA_PP_GRTAVFS_FW_SEP_FUSE_e +PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues = c__EA_PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues +class struct_c__SA_SviTelemetryScale_t(Structure): + pass + +struct_c__SA_SviTelemetryScale_t._pack_ = 1 # source:False +struct_c__SA_SviTelemetryScale_t._fields_ = [ + ('Offset', ctypes.c_byte), + ('Padding', ctypes.c_ubyte), + ('MaxCurrent', ctypes.c_uint16), +] + +SviTelemetryScale_t = struct_c__SA_SviTelemetryScale_t + +# values for enumeration 'c__EA_PP_OD_POWER_FEATURE_e' +c__EA_PP_OD_POWER_FEATURE_e__enumvalues = { + 0: 'PP_OD_POWER_FEATURE_ALWAYS_ENABLED', + 1: 'PP_OD_POWER_FEATURE_DISABLED_WHILE_GAMING', + 2: 'PP_OD_POWER_FEATURE_ALWAYS_DISABLED', +} +PP_OD_POWER_FEATURE_ALWAYS_ENABLED = 0 +PP_OD_POWER_FEATURE_DISABLED_WHILE_GAMING = 1 +PP_OD_POWER_FEATURE_ALWAYS_DISABLED = 2 +c__EA_PP_OD_POWER_FEATURE_e = ctypes.c_uint32 # enum +PP_OD_POWER_FEATURE_e = c__EA_PP_OD_POWER_FEATURE_e +PP_OD_POWER_FEATURE_e__enumvalues = c__EA_PP_OD_POWER_FEATURE_e__enumvalues + +# values for enumeration 'c__EA_FanMode_e' +c__EA_FanMode_e__enumvalues = { + 0: 'FAN_MODE_AUTO', + 1: 'FAN_MODE_MANUAL_LINEAR', +} +FAN_MODE_AUTO = 0 +FAN_MODE_MANUAL_LINEAR = 1 +c__EA_FanMode_e = ctypes.c_uint32 # enum +FanMode_e = c__EA_FanMode_e +FanMode_e__enumvalues = c__EA_FanMode_e__enumvalues + +# values for enumeration 'c__EA_OD_FAIL_e' +c__EA_OD_FAIL_e__enumvalues = { + 0: 'OD_NO_ERROR', + 1: 'OD_REQUEST_ADVANCED_NOT_SUPPORTED', + 2: 'OD_UNSUPPORTED_FEATURE', + 3: 'OD_INVALID_FEATURE_COMBO_ERROR', + 4: 'OD_GFXCLK_VF_CURVE_OFFSET_ERROR', + 5: 'OD_VDD_GFX_VMAX_ERROR', + 6: 'OD_VDD_SOC_VMAX_ERROR', + 7: 'OD_PPT_ERROR', + 8: 'OD_FAN_MIN_PWM_ERROR', + 9: 'OD_FAN_ACOUSTIC_TARGET_ERROR', + 10: 'OD_FAN_ACOUSTIC_LIMIT_ERROR', + 11: 'OD_FAN_TARGET_TEMP_ERROR', + 12: 'OD_FAN_ZERO_RPM_STOP_TEMP_ERROR', + 13: 'OD_FAN_CURVE_PWM_ERROR', + 14: 'OD_FAN_CURVE_TEMP_ERROR', + 15: 'OD_FULL_CTRL_GFXCLK_ERROR', + 16: 'OD_FULL_CTRL_UCLK_ERROR', + 17: 'OD_FULL_CTRL_FCLK_ERROR', + 18: 'OD_FULL_CTRL_VDD_GFX_ERROR', + 19: 'OD_FULL_CTRL_VDD_SOC_ERROR', + 20: 'OD_TDC_ERROR', + 21: 'OD_GFXCLK_ERROR', + 22: 'OD_UCLK_ERROR', + 23: 'OD_FCLK_ERROR', + 24: 'OD_OP_TEMP_ERROR', + 25: 'OD_OP_GFX_EDC_ERROR', + 26: 'OD_OP_GFX_PCC_ERROR', + 27: 'OD_POWER_FEATURE_CTRL_ERROR', +} +OD_NO_ERROR = 0 +OD_REQUEST_ADVANCED_NOT_SUPPORTED = 1 +OD_UNSUPPORTED_FEATURE = 2 +OD_INVALID_FEATURE_COMBO_ERROR = 3 +OD_GFXCLK_VF_CURVE_OFFSET_ERROR = 4 +OD_VDD_GFX_VMAX_ERROR = 5 +OD_VDD_SOC_VMAX_ERROR = 6 +OD_PPT_ERROR = 7 +OD_FAN_MIN_PWM_ERROR = 8 +OD_FAN_ACOUSTIC_TARGET_ERROR = 9 +OD_FAN_ACOUSTIC_LIMIT_ERROR = 10 +OD_FAN_TARGET_TEMP_ERROR = 11 +OD_FAN_ZERO_RPM_STOP_TEMP_ERROR = 12 +OD_FAN_CURVE_PWM_ERROR = 13 +OD_FAN_CURVE_TEMP_ERROR = 14 +OD_FULL_CTRL_GFXCLK_ERROR = 15 +OD_FULL_CTRL_UCLK_ERROR = 16 +OD_FULL_CTRL_FCLK_ERROR = 17 +OD_FULL_CTRL_VDD_GFX_ERROR = 18 +OD_FULL_CTRL_VDD_SOC_ERROR = 19 +OD_TDC_ERROR = 20 +OD_GFXCLK_ERROR = 21 +OD_UCLK_ERROR = 22 +OD_FCLK_ERROR = 23 +OD_OP_TEMP_ERROR = 24 +OD_OP_GFX_EDC_ERROR = 25 +OD_OP_GFX_PCC_ERROR = 26 +OD_POWER_FEATURE_CTRL_ERROR = 27 +c__EA_OD_FAIL_e = ctypes.c_uint32 # enum +OD_FAIL_e = c__EA_OD_FAIL_e +OD_FAIL_e__enumvalues = c__EA_OD_FAIL_e__enumvalues +class struct_c__SA_OverDriveTable_t(Structure): + pass + +struct_c__SA_OverDriveTable_t._pack_ = 1 # source:False +struct_c__SA_OverDriveTable_t._fields_ = [ + ('FeatureCtrlMask', ctypes.c_uint32), + ('VoltageOffsetPerZoneBoundary', ctypes.c_int16 * 6), + ('VddGfxVmax', ctypes.c_uint16), + ('VddSocVmax', ctypes.c_uint16), + ('IdlePwrSavingFeaturesCtrl', ctypes.c_ubyte), + ('RuntimePwrSavingFeaturesCtrl', ctypes.c_ubyte), + ('Padding', ctypes.c_uint16), + ('GfxclkFoffset', ctypes.c_int16), + ('Padding1', ctypes.c_uint16), + ('UclkFmin', ctypes.c_uint16), + ('UclkFmax', ctypes.c_uint16), + ('FclkFmin', ctypes.c_uint16), + ('FclkFmax', ctypes.c_uint16), + ('Ppt', ctypes.c_int16), + ('Tdc', ctypes.c_int16), + ('FanLinearPwmPoints', ctypes.c_ubyte * 6), + ('FanLinearTempPoints', ctypes.c_ubyte * 6), + ('FanMinimumPwm', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetTemperature', ctypes.c_uint16), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('FanZeroRpmStopTemp', ctypes.c_ubyte), + ('FanMode', ctypes.c_ubyte), + ('MaxOpTemp', ctypes.c_ubyte), + ('AdvancedOdModeEnabled', ctypes.c_ubyte), + ('Padding2', ctypes.c_ubyte * 3), + ('GfxVoltageFullCtrlMode', ctypes.c_uint16), + ('SocVoltageFullCtrlMode', ctypes.c_uint16), + ('GfxclkFullCtrlMode', ctypes.c_uint16), + ('UclkFullCtrlMode', ctypes.c_uint16), + ('FclkFullCtrlMode', ctypes.c_uint16), + ('Padding3', ctypes.c_uint16), + ('GfxEdc', ctypes.c_int16), + ('GfxPccLimitControl', ctypes.c_int16), + ('GfxclkFmaxVmax', ctypes.c_uint16), + ('GfxclkFmaxVmaxTemperature', ctypes.c_ubyte), + ('Padding4', ctypes.c_ubyte * 1), + ('Spare', ctypes.c_uint32 * 9), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +OverDriveTable_t = struct_c__SA_OverDriveTable_t +class struct_c__SA_OverDriveTableExternal_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('OverDriveTable', OverDriveTable_t), + ] + +OverDriveTableExternal_t = struct_c__SA_OverDriveTableExternal_t +class struct_c__SA_OverDriveLimits_t(Structure): + pass + +struct_c__SA_OverDriveLimits_t._pack_ = 1 # source:False +struct_c__SA_OverDriveLimits_t._fields_ = [ + ('FeatureCtrlMask', ctypes.c_uint32), + ('VoltageOffsetPerZoneBoundary', ctypes.c_int16 * 6), + ('VddGfxVmax', ctypes.c_uint16), + ('VddSocVmax', ctypes.c_uint16), + ('GfxclkFoffset', ctypes.c_int16), + ('Padding', ctypes.c_uint16), + ('UclkFmin', ctypes.c_uint16), + ('UclkFmax', ctypes.c_uint16), + ('FclkFmin', ctypes.c_uint16), + ('FclkFmax', ctypes.c_uint16), + ('Ppt', ctypes.c_int16), + ('Tdc', ctypes.c_int16), + ('FanLinearPwmPoints', ctypes.c_ubyte * 6), + ('FanLinearTempPoints', ctypes.c_ubyte * 6), + ('FanMinimumPwm', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetTemperature', ctypes.c_uint16), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('MaxOpTemp', ctypes.c_ubyte), + ('Padding1', ctypes.c_ubyte * 2), + ('GfxVoltageFullCtrlMode', ctypes.c_uint16), + ('SocVoltageFullCtrlMode', ctypes.c_uint16), + ('GfxclkFullCtrlMode', ctypes.c_uint16), + ('UclkFullCtrlMode', ctypes.c_uint16), + ('FclkFullCtrlMode', ctypes.c_uint16), + ('GfxEdc', ctypes.c_int16), + ('GfxPccLimitControl', ctypes.c_int16), + ('Padding2', ctypes.c_int16), + ('Spare', ctypes.c_uint32 * 5), +] + +OverDriveLimits_t = struct_c__SA_OverDriveLimits_t + +# values for enumeration 'c__EA_BOARD_GPIO_TYPE_e' +c__EA_BOARD_GPIO_TYPE_e__enumvalues = { + 0: 'BOARD_GPIO_SMUIO_0', + 1: 'BOARD_GPIO_SMUIO_1', + 2: 'BOARD_GPIO_SMUIO_2', + 3: 'BOARD_GPIO_SMUIO_3', + 4: 'BOARD_GPIO_SMUIO_4', + 5: 'BOARD_GPIO_SMUIO_5', + 6: 'BOARD_GPIO_SMUIO_6', + 7: 'BOARD_GPIO_SMUIO_7', + 8: 'BOARD_GPIO_SMUIO_8', + 9: 'BOARD_GPIO_SMUIO_9', + 10: 'BOARD_GPIO_SMUIO_10', + 11: 'BOARD_GPIO_SMUIO_11', + 12: 'BOARD_GPIO_SMUIO_12', + 13: 'BOARD_GPIO_SMUIO_13', + 14: 'BOARD_GPIO_SMUIO_14', + 15: 'BOARD_GPIO_SMUIO_15', + 16: 'BOARD_GPIO_SMUIO_16', + 17: 'BOARD_GPIO_SMUIO_17', + 18: 'BOARD_GPIO_SMUIO_18', + 19: 'BOARD_GPIO_SMUIO_19', + 20: 'BOARD_GPIO_SMUIO_20', + 21: 'BOARD_GPIO_SMUIO_21', + 22: 'BOARD_GPIO_SMUIO_22', + 23: 'BOARD_GPIO_SMUIO_23', + 24: 'BOARD_GPIO_SMUIO_24', + 25: 'BOARD_GPIO_SMUIO_25', + 26: 'BOARD_GPIO_SMUIO_26', + 27: 'BOARD_GPIO_SMUIO_27', + 28: 'BOARD_GPIO_SMUIO_28', + 29: 'BOARD_GPIO_SMUIO_29', + 30: 'BOARD_GPIO_SMUIO_30', + 31: 'BOARD_GPIO_SMUIO_31', + 32: 'MAX_BOARD_GPIO_SMUIO_NUM', + 33: 'BOARD_GPIO_DC_GEN_A', + 34: 'BOARD_GPIO_DC_GEN_B', + 35: 'BOARD_GPIO_DC_GEN_C', + 36: 'BOARD_GPIO_DC_GEN_D', + 37: 'BOARD_GPIO_DC_GEN_E', + 38: 'BOARD_GPIO_DC_GEN_F', + 39: 'BOARD_GPIO_DC_GEN_G', + 40: 'BOARD_GPIO_DC_GENLK_CLK', + 41: 'BOARD_GPIO_DC_GENLK_VSYNC', + 42: 'BOARD_GPIO_DC_SWAPLOCK_A', + 43: 'BOARD_GPIO_DC_SWAPLOCK_B', + 44: 'MAX_BOARD_DC_GPIO_NUM', + 45: 'BOARD_GPIO_LV_EN', +} +BOARD_GPIO_SMUIO_0 = 0 +BOARD_GPIO_SMUIO_1 = 1 +BOARD_GPIO_SMUIO_2 = 2 +BOARD_GPIO_SMUIO_3 = 3 +BOARD_GPIO_SMUIO_4 = 4 +BOARD_GPIO_SMUIO_5 = 5 +BOARD_GPIO_SMUIO_6 = 6 +BOARD_GPIO_SMUIO_7 = 7 +BOARD_GPIO_SMUIO_8 = 8 +BOARD_GPIO_SMUIO_9 = 9 +BOARD_GPIO_SMUIO_10 = 10 +BOARD_GPIO_SMUIO_11 = 11 +BOARD_GPIO_SMUIO_12 = 12 +BOARD_GPIO_SMUIO_13 = 13 +BOARD_GPIO_SMUIO_14 = 14 +BOARD_GPIO_SMUIO_15 = 15 +BOARD_GPIO_SMUIO_16 = 16 +BOARD_GPIO_SMUIO_17 = 17 +BOARD_GPIO_SMUIO_18 = 18 +BOARD_GPIO_SMUIO_19 = 19 +BOARD_GPIO_SMUIO_20 = 20 +BOARD_GPIO_SMUIO_21 = 21 +BOARD_GPIO_SMUIO_22 = 22 +BOARD_GPIO_SMUIO_23 = 23 +BOARD_GPIO_SMUIO_24 = 24 +BOARD_GPIO_SMUIO_25 = 25 +BOARD_GPIO_SMUIO_26 = 26 +BOARD_GPIO_SMUIO_27 = 27 +BOARD_GPIO_SMUIO_28 = 28 +BOARD_GPIO_SMUIO_29 = 29 +BOARD_GPIO_SMUIO_30 = 30 +BOARD_GPIO_SMUIO_31 = 31 +MAX_BOARD_GPIO_SMUIO_NUM = 32 +BOARD_GPIO_DC_GEN_A = 33 +BOARD_GPIO_DC_GEN_B = 34 +BOARD_GPIO_DC_GEN_C = 35 +BOARD_GPIO_DC_GEN_D = 36 +BOARD_GPIO_DC_GEN_E = 37 +BOARD_GPIO_DC_GEN_F = 38 +BOARD_GPIO_DC_GEN_G = 39 +BOARD_GPIO_DC_GENLK_CLK = 40 +BOARD_GPIO_DC_GENLK_VSYNC = 41 +BOARD_GPIO_DC_SWAPLOCK_A = 42 +BOARD_GPIO_DC_SWAPLOCK_B = 43 +MAX_BOARD_DC_GPIO_NUM = 44 +BOARD_GPIO_LV_EN = 45 +c__EA_BOARD_GPIO_TYPE_e = ctypes.c_uint32 # enum +BOARD_GPIO_TYPE_e = c__EA_BOARD_GPIO_TYPE_e +BOARD_GPIO_TYPE_e__enumvalues = c__EA_BOARD_GPIO_TYPE_e__enumvalues +class struct_c__SA_BootValues_t(Structure): + pass + +struct_c__SA_BootValues_t._pack_ = 1 # source:False +struct_c__SA_BootValues_t._fields_ = [ + ('InitImuClk', ctypes.c_uint16), + ('InitSocclk', ctypes.c_uint16), + ('InitMpioclk', ctypes.c_uint16), + ('InitSmnclk', ctypes.c_uint16), + ('InitDispClk', ctypes.c_uint16), + ('InitDppClk', ctypes.c_uint16), + ('InitDprefclk', ctypes.c_uint16), + ('InitDcfclk', ctypes.c_uint16), + ('InitDtbclk', ctypes.c_uint16), + ('InitDbguSocClk', ctypes.c_uint16), + ('InitGfxclk_bypass', ctypes.c_uint16), + ('InitMp1clk', ctypes.c_uint16), + ('InitLclk', ctypes.c_uint16), + ('InitDbguBacoClk', ctypes.c_uint16), + ('InitBaco400clk', ctypes.c_uint16), + ('InitBaco1200clk_bypass', ctypes.c_uint16), + ('InitBaco700clk_bypass', ctypes.c_uint16), + ('InitBaco500clk', ctypes.c_uint16), + ('InitDclk0', ctypes.c_uint16), + ('InitVclk0', ctypes.c_uint16), + ('InitFclk', ctypes.c_uint16), + ('Padding1', ctypes.c_uint16), + ('InitUclkLevel', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 3), + ('InitVcoFreqPll0', ctypes.c_uint32), + ('InitVcoFreqPll1', ctypes.c_uint32), + ('InitVcoFreqPll2', ctypes.c_uint32), + ('InitVcoFreqPll3', ctypes.c_uint32), + ('InitVcoFreqPll4', ctypes.c_uint32), + ('InitVcoFreqPll5', ctypes.c_uint32), + ('InitVcoFreqPll6', ctypes.c_uint32), + ('InitVcoFreqPll7', ctypes.c_uint32), + ('InitVcoFreqPll8', ctypes.c_uint32), + ('InitGfx', ctypes.c_uint16), + ('InitSoc', ctypes.c_uint16), + ('InitVddIoMem', ctypes.c_uint16), + ('InitVddCiMem', ctypes.c_uint16), + ('Spare', ctypes.c_uint32 * 8), +] + +BootValues_t = struct_c__SA_BootValues_t +class struct_c__SA_MsgLimits_t(Structure): + pass + +struct_c__SA_MsgLimits_t._pack_ = 1 # source:False +struct_c__SA_MsgLimits_t._fields_ = [ + ('Power', ctypes.c_uint16 * 2 * 4), + ('Tdc', ctypes.c_uint16 * 2), + ('Temperature', ctypes.c_uint16 * 12), + ('PwmLimitMin', ctypes.c_ubyte), + ('PwmLimitMax', ctypes.c_ubyte), + ('FanTargetTemperature', ctypes.c_ubyte), + ('Spare1', ctypes.c_ubyte * 1), + ('AcousticTargetRpmThresholdMin', ctypes.c_uint16), + ('AcousticTargetRpmThresholdMax', ctypes.c_uint16), + ('AcousticLimitRpmThresholdMin', ctypes.c_uint16), + ('AcousticLimitRpmThresholdMax', ctypes.c_uint16), + ('PccLimitMin', ctypes.c_uint16), + ('PccLimitMax', ctypes.c_uint16), + ('FanStopTempMin', ctypes.c_uint16), + ('FanStopTempMax', ctypes.c_uint16), + ('FanStartTempMin', ctypes.c_uint16), + ('FanStartTempMax', ctypes.c_uint16), + ('PowerMinPpt0', ctypes.c_uint16 * 2), + ('Spare', ctypes.c_uint32 * 11), +] + +MsgLimits_t = struct_c__SA_MsgLimits_t +class struct_c__SA_DriverReportedClocks_t(Structure): + pass + +struct_c__SA_DriverReportedClocks_t._pack_ = 1 # source:False +struct_c__SA_DriverReportedClocks_t._fields_ = [ + ('BaseClockAc', ctypes.c_uint16), + ('GameClockAc', ctypes.c_uint16), + ('BoostClockAc', ctypes.c_uint16), + ('BaseClockDc', ctypes.c_uint16), + ('GameClockDc', ctypes.c_uint16), + ('BoostClockDc', ctypes.c_uint16), + ('MaxReportedClock', ctypes.c_uint16), + ('Padding', ctypes.c_uint16), + ('Reserved', ctypes.c_uint32 * 3), +] + +DriverReportedClocks_t = struct_c__SA_DriverReportedClocks_t +class struct_c__SA_AvfsDcBtcParams_t(Structure): + pass + +struct_c__SA_AvfsDcBtcParams_t._pack_ = 1 # source:False +struct_c__SA_AvfsDcBtcParams_t._fields_ = [ + ('DcBtcEnabled', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 3), + ('DcTol', ctypes.c_uint16), + ('DcBtcGb', ctypes.c_uint16), + ('DcBtcMin', ctypes.c_uint16), + ('DcBtcMax', ctypes.c_uint16), + ('DcBtcGbScalar', LinearInt_t), +] + +AvfsDcBtcParams_t = struct_c__SA_AvfsDcBtcParams_t +class struct_c__SA_AvfsFuseOverride_t(Structure): + pass + +struct_c__SA_AvfsFuseOverride_t._pack_ = 1 # source:False +struct_c__SA_AvfsFuseOverride_t._fields_ = [ + ('AvfsTemp', ctypes.c_uint16 * 2), + ('VftFMin', ctypes.c_uint16), + ('VInversion', ctypes.c_uint16), + ('qVft', struct_c__SA_QuadraticInt_t * 2), + ('qAvfsGb', QuadraticInt_t), + ('qAvfsGb2', QuadraticInt_t), +] + +AvfsFuseOverride_t = struct_c__SA_AvfsFuseOverride_t +class struct_c__SA_PFE_Settings_t(Structure): + pass + +struct_c__SA_PFE_Settings_t._pack_ = 1 # source:False +struct_c__SA_PFE_Settings_t._fields_ = [ + ('Version', ctypes.c_ubyte), + ('Spare8', ctypes.c_ubyte * 3), + ('FeaturesToRun', ctypes.c_uint32 * 2), + ('FwDStateMask', ctypes.c_uint32), + ('DebugOverrides', ctypes.c_uint32), + ('Spare', ctypes.c_uint32 * 2), +] + +PFE_Settings_t = struct_c__SA_PFE_Settings_t +class struct_c__SA_SkuTable_t(Structure): + pass + +struct_c__SA_SkuTable_t._pack_ = 1 # source:False +struct_c__SA_SkuTable_t._fields_ = [ + ('Version', ctypes.c_uint32), + ('TotalPowerConfig', ctypes.c_ubyte), + ('CustomerVariant', ctypes.c_ubyte), + ('MemoryTemperatureTypeMask', ctypes.c_ubyte), + ('SmartShiftVersion', ctypes.c_ubyte), + ('SocketPowerLimitSpare', ctypes.c_ubyte * 10), + ('EnableLegacyPptLimit', ctypes.c_ubyte), + ('UseInputTelemetry', ctypes.c_ubyte), + ('SmartShiftMinReportedPptinDcs', ctypes.c_ubyte), + ('PaddingPpt', ctypes.c_ubyte * 7), + ('HwCtfTempLimit', ctypes.c_uint16), + ('PaddingInfra', ctypes.c_uint16), + ('FitControllerFailureRateLimit', ctypes.c_uint32), + ('FitControllerGfxDutyCycle', ctypes.c_uint32), + ('FitControllerSocDutyCycle', ctypes.c_uint32), + ('FitControllerSocOffset', ctypes.c_uint32), + ('GfxApccPlusResidencyLimit', ctypes.c_uint32), + ('ThrottlerControlMask', ctypes.c_uint32), + ('UlvVoltageOffset', ctypes.c_uint16 * 2), + ('Padding', ctypes.c_ubyte * 2), + ('DeepUlvVoltageOffsetSoc', ctypes.c_uint16), + ('DefaultMaxVoltage', ctypes.c_uint16 * 2), + ('BoostMaxVoltage', ctypes.c_uint16 * 2), + ('VminTempHystersis', ctypes.c_int16 * 2), + ('VminTempThreshold', ctypes.c_int16 * 2), + ('Vmin_Hot_T0', ctypes.c_uint16 * 2), + ('Vmin_Cold_T0', ctypes.c_uint16 * 2), + ('Vmin_Hot_Eol', ctypes.c_uint16 * 2), + ('Vmin_Cold_Eol', ctypes.c_uint16 * 2), + ('Vmin_Aging_Offset', ctypes.c_uint16 * 2), + ('Spare_Vmin_Plat_Offset_Hot', ctypes.c_uint16 * 2), + ('Spare_Vmin_Plat_Offset_Cold', ctypes.c_uint16 * 2), + ('VcBtcFixedVminAgingOffset', ctypes.c_uint16 * 2), + ('VcBtcVmin2PsmDegrationGb', ctypes.c_uint16 * 2), + ('VcBtcPsmA', ctypes.c_uint32 * 2), + ('VcBtcPsmB', ctypes.c_uint32 * 2), + ('VcBtcVminA', ctypes.c_uint32 * 2), + ('VcBtcVminB', ctypes.c_uint32 * 2), + ('PerPartVminEnabled', ctypes.c_ubyte * 2), + ('VcBtcEnabled', ctypes.c_ubyte * 2), + ('SocketPowerLimitAcTau', ctypes.c_uint16 * 4), + ('SocketPowerLimitDcTau', ctypes.c_uint16 * 4), + ('Gfx_Vmin_droop', QuadraticInt_t), + ('Soc_Vmin_droop', QuadraticInt_t), + ('SpareVmin', ctypes.c_uint32 * 6), + ('DpmDescriptor', struct_c__SA_DpmDescriptor_t * 11), + ('FreqTableGfx', ctypes.c_uint16 * 16), + ('FreqTableVclk', ctypes.c_uint16 * 8), + ('FreqTableDclk', ctypes.c_uint16 * 8), + ('FreqTableSocclk', ctypes.c_uint16 * 8), + ('FreqTableUclk', ctypes.c_uint16 * 6), + ('FreqTableShadowUclk', ctypes.c_uint16 * 6), + ('FreqTableDispclk', ctypes.c_uint16 * 8), + ('FreqTableDppClk', ctypes.c_uint16 * 8), + ('FreqTableDprefclk', ctypes.c_uint16 * 8), + ('FreqTableDcfclk', ctypes.c_uint16 * 8), + ('FreqTableDtbclk', ctypes.c_uint16 * 8), + ('FreqTableFclk', ctypes.c_uint16 * 8), + ('DcModeMaxFreq', ctypes.c_uint32 * 11), + ('GfxclkAibFmax', ctypes.c_uint16), + ('GfxDpmPadding', ctypes.c_uint16), + ('GfxclkFgfxoffEntry', ctypes.c_uint16), + ('GfxclkFgfxoffExitImu', ctypes.c_uint16), + ('GfxclkFgfxoffExitRlc', ctypes.c_uint16), + ('GfxclkThrottleClock', ctypes.c_uint16), + ('EnableGfxPowerStagesGpio', ctypes.c_ubyte), + ('GfxIdlePadding', ctypes.c_ubyte), + ('SmsRepairWRCKClkDivEn', ctypes.c_ubyte), + ('SmsRepairWRCKClkDivVal', ctypes.c_ubyte), + ('GfxOffEntryEarlyMGCGEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGDelayEn', ctypes.c_ubyte), + ('GfxOffEntryForceCGCGDelayVal', ctypes.c_ubyte), + ('GfxclkFreqGfxUlv', ctypes.c_uint16), + ('GfxIdlePadding2', ctypes.c_ubyte * 2), + ('GfxOffEntryHysteresis', ctypes.c_uint32), + ('GfxoffSpare', ctypes.c_uint32 * 15), + ('DfllMstrOscConfigA', ctypes.c_uint16), + ('DfllSlvOscConfigA', ctypes.c_uint16), + ('DfllBtcMasterScalerM', ctypes.c_uint32), + ('DfllBtcMasterScalerB', ctypes.c_int32), + ('DfllBtcSlaveScalerM', ctypes.c_uint32), + ('DfllBtcSlaveScalerB', ctypes.c_int32), + ('DfllPccAsWaitCtrl', ctypes.c_uint32), + ('DfllPccAsStepCtrl', ctypes.c_uint32), + ('GfxDfllSpare', ctypes.c_uint32 * 9), + ('DvoPsmDownThresholdVoltage', ctypes.c_uint32), + ('DvoPsmUpThresholdVoltage', ctypes.c_uint32), + ('DvoFmaxLowScaler', ctypes.c_uint32), + ('PaddingDcs', ctypes.c_uint32), + ('DcsMinGfxOffTime', ctypes.c_uint16), + ('DcsMaxGfxOffTime', ctypes.c_uint16), + ('DcsMinCreditAccum', ctypes.c_uint32), + ('DcsExitHysteresis', ctypes.c_uint16), + ('DcsTimeout', ctypes.c_uint16), + ('DcsPfGfxFopt', ctypes.c_uint32), + ('DcsPfUclkFopt', ctypes.c_uint32), + ('FoptEnabled', ctypes.c_ubyte), + ('DcsSpare2', ctypes.c_ubyte * 3), + ('DcsFoptM', ctypes.c_uint32), + ('DcsFoptB', ctypes.c_uint32), + ('DcsSpare', ctypes.c_uint32 * 9), + ('UseStrobeModeOptimizations', ctypes.c_ubyte), + ('PaddingMem', ctypes.c_ubyte * 3), + ('UclkDpmPstates', ctypes.c_ubyte * 6), + ('UclkDpmShadowPstates', ctypes.c_ubyte * 6), + ('FreqTableUclkDiv', ctypes.c_ubyte * 6), + ('FreqTableShadowUclkDiv', ctypes.c_ubyte * 6), + ('MemVmempVoltage', ctypes.c_uint16 * 6), + ('MemVddioVoltage', ctypes.c_uint16 * 6), + ('DalDcModeMaxUclkFreq', ctypes.c_uint16), + ('PaddingsMem', ctypes.c_ubyte * 2), + ('PaddingFclk', ctypes.c_uint32), + ('PcieGenSpeed', ctypes.c_ubyte * 3), + ('PcieLaneCount', ctypes.c_ubyte * 3), + ('LclkFreq', ctypes.c_uint16 * 3), + ('OverrideGfxAvfsFuses', ctypes.c_ubyte), + ('GfxAvfsPadding', ctypes.c_ubyte * 1), + ('DroopGBStDev', ctypes.c_uint16), + ('SocHwRtAvfsFuses', ctypes.c_uint32 * 32), + ('GfxL2HwRtAvfsFuses', ctypes.c_uint32 * 32), + ('PsmDidt_Vcross', ctypes.c_uint16 * 2), + ('PsmDidt_StaticDroop_A', ctypes.c_uint32 * 3), + ('PsmDidt_StaticDroop_B', ctypes.c_uint32 * 3), + ('PsmDidt_DynDroop_A', ctypes.c_uint32 * 3), + ('PsmDidt_DynDroop_B', ctypes.c_uint32 * 3), + ('spare_HwRtAvfsFuses', ctypes.c_uint32 * 19), + ('SocCommonRtAvfs', ctypes.c_uint32 * 13), + ('GfxCommonRtAvfs', ctypes.c_uint32 * 13), + ('SocFwRtAvfsFuses', ctypes.c_uint32 * 19), + ('GfxL2FwRtAvfsFuses', ctypes.c_uint32 * 19), + ('spare_FwRtAvfsFuses', ctypes.c_uint32 * 19), + ('Soc_Droop_PWL_F', ctypes.c_uint32 * 5), + ('Soc_Droop_PWL_a', ctypes.c_uint32 * 5), + ('Soc_Droop_PWL_b', ctypes.c_uint32 * 5), + ('Soc_Droop_PWL_c', ctypes.c_uint32 * 5), + ('Gfx_Droop_PWL_F', ctypes.c_uint32 * 5), + ('Gfx_Droop_PWL_a', ctypes.c_uint32 * 5), + ('Gfx_Droop_PWL_b', ctypes.c_uint32 * 5), + ('Gfx_Droop_PWL_c', ctypes.c_uint32 * 5), + ('Gfx_Static_PWL_Offset', ctypes.c_uint32 * 5), + ('Soc_Static_PWL_Offset', ctypes.c_uint32 * 5), + ('dGbV_dT_vmin', ctypes.c_uint32), + ('dGbV_dT_vmax', ctypes.c_uint32), + ('PaddingV2F', ctypes.c_uint32 * 4), + ('DcBtcGfxParams', AvfsDcBtcParams_t), + ('SSCurve_GFX', QuadraticInt_t), + ('GfxAvfsSpare', ctypes.c_uint32 * 29), + ('OverrideSocAvfsFuses', ctypes.c_ubyte), + ('MinSocAvfsRevision', ctypes.c_ubyte), + ('SocAvfsPadding', ctypes.c_ubyte * 2), + ('SocAvfsFuseOverride', struct_c__SA_AvfsFuseOverride_t * 1), + ('dBtcGbSoc', struct_c__SA_DroopInt_t * 1), + ('qAgingGb', struct_c__SA_LinearInt_t * 1), + ('qStaticVoltageOffset', struct_c__SA_QuadraticInt_t * 1), + ('DcBtcSocParams', struct_c__SA_AvfsDcBtcParams_t * 1), + ('SSCurve_SOC', QuadraticInt_t), + ('SocAvfsSpare', ctypes.c_uint32 * 29), + ('BootValues', BootValues_t), + ('DriverReportedClocks', DriverReportedClocks_t), + ('MsgLimits', MsgLimits_t), + ('OverDriveLimitsBasicMin', OverDriveLimits_t), + ('OverDriveLimitsBasicMax', OverDriveLimits_t), + ('OverDriveLimitsAdvancedMin', OverDriveLimits_t), + ('OverDriveLimitsAdvancedMax', OverDriveLimits_t), + ('TotalBoardPowerSupport', ctypes.c_ubyte), + ('TotalBoardPowerPadding', ctypes.c_ubyte * 1), + ('TotalBoardPowerRoc', ctypes.c_uint16), + ('qFeffCoeffGameClock', struct_c__SA_QuadraticInt_t * 2), + ('qFeffCoeffBaseClock', struct_c__SA_QuadraticInt_t * 2), + ('qFeffCoeffBoostClock', struct_c__SA_QuadraticInt_t * 2), + ('AptUclkGfxclkLookup', ctypes.c_int32 * 6 * 2), + ('AptUclkGfxclkLookupHyst', ctypes.c_uint32 * 6 * 2), + ('AptPadding', ctypes.c_uint32), + ('GfxXvminDidtDroopThresh', QuadraticInt_t), + ('GfxXvminDidtResetDDWait', ctypes.c_uint32), + ('GfxXvminDidtClkStopWait', ctypes.c_uint32), + ('GfxXvminDidtFcsStepCtrl', ctypes.c_uint32), + ('GfxXvminDidtFcsWaitCtrl', ctypes.c_uint32), + ('PsmModeEnabled', ctypes.c_uint32), + ('P2v_a', ctypes.c_uint32), + ('P2v_b', ctypes.c_uint32), + ('P2v_c', ctypes.c_uint32), + ('T2p_a', ctypes.c_uint32), + ('T2p_b', ctypes.c_uint32), + ('T2p_c', ctypes.c_uint32), + ('P2vTemp', ctypes.c_uint32), + ('PsmDidtStaticSettings', QuadraticInt_t), + ('PsmDidtDynamicSettings', QuadraticInt_t), + ('PsmDidtAvgDiv', ctypes.c_ubyte), + ('PsmDidtForceStall', ctypes.c_ubyte), + ('PsmDidtReleaseTimer', ctypes.c_uint16), + ('PsmDidtStallPattern', ctypes.c_uint32), + ('CacEdcCacLeakageC0', ctypes.c_uint32), + ('CacEdcCacLeakageC1', ctypes.c_uint32), + ('CacEdcCacLeakageC2', ctypes.c_uint32), + ('CacEdcCacLeakageC3', ctypes.c_uint32), + ('CacEdcCacLeakageC4', ctypes.c_uint32), + ('CacEdcCacLeakageC5', ctypes.c_uint32), + ('CacEdcGfxClkScalar', ctypes.c_uint32), + ('CacEdcGfxClkIntercept', ctypes.c_uint32), + ('CacEdcCac_m', ctypes.c_uint32), + ('CacEdcCac_b', ctypes.c_uint32), + ('CacEdcCurrLimitGuardband', ctypes.c_uint32), + ('CacEdcDynToTotalCacRatio', ctypes.c_uint32), + ('XVmin_Gfx_EdcThreshScalar', ctypes.c_uint32), + ('XVmin_Gfx_EdcEnableFreq', ctypes.c_uint32), + ('XVmin_Gfx_EdcPccAsStepCtrl', ctypes.c_uint32), + ('XVmin_Gfx_EdcPccAsWaitCtrl', ctypes.c_uint32), + ('XVmin_Gfx_EdcThreshold', ctypes.c_uint16), + ('XVmin_Gfx_EdcFiltHysWaitCtrl', ctypes.c_uint16), + ('XVmin_Soc_EdcThreshScalar', ctypes.c_uint32), + ('XVmin_Soc_EdcEnableFreq', ctypes.c_uint32), + ('XVmin_Soc_EdcThreshold', ctypes.c_uint32), + ('XVmin_Soc_EdcStepUpTime', ctypes.c_uint16), + ('XVmin_Soc_EdcStepDownTime', ctypes.c_uint16), + ('XVmin_Soc_EdcInitPccStep', ctypes.c_ubyte), + ('PaddingSocEdc', ctypes.c_ubyte * 3), + ('GfxXvminFuseOverride', ctypes.c_ubyte), + ('SocXvminFuseOverride', ctypes.c_ubyte), + ('PaddingXvminFuseOverride', ctypes.c_ubyte * 2), + ('GfxXvminFddTempLow', ctypes.c_ubyte), + ('GfxXvminFddTempHigh', ctypes.c_ubyte), + ('SocXvminFddTempLow', ctypes.c_ubyte), + ('SocXvminFddTempHigh', ctypes.c_ubyte), + ('GfxXvminFddVolt0', ctypes.c_uint16), + ('GfxXvminFddVolt1', ctypes.c_uint16), + ('GfxXvminFddVolt2', ctypes.c_uint16), + ('SocXvminFddVolt0', ctypes.c_uint16), + ('SocXvminFddVolt1', ctypes.c_uint16), + ('SocXvminFddVolt2', ctypes.c_uint16), + ('GfxXvminDsFddDsm', ctypes.c_uint16 * 6), + ('GfxXvminEdcFddDsm', ctypes.c_uint16 * 6), + ('SocXvminEdcFddDsm', ctypes.c_uint16 * 6), + ('Spare', ctypes.c_uint32), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SkuTable_t = struct_c__SA_SkuTable_t +class struct_c__SA_Svi3RegulatorSettings_t(Structure): + pass + +struct_c__SA_Svi3RegulatorSettings_t._pack_ = 1 # source:False +struct_c__SA_Svi3RegulatorSettings_t._fields_ = [ + ('SlewRateConditions', ctypes.c_ubyte), + ('LoadLineAdjust', ctypes.c_ubyte), + ('VoutOffset', ctypes.c_ubyte), + ('VidMax', ctypes.c_ubyte), + ('VidMin', ctypes.c_ubyte), + ('TenBitTelEn', ctypes.c_ubyte), + ('SixteenBitTelEn', ctypes.c_ubyte), + ('OcpThresh', ctypes.c_ubyte), + ('OcpWarnThresh', ctypes.c_ubyte), + ('OcpSettings', ctypes.c_ubyte), + ('VrhotThresh', ctypes.c_ubyte), + ('OtpThresh', ctypes.c_ubyte), + ('UvpOvpDeltaRef', ctypes.c_ubyte), + ('PhaseShed', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 10), + ('SettingOverrideMask', ctypes.c_uint32), +] + +Svi3RegulatorSettings_t = struct_c__SA_Svi3RegulatorSettings_t +class struct_c__SA_BoardTable_t(Structure): + pass + +struct_c__SA_BoardTable_t._pack_ = 1 # source:False +struct_c__SA_BoardTable_t._fields_ = [ + ('Version', ctypes.c_uint32), + ('I2cControllers', struct_c__SA_I2cControllerConfig_t * 8), + ('SlaveAddrMapping', ctypes.c_ubyte * 4), + ('VrPsiSupport', ctypes.c_ubyte * 4), + ('Svi3SvcSpeed', ctypes.c_uint32), + ('EnablePsi6', ctypes.c_ubyte * 4), + ('Svi3RegSettings', struct_c__SA_Svi3RegulatorSettings_t * 4), + ('LedOffGpio', ctypes.c_ubyte), + ('FanOffGpio', ctypes.c_ubyte), + ('GfxVrPowerStageOffGpio', ctypes.c_ubyte), + ('AcDcGpio', ctypes.c_ubyte), + ('AcDcPolarity', ctypes.c_ubyte), + ('VR0HotGpio', ctypes.c_ubyte), + ('VR0HotPolarity', ctypes.c_ubyte), + ('GthrGpio', ctypes.c_ubyte), + ('GthrPolarity', ctypes.c_ubyte), + ('LedPin0', ctypes.c_ubyte), + ('LedPin1', ctypes.c_ubyte), + ('LedPin2', ctypes.c_ubyte), + ('LedEnableMask', ctypes.c_ubyte), + ('LedPcie', ctypes.c_ubyte), + ('LedError', ctypes.c_ubyte), + ('PaddingLed', ctypes.c_ubyte), + ('UclkTrainingModeSpreadPercent', ctypes.c_ubyte), + ('UclkSpreadPadding', ctypes.c_ubyte), + ('UclkSpreadFreq', ctypes.c_uint16), + ('UclkSpreadPercent', ctypes.c_ubyte * 16), + ('GfxclkSpreadEnable', ctypes.c_ubyte), + ('FclkSpreadPercent', ctypes.c_ubyte), + ('FclkSpreadFreq', ctypes.c_uint16), + ('DramWidth', ctypes.c_ubyte), + ('PaddingMem1', ctypes.c_ubyte * 7), + ('HsrEnabled', ctypes.c_ubyte), + ('VddqOffEnabled', ctypes.c_ubyte), + ('PaddingUmcFlags', ctypes.c_ubyte * 2), + ('Paddign1', ctypes.c_uint32), + ('BacoEntryDelay', ctypes.c_uint32), + ('FuseWritePowerMuxPresent', ctypes.c_ubyte), + ('FuseWritePadding', ctypes.c_ubyte * 3), + ('LoadlineGfx', ctypes.c_uint32), + ('LoadlineSoc', ctypes.c_uint32), + ('GfxEdcLimit', ctypes.c_uint32), + ('SocEdcLimit', ctypes.c_uint32), + ('RestBoardPower', ctypes.c_uint32), + ('ConnectorsImpedance', ctypes.c_uint32), + ('EpcsSens0', ctypes.c_ubyte), + ('EpcsSens1', ctypes.c_ubyte), + ('PaddingEpcs', ctypes.c_ubyte * 2), + ('BoardSpare', ctypes.c_uint32 * 52), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +BoardTable_t = struct_c__SA_BoardTable_t +class struct_c__SA_CustomSkuTable_t(Structure): + pass + +struct_c__SA_CustomSkuTable_t._pack_ = 1 # source:False +struct_c__SA_CustomSkuTable_t._fields_ = [ + ('SocketPowerLimitAc', ctypes.c_uint16 * 4), + ('VrTdcLimit', ctypes.c_uint16 * 2), + ('TotalIdleBoardPowerM', ctypes.c_int16), + ('TotalIdleBoardPowerB', ctypes.c_int16), + ('TotalBoardPowerM', ctypes.c_int16), + ('TotalBoardPowerB', ctypes.c_int16), + ('TemperatureLimit', ctypes.c_uint16 * 12), + ('FanStopTemp', ctypes.c_uint16 * 12), + ('FanStartTemp', ctypes.c_uint16 * 12), + ('FanGain', ctypes.c_uint16 * 12), + ('FanPwmMin', ctypes.c_uint16), + ('AcousticTargetRpmThreshold', ctypes.c_uint16), + ('AcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanMaximumRpm', ctypes.c_uint16), + ('MGpuAcousticLimitRpmThreshold', ctypes.c_uint16), + ('FanTargetGfxclk', ctypes.c_uint16), + ('TempInputSelectMask', ctypes.c_uint32), + ('FanZeroRpmEnable', ctypes.c_ubyte), + ('FanTachEdgePerRev', ctypes.c_ubyte), + ('FanPadding', ctypes.c_uint16), + ('FanTargetTemperature', ctypes.c_uint16 * 12), + ('FuzzyFan_ErrorSetDelta', ctypes.c_int16), + ('FuzzyFan_ErrorRateSetDelta', ctypes.c_int16), + ('FuzzyFan_PwmSetDelta', ctypes.c_int16), + ('FanPadding2', ctypes.c_uint16), + ('FwCtfLimit', ctypes.c_uint16 * 12), + ('IntakeTempEnableRPM', ctypes.c_uint16), + ('IntakeTempOffsetTemp', ctypes.c_int16), + ('IntakeTempReleaseTemp', ctypes.c_uint16), + ('IntakeTempHighIntakeAcousticLimit', ctypes.c_uint16), + ('IntakeTempAcouticLimitReleaseRate', ctypes.c_uint16), + ('FanAbnormalTempLimitOffset', ctypes.c_int16), + ('FanStalledTriggerRpm', ctypes.c_uint16), + ('FanAbnormalTriggerRpmCoeff', ctypes.c_uint16), + ('FanSpare', ctypes.c_uint16 * 1), + ('FanIntakeSensorSupport', ctypes.c_ubyte), + ('FanIntakePadding', ctypes.c_ubyte), + ('FanSpare2', ctypes.c_uint32 * 12), + ('ODFeatureCtrlMask', ctypes.c_uint32), + ('TemperatureLimit_Hynix', ctypes.c_uint16), + ('TemperatureLimit_Micron', ctypes.c_uint16), + ('TemperatureFwCtfLimit_Hynix', ctypes.c_uint16), + ('TemperatureFwCtfLimit_Micron', ctypes.c_uint16), + ('PlatformTdcLimit', ctypes.c_uint16 * 2), + ('SocketPowerLimitDc', ctypes.c_uint16 * 4), + ('SocketPowerLimitSmartShift2', ctypes.c_uint16), + ('CustomSkuSpare16b', ctypes.c_uint16), + ('CustomSkuSpare32b', ctypes.c_uint32 * 10), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +CustomSkuTable_t = struct_c__SA_CustomSkuTable_t +class struct_c__SA_PPTable_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('PFE_Settings', PFE_Settings_t), + ('SkuTable', SkuTable_t), + ('CustomSkuTable', CustomSkuTable_t), + ('BoardTable', BoardTable_t), + ] + +PPTable_t = struct_c__SA_PPTable_t +class struct_c__SA_DriverSmuConfig_t(Structure): + pass + +struct_c__SA_DriverSmuConfig_t._pack_ = 1 # source:False +struct_c__SA_DriverSmuConfig_t._fields_ = [ + ('GfxclkAverageLpfTau', ctypes.c_uint16), + ('FclkAverageLpfTau', ctypes.c_uint16), + ('UclkAverageLpfTau', ctypes.c_uint16), + ('GfxActivityLpfTau', ctypes.c_uint16), + ('UclkActivityLpfTau', ctypes.c_uint16), + ('UclkMaxActivityLpfTau', ctypes.c_uint16), + ('SocketPowerLpfTau', ctypes.c_uint16), + ('VcnClkAverageLpfTau', ctypes.c_uint16), + ('VcnUsageAverageLpfTau', ctypes.c_uint16), + ('PcieActivityLpTau', ctypes.c_uint16), +] + +DriverSmuConfig_t = struct_c__SA_DriverSmuConfig_t +class struct_c__SA_DriverSmuConfigExternal_t(Structure): + pass + +struct_c__SA_DriverSmuConfigExternal_t._pack_ = 1 # source:False +struct_c__SA_DriverSmuConfigExternal_t._fields_ = [ + ('DriverSmuConfig', DriverSmuConfig_t), + ('Spare', ctypes.c_uint32 * 8), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DriverSmuConfigExternal_t = struct_c__SA_DriverSmuConfigExternal_t +class struct_c__SA_DriverInfoTable_t(Structure): + pass + +struct_c__SA_DriverInfoTable_t._pack_ = 1 # source:False +struct_c__SA_DriverInfoTable_t._fields_ = [ + ('FreqTableGfx', ctypes.c_uint16 * 16), + ('FreqTableVclk', ctypes.c_uint16 * 8), + ('FreqTableDclk', ctypes.c_uint16 * 8), + ('FreqTableSocclk', ctypes.c_uint16 * 8), + ('FreqTableUclk', ctypes.c_uint16 * 6), + ('FreqTableDispclk', ctypes.c_uint16 * 8), + ('FreqTableDppClk', ctypes.c_uint16 * 8), + ('FreqTableDprefclk', ctypes.c_uint16 * 8), + ('FreqTableDcfclk', ctypes.c_uint16 * 8), + ('FreqTableDtbclk', ctypes.c_uint16 * 8), + ('FreqTableFclk', ctypes.c_uint16 * 8), + ('DcModeMaxFreq', ctypes.c_uint16 * 11), + ('Padding', ctypes.c_uint16), + ('Spare', ctypes.c_uint32 * 32), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DriverInfoTable_t = struct_c__SA_DriverInfoTable_t +class struct_c__SA_SmuMetrics_t(Structure): + pass + +struct_c__SA_SmuMetrics_t._pack_ = 1 # source:False +struct_c__SA_SmuMetrics_t._fields_ = [ + ('CurrClock', ctypes.c_uint32 * 11), + ('AverageGfxclkFrequencyTarget', ctypes.c_uint16), + ('AverageGfxclkFrequencyPreDs', ctypes.c_uint16), + ('AverageGfxclkFrequencyPostDs', ctypes.c_uint16), + ('AverageFclkFrequencyPreDs', ctypes.c_uint16), + ('AverageFclkFrequencyPostDs', ctypes.c_uint16), + ('AverageMemclkFrequencyPreDs', ctypes.c_uint16), + ('AverageMemclkFrequencyPostDs', ctypes.c_uint16), + ('AverageVclk0Frequency', ctypes.c_uint16), + ('AverageDclk0Frequency', ctypes.c_uint16), + ('AverageVclk1Frequency', ctypes.c_uint16), + ('AverageDclk1Frequency', ctypes.c_uint16), + ('AveragePCIeBusy', ctypes.c_uint16), + ('dGPU_W_MAX', ctypes.c_uint16), + ('padding', ctypes.c_uint16), + ('MovingAverageGfxclkFrequencyTarget', ctypes.c_uint16), + ('MovingAverageGfxclkFrequencyPreDs', ctypes.c_uint16), + ('MovingAverageGfxclkFrequencyPostDs', ctypes.c_uint16), + ('MovingAverageFclkFrequencyPreDs', ctypes.c_uint16), + ('MovingAverageFclkFrequencyPostDs', ctypes.c_uint16), + ('MovingAverageMemclkFrequencyPreDs', ctypes.c_uint16), + ('MovingAverageMemclkFrequencyPostDs', ctypes.c_uint16), + ('MovingAverageVclk0Frequency', ctypes.c_uint16), + ('MovingAverageDclk0Frequency', ctypes.c_uint16), + ('MovingAverageGfxActivity', ctypes.c_uint16), + ('MovingAverageUclkActivity', ctypes.c_uint16), + ('MovingAverageVcn0ActivityPercentage', ctypes.c_uint16), + ('MovingAveragePCIeBusy', ctypes.c_uint16), + ('MovingAverageUclkActivity_MAX', ctypes.c_uint16), + ('MovingAverageSocketPower', ctypes.c_uint16), + ('MovingAveragePadding', ctypes.c_uint16), + ('MetricsCounter', ctypes.c_uint32), + ('AvgVoltage', ctypes.c_uint16 * 4), + ('AvgCurrent', ctypes.c_uint16 * 4), + ('AverageGfxActivity', ctypes.c_uint16), + ('AverageUclkActivity', ctypes.c_uint16), + ('AverageVcn0ActivityPercentage', ctypes.c_uint16), + ('Vcn1ActivityPercentage', ctypes.c_uint16), + ('EnergyAccumulator', ctypes.c_uint32), + ('AverageSocketPower', ctypes.c_uint16), + ('AverageTotalBoardPower', ctypes.c_uint16), + ('AvgTemperature', ctypes.c_uint16 * 12), + ('AvgTemperatureFanIntake', ctypes.c_uint16), + ('PcieRate', ctypes.c_ubyte), + ('PcieWidth', ctypes.c_ubyte), + ('AvgFanPwm', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 1), + ('AvgFanRpm', ctypes.c_uint16), + ('ThrottlingPercentage', ctypes.c_ubyte * 21), + ('VmaxThrottlingPercentage', ctypes.c_ubyte), + ('padding1', ctypes.c_ubyte * 2), + ('D3HotEntryCountPerMode', ctypes.c_uint32 * 4), + ('D3HotExitCountPerMode', ctypes.c_uint32 * 4), + ('ArmMsgReceivedCountPerMode', ctypes.c_uint32 * 4), + ('ApuSTAPMSmartShiftLimit', ctypes.c_uint16), + ('ApuSTAPMLimit', ctypes.c_uint16), + ('AvgApuSocketPower', ctypes.c_uint16), + ('AverageUclkActivity_MAX', ctypes.c_uint16), + ('PublicSerialNumberLower', ctypes.c_uint32), + ('PublicSerialNumberUpper', ctypes.c_uint32), +] + +SmuMetrics_t = struct_c__SA_SmuMetrics_t +class struct_c__SA_SmuMetricsExternal_t(Structure): + pass + +struct_c__SA_SmuMetricsExternal_t._pack_ = 1 # source:False +struct_c__SA_SmuMetricsExternal_t._fields_ = [ + ('SmuMetrics', SmuMetrics_t), + ('Spare', ctypes.c_uint32 * 30), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +SmuMetricsExternal_t = struct_c__SA_SmuMetricsExternal_t +class struct_c__SA_WatermarkRowGeneric_t(Structure): + pass + +struct_c__SA_WatermarkRowGeneric_t._pack_ = 1 # source:False +struct_c__SA_WatermarkRowGeneric_t._fields_ = [ + ('WmSetting', ctypes.c_ubyte), + ('Flags', ctypes.c_ubyte), + ('Padding', ctypes.c_ubyte * 2), +] + +WatermarkRowGeneric_t = struct_c__SA_WatermarkRowGeneric_t + +# values for enumeration 'c__EA_WATERMARKS_FLAGS_e' +c__EA_WATERMARKS_FLAGS_e__enumvalues = { + 0: 'WATERMARKS_CLOCK_RANGE', + 1: 'WATERMARKS_DUMMY_PSTATE', + 2: 'WATERMARKS_MALL', + 3: 'WATERMARKS_COUNT', +} +WATERMARKS_CLOCK_RANGE = 0 +WATERMARKS_DUMMY_PSTATE = 1 +WATERMARKS_MALL = 2 +WATERMARKS_COUNT = 3 +c__EA_WATERMARKS_FLAGS_e = ctypes.c_uint32 # enum +WATERMARKS_FLAGS_e = c__EA_WATERMARKS_FLAGS_e +WATERMARKS_FLAGS_e__enumvalues = c__EA_WATERMARKS_FLAGS_e__enumvalues +class struct_c__SA_Watermarks_t(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('WatermarkRow', struct_c__SA_WatermarkRowGeneric_t * 4), + ] + +Watermarks_t = struct_c__SA_Watermarks_t +class struct_c__SA_WatermarksExternal_t(Structure): + pass + +struct_c__SA_WatermarksExternal_t._pack_ = 1 # source:False +struct_c__SA_WatermarksExternal_t._fields_ = [ + ('Watermarks', Watermarks_t), + ('Spare', ctypes.c_uint32 * 16), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +WatermarksExternal_t = struct_c__SA_WatermarksExternal_t +class struct_c__SA_AvfsDebugTable_t(Structure): + pass + +struct_c__SA_AvfsDebugTable_t._pack_ = 1 # source:False +struct_c__SA_AvfsDebugTable_t._fields_ = [ + ('avgPsmCount', ctypes.c_uint16 * 76), + ('minPsmCount', ctypes.c_uint16 * 76), + ('maxPsmCount', ctypes.c_uint16 * 76), + ('avgPsmVoltage', ctypes.c_float * 76), + ('minPsmVoltage', ctypes.c_float * 76), + ('maxPsmVoltage', ctypes.c_float * 76), +] + +AvfsDebugTable_t = struct_c__SA_AvfsDebugTable_t +class struct_c__SA_AvfsDebugTableExternal_t(Structure): + pass + +struct_c__SA_AvfsDebugTableExternal_t._pack_ = 1 # source:False +struct_c__SA_AvfsDebugTableExternal_t._fields_ = [ + ('AvfsDebugTable', AvfsDebugTable_t), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +AvfsDebugTableExternal_t = struct_c__SA_AvfsDebugTableExternal_t +class struct_c__SA_DpmActivityMonitorCoeffInt_t(Structure): + pass + +struct_c__SA_DpmActivityMonitorCoeffInt_t._pack_ = 1 # source:False +struct_c__SA_DpmActivityMonitorCoeffInt_t._fields_ = [ + ('Gfx_ActiveHystLimit', ctypes.c_ubyte), + ('Gfx_IdleHystLimit', ctypes.c_ubyte), + ('Gfx_FPS', ctypes.c_ubyte), + ('Gfx_MinActiveFreqType', ctypes.c_ubyte), + ('Gfx_BoosterFreqType', ctypes.c_ubyte), + ('PaddingGfx', ctypes.c_ubyte), + ('Gfx_MinActiveFreq', ctypes.c_uint16), + ('Gfx_BoosterFreq', ctypes.c_uint16), + ('Gfx_PD_Data_time_constant', ctypes.c_uint16), + ('Gfx_PD_Data_limit_a', ctypes.c_uint32), + ('Gfx_PD_Data_limit_b', ctypes.c_uint32), + ('Gfx_PD_Data_limit_c', ctypes.c_uint32), + ('Gfx_PD_Data_error_coeff', ctypes.c_uint32), + ('Gfx_PD_Data_error_rate_coeff', ctypes.c_uint32), + ('Fclk_ActiveHystLimit', ctypes.c_ubyte), + ('Fclk_IdleHystLimit', ctypes.c_ubyte), + ('Fclk_FPS', ctypes.c_ubyte), + ('Fclk_MinActiveFreqType', ctypes.c_ubyte), + ('Fclk_BoosterFreqType', ctypes.c_ubyte), + ('PaddingFclk', ctypes.c_ubyte), + ('Fclk_MinActiveFreq', ctypes.c_uint16), + ('Fclk_BoosterFreq', ctypes.c_uint16), + ('Fclk_PD_Data_time_constant', ctypes.c_uint16), + ('Fclk_PD_Data_limit_a', ctypes.c_uint32), + ('Fclk_PD_Data_limit_b', ctypes.c_uint32), + ('Fclk_PD_Data_limit_c', ctypes.c_uint32), + ('Fclk_PD_Data_error_coeff', ctypes.c_uint32), + ('Fclk_PD_Data_error_rate_coeff', ctypes.c_uint32), + ('Mem_UpThreshold_Limit', ctypes.c_uint32 * 6), + ('Mem_UpHystLimit', ctypes.c_ubyte * 6), + ('Mem_DownHystLimit', ctypes.c_uint16 * 6), + ('Mem_Fps', ctypes.c_uint16), +] + +DpmActivityMonitorCoeffInt_t = struct_c__SA_DpmActivityMonitorCoeffInt_t +class struct_c__SA_DpmActivityMonitorCoeffIntExternal_t(Structure): + pass + +struct_c__SA_DpmActivityMonitorCoeffIntExternal_t._pack_ = 1 # source:False +struct_c__SA_DpmActivityMonitorCoeffIntExternal_t._fields_ = [ + ('DpmActivityMonitorCoeffInt', DpmActivityMonitorCoeffInt_t), + ('MmHubPadding', ctypes.c_uint32 * 8), +] + +DpmActivityMonitorCoeffIntExternal_t = struct_c__SA_DpmActivityMonitorCoeffIntExternal_t +__AMDGPU_SMU_H__ = True # macro +int32_t = True # macro +uint32_t = True # macro +int8_t = True # macro +uint8_t = True # macro +uint16_t = True # macro +int16_t = True # macro +uint64_t = True # macro +bool = True # macro +u32 = True # macro +SMU_THERMAL_MINIMUM_ALERT_TEMP = 0 # macro +SMU_THERMAL_MAXIMUM_ALERT_TEMP = 255 # macro +SMU_TEMPERATURE_UNITS_PER_CENTIGRADES = 1000 # macro +SMU_FW_NAME_LEN = 0x24 # macro +SMU_DPM_USER_PROFILE_RESTORE = (1<<0) # macro +SMU_CUSTOM_FAN_SPEED_RPM = (1<<1) # macro +SMU_CUSTOM_FAN_SPEED_PWM = (1<<2) # macro +SMU_THROTTLER_PPT0_BIT = 0 # macro +SMU_THROTTLER_PPT1_BIT = 1 # macro +SMU_THROTTLER_PPT2_BIT = 2 # macro +SMU_THROTTLER_PPT3_BIT = 3 # macro +SMU_THROTTLER_SPL_BIT = 4 # macro +SMU_THROTTLER_FPPT_BIT = 5 # macro +SMU_THROTTLER_SPPT_BIT = 6 # macro +SMU_THROTTLER_SPPT_APU_BIT = 7 # macro +SMU_THROTTLER_TDC_GFX_BIT = 16 # macro +SMU_THROTTLER_TDC_SOC_BIT = 17 # macro +SMU_THROTTLER_TDC_MEM_BIT = 18 # macro +SMU_THROTTLER_TDC_VDD_BIT = 19 # macro +SMU_THROTTLER_TDC_CVIP_BIT = 20 # macro +SMU_THROTTLER_EDC_CPU_BIT = 21 # macro +SMU_THROTTLER_EDC_GFX_BIT = 22 # macro +SMU_THROTTLER_APCC_BIT = 23 # macro +SMU_THROTTLER_TEMP_GPU_BIT = 32 # macro +SMU_THROTTLER_TEMP_CORE_BIT = 33 # macro +SMU_THROTTLER_TEMP_MEM_BIT = 34 # macro +SMU_THROTTLER_TEMP_EDGE_BIT = 35 # macro +SMU_THROTTLER_TEMP_HOTSPOT_BIT = 36 # macro +SMU_THROTTLER_TEMP_SOC_BIT = 37 # macro +SMU_THROTTLER_TEMP_VR_GFX_BIT = 38 # macro +SMU_THROTTLER_TEMP_VR_SOC_BIT = 39 # macro +SMU_THROTTLER_TEMP_VR_MEM0_BIT = 40 # macro +SMU_THROTTLER_TEMP_VR_MEM1_BIT = 41 # macro +SMU_THROTTLER_TEMP_LIQUID0_BIT = 42 # macro +SMU_THROTTLER_TEMP_LIQUID1_BIT = 43 # macro +SMU_THROTTLER_VRHOT0_BIT = 44 # macro +SMU_THROTTLER_VRHOT1_BIT = 45 # macro +SMU_THROTTLER_PROCHOT_CPU_BIT = 46 # macro +SMU_THROTTLER_PROCHOT_GFX_BIT = 47 # macro +SMU_THROTTLER_PPM_BIT = 56 # macro +SMU_THROTTLER_FIT_BIT = 57 # macro +# def SMU_TABLE_INIT(tables, table_id, s, a, d): # macro +# return {tables[table_id].size=s;tables[table_id].align=a;tables[table_id].domain=d;}(0) +class struct_smu_hw_power_state(Structure): + pass + +struct_smu_hw_power_state._pack_ = 1 # source:False +struct_smu_hw_power_state._fields_ = [ + ('magic', ctypes.c_uint32), +] + +class struct_smu_power_state(Structure): + pass + + +# values for enumeration 'smu_state_ui_label' +smu_state_ui_label__enumvalues = { + 0: 'SMU_STATE_UI_LABEL_NONE', + 1: 'SMU_STATE_UI_LABEL_BATTERY', + 2: 'SMU_STATE_UI_TABEL_MIDDLE_LOW', + 3: 'SMU_STATE_UI_LABEL_BALLANCED', + 4: 'SMU_STATE_UI_LABEL_MIDDLE_HIGHT', + 5: 'SMU_STATE_UI_LABEL_PERFORMANCE', + 6: 'SMU_STATE_UI_LABEL_BACO', +} +SMU_STATE_UI_LABEL_NONE = 0 +SMU_STATE_UI_LABEL_BATTERY = 1 +SMU_STATE_UI_TABEL_MIDDLE_LOW = 2 +SMU_STATE_UI_LABEL_BALLANCED = 3 +SMU_STATE_UI_LABEL_MIDDLE_HIGHT = 4 +SMU_STATE_UI_LABEL_PERFORMANCE = 5 +SMU_STATE_UI_LABEL_BACO = 6 +smu_state_ui_label = ctypes.c_uint32 # enum + +# values for enumeration 'smu_state_classification_flag' +smu_state_classification_flag__enumvalues = { + 1: 'SMU_STATE_CLASSIFICATION_FLAG_BOOT', + 2: 'SMU_STATE_CLASSIFICATION_FLAG_THERMAL', + 4: 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE', + 8: 'SMU_STATE_CLASSIFICATION_FLAG_RESET', + 16: 'SMU_STATE_CLASSIFICATION_FLAG_FORCED', + 32: 'SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE', + 64: 'SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE', + 128: 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE', + 256: 'SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE', + 512: 'SMU_STATE_CLASSIFICATION_FLAG_UVD', + 1024: 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW', + 2048: 'SMU_STATE_CLASSIFICATION_FLAG_ACPI', + 4096: 'SMU_STATE_CLASSIFICATION_FLAG_HD2', + 8192: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_HD', + 16384: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_SD', + 32768: 'SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE', + 65536: 'SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE', + 131072: 'SMU_STATE_CLASSIFICATION_FLAG_BACO', + 262144: 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2', + 524288: 'SMU_STATE_CLASSIFICATION_FLAG_ULV', + 1048576: 'SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC', +} +SMU_STATE_CLASSIFICATION_FLAG_BOOT = 1 +SMU_STATE_CLASSIFICATION_FLAG_THERMAL = 2 +SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE = 4 +SMU_STATE_CLASSIFICATION_FLAG_RESET = 8 +SMU_STATE_CLASSIFICATION_FLAG_FORCED = 16 +SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE = 32 +SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE = 64 +SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE = 128 +SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE = 256 +SMU_STATE_CLASSIFICATION_FLAG_UVD = 512 +SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW = 1024 +SMU_STATE_CLASSIFICATION_FLAG_ACPI = 2048 +SMU_STATE_CLASSIFICATION_FLAG_HD2 = 4096 +SMU_STATE_CLASSIFICATION_FLAG_UVD_HD = 8192 +SMU_STATE_CLASSIFICATION_FLAG_UVD_SD = 16384 +SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE = 32768 +SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE = 65536 +SMU_STATE_CLASSIFICATION_FLAG_BACO = 131072 +SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2 = 262144 +SMU_STATE_CLASSIFICATION_FLAG_ULV = 524288 +SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC = 1048576 +smu_state_classification_flag = ctypes.c_uint32 # enum +class struct_smu_state_classification_block(Structure): + pass + +struct_smu_state_classification_block._pack_ = 1 # source:False +struct_smu_state_classification_block._fields_ = [ + ('ui_label', smu_state_ui_label), + ('flags', smu_state_classification_flag), + ('bios_index', ctypes.c_int32), + ('temporary_state', ctypes.c_bool), + ('to_be_deleted', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 2), +] + +class struct_smu_state_pcie_block(Structure): + pass + +struct_smu_state_pcie_block._pack_ = 1 # source:False +struct_smu_state_pcie_block._fields_ = [ + ('lanes', ctypes.c_uint32), +] + + +# values for enumeration 'smu_refreshrate_source' +smu_refreshrate_source__enumvalues = { + 0: 'SMU_REFRESHRATE_SOURCE_EDID', + 1: 'SMU_REFRESHRATE_SOURCE_EXPLICIT', +} +SMU_REFRESHRATE_SOURCE_EDID = 0 +SMU_REFRESHRATE_SOURCE_EXPLICIT = 1 +smu_refreshrate_source = ctypes.c_uint32 # enum +class struct_smu_state_display_block(Structure): + pass + +struct_smu_state_display_block._pack_ = 1 # source:False +struct_smu_state_display_block._fields_ = [ + ('disable_frame_modulation', ctypes.c_bool), + ('limit_refreshrate', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 2), + ('refreshrate_source', smu_refreshrate_source), + ('explicit_refreshrate', ctypes.c_int32), + ('edid_refreshrate_index', ctypes.c_int32), + ('enable_vari_bright', ctypes.c_bool), + ('PADDING_1', ctypes.c_ubyte * 3), +] + +class struct_smu_state_memory_block(Structure): + pass + +struct_smu_state_memory_block._pack_ = 1 # source:False +struct_smu_state_memory_block._fields_ = [ + ('dll_off', ctypes.c_bool), + ('m3arb', ctypes.c_ubyte), + ('unused', ctypes.c_ubyte * 3), +] + +class struct_smu_state_software_algorithm_block(Structure): + pass + +struct_smu_state_software_algorithm_block._pack_ = 1 # source:False +struct_smu_state_software_algorithm_block._fields_ = [ + ('disable_load_balancing', ctypes.c_bool), + ('enable_sleep_for_timestamps', ctypes.c_bool), +] + +class struct_smu_temperature_range(Structure): + pass + +struct_smu_temperature_range._pack_ = 1 # source:False +struct_smu_temperature_range._fields_ = [ + ('min', ctypes.c_int32), + ('max', ctypes.c_int32), + ('edge_emergency_max', ctypes.c_int32), + ('hotspot_min', ctypes.c_int32), + ('hotspot_crit_max', ctypes.c_int32), + ('hotspot_emergency_max', ctypes.c_int32), + ('mem_min', ctypes.c_int32), + ('mem_crit_max', ctypes.c_int32), + ('mem_emergency_max', ctypes.c_int32), + ('software_shutdown_temp', ctypes.c_int32), + ('software_shutdown_temp_offset', ctypes.c_int32), +] + +class struct_smu_state_validation_block(Structure): + pass + +struct_smu_state_validation_block._pack_ = 1 # source:False +struct_smu_state_validation_block._fields_ = [ + ('single_display_only', ctypes.c_bool), + ('disallow_on_dc', ctypes.c_bool), + ('supported_power_levels', ctypes.c_ubyte), +] + +class struct_smu_uvd_clocks(Structure): + pass + +struct_smu_uvd_clocks._pack_ = 1 # source:False +struct_smu_uvd_clocks._fields_ = [ + ('vclk', ctypes.c_uint32), + ('dclk', ctypes.c_uint32), +] + + +# values for enumeration 'smu_power_src_type' +smu_power_src_type__enumvalues = { + 0: 'SMU_POWER_SOURCE_AC', + 1: 'SMU_POWER_SOURCE_DC', + 2: 'SMU_POWER_SOURCE_COUNT', +} +SMU_POWER_SOURCE_AC = 0 +SMU_POWER_SOURCE_DC = 1 +SMU_POWER_SOURCE_COUNT = 2 +smu_power_src_type = ctypes.c_uint32 # enum + +# values for enumeration 'smu_ppt_limit_type' +smu_ppt_limit_type__enumvalues = { + 0: 'SMU_DEFAULT_PPT_LIMIT', + 1: 'SMU_FAST_PPT_LIMIT', +} +SMU_DEFAULT_PPT_LIMIT = 0 +SMU_FAST_PPT_LIMIT = 1 +smu_ppt_limit_type = ctypes.c_uint32 # enum + +# values for enumeration 'smu_ppt_limit_level' +smu_ppt_limit_level__enumvalues = { + -1: 'SMU_PPT_LIMIT_MIN', + 0: 'SMU_PPT_LIMIT_CURRENT', + 1: 'SMU_PPT_LIMIT_DEFAULT', + 2: 'SMU_PPT_LIMIT_MAX', +} +SMU_PPT_LIMIT_MIN = -1 +SMU_PPT_LIMIT_CURRENT = 0 +SMU_PPT_LIMIT_DEFAULT = 1 +SMU_PPT_LIMIT_MAX = 2 +smu_ppt_limit_level = ctypes.c_int32 # enum + +# values for enumeration 'smu_memory_pool_size' +smu_memory_pool_size__enumvalues = { + 0: 'SMU_MEMORY_POOL_SIZE_ZERO', + 268435456: 'SMU_MEMORY_POOL_SIZE_256_MB', + 536870912: 'SMU_MEMORY_POOL_SIZE_512_MB', + 1073741824: 'SMU_MEMORY_POOL_SIZE_1_GB', + 2147483648: 'SMU_MEMORY_POOL_SIZE_2_GB', +} +SMU_MEMORY_POOL_SIZE_ZERO = 0 +SMU_MEMORY_POOL_SIZE_256_MB = 268435456 +SMU_MEMORY_POOL_SIZE_512_MB = 536870912 +SMU_MEMORY_POOL_SIZE_1_GB = 1073741824 +SMU_MEMORY_POOL_SIZE_2_GB = 2147483648 +smu_memory_pool_size = ctypes.c_uint32 # enum + +# values for enumeration 'smu_clk_type' +smu_clk_type__enumvalues = { + 0: 'SMU_GFXCLK', + 1: 'SMU_VCLK', + 2: 'SMU_DCLK', + 3: 'SMU_VCLK1', + 4: 'SMU_DCLK1', + 5: 'SMU_ECLK', + 6: 'SMU_SOCCLK', + 7: 'SMU_UCLK', + 8: 'SMU_DCEFCLK', + 9: 'SMU_DISPCLK', + 10: 'SMU_PIXCLK', + 11: 'SMU_PHYCLK', + 12: 'SMU_FCLK', + 13: 'SMU_SCLK', + 14: 'SMU_MCLK', + 15: 'SMU_PCIE', + 16: 'SMU_LCLK', + 17: 'SMU_OD_CCLK', + 18: 'SMU_OD_SCLK', + 19: 'SMU_OD_MCLK', + 20: 'SMU_OD_VDDC_CURVE', + 21: 'SMU_OD_RANGE', + 22: 'SMU_OD_VDDGFX_OFFSET', + 23: 'SMU_OD_FAN_CURVE', + 24: 'SMU_OD_ACOUSTIC_LIMIT', + 25: 'SMU_OD_ACOUSTIC_TARGET', + 26: 'SMU_OD_FAN_TARGET_TEMPERATURE', + 27: 'SMU_OD_FAN_MINIMUM_PWM', + 28: 'SMU_CLK_COUNT', +} +SMU_GFXCLK = 0 +SMU_VCLK = 1 +SMU_DCLK = 2 +SMU_VCLK1 = 3 +SMU_DCLK1 = 4 +SMU_ECLK = 5 +SMU_SOCCLK = 6 +SMU_UCLK = 7 +SMU_DCEFCLK = 8 +SMU_DISPCLK = 9 +SMU_PIXCLK = 10 +SMU_PHYCLK = 11 +SMU_FCLK = 12 +SMU_SCLK = 13 +SMU_MCLK = 14 +SMU_PCIE = 15 +SMU_LCLK = 16 +SMU_OD_CCLK = 17 +SMU_OD_SCLK = 18 +SMU_OD_MCLK = 19 +SMU_OD_VDDC_CURVE = 20 +SMU_OD_RANGE = 21 +SMU_OD_VDDGFX_OFFSET = 22 +SMU_OD_FAN_CURVE = 23 +SMU_OD_ACOUSTIC_LIMIT = 24 +SMU_OD_ACOUSTIC_TARGET = 25 +SMU_OD_FAN_TARGET_TEMPERATURE = 26 +SMU_OD_FAN_MINIMUM_PWM = 27 +SMU_CLK_COUNT = 28 +smu_clk_type = ctypes.c_uint32 # enum +class struct_smu_user_dpm_profile(Structure): + pass + +struct_smu_user_dpm_profile._pack_ = 1 # source:False +struct_smu_user_dpm_profile._fields_ = [ + ('fan_mode', ctypes.c_uint32), + ('power_limit', ctypes.c_uint32), + ('fan_speed_pwm', ctypes.c_uint32), + ('fan_speed_rpm', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('user_od', ctypes.c_uint32), + ('clk_mask', ctypes.c_uint32 * 28), + ('clk_dependency', ctypes.c_uint32), +] + +class struct_smu_table(Structure): + pass + +class struct_amdgpu_bo(Structure): + pass + +struct_smu_table._pack_ = 1 # source:False +struct_smu_table._fields_ = [ + ('size', ctypes.c_uint64), + ('align', ctypes.c_uint32), + ('domain', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 3), + ('mc_address', ctypes.c_uint64), + ('cpu_addr', ctypes.POINTER(None)), + ('bo', ctypes.POINTER(struct_amdgpu_bo)), + ('version', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + + +# values for enumeration 'smu_perf_level_designation' +smu_perf_level_designation__enumvalues = { + 0: 'PERF_LEVEL_ACTIVITY', + 1: 'PERF_LEVEL_POWER_CONTAINMENT', +} +PERF_LEVEL_ACTIVITY = 0 +PERF_LEVEL_POWER_CONTAINMENT = 1 +smu_perf_level_designation = ctypes.c_uint32 # enum +class struct_smu_performance_level(Structure): + pass + +struct_smu_performance_level._pack_ = 1 # source:False +struct_smu_performance_level._fields_ = [ + ('core_clock', ctypes.c_uint32), + ('memory_clock', ctypes.c_uint32), + ('vddc', ctypes.c_uint32), + ('vddci', ctypes.c_uint32), + ('non_local_mem_freq', ctypes.c_uint32), + ('non_local_mem_width', ctypes.c_uint32), +] + +class struct_smu_clock_info(Structure): + pass + +struct_smu_clock_info._pack_ = 1 # source:False +struct_smu_clock_info._fields_ = [ + ('min_mem_clk', ctypes.c_uint32), + ('max_mem_clk', ctypes.c_uint32), + ('min_eng_clk', ctypes.c_uint32), + ('max_eng_clk', ctypes.c_uint32), + ('min_bus_bandwidth', ctypes.c_uint32), + ('max_bus_bandwidth', ctypes.c_uint32), +] + +class struct_smu_bios_boot_up_values(Structure): + pass + +struct_smu_bios_boot_up_values._pack_ = 1 # source:False +struct_smu_bios_boot_up_values._fields_ = [ + ('revision', ctypes.c_uint32), + ('gfxclk', ctypes.c_uint32), + ('uclk', ctypes.c_uint32), + ('socclk', ctypes.c_uint32), + ('dcefclk', ctypes.c_uint32), + ('eclk', ctypes.c_uint32), + ('vclk', ctypes.c_uint32), + ('dclk', ctypes.c_uint32), + ('vddc', ctypes.c_uint16), + ('vddci', ctypes.c_uint16), + ('mvddc', ctypes.c_uint16), + ('vdd_gfx', ctypes.c_uint16), + ('cooling_id', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 3), + ('pp_table_id', ctypes.c_uint32), + ('format_revision', ctypes.c_uint32), + ('content_revision', ctypes.c_uint32), + ('fclk', ctypes.c_uint32), + ('lclk', ctypes.c_uint32), + ('firmware_caps', ctypes.c_uint32), +] + + +# values for enumeration 'smu_table_id' +smu_table_id__enumvalues = { + 0: 'SMU_TABLE_PPTABLE', + 1: 'SMU_TABLE_WATERMARKS', + 2: 'SMU_TABLE_CUSTOM_DPM', + 3: 'SMU_TABLE_DPMCLOCKS', + 4: 'SMU_TABLE_AVFS', + 5: 'SMU_TABLE_AVFS_PSM_DEBUG', + 6: 'SMU_TABLE_AVFS_FUSE_OVERRIDE', + 7: 'SMU_TABLE_PMSTATUSLOG', + 8: 'SMU_TABLE_SMU_METRICS', + 9: 'SMU_TABLE_DRIVER_SMU_CONFIG', + 10: 'SMU_TABLE_ACTIVITY_MONITOR_COEFF', + 11: 'SMU_TABLE_OVERDRIVE', + 12: 'SMU_TABLE_I2C_COMMANDS', + 13: 'SMU_TABLE_PACE', + 14: 'SMU_TABLE_ECCINFO', + 15: 'SMU_TABLE_COMBO_PPTABLE', + 16: 'SMU_TABLE_WIFIBAND', + 17: 'SMU_TABLE_COUNT', +} +SMU_TABLE_PPTABLE = 0 +SMU_TABLE_WATERMARKS = 1 +SMU_TABLE_CUSTOM_DPM = 2 +SMU_TABLE_DPMCLOCKS = 3 +SMU_TABLE_AVFS = 4 +SMU_TABLE_AVFS_PSM_DEBUG = 5 +SMU_TABLE_AVFS_FUSE_OVERRIDE = 6 +SMU_TABLE_PMSTATUSLOG = 7 +SMU_TABLE_SMU_METRICS = 8 +SMU_TABLE_DRIVER_SMU_CONFIG = 9 +SMU_TABLE_ACTIVITY_MONITOR_COEFF = 10 +SMU_TABLE_OVERDRIVE = 11 +SMU_TABLE_I2C_COMMANDS = 12 +SMU_TABLE_PACE = 13 +SMU_TABLE_ECCINFO = 14 +SMU_TABLE_COMBO_PPTABLE = 15 +SMU_TABLE_WIFIBAND = 16 +SMU_TABLE_COUNT = 17 +smu_table_id = ctypes.c_uint32 # enum +__all__ = \ + ['ALLOWED_FEATURE_CTRL_DEFAULT', 'ALLOWED_FEATURE_CTRL_SCPM', + 'AVFS_D_COUNT', 'AVFS_D_G', 'AVFS_D_e', 'AVFS_D_e__enumvalues', + 'AVFS_TEMP_COLD', 'AVFS_TEMP_COUNT', 'AVFS_TEMP_HOT', + 'AVFS_TEMP_e', 'AVFS_TEMP_e__enumvalues', 'AVFS_VOLTAGE_COUNT', + 'AVFS_VOLTAGE_GFX', 'AVFS_VOLTAGE_SOC', 'AVFS_VOLTAGE_TYPE_e', + 'AVFS_VOLTAGE_TYPE_e__enumvalues', 'AvfsDcBtcParams_t', + 'AvfsDebugTableExternal_t', 'AvfsDebugTable_t', + 'AvfsFuseOverride_t', 'BACO_SEQUENCE', 'BAMACO_SEQUENCE', + 'BOARD_GPIO_DC_GENLK_CLK', 'BOARD_GPIO_DC_GENLK_VSYNC', + 'BOARD_GPIO_DC_GEN_A', 'BOARD_GPIO_DC_GEN_B', + 'BOARD_GPIO_DC_GEN_C', 'BOARD_GPIO_DC_GEN_D', + 'BOARD_GPIO_DC_GEN_E', 'BOARD_GPIO_DC_GEN_F', + 'BOARD_GPIO_DC_GEN_G', 'BOARD_GPIO_DC_SWAPLOCK_A', + 'BOARD_GPIO_DC_SWAPLOCK_B', 'BOARD_GPIO_LV_EN', + 'BOARD_GPIO_SMUIO_0', 'BOARD_GPIO_SMUIO_1', 'BOARD_GPIO_SMUIO_10', + 'BOARD_GPIO_SMUIO_11', 'BOARD_GPIO_SMUIO_12', + 'BOARD_GPIO_SMUIO_13', 'BOARD_GPIO_SMUIO_14', + 'BOARD_GPIO_SMUIO_15', 'BOARD_GPIO_SMUIO_16', + 'BOARD_GPIO_SMUIO_17', 'BOARD_GPIO_SMUIO_18', + 'BOARD_GPIO_SMUIO_19', 'BOARD_GPIO_SMUIO_2', + 'BOARD_GPIO_SMUIO_20', 'BOARD_GPIO_SMUIO_21', + 'BOARD_GPIO_SMUIO_22', 'BOARD_GPIO_SMUIO_23', + 'BOARD_GPIO_SMUIO_24', 'BOARD_GPIO_SMUIO_25', + 'BOARD_GPIO_SMUIO_26', 'BOARD_GPIO_SMUIO_27', + 'BOARD_GPIO_SMUIO_28', 'BOARD_GPIO_SMUIO_29', + 'BOARD_GPIO_SMUIO_3', 'BOARD_GPIO_SMUIO_30', + 'BOARD_GPIO_SMUIO_31', 'BOARD_GPIO_SMUIO_4', 'BOARD_GPIO_SMUIO_5', + 'BOARD_GPIO_SMUIO_6', 'BOARD_GPIO_SMUIO_7', 'BOARD_GPIO_SMUIO_8', + 'BOARD_GPIO_SMUIO_9', 'BOARD_GPIO_TYPE_e', + 'BOARD_GPIO_TYPE_e__enumvalues', 'BoardTable_t', 'BootValues_t', + 'CMDCONFIG_READWRITE_BIT', 'CMDCONFIG_READWRITE_MASK', + 'CMDCONFIG_RESTART_BIT', 'CMDCONFIG_RESTART_MASK', + 'CMDCONFIG_STOP_BIT', 'CMDCONFIG_STOP_MASK', + 'CUSTOMER_VARIANT_COUNT', 'CUSTOMER_VARIANT_FALCON', + 'CUSTOMER_VARIANT_ROW', 'CUSTOMER_VARIANT_e', + 'CUSTOMER_VARIANT_e__enumvalues', 'CustomSkuTable_t', + 'D3HOTSequence_e', 'D3HOTSequence_e__enumvalues', + 'D3HOT_SEQUENCE_COUNT', 'DCS_ARCH_ASYNC', 'DCS_ARCH_DISABLED', + 'DCS_ARCH_FADCS', 'DCS_ARCH_e', 'DCS_ARCH_e__enumvalues', + 'DEBUG_OVERRIDE_DFLL_BTC_FCW_LOG', + 'DEBUG_OVERRIDE_DFLL_MASTER_MODE', + 'DEBUG_OVERRIDE_DISABLE_D0i2_REENTRY_HSR_TIMER_CHECK', + 'DEBUG_OVERRIDE_DISABLE_DFLL', + 'DEBUG_OVERRIDE_DISABLE_FAST_FCLK_TIMER', + 'DEBUG_OVERRIDE_DISABLE_FMAX_VMAX', + 'DEBUG_OVERRIDE_DISABLE_IMU_FW_CHECKS', + 'DEBUG_OVERRIDE_DISABLE_MEMORY_VOLTAGE_SCALING', + 'DEBUG_OVERRIDE_DISABLE_VCN_PG', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_DCN_FCLK', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_MP0_FCLK', + 'DEBUG_OVERRIDE_DISABLE_VOLT_LINK_VCN_DCFCLK', + 'DEBUG_OVERRIDE_ENABLE_PER_WGP_RESIENCY', + 'DEBUG_OVERRIDE_ENABLE_PROFILING_MODE', + 'DEBUG_OVERRIDE_ENABLE_RLC_VF_BRINGUP_MODE', + 'DEBUG_OVERRIDE_ENABLE_SOC_VF_BRINGUP_MODE', + 'DEBUG_OVERRIDE_NOT_USE', 'DRAM_BIT_WIDTH_COUNT', + 'DRAM_BIT_WIDTH_DISABLED', 'DRAM_BIT_WIDTH_TYPE_e', + 'DRAM_BIT_WIDTH_TYPE_e__enumvalues', 'DRAM_BIT_WIDTH_X_128', + 'DRAM_BIT_WIDTH_X_16', 'DRAM_BIT_WIDTH_X_32', + 'DRAM_BIT_WIDTH_X_64', 'DRAM_BIT_WIDTH_X_8', + 'DpmActivityMonitorCoeffIntExternal_t', + 'DpmActivityMonitorCoeffInt_t', 'DpmDescriptor_t', + 'DriverInfoTable_t', 'DriverReportedClocks_t', + 'DriverSmuConfigExternal_t', 'DriverSmuConfig_t', 'DroopInt_t', + 'ENABLE_DEBUG_FEATURES', 'EPCS_HIGH_POWER', + 'EPCS_HIGH_POWER_LIMIT', 'EPCS_LOW_POWER', 'EPCS_LOW_POWER_LIMIT', + 'EPCS_NORMAL_POWER', 'EPCS_NORMAL_POWER_LIMIT', + 'EPCS_NOT_CONFIGURED', 'EPCS_NO_BOOTUP', 'EPCS_SHORTED_LIMIT', + 'EPCS_SHORTED_POWER', 'EPCS_STATUS_COUNT', 'EPCS_STATUS_e', + 'EPCS_STATUS_e__enumvalues', 'EccInfoTable_t', 'EccInfo_t', + 'FAN_MODE_AUTO', 'FAN_MODE_MANUAL_LINEAR', 'FEATURE_ACDC_BIT', + 'FEATURE_APT_ALL_ENABLE_BIT', 'FEATURE_APT_PF_DCS_BIT', + 'FEATURE_APT_SQ_THROTTLE_BIT', 'FEATURE_ATHUB_MMHUB_PG_BIT', + 'FEATURE_ATHUB_PG_BIT', 'FEATURE_BACO_BIT', 'FEATURE_BACO_CG_BIT', + 'FEATURE_BACO_MPCLK_DS_BIT', 'FEATURE_BOOT_POWER_OPT_BIT', + 'FEATURE_BOOT_TIME_CAL_BIT', 'FEATURE_BTC_COUNT', + 'FEATURE_BTC_NOP', 'FEATURE_BTC_RESTORE', 'FEATURE_BTC_SAVE', + 'FEATURE_BTC_e', 'FEATURE_BTC_e__enumvalues', 'FEATURE_CC6_BIT', + 'FEATURE_CCLK_DPM_BIT', 'FEATURE_CLOCK_POWER_DOWN_BYPASS_BIT', + 'FEATURE_CLOCK_STRETCH_COMPENSATOR', 'FEATURE_CORE_DLDO_BIT', + 'FEATURE_CPPC_BIT', 'FEATURE_CPPC_PREFERRED_CORES', + 'FEATURE_CPUOFF_BIT', 'FEATURE_DATA_CALCULATION_BIT', + 'FEATURE_DCFCLK_DPM_BIT', 'FEATURE_DF_CSTATES_BIT', + 'FEATURE_DF_CSTATE_BIT', 'FEATURE_DF_LIGHT_CSTATE', + 'FEATURE_DPM_DCN_BIT', 'FEATURE_DPM_FCLK_BIT', + 'FEATURE_DPM_GFXCLK_BIT', 'FEATURE_DPM_GFX_POWER_OPTIMIZER_BIT', + 'FEATURE_DPM_LINK_BIT', 'FEATURE_DPM_SOCCLK_BIT', + 'FEATURE_DPM_UCLK_BIT', 'FEATURE_DS_DCFCLK_BIT', + 'FEATURE_DS_FCLK_BIT', 'FEATURE_DS_GFXCLK_BIT', + 'FEATURE_DS_HSPCLK_BIT', 'FEATURE_DS_IPUCLK_BIT', + 'FEATURE_DS_ISPCLK_BIT', 'FEATURE_DS_LCLK_BIT', + 'FEATURE_DS_MP1CLK_BIT', 'FEATURE_DS_MPIO_BIT', + 'FEATURE_DS_MPM_BIT', 'FEATURE_DS_SHUBCLK_BIT', + 'FEATURE_DS_SMNCLK_BIT', 'FEATURE_DS_SOCCLK_BIT', + 'FEATURE_DS_UCLK_BIT', 'FEATURE_DS_UMCCLK_BIT', + 'FEATURE_DS_VCN_BIT', 'FEATURE_DS_VPECLK_BIT', 'FEATURE_DVO_BIT', + 'FEATURE_EDC_BIT', 'FEATURE_EDC_PWRBRK_BIT', + 'FEATURE_FAN_ABNORMAL_BIT', 'FEATURE_FAN_CONTROLLER_BIT', + 'FEATURE_FAN_CONTROL_BIT', 'FEATURE_FAST_PSTATE_CLDO_BIT', + 'FEATURE_FCLK_DPM_BIT', 'FEATURE_FIT_BIT', 'FEATURE_FW_CTF_BIT', + 'FEATURE_FW_DATA_READ_BIT', 'FEATURE_FW_DSTATE_BIT', + 'FEATURE_GFXCLK_SPREAD_SPECTRUM_BIT', 'FEATURE_GFXOFF_BIT', + 'FEATURE_GFX_DCS_BIT', 'FEATURE_GFX_DEM_BIT', + 'FEATURE_GFX_DIDT_XVMIN_BIT', 'FEATURE_GFX_DPM_BIT', + 'FEATURE_GFX_EDC_BIT', 'FEATURE_GFX_EDC_XVMIN_BIT', + 'FEATURE_GFX_IMU_BIT', 'FEATURE_GFX_PCC_DFLL_BIT', + 'FEATURE_GFX_PSM_DIDT_BIT', 'FEATURE_GFX_READ_MARGIN_BIT', + 'FEATURE_GFX_ULV_BIT', 'FEATURE_GTHR_BIT', + 'FEATURE_IOMMUL2_PG_BIT', 'FEATURE_IPU_DPM_BIT', + 'FEATURE_ISP_DPM_BIT', 'FEATURE_LCLK_DPM_BIT', + 'FEATURE_LED_DISPLAY_BIT', 'FEATURE_LOW_POWER_DCNCLKS_BIT', + 'FEATURE_MEM_TEMP_READ_BIT', 'FEATURE_MM_DPM_BIT', + 'FEATURE_OPTIMIZED_VMIN_BIT', 'FEATURE_OUT_OF_BAND_MONITOR_BIT', + 'FEATURE_P3T_BIT', 'FEATURE_PCC_BIT', 'FEATURE_PERF_LIMIT_BIT', + 'FEATURE_PLL_POWER_DOWN_BIT', 'FEATURE_PPT_BIT', + 'FEATURE_PROCHOT_BIT', 'FEATURE_PSI_BIT', 'FEATURE_PWR_ALL', + 'FEATURE_PWR_BACO', 'FEATURE_PWR_DOMAIN_COUNT', + 'FEATURE_PWR_DOMAIN_e', 'FEATURE_PWR_DOMAIN_e__enumvalues', + 'FEATURE_PWR_GFX', 'FEATURE_PWR_S5', 'FEATURE_PWR_SOC', + 'FEATURE_RESERVED0_BIT', 'FEATURE_RESERVED1_BIT', + 'FEATURE_S0I3_BIT', 'FEATURE_SHUBCLK_DPM_BIT', + 'FEATURE_SMARTSHIFT_BIT', 'FEATURE_SMART_L3_RINSER_BIT', + 'FEATURE_SMU_LOW_POWER_BIT', 'FEATURE_SOCCLK_DPM_BIT', + 'FEATURE_SOC_CG_BIT', 'FEATURE_SOC_EDC_XVMIN_BIT', + 'FEATURE_SOC_MPCLK_DS_BIT', 'FEATURE_SOC_PCC_BIT', + 'FEATURE_SPARE_59_BIT', 'FEATURE_SPARE_60_BIT', + 'FEATURE_SPARE_61_BIT', 'FEATURE_SPARE_62_BIT', + 'FEATURE_SPARE_63_BIT', 'FEATURE_STAPM_BIT', 'FEATURE_TDC_BIT', + 'FEATURE_THERMAL_BIT', 'FEATURE_THROTTLERS_BIT', + 'FEATURE_VCN_DPM_BIT', 'FEATURE_VDDIO_MEM_SCALING_BIT', + 'FEATURE_VDDOFF_BIT', 'FEATURE_VDDOFF_ECO_BIT', + 'FEATURE_VMEMP_SCALING_BIT', 'FEATURE_VPE_DPM_BIT', + 'FEATURE_VR0HOT_BIT', 'FEATURE_WHISPER_MODE_BIT', + 'FEATURE_ZSTATES_BIT', 'FEATURE_ZSTATES_ECO_BIT', + 'FOPT_CALC_AC_CALC_DC', 'FOPT_CALC_AC_PPTABLE_DC', 'FOPT_CALC_e', + 'FOPT_CALC_e__enumvalues', 'FOPT_PPTABLE_AC_CALC_DC', + 'FOPT_PPTABLE_AC_PPTABLE_DC', 'FW_DSTATE_CLDO_PRG_BIT', + 'FW_DSTATE_D0i3_2_QUIET_FW_BIT', 'FW_DSTATE_DF_PLL_PWRDN_BIT', + 'FW_DSTATE_G6_HSR_BIT', 'FW_DSTATE_G6_PHY_VMEMP_OFF_BIT', + 'FW_DSTATE_HSR_NON_STROBE_BIT', 'FW_DSTATE_MALL_ALLOC_BIT', + 'FW_DSTATE_MALL_FLUSH_BIT', 'FW_DSTATE_MEM_PLL_PWRDN_BIT', + 'FW_DSTATE_MEM_PSI_BIT', 'FW_DSTATE_MMHUB_INTERLOCK_BIT', + 'FW_DSTATE_MP0_ENTER_WFI_BIT', 'FW_DSTATE_MP1_WHISPER_MODE_BIT', + 'FW_DSTATE_SMN_DS_BIT', 'FW_DSTATE_SOC_LIV_MIN_BIT', + 'FW_DSTATE_SOC_PLL_PWRDN_BIT', 'FW_DSTATE_SOC_PSI_BIT', + 'FW_DSTATE_SOC_ULV_BIT', 'FanMode_e', 'FanMode_e__enumvalues', + 'FwStatus_t', 'FwStatus_t_v14_0_1', + 'GPIO_INT_POLARITY_ACTIVE_HIGH', 'GPIO_INT_POLARITY_ACTIVE_LOW', + 'GpioIntPolarity_e', 'GpioIntPolarity_e__enumvalues', + 'I2C_CMD_COUNT', 'I2C_CMD_READ', 'I2C_CMD_WRITE', + 'I2C_CONTROLLER_DISABLED', 'I2C_CONTROLLER_ENABLED', + 'I2C_CONTROLLER_NAME_COUNT', 'I2C_CONTROLLER_NAME_FAN_INTAKE', + 'I2C_CONTROLLER_NAME_LIQUID0', 'I2C_CONTROLLER_NAME_LIQUID1', + 'I2C_CONTROLLER_NAME_PLX', 'I2C_CONTROLLER_NAME_VR_GFX', + 'I2C_CONTROLLER_NAME_VR_SOC', 'I2C_CONTROLLER_NAME_VR_VDDIO', + 'I2C_CONTROLLER_NAME_VR_VMEMP', 'I2C_CONTROLLER_PORT_0', + 'I2C_CONTROLLER_PORT_1', 'I2C_CONTROLLER_PORT_COUNT', + 'I2C_CONTROLLER_PROTOCOL_COUNT', + 'I2C_CONTROLLER_PROTOCOL_INA3221', + 'I2C_CONTROLLER_PROTOCOL_TMP_MAX31875', + 'I2C_CONTROLLER_PROTOCOL_TMP_MAX6604', + 'I2C_CONTROLLER_PROTOCOL_VR_IR35217', + 'I2C_CONTROLLER_PROTOCOL_VR_XPDE132G5', + 'I2C_CONTROLLER_THROTTLER_COUNT', + 'I2C_CONTROLLER_THROTTLER_FAN_INTAKE', + 'I2C_CONTROLLER_THROTTLER_INA3221', + 'I2C_CONTROLLER_THROTTLER_LIQUID0', + 'I2C_CONTROLLER_THROTTLER_LIQUID1', + 'I2C_CONTROLLER_THROTTLER_PLX', + 'I2C_CONTROLLER_THROTTLER_TYPE_NONE', + 'I2C_CONTROLLER_THROTTLER_VR_GFX', + 'I2C_CONTROLLER_THROTTLER_VR_SOC', + 'I2C_CONTROLLER_THROTTLER_VR_VDDIO', + 'I2C_CONTROLLER_THROTTLER_VR_VMEMP', 'I2C_PORT_GPIO', + 'I2C_PORT_SVD_SCL', 'I2C_SPEED_COUNT', 'I2C_SPEED_FAST_100K', + 'I2C_SPEED_FAST_400K', 'I2C_SPEED_FAST_50K', + 'I2C_SPEED_FAST_PLUS_1M', 'I2C_SPEED_HIGH_1M', + 'I2C_SPEED_HIGH_2M', 'I2cCmdType_e', 'I2cCmdType_e__enumvalues', + 'I2cControllerConfig_t', 'I2cControllerName_e', + 'I2cControllerName_e__enumvalues', 'I2cControllerPort_e', + 'I2cControllerPort_e__enumvalues', 'I2cControllerProtocol_e', + 'I2cControllerProtocol_e__enumvalues', 'I2cControllerThrottler_e', + 'I2cControllerThrottler_e__enumvalues', 'I2cPort_e', + 'I2cPort_e__enumvalues', 'I2cSpeed_e', 'I2cSpeed_e__enumvalues', + 'IH_INTERRUPT_CONTEXT_ID_AC', 'IH_INTERRUPT_CONTEXT_ID_AUDIO_D0', + 'IH_INTERRUPT_CONTEXT_ID_AUDIO_D3', + 'IH_INTERRUPT_CONTEXT_ID_BACO', 'IH_INTERRUPT_CONTEXT_ID_DC', + 'IH_INTERRUPT_CONTEXT_ID_DYNAMIC_TABLE', + 'IH_INTERRUPT_CONTEXT_ID_FAN_ABNORMAL', + 'IH_INTERRUPT_CONTEXT_ID_FAN_RECOVERY', + 'IH_INTERRUPT_CONTEXT_ID_THERMAL_THROTTLING', + 'IH_INTERRUPT_ID_TO_DRIVER', 'INVALID_BOARD_GPIO', + 'LED_DISPLAY_ERROR_BIT', 'LED_DISPLAY_GFX_DPM_BIT', + 'LED_DISPLAY_PCIE_BIT', 'LinearInt_t', 'MAX_BOARD_DC_GPIO_NUM', + 'MAX_BOARD_GPIO_SMUIO_NUM', 'MAX_SW_I2C_COMMANDS', + 'MEM_TEMP_READ_IN_BAND_DUMMY_PSTATE_BIT', + 'MEM_TEMP_READ_IN_BAND_REFRESH_BIT', + 'MEM_TEMP_READ_OUT_OF_BAND_BIT', 'MEM_VENDOR_COUNT', + 'MEM_VENDOR_ELPIDA', 'MEM_VENDOR_ESMT', 'MEM_VENDOR_ETRON', + 'MEM_VENDOR_HYNIX', 'MEM_VENDOR_INFINEON', 'MEM_VENDOR_MICRON', + 'MEM_VENDOR_MOSEL', 'MEM_VENDOR_NANYA', 'MEM_VENDOR_PLACEHOLDER0', + 'MEM_VENDOR_PLACEHOLDER1', 'MEM_VENDOR_PLACEHOLDER2', + 'MEM_VENDOR_PLACEHOLDER3', 'MEM_VENDOR_PLACEHOLDER4', + 'MEM_VENDOR_PLACEHOLDER5', 'MEM_VENDOR_SAMSUNG', + 'MEM_VENDOR_WINBOND', 'MEM_VENDOR_e', 'MEM_VENDOR_e__enumvalues', + 'MSR_SEQUENCE', 'MsgLimits_t', 'NUM_DCFCLK_DPM_LEVELS', + 'NUM_DCLK_DPM_LEVELS', 'NUM_DISPCLK_DPM_LEVELS', + 'NUM_DPPCLK_DPM_LEVELS', 'NUM_DPREFCLK_DPM_LEVELS', + 'NUM_DTBCLK_DPM_LEVELS', 'NUM_FCLK_DPM_LEVELS', 'NUM_FEATURES', + 'NUM_GFXCLK_DPM_LEVELS', 'NUM_I2C_CONTROLLERS', 'NUM_LINK_LEVELS', + 'NUM_MP0CLK_DPM_LEVELS', 'NUM_OD_FAN_MAX_POINTS', + 'NUM_SOCCLK_DPM_LEVELS', 'NUM_UCLK_DPM_LEVELS', + 'NUM_VCLK_DPM_LEVELS', 'NUM_WM_RANGES', 'OD_FAIL_e', + 'OD_FAIL_e__enumvalues', 'OD_FAN_ACOUSTIC_LIMIT_ERROR', + 'OD_FAN_ACOUSTIC_TARGET_ERROR', 'OD_FAN_CURVE_PWM_ERROR', + 'OD_FAN_CURVE_TEMP_ERROR', 'OD_FAN_MIN_PWM_ERROR', + 'OD_FAN_TARGET_TEMP_ERROR', 'OD_FAN_ZERO_RPM_STOP_TEMP_ERROR', + 'OD_FCLK_ERROR', 'OD_FULL_CTRL_FCLK_ERROR', + 'OD_FULL_CTRL_GFXCLK_ERROR', 'OD_FULL_CTRL_UCLK_ERROR', + 'OD_FULL_CTRL_VDD_GFX_ERROR', 'OD_FULL_CTRL_VDD_SOC_ERROR', + 'OD_GFXCLK_ERROR', 'OD_GFXCLK_VF_CURVE_OFFSET_ERROR', + 'OD_INVALID_FEATURE_COMBO_ERROR', 'OD_NO_ERROR', + 'OD_OP_GFX_EDC_ERROR', 'OD_OP_GFX_PCC_ERROR', 'OD_OP_TEMP_ERROR', + 'OD_POWER_FEATURE_CTRL_ERROR', 'OD_PPT_ERROR', + 'OD_REQUEST_ADVANCED_NOT_SUPPORTED', 'OD_TDC_ERROR', + 'OD_UCLK_ERROR', 'OD_UNSUPPORTED_FEATURE', + 'OD_VDD_GFX_VMAX_ERROR', 'OD_VDD_SOC_VMAX_ERROR', + 'OverDriveLimits_t', 'OverDriveTableExternal_t', + 'OverDriveTable_t', 'PERF_LEVEL_ACTIVITY', + 'PERF_LEVEL_POWER_CONTAINMENT', 'PFE_Settings_t', + 'PG_DYNAMIC_MODE', 'PG_POWER_DOWN', 'PG_POWER_UP', + 'PG_STATIC_MODE', 'PMFW_VOLT_PLANE_COUNT', 'PMFW_VOLT_PLANE_GFX', + 'PMFW_VOLT_PLANE_SOC', 'PMFW_VOLT_PLANE_e', + 'PMFW_VOLT_PLANE_e__enumvalues', 'POWER_SOURCE_AC', + 'POWER_SOURCE_COUNT', 'POWER_SOURCE_DC', 'POWER_SOURCE_e', + 'POWER_SOURCE_e__enumvalues', 'PPCLK_COUNT', 'PPCLK_DCFCLK', + 'PPCLK_DCLK_0', 'PPCLK_DISPCLK', 'PPCLK_DPPCLK', 'PPCLK_DPREFCLK', + 'PPCLK_DTBCLK', 'PPCLK_FCLK', 'PPCLK_GFXCLK', 'PPCLK_SOCCLK', + 'PPCLK_UCLK', 'PPCLK_VCLK_0', 'PPCLK_e', 'PPCLK_e__enumvalues', + 'PPSMC_MSG_AllowGfxDcs', 'PPSMC_MSG_AllowGfxOff', + 'PPSMC_MSG_AllowIHHostInterrupt', 'PPSMC_MSG_ArmD3', + 'PPSMC_MSG_BacoAudioD3PME', 'PPSMC_MSG_DisableAllSmuFeatures', + 'PPSMC_MSG_DisableSmuFeaturesHigh', + 'PPSMC_MSG_DisableSmuFeaturesLow', 'PPSMC_MSG_DisallowGfxDcs', + 'PPSMC_MSG_DisallowGfxOff', 'PPSMC_MSG_DramLogSetDramAddrHigh', + 'PPSMC_MSG_DramLogSetDramAddrLow', 'PPSMC_MSG_DramLogSetDramSize', + 'PPSMC_MSG_DummyUndefined', 'PPSMC_MSG_DumpSTBtoDram', + 'PPSMC_MSG_EnableAllSmuFeatures', + 'PPSMC_MSG_EnableAudioStutterWA', 'PPSMC_MSG_EnableShadowDpm', + 'PPSMC_MSG_EnableSmuFeaturesHigh', + 'PPSMC_MSG_EnableSmuFeaturesLow', 'PPSMC_MSG_EnterBaco', + 'PPSMC_MSG_ExitBaco', 'PPSMC_MSG_ExtPwrConnSupport', + 'PPSMC_MSG_GetAllRunningSmuFeatures', + 'PPSMC_MSG_GetDcModeMaxDpmFreq', 'PPSMC_MSG_GetDpmFreqByIndex', + 'PPSMC_MSG_GetDriverIfVersion', 'PPSMC_MSG_GetMaxDpmFreq', + 'PPSMC_MSG_GetMinDpmFreq', 'PPSMC_MSG_GetPptLimit', + 'PPSMC_MSG_GetRunningSmuFeaturesHigh', + 'PPSMC_MSG_GetRunningSmuFeaturesLow', 'PPSMC_MSG_GetSmuVersion', + 'PPSMC_MSG_GetSvi3Voltage', 'PPSMC_MSG_GetVoltageByDpm', + 'PPSMC_MSG_Mode3Reset', 'PPSMC_MSG_NotifyPowerSource', + 'PPSMC_MSG_OverridePcieParameters', 'PPSMC_MSG_PowerDownJpeg', + 'PPSMC_MSG_PowerDownUmsch', 'PPSMC_MSG_PowerDownVcn', + 'PPSMC_MSG_PowerUpJpeg', 'PPSMC_MSG_PowerUpUmsch', + 'PPSMC_MSG_PowerUpVcn', + 'PPSMC_MSG_PreloadSwPstateForUclkOverDrive', + 'PPSMC_MSG_PrepareMp1ForUnload', + 'PPSMC_MSG_ReenableAcDcInterrupt', 'PPSMC_MSG_RunDcBtc', + 'PPSMC_MSG_STBtoDramLogSetDramAddress', + 'PPSMC_MSG_STBtoDramLogSetDramSize', + 'PPSMC_MSG_SetAllowedFeaturesMaskHigh', + 'PPSMC_MSG_SetAllowedFeaturesMaskLow', + 'PPSMC_MSG_SetBadMemoryPagesRetiredFlagsPerChannel', + 'PPSMC_MSG_SetDcsArch', 'PPSMC_MSG_SetDriverDramAddr', + 'PPSMC_MSG_SetDriverDramAddrHigh', + 'PPSMC_MSG_SetDriverDramAddrLow', + 'PPSMC_MSG_SetExternalClientDfCstateAllow', + 'PPSMC_MSG_SetFwDstatesMask', 'PPSMC_MSG_SetHardMaxByFreq', + 'PPSMC_MSG_SetHardMinByFreq', 'PPSMC_MSG_SetMGpuFanBoostLimitRpm', + 'PPSMC_MSG_SetNumBadMemoryPagesRetired', + 'PPSMC_MSG_SetOBMTraceBufferLogging', 'PPSMC_MSG_SetPptLimit', + 'PPSMC_MSG_SetPriorityDeltaGain', 'PPSMC_MSG_SetSoftMaxByFreq', + 'PPSMC_MSG_SetSoftMinByFreq', + 'PPSMC_MSG_SetSystemVirtualDramAddrHigh', + 'PPSMC_MSG_SetSystemVirtualDramAddrLow', + 'PPSMC_MSG_SetTemperatureInputSelect', + 'PPSMC_MSG_SetThrottlerMask', 'PPSMC_MSG_SetToolsDramAddr', + 'PPSMC_MSG_SetToolsDramAddrHigh', 'PPSMC_MSG_SetToolsDramAddrLow', + 'PPSMC_MSG_SetVideoFps', 'PPSMC_MSG_SetWorkloadMask', + 'PPSMC_MSG_TestMessage', 'PPSMC_MSG_TransferTableDram2Smu', + 'PPSMC_MSG_TransferTableDram2SmuWithAddr', + 'PPSMC_MSG_TransferTableSmu2Dram', + 'PPSMC_MSG_TransferTableSmu2DramWithAddr', + 'PPSMC_MSG_TriggerVFFLR', 'PPSMC_MSG_UpdatePolicy', + 'PPSMC_MSG_UseDefaultPPTable', 'PPSMC_MSG_UseProfilingMode', + 'PPSMC_Message_Count', 'PPSMC_Result_CmdRejectedBusy', + 'PPSMC_Result_CmdRejectedPrereq', 'PPSMC_Result_Failed', + 'PPSMC_Result_OK', 'PPSMC_Result_UnknownCmd', 'PPSMC_VERSION', + 'PPTABLE_VERSION', 'PPT_THROTTLER_COUNT', 'PPT_THROTTLER_PPT0', + 'PPT_THROTTLER_PPT1', 'PPT_THROTTLER_PPT2', 'PPT_THROTTLER_PPT3', + 'PPT_THROTTLER_e', 'PPT_THROTTLER_e__enumvalues', 'PPTable_t', + 'PP_GRTAVFS_FW_COMMON_FUSE_COUNT', 'PP_GRTAVFS_FW_COMMON_FUSE_e', + 'PP_GRTAVFS_FW_COMMON_FUSE_e__enumvalues', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z1_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z2_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z3_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_COLD_T0', + 'PP_GRTAVFS_FW_COMMON_PPVMIN_Z4_HOT_T0', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z0', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z1', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z2', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z3', + 'PP_GRTAVFS_FW_COMMON_SRAM_RM_Z4', 'PP_GRTAVFS_FW_SEP_FUSE_COUNT', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_0', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_1', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_2', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_3', + 'PP_GRTAVFS_FW_SEP_FUSE_FREQUENCY_TO_COUNT_SCALER_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_0', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_2', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_3', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB1_PWL_VOLTAGE_NEG_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_0', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_1', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_2', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_3', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_4', + 'PP_GRTAVFS_FW_SEP_FUSE_GB2_PWL_VOLTAGE_NEG_1', + 'PP_GRTAVFS_FW_SEP_FUSE_VF4_FREQUENCY', + 'PP_GRTAVFS_FW_SEP_FUSE_VF_NEG_1_FREQUENCY', + 'PP_GRTAVFS_FW_SEP_FUSE_e', + 'PP_GRTAVFS_FW_SEP_FUSE_e__enumvalues', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE0', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE1', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE2', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE3', + 'PP_GRTAVFS_HW_CPOSCALINGCTRL_ZONE4', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE0', 'PP_GRTAVFS_HW_CPO_CTL_ZONE1', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE2', 'PP_GRTAVFS_HW_CPO_CTL_ZONE3', + 'PP_GRTAVFS_HW_CPO_CTL_ZONE4', 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE0', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE1', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE2', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE3', + 'PP_GRTAVFS_HW_CPO_EN_0_31_ZONE4', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE0', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE1', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE2', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE3', + 'PP_GRTAVFS_HW_CPO_EN_32_63_ZONE4', 'PP_GRTAVFS_HW_FUSE_COUNT', + 'PP_GRTAVFS_HW_FUSE_e', 'PP_GRTAVFS_HW_FUSE_e__enumvalues', + 'PP_GRTAVFS_HW_RESERVED_0', 'PP_GRTAVFS_HW_RESERVED_1', + 'PP_GRTAVFS_HW_RESERVED_2', 'PP_GRTAVFS_HW_RESERVED_3', + 'PP_GRTAVFS_HW_RESERVED_4', 'PP_GRTAVFS_HW_RESERVED_5', + 'PP_GRTAVFS_HW_RESERVED_6', 'PP_GRTAVFS_HW_VOLTAGE_GB', + 'PP_GRTAVFS_HW_ZONE0_VF', 'PP_GRTAVFS_HW_ZONE1_VF1', + 'PP_GRTAVFS_HW_ZONE2_VF2', 'PP_GRTAVFS_HW_ZONE3_VF3', + 'PP_NUM_OD_VF_CURVE_POINTS', 'PP_NUM_PSM_DIDT_PWL_ZONES', + 'PP_NUM_RTAVFS_PWL_ZONES', 'PP_OD_FEATURE_COUNT', + 'PP_OD_FEATURE_EDC_BIT', 'PP_OD_FEATURE_FAN_CURVE_BIT', + 'PP_OD_FEATURE_FAN_LEGACY_BIT', 'PP_OD_FEATURE_FCLK_BIT', + 'PP_OD_FEATURE_FULL_CTRL_BIT', 'PP_OD_FEATURE_GFXCLK_BIT', + 'PP_OD_FEATURE_GFX_VF_CURVE_BIT', 'PP_OD_FEATURE_GFX_VMAX_BIT', + 'PP_OD_FEATURE_PPT_BIT', 'PP_OD_FEATURE_SOC_VMAX_BIT', + 'PP_OD_FEATURE_TDC_BIT', 'PP_OD_FEATURE_TEMPERATURE_BIT', + 'PP_OD_FEATURE_UCLK_BIT', 'PP_OD_FEATURE_ZERO_FAN_BIT', + 'PP_OD_POWER_FEATURE_ALWAYS_DISABLED', + 'PP_OD_POWER_FEATURE_ALWAYS_ENABLED', + 'PP_OD_POWER_FEATURE_DISABLED_WHILE_GAMING', + 'PP_OD_POWER_FEATURE_e', 'PP_OD_POWER_FEATURE_e__enumvalues', + 'PSI_SEL_VR0_PLANE0_PSI0', 'PSI_SEL_VR0_PLANE0_PSI1', + 'PSI_SEL_VR0_PLANE1_PSI0', 'PSI_SEL_VR0_PLANE1_PSI1', + 'PSI_SEL_VR1_PLANE0_PSI0', 'PSI_SEL_VR1_PLANE0_PSI1', + 'PSI_SEL_VR1_PLANE1_PSI0', 'PSI_SEL_VR1_PLANE1_PSI1', + 'PWR_CONFIG_TBP_DESKTOP', 'PWR_CONFIG_TBP_MOBILE', + 'PWR_CONFIG_TCP_ESTIMATED', 'PWR_CONFIG_TCP_MEASURED', + 'PWR_CONFIG_TDP', 'PWR_CONFIG_TGP', 'PowerGatingMode_e', + 'PowerGatingMode_e__enumvalues', 'PowerGatingSettings_e', + 'PowerGatingSettings_e__enumvalues', 'PwrConfig_e', + 'PwrConfig_e__enumvalues', 'QuadraticInt_t', + 'SMARTSHIFT_VERSION_1', 'SMARTSHIFT_VERSION_2', + 'SMARTSHIFT_VERSION_3', 'SMARTSHIFT_VERSION_e', + 'SMARTSHIFT_VERSION_e__enumvalues', 'SMU14_DRIVER_IF_V14_0_H', + 'SMU14_Firmware_Footer', 'SMU_CLK_COUNT', + 'SMU_CUSTOM_FAN_SPEED_PWM', 'SMU_CUSTOM_FAN_SPEED_RPM', + 'SMU_DCEFCLK', 'SMU_DCLK', 'SMU_DCLK1', 'SMU_DEFAULT_PPT_LIMIT', + 'SMU_DISPCLK', 'SMU_DPM_USER_PROFILE_RESTORE', 'SMU_ECLK', + 'SMU_FAST_PPT_LIMIT', 'SMU_FCLK', 'SMU_FW_NAME_LEN', + 'SMU_Firmware_Header', 'SMU_GFXCLK', 'SMU_LCLK', 'SMU_MCLK', + 'SMU_MEMORY_POOL_SIZE_1_GB', 'SMU_MEMORY_POOL_SIZE_256_MB', + 'SMU_MEMORY_POOL_SIZE_2_GB', 'SMU_MEMORY_POOL_SIZE_512_MB', + 'SMU_MEMORY_POOL_SIZE_ZERO', 'SMU_OD_ACOUSTIC_LIMIT', + 'SMU_OD_ACOUSTIC_TARGET', 'SMU_OD_CCLK', 'SMU_OD_FAN_CURVE', + 'SMU_OD_FAN_MINIMUM_PWM', 'SMU_OD_FAN_TARGET_TEMPERATURE', + 'SMU_OD_MCLK', 'SMU_OD_RANGE', 'SMU_OD_SCLK', 'SMU_OD_VDDC_CURVE', + 'SMU_OD_VDDGFX_OFFSET', 'SMU_PCIE', 'SMU_PHYCLK', 'SMU_PIXCLK', + 'SMU_POWER_SOURCE_AC', 'SMU_POWER_SOURCE_COUNT', + 'SMU_POWER_SOURCE_DC', 'SMU_PPT_LIMIT_CURRENT', + 'SMU_PPT_LIMIT_DEFAULT', 'SMU_PPT_LIMIT_MAX', 'SMU_PPT_LIMIT_MIN', + 'SMU_REFRESHRATE_SOURCE_EDID', 'SMU_REFRESHRATE_SOURCE_EXPLICIT', + 'SMU_SCLK', 'SMU_SOCCLK', + 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE', + 'SMU_STATE_CLASSIFICATIN_FLAG_LIMITED_POWER_SOURCE2', + 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_3D_PERFORMANCE_LOW', + 'SMU_STATE_CLASSIFICATION_FLAG_ACPI', + 'SMU_STATE_CLASSIFICATION_FLAG_AC_OVERDIRVER_TEMPLATE', + 'SMU_STATE_CLASSIFICATION_FLAG_BACO', + 'SMU_STATE_CLASSIFICATION_FLAG_BOOT', + 'SMU_STATE_CLASSIFICATION_FLAG_DC_OVERDIRVER_TEMPLATE', + 'SMU_STATE_CLASSIFICATION_FLAG_FORCED', + 'SMU_STATE_CLASSIFICATION_FLAG_HD2', + 'SMU_STATE_CLASSIFICATION_FLAG_RESET', + 'SMU_STATE_CLASSIFICATION_FLAG_THERMAL', + 'SMU_STATE_CLASSIFICATION_FLAG_ULV', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_2D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_3D_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_USER_DC_PERFORMANCE', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_HD', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_MVC', + 'SMU_STATE_CLASSIFICATION_FLAG_UVD_SD', 'SMU_STATE_UI_LABEL_BACO', + 'SMU_STATE_UI_LABEL_BALLANCED', 'SMU_STATE_UI_LABEL_BATTERY', + 'SMU_STATE_UI_LABEL_MIDDLE_HIGHT', 'SMU_STATE_UI_LABEL_NONE', + 'SMU_STATE_UI_LABEL_PERFORMANCE', 'SMU_STATE_UI_TABEL_MIDDLE_LOW', + 'SMU_TABLE_ACTIVITY_MONITOR_COEFF', 'SMU_TABLE_AVFS', + 'SMU_TABLE_AVFS_FUSE_OVERRIDE', 'SMU_TABLE_AVFS_PSM_DEBUG', + 'SMU_TABLE_COMBO_PPTABLE', 'SMU_TABLE_COUNT', + 'SMU_TABLE_CUSTOM_DPM', 'SMU_TABLE_DPMCLOCKS', + 'SMU_TABLE_DRIVER_SMU_CONFIG', 'SMU_TABLE_ECCINFO', + 'SMU_TABLE_I2C_COMMANDS', 'SMU_TABLE_OVERDRIVE', 'SMU_TABLE_PACE', + 'SMU_TABLE_PMSTATUSLOG', 'SMU_TABLE_PPTABLE', + 'SMU_TABLE_SMU_METRICS', 'SMU_TABLE_WATERMARKS', + 'SMU_TABLE_WIFIBAND', 'SMU_TEMPERATURE_UNITS_PER_CENTIGRADES', + 'SMU_THERMAL_MAXIMUM_ALERT_TEMP', + 'SMU_THERMAL_MINIMUM_ALERT_TEMP', 'SMU_THROTTLER_APCC_BIT', + 'SMU_THROTTLER_EDC_CPU_BIT', 'SMU_THROTTLER_EDC_GFX_BIT', + 'SMU_THROTTLER_FIT_BIT', 'SMU_THROTTLER_FPPT_BIT', + 'SMU_THROTTLER_PPM_BIT', 'SMU_THROTTLER_PPT0_BIT', + 'SMU_THROTTLER_PPT1_BIT', 'SMU_THROTTLER_PPT2_BIT', + 'SMU_THROTTLER_PPT3_BIT', 'SMU_THROTTLER_PROCHOT_CPU_BIT', + 'SMU_THROTTLER_PROCHOT_GFX_BIT', 'SMU_THROTTLER_SPL_BIT', + 'SMU_THROTTLER_SPPT_APU_BIT', 'SMU_THROTTLER_SPPT_BIT', + 'SMU_THROTTLER_TDC_CVIP_BIT', 'SMU_THROTTLER_TDC_GFX_BIT', + 'SMU_THROTTLER_TDC_MEM_BIT', 'SMU_THROTTLER_TDC_SOC_BIT', + 'SMU_THROTTLER_TDC_VDD_BIT', 'SMU_THROTTLER_TEMP_CORE_BIT', + 'SMU_THROTTLER_TEMP_EDGE_BIT', 'SMU_THROTTLER_TEMP_GPU_BIT', + 'SMU_THROTTLER_TEMP_HOTSPOT_BIT', + 'SMU_THROTTLER_TEMP_LIQUID0_BIT', + 'SMU_THROTTLER_TEMP_LIQUID1_BIT', 'SMU_THROTTLER_TEMP_MEM_BIT', + 'SMU_THROTTLER_TEMP_SOC_BIT', 'SMU_THROTTLER_TEMP_VR_GFX_BIT', + 'SMU_THROTTLER_TEMP_VR_MEM0_BIT', + 'SMU_THROTTLER_TEMP_VR_MEM1_BIT', 'SMU_THROTTLER_TEMP_VR_SOC_BIT', + 'SMU_THROTTLER_VRHOT0_BIT', 'SMU_THROTTLER_VRHOT1_BIT', + 'SMU_UCLK', 'SMU_V14_0_2_PPSMC_H', 'SMU_VCLK', 'SMU_VCLK1', + 'SVI_PLANE_COUNT', 'SVI_PLANE_VDDCI_MEM', 'SVI_PLANE_VDDIO_MEM', + 'SVI_PLANE_VDD_GFX', 'SVI_PLANE_VDD_SOC', 'SVI_PLANE_e', + 'SVI_PLANE_e__enumvalues', 'SVI_PSI_0', 'SVI_PSI_1', 'SVI_PSI_2', + 'SVI_PSI_3', 'SVI_PSI_4', 'SVI_PSI_5', 'SVI_PSI_6', 'SVI_PSI_7', + 'SVI_PSI_e', 'SVI_PSI_e__enumvalues', 'SkuTable_t', + 'SmuMetricsExternal_t', 'SmuMetrics_t', 'Svi3RegulatorSettings_t', + 'SviTelemetryScale_t', 'SwI2cCmd_t', 'SwI2cRequestExternal_t', + 'SwI2cRequest_t', 'TABLE_ACOUSTIC_LIMIT_RPM_FAILED', + 'TABLE_ACOUSTIC_TARGET_RPM_FAILED', + 'TABLE_ACTIVITY_MONITOR_COEFF', 'TABLE_AVFS_PSM_DEBUG', + 'TABLE_COMBO_PPTABLE', 'TABLE_COUNT', 'TABLE_CUSTOM_SKUTABLE', + 'TABLE_DRIVER_INFO', 'TABLE_DRIVER_SMU_CONFIG', 'TABLE_ECCINFO', + 'TABLE_FAN_PWM_MIN_FAILED', 'TABLE_FAN_START_TEMP_FAILED', + 'TABLE_FAN_STOP_TEMP_FAILED', 'TABLE_FAN_TARGET_TEMP_FAILED', + 'TABLE_I2C_COMMANDS', 'TABLE_MGPU_ACOUSTIC_TARGET_RPM_FAILED', + 'TABLE_OVERDRIVE', 'TABLE_PMSTATUSLOG', 'TABLE_PPTABLE', + 'TABLE_PPT_FAILED', 'TABLE_SMU_METRICS', 'TABLE_TDC_FAILED', + 'TABLE_TEMP_FAILED', 'TABLE_TRANSFER_FAILED', 'TABLE_TRANSFER_OK', + 'TABLE_TRANSFER_PENDING', 'TABLE_WATERMARKS', + 'TDC_THROTTLER_COUNT', 'TDC_THROTTLER_GFX', 'TDC_THROTTLER_SOC', + 'TDC_THROTTLER_e', 'TDC_THROTTLER_e__enumvalues', 'TEMP_COUNT', + 'TEMP_EDGE', 'TEMP_HOTSPOT', 'TEMP_HOTSPOT_GFX', + 'TEMP_HOTSPOT_SOC', 'TEMP_LIQUID0', 'TEMP_LIQUID1', 'TEMP_MEM', + 'TEMP_PLX', 'TEMP_VR_GFX', 'TEMP_VR_MEM0', 'TEMP_VR_MEM1', + 'TEMP_VR_SOC', 'TEMP_e', 'TEMP_e__enumvalues', 'THROTTLER_COUNT', + 'THROTTLER_FIT_BIT', 'THROTTLER_GFX_APCC_PLUS_BIT', + 'THROTTLER_GFX_DVO_BIT', 'THROTTLER_PPT0_BIT', + 'THROTTLER_PPT1_BIT', 'THROTTLER_PPT2_BIT', 'THROTTLER_PPT3_BIT', + 'THROTTLER_TDC_GFX_BIT', 'THROTTLER_TDC_SOC_BIT', + 'THROTTLER_TEMP_EDGE_BIT', 'THROTTLER_TEMP_HOTSPOT_BIT', + 'THROTTLER_TEMP_HOTSPOT_GFX_BIT', + 'THROTTLER_TEMP_HOTSPOT_SOC_BIT', 'THROTTLER_TEMP_LIQUID0_BIT', + 'THROTTLER_TEMP_LIQUID1_BIT', 'THROTTLER_TEMP_MEM_BIT', + 'THROTTLER_TEMP_PLX_BIT', 'THROTTLER_TEMP_VR_GFX_BIT', + 'THROTTLER_TEMP_VR_MEM0_BIT', 'THROTTLER_TEMP_VR_MEM1_BIT', + 'THROTTLER_TEMP_VR_SOC_BIT', 'UCLK_DIV_BY_1', 'UCLK_DIV_BY_2', + 'UCLK_DIV_BY_4', 'UCLK_DIV_BY_8', 'UCLK_DIV_e', + 'UCLK_DIV_e__enumvalues', 'ULPS_SEQUENCE', 'VOLTAGE_MODE_COUNT', + 'VOLTAGE_MODE_FUSES', 'VOLTAGE_MODE_PPTABLE', 'VOLTAGE_MODE_e', + 'VOLTAGE_MODE_e__enumvalues', 'VR_MAPPING_PLANE_SELECT_MASK', + 'VR_MAPPING_PLANE_SELECT_SHIFT', 'VR_MAPPING_VR_SELECT_MASK', + 'VR_MAPPING_VR_SELECT_SHIFT', 'WATERMARKS_CLOCK_RANGE', + 'WATERMARKS_COUNT', 'WATERMARKS_DUMMY_PSTATE', + 'WATERMARKS_FLAGS_e', 'WATERMARKS_FLAGS_e__enumvalues', + 'WATERMARKS_MALL', 'WORKLOAD_PPLIB_CGVDI_BIT', + 'WORKLOAD_PPLIB_COMPUTE_BIT', 'WORKLOAD_PPLIB_COUNT', + 'WORKLOAD_PPLIB_CUSTOM_BIT', 'WORKLOAD_PPLIB_DEFAULT_BIT', + 'WORKLOAD_PPLIB_DIRECT_ML_BIT', + 'WORKLOAD_PPLIB_FULL_SCREEN_3D_BIT', + 'WORKLOAD_PPLIB_POWER_SAVING_BIT', 'WORKLOAD_PPLIB_VIDEO_BIT', + 'WORKLOAD_PPLIB_VR_BIT', 'WORKLOAD_PPLIB_WINDOW_3D_BIT', + 'WatermarkRowGeneric_t', 'WatermarksExternal_t', 'Watermarks_t', + '__AMDGPU_SMU_H__', '__SMU_V14_0_0_PMFW_H__', 'bool', + 'c__EA_AVFS_D_e', 'c__EA_AVFS_TEMP_e', + 'c__EA_AVFS_VOLTAGE_TYPE_e', 'c__EA_BOARD_GPIO_TYPE_e', + 'c__EA_CUSTOMER_VARIANT_e', 'c__EA_D3HOTSequence_e', + 'c__EA_DCS_ARCH_e', 'c__EA_DRAM_BIT_WIDTH_TYPE_e', + 'c__EA_EPCS_STATUS_e', 'c__EA_FEATURE_BTC_e', + 'c__EA_FEATURE_PWR_DOMAIN_e', 'c__EA_FOPT_CALC_e', + 'c__EA_FanMode_e', 'c__EA_GpioIntPolarity_e', + 'c__EA_I2cCmdType_e', 'c__EA_I2cControllerName_e', + 'c__EA_I2cControllerPort_e', 'c__EA_I2cControllerProtocol_e', + 'c__EA_I2cControllerThrottler_e', 'c__EA_I2cPort_e', + 'c__EA_I2cSpeed_e', 'c__EA_MEM_VENDOR_e', 'c__EA_OD_FAIL_e', + 'c__EA_PMFW_VOLT_PLANE_e', 'c__EA_POWER_SOURCE_e', + 'c__EA_PPCLK_e', 'c__EA_PPT_THROTTLER_e', + 'c__EA_PP_GRTAVFS_FW_COMMON_FUSE_e', + 'c__EA_PP_GRTAVFS_FW_SEP_FUSE_e', 'c__EA_PP_GRTAVFS_HW_FUSE_e', + 'c__EA_PP_OD_POWER_FEATURE_e', 'c__EA_PowerGatingMode_e', + 'c__EA_PowerGatingSettings_e', 'c__EA_PwrConfig_e', + 'c__EA_SMARTSHIFT_VERSION_e', 'c__EA_SVI_PLANE_e', + 'c__EA_SVI_PSI_e', 'c__EA_TDC_THROTTLER_e', 'c__EA_TEMP_e', + 'c__EA_UCLK_DIV_e', 'c__EA_VOLTAGE_MODE_e', + 'c__EA_WATERMARKS_FLAGS_e', 'int16_t', 'int32_t', 'int8_t', + 'smu_clk_type', 'smu_memory_pool_size', + 'smu_perf_level_designation', 'smu_power_src_type', + 'smu_ppt_limit_level', 'smu_ppt_limit_type', + 'smu_refreshrate_source', 'smu_state_classification_flag', + 'smu_state_ui_label', 'smu_table_id', + 'struct_SMU14_Firmware_Footer', 'struct_amdgpu_bo', + 'struct_c__SA_AvfsDcBtcParams_t', + 'struct_c__SA_AvfsDebugTableExternal_t', + 'struct_c__SA_AvfsDebugTable_t', + 'struct_c__SA_AvfsFuseOverride_t', 'struct_c__SA_BoardTable_t', + 'struct_c__SA_BootValues_t', 'struct_c__SA_CustomSkuTable_t', + 'struct_c__SA_DpmActivityMonitorCoeffIntExternal_t', + 'struct_c__SA_DpmActivityMonitorCoeffInt_t', + 'struct_c__SA_DpmDescriptor_t', 'struct_c__SA_DriverInfoTable_t', + 'struct_c__SA_DriverReportedClocks_t', + 'struct_c__SA_DriverSmuConfigExternal_t', + 'struct_c__SA_DriverSmuConfig_t', 'struct_c__SA_DroopInt_t', + 'struct_c__SA_EccInfoTable_t', 'struct_c__SA_EccInfo_t', + 'struct_c__SA_FwStatus_t', 'struct_c__SA_FwStatus_t_v14_0_1', + 'struct_c__SA_I2cControllerConfig_t', 'struct_c__SA_LinearInt_t', + 'struct_c__SA_MsgLimits_t', 'struct_c__SA_OverDriveLimits_t', + 'struct_c__SA_OverDriveTableExternal_t', + 'struct_c__SA_OverDriveTable_t', 'struct_c__SA_PFE_Settings_t', + 'struct_c__SA_PPTable_t', 'struct_c__SA_QuadraticInt_t', + 'struct_c__SA_SMU_Firmware_Header', 'struct_c__SA_SkuTable_t', + 'struct_c__SA_SmuMetricsExternal_t', 'struct_c__SA_SmuMetrics_t', + 'struct_c__SA_Svi3RegulatorSettings_t', + 'struct_c__SA_SviTelemetryScale_t', 'struct_c__SA_SwI2cCmd_t', + 'struct_c__SA_SwI2cRequestExternal_t', + 'struct_c__SA_SwI2cRequest_t', + 'struct_c__SA_WatermarkRowGeneric_t', + 'struct_c__SA_WatermarksExternal_t', 'struct_c__SA_Watermarks_t', + 'struct_smu_bios_boot_up_values', 'struct_smu_clock_info', + 'struct_smu_hw_power_state', 'struct_smu_performance_level', + 'struct_smu_power_state', 'struct_smu_state_classification_block', + 'struct_smu_state_display_block', 'struct_smu_state_memory_block', + 'struct_smu_state_pcie_block', + 'struct_smu_state_software_algorithm_block', + 'struct_smu_state_validation_block', 'struct_smu_table', + 'struct_smu_temperature_range', 'struct_smu_user_dpm_profile', + 'struct_smu_uvd_clocks', 'u32', 'uint16_t', 'uint32_t', + 'uint64_t', 'uint8_t'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/soc21.py b/tinygrad_repo/tinygrad/runtime/autogen/am/soc21.py new file mode 100644 index 0000000000..34a95940d1 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/soc21.py @@ -0,0 +1,39083 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + + + +_soc21_ENUM_HEADER = True # macro +SQ_WAVE_TYPE_PS0 = 0x00000000 # macro +SQIND_GLOBAL_REGS_OFFSET = 0x00000000 # macro +SQIND_GLOBAL_REGS_SIZE = 0x00000008 # macro +SQIND_LOCAL_REGS_OFFSET = 0x00000008 # macro +SQIND_LOCAL_REGS_SIZE = 0x00000008 # macro +SQIND_WAVE_HWREGS_OFFSET = 0x00000100 # macro +SQIND_WAVE_HWREGS_SIZE = 0x00000100 # macro +SQIND_WAVE_SGPRS_OFFSET = 0x00000200 # macro +SQIND_WAVE_SGPRS_SIZE = 0x00000200 # macro +SQIND_WAVE_VGPRS_OFFSET = 0x00000400 # macro +SQIND_WAVE_VGPRS_SIZE = 0x00000400 # macro +SQ_GFXDEC_BEGIN = 0x0000a000 # macro +SQ_GFXDEC_END = 0x0000c000 # macro +SQ_GFXDEC_STATE_ID_SHIFT = 0x0000000a # macro +SQDEC_BEGIN = 0x00002300 # macro +SQDEC_END = 0x000023ff # macro +SQPERFSDEC_BEGIN = 0x0000d9c0 # macro +SQPERFSDEC_END = 0x0000da40 # macro +SQPERFDDEC_BEGIN = 0x0000d1c0 # macro +SQPERFDDEC_END = 0x0000d240 # macro +SQGFXUDEC_BEGIN = 0x0000c330 # macro +SQGFXUDEC_END = 0x0000c380 # macro +SQPWRDEC_BEGIN = 0x0000f08c # macro +SQPWRDEC_END = 0x0000f094 # macro +SQ_DISPATCHER_GFX_MIN = 0x00000010 # macro +SQ_DISPATCHER_GFX_CNT_PER_RING = 0x00000008 # macro +SQ_MAX_PGM_SGPRS = 0x00000068 # macro +SQ_MAX_PGM_VGPRS = 0x00000100 # macro +SQ_EX_MODE_EXCP_VALU_BASE = 0x00000000 # macro +SQ_EX_MODE_EXCP_VALU_SIZE = 0x00000007 # macro +SQ_EX_MODE_EXCP_INVALID = 0x00000000 # macro +SQ_EX_MODE_EXCP_INPUT_DENORM = 0x00000001 # macro +SQ_EX_MODE_EXCP_DIV0 = 0x00000002 # macro +SQ_EX_MODE_EXCP_OVERFLOW = 0x00000003 # macro +SQ_EX_MODE_EXCP_UNDERFLOW = 0x00000004 # macro +SQ_EX_MODE_EXCP_INEXACT = 0x00000005 # macro +SQ_EX_MODE_EXCP_INT_DIV0 = 0x00000006 # macro +SQ_EX_MODE_EXCP_ADDR_WATCH0 = 0x00000007 # macro +SQ_EX_MODE_EXCP_MEM_VIOL = 0x00000008 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH1 = 0x00000000 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH2 = 0x00000001 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH3 = 0x00000002 # macro +INST_ID_PRIV_START = 0x80000000 # macro +INST_ID_ECC_INTERRUPT_MSG = 0xfffffff0 # macro +INST_ID_TTRACE_NEW_PC_MSG = 0xfffffff1 # macro +INST_ID_HW_TRAP = 0xfffffff2 # macro +INST_ID_KILL_SEQ = 0xfffffff3 # macro +INST_ID_SPI_WREXEC = 0xfffffff4 # macro +INST_ID_HW_TRAP_GET_TBA = 0xfffffff5 # macro +INST_ID_HOST_REG_TRAP_MSG = 0xfffffffe # macro +SIMM16_WAITCNT_EXP_CNT_START = 0x00000000 # macro +SIMM16_WAITCNT_EXP_CNT_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_LGKM_CNT_START = 0x00000004 # macro +SIMM16_WAITCNT_LGKM_CNT_SIZE = 0x00000006 # macro +SIMM16_WAITCNT_VM_CNT_START = 0x0000000a # macro +SIMM16_WAITCNT_VM_CNT_SIZE = 0x00000006 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_START = 0x00000000 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_START = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_START = 0x00000002 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_HOLD_CNT_START = 0x00000006 # macro +SIMM16_WAITCNT_DEPCTR_HOLD_CNT_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_START = 0x00000007 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_START = 0x00000008 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_START = 0x0000000b # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE = 0x00000005 # macro +SIMM16_WAIT_EVENT_EXP_RDY_START = 0x00000000 # macro +SIMM16_WAIT_EVENT_EXP_RDY_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_SA_SDST_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_SA_EXEC_SIZE = 0x00000002 # macro +SQ_WAVE_IB_DEP_SA_M0_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_VM_VSRC_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_HOLD_CNT_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_VA_SSRC_SIZE = 0x00000003 # macro +SQ_WAVE_IB_DEP_VA_SDST_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_VA_VCC_SIZE = 0x00000003 # macro +SQ_WAVE_IB_DEP_VA_EXEC_SIZE = 0x00000002 # macro +SQ_WAVE_IB_DEP_VA_VDST_SIZE = 0x00000005 # macro +SQ_WAVE_IB_DEP_LDS_DIR_SIZE = 0x00000003 # macro +SQ_EDC_FUE_CNTL_SIMD0 = 0x00000000 # macro +SQ_EDC_FUE_CNTL_SIMD1 = 0x00000001 # macro +SQ_EDC_FUE_CNTL_SIMD2 = 0x00000002 # macro +SQ_EDC_FUE_CNTL_SIMD3 = 0x00000003 # macro +SQ_EDC_FUE_CNTL_SQ = 0x00000004 # macro +SQ_EDC_FUE_CNTL_LDS = 0x00000005 # macro +SQ_EDC_FUE_CNTL_TD = 0x00000006 # macro +SQ_EDC_FUE_CNTL_TA = 0x00000007 # macro +SQ_EDC_FUE_CNTL_TCP = 0x00000008 # macro +CSDATA_TYPE_WIDTH = 0x00000002 # macro +CSDATA_ADDR_WIDTH = 0x00000007 # macro +CSDATA_DATA_WIDTH = 0x00000020 # macro +CSCNTL_TYPE_WIDTH = 0x00000002 # macro +CSCNTL_ADDR_WIDTH = 0x00000007 # macro +CSCNTL_DATA_WIDTH = 0x00000020 # macro +GSTHREADID_SIZE = 0x00000002 # macro +GB_TILING_CONFIG_TABLE_SIZE = 0x00000020 # macro +GB_TILING_CONFIG_MACROTABLE_SIZE = 0x00000010 # macro +SEM_ECC_ERROR = 0x00000000 # macro +SEM_TRANS_ERROR = 0x00000001 # macro +SEM_RESP_FAILED = 0x00000002 # macro +SEM_RESP_PASSED = 0x00000003 # macro +IQ_QUEUE_SLEEP = 0x00000000 # macro +IQ_OFFLOAD_RETRY = 0x00000001 # macro +IQ_SCH_WAVE_MSG = 0x00000002 # macro +IQ_SEM_REARM = 0x00000003 # macro +IQ_DEQUEUE_RETRY = 0x00000004 # macro +IQ_INTR_TYPE_PQ = 0x00000000 # macro +IQ_INTR_TYPE_IB = 0x00000001 # macro +IQ_INTR_TYPE_MQD = 0x00000002 # macro +VMID_SZ = 0x00000004 # macro +SRCID_RLC = 0x00000000 # macro +SRCID_RLCV = 0x00000006 # macro +SRCID_SECURE_CP = 0x00000007 # macro +SRCID_NONSECURE_CP = 0x00000001 # macro +SRCID_SECURE_CP_RCIU = 0x00000007 # macro +SRCID_NONSECURE_CP_RCIU = 0x00000001 # macro +CONFIG_SPACE_START = 0x00002000 # macro +CONFIG_SPACE_END = 0x00009fff # macro +CONFIG_SPACE1_START = 0x00002000 # macro +CONFIG_SPACE1_END = 0x00002bff # macro +CONFIG_SPACE2_START = 0x00003000 # macro +CONFIG_SPACE2_END = 0x00009fff # macro +UCONFIG_SPACE_START = 0x0000c000 # macro +UCONFIG_SPACE_END = 0x0000ffff # macro +PERSISTENT_SPACE_START = 0x00002c00 # macro +PERSISTENT_SPACE_END = 0x00002fff # macro +CONTEXT_SPACE_START = 0x0000a000 # macro +CONTEXT_SPACE_END = 0x0000a3ff # macro +ROM_SIGNATURE = 0x0000aa55 # macro + +# values for enumeration 'DSM_DATA_SEL' +DSM_DATA_SEL__enumvalues = { + 0: 'DSM_DATA_SEL_DISABLE', + 1: 'DSM_DATA_SEL_0', + 2: 'DSM_DATA_SEL_1', + 3: 'DSM_DATA_SEL_BOTH', +} +DSM_DATA_SEL_DISABLE = 0 +DSM_DATA_SEL_0 = 1 +DSM_DATA_SEL_1 = 2 +DSM_DATA_SEL_BOTH = 3 +DSM_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_ENABLE_ERROR_INJECT' +DSM_ENABLE_ERROR_INJECT__enumvalues = { + 0: 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 1: 'DSM_ENABLE_ERROR_INJECT_SINGLE', + 2: 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE', + 3: 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED', +} +DSM_ENABLE_ERROR_INJECT_FED_IN = 0 +DSM_ENABLE_ERROR_INJECT_SINGLE = 1 +DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE = 2 +DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED = 3 +DSM_ENABLE_ERROR_INJECT = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_SELECT_INJECT_DELAY' +DSM_SELECT_INJECT_DELAY__enumvalues = { + 0: 'DSM_SELECT_INJECT_DELAY_NO_DELAY', + 1: 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', +} +DSM_SELECT_INJECT_DELAY_NO_DELAY = 0 +DSM_SELECT_INJECT_DELAY_DELAY_ERROR = 1 +DSM_SELECT_INJECT_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_SINGLE_WRITE' +DSM_SINGLE_WRITE__enumvalues = { + 0: 'DSM_SINGLE_WRITE_DIS', + 1: 'DSM_SINGLE_WRITE_EN', +} +DSM_SINGLE_WRITE_DIS = 0 +DSM_SINGLE_WRITE_EN = 1 +DSM_SINGLE_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_NUM_SIMD_PER_CU' +ENUM_NUM_SIMD_PER_CU__enumvalues = { + 2: 'NUM_SIMD_PER_CU', +} +NUM_SIMD_PER_CU = 2 +ENUM_NUM_SIMD_PER_CU = ctypes.c_uint32 # enum + +# values for enumeration 'GATCL1RequestType' +GATCL1RequestType__enumvalues = { + 0: 'GATCL1_TYPE_NORMAL', + 1: 'GATCL1_TYPE_SHOOTDOWN', + 2: 'GATCL1_TYPE_BYPASS', +} +GATCL1_TYPE_NORMAL = 0 +GATCL1_TYPE_SHOOTDOWN = 1 +GATCL1_TYPE_BYPASS = 2 +GATCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'GL0V_CACHE_POLICIES' +GL0V_CACHE_POLICIES__enumvalues = { + 0: 'GL0V_CACHE_POLICY_MISS_LRU', + 1: 'GL0V_CACHE_POLICY_MISS_EVICT', + 2: 'GL0V_CACHE_POLICY_HIT_LRU', + 3: 'GL0V_CACHE_POLICY_HIT_EVICT', +} +GL0V_CACHE_POLICY_MISS_LRU = 0 +GL0V_CACHE_POLICY_MISS_EVICT = 1 +GL0V_CACHE_POLICY_HIT_LRU = 2 +GL0V_CACHE_POLICY_HIT_EVICT = 3 +GL0V_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_POLICIES' +GL1_CACHE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_POLICY_MISS_LRU', + 1: 'GL1_CACHE_POLICY_MISS_EVICT', + 2: 'GL1_CACHE_POLICY_HIT_LRU', + 3: 'GL1_CACHE_POLICY_HIT_EVICT', +} +GL1_CACHE_POLICY_MISS_LRU = 0 +GL1_CACHE_POLICY_MISS_EVICT = 1 +GL1_CACHE_POLICY_HIT_LRU = 2 +GL1_CACHE_POLICY_HIT_EVICT = 3 +GL1_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_STORE_POLICIES' +GL1_CACHE_STORE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_STORE_POLICY_BYPASS', +} +GL1_CACHE_STORE_POLICY_BYPASS = 0 +GL1_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_CACHE_POLICIES' +GL2_CACHE_POLICIES__enumvalues = { + 0: 'GL2_CACHE_POLICY_LRU', + 1: 'GL2_CACHE_POLICY_STREAM', + 2: 'GL2_CACHE_POLICY_NOA', + 3: 'GL2_CACHE_POLICY_BYPASS', +} +GL2_CACHE_POLICY_LRU = 0 +GL2_CACHE_POLICY_STREAM = 1 +GL2_CACHE_POLICY_NOA = 2 +GL2_CACHE_POLICY_BYPASS = 3 +GL2_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'Hdp_SurfaceEndian' +Hdp_SurfaceEndian__enumvalues = { + 0: 'HDP_ENDIAN_NONE', + 1: 'HDP_ENDIAN_8IN16', + 2: 'HDP_ENDIAN_8IN32', + 3: 'HDP_ENDIAN_8IN64', +} +HDP_ENDIAN_NONE = 0 +HDP_ENDIAN_8IN16 = 1 +HDP_ENDIAN_8IN32 = 2 +HDP_ENDIAN_8IN64 = 3 +Hdp_SurfaceEndian = ctypes.c_uint32 # enum + +# values for enumeration 'MTYPE' +MTYPE__enumvalues = { + 0: 'MTYPE_C_RW_US', + 1: 'MTYPE_RESERVED_1', + 2: 'MTYPE_C_RO_S', + 3: 'MTYPE_UC', + 4: 'MTYPE_C_RW_S', + 5: 'MTYPE_RESERVED_5', + 6: 'MTYPE_C_RO_US', + 7: 'MTYPE_RESERVED_7', +} +MTYPE_C_RW_US = 0 +MTYPE_RESERVED_1 = 1 +MTYPE_C_RO_S = 2 +MTYPE_UC = 3 +MTYPE_C_RW_S = 4 +MTYPE_RESERVED_5 = 5 +MTYPE_C_RO_US = 6 +MTYPE_RESERVED_7 = 7 +MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_COUNTER_MODE' +PERFMON_COUNTER_MODE__enumvalues = { + 0: 'PERFMON_COUNTER_MODE_ACCUM', + 1: 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 2: 'PERFMON_COUNTER_MODE_MAX', + 3: 'PERFMON_COUNTER_MODE_DIRTY', + 4: 'PERFMON_COUNTER_MODE_SAMPLE', + 5: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 6: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 7: 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 8: 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 9: 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 15: 'PERFMON_COUNTER_MODE_RESERVED', +} +PERFMON_COUNTER_MODE_ACCUM = 0 +PERFMON_COUNTER_MODE_ACTIVE_CYCLES = 1 +PERFMON_COUNTER_MODE_MAX = 2 +PERFMON_COUNTER_MODE_DIRTY = 3 +PERFMON_COUNTER_MODE_SAMPLE = 4 +PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT = 5 +PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT = 6 +PERFMON_COUNTER_MODE_CYCLES_GE_HI = 7 +PERFMON_COUNTER_MODE_CYCLES_EQ_HI = 8 +PERFMON_COUNTER_MODE_INACTIVE_CYCLES = 9 +PERFMON_COUNTER_MODE_RESERVED = 15 +PERFMON_COUNTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_SPM_MODE' +PERFMON_SPM_MODE__enumvalues = { + 0: 'PERFMON_SPM_MODE_OFF', + 1: 'PERFMON_SPM_MODE_16BIT_CLAMP', + 2: 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 3: 'PERFMON_SPM_MODE_32BIT_CLAMP', + 4: 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 5: 'PERFMON_SPM_MODE_RESERVED_5', + 6: 'PERFMON_SPM_MODE_RESERVED_6', + 7: 'PERFMON_SPM_MODE_RESERVED_7', + 8: 'PERFMON_SPM_MODE_TEST_MODE_0', + 9: 'PERFMON_SPM_MODE_TEST_MODE_1', + 10: 'PERFMON_SPM_MODE_TEST_MODE_2', +} +PERFMON_SPM_MODE_OFF = 0 +PERFMON_SPM_MODE_16BIT_CLAMP = 1 +PERFMON_SPM_MODE_16BIT_NO_CLAMP = 2 +PERFMON_SPM_MODE_32BIT_CLAMP = 3 +PERFMON_SPM_MODE_32BIT_NO_CLAMP = 4 +PERFMON_SPM_MODE_RESERVED_5 = 5 +PERFMON_SPM_MODE_RESERVED_6 = 6 +PERFMON_SPM_MODE_RESERVED_7 = 7 +PERFMON_SPM_MODE_TEST_MODE_0 = 8 +PERFMON_SPM_MODE_TEST_MODE_1 = 9 +PERFMON_SPM_MODE_TEST_MODE_2 = 10 +PERFMON_SPM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RMI_CID' +RMI_CID__enumvalues = { + 0: 'RMI_CID_CC', + 1: 'RMI_CID_FC', + 2: 'RMI_CID_CM', + 3: 'RMI_CID_DC', + 4: 'RMI_CID_Z', + 5: 'RMI_CID_S', + 6: 'RMI_CID_TILE', + 7: 'RMI_CID_ZPCPSD', +} +RMI_CID_CC = 0 +RMI_CID_FC = 1 +RMI_CID_CM = 2 +RMI_CID_DC = 3 +RMI_CID_Z = 4 +RMI_CID_S = 5 +RMI_CID_TILE = 6 +RMI_CID_ZPCPSD = 7 +RMI_CID = ctypes.c_uint32 # enum + +# values for enumeration 'ReadPolicy' +ReadPolicy__enumvalues = { + 0: 'CACHE_LRU_RD', + 1: 'CACHE_STREAM_RD', + 2: 'CACHE_NOA', + 3: 'RESERVED_RDPOLICY', +} +CACHE_LRU_RD = 0 +CACHE_STREAM_RD = 1 +CACHE_NOA = 2 +RESERVED_RDPOLICY = 3 +ReadPolicy = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERFMON_SEL' +SDMA_PERFMON_SEL__enumvalues = { + 0: 'SDMA_PERFMON_SEL_CYCLE', + 1: 'SDMA_PERFMON_SEL_IDLE', + 2: 'SDMA_PERFMON_SEL_REG_IDLE', + 3: 'SDMA_PERFMON_SEL_RB_EMPTY', + 4: 'SDMA_PERFMON_SEL_RB_FULL', + 5: 'SDMA_PERFMON_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERFMON_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERFMON_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERFMON_SEL_RB_RPTR_WB', + 9: 'SDMA_PERFMON_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERFMON_SEL_RB_CMD_FULL', + 11: 'SDMA_PERFMON_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERFMON_SEL_IB_CMD_FULL', + 13: 'SDMA_PERFMON_SEL_EX_IDLE', + 14: 'SDMA_PERFMON_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERFMON_SEL_WR_BA_RTR', + 17: 'SDMA_PERFMON_SEL_MC_WR_IDLE', + 18: 'SDMA_PERFMON_SEL_MC_WR_COUNT', + 19: 'SDMA_PERFMON_SEL_RD_BA_RTR', + 20: 'SDMA_PERFMON_SEL_MC_RD_IDLE', + 21: 'SDMA_PERFMON_SEL_MC_RD_COUNT', + 22: 'SDMA_PERFMON_SEL_MC_RD_RET_STALL', + 23: 'SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE', + 26: 'SDMA_PERFMON_SEL_SEM_IDLE', + 27: 'SDMA_PERFMON_SEL_SEM_REQ_STALL', + 28: 'SDMA_PERFMON_SEL_SEM_REQ_COUNT', + 29: 'SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE', + 30: 'SDMA_PERFMON_SEL_SEM_RESP_FAIL', + 31: 'SDMA_PERFMON_SEL_SEM_RESP_PASS', + 32: 'SDMA_PERFMON_SEL_INT_IDLE', + 33: 'SDMA_PERFMON_SEL_INT_REQ_STALL', + 34: 'SDMA_PERFMON_SEL_INT_REQ_COUNT', + 35: 'SDMA_PERFMON_SEL_INT_RESP_ACCEPTED', + 36: 'SDMA_PERFMON_SEL_INT_RESP_RETRY', + 37: 'SDMA_PERFMON_SEL_NUM_PACKET', + 39: 'SDMA_PERFMON_SEL_CE_WREQ_IDLE', + 40: 'SDMA_PERFMON_SEL_CE_WR_IDLE', + 41: 'SDMA_PERFMON_SEL_CE_SPLIT_IDLE', + 42: 'SDMA_PERFMON_SEL_CE_RREQ_IDLE', + 43: 'SDMA_PERFMON_SEL_CE_OUT_IDLE', + 44: 'SDMA_PERFMON_SEL_CE_IN_IDLE', + 45: 'SDMA_PERFMON_SEL_CE_DST_IDLE', + 48: 'SDMA_PERFMON_SEL_CE_AFIFO_FULL', + 51: 'SDMA_PERFMON_SEL_CE_INFO_FULL', + 52: 'SDMA_PERFMON_SEL_CE_INFO1_FULL', + 53: 'SDMA_PERFMON_SEL_CE_RD_STALL', + 54: 'SDMA_PERFMON_SEL_CE_WR_STALL', + 55: 'SDMA_PERFMON_SEL_GFX_SELECT', + 56: 'SDMA_PERFMON_SEL_RLC0_SELECT', + 57: 'SDMA_PERFMON_SEL_RLC1_SELECT', + 58: 'SDMA_PERFMON_SEL_PAGE_SELECT', + 59: 'SDMA_PERFMON_SEL_CTX_CHANGE', + 60: 'SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED', + 61: 'SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION', + 62: 'SDMA_PERFMON_SEL_DOORBELL', + 63: 'SDMA_PERFMON_SEL_F32_L1_WR_VLD', + 64: 'SDMA_PERFMON_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERFMON_SEL_CPF_SDMA_INVREQ', + 66: 'SDMA_PERFMON_SEL_SDMA_CPF_INVACK', + 67: 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ', + 68: 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK', + 69: 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL', + 70: 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL', + 71: 'SDMA_PERFMON_SEL_UTCL2_RET_XNACK', + 72: 'SDMA_PERFMON_SEL_UTCL2_RET_ACK', + 73: 'SDMA_PERFMON_SEL_UTCL2_FREE', + 74: 'SDMA_PERFMON_SEL_SDMA_UTCL2_SEND', + 75: 'SDMA_PERFMON_SEL_DMA_L1_WR_SEND', + 76: 'SDMA_PERFMON_SEL_DMA_L1_RD_SEND', + 77: 'SDMA_PERFMON_SEL_DMA_MC_WR_SEND', + 78: 'SDMA_PERFMON_SEL_DMA_MC_RD_SEND', + 79: 'SDMA_PERFMON_SEL_GPUVM_INV_HIGH', + 80: 'SDMA_PERFMON_SEL_GPUVM_INV_LOW', + 81: 'SDMA_PERFMON_SEL_L1_WRL2_IDLE', + 82: 'SDMA_PERFMON_SEL_L1_RDL2_IDLE', + 83: 'SDMA_PERFMON_SEL_L1_WRMC_IDLE', + 84: 'SDMA_PERFMON_SEL_L1_RDMC_IDLE', + 85: 'SDMA_PERFMON_SEL_L1_WR_INV_IDLE', + 86: 'SDMA_PERFMON_SEL_L1_RD_INV_IDLE', + 87: 'SDMA_PERFMON_SEL_META_L2_REQ_SEND', + 88: 'SDMA_PERFMON_SEL_L2_META_RET_VLD', + 89: 'SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND', + 90: 'SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN', + 91: 'SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND', + 92: 'SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN', + 93: 'SDMA_PERFMON_SEL_META_REQ_SEND', + 94: 'SDMA_PERFMON_SEL_META_RTN_VLD', + 95: 'SDMA_PERFMON_SEL_TLBI_SEND', + 96: 'SDMA_PERFMON_SEL_TLBI_RTN', + 97: 'SDMA_PERFMON_SEL_GCR_SEND', + 98: 'SDMA_PERFMON_SEL_GCR_RTN', + 99: 'SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER', + 100: 'SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER', +} +SDMA_PERFMON_SEL_CYCLE = 0 +SDMA_PERFMON_SEL_IDLE = 1 +SDMA_PERFMON_SEL_REG_IDLE = 2 +SDMA_PERFMON_SEL_RB_EMPTY = 3 +SDMA_PERFMON_SEL_RB_FULL = 4 +SDMA_PERFMON_SEL_RB_WPTR_WRAP = 5 +SDMA_PERFMON_SEL_RB_RPTR_WRAP = 6 +SDMA_PERFMON_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERFMON_SEL_RB_RPTR_WB = 8 +SDMA_PERFMON_SEL_RB_CMD_IDLE = 9 +SDMA_PERFMON_SEL_RB_CMD_FULL = 10 +SDMA_PERFMON_SEL_IB_CMD_IDLE = 11 +SDMA_PERFMON_SEL_IB_CMD_FULL = 12 +SDMA_PERFMON_SEL_EX_IDLE = 13 +SDMA_PERFMON_SEL_SRBM_REG_SEND = 14 +SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERFMON_SEL_WR_BA_RTR = 16 +SDMA_PERFMON_SEL_MC_WR_IDLE = 17 +SDMA_PERFMON_SEL_MC_WR_COUNT = 18 +SDMA_PERFMON_SEL_RD_BA_RTR = 19 +SDMA_PERFMON_SEL_MC_RD_IDLE = 20 +SDMA_PERFMON_SEL_MC_RD_COUNT = 21 +SDMA_PERFMON_SEL_MC_RD_RET_STALL = 22 +SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE = 23 +SDMA_PERFMON_SEL_SEM_IDLE = 26 +SDMA_PERFMON_SEL_SEM_REQ_STALL = 27 +SDMA_PERFMON_SEL_SEM_REQ_COUNT = 28 +SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE = 29 +SDMA_PERFMON_SEL_SEM_RESP_FAIL = 30 +SDMA_PERFMON_SEL_SEM_RESP_PASS = 31 +SDMA_PERFMON_SEL_INT_IDLE = 32 +SDMA_PERFMON_SEL_INT_REQ_STALL = 33 +SDMA_PERFMON_SEL_INT_REQ_COUNT = 34 +SDMA_PERFMON_SEL_INT_RESP_ACCEPTED = 35 +SDMA_PERFMON_SEL_INT_RESP_RETRY = 36 +SDMA_PERFMON_SEL_NUM_PACKET = 37 +SDMA_PERFMON_SEL_CE_WREQ_IDLE = 39 +SDMA_PERFMON_SEL_CE_WR_IDLE = 40 +SDMA_PERFMON_SEL_CE_SPLIT_IDLE = 41 +SDMA_PERFMON_SEL_CE_RREQ_IDLE = 42 +SDMA_PERFMON_SEL_CE_OUT_IDLE = 43 +SDMA_PERFMON_SEL_CE_IN_IDLE = 44 +SDMA_PERFMON_SEL_CE_DST_IDLE = 45 +SDMA_PERFMON_SEL_CE_AFIFO_FULL = 48 +SDMA_PERFMON_SEL_CE_INFO_FULL = 51 +SDMA_PERFMON_SEL_CE_INFO1_FULL = 52 +SDMA_PERFMON_SEL_CE_RD_STALL = 53 +SDMA_PERFMON_SEL_CE_WR_STALL = 54 +SDMA_PERFMON_SEL_GFX_SELECT = 55 +SDMA_PERFMON_SEL_RLC0_SELECT = 56 +SDMA_PERFMON_SEL_RLC1_SELECT = 57 +SDMA_PERFMON_SEL_PAGE_SELECT = 58 +SDMA_PERFMON_SEL_CTX_CHANGE = 59 +SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED = 60 +SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION = 61 +SDMA_PERFMON_SEL_DOORBELL = 62 +SDMA_PERFMON_SEL_F32_L1_WR_VLD = 63 +SDMA_PERFMON_SEL_CE_L1_WR_VLD = 64 +SDMA_PERFMON_SEL_CPF_SDMA_INVREQ = 65 +SDMA_PERFMON_SEL_SDMA_CPF_INVACK = 66 +SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ = 67 +SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK = 68 +SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL = 69 +SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL = 70 +SDMA_PERFMON_SEL_UTCL2_RET_XNACK = 71 +SDMA_PERFMON_SEL_UTCL2_RET_ACK = 72 +SDMA_PERFMON_SEL_UTCL2_FREE = 73 +SDMA_PERFMON_SEL_SDMA_UTCL2_SEND = 74 +SDMA_PERFMON_SEL_DMA_L1_WR_SEND = 75 +SDMA_PERFMON_SEL_DMA_L1_RD_SEND = 76 +SDMA_PERFMON_SEL_DMA_MC_WR_SEND = 77 +SDMA_PERFMON_SEL_DMA_MC_RD_SEND = 78 +SDMA_PERFMON_SEL_GPUVM_INV_HIGH = 79 +SDMA_PERFMON_SEL_GPUVM_INV_LOW = 80 +SDMA_PERFMON_SEL_L1_WRL2_IDLE = 81 +SDMA_PERFMON_SEL_L1_RDL2_IDLE = 82 +SDMA_PERFMON_SEL_L1_WRMC_IDLE = 83 +SDMA_PERFMON_SEL_L1_RDMC_IDLE = 84 +SDMA_PERFMON_SEL_L1_WR_INV_IDLE = 85 +SDMA_PERFMON_SEL_L1_RD_INV_IDLE = 86 +SDMA_PERFMON_SEL_META_L2_REQ_SEND = 87 +SDMA_PERFMON_SEL_L2_META_RET_VLD = 88 +SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND = 89 +SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN = 90 +SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND = 91 +SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN = 92 +SDMA_PERFMON_SEL_META_REQ_SEND = 93 +SDMA_PERFMON_SEL_META_RTN_VLD = 94 +SDMA_PERFMON_SEL_TLBI_SEND = 95 +SDMA_PERFMON_SEL_TLBI_RTN = 96 +SDMA_PERFMON_SEL_GCR_SEND = 97 +SDMA_PERFMON_SEL_GCR_RTN = 98 +SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER = 99 +SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER = 100 +SDMA_PERFMON_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERF_SEL' +SDMA_PERF_SEL__enumvalues = { + 0: 'SDMA_PERF_SEL_CYCLE', + 1: 'SDMA_PERF_SEL_IDLE', + 2: 'SDMA_PERF_SEL_REG_IDLE', + 3: 'SDMA_PERF_SEL_RB_EMPTY', + 4: 'SDMA_PERF_SEL_RB_FULL', + 5: 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERF_SEL_RB_RPTR_WB', + 9: 'SDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERF_SEL_RB_CMD_FULL', + 11: 'SDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERF_SEL_IB_CMD_FULL', + 13: 'SDMA_PERF_SEL_EX_IDLE', + 14: 'SDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERF_SEL_MC_WR_IDLE', + 17: 'SDMA_PERF_SEL_MC_WR_COUNT', + 18: 'SDMA_PERF_SEL_MC_RD_IDLE', + 19: 'SDMA_PERF_SEL_MC_RD_COUNT', + 20: 'SDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'SDMA_PERF_SEL_SEM_IDLE', + 25: 'SDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'SDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'SDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'SDMA_PERF_SEL_INT_IDLE', + 31: 'SDMA_PERF_SEL_INT_REQ_STALL', + 32: 'SDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'SDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'SDMA_PERF_SEL_NUM_PACKET', + 37: 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'SDMA_PERF_SEL_CE_WR_IDLE', + 39: 'SDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'SDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'SDMA_PERF_SEL_CE_IN_IDLE', + 43: 'SDMA_PERF_SEL_CE_DST_IDLE', + 46: 'SDMA_PERF_SEL_CE_AFIFO_FULL', + 49: 'SDMA_PERF_SEL_CE_INFO_FULL', + 50: 'SDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'SDMA_PERF_SEL_CE_RD_STALL', + 52: 'SDMA_PERF_SEL_CE_WR_STALL', + 53: 'SDMA_PERF_SEL_GFX_SELECT', + 54: 'SDMA_PERF_SEL_RLC0_SELECT', + 55: 'SDMA_PERF_SEL_RLC1_SELECT', + 56: 'SDMA_PERF_SEL_PAGE_SELECT', + 57: 'SDMA_PERF_SEL_CTX_CHANGE', + 58: 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'SDMA_PERF_SEL_DOORBELL', + 61: 'SDMA_PERF_SEL_RD_BA_RTR', + 62: 'SDMA_PERF_SEL_WR_BA_RTR', + 63: 'SDMA_PERF_SEL_F32_L1_WR_VLD', + 64: 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', + 66: 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 67: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 68: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 69: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 70: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 71: 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 72: 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 73: 'SDMA_PERF_SEL_UTCL2_FREE', + 74: 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 75: 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 76: 'SDMA_PERF_SEL_DMA_L1_RD_SEND', + 77: 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 78: 'SDMA_PERF_SEL_DMA_MC_RD_SEND', + 79: 'SDMA_PERF_SEL_GPUVM_INV_HIGH', + 80: 'SDMA_PERF_SEL_GPUVM_INV_LOW', + 81: 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 82: 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 83: 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 84: 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 85: 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 86: 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 87: 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 88: 'SDMA_PERF_SEL_L2_META_RET_VLD', + 89: 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 90: 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 91: 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', + 92: 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', + 93: 'SDMA_PERF_SEL_META_REQ_SEND', + 94: 'SDMA_PERF_SEL_META_RTN_VLD', + 95: 'SDMA_PERF_SEL_TLBI_SEND', + 96: 'SDMA_PERF_SEL_TLBI_RTN', + 97: 'SDMA_PERF_SEL_GCR_SEND', + 98: 'SDMA_PERF_SEL_GCR_RTN', + 99: 'SDMA_PERF_SEL_CGCG_FENCE', + 100: 'SDMA_PERF_SEL_CE_CH_WR_REQ', + 101: 'SDMA_PERF_SEL_CE_CH_WR_RET', + 102: 'SDMA_PERF_SEL_F32_CH_WR_REQ', + 103: 'SDMA_PERF_SEL_F32_CH_WR_RET', + 104: 'SDMA_PERF_SEL_CE_OR_F32_CH_RD_REQ', + 105: 'SDMA_PERF_SEL_CE_OR_F32_CH_RD_RET', + 106: 'SDMA_PERF_SEL_RB_CH_RD_REQ', + 107: 'SDMA_PERF_SEL_RB_CH_RD_RET', + 108: 'SDMA_PERF_SEL_IB_CH_RD_REQ', + 109: 'SDMA_PERF_SEL_IB_CH_RD_RET', + 110: 'SDMA_PERF_SEL_WPTR_CH_RD_REQ', + 111: 'SDMA_PERF_SEL_WPTR_CH_RD_RET', + 112: 'SDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 113: 'SDMA_PERF_SEL_UTCL1_UTCL2_RET', + 114: 'SDMA_PERF_SEL_CMD_OP_MATCH', + 115: 'SDMA_PERF_SEL_CMD_OP_START', + 116: 'SDMA_PERF_SEL_CMD_OP_END', + 117: 'SDMA_PERF_SEL_CE_BUSY', + 118: 'SDMA_PERF_SEL_CE_BUSY_START', + 119: 'SDMA_PERF_SEL_CE_BUSY_END', + 120: 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 121: 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 122: 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 123: 'SDMA_PERF_SEL_CE_CH_WRREQ_SEND', + 124: 'SDMA_PERF_SEL_CH_CE_WRRET_VALID', + 125: 'SDMA_PERF_SEL_CE_CH_RDREQ_SEND', + 126: 'SDMA_PERF_SEL_CH_CE_RDRET_VALID', +} +SDMA_PERF_SEL_CYCLE = 0 +SDMA_PERF_SEL_IDLE = 1 +SDMA_PERF_SEL_REG_IDLE = 2 +SDMA_PERF_SEL_RB_EMPTY = 3 +SDMA_PERF_SEL_RB_FULL = 4 +SDMA_PERF_SEL_RB_WPTR_WRAP = 5 +SDMA_PERF_SEL_RB_RPTR_WRAP = 6 +SDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERF_SEL_RB_RPTR_WB = 8 +SDMA_PERF_SEL_RB_CMD_IDLE = 9 +SDMA_PERF_SEL_RB_CMD_FULL = 10 +SDMA_PERF_SEL_IB_CMD_IDLE = 11 +SDMA_PERF_SEL_IB_CMD_FULL = 12 +SDMA_PERF_SEL_EX_IDLE = 13 +SDMA_PERF_SEL_SRBM_REG_SEND = 14 +SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERF_SEL_MC_WR_IDLE = 16 +SDMA_PERF_SEL_MC_WR_COUNT = 17 +SDMA_PERF_SEL_MC_RD_IDLE = 18 +SDMA_PERF_SEL_MC_RD_COUNT = 19 +SDMA_PERF_SEL_MC_RD_RET_STALL = 20 +SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +SDMA_PERF_SEL_SEM_IDLE = 24 +SDMA_PERF_SEL_SEM_REQ_STALL = 25 +SDMA_PERF_SEL_SEM_REQ_COUNT = 26 +SDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +SDMA_PERF_SEL_SEM_RESP_FAIL = 28 +SDMA_PERF_SEL_SEM_RESP_PASS = 29 +SDMA_PERF_SEL_INT_IDLE = 30 +SDMA_PERF_SEL_INT_REQ_STALL = 31 +SDMA_PERF_SEL_INT_REQ_COUNT = 32 +SDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +SDMA_PERF_SEL_INT_RESP_RETRY = 34 +SDMA_PERF_SEL_NUM_PACKET = 35 +SDMA_PERF_SEL_CE_WREQ_IDLE = 37 +SDMA_PERF_SEL_CE_WR_IDLE = 38 +SDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +SDMA_PERF_SEL_CE_RREQ_IDLE = 40 +SDMA_PERF_SEL_CE_OUT_IDLE = 41 +SDMA_PERF_SEL_CE_IN_IDLE = 42 +SDMA_PERF_SEL_CE_DST_IDLE = 43 +SDMA_PERF_SEL_CE_AFIFO_FULL = 46 +SDMA_PERF_SEL_CE_INFO_FULL = 49 +SDMA_PERF_SEL_CE_INFO1_FULL = 50 +SDMA_PERF_SEL_CE_RD_STALL = 51 +SDMA_PERF_SEL_CE_WR_STALL = 52 +SDMA_PERF_SEL_GFX_SELECT = 53 +SDMA_PERF_SEL_RLC0_SELECT = 54 +SDMA_PERF_SEL_RLC1_SELECT = 55 +SDMA_PERF_SEL_PAGE_SELECT = 56 +SDMA_PERF_SEL_CTX_CHANGE = 57 +SDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +SDMA_PERF_SEL_DOORBELL = 60 +SDMA_PERF_SEL_RD_BA_RTR = 61 +SDMA_PERF_SEL_WR_BA_RTR = 62 +SDMA_PERF_SEL_F32_L1_WR_VLD = 63 +SDMA_PERF_SEL_CE_L1_WR_VLD = 64 +SDMA_PERF_SEL_CPF_SDMA_INVREQ = 65 +SDMA_PERF_SEL_SDMA_CPF_INVACK = 66 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ = 67 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK = 68 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL = 69 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL = 70 +SDMA_PERF_SEL_UTCL2_RET_XNACK = 71 +SDMA_PERF_SEL_UTCL2_RET_ACK = 72 +SDMA_PERF_SEL_UTCL2_FREE = 73 +SDMA_PERF_SEL_SDMA_UTCL2_SEND = 74 +SDMA_PERF_SEL_DMA_L1_WR_SEND = 75 +SDMA_PERF_SEL_DMA_L1_RD_SEND = 76 +SDMA_PERF_SEL_DMA_MC_WR_SEND = 77 +SDMA_PERF_SEL_DMA_MC_RD_SEND = 78 +SDMA_PERF_SEL_GPUVM_INV_HIGH = 79 +SDMA_PERF_SEL_GPUVM_INV_LOW = 80 +SDMA_PERF_SEL_L1_WRL2_IDLE = 81 +SDMA_PERF_SEL_L1_RDL2_IDLE = 82 +SDMA_PERF_SEL_L1_WRMC_IDLE = 83 +SDMA_PERF_SEL_L1_RDMC_IDLE = 84 +SDMA_PERF_SEL_L1_WR_INV_IDLE = 85 +SDMA_PERF_SEL_L1_RD_INV_IDLE = 86 +SDMA_PERF_SEL_META_L2_REQ_SEND = 87 +SDMA_PERF_SEL_L2_META_RET_VLD = 88 +SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND = 89 +SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN = 90 +SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND = 91 +SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN = 92 +SDMA_PERF_SEL_META_REQ_SEND = 93 +SDMA_PERF_SEL_META_RTN_VLD = 94 +SDMA_PERF_SEL_TLBI_SEND = 95 +SDMA_PERF_SEL_TLBI_RTN = 96 +SDMA_PERF_SEL_GCR_SEND = 97 +SDMA_PERF_SEL_GCR_RTN = 98 +SDMA_PERF_SEL_CGCG_FENCE = 99 +SDMA_PERF_SEL_CE_CH_WR_REQ = 100 +SDMA_PERF_SEL_CE_CH_WR_RET = 101 +SDMA_PERF_SEL_F32_CH_WR_REQ = 102 +SDMA_PERF_SEL_F32_CH_WR_RET = 103 +SDMA_PERF_SEL_CE_OR_F32_CH_RD_REQ = 104 +SDMA_PERF_SEL_CE_OR_F32_CH_RD_RET = 105 +SDMA_PERF_SEL_RB_CH_RD_REQ = 106 +SDMA_PERF_SEL_RB_CH_RD_RET = 107 +SDMA_PERF_SEL_IB_CH_RD_REQ = 108 +SDMA_PERF_SEL_IB_CH_RD_RET = 109 +SDMA_PERF_SEL_WPTR_CH_RD_REQ = 110 +SDMA_PERF_SEL_WPTR_CH_RD_RET = 111 +SDMA_PERF_SEL_UTCL1_UTCL2_REQ = 112 +SDMA_PERF_SEL_UTCL1_UTCL2_RET = 113 +SDMA_PERF_SEL_CMD_OP_MATCH = 114 +SDMA_PERF_SEL_CMD_OP_START = 115 +SDMA_PERF_SEL_CMD_OP_END = 116 +SDMA_PERF_SEL_CE_BUSY = 117 +SDMA_PERF_SEL_CE_BUSY_START = 118 +SDMA_PERF_SEL_CE_BUSY_END = 119 +SDMA_PERF_SEL_F32_PERFCNT_TRIGGER = 120 +SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START = 121 +SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END = 122 +SDMA_PERF_SEL_CE_CH_WRREQ_SEND = 123 +SDMA_PERF_SEL_CH_CE_WRRET_VALID = 124 +SDMA_PERF_SEL_CE_CH_RDREQ_SEND = 125 +SDMA_PERF_SEL_CH_CE_RDRET_VALID = 126 +SDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_CACHE_POLICIES' +TCC_CACHE_POLICIES__enumvalues = { + 0: 'TCC_CACHE_POLICY_LRU', + 1: 'TCC_CACHE_POLICY_STREAM', +} +TCC_CACHE_POLICY_LRU = 0 +TCC_CACHE_POLICY_STREAM = 1 +TCC_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_MTYPE' +TCC_MTYPE__enumvalues = { + 0: 'MTYPE_NC', + 1: 'MTYPE_WC', + 2: 'MTYPE_CC', +} +MTYPE_NC = 0 +MTYPE_WC = 1 +MTYPE_CC = 2 +TCC_MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0FaultType' +UTCL0FaultType__enumvalues = { + 0: 'UTCL0_XNACK_SUCCESS', + 1: 'UTCL0_XNACK_RETRY', + 2: 'UTCL0_XNACK_PRT', + 3: 'UTCL0_XNACK_NO_RETRY', +} +UTCL0_XNACK_SUCCESS = 0 +UTCL0_XNACK_RETRY = 1 +UTCL0_XNACK_PRT = 2 +UTCL0_XNACK_NO_RETRY = 3 +UTCL0FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0RequestType' +UTCL0RequestType__enumvalues = { + 0: 'UTCL0_TYPE_NORMAL', + 1: 'UTCL0_TYPE_SHOOTDOWN', + 2: 'UTCL0_TYPE_BYPASS', +} +UTCL0_TYPE_NORMAL = 0 +UTCL0_TYPE_SHOOTDOWN = 1 +UTCL0_TYPE_BYPASS = 2 +UTCL0RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1FaultType' +UTCL1FaultType__enumvalues = { + 0: 'UTCL1_XNACK_SUCCESS', + 1: 'UTCL1_XNACK_RETRY', + 2: 'UTCL1_XNACK_PRT', + 3: 'UTCL1_XNACK_NO_RETRY', +} +UTCL1_XNACK_SUCCESS = 0 +UTCL1_XNACK_RETRY = 1 +UTCL1_XNACK_PRT = 2 +UTCL1_XNACK_NO_RETRY = 3 +UTCL1FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1RequestType' +UTCL1RequestType__enumvalues = { + 0: 'UTCL1_TYPE_NORMAL', + 1: 'UTCL1_TYPE_SHOOTDOWN', + 2: 'UTCL1_TYPE_BYPASS', +} +UTCL1_TYPE_NORMAL = 0 +UTCL1_TYPE_SHOOTDOWN = 1 +UTCL1_TYPE_BYPASS = 2 +UTCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'VMEMCMD_RETURN_ORDER' +VMEMCMD_RETURN_ORDER__enumvalues = { + 0: 'VMEMCMD_RETURN_OUT_OF_ORDER', + 1: 'VMEMCMD_RETURN_IN_ORDER', + 2: 'VMEMCMD_RETURN_IN_ORDER_READ', +} +VMEMCMD_RETURN_OUT_OF_ORDER = 0 +VMEMCMD_RETURN_IN_ORDER = 1 +VMEMCMD_RETURN_IN_ORDER_READ = 2 +VMEMCMD_RETURN_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'WritePolicy' +WritePolicy__enumvalues = { + 0: 'CACHE_LRU_WR', + 1: 'CACHE_STREAM', + 2: 'CACHE_NOA_WR', + 3: 'CACHE_BYPASS', +} +CACHE_LRU_WR = 0 +CACHE_STREAM = 1 +CACHE_NOA_WR = 2 +CACHE_BYPASS = 3 +WritePolicy = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_BYPASS' +CNVC_BYPASS__enumvalues = { + 0: 'CNVC_BYPASS_DISABLE', + 1: 'CNVC_BYPASS_EN', +} +CNVC_BYPASS_DISABLE = 0 +CNVC_BYPASS_EN = 1 +CNVC_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_COEF_FORMAT_ENUM' +CNVC_COEF_FORMAT_ENUM__enumvalues = { + 0: 'CNVC_FIX_S2_13', + 1: 'CNVC_FIX_S3_12', +} +CNVC_FIX_S2_13 = 0 +CNVC_FIX_S3_12 = 1 +CNVC_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_ENABLE' +CNVC_ENABLE__enumvalues = { + 0: 'CNVC_DIS', + 1: 'CNVC_EN', +} +CNVC_DIS = 0 +CNVC_EN = 1 +CNVC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CNVC_PENDING' +CNVC_PENDING__enumvalues = { + 0: 'CNVC_NOT_PENDING', + 1: 'CNVC_YES_PENDING', +} +CNVC_NOT_PENDING = 0 +CNVC_YES_PENDING = 1 +CNVC_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'COLOR_KEYER_MODE' +COLOR_KEYER_MODE__enumvalues = { + 0: 'FORCE_00', + 1: 'FORCE_FF', + 2: 'RANGE_00', + 3: 'RANGE_FF', +} +FORCE_00 = 0 +FORCE_FF = 1 +RANGE_00 = 2 +RANGE_FF = 3 +COLOR_KEYER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DENORM_TRUNCATE' +DENORM_TRUNCATE__enumvalues = { + 0: 'CNVC_ROUND', + 1: 'CNVC_TRUNCATE', +} +CNVC_ROUND = 0 +CNVC_TRUNCATE = 1 +DENORM_TRUNCATE = ctypes.c_uint32 # enum + +# values for enumeration 'FORMAT_CROSSBAR' +FORMAT_CROSSBAR__enumvalues = { + 0: 'FORMAT_CROSSBAR_R', + 1: 'FORMAT_CROSSBAR_G', + 2: 'FORMAT_CROSSBAR_B', +} +FORMAT_CROSSBAR_R = 0 +FORMAT_CROSSBAR_G = 1 +FORMAT_CROSSBAR_B = 2 +FORMAT_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'PIX_EXPAND_MODE' +PIX_EXPAND_MODE__enumvalues = { + 0: 'PIX_DYNAMIC_EXPANSION', + 1: 'PIX_ZERO_EXPANSION', +} +PIX_DYNAMIC_EXPANSION = 0 +PIX_ZERO_EXPANSION = 1 +PIX_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_CSC_MODE_ENUM' +PRE_CSC_MODE_ENUM__enumvalues = { + 0: 'PRE_CSC_BYPASS', + 1: 'PRE_CSC_SET_A', + 2: 'PRE_CSC_SET_B', +} +PRE_CSC_BYPASS = 0 +PRE_CSC_SET_A = 1 +PRE_CSC_SET_B = 2 +PRE_CSC_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_DEGAM_MODE' +PRE_DEGAM_MODE__enumvalues = { + 0: 'PRE_DEGAM_BYPASS', + 1: 'PRE_DEGAM_ENABLE', +} +PRE_DEGAM_BYPASS = 0 +PRE_DEGAM_ENABLE = 1 +PRE_DEGAM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_DEGAM_SELECT' +PRE_DEGAM_SELECT__enumvalues = { + 0: 'PRE_DEGAM_SRGB', + 1: 'PRE_DEGAM_GAMMA_22', + 2: 'PRE_DEGAM_GAMMA_24', + 3: 'PRE_DEGAM_GAMMA_26', + 4: 'PRE_DEGAM_BT2020', + 5: 'PRE_DEGAM_BT2100PQ', + 6: 'PRE_DEGAM_BT2100HLG', +} +PRE_DEGAM_SRGB = 0 +PRE_DEGAM_GAMMA_22 = 1 +PRE_DEGAM_GAMMA_24 = 2 +PRE_DEGAM_GAMMA_26 = 3 +PRE_DEGAM_BT2020 = 4 +PRE_DEGAM_BT2100PQ = 5 +PRE_DEGAM_BT2100HLG = 6 +PRE_DEGAM_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_PIXEL_FORMAT' +SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'ARGB1555', + 2: 'RGBA5551', + 3: 'RGB565', + 4: 'BGR565', + 5: 'ARGB4444', + 6: 'RGBA4444', + 8: 'ARGB8888', + 9: 'RGBA8888', + 10: 'ARGB2101010', + 11: 'RGBA1010102', + 12: 'AYCrCb8888', + 13: 'YCrCbA8888', + 14: 'ACrYCb8888', + 15: 'CrYCbA8888', + 16: 'ARGB16161616_10MSB', + 17: 'RGBA16161616_10MSB', + 18: 'ARGB16161616_10LSB', + 19: 'RGBA16161616_10LSB', + 20: 'ARGB16161616_12MSB', + 21: 'RGBA16161616_12MSB', + 22: 'ARGB16161616_12LSB', + 23: 'RGBA16161616_12LSB', + 24: 'ARGB16161616_FLOAT', + 25: 'RGBA16161616_FLOAT', + 26: 'ARGB16161616_UNORM', + 27: 'RGBA16161616_UNORM', + 28: 'ARGB16161616_SNORM', + 29: 'RGBA16161616_SNORM', + 32: 'AYCrCb16161616_10MSB', + 33: 'AYCrCb16161616_10LSB', + 34: 'YCrCbA16161616_10MSB', + 35: 'YCrCbA16161616_10LSB', + 36: 'ACrYCb16161616_10MSB', + 37: 'ACrYCb16161616_10LSB', + 38: 'CrYCbA16161616_10MSB', + 39: 'CrYCbA16161616_10LSB', + 40: 'AYCrCb16161616_12MSB', + 41: 'AYCrCb16161616_12LSB', + 42: 'YCrCbA16161616_12MSB', + 43: 'YCrCbA16161616_12LSB', + 44: 'ACrYCb16161616_12MSB', + 45: 'ACrYCb16161616_12LSB', + 46: 'CrYCbA16161616_12MSB', + 47: 'CrYCbA16161616_12LSB', + 64: 'Y8_CrCb88_420_PLANAR', + 65: 'Y8_CbCr88_420_PLANAR', + 66: 'Y10_CrCb1010_420_PLANAR', + 67: 'Y10_CbCr1010_420_PLANAR', + 68: 'Y12_CrCb1212_420_PLANAR', + 69: 'Y12_CbCr1212_420_PLANAR', + 72: 'YCrYCb8888_422_PACKED', + 73: 'YCbYCr8888_422_PACKED', + 74: 'CrYCbY8888_422_PACKED', + 75: 'CbYCrY8888_422_PACKED', + 76: 'YCrYCb10101010_422_PACKED', + 77: 'YCbYCr10101010_422_PACKED', + 78: 'CrYCbY10101010_422_PACKED', + 79: 'CbYCrY10101010_422_PACKED', + 80: 'YCrYCb12121212_422_PACKED', + 81: 'YCbYCr12121212_422_PACKED', + 82: 'CrYCbY12121212_422_PACKED', + 83: 'CbYCrY12121212_422_PACKED', + 112: 'RGB111110_FIX', + 113: 'BGR101111_FIX', + 114: 'ACrYCb2101010', + 115: 'CrYCbA1010102', + 116: 'RGBE', + 118: 'RGB111110_FLOAT', + 119: 'BGR101111_FLOAT', + 120: 'MONO_8', + 121: 'MONO_10MSB', + 122: 'MONO_10LSB', + 123: 'MONO_12MSB', + 124: 'MONO_12LSB', + 125: 'MONO_16', +} +ARGB1555 = 1 +RGBA5551 = 2 +RGB565 = 3 +BGR565 = 4 +ARGB4444 = 5 +RGBA4444 = 6 +ARGB8888 = 8 +RGBA8888 = 9 +ARGB2101010 = 10 +RGBA1010102 = 11 +AYCrCb8888 = 12 +YCrCbA8888 = 13 +ACrYCb8888 = 14 +CrYCbA8888 = 15 +ARGB16161616_10MSB = 16 +RGBA16161616_10MSB = 17 +ARGB16161616_10LSB = 18 +RGBA16161616_10LSB = 19 +ARGB16161616_12MSB = 20 +RGBA16161616_12MSB = 21 +ARGB16161616_12LSB = 22 +RGBA16161616_12LSB = 23 +ARGB16161616_FLOAT = 24 +RGBA16161616_FLOAT = 25 +ARGB16161616_UNORM = 26 +RGBA16161616_UNORM = 27 +ARGB16161616_SNORM = 28 +RGBA16161616_SNORM = 29 +AYCrCb16161616_10MSB = 32 +AYCrCb16161616_10LSB = 33 +YCrCbA16161616_10MSB = 34 +YCrCbA16161616_10LSB = 35 +ACrYCb16161616_10MSB = 36 +ACrYCb16161616_10LSB = 37 +CrYCbA16161616_10MSB = 38 +CrYCbA16161616_10LSB = 39 +AYCrCb16161616_12MSB = 40 +AYCrCb16161616_12LSB = 41 +YCrCbA16161616_12MSB = 42 +YCrCbA16161616_12LSB = 43 +ACrYCb16161616_12MSB = 44 +ACrYCb16161616_12LSB = 45 +CrYCbA16161616_12MSB = 46 +CrYCbA16161616_12LSB = 47 +Y8_CrCb88_420_PLANAR = 64 +Y8_CbCr88_420_PLANAR = 65 +Y10_CrCb1010_420_PLANAR = 66 +Y10_CbCr1010_420_PLANAR = 67 +Y12_CrCb1212_420_PLANAR = 68 +Y12_CbCr1212_420_PLANAR = 69 +YCrYCb8888_422_PACKED = 72 +YCbYCr8888_422_PACKED = 73 +CrYCbY8888_422_PACKED = 74 +CbYCrY8888_422_PACKED = 75 +YCrYCb10101010_422_PACKED = 76 +YCbYCr10101010_422_PACKED = 77 +CrYCbY10101010_422_PACKED = 78 +CbYCrY10101010_422_PACKED = 79 +YCrYCb12121212_422_PACKED = 80 +YCbYCr12121212_422_PACKED = 81 +CrYCbY12121212_422_PACKED = 82 +CbYCrY12121212_422_PACKED = 83 +RGB111110_FIX = 112 +BGR101111_FIX = 113 +ACrYCb2101010 = 114 +CrYCbA1010102 = 115 +RGBE = 116 +RGB111110_FLOAT = 118 +BGR101111_FLOAT = 119 +MONO_8 = 120 +MONO_10MSB = 121 +MONO_10LSB = 122 +MONO_12MSB = 123 +MONO_12LSB = 124 +MONO_16 = 125 +SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'XNORM' +XNORM__enumvalues = { + 0: 'XNORM_A', + 1: 'XNORM_B', +} +XNORM_A = 0 +XNORM_B = 1 +XNORM = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ENABLE' +CUR_ENABLE__enumvalues = { + 0: 'CUR_DIS', + 1: 'CUR_EN', +} +CUR_DIS = 0 +CUR_EN = 1 +CUR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_EXPAND_MODE' +CUR_EXPAND_MODE__enumvalues = { + 0: 'CUR_DYNAMIC_EXPANSION', + 1: 'CUR_ZERO_EXPANSION', +} +CUR_DYNAMIC_EXPANSION = 0 +CUR_ZERO_EXPANSION = 1 +CUR_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_INV_CLAMP' +CUR_INV_CLAMP__enumvalues = { + 0: 'CUR_CLAMP_DIS', + 1: 'CUR_CLAMP_EN', +} +CUR_CLAMP_DIS = 0 +CUR_CLAMP_EN = 1 +CUR_INV_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_MODE' +CUR_MODE__enumvalues = { + 0: 'MONO_2BIT', + 1: 'COLOR_24BIT_1BIT_AND', + 2: 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'COLOR_64BIT_FP_PREMULT', + 5: 'COLOR_64BIT_FP_UNPREMULT', +} +MONO_2BIT = 0 +COLOR_24BIT_1BIT_AND = 1 +COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +COLOR_64BIT_FP_PREMULT = 4 +COLOR_64BIT_FP_UNPREMULT = 5 +CUR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_PENDING' +CUR_PENDING__enumvalues = { + 0: 'CUR_NOT_PENDING', + 1: 'CUR_YES_PENDING', +} +CUR_NOT_PENDING = 0 +CUR_YES_PENDING = 1 +CUR_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ROM_EN' +CUR_ROM_EN__enumvalues = { + 0: 'CUR_FP_NO_ROM', + 1: 'CUR_FP_USE_ROM', +} +CUR_FP_NO_ROM = 0 +CUR_FP_USE_ROM = 1 +CUR_ROM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'COEF_RAM_SELECT_RD' +COEF_RAM_SELECT_RD__enumvalues = { + 0: 'COEF_RAM_SELECT_BACK', + 1: 'COEF_RAM_SELECT_CURRENT', +} +COEF_RAM_SELECT_BACK = 0 +COEF_RAM_SELECT_CURRENT = 1 +COEF_RAM_SELECT_RD = ctypes.c_uint32 # enum + +# values for enumeration 'DSCL_MODE_SEL' +DSCL_MODE_SEL__enumvalues = { + 0: 'DSCL_MODE_SCALING_444_BYPASS', + 1: 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 2: 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 3: 'DSCL_MODE_SCALING_YCBCR_ENABLE', + 4: 'DSCL_MODE_LUMA_SCALING_BYPASS', + 5: 'DSCL_MODE_CHROMA_SCALING_BYPASS', + 6: 'DSCL_MODE_DSCL_BYPASS', +} +DSCL_MODE_SCALING_444_BYPASS = 0 +DSCL_MODE_SCALING_444_RGB_ENABLE = 1 +DSCL_MODE_SCALING_444_YCBCR_ENABLE = 2 +DSCL_MODE_SCALING_YCBCR_ENABLE = 3 +DSCL_MODE_LUMA_SCALING_BYPASS = 4 +DSCL_MODE_CHROMA_SCALING_BYPASS = 5 +DSCL_MODE_DSCL_BYPASS = 6 +DSCL_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'LB_ALPHA_EN' +LB_ALPHA_EN__enumvalues = { + 0: 'LB_ALPHA_DISABLE', + 1: 'LB_ALPHA_ENABLE', +} +LB_ALPHA_DISABLE = 0 +LB_ALPHA_ENABLE = 1 +LB_ALPHA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERLEAVE_EN' +LB_INTERLEAVE_EN__enumvalues = { + 0: 'LB_INTERLEAVE_DISABLE', + 1: 'LB_INTERLEAVE_ENABLE', +} +LB_INTERLEAVE_DISABLE = 0 +LB_INTERLEAVE_ENABLE = 1 +LB_INTERLEAVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MEMORY_CONFIG' +LB_MEMORY_CONFIG__enumvalues = { + 0: 'LB_MEMORY_CONFIG_0', + 1: 'LB_MEMORY_CONFIG_1', + 2: 'LB_MEMORY_CONFIG_2', + 3: 'LB_MEMORY_CONFIG_3', +} +LB_MEMORY_CONFIG_0 = 0 +LB_MEMORY_CONFIG_1 = 1 +LB_MEMORY_CONFIG_2 = 2 +LB_MEMORY_CONFIG_3 = 3 +LB_MEMORY_CONFIG = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_BYPASS_SEL' +OBUF_BYPASS_SEL__enumvalues = { + 0: 'OBUF_BYPASS_DIS', + 1: 'OBUF_BYPASS_EN', +} +OBUF_BYPASS_DIS = 0 +OBUF_BYPASS_EN = 1 +OBUF_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_IS_HALF_RECOUT_WIDTH_SEL' +OBUF_IS_HALF_RECOUT_WIDTH_SEL__enumvalues = { + 0: 'OBUF_FULL_RECOUT', + 1: 'OBUF_HALF_RECOUT', +} +OBUF_FULL_RECOUT = 0 +OBUF_HALF_RECOUT = 1 +OBUF_IS_HALF_RECOUT_WIDTH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_USE_FULL_BUFFER_SEL' +OBUF_USE_FULL_BUFFER_SEL__enumvalues = { + 0: 'OBUF_RECOUT', + 1: 'OBUF_FULL', +} +OBUF_RECOUT = 0 +OBUF_FULL = 1 +OBUF_USE_FULL_BUFFER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_2TAP_HARDCODE' +SCL_2TAP_HARDCODE__enumvalues = { + 0: 'SCL_COEF_2TAP_HARDCODE_OFF', + 1: 'SCL_COEF_2TAP_HARDCODE_ON', +} +SCL_COEF_2TAP_HARDCODE_OFF = 0 +SCL_COEF_2TAP_HARDCODE_ON = 1 +SCL_2TAP_HARDCODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_ALPHA_COEF' +SCL_ALPHA_COEF__enumvalues = { + 0: 'SCL_ALPHA_COEF_FIRST', + 1: 'SCL_ALPHA_COEF_SECOND', +} +SCL_ALPHA_COEF_FIRST = 0 +SCL_ALPHA_COEF_SECOND = 1 +SCL_ALPHA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_AUTOCAL_MODE' +SCL_AUTOCAL_MODE__enumvalues = { + 0: 'AUTOCAL_MODE_OFF', + 1: 'AUTOCAL_MODE_AUTOSCALE', + 2: 'AUTOCAL_MODE_AUTOCENTER', + 3: 'AUTOCAL_MODE_AUTOREPLICATE', +} +AUTOCAL_MODE_OFF = 0 +AUTOCAL_MODE_AUTOSCALE = 1 +AUTOCAL_MODE_AUTOCENTER = 2 +AUTOCAL_MODE_AUTOREPLICATE = 3 +SCL_AUTOCAL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_BOUNDARY' +SCL_BOUNDARY__enumvalues = { + 0: 'SCL_BOUNDARY_EDGE', + 1: 'SCL_BOUNDARY_BLACK', +} +SCL_BOUNDARY_EDGE = 0 +SCL_BOUNDARY_BLACK = 1 +SCL_BOUNDARY = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_CHROMA_COEF' +SCL_CHROMA_COEF__enumvalues = { + 0: 'SCL_CHROMA_COEF_FIRST', + 1: 'SCL_CHROMA_COEF_SECOND', +} +SCL_CHROMA_COEF_FIRST = 0 +SCL_CHROMA_COEF_SECOND = 1 +SCL_CHROMA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_FILTER_TYPE_SEL' +SCL_COEF_FILTER_TYPE_SEL__enumvalues = { + 0: 'SCL_COEF_LUMA_VERT_FILTER', + 1: 'SCL_COEF_LUMA_HORZ_FILTER', + 2: 'SCL_COEF_CHROMA_VERT_FILTER', + 3: 'SCL_COEF_CHROMA_HORZ_FILTER', +} +SCL_COEF_LUMA_VERT_FILTER = 0 +SCL_COEF_LUMA_HORZ_FILTER = 1 +SCL_COEF_CHROMA_VERT_FILTER = 2 +SCL_COEF_CHROMA_HORZ_FILTER = 3 +SCL_COEF_FILTER_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_RAM_SEL' +SCL_COEF_RAM_SEL__enumvalues = { + 0: 'SCL_COEF_RAM_SEL_0', + 1: 'SCL_COEF_RAM_SEL_1', +} +SCL_COEF_RAM_SEL_0 = 0 +SCL_COEF_RAM_SEL_1 = 1 +SCL_COEF_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_SHARP_EN' +SCL_SHARP_EN__enumvalues = { + 0: 'SCL_SHARP_DISABLE', + 1: 'SCL_SHARP_ENABLE', +} +SCL_SHARP_DISABLE = 0 +SCL_SHARP_ENABLE = 1 +SCL_SHARP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_30BIT_ENUM' +CMC_3DLUT_30BIT_ENUM__enumvalues = { + 0: 'CMC_3DLUT_36BIT', + 1: 'CMC_3DLUT_30BIT', +} +CMC_3DLUT_36BIT = 0 +CMC_3DLUT_30BIT = 1 +CMC_3DLUT_30BIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_RAM_SEL' +CMC_3DLUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAM0_ACCESS', + 1: 'CMC_RAM1_ACCESS', + 2: 'CMC_RAM2_ACCESS', + 3: 'CMC_RAM3_ACCESS', +} +CMC_RAM0_ACCESS = 0 +CMC_RAM1_ACCESS = 1 +CMC_RAM2_ACCESS = 2 +CMC_RAM3_ACCESS = 3 +CMC_3DLUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_SIZE_ENUM' +CMC_3DLUT_SIZE_ENUM__enumvalues = { + 0: 'CMC_3DLUT_17CUBE', + 1: 'CMC_3DLUT_9CUBE', +} +CMC_3DLUT_17CUBE = 0 +CMC_3DLUT_9CUBE = 1 +CMC_3DLUT_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_CONFIG_ENUM' +CMC_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'CMC_LUT_2CFG_NO_MEMORY', + 1: 'CMC_LUT_2CFG_MEMORY_A', + 2: 'CMC_LUT_2CFG_MEMORY_B', +} +CMC_LUT_2CFG_NO_MEMORY = 0 +CMC_LUT_2CFG_MEMORY_A = 1 +CMC_LUT_2CFG_MEMORY_B = 2 +CMC_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_MODE_ENUM' +CMC_LUT_2_MODE_ENUM__enumvalues = { + 0: 'CMC_LUT_2_MODE_BYPASS', + 1: 'CMC_LUT_2_MODE_RAMA_LUT', + 2: 'CMC_LUT_2_MODE_RAMB_LUT', +} +CMC_LUT_2_MODE_BYPASS = 0 +CMC_LUT_2_MODE_RAMA_LUT = 1 +CMC_LUT_2_MODE_RAMB_LUT = 2 +CMC_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_NUM_SEG' +CMC_LUT_NUM_SEG__enumvalues = { + 0: 'CMC_SEGMENTS_1', + 1: 'CMC_SEGMENTS_2', + 2: 'CMC_SEGMENTS_4', + 3: 'CMC_SEGMENTS_8', + 4: 'CMC_SEGMENTS_16', + 5: 'CMC_SEGMENTS_32', + 6: 'CMC_SEGMENTS_64', + 7: 'CMC_SEGMENTS_128', +} +CMC_SEGMENTS_1 = 0 +CMC_SEGMENTS_2 = 1 +CMC_SEGMENTS_4 = 2 +CMC_SEGMENTS_8 = 3 +CMC_SEGMENTS_16 = 4 +CMC_SEGMENTS_32 = 5 +CMC_SEGMENTS_64 = 6 +CMC_SEGMENTS_128 = 7 +CMC_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_RAM_SEL' +CMC_LUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAMA_ACCESS', + 1: 'CMC_RAMB_ACCESS', +} +CMC_RAMA_ACCESS = 0 +CMC_RAMB_ACCESS = 1 +CMC_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_BYPASS' +CM_BYPASS__enumvalues = { + 0: 'NON_BYPASS', + 1: 'BYPASS_EN', +} +NON_BYPASS = 0 +BYPASS_EN = 1 +CM_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CM_COEF_FORMAT_ENUM' +CM_COEF_FORMAT_ENUM__enumvalues = { + 0: 'FIX_S2_13', + 1: 'FIX_S3_12', +} +FIX_S2_13 = 0 +FIX_S3_12 = 1 +CM_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_DATA_SIGNED' +CM_DATA_SIGNED__enumvalues = { + 0: 'UNSIGNED', + 1: 'SIGNED', +} +UNSIGNED = 0 +SIGNED = 1 +CM_DATA_SIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'CM_EN' +CM_EN__enumvalues = { + 0: 'CM_DISABLE', + 1: 'CM_ENABLE', +} +CM_DISABLE = 0 +CM_ENABLE = 1 +CM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_MODE_ENUM' +CM_GAMMA_LUT_MODE_ENUM__enumvalues = { + 0: 'BYPASS', + 1: 'RESERVED_1', + 2: 'RAM_LUT', + 3: 'RESERVED_3', +} +BYPASS = 0 +RESERVED_1 = 1 +RAM_LUT = 2 +RESERVED_3 = 3 +CM_GAMMA_LUT_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_PWL_DISABLE_ENUM' +CM_GAMMA_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'ENABLE_PWL', + 1: 'DISABLE_PWL', +} +ENABLE_PWL = 0 +DISABLE_PWL = 1 +CM_GAMMA_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_SEL_ENUM' +CM_GAMMA_LUT_SEL_ENUM__enumvalues = { + 0: 'RAMA', + 1: 'RAMB', +} +RAMA = 0 +RAMB = 1 +CM_GAMMA_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMUT_REMAP_MODE_ENUM' +CM_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'BYPASS_GAMUT', + 1: 'GAMUT_COEF', + 2: 'GAMUT_COEF_B', +} +BYPASS_GAMUT = 0 +GAMUT_COEF = 1 +GAMUT_COEF_B = 2 +CM_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_CONFIG_ENUM' +CM_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'LUT_2CFG_NO_MEMORY', + 1: 'LUT_2CFG_MEMORY_A', + 2: 'LUT_2CFG_MEMORY_B', +} +LUT_2CFG_NO_MEMORY = 0 +LUT_2CFG_MEMORY_A = 1 +LUT_2CFG_MEMORY_B = 2 +CM_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_MODE_ENUM' +CM_LUT_2_MODE_ENUM__enumvalues = { + 0: 'LUT_2_MODE_BYPASS', + 1: 'LUT_2_MODE_RAMA_LUT', + 2: 'LUT_2_MODE_RAMB_LUT', +} +LUT_2_MODE_BYPASS = 0 +LUT_2_MODE_RAMA_LUT = 1 +LUT_2_MODE_RAMB_LUT = 2 +CM_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_CONFIG_ENUM' +CM_LUT_4_CONFIG_ENUM__enumvalues = { + 0: 'LUT_4CFG_NO_MEMORY', + 1: 'LUT_4CFG_ROM_A', + 2: 'LUT_4CFG_ROM_B', + 3: 'LUT_4CFG_MEMORY_A', + 4: 'LUT_4CFG_MEMORY_B', +} +LUT_4CFG_NO_MEMORY = 0 +LUT_4CFG_ROM_A = 1 +LUT_4CFG_ROM_B = 2 +LUT_4CFG_MEMORY_A = 3 +LUT_4CFG_MEMORY_B = 4 +CM_LUT_4_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_MODE_ENUM' +CM_LUT_4_MODE_ENUM__enumvalues = { + 0: 'LUT_4_MODE_BYPASS', + 1: 'LUT_4_MODE_ROMA_LUT', + 2: 'LUT_4_MODE_ROMB_LUT', + 3: 'LUT_4_MODE_RAMA_LUT', + 4: 'LUT_4_MODE_RAMB_LUT', +} +LUT_4_MODE_BYPASS = 0 +LUT_4_MODE_ROMA_LUT = 1 +LUT_4_MODE_ROMB_LUT = 2 +LUT_4_MODE_RAMA_LUT = 3 +LUT_4_MODE_RAMB_LUT = 4 +CM_LUT_4_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_CONFIG_MODE' +CM_LUT_CONFIG_MODE__enumvalues = { + 0: 'DIFFERENT_RGB', + 1: 'ALL_USE_R', +} +DIFFERENT_RGB = 0 +ALL_USE_R = 1 +CM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_NUM_SEG' +CM_LUT_NUM_SEG__enumvalues = { + 0: 'SEGMENTS_1', + 1: 'SEGMENTS_2', + 2: 'SEGMENTS_4', + 3: 'SEGMENTS_8', + 4: 'SEGMENTS_16', + 5: 'SEGMENTS_32', + 6: 'SEGMENTS_64', + 7: 'SEGMENTS_128', +} +SEGMENTS_1 = 0 +SEGMENTS_2 = 1 +SEGMENTS_4 = 2 +SEGMENTS_8 = 3 +SEGMENTS_16 = 4 +SEGMENTS_32 = 5 +SEGMENTS_64 = 6 +SEGMENTS_128 = 7 +CM_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_RAM_SEL' +CM_LUT_RAM_SEL__enumvalues = { + 0: 'RAMA_ACCESS', + 1: 'RAMB_ACCESS', +} +RAMA_ACCESS = 0 +RAMB_ACCESS = 1 +CM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_READ_COLOR_SEL' +CM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'BLUE_LUT', + 1: 'GREEN_LUT', + 2: 'RED_LUT', +} +BLUE_LUT = 0 +GREEN_LUT = 1 +RED_LUT = 2 +CM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_READ_DBG' +CM_LUT_READ_DBG__enumvalues = { + 0: 'DISABLE_DEBUG', + 1: 'ENABLE_DEBUG', +} +DISABLE_DEBUG = 0 +ENABLE_DEBUG = 1 +CM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'CM_PENDING' +CM_PENDING__enumvalues = { + 0: 'CM_NOT_PENDING', + 1: 'CM_YES_PENDING', +} +CM_NOT_PENDING = 0 +CM_YES_PENDING = 1 +CM_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CM_POST_CSC_MODE_ENUM' +CM_POST_CSC_MODE_ENUM__enumvalues = { + 0: 'BYPASS_POST_CSC', + 1: 'COEF_POST_CSC', + 2: 'COEF_POST_CSC_B', +} +BYPASS_POST_CSC = 0 +COEF_POST_CSC = 1 +COEF_POST_CSC_B = 2 +CM_POST_CSC_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_WRITE_BASE_ONLY' +CM_WRITE_BASE_ONLY__enumvalues = { + 0: 'WRITE_BOTH', + 1: 'WRITE_BASE_ONLY', +} +WRITE_BOTH = 0 +WRITE_BASE_ONLY = 1 +CM_WRITE_BASE_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_CUR_SEL' +CRC_CUR_SEL__enumvalues = { + 0: 'CRC_CUR_0', + 1: 'CRC_CUR_1', +} +CRC_CUR_0 = 0 +CRC_CUR_1 = 1 +CRC_CUR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_INTERLACE_SEL' +CRC_INTERLACE_SEL__enumvalues = { + 0: 'CRC_INTERLACE_0', + 1: 'CRC_INTERLACE_1', + 2: 'CRC_INTERLACE_2', + 3: 'CRC_INTERLACE_3', +} +CRC_INTERLACE_0 = 0 +CRC_INTERLACE_1 = 1 +CRC_INTERLACE_2 = 2 +CRC_INTERLACE_3 = 3 +CRC_INTERLACE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_IN_CUR_SEL' +CRC_IN_CUR_SEL__enumvalues = { + 0: 'CRC_IN_CUR_0', + 1: 'CRC_IN_CUR_1', + 2: 'CRC_IN_CUR_2', + 3: 'CRC_IN_CUR_3', +} +CRC_IN_CUR_0 = 0 +CRC_IN_CUR_1 = 1 +CRC_IN_CUR_2 = 2 +CRC_IN_CUR_3 = 3 +CRC_IN_CUR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_IN_PIX_SEL' +CRC_IN_PIX_SEL__enumvalues = { + 0: 'CRC_IN_PIX_0', + 1: 'CRC_IN_PIX_1', + 2: 'CRC_IN_PIX_2', + 3: 'CRC_IN_PIX_3', + 4: 'CRC_IN_PIX_4', + 5: 'CRC_IN_PIX_5', + 6: 'CRC_IN_PIX_6', + 7: 'CRC_IN_PIX_7', +} +CRC_IN_PIX_0 = 0 +CRC_IN_PIX_1 = 1 +CRC_IN_PIX_2 = 2 +CRC_IN_PIX_3 = 3 +CRC_IN_PIX_4 = 4 +CRC_IN_PIX_5 = 5 +CRC_IN_PIX_6 = 6 +CRC_IN_PIX_7 = 7 +CRC_IN_PIX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_SRC_SEL' +CRC_SRC_SEL__enumvalues = { + 0: 'CRC_SRC_0', + 1: 'CRC_SRC_1', + 2: 'CRC_SRC_2', + 3: 'CRC_SRC_3', +} +CRC_SRC_0 = 0 +CRC_SRC_1 = 1 +CRC_SRC_2 = 2 +CRC_SRC_3 = 3 +CRC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_STEREO_SEL' +CRC_STEREO_SEL__enumvalues = { + 0: 'CRC_STEREO_0', + 1: 'CRC_STEREO_1', + 2: 'CRC_STEREO_2', + 3: 'CRC_STEREO_3', +} +CRC_STEREO_0 = 0 +CRC_STEREO_1 = 1 +CRC_STEREO_2 = 2 +CRC_STEREO_3 = 3 +CRC_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_SEL' +TEST_CLK_SEL__enumvalues = { + 0: 'TEST_CLK_SEL_0', + 1: 'TEST_CLK_SEL_1', + 2: 'TEST_CLK_SEL_2', + 3: 'TEST_CLK_SEL_3', + 4: 'TEST_CLK_SEL_4', + 5: 'TEST_CLK_SEL_5', + 6: 'TEST_CLK_SEL_6', + 7: 'TEST_CLK_SEL_7', +} +TEST_CLK_SEL_0 = 0 +TEST_CLK_SEL_1 = 1 +TEST_CLK_SEL_2 = 2 +TEST_CLK_SEL_3 = 3 +TEST_CLK_SEL_4 = 4 +TEST_CLK_SEL_5 = 5 +TEST_CLK_SEL_6 = 6 +TEST_CLK_SEL_7 = 7 +TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_ACTIVE' +PERFCOUNTER_ACTIVE__enumvalues = { + 0: 'PERFCOUNTER_IS_IDLE', + 1: 'PERFCOUNTER_IS_ACTIVE', +} +PERFCOUNTER_IS_IDLE = 0 +PERFCOUNTER_IS_ACTIVE = 1 +PERFCOUNTER_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT0_STATE' +PERFCOUNTER_CNT0_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT0_STATE_RESET', + 1: 'PERFCOUNTER_CNT0_STATE_START', + 2: 'PERFCOUNTER_CNT0_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT0_STATE_HW', +} +PERFCOUNTER_CNT0_STATE_RESET = 0 +PERFCOUNTER_CNT0_STATE_START = 1 +PERFCOUNTER_CNT0_STATE_FREEZE = 2 +PERFCOUNTER_CNT0_STATE_HW = 3 +PERFCOUNTER_CNT0_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT1_STATE' +PERFCOUNTER_CNT1_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT1_STATE_RESET', + 1: 'PERFCOUNTER_CNT1_STATE_START', + 2: 'PERFCOUNTER_CNT1_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT1_STATE_HW', +} +PERFCOUNTER_CNT1_STATE_RESET = 0 +PERFCOUNTER_CNT1_STATE_START = 1 +PERFCOUNTER_CNT1_STATE_FREEZE = 2 +PERFCOUNTER_CNT1_STATE_HW = 3 +PERFCOUNTER_CNT1_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT2_STATE' +PERFCOUNTER_CNT2_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT2_STATE_RESET', + 1: 'PERFCOUNTER_CNT2_STATE_START', + 2: 'PERFCOUNTER_CNT2_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT2_STATE_HW', +} +PERFCOUNTER_CNT2_STATE_RESET = 0 +PERFCOUNTER_CNT2_STATE_START = 1 +PERFCOUNTER_CNT2_STATE_FREEZE = 2 +PERFCOUNTER_CNT2_STATE_HW = 3 +PERFCOUNTER_CNT2_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT3_STATE' +PERFCOUNTER_CNT3_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT3_STATE_RESET', + 1: 'PERFCOUNTER_CNT3_STATE_START', + 2: 'PERFCOUNTER_CNT3_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT3_STATE_HW', +} +PERFCOUNTER_CNT3_STATE_RESET = 0 +PERFCOUNTER_CNT3_STATE_START = 1 +PERFCOUNTER_CNT3_STATE_FREEZE = 2 +PERFCOUNTER_CNT3_STATE_HW = 3 +PERFCOUNTER_CNT3_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT4_STATE' +PERFCOUNTER_CNT4_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT4_STATE_RESET', + 1: 'PERFCOUNTER_CNT4_STATE_START', + 2: 'PERFCOUNTER_CNT4_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT4_STATE_HW', +} +PERFCOUNTER_CNT4_STATE_RESET = 0 +PERFCOUNTER_CNT4_STATE_START = 1 +PERFCOUNTER_CNT4_STATE_FREEZE = 2 +PERFCOUNTER_CNT4_STATE_HW = 3 +PERFCOUNTER_CNT4_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT5_STATE' +PERFCOUNTER_CNT5_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT5_STATE_RESET', + 1: 'PERFCOUNTER_CNT5_STATE_START', + 2: 'PERFCOUNTER_CNT5_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT5_STATE_HW', +} +PERFCOUNTER_CNT5_STATE_RESET = 0 +PERFCOUNTER_CNT5_STATE_START = 1 +PERFCOUNTER_CNT5_STATE_FREEZE = 2 +PERFCOUNTER_CNT5_STATE_HW = 3 +PERFCOUNTER_CNT5_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT6_STATE' +PERFCOUNTER_CNT6_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT6_STATE_RESET', + 1: 'PERFCOUNTER_CNT6_STATE_START', + 2: 'PERFCOUNTER_CNT6_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT6_STATE_HW', +} +PERFCOUNTER_CNT6_STATE_RESET = 0 +PERFCOUNTER_CNT6_STATE_START = 1 +PERFCOUNTER_CNT6_STATE_FREEZE = 2 +PERFCOUNTER_CNT6_STATE_HW = 3 +PERFCOUNTER_CNT6_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT7_STATE' +PERFCOUNTER_CNT7_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT7_STATE_RESET', + 1: 'PERFCOUNTER_CNT7_STATE_START', + 2: 'PERFCOUNTER_CNT7_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT7_STATE_HW', +} +PERFCOUNTER_CNT7_STATE_RESET = 0 +PERFCOUNTER_CNT7_STATE_START = 1 +PERFCOUNTER_CNT7_STATE_FREEZE = 2 +PERFCOUNTER_CNT7_STATE_HW = 3 +PERFCOUNTER_CNT7_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTL_SEL' +PERFCOUNTER_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_CNTL_SEL_0', + 1: 'PERFCOUNTER_CNTL_SEL_1', + 2: 'PERFCOUNTER_CNTL_SEL_2', + 3: 'PERFCOUNTER_CNTL_SEL_3', + 4: 'PERFCOUNTER_CNTL_SEL_4', + 5: 'PERFCOUNTER_CNTL_SEL_5', + 6: 'PERFCOUNTER_CNTL_SEL_6', + 7: 'PERFCOUNTER_CNTL_SEL_7', +} +PERFCOUNTER_CNTL_SEL_0 = 0 +PERFCOUNTER_CNTL_SEL_1 = 1 +PERFCOUNTER_CNTL_SEL_2 = 2 +PERFCOUNTER_CNTL_SEL_3 = 3 +PERFCOUNTER_CNTL_SEL_4 = 4 +PERFCOUNTER_CNTL_SEL_5 = 5 +PERFCOUNTER_CNTL_SEL_6 = 6 +PERFCOUNTER_CNTL_SEL_7 = 7 +PERFCOUNTER_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTOFF_START_DIS' +PERFCOUNTER_CNTOFF_START_DIS__enumvalues = { + 0: 'PERFCOUNTER_CNTOFF_START_ENABLE', + 1: 'PERFCOUNTER_CNTOFF_START_DISABLE', +} +PERFCOUNTER_CNTOFF_START_ENABLE = 0 +PERFCOUNTER_CNTOFF_START_DISABLE = 1 +PERFCOUNTER_CNTOFF_START_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_COUNTED_VALUE_TYPE' +PERFCOUNTER_COUNTED_VALUE_TYPE__enumvalues = { + 0: 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 1: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 2: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', +} +PERFCOUNTER_COUNTED_VALUE_TYPE_ACC = 0 +PERFCOUNTER_COUNTED_VALUE_TYPE_MAX = 1 +PERFCOUNTER_COUNTED_VALUE_TYPE_MIN = 2 +PERFCOUNTER_COUNTED_VALUE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CVALUE_SEL' +PERFCOUNTER_CVALUE_SEL__enumvalues = { + 0: 'PERFCOUNTER_CVALUE_SEL_47_0', + 1: 'PERFCOUNTER_CVALUE_SEL_15_0', + 2: 'PERFCOUNTER_CVALUE_SEL_31_16', + 3: 'PERFCOUNTER_CVALUE_SEL_47_32', + 4: 'PERFCOUNTER_CVALUE_SEL_11_0', + 5: 'PERFCOUNTER_CVALUE_SEL_23_12', + 6: 'PERFCOUNTER_CVALUE_SEL_35_24', + 7: 'PERFCOUNTER_CVALUE_SEL_47_36', +} +PERFCOUNTER_CVALUE_SEL_47_0 = 0 +PERFCOUNTER_CVALUE_SEL_15_0 = 1 +PERFCOUNTER_CVALUE_SEL_31_16 = 2 +PERFCOUNTER_CVALUE_SEL_47_32 = 3 +PERFCOUNTER_CVALUE_SEL_11_0 = 4 +PERFCOUNTER_CVALUE_SEL_23_12 = 5 +PERFCOUNTER_CVALUE_SEL_35_24 = 6 +PERFCOUNTER_CVALUE_SEL_47_36 = 7 +PERFCOUNTER_CVALUE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_CNTL_SEL' +PERFCOUNTER_HW_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', + 1: 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', +} +PERFCOUNTER_HW_CNTL_SEL_RUNEN = 0 +PERFCOUNTER_HW_CNTL_SEL_CNTOFF = 1 +PERFCOUNTER_HW_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP1_SEL' +PERFCOUNTER_HW_STOP1_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP1_0', + 1: 'PERFCOUNTER_HW_STOP1_1', +} +PERFCOUNTER_HW_STOP1_0 = 0 +PERFCOUNTER_HW_STOP1_1 = 1 +PERFCOUNTER_HW_STOP1_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP2_SEL' +PERFCOUNTER_HW_STOP2_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP2_0', + 1: 'PERFCOUNTER_HW_STOP2_1', +} +PERFCOUNTER_HW_STOP2_0 = 0 +PERFCOUNTER_HW_STOP2_1 = 1 +PERFCOUNTER_HW_STOP2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INC_MODE' +PERFCOUNTER_INC_MODE__enumvalues = { + 0: 'PERFCOUNTER_INC_MODE_MULTI_BIT', + 1: 'PERFCOUNTER_INC_MODE_BOTH_EDGE', + 2: 'PERFCOUNTER_INC_MODE_LSB', + 3: 'PERFCOUNTER_INC_MODE_POS_EDGE', + 4: 'PERFCOUNTER_INC_MODE_NEG_EDGE', +} +PERFCOUNTER_INC_MODE_MULTI_BIT = 0 +PERFCOUNTER_INC_MODE_BOTH_EDGE = 1 +PERFCOUNTER_INC_MODE_LSB = 2 +PERFCOUNTER_INC_MODE_POS_EDGE = 3 +PERFCOUNTER_INC_MODE_NEG_EDGE = 4 +PERFCOUNTER_INC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_EN' +PERFCOUNTER_INT_EN__enumvalues = { + 0: 'PERFCOUNTER_INT_DISABLE', + 1: 'PERFCOUNTER_INT_ENABLE', +} +PERFCOUNTER_INT_DISABLE = 0 +PERFCOUNTER_INT_ENABLE = 1 +PERFCOUNTER_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_TYPE' +PERFCOUNTER_INT_TYPE__enumvalues = { + 0: 'PERFCOUNTER_INT_TYPE_LEVEL', + 1: 'PERFCOUNTER_INT_TYPE_PULSE', +} +PERFCOUNTER_INT_TYPE_LEVEL = 0 +PERFCOUNTER_INT_TYPE_PULSE = 1 +PERFCOUNTER_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_OFF_MASK' +PERFCOUNTER_OFF_MASK__enumvalues = { + 0: 'PERFCOUNTER_OFF_MASK_DISABLE', + 1: 'PERFCOUNTER_OFF_MASK_ENABLE', +} +PERFCOUNTER_OFF_MASK_DISABLE = 0 +PERFCOUNTER_OFF_MASK_ENABLE = 1 +PERFCOUNTER_OFF_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RESTART_EN' +PERFCOUNTER_RESTART_EN__enumvalues = { + 0: 'PERFCOUNTER_RESTART_DISABLE', + 1: 'PERFCOUNTER_RESTART_ENABLE', +} +PERFCOUNTER_RESTART_DISABLE = 0 +PERFCOUNTER_RESTART_ENABLE = 1 +PERFCOUNTER_RESTART_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RUNEN_MODE' +PERFCOUNTER_RUNEN_MODE__enumvalues = { + 0: 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 1: 'PERFCOUNTER_RUNEN_MODE_EDGE', +} +PERFCOUNTER_RUNEN_MODE_LEVEL = 0 +PERFCOUNTER_RUNEN_MODE_EDGE = 1 +PERFCOUNTER_RUNEN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL0' +PERFCOUNTER_STATE_SEL0__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL0_LOCAL', +} +PERFCOUNTER_STATE_SEL0_GLOBAL = 0 +PERFCOUNTER_STATE_SEL0_LOCAL = 1 +PERFCOUNTER_STATE_SEL0 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL1' +PERFCOUNTER_STATE_SEL1__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL1_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL1_LOCAL', +} +PERFCOUNTER_STATE_SEL1_GLOBAL = 0 +PERFCOUNTER_STATE_SEL1_LOCAL = 1 +PERFCOUNTER_STATE_SEL1 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL2' +PERFCOUNTER_STATE_SEL2__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL2_LOCAL', +} +PERFCOUNTER_STATE_SEL2_GLOBAL = 0 +PERFCOUNTER_STATE_SEL2_LOCAL = 1 +PERFCOUNTER_STATE_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL3' +PERFCOUNTER_STATE_SEL3__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL3_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL3_LOCAL', +} +PERFCOUNTER_STATE_SEL3_GLOBAL = 0 +PERFCOUNTER_STATE_SEL3_LOCAL = 1 +PERFCOUNTER_STATE_SEL3 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL4' +PERFCOUNTER_STATE_SEL4__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL4_LOCAL', +} +PERFCOUNTER_STATE_SEL4_GLOBAL = 0 +PERFCOUNTER_STATE_SEL4_LOCAL = 1 +PERFCOUNTER_STATE_SEL4 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL5' +PERFCOUNTER_STATE_SEL5__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL5_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL5_LOCAL', +} +PERFCOUNTER_STATE_SEL5_GLOBAL = 0 +PERFCOUNTER_STATE_SEL5_LOCAL = 1 +PERFCOUNTER_STATE_SEL5 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL6' +PERFCOUNTER_STATE_SEL6__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL6_LOCAL', +} +PERFCOUNTER_STATE_SEL6_GLOBAL = 0 +PERFCOUNTER_STATE_SEL6_LOCAL = 1 +PERFCOUNTER_STATE_SEL6 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL7' +PERFCOUNTER_STATE_SEL7__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL7_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL7_LOCAL', +} +PERFCOUNTER_STATE_SEL7_GLOBAL = 0 +PERFCOUNTER_STATE_SEL7_LOCAL = 1 +PERFCOUNTER_STATE_SEL7 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_AND_OR' +PERFMON_CNTOFF_AND_OR__enumvalues = { + 0: 'PERFMON_CNTOFF_OR', + 1: 'PERFMON_CNTOFF_AND', +} +PERFMON_CNTOFF_OR = 0 +PERFMON_CNTOFF_AND = 1 +PERFMON_CNTOFF_AND_OR = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_EN' +PERFMON_CNTOFF_INT_EN__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_DISABLE', + 1: 'PERFMON_CNTOFF_INT_ENABLE', +} +PERFMON_CNTOFF_INT_DISABLE = 0 +PERFMON_CNTOFF_INT_ENABLE = 1 +PERFMON_CNTOFF_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_TYPE' +PERFMON_CNTOFF_INT_TYPE__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_TYPE_LEVEL', + 1: 'PERFMON_CNTOFF_INT_TYPE_PULSE', +} +PERFMON_CNTOFF_INT_TYPE_LEVEL = 0 +PERFMON_CNTOFF_INT_TYPE_PULSE = 1 +PERFMON_CNTOFF_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_STATE' +PERFMON_STATE__enumvalues = { + 0: 'PERFMON_STATE_RESET', + 1: 'PERFMON_STATE_START', + 2: 'PERFMON_STATE_FREEZE', + 3: 'PERFMON_STATE_HW', +} +PERFMON_STATE_RESET = 0 +PERFMON_STATE_START = 1 +PERFMON_STATE_FREEZE = 2 +PERFMON_STATE_HW = 3 +PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'BIGK_FRAGMENT_SIZE' +BIGK_FRAGMENT_SIZE__enumvalues = { + 0: 'VM_PG_SIZE_4KB', + 1: 'VM_PG_SIZE_8KB', + 2: 'VM_PG_SIZE_16KB', + 3: 'VM_PG_SIZE_32KB', + 4: 'VM_PG_SIZE_64KB', + 5: 'VM_PG_SIZE_128KB', + 6: 'VM_PG_SIZE_256KB', + 7: 'VM_PG_SIZE_512KB', + 8: 'VM_PG_SIZE_1024KB', + 9: 'VM_PG_SIZE_2048KB', +} +VM_PG_SIZE_4KB = 0 +VM_PG_SIZE_8KB = 1 +VM_PG_SIZE_16KB = 2 +VM_PG_SIZE_32KB = 3 +VM_PG_SIZE_64KB = 4 +VM_PG_SIZE_128KB = 5 +VM_PG_SIZE_256KB = 6 +VM_PG_SIZE_512KB = 7 +VM_PG_SIZE_1024KB = 8 +VM_PG_SIZE_2048KB = 9 +BIGK_FRAGMENT_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'CHUNK_SIZE' +CHUNK_SIZE__enumvalues = { + 0: 'CHUNK_SIZE_1KB', + 1: 'CHUNK_SIZE_2KB', + 2: 'CHUNK_SIZE_4KB', + 3: 'CHUNK_SIZE_8KB', + 4: 'CHUNK_SIZE_16KB', + 5: 'CHUNK_SIZE_32KB', + 6: 'CHUNK_SIZE_64KB', +} +CHUNK_SIZE_1KB = 0 +CHUNK_SIZE_2KB = 1 +CHUNK_SIZE_4KB = 2 +CHUNK_SIZE_8KB = 3 +CHUNK_SIZE_16KB = 4 +CHUNK_SIZE_32KB = 5 +CHUNK_SIZE_64KB = 6 +CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'COMPAT_LEVEL' +COMPAT_LEVEL__enumvalues = { + 0: 'ADDR_GEN_ZERO', + 1: 'ADDR_GEN_ONE', + 2: 'ADDR_GEN_TWO', + 3: 'ADDR_RESERVED', +} +ADDR_GEN_ZERO = 0 +ADDR_GEN_ONE = 1 +ADDR_GEN_TWO = 2 +ADDR_RESERVED = 3 +COMPAT_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPTE_GROUP_SIZE' +DPTE_GROUP_SIZE__enumvalues = { + 0: 'DPTE_GROUP_SIZE_64B', + 1: 'DPTE_GROUP_SIZE_128B', + 2: 'DPTE_GROUP_SIZE_256B', + 3: 'DPTE_GROUP_SIZE_512B', + 4: 'DPTE_GROUP_SIZE_1024B', + 5: 'DPTE_GROUP_SIZE_2048B', +} +DPTE_GROUP_SIZE_64B = 0 +DPTE_GROUP_SIZE_128B = 1 +DPTE_GROUP_SIZE_256B = 2 +DPTE_GROUP_SIZE_512B = 3 +DPTE_GROUP_SIZE_1024B = 4 +DPTE_GROUP_SIZE_2048B = 5 +DPTE_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'FORCE_ONE_ROW_FOR_FRAME' +FORCE_ONE_ROW_FOR_FRAME__enumvalues = { + 0: 'FORCE_ONE_ROW_FOR_FRAME_0', + 1: 'FORCE_ONE_ROW_FOR_FRAME_1', +} +FORCE_ONE_ROW_FOR_FRAME_0 = 0 +FORCE_ONE_ROW_FOR_FRAME_1 = 1 +FORCE_ONE_ROW_FOR_FRAME = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_BLANK_EN' +HUBP_BLANK_EN__enumvalues = { + 0: 'HUBP_BLANK_SW_DEASSERT', + 1: 'HUBP_BLANK_SW_ASSERT', +} +HUBP_BLANK_SW_DEASSERT = 0 +HUBP_BLANK_SW_ASSERT = 1 +HUBP_BLANK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_IN_BLANK' +HUBP_IN_BLANK__enumvalues = { + 0: 'HUBP_IN_ACTIVE', + 1: 'HUBP_IN_VBLANK', +} +HUBP_IN_ACTIVE = 0 +HUBP_IN_VBLANK = 1 +HUBP_IN_BLANK = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_MEASURE_WIN_MODE_DCFCLK' +HUBP_MEASURE_WIN_MODE_DCFCLK__enumvalues = { + 0: 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 1: 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 2: 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 3: 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', +} +HUBP_MEASURE_WIN_MODE_DCFCLK_0 = 0 +HUBP_MEASURE_WIN_MODE_DCFCLK_1 = 1 +HUBP_MEASURE_WIN_MODE_DCFCLK_2 = 2 +HUBP_MEASURE_WIN_MODE_DCFCLK_3 = 3 +HUBP_MEASURE_WIN_MODE_DCFCLK = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_NO_OUTSTANDING_REQ' +HUBP_NO_OUTSTANDING_REQ__enumvalues = { + 0: 'OUTSTANDING_REQ', + 1: 'NO_OUTSTANDING_REQ', +} +OUTSTANDING_REQ = 0 +NO_OUTSTANDING_REQ = 1 +HUBP_NO_OUTSTANDING_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_SOFT_RESET' +HUBP_SOFT_RESET__enumvalues = { + 0: 'HUBP_SOFT_RESET_ON', + 1: 'HUBP_SOFT_RESET_OFF', +} +HUBP_SOFT_RESET_ON = 0 +HUBP_SOFT_RESET_OFF = 1 +HUBP_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_TTU_DISABLE' +HUBP_TTU_DISABLE__enumvalues = { + 0: 'HUBP_TTU_ENABLED', + 1: 'HUBP_TTU_DISABLED', +} +HUBP_TTU_ENABLED = 0 +HUBP_TTU_DISABLED = 1 +HUBP_TTU_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VREADY_AT_OR_AFTER_VSYNC' +HUBP_VREADY_AT_OR_AFTER_VSYNC__enumvalues = { + 0: 'VREADY_BEFORE_VSYNC', + 1: 'VREADY_AT_OR_AFTER_VSYNC', +} +VREADY_BEFORE_VSYNC = 0 +VREADY_AT_OR_AFTER_VSYNC = 1 +HUBP_VREADY_AT_OR_AFTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VTG_SEL' +HUBP_VTG_SEL__enumvalues = { + 0: 'VTG_SEL_0', + 1: 'VTG_SEL_1', + 2: 'VTG_SEL_2', + 3: 'VTG_SEL_3', + 4: 'VTG_SEL_4', + 5: 'VTG_SEL_5', +} +VTG_SEL_0 = 0 +VTG_SEL_1 = 1 +VTG_SEL_2 = 2 +VTG_SEL_3 = 3 +VTG_SEL_4 = 4 +VTG_SEL_5 = 5 +HUBP_VTG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'H_MIRROR_EN' +H_MIRROR_EN__enumvalues = { + 0: 'HW_MIRRORING_DISABLE', + 1: 'HW_MIRRORING_ENABLE', +} +HW_MIRRORING_DISABLE = 0 +HW_MIRRORING_ENABLE = 1 +H_MIRROR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LEGACY_PIPE_INTERLEAVE' +LEGACY_PIPE_INTERLEAVE__enumvalues = { + 0: 'LEGACY_PIPE_INTERLEAVE_256B', + 1: 'LEGACY_PIPE_INTERLEAVE_512B', +} +LEGACY_PIPE_INTERLEAVE_256B = 0 +LEGACY_PIPE_INTERLEAVE_512B = 1 +LEGACY_PIPE_INTERLEAVE = ctypes.c_uint32 # enum + +# values for enumeration 'META_CHUNK_SIZE' +META_CHUNK_SIZE__enumvalues = { + 0: 'META_CHUNK_SIZE_1KB', + 1: 'META_CHUNK_SIZE_2KB', + 2: 'META_CHUNK_SIZE_4KB', + 3: 'META_CHUNK_SIZE_8KB', +} +META_CHUNK_SIZE_1KB = 0 +META_CHUNK_SIZE_2KB = 1 +META_CHUNK_SIZE_4KB = 2 +META_CHUNK_SIZE_8KB = 3 +META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'META_LINEAR' +META_LINEAR__enumvalues = { + 0: 'META_SURF_TILED', + 1: 'META_SURF_LINEAR', +} +META_SURF_TILED = 0 +META_SURF_LINEAR = 1 +META_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_CHUNK_SIZE' +MIN_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_CHUNK_SIZE', + 1: 'MIN_CHUNK_SIZE_256B', + 2: 'MIN_CHUNK_SIZE_512B', + 3: 'MIN_CHUNK_SIZE_1024B', +} +NO_MIN_CHUNK_SIZE = 0 +MIN_CHUNK_SIZE_256B = 1 +MIN_CHUNK_SIZE_512B = 2 +MIN_CHUNK_SIZE_1024B = 3 +MIN_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_META_CHUNK_SIZE' +MIN_META_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_META_CHUNK_SIZE', + 1: 'MIN_META_CHUNK_SIZE_64B', + 2: 'MIN_META_CHUNK_SIZE_128B', + 3: 'MIN_META_CHUNK_SIZE_256B', +} +NO_MIN_META_CHUNK_SIZE = 0 +MIN_META_CHUNK_SIZE_64B = 1 +MIN_META_CHUNK_SIZE_128B = 2 +MIN_META_CHUNK_SIZE_256B = 3 +MIN_META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_ALIGNED' +PIPE_ALIGNED__enumvalues = { + 0: 'PIPE_UNALIGNED_SURF', + 1: 'PIPE_ALIGNED_SURF', +} +PIPE_UNALIGNED_SURF = 0 +PIPE_ALIGNED_SURF = 1 +PIPE_ALIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'PTE_BUFFER_MODE' +PTE_BUFFER_MODE__enumvalues = { + 0: 'PTE_BUFFER_MODE_0', + 1: 'PTE_BUFFER_MODE_1', +} +PTE_BUFFER_MODE_0 = 0 +PTE_BUFFER_MODE_1 = 1 +PTE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PTE_ROW_HEIGHT_LINEAR' +PTE_ROW_HEIGHT_LINEAR__enumvalues = { + 0: 'PTE_ROW_HEIGHT_LINEAR_8L', + 1: 'PTE_ROW_HEIGHT_LINEAR_16L', + 2: 'PTE_ROW_HEIGHT_LINEAR_32L', + 3: 'PTE_ROW_HEIGHT_LINEAR_64L', + 4: 'PTE_ROW_HEIGHT_LINEAR_128L', + 5: 'PTE_ROW_HEIGHT_LINEAR_256L', + 6: 'PTE_ROW_HEIGHT_LINEAR_512L', + 7: 'PTE_ROW_HEIGHT_LINEAR_1024L', +} +PTE_ROW_HEIGHT_LINEAR_8L = 0 +PTE_ROW_HEIGHT_LINEAR_16L = 1 +PTE_ROW_HEIGHT_LINEAR_32L = 2 +PTE_ROW_HEIGHT_LINEAR_64L = 3 +PTE_ROW_HEIGHT_LINEAR_128L = 4 +PTE_ROW_HEIGHT_LINEAR_256L = 5 +PTE_ROW_HEIGHT_LINEAR_512L = 6 +PTE_ROW_HEIGHT_LINEAR_1024L = 7 +PTE_ROW_HEIGHT_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'ROTATION_ANGLE' +ROTATION_ANGLE__enumvalues = { + 0: 'ROTATE_0_DEGREES', + 1: 'ROTATE_90_DEGREES', + 2: 'ROTATE_180_DEGREES', + 3: 'ROTATE_270_DEGREES', +} +ROTATE_0_DEGREES = 0 +ROTATE_90_DEGREES = 1 +ROTATE_180_DEGREES = 2 +ROTATE_270_DEGREES = 3 +ROTATION_ANGLE = ctypes.c_uint32 # enum + +# values for enumeration 'SWATH_HEIGHT' +SWATH_HEIGHT__enumvalues = { + 0: 'SWATH_HEIGHT_1L', + 1: 'SWATH_HEIGHT_2L', + 2: 'SWATH_HEIGHT_4L', + 3: 'SWATH_HEIGHT_8L', + 4: 'SWATH_HEIGHT_16L', +} +SWATH_HEIGHT_1L = 0 +SWATH_HEIGHT_2L = 1 +SWATH_HEIGHT_4L = 2 +SWATH_HEIGHT_8L = 3 +SWATH_HEIGHT_16L = 4 +SWATH_HEIGHT = ctypes.c_uint32 # enum + +# values for enumeration 'USE_MALL_FOR_CURSOR' +USE_MALL_FOR_CURSOR__enumvalues = { + 0: 'USE_MALL_FOR_CURSOR_0', + 1: 'USE_MALL_FOR_CURSOR_1', +} +USE_MALL_FOR_CURSOR_0 = 0 +USE_MALL_FOR_CURSOR_1 = 1 +USE_MALL_FOR_CURSOR = ctypes.c_uint32 # enum + +# values for enumeration 'USE_MALL_FOR_PSTATE_CHANGE' +USE_MALL_FOR_PSTATE_CHANGE__enumvalues = { + 0: 'USE_MALL_FOR_PSTATE_CHANGE_0', + 1: 'USE_MALL_FOR_PSTATE_CHANGE_1', +} +USE_MALL_FOR_PSTATE_CHANGE_0 = 0 +USE_MALL_FOR_PSTATE_CHANGE_1 = 1 +USE_MALL_FOR_PSTATE_CHANGE = ctypes.c_uint32 # enum + +# values for enumeration 'USE_MALL_FOR_STATIC_SCREEN' +USE_MALL_FOR_STATIC_SCREEN__enumvalues = { + 0: 'USE_MALL_FOR_STATIC_SCREEN_0', + 1: 'USE_MALL_FOR_STATIC_SCREEN_1', +} +USE_MALL_FOR_STATIC_SCREEN_0 = 0 +USE_MALL_FOR_STATIC_SCREEN_1 = 1 +USE_MALL_FOR_STATIC_SCREEN = ctypes.c_uint32 # enum + +# values for enumeration 'VMPG_SIZE' +VMPG_SIZE__enumvalues = { + 0: 'VMPG_SIZE_4KB', + 1: 'VMPG_SIZE_64KB', +} +VMPG_SIZE_4KB = 0 +VMPG_SIZE_64KB = 1 +VMPG_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VM_GROUP_SIZE' +VM_GROUP_SIZE__enumvalues = { + 0: 'VM_GROUP_SIZE_64B', + 1: 'VM_GROUP_SIZE_128B', + 2: 'VM_GROUP_SIZE_256B', + 3: 'VM_GROUP_SIZE_512B', + 4: 'VM_GROUP_SIZE_1024B', + 5: 'VM_GROUP_SIZE_2048B', +} +VM_GROUP_SIZE_64B = 0 +VM_GROUP_SIZE_128B = 1 +VM_GROUP_SIZE_256B = 2 +VM_GROUP_SIZE_512B = 3 +VM_GROUP_SIZE_1024B = 4 +VM_GROUP_SIZE_2048B = 5 +VM_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_MIN_FREE_ENTRIES' +DFQ_MIN_FREE_ENTRIES__enumvalues = { + 0: 'DFQ_MIN_FREE_ENTRIES_0', + 1: 'DFQ_MIN_FREE_ENTRIES_1', + 2: 'DFQ_MIN_FREE_ENTRIES_2', + 3: 'DFQ_MIN_FREE_ENTRIES_3', + 4: 'DFQ_MIN_FREE_ENTRIES_4', + 5: 'DFQ_MIN_FREE_ENTRIES_5', + 6: 'DFQ_MIN_FREE_ENTRIES_6', + 7: 'DFQ_MIN_FREE_ENTRIES_7', +} +DFQ_MIN_FREE_ENTRIES_0 = 0 +DFQ_MIN_FREE_ENTRIES_1 = 1 +DFQ_MIN_FREE_ENTRIES_2 = 2 +DFQ_MIN_FREE_ENTRIES_3 = 3 +DFQ_MIN_FREE_ENTRIES_4 = 4 +DFQ_MIN_FREE_ENTRIES_5 = 5 +DFQ_MIN_FREE_ENTRIES_6 = 6 +DFQ_MIN_FREE_ENTRIES_7 = 7 +DFQ_MIN_FREE_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_NUM_ENTRIES' +DFQ_NUM_ENTRIES__enumvalues = { + 0: 'DFQ_NUM_ENTRIES_0', + 1: 'DFQ_NUM_ENTRIES_1', + 2: 'DFQ_NUM_ENTRIES_2', + 3: 'DFQ_NUM_ENTRIES_3', + 4: 'DFQ_NUM_ENTRIES_4', + 5: 'DFQ_NUM_ENTRIES_5', + 6: 'DFQ_NUM_ENTRIES_6', + 7: 'DFQ_NUM_ENTRIES_7', + 8: 'DFQ_NUM_ENTRIES_8', +} +DFQ_NUM_ENTRIES_0 = 0 +DFQ_NUM_ENTRIES_1 = 1 +DFQ_NUM_ENTRIES_2 = 2 +DFQ_NUM_ENTRIES_3 = 3 +DFQ_NUM_ENTRIES_4 = 4 +DFQ_NUM_ENTRIES_5 = 5 +DFQ_NUM_ENTRIES_6 = 6 +DFQ_NUM_ENTRIES_7 = 7 +DFQ_NUM_ENTRIES_8 = 8 +DFQ_NUM_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_SIZE' +DFQ_SIZE__enumvalues = { + 0: 'DFQ_SIZE_0', + 1: 'DFQ_SIZE_1', + 2: 'DFQ_SIZE_2', + 3: 'DFQ_SIZE_3', + 4: 'DFQ_SIZE_4', + 5: 'DFQ_SIZE_5', + 6: 'DFQ_SIZE_6', + 7: 'DFQ_SIZE_7', +} +DFQ_SIZE_0 = 0 +DFQ_SIZE_1 = 1 +DFQ_SIZE_2 = 2 +DFQ_SIZE_3 = 3 +DFQ_SIZE_4 = 4 +DFQ_SIZE_5 = 5 +DFQ_SIZE_6 = 6 +DFQ_SIZE_7 = 7 +DFQ_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_VM_DONE' +DMDATA_VM_DONE__enumvalues = { + 0: 'DMDATA_VM_IS_NOT_DONE', + 1: 'DMDATA_VM_IS_DONE', +} +DMDATA_VM_IS_NOT_DONE = 0 +DMDATA_VM_IS_DONE = 1 +DMDATA_VM_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'EXPANSION_MODE' +EXPANSION_MODE__enumvalues = { + 0: 'EXPANSION_MODE_ZERO', + 1: 'EXPANSION_MODE_CONSERVATIVE', + 2: 'EXPANSION_MODE_OPTIMAL', +} +EXPANSION_MODE_ZERO = 0 +EXPANSION_MODE_CONSERVATIVE = 1 +EXPANSION_MODE_OPTIMAL = 2 +EXPANSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FLIP_RATE' +FLIP_RATE__enumvalues = { + 0: 'FLIP_RATE_0', + 1: 'FLIP_RATE_1', + 2: 'FLIP_RATE_2', + 3: 'FLIP_RATE_3', + 4: 'FLIP_RATE_4', + 5: 'FLIP_RATE_5', + 6: 'FLIP_RATE_6', + 7: 'FLIP_RATE_7', +} +FLIP_RATE_0 = 0 +FLIP_RATE_1 = 1 +FLIP_RATE_2 = 2 +FLIP_RATE_3 = 3 +FLIP_RATE_4 = 4 +FLIP_RATE_5 = 5 +FLIP_RATE_6 = 6 +FLIP_RATE_7 = 7 +FLIP_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'INT_MASK' +INT_MASK__enumvalues = { + 0: 'INT_DISABLED', + 1: 'INT_ENABLED', +} +INT_DISABLED = 0 +INT_ENABLED = 1 +INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_IN_FLUSH_URGENT' +PIPE_IN_FLUSH_URGENT__enumvalues = { + 0: 'PIPE_IN_FLUSH_URGENT_ENABLE', + 1: 'PIPE_IN_FLUSH_URGENT_DISABLE', +} +PIPE_IN_FLUSH_URGENT_ENABLE = 0 +PIPE_IN_FLUSH_URGENT_DISABLE = 1 +PIPE_IN_FLUSH_URGENT = ctypes.c_uint32 # enum + +# values for enumeration 'PRQ_MRQ_FLUSH_URGENT' +PRQ_MRQ_FLUSH_URGENT__enumvalues = { + 0: 'PRQ_MRQ_FLUSH_URGENT_ENABLE', + 1: 'PRQ_MRQ_FLUSH_URGENT_DISABLE', +} +PRQ_MRQ_FLUSH_URGENT_ENABLE = 0 +PRQ_MRQ_FLUSH_URGENT_DISABLE = 1 +PRQ_MRQ_FLUSH_URGENT = ctypes.c_uint32 # enum + +# values for enumeration 'ROW_TTU_MODE' +ROW_TTU_MODE__enumvalues = { + 0: 'END_OF_ROW_MODE', + 1: 'WATERMARK_MODE', +} +END_OF_ROW_MODE = 0 +WATERMARK_MODE = 1 +ROW_TTU_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC' +SURFACE_DCC__enumvalues = { + 0: 'SURFACE_IS_NOT_DCC', + 1: 'SURFACE_IS_DCC', +} +SURFACE_IS_NOT_DCC = 0 +SURFACE_IS_DCC = 1 +SURFACE_DCC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_128B' +SURFACE_DCC_IND_128B__enumvalues = { + 0: 'SURFACE_DCC_IS_NOT_IND_128B', + 1: 'SURFACE_DCC_IS_IND_128B', +} +SURFACE_DCC_IS_NOT_IND_128B = 0 +SURFACE_DCC_IS_IND_128B = 1 +SURFACE_DCC_IND_128B = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_64B' +SURFACE_DCC_IND_64B__enumvalues = { + 0: 'SURFACE_DCC_IS_NOT_IND_64B', + 1: 'SURFACE_DCC_IS_IND_64B', +} +SURFACE_DCC_IS_NOT_IND_64B = 0 +SURFACE_DCC_IS_IND_64B = 1 +SURFACE_DCC_IND_64B = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_BLK' +SURFACE_DCC_IND_BLK__enumvalues = { + 0: 'SURFACE_DCC_BLOCK_IS_UNCONSTRAINED', + 1: 'SURFACE_DCC_BLOCK_IS_IND_64B', + 2: 'SURFACE_DCC_BLOCK_IS_IND_128B', + 3: 'SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL', +} +SURFACE_DCC_BLOCK_IS_UNCONSTRAINED = 0 +SURFACE_DCC_BLOCK_IS_IND_64B = 1 +SURFACE_DCC_BLOCK_IS_IND_128B = 2 +SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL = 3 +SURFACE_DCC_IND_BLK = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_AWAY_INT_TYPE' +SURFACE_FLIP_AWAY_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_AWAY_INT_LEVEL', + 1: 'SURFACE_FLIP_AWAY_INT_PULSE', +} +SURFACE_FLIP_AWAY_INT_LEVEL = 0 +SURFACE_FLIP_AWAY_INT_PULSE = 1 +SURFACE_FLIP_AWAY_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_EXEC_DEBUG_MODE' +SURFACE_FLIP_EXEC_DEBUG_MODE__enumvalues = { + 0: 'SURFACE_FLIP_EXEC_NORMAL_MODE', + 1: 'SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE', +} +SURFACE_FLIP_EXEC_NORMAL_MODE = 0 +SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE = 1 +SURFACE_FLIP_EXEC_DEBUG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_INT_TYPE' +SURFACE_FLIP_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_INT_LEVEL', + 1: 'SURFACE_FLIP_INT_PULSE', +} +SURFACE_FLIP_INT_LEVEL = 0 +SURFACE_FLIP_INT_PULSE = 1 +SURFACE_FLIP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_IN_STEREOSYNC' +SURFACE_FLIP_IN_STEREOSYNC__enumvalues = { + 0: 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 1: 'SURFACE_FLIP_IN_STEREOSYNC_MODE', +} +SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE = 0 +SURFACE_FLIP_IN_STEREOSYNC_MODE = 1 +SURFACE_FLIP_IN_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_MODE_FOR_STEREOSYNC' +SURFACE_FLIP_MODE_FOR_STEREOSYNC__enumvalues = { + 0: 'FLIP_ANY_FRAME', + 1: 'FLIP_LEFT_EYE', + 2: 'FLIP_RIGHT_EYE', + 3: 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', +} +FLIP_ANY_FRAME = 0 +FLIP_LEFT_EYE = 1 +FLIP_RIGHT_EYE = 2 +SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED = 3 +SURFACE_FLIP_MODE_FOR_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_DISABLE' +SURFACE_FLIP_STEREO_SELECT_DISABLE__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 1: 'SURFACE_FLIP_STEREO_SELECT_DISABLED', +} +SURFACE_FLIP_STEREO_SELECT_ENABLED = 0 +SURFACE_FLIP_STEREO_SELECT_DISABLED = 1 +SURFACE_FLIP_STEREO_SELECT_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_POLARITY' +SURFACE_FLIP_STEREO_SELECT_POLARITY__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 1: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', +} +SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT = 0 +SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT = 1 +SURFACE_FLIP_STEREO_SELECT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_TYPE' +SURFACE_FLIP_TYPE__enumvalues = { + 0: 'SURFACE_V_FLIP', + 1: 'SURFACE_I_FLIP', +} +SURFACE_V_FLIP = 0 +SURFACE_I_FLIP = 1 +SURFACE_FLIP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_VUPDATE_SKIP_NUM' +SURFACE_FLIP_VUPDATE_SKIP_NUM__enumvalues = { + 0: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 1: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 2: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 3: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 4: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 5: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 6: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 7: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 8: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 9: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', + 10: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 11: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 12: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 13: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 14: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 15: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', +} +SURFACE_FLIP_VUPDATE_SKIP_NUM_0 = 0 +SURFACE_FLIP_VUPDATE_SKIP_NUM_1 = 1 +SURFACE_FLIP_VUPDATE_SKIP_NUM_2 = 2 +SURFACE_FLIP_VUPDATE_SKIP_NUM_3 = 3 +SURFACE_FLIP_VUPDATE_SKIP_NUM_4 = 4 +SURFACE_FLIP_VUPDATE_SKIP_NUM_5 = 5 +SURFACE_FLIP_VUPDATE_SKIP_NUM_6 = 6 +SURFACE_FLIP_VUPDATE_SKIP_NUM_7 = 7 +SURFACE_FLIP_VUPDATE_SKIP_NUM_8 = 8 +SURFACE_FLIP_VUPDATE_SKIP_NUM_9 = 9 +SURFACE_FLIP_VUPDATE_SKIP_NUM_10 = 10 +SURFACE_FLIP_VUPDATE_SKIP_NUM_11 = 11 +SURFACE_FLIP_VUPDATE_SKIP_NUM_12 = 12 +SURFACE_FLIP_VUPDATE_SKIP_NUM_13 = 13 +SURFACE_FLIP_VUPDATE_SKIP_NUM_14 = 14 +SURFACE_FLIP_VUPDATE_SKIP_NUM_15 = 15 +SURFACE_FLIP_VUPDATE_SKIP_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_INUSE_RAED_NO_LATCH' +SURFACE_INUSE_RAED_NO_LATCH__enumvalues = { + 0: 'SURFACE_INUSE_IS_LATCHED', + 1: 'SURFACE_INUSE_IS_NOT_LATCHED', +} +SURFACE_INUSE_IS_LATCHED = 0 +SURFACE_INUSE_IS_NOT_LATCHED = 1 +SURFACE_INUSE_RAED_NO_LATCH = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_TMZ' +SURFACE_TMZ__enumvalues = { + 0: 'SURFACE_IS_NOT_TMZ', + 1: 'SURFACE_IS_TMZ', +} +SURFACE_IS_NOT_TMZ = 0 +SURFACE_IS_TMZ = 1 +SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_UPDATE_LOCK' +SURFACE_UPDATE_LOCK__enumvalues = { + 0: 'SURFACE_UPDATE_IS_UNLOCKED', + 1: 'SURFACE_UPDATE_IS_LOCKED', +} +SURFACE_UPDATE_IS_UNLOCKED = 0 +SURFACE_UPDATE_IS_LOCKED = 1 +SURFACE_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_ALPHA' +CROSSBAR_FOR_ALPHA__enumvalues = { + 0: 'ALPHA_DATA_ONTO_ALPHA_PORT', + 1: 'Y_G_DATA_ONTO_ALPHA_PORT', + 2: 'CB_B_DATA_ONTO_ALPHA_PORT', + 3: 'CR_R_DATA_ONTO_ALPHA_PORT', +} +ALPHA_DATA_ONTO_ALPHA_PORT = 0 +Y_G_DATA_ONTO_ALPHA_PORT = 1 +CB_B_DATA_ONTO_ALPHA_PORT = 2 +CR_R_DATA_ONTO_ALPHA_PORT = 3 +CROSSBAR_FOR_ALPHA = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CB_B' +CROSSBAR_FOR_CB_B__enumvalues = { + 0: 'ALPHA_DATA_ONTO_CB_B_PORT', + 1: 'Y_G_DATA_ONTO_CB_B_PORT', + 2: 'CB_B_DATA_ONTO_CB_B_PORT', + 3: 'CR_R_DATA_ONTO_CB_B_PORT', +} +ALPHA_DATA_ONTO_CB_B_PORT = 0 +Y_G_DATA_ONTO_CB_B_PORT = 1 +CB_B_DATA_ONTO_CB_B_PORT = 2 +CR_R_DATA_ONTO_CB_B_PORT = 3 +CROSSBAR_FOR_CB_B = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CR_R' +CROSSBAR_FOR_CR_R__enumvalues = { + 0: 'ALPHA_DATA_ONTO_CR_R_PORT', + 1: 'Y_G_DATA_ONTO_CR_R_PORT', + 2: 'CB_B_DATA_ONTO_CR_R_PORT', + 3: 'CR_R_DATA_ONTO_CR_R_PORT', +} +ALPHA_DATA_ONTO_CR_R_PORT = 0 +Y_G_DATA_ONTO_CR_R_PORT = 1 +CB_B_DATA_ONTO_CR_R_PORT = 2 +CR_R_DATA_ONTO_CR_R_PORT = 3 +CROSSBAR_FOR_CR_R = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_Y_G' +CROSSBAR_FOR_Y_G__enumvalues = { + 0: 'ALPHA_DATA_ONTO_Y_G_PORT', + 1: 'Y_G_DATA_ONTO_Y_G_PORT', + 2: 'CB_B_DATA_ONTO_Y_G_PORT', + 3: 'CR_R_DATA_ONTO_Y_G_PORT', +} +ALPHA_DATA_ONTO_Y_G_PORT = 0 +Y_G_DATA_ONTO_Y_G_PORT = 1 +CB_B_DATA_ONTO_Y_G_PORT = 2 +CR_R_DATA_ONTO_Y_G_PORT = 3 +CROSSBAR_FOR_Y_G = ctypes.c_uint32 # enum + +# values for enumeration 'DETILE_BUFFER_PACKER_ENABLE' +DETILE_BUFFER_PACKER_ENABLE__enumvalues = { + 0: 'DETILE_BUFFER_PACKER_IS_DISABLE', + 1: 'DETILE_BUFFER_PACKER_IS_ENABLE', +} +DETILE_BUFFER_PACKER_IS_DISABLE = 0 +DETILE_BUFFER_PACKER_IS_ENABLE = 1 +DETILE_BUFFER_PACKER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_MODE' +MEM_PWR_DIS_MODE__enumvalues = { + 0: 'MEM_POWER_DIS_MODE_ENABLE', + 1: 'MEM_POWER_DIS_MODE_DISABLE', +} +MEM_POWER_DIS_MODE_ENABLE = 0 +MEM_POWER_DIS_MODE_DISABLE = 1 +MEM_PWR_DIS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_MODE' +MEM_PWR_FORCE_MODE__enumvalues = { + 0: 'MEM_POWER_FORCE_MODE_OFF', + 1: 'MEM_POWER_FORCE_MODE_LIGHT_SLEEP', + 2: 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', + 3: 'MEM_POWER_FORCE_MODE_SHUT_DOWN', +} +MEM_POWER_FORCE_MODE_OFF = 0 +MEM_POWER_FORCE_MODE_LIGHT_SLEEP = 1 +MEM_POWER_FORCE_MODE_DEEP_SLEEP = 2 +MEM_POWER_FORCE_MODE_SHUT_DOWN = 3 +MEM_PWR_FORCE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_STATUS' +MEM_PWR_STATUS__enumvalues = { + 0: 'MEM_POWER_STATUS_ON', + 1: 'MEM_POWER_STATUS_LIGHT_SLEEP', + 2: 'MEM_POWER_STATUS_DEEP_SLEEP', + 3: 'MEM_POWER_STATUS_SHUT_DOWN', +} +MEM_POWER_STATUS_ON = 0 +MEM_POWER_STATUS_LIGHT_SLEEP = 1 +MEM_POWER_STATUS_DEEP_SLEEP = 2 +MEM_POWER_STATUS_SHUT_DOWN = 3 +MEM_PWR_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_INT_MASK_MODE' +PIPE_INT_MASK_MODE__enumvalues = { + 0: 'PIPE_INT_MASK_MODE_DISABLE', + 1: 'PIPE_INT_MASK_MODE_ENABLE', +} +PIPE_INT_MASK_MODE_DISABLE = 0 +PIPE_INT_MASK_MODE_ENABLE = 1 +PIPE_INT_MASK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_INT_TYPE_MODE' +PIPE_INT_TYPE_MODE__enumvalues = { + 0: 'PIPE_INT_TYPE_MODE_DISABLE', + 1: 'PIPE_INT_TYPE_MODE_ENABLE', +} +PIPE_INT_TYPE_MODE_DISABLE = 0 +PIPE_INT_TYPE_MODE_ENABLE = 1 +PIPE_INT_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE' +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', +} +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CROB_MEM_PWR_LIGHT_SLEEP_MODE' +CROB_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +CROB_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_2X_MAGNIFY' +CURSOR_2X_MAGNIFY__enumvalues = { + 0: 'CURSOR_2X_MAGNIFY_IS_DISABLE', + 1: 'CURSOR_2X_MAGNIFY_IS_ENABLE', +} +CURSOR_2X_MAGNIFY_IS_DISABLE = 0 +CURSOR_2X_MAGNIFY_IS_ENABLE = 1 +CURSOR_2X_MAGNIFY = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_ENABLE' +CURSOR_ENABLE__enumvalues = { + 0: 'CURSOR_IS_DISABLE', + 1: 'CURSOR_IS_ENABLE', +} +CURSOR_IS_DISABLE = 0 +CURSOR_IS_ENABLE = 1 +CURSOR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_LINES_PER_CHUNK' +CURSOR_LINES_PER_CHUNK__enumvalues = { + 0: 'CURSOR_LINE_PER_CHUNK_1', + 1: 'CURSOR_LINE_PER_CHUNK_2', + 2: 'CURSOR_LINE_PER_CHUNK_4', + 3: 'CURSOR_LINE_PER_CHUNK_8', + 4: 'CURSOR_LINE_PER_CHUNK_16', +} +CURSOR_LINE_PER_CHUNK_1 = 0 +CURSOR_LINE_PER_CHUNK_2 = 1 +CURSOR_LINE_PER_CHUNK_4 = 2 +CURSOR_LINE_PER_CHUNK_8 = 3 +CURSOR_LINE_PER_CHUNK_16 = 4 +CURSOR_LINES_PER_CHUNK = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_MODE' +CURSOR_MODE__enumvalues = { + 0: 'CURSOR_MONO_2BIT', + 1: 'CURSOR_COLOR_24BIT_1BIT_AND', + 2: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'CURSOR_COLOR_64BIT_FP_PREMULT', + 5: 'CURSOR_COLOR_64BIT_FP_UNPREMULT', +} +CURSOR_MONO_2BIT = 0 +CURSOR_COLOR_24BIT_1BIT_AND = 1 +CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +CURSOR_COLOR_64BIT_FP_PREMULT = 4 +CURSOR_COLOR_64BIT_FP_UNPREMULT = 5 +CURSOR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_EN' +CURSOR_PERFMON_LATENCY_MEASURE_EN__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', +} +CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED = 0 +CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED = 1 +CURSOR_PERFMON_LATENCY_MEASURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_SEL' +CURSOR_PERFMON_LATENCY_MEASURE_SEL__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', +} +CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY = 0 +CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY = 1 +CURSOR_PERFMON_LATENCY_MEASURE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PITCH' +CURSOR_PITCH__enumvalues = { + 0: 'CURSOR_PITCH_64_PIXELS', + 1: 'CURSOR_PITCH_128_PIXELS', + 2: 'CURSOR_PITCH_256_PIXELS', +} +CURSOR_PITCH_64_PIXELS = 0 +CURSOR_PITCH_128_PIXELS = 1 +CURSOR_PITCH_256_PIXELS = 2 +CURSOR_PITCH = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_REQ_MODE' +CURSOR_REQ_MODE__enumvalues = { + 0: 'CURSOR_REQUEST_NORMALLY', + 1: 'CURSOR_REQUEST_EARLY', +} +CURSOR_REQUEST_NORMALLY = 0 +CURSOR_REQUEST_EARLY = 1 +CURSOR_REQ_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SNOOP' +CURSOR_SNOOP__enumvalues = { + 0: 'CURSOR_IS_NOT_SNOOP', + 1: 'CURSOR_IS_SNOOP', +} +CURSOR_IS_NOT_SNOOP = 0 +CURSOR_IS_SNOOP = 1 +CURSOR_SNOOP = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_STEREO_EN' +CURSOR_STEREO_EN__enumvalues = { + 0: 'CURSOR_STEREO_IS_DISABLED', + 1: 'CURSOR_STEREO_IS_ENABLED', +} +CURSOR_STEREO_IS_DISABLED = 0 +CURSOR_STEREO_IS_ENABLED = 1 +CURSOR_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SURFACE_TMZ' +CURSOR_SURFACE_TMZ__enumvalues = { + 0: 'CURSOR_SURFACE_IS_NOT_TMZ', + 1: 'CURSOR_SURFACE_IS_TMZ', +} +CURSOR_SURFACE_IS_NOT_TMZ = 0 +CURSOR_SURFACE_IS_TMZ = 1 +CURSOR_SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SYSTEM' +CURSOR_SYSTEM__enumvalues = { + 0: 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', + 1: 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', +} +CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS = 0 +CURSOR_IN_GUEST_PHYSICAL_ADDRESS = 1 +CURSOR_SYSTEM = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS' +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS__enumvalues = { + 0: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 1: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', +} +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0 = 0 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1 = 1 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_DONE' +DMDATA_DONE__enumvalues = { + 0: 'DMDATA_NOT_SENT_TO_DIG', + 1: 'DMDATA_SENT_TO_DIG', +} +DMDATA_NOT_SENT_TO_DIG = 0 +DMDATA_SENT_TO_DIG = 1 +DMDATA_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_MODE' +DMDATA_MODE__enumvalues = { + 0: 'DMDATA_SOFTWARE_UPDATE_MODE', + 1: 'DMDATA_HARDWARE_UPDATE_MODE', +} +DMDATA_SOFTWARE_UPDATE_MODE = 0 +DMDATA_HARDWARE_UPDATE_MODE = 1 +DMDATA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_QOS_MODE' +DMDATA_QOS_MODE__enumvalues = { + 0: 'DMDATA_QOS_LEVEL_FROM_TTU', + 1: 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', +} +DMDATA_QOS_LEVEL_FROM_TTU = 0 +DMDATA_QOS_LEVEL_FROM_SOFTWARE = 1 +DMDATA_QOS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_REPEAT' +DMDATA_REPEAT__enumvalues = { + 0: 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', + 1: 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', +} +DMDATA_USE_FOR_CURRENT_FRAME_ONLY = 0 +DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES = 1 +DMDATA_REPEAT = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW' +DMDATA_UNDERFLOW__enumvalues = { + 0: 'DMDATA_NOT_UNDERFLOW', + 1: 'DMDATA_UNDERFLOWED', +} +DMDATA_NOT_UNDERFLOW = 0 +DMDATA_UNDERFLOWED = 1 +DMDATA_UNDERFLOW = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW_CLEAR' +DMDATA_UNDERFLOW_CLEAR__enumvalues = { + 0: 'DMDATA_DONT_CLEAR', + 1: 'DMDATA_CLEAR_UNDERFLOW_STATUS', +} +DMDATA_DONT_CLEAR = 0 +DMDATA_CLEAR_UNDERFLOW_STATUS = 1 +DMDATA_UNDERFLOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UPDATED' +DMDATA_UPDATED__enumvalues = { + 0: 'DMDATA_NOT_UPDATED', + 1: 'DMDATA_WAS_UPDATED', +} +DMDATA_NOT_UPDATED = 0 +DMDATA_WAS_UPDATED = 1 +DMDATA_UPDATED = ctypes.c_uint32 # enum + +# values for enumeration 'RESPONSE_STATUS' +RESPONSE_STATUS__enumvalues = { + 0: 'OKAY', + 1: 'EXOKAY', + 2: 'SLVERR', + 3: 'DECERR', + 4: 'EARLY', + 5: 'OKAY_NODATA', + 6: 'PROTVIOL', + 7: 'TRANSERR', + 8: 'CMPTO', + 12: 'CRS', +} +OKAY = 0 +EXOKAY = 1 +SLVERR = 2 +DECERR = 3 +EARLY = 4 +OKAY_NODATA = 5 +PROTVIOL = 6 +TRANSERR = 7 +CMPTO = 8 +CRS = 12 +RESPONSE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE' +DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_MEM_PWR_DIS_MODE' +DCHUBBUB_MEM_PWR_DIS_MODE__enumvalues = { + 0: 'DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE', + 1: 'DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE', +} +DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE = 0 +DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE = 1 +DCHUBBUB_MEM_PWR_DIS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_MEM_PWR_MODE' +DCHUBBUB_MEM_PWR_MODE__enumvalues = { + 0: 'DCHUBBUB_MEM_POWER_MODE_OFF', + 1: 'DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP', + 2: 'DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP', + 3: 'DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN', +} +DCHUBBUB_MEM_POWER_MODE_OFF = 0 +DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP = 1 +DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP = 2 +DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN = 3 +DCHUBBUB_MEM_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CFG_VUPDATE_LOCK_SET' +MPC_CFG_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_MPC_TEST_CLK_SEL' +MPC_CFG_MPC_TEST_CLK_SEL__enumvalues = { + 0: 'MPC_CFG_MPC_TEST_CLK_SEL_0', + 1: 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 2: 'MPC_CFG_MPC_TEST_CLK_SEL_2', + 3: 'MPC_CFG_MPC_TEST_CLK_SEL_3', +} +MPC_CFG_MPC_TEST_CLK_SEL_0 = 0 +MPC_CFG_MPC_TEST_CLK_SEL_1 = 1 +MPC_CFG_MPC_TEST_CLK_SEL_2 = 2 +MPC_CFG_MPC_TEST_CLK_SEL_3 = 3 +MPC_CFG_MPC_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN' +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE', +} +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_INTERLACE_MODE' +MPC_CRC_CALC_INTERLACE_MODE__enumvalues = { + 0: 'MPC_CRC_INTERLACE_MODE_TOP', + 1: 'MPC_CRC_INTERLACE_MODE_BOTTOM', + 2: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 3: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', +} +MPC_CRC_INTERLACE_MODE_TOP = 0 +MPC_CRC_INTERLACE_MODE_BOTTOM = 1 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM = 2 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_MODE' +MPC_CRC_CALC_MODE__enumvalues = { + 0: 'MPC_CRC_ONE_SHOT_MODE', + 1: 'MPC_CRC_CONTINUOUS_MODE', +} +MPC_CRC_ONE_SHOT_MODE = 0 +MPC_CRC_CONTINUOUS_MODE = 1 +MPC_CRC_CALC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_STEREO_MODE' +MPC_CRC_CALC_STEREO_MODE__enumvalues = { + 0: 'MPC_CRC_STEREO_MODE_LEFT', + 1: 'MPC_CRC_STEREO_MODE_RIGHT', + 2: 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 3: 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', +} +MPC_CRC_STEREO_MODE_LEFT = 0 +MPC_CRC_STEREO_MODE_RIGHT = 1 +MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT = 2 +MPC_CRC_STEREO_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_SOURCE_SELECT' +MPC_CRC_SOURCE_SELECT__enumvalues = { + 0: 'MPC_CRC_SOURCE_SEL_DPP', + 1: 'MPC_CRC_SOURCE_SEL_OPP', + 2: 'MPC_CRC_SOURCE_SEL_DWB', + 3: 'MPC_CRC_SOURCE_SEL_OTHER', +} +MPC_CRC_SOURCE_SEL_DPP = 0 +MPC_CRC_SOURCE_SEL_OPP = 1 +MPC_CRC_SOURCE_SEL_DWB = 2 +MPC_CRC_SOURCE_SEL_OTHER = 3 +MPC_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_DEBUG_BUS1_DATA_SELECT' +MPC_DEBUG_BUS1_DATA_SELECT__enumvalues = { + 0: 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_CFG', + 1: 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_CONT', + 2: 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV1', + 3: 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV', +} +MPC_DEBUG_BUS1_DATA_SELECT_MPC_CFG = 0 +MPC_DEBUG_BUS1_DATA_SELECT_MPC_CONT = 1 +MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV1 = 2 +MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV = 3 +MPC_DEBUG_BUS1_DATA_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_DEBUG_BUS2_DATA_SELECT' +MPC_DEBUG_BUS2_DATA_SELECT__enumvalues = { + 0: 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC', + 1: 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC_CONT', + 2: 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC_MCM', + 3: 'MPC_DEBUG_BUS2_DATA_SELECT_RES', +} +MPC_DEBUG_BUS2_DATA_SELECT_MPCC = 0 +MPC_DEBUG_BUS2_DATA_SELECT_MPCC_CONT = 1 +MPC_DEBUG_BUS2_DATA_SELECT_MPCC_MCM = 2 +MPC_DEBUG_BUS2_DATA_SELECT_RES = 3 +MPC_DEBUG_BUS2_DATA_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT' +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT__enumvalues = { + 0: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_DEBUG_ID', + 1: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_DEBUG_ID', + 2: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_OGAM_DEBUG_ID', + 3: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_OCSC_DEBUG_ID', + 4: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFR_DEBUG_DATA', + 5: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFT_DEBUG_DATA', + 6: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_RSV1', + 7: 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_MCM_DEBUG_ID', +} +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_DEBUG_ID = 0 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_DEBUG_ID = 1 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_OGAM_DEBUG_ID = 2 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_OCSC_DEBUG_ID = 3 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFR_DEBUG_DATA = 4 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFT_DEBUG_DATA = 5 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_RSV1 = 6 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_MCM_DEBUG_ID = 7 +MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_DEBUG_BUS_MPCC_BYTE_SELECT' +MPC_DEBUG_BUS_MPCC_BYTE_SELECT__enumvalues = { + 0: 'MPC_DEBUG_BUS_MPCC_BYTE0', + 1: 'MPC_DEBUG_BUS_MPCC_BYTE1', + 2: 'MPC_DEBUG_BUS_MPCC_BYTE2', + 3: 'MPC_DEBUG_BUS_MPCC_BYTE3', +} +MPC_DEBUG_BUS_MPCC_BYTE0 = 0 +MPC_DEBUG_BUS_MPCC_BYTE1 = 1 +MPC_DEBUG_BUS_MPCC_BYTE2 = 2 +MPC_DEBUG_BUS_MPCC_BYTE3 = 3 +MPC_DEBUG_BUS_MPCC_BYTE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OCSC_COEF_FORMAT' +MPC_OCSC_COEF_FORMAT__enumvalues = { + 0: 'MPC_OCSC_COEF_FORMAT_S2_13', + 1: 'MPC_OCSC_COEF_FORMAT_S3_12', +} +MPC_OCSC_COEF_FORMAT_S2_13 = 0 +MPC_OCSC_COEF_FORMAT_S3_12 = 1 +MPC_OCSC_COEF_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN' +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE', +} +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_CSC_MODE' +MPC_OUT_CSC_MODE__enumvalues = { + 0: 'MPC_OUT_CSC_MODE_0', + 1: 'MPC_OUT_CSC_MODE_1', + 2: 'MPC_OUT_CSC_MODE_2', + 3: 'MPC_OUT_CSC_MODE_RSV', +} +MPC_OUT_CSC_MODE_0 = 0 +MPC_OUT_CSC_MODE_1 = 1 +MPC_OUT_CSC_MODE_2 = 2 +MPC_OUT_CSC_MODE_RSV = 3 +MPC_OUT_CSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE' +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE__enumvalues = { + 0: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 1: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 2: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 3: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 4: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 5: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 6: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 7: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', +} +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS = 0 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS = 1 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS = 2 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS = 3 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS = 4 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS = 5 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS = 6 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH = 7 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_RATE_CONTROL_DISABLE_SET' +MPC_OUT_RATE_CONTROL_DISABLE_SET__enumvalues = { + 0: 'MPC_OUT_RATE_CONTROL_SET_ENABLE', + 1: 'MPC_OUT_RATE_CONTROL_SET_DISABLE', +} +MPC_OUT_RATE_CONTROL_SET_ENABLE = 0 +MPC_OUT_RATE_CONTROL_SET_DISABLE = 1 +MPC_OUT_RATE_CONTROL_DISABLE_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_BG_COLOR_BPC' +MPCC_BG_COLOR_BPC__enumvalues = { + 0: 'MPCC_BG_COLOR_BPC_8bit', + 1: 'MPCC_BG_COLOR_BPC_9bit', + 2: 'MPCC_BG_COLOR_BPC_10bit', + 3: 'MPCC_BG_COLOR_BPC_11bit', + 4: 'MPCC_BG_COLOR_BPC_12bit', +} +MPCC_BG_COLOR_BPC_8bit = 0 +MPCC_BG_COLOR_BPC_9bit = 1 +MPCC_BG_COLOR_BPC_10bit = 2 +MPCC_BG_COLOR_BPC_11bit = 3 +MPCC_BG_COLOR_BPC_12bit = 4 +MPCC_BG_COLOR_BPC = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY' +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 1: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', +} +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE = 0 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE = 1 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE' +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 1: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 2: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 3: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', +} +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA = 0 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN = 1 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA = 2 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED = 3 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE' +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 1: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', +} +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE = 0 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE = 1 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE' +MPCC_CONTROL_MPCC_BOT_GAIN_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 1: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', +} +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0 = 0 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1 = 1 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_MODE' +MPCC_CONTROL_MPCC_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 1: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 2: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 3: 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', +} +MPCC_CONTROL_MPCC_MODE_BYPASS = 0 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH = 1 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY = 2 +MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING = 3 +MPCC_CONTROL_MPCC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_EN' +MPCC_SM_CONTROL_MPCC_SM_EN__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_EN_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_EN_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT' +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT' +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_MODE' +MPCC_SM_CONTROL_MPCC_SM_MODE__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 2: 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 4: 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 6: 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', +} +MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE = 0 +MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING = 2 +MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING = 4 +MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING = 6 +MPCC_SM_CONTROL_MPCC_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN' +MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_TRUE', +} +MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM' +MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM__enumvalues = { + 0: 'MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13', + 1: 'MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12', +} +MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13 = 0 +MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12 = 1 +MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_GAMUT_REMAP_MODE_ENUM' +MPCC_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'MPCC_GAMUT_REMAP_MODE_0', + 1: 'MPCC_GAMUT_REMAP_MODE_1', + 2: 'MPCC_GAMUT_REMAP_MODE_2', + 3: 'MPCC_GAMUT_REMAP_MODE_RSV', +} +MPCC_GAMUT_REMAP_MODE_0 = 0 +MPCC_GAMUT_REMAP_MODE_1 = 1 +MPCC_GAMUT_REMAP_MODE_2 = 2 +MPCC_GAMUT_REMAP_MODE_RSV = 3 +MPCC_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_2_CONFIG_ENUM' +MPCC_OGAM_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'MPCC_OGAM_LUT_2CFG_NO_MEMORY', + 1: 'MPCC_OGAM_LUT_2CFG_MEMORY_A', + 2: 'MPCC_OGAM_LUT_2CFG_MEMORY_B', +} +MPCC_OGAM_LUT_2CFG_NO_MEMORY = 0 +MPCC_OGAM_LUT_2CFG_MEMORY_A = 1 +MPCC_OGAM_LUT_2CFG_MEMORY_B = 2 +MPCC_OGAM_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_CONFIG_MODE' +MPCC_OGAM_LUT_CONFIG_MODE__enumvalues = { + 0: 'MPCC_OGAM_DIFFERENT_RGB', + 1: 'MPCC_OGAM_ALL_USE_R', +} +MPCC_OGAM_DIFFERENT_RGB = 0 +MPCC_OGAM_ALL_USE_R = 1 +MPCC_OGAM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_PWL_DISABLE_ENUM' +MPCC_OGAM_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'MPCC_OGAM_ENABLE_PWL', + 1: 'MPCC_OGAM_DISABLE_PWL', +} +MPCC_OGAM_ENABLE_PWL = 0 +MPCC_OGAM_DISABLE_PWL = 1 +MPCC_OGAM_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL' +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 1: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', +} +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA = 0 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB = 1 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_RAM_SEL' +MPCC_OGAM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_OGAM_RAMA_ACCESS', + 1: 'MPCC_OGAM_RAMB_ACCESS', +} +MPCC_OGAM_RAMA_ACCESS = 0 +MPCC_OGAM_RAMB_ACCESS = 1 +MPCC_OGAM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_READ_COLOR_SEL' +MPCC_OGAM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'MPCC_OGAM_BLUE_LUT', + 1: 'MPCC_OGAM_GREEN_LUT', + 2: 'MPCC_OGAM_RED_LUT', +} +MPCC_OGAM_BLUE_LUT = 0 +MPCC_OGAM_GREEN_LUT = 1 +MPCC_OGAM_RED_LUT = 2 +MPCC_OGAM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_READ_DBG' +MPCC_OGAM_LUT_READ_DBG__enumvalues = { + 0: 'MPCC_OGAM_DISABLE_DEBUG', + 1: 'MPCC_OGAM_ENABLE_DEBUG', +} +MPCC_OGAM_DISABLE_DEBUG = 0 +MPCC_OGAM_ENABLE_DEBUG = 1 +MPCC_OGAM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_SEL_ENUM' +MPCC_OGAM_LUT_SEL_ENUM__enumvalues = { + 0: 'MPCC_OGAM_RAMA', + 1: 'MPCC_OGAM_RAMB', +} +MPCC_OGAM_RAMA = 0 +MPCC_OGAM_RAMB = 1 +MPCC_OGAM_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM' +MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM__enumvalues = { + 0: 'MPCC_OGAM_MODE_0', + 1: 'MPCC_OGAM_MODE_RSV1', + 2: 'MPCC_OGAM_MODE_2', + 3: 'MPCC_OGAM_MODE_RSV', +} +MPCC_OGAM_MODE_0 = 0 +MPCC_OGAM_MODE_RSV1 = 1 +MPCC_OGAM_MODE_2 = 2 +MPCC_OGAM_MODE_RSV = 3 +MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_NUM_SEG' +MPCC_OGAM_NUM_SEG__enumvalues = { + 0: 'MPCC_OGAM_SEGMENTS_1', + 1: 'MPCC_OGAM_SEGMENTS_2', + 2: 'MPCC_OGAM_SEGMENTS_4', + 3: 'MPCC_OGAM_SEGMENTS_8', + 4: 'MPCC_OGAM_SEGMENTS_16', + 5: 'MPCC_OGAM_SEGMENTS_32', + 6: 'MPCC_OGAM_SEGMENTS_64', + 7: 'MPCC_OGAM_SEGMENTS_128', +} +MPCC_OGAM_SEGMENTS_1 = 0 +MPCC_OGAM_SEGMENTS_2 = 1 +MPCC_OGAM_SEGMENTS_4 = 2 +MPCC_OGAM_SEGMENTS_8 = 3 +MPCC_OGAM_SEGMENTS_16 = 4 +MPCC_OGAM_SEGMENTS_32 = 5 +MPCC_OGAM_SEGMENTS_64 = 6 +MPCC_OGAM_SEGMENTS_128 = 7 +MPCC_OGAM_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN' +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE', +} +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_30BIT_ENUM' +MPCC_MCM_3DLUT_30BIT_ENUM__enumvalues = { + 0: 'MPCC_MCM_3DLUT_36BIT', + 1: 'MPCC_MCM_3DLUT_30BIT', +} +MPCC_MCM_3DLUT_36BIT = 0 +MPCC_MCM_3DLUT_30BIT = 1 +MPCC_MCM_3DLUT_30BIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_RAM_SEL' +MPCC_MCM_3DLUT_RAM_SEL__enumvalues = { + 0: 'MPCC_MCM_RAM0_ACCESS', + 1: 'MPCC_MCM_RAM1_ACCESS', + 2: 'MPCC_MCM_RAM2_ACCESS', + 3: 'MPCC_MCM_RAM3_ACCESS', +} +MPCC_MCM_RAM0_ACCESS = 0 +MPCC_MCM_RAM1_ACCESS = 1 +MPCC_MCM_RAM2_ACCESS = 2 +MPCC_MCM_RAM3_ACCESS = 3 +MPCC_MCM_3DLUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_SIZE_ENUM' +MPCC_MCM_3DLUT_SIZE_ENUM__enumvalues = { + 0: 'MPCC_MCM_3DLUT_17CUBE', + 1: 'MPCC_MCM_3DLUT_9CUBE', +} +MPCC_MCM_3DLUT_17CUBE = 0 +MPCC_MCM_3DLUT_9CUBE = 1 +MPCC_MCM_3DLUT_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_MODE_ENUM' +MPCC_MCM_GAMMA_LUT_MODE_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_BYPASS', + 1: 'MPCC_MCM_GAMMA_LUT_RESERVED_1', + 2: 'MPCC_MCM_GAMMA_LUT_RAM_LUT', + 3: 'MPCC_MCM_GAMMA_LUT_RESERVED_3', +} +MPCC_MCM_GAMMA_LUT_BYPASS = 0 +MPCC_MCM_GAMMA_LUT_RESERVED_1 = 1 +MPCC_MCM_GAMMA_LUT_RAM_LUT = 2 +MPCC_MCM_GAMMA_LUT_RESERVED_3 = 3 +MPCC_MCM_GAMMA_LUT_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM' +MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_ENABLE_PWL', + 1: 'MPCC_MCM_GAMMA_LUT_DISABLE_PWL', +} +MPCC_MCM_GAMMA_LUT_ENABLE_PWL = 0 +MPCC_MCM_GAMMA_LUT_DISABLE_PWL = 1 +MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_SEL_ENUM' +MPCC_MCM_GAMMA_LUT_SEL_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_RAMA', + 1: 'MPCC_MCM_GAMMA_LUT_RAMB', +} +MPCC_MCM_GAMMA_LUT_RAMA = 0 +MPCC_MCM_GAMMA_LUT_RAMB = 1 +MPCC_MCM_GAMMA_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_2_MODE_ENUM' +MPCC_MCM_LUT_2_MODE_ENUM__enumvalues = { + 0: 'MPCC_MCM_LUT_2_MODE_BYPASS', + 1: 'MPCC_MCM_LUT_2_MODE_RAMA_LUT', + 2: 'MPCC_MCM_LUT_2_MODE_RAMB_LUT', +} +MPCC_MCM_LUT_2_MODE_BYPASS = 0 +MPCC_MCM_LUT_2_MODE_RAMA_LUT = 1 +MPCC_MCM_LUT_2_MODE_RAMB_LUT = 2 +MPCC_MCM_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_CONFIG_MODE' +MPCC_MCM_LUT_CONFIG_MODE__enumvalues = { + 0: 'MPCC_MCM_LUT_DIFFERENT_RGB', + 1: 'MPCC_MCM_LUT_ALL_USE_R', +} +MPCC_MCM_LUT_DIFFERENT_RGB = 0 +MPCC_MCM_LUT_ALL_USE_R = 1 +MPCC_MCM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_NUM_SEG' +MPCC_MCM_LUT_NUM_SEG__enumvalues = { + 0: 'MPCC_MCM_LUT_SEGMENTS_1', + 1: 'MPCC_MCM_LUT_SEGMENTS_2', + 2: 'MPCC_MCM_LUT_SEGMENTS_4', + 3: 'MPCC_MCM_LUT_SEGMENTS_8', + 4: 'MPCC_MCM_LUT_SEGMENTS_16', + 5: 'MPCC_MCM_LUT_SEGMENTS_32', + 6: 'MPCC_MCM_LUT_SEGMENTS_64', + 7: 'MPCC_MCM_LUT_SEGMENTS_128', +} +MPCC_MCM_LUT_SEGMENTS_1 = 0 +MPCC_MCM_LUT_SEGMENTS_2 = 1 +MPCC_MCM_LUT_SEGMENTS_4 = 2 +MPCC_MCM_LUT_SEGMENTS_8 = 3 +MPCC_MCM_LUT_SEGMENTS_16 = 4 +MPCC_MCM_LUT_SEGMENTS_32 = 5 +MPCC_MCM_LUT_SEGMENTS_64 = 6 +MPCC_MCM_LUT_SEGMENTS_128 = 7 +MPCC_MCM_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_RAM_SEL' +MPCC_MCM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_MCM_LUT_RAMA_ACCESS', + 1: 'MPCC_MCM_LUT_RAMB_ACCESS', +} +MPCC_MCM_LUT_RAMA_ACCESS = 0 +MPCC_MCM_LUT_RAMB_ACCESS = 1 +MPCC_MCM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_READ_COLOR_SEL' +MPCC_MCM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'MPCC_MCM_LUT_BLUE_LUT', + 1: 'MPCC_MCM_LUT_GREEN_LUT', + 2: 'MPCC_MCM_LUT_RED_LUT', +} +MPCC_MCM_LUT_BLUE_LUT = 0 +MPCC_MCM_LUT_GREEN_LUT = 1 +MPCC_MCM_LUT_RED_LUT = 2 +MPCC_MCM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_READ_DBG' +MPCC_MCM_LUT_READ_DBG__enumvalues = { + 0: 'MPCC_MCM_LUT_DISABLE_DEBUG', + 1: 'MPCC_MCM_LUT_ENABLE_DEBUG', +} +MPCC_MCM_LUT_DISABLE_DEBUG = 0 +MPCC_MCM_LUT_ENABLE_DEBUG = 1 +MPCC_MCM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_MEM_PWR_FORCE_ENUM' +MPCC_MCM_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'MPCC_MCM_MEM_PWR_FORCE_DIS', + 1: 'MPCC_MCM_MEM_PWR_FORCE_LS', + 2: 'MPCC_MCM_MEM_PWR_FORCE_DS', + 3: 'MPCC_MCM_MEM_PWR_FORCE_SD', +} +MPCC_MCM_MEM_PWR_FORCE_DIS = 0 +MPCC_MCM_MEM_PWR_FORCE_LS = 1 +MPCC_MCM_MEM_PWR_FORCE_DS = 2 +MPCC_MCM_MEM_PWR_FORCE_SD = 3 +MPCC_MCM_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_MEM_PWR_STATE_ENUM' +MPCC_MCM_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'MPCC_MCM_MEM_PWR_STATE_ON', + 1: 'MPCC_MCM_MEM_PWR_STATE_LS', + 2: 'MPCC_MCM_MEM_PWR_STATE_DS', + 3: 'MPCC_MCM_MEM_PWR_STATE_SD', +} +MPCC_MCM_MEM_PWR_STATE_ON = 0 +MPCC_MCM_MEM_PWR_STATE_LS = 1 +MPCC_MCM_MEM_PWR_STATE_DS = 2 +MPCC_MCM_MEM_PWR_STATE_SD = 3 +MPCC_MCM_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_BIT_DEPTH' +ENUM_DPG_BIT_DEPTH__enumvalues = { + 0: 'ENUM_DPG_BIT_DEPTH_6BPC', + 1: 'ENUM_DPG_BIT_DEPTH_8BPC', + 2: 'ENUM_DPG_BIT_DEPTH_10BPC', + 3: 'ENUM_DPG_BIT_DEPTH_12BPC', +} +ENUM_DPG_BIT_DEPTH_6BPC = 0 +ENUM_DPG_BIT_DEPTH_8BPC = 1 +ENUM_DPG_BIT_DEPTH_10BPC = 2 +ENUM_DPG_BIT_DEPTH_12BPC = 3 +ENUM_DPG_BIT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_DYNAMIC_RANGE' +ENUM_DPG_DYNAMIC_RANGE__enumvalues = { + 0: 'ENUM_DPG_DYNAMIC_RANGE_VESA', + 1: 'ENUM_DPG_DYNAMIC_RANGE_CEA', +} +ENUM_DPG_DYNAMIC_RANGE_VESA = 0 +ENUM_DPG_DYNAMIC_RANGE_CEA = 1 +ENUM_DPG_DYNAMIC_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_EN' +ENUM_DPG_EN__enumvalues = { + 0: 'ENUM_DPG_DISABLE', + 1: 'ENUM_DPG_ENABLE', +} +ENUM_DPG_DISABLE = 0 +ENUM_DPG_ENABLE = 1 +ENUM_DPG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_FIELD_POLARITY' +ENUM_DPG_FIELD_POLARITY__enumvalues = { + 0: 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 1: 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', +} +ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD = 0 +ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN = 1 +ENUM_DPG_FIELD_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_MODE' +ENUM_DPG_MODE__enumvalues = { + 0: 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 1: 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 2: 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 3: 'ENUM_DPG_MODE_VERTICAL_BAR', + 4: 'ENUM_DPG_MODE_HORIZONTAL_BAR', + 5: 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 6: 'ENUM_DPG_MODE_RGB_DUAL_RAMP', + 7: 'ENUM_DPG_MODE_RGB_XR_BIAS', +} +ENUM_DPG_MODE_RGB_COLOUR_BLOCK = 0 +ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK = 1 +ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK = 2 +ENUM_DPG_MODE_VERTICAL_BAR = 3 +ENUM_DPG_MODE_HORIZONTAL_BAR = 4 +ENUM_DPG_MODE_RGB_SINGLE_RAMP = 5 +ENUM_DPG_MODE_RGB_DUAL_RAMP = 6 +ENUM_DPG_MODE_RGB_XR_BIAS = 7 +ENUM_DPG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_DIS_CTRL' +FMTMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 1: 'FMTMEM_DISABLE_MEM_PWR_CTRL', +} +FMTMEM_ENABLE_MEM_PWR_CTRL = 0 +FMTMEM_DISABLE_MEM_PWR_CTRL = 1 +FMTMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_FORCE_CTRL' +FMTMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'FMTMEM_NO_FORCE_REQUEST', + 1: 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', +} +FMTMEM_NO_FORCE_REQUEST = 0 +FMTMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +FMTMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +FMTMEM_FORCE_SHUT_DOWN_REQUEST = 3 +FMTMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL' +FMT_BIT_DEPTH_CONTROL_25FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 1: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 2: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 3: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei = 0 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi = 1 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi = 2 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL' +FMT_BIT_DEPTH_CONTROL_50FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 1: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 2: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 3: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', +} +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A = 0 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B = 1 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C = 2 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D = 3 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL' +FMT_BIT_DEPTH_CONTROL_75FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 1: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 2: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 3: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E = 0 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F = 1 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G = 2 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2 = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4 = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CLAMP_CNTL_COLOR_FORMAT' +FMT_CLAMP_CNTL_COLOR_FORMAT__enumvalues = { + 0: 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 1: 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 2: 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 3: 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 4: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 5: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 6: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 7: 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', +} +FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC = 0 +FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC = 1 +FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC = 2 +FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC = 3 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1 = 4 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2 = 5 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3 = 6 +FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE = 7 +FMT_CLAMP_CNTL_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS' +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS__enumvalues = { + 0: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 1: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', +} +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE = 0 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE = 1 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_PIXEL_ENCODING' +FMT_CONTROL_PIXEL_ENCODING__enumvalues = { + 0: 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 1: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 2: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 3: 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', +} +FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444 = 0 +FMT_CONTROL_PIXEL_ENCODING_YCBCR422 = 1 +FMT_CONTROL_PIXEL_ENCODING_YCBCR420 = 2 +FMT_CONTROL_PIXEL_ENCODING_RESERVED = 3 +FMT_CONTROL_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_MODE' +FMT_CONTROL_SUBSAMPLING_MODE__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 1: 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 2: 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 3: 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', +} +FMT_CONTROL_SUBSAMPLING_MODE_DROP = 0 +FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE = 1 +FMT_CONTROL_SUBSAMPLING_MOME_3_TAP = 2 +FMT_CONTROL_SUBSAMPLING_MOME_RESERVED = 3 +FMT_CONTROL_SUBSAMPLING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_ORDER' +FMT_CONTROL_SUBSAMPLING_ORDER__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 1: 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', +} +FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR = 0 +FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB = 1 +FMT_CONTROL_SUBSAMPLING_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DEBUG_CNTL_COLOR_SELECT' +FMT_DEBUG_CNTL_COLOR_SELECT__enumvalues = { + 0: 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 1: 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 2: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 3: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', +} +FMT_DEBUG_CNTL_COLOR_SELECT_BLUE = 0 +FMT_DEBUG_CNTL_COLOR_SELECT_GREEN = 1 +FMT_DEBUG_CNTL_COLOR_SELECT_RED1 = 2 +FMT_DEBUG_CNTL_COLOR_SELECT_RED2 = 3 +FMT_DEBUG_CNTL_COLOR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DYNAMIC_EXP_MODE' +FMT_DYNAMIC_EXP_MODE__enumvalues = { + 0: 'FMT_DYNAMIC_EXP_MODE_10to12', + 1: 'FMT_DYNAMIC_EXP_MODE_8to12', +} +FMT_DYNAMIC_EXP_MODE_10to12 = 0 +FMT_DYNAMIC_EXP_MODE_8to12 = 1 +FMT_DYNAMIC_EXP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_FRAME_RANDOM_ENABLE_CONTROL' +FMT_FRAME_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 1: 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', +} +FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME = 0 +FMT_FRAME_RANDOM_ENABLE_RESET_ONCE = 1 +FMT_FRAME_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_POWER_STATE_ENUM' +FMT_POWER_STATE_ENUM__enumvalues = { + 0: 'FMT_POWER_STATE_ENUM_ON', + 1: 'FMT_POWER_STATE_ENUM_LS', + 2: 'FMT_POWER_STATE_ENUM_DS', + 3: 'FMT_POWER_STATE_ENUM_SD', +} +FMT_POWER_STATE_ENUM_ON = 0 +FMT_POWER_STATE_ENUM_LS = 1 +FMT_POWER_STATE_ENUM_DS = 2 +FMT_POWER_STATE_ENUM_SD = 3 +FMT_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_RGB_RANDOM_ENABLE_CONTROL' +FMT_RGB_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 1: 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', +} +FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE = 0 +FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE = 1 +FMT_RGB_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL' +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 1: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 2: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 3: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', +} +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP = 0 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1 = 1 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2 = 2 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED = 3 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_MODE' +FMT_SPATIAL_DITHER_MODE__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_MODE_0', + 1: 'FMT_SPATIAL_DITHER_MODE_1', + 2: 'FMT_SPATIAL_DITHER_MODE_2', + 3: 'FMT_SPATIAL_DITHER_MODE_3', +} +FMT_SPATIAL_DITHER_MODE_0 = 0 +FMT_SPATIAL_DITHER_MODE_1 = 1 +FMT_SPATIAL_DITHER_MODE_2 = 2 +FMT_SPATIAL_DITHER_MODE_3 = 3 +FMT_SPATIAL_DITHER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_STEREOSYNC_OVERRIDE_CONTROL' +FMT_STEREOSYNC_OVERRIDE_CONTROL__enumvalues = { + 0: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 1: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', +} +FMT_STEREOSYNC_OVERRIDE_CONTROL_0 = 0 +FMT_STEREOSYNC_OVERRIDE_CONTROL_1 = 1 +FMT_STEREOSYNC_OVERRIDE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0' +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0__enumvalues = { + 0: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 1: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', +} +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR = 0 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB = 1 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0 = ctypes.c_uint32 # enum + +# values for enumeration 'OPPBUF_DISPLAY_SEGMENTATION' +OPPBUF_DISPLAY_SEGMENTATION__enumvalues = { + 0: 'OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT', + 1: 'OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT', + 2: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT', + 3: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT', + 4: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT', +} +OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT = 0 +OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT = 1 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT = 2 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT = 3 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT = 4 +OPPBUF_DISPLAY_SEGMENTATION = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CLOCK_ENABLE_CONTROL' +OPP_PIPE_CLOCK_ENABLE_CONTROL__enumvalues = { + 0: 'OPP_PIPE_CLOCK_DISABLE', + 1: 'OPP_PIPE_CLOCK_ENABLE', +} +OPP_PIPE_CLOCK_DISABLE = 0 +OPP_PIPE_CLOCK_ENABLE = 1 +OPP_PIPE_CLOCK_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL' +OPP_PIPE_DIGTIAL_BYPASS_CONTROL__enumvalues = { + 0: 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 1: 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', +} +OPP_PIPE_DIGTIAL_BYPASS_DISABLE = 0 +OPP_PIPE_DIGTIAL_BYPASS_ENABLE = 1 +OPP_PIPE_DIGTIAL_BYPASS_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_CONT_EN' +OPP_PIPE_CRC_CONT_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_MODE_ONE_SHOT', + 1: 'OPP_PIPE_CRC_MODE_CONTINUOUS', +} +OPP_PIPE_CRC_MODE_ONE_SHOT = 0 +OPP_PIPE_CRC_MODE_CONTINUOUS = 1 +OPP_PIPE_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_EN' +OPP_PIPE_CRC_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_DISABLE', + 1: 'OPP_PIPE_CRC_ENABLE', +} +OPP_PIPE_CRC_DISABLE = 0 +OPP_PIPE_CRC_ENABLE = 1 +OPP_PIPE_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_EN' +OPP_PIPE_CRC_INTERLACE_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 1: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', +} +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE = 0 +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED = 1 +OPP_PIPE_CRC_INTERLACE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_MODE' +OPP_PIPE_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', + 1: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 3: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', +} +OPP_PIPE_CRC_INTERLACE_MODE_TOP = 0 +OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM = 1 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD = 2 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD = 3 +OPP_PIPE_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_ONE_SHOT_PENDING' +OPP_PIPE_CRC_ONE_SHOT_PENDING__enumvalues = { + 0: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 1: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', +} +OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING = 0 +OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING = 1 +OPP_PIPE_CRC_ONE_SHOT_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_PIXEL_SELECT' +OPP_PIPE_CRC_PIXEL_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 1: 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 2: 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 3: 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', +} +OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS = 0 +OPP_PIPE_CRC_PIXEL_SELECT_RESERVED = 1 +OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS = 2 +OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS = 3 +OPP_PIPE_CRC_PIXEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_SOURCE_SELECT' +OPP_PIPE_CRC_SOURCE_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 1: 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', +} +OPP_PIPE_CRC_SOURCE_SELECT_FMT = 0 +OPP_PIPE_CRC_SOURCE_SELECT_SFT = 1 +OPP_PIPE_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_EN' +OPP_PIPE_CRC_STEREO_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 1: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', +} +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO = 0 +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO = 1 +OPP_PIPE_CRC_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_MODE' +OPP_PIPE_CRC_STEREO_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_MODE_LEFT', + 1: 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 2: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 3: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', +} +OPP_PIPE_CRC_STEREO_MODE_LEFT = 0 +OPP_PIPE_CRC_STEREO_MODE_RIGHT = 1 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE = 2 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE = 3 +OPP_PIPE_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_ABM_DEBUG_BUS_SELECT_CONTROL' +OPP_ABM_DEBUG_BUS_SELECT_CONTROL__enumvalues = { + 0: 'DEBUG_BUS_SELECT_ABM0', + 1: 'DEBUG_BUS_SELECT_ABM1', + 2: 'DEBUG_BUS_SELECT_ABM2', + 3: 'DEBUG_BUS_SELECT_ABM3', + 4: 'DEBUG_BUS_SELECT_ABM_RESERVED0', + 5: 'DEBUG_BUS_SELECT_ABM_RESERVED1', +} +DEBUG_BUS_SELECT_ABM0 = 0 +DEBUG_BUS_SELECT_ABM1 = 1 +DEBUG_BUS_SELECT_ABM2 = 2 +DEBUG_BUS_SELECT_ABM3 = 3 +DEBUG_BUS_SELECT_ABM_RESERVED0 = 4 +DEBUG_BUS_SELECT_ABM_RESERVED1 = 5 +OPP_ABM_DEBUG_BUS_SELECT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_DPG_DEBUG_BUS_SELECT_CONTROL' +OPP_DPG_DEBUG_BUS_SELECT_CONTROL__enumvalues = { + 0: 'DEBUG_BUS_SELECT_DPG0', + 1: 'DEBUG_BUS_SELECT_DPG1', + 2: 'DEBUG_BUS_SELECT_DPG2', + 3: 'DEBUG_BUS_SELECT_DPG3', + 4: 'DEBUG_BUS_SELECT_DPG_RESERVED0', + 5: 'DEBUG_BUS_SELECT_DPG_RESERVED1', +} +DEBUG_BUS_SELECT_DPG0 = 0 +DEBUG_BUS_SELECT_DPG1 = 1 +DEBUG_BUS_SELECT_DPG2 = 2 +DEBUG_BUS_SELECT_DPG3 = 3 +DEBUG_BUS_SELECT_DPG_RESERVED0 = 4 +DEBUG_BUS_SELECT_DPG_RESERVED1 = 5 +OPP_DPG_DEBUG_BUS_SELECT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_FMT_DEBUG_BUS_SELECT_CONTROL' +OPP_FMT_DEBUG_BUS_SELECT_CONTROL__enumvalues = { + 0: 'DEBUG_BUS_SELECT_FMT0', + 1: 'DEBUG_BUS_SELECT_FMT1', + 2: 'DEBUG_BUS_SELECT_FMT2', + 3: 'DEBUG_BUS_SELECT_FMT3', + 4: 'DEBUG_BUS_SELECT_FMT_RESERVED0', + 5: 'DEBUG_BUS_SELECT_FMT_RESERVED1', +} +DEBUG_BUS_SELECT_FMT0 = 0 +DEBUG_BUS_SELECT_FMT1 = 1 +DEBUG_BUS_SELECT_FMT2 = 2 +DEBUG_BUS_SELECT_FMT3 = 3 +DEBUG_BUS_SELECT_FMT_RESERVED0 = 4 +DEBUG_BUS_SELECT_FMT_RESERVED1 = 5 +OPP_FMT_DEBUG_BUS_SELECT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_OPPBUF_DEBUG_BUS_SELECT_CONTROL' +OPP_OPPBUF_DEBUG_BUS_SELECT_CONTROL__enumvalues = { + 0: 'DEBUG_BUS_SELECT_OPPBUF0', + 1: 'DEBUG_BUS_SELECT_OPPBUF1', + 2: 'DEBUG_BUS_SELECT_OPPBUF2', + 3: 'DEBUG_BUS_SELECT_OPPBUF3', + 4: 'DEBUG_BUS_SELECT_OPPBUF_RESERVED0', + 5: 'DEBUG_BUS_SELECT_OPPBUF_RESERVED1', +} +DEBUG_BUS_SELECT_OPPBUF0 = 0 +DEBUG_BUS_SELECT_OPPBUF1 = 1 +DEBUG_BUS_SELECT_OPPBUF2 = 2 +DEBUG_BUS_SELECT_OPPBUF3 = 3 +DEBUG_BUS_SELECT_OPPBUF_RESERVED0 = 4 +DEBUG_BUS_SELECT_OPPBUF_RESERVED1 = 5 +OPP_OPPBUF_DEBUG_BUS_SELECT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_OPP_PIPE_DEBUG_BUS_SELECT_CONTROL' +OPP_OPP_PIPE_DEBUG_BUS_SELECT_CONTROL__enumvalues = { + 0: 'DEBUG_BUS_SELECT_OPP_PIPE0', + 1: 'DEBUG_BUS_SELECT_OPP_PIPE1', + 2: 'DEBUG_BUS_SELECT_OPP_PIPE2', + 3: 'DEBUG_BUS_SELECT_OPP_PIPE3', + 4: 'DEBUG_BUS_SELECT_OPP_PIPE_RESERVED0', + 5: 'DEBUG_BUS_SELECT_OPP_PIPE_RESERVED1', +} +DEBUG_BUS_SELECT_OPP_PIPE0 = 0 +DEBUG_BUS_SELECT_OPP_PIPE1 = 1 +DEBUG_BUS_SELECT_OPP_PIPE2 = 2 +DEBUG_BUS_SELECT_OPP_PIPE3 = 3 +DEBUG_BUS_SELECT_OPP_PIPE_RESERVED0 = 4 +DEBUG_BUS_SELECT_OPP_PIPE_RESERVED1 = 5 +OPP_OPP_PIPE_DEBUG_BUS_SELECT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TEST_CLK_SEL_CONTROL' +OPP_TEST_CLK_SEL_CONTROL__enumvalues = { + 0: 'OPP_TEST_CLK_SEL_DISPCLK_P', + 1: 'OPP_TEST_CLK_SEL_DISPCLK_R', + 2: 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', + 3: 'OPP_TEST_CLK_SEL_DISPCLK_ABM1', + 4: 'OPP_TEST_CLK_SEL_DISPCLK_ABM2', + 5: 'OPP_TEST_CLK_SEL_DISPCLK_ABM3', + 6: 'OPP_TEST_CLK_SEL_RESERVED0', + 7: 'OPP_TEST_CLK_SEL_RESERVED1', + 8: 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', + 9: 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', + 10: 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', + 11: 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', + 12: 'OPP_TEST_CLK_SEL_RESERVED2', + 13: 'OPP_TEST_CLK_SEL_RESERVED3', +} +OPP_TEST_CLK_SEL_DISPCLK_P = 0 +OPP_TEST_CLK_SEL_DISPCLK_R = 1 +OPP_TEST_CLK_SEL_DISPCLK_ABM0 = 2 +OPP_TEST_CLK_SEL_DISPCLK_ABM1 = 3 +OPP_TEST_CLK_SEL_DISPCLK_ABM2 = 4 +OPP_TEST_CLK_SEL_DISPCLK_ABM3 = 5 +OPP_TEST_CLK_SEL_RESERVED0 = 6 +OPP_TEST_CLK_SEL_RESERVED1 = 7 +OPP_TEST_CLK_SEL_DISPCLK_OPP0 = 8 +OPP_TEST_CLK_SEL_DISPCLK_OPP1 = 9 +OPP_TEST_CLK_SEL_DISPCLK_OPP2 = 10 +OPP_TEST_CLK_SEL_DISPCLK_OPP3 = 11 +OPP_TEST_CLK_SEL_RESERVED2 = 12 +OPP_TEST_CLK_SEL_RESERVED3 = 13 +OPP_TEST_CLK_SEL_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_ENABLE_STATUS' +OPP_TOP_CLOCK_ENABLE_STATUS__enumvalues = { + 0: 'OPP_TOP_CLOCK_DISABLED_STATUS', + 1: 'OPP_TOP_CLOCK_ENABLED_STATUS', +} +OPP_TOP_CLOCK_DISABLED_STATUS = 0 +OPP_TOP_CLOCK_ENABLED_STATUS = 1 +OPP_TOP_CLOCK_ENABLE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_GATING_CONTROL' +OPP_TOP_CLOCK_GATING_CONTROL__enumvalues = { + 0: 'OPP_TOP_CLOCK_GATING_ENABLED', + 1: 'OPP_TOP_CLOCK_GATING_DISABLED', +} +OPP_TOP_CLOCK_GATING_ENABLED = 0 +OPP_TOP_CLOCK_GATING_DISABLED = 1 +OPP_TOP_CLOCK_GATING_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DSCRM_EN' +ENUM_DSCRM_EN__enumvalues = { + 0: 'ENUM_DSCRM_DISABLE', + 1: 'ENUM_DSCRM_ENABLE', +} +ENUM_DSCRM_DISABLE = 0 +ENUM_DSCRM_ENABLE = 1 +ENUM_DSCRM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK' +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_SEL' +MASTER_UPDATE_LOCK_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_SEL_0', + 1: 'MASTER_UPDATE_LOCK_SEL_1', + 2: 'MASTER_UPDATE_LOCK_SEL_2', + 3: 'MASTER_UPDATE_LOCK_SEL_3', + 4: 'MASTER_UPDATE_LOCK_SEL_RESERVED4', + 5: 'MASTER_UPDATE_LOCK_SEL_RESERVED5', +} +MASTER_UPDATE_LOCK_SEL_0 = 0 +MASTER_UPDATE_LOCK_SEL_1 = 1 +MASTER_UPDATE_LOCK_SEL_2 = 2 +MASTER_UPDATE_LOCK_SEL_3 = 3 +MASTER_UPDATE_LOCK_SEL_RESERVED4 = 4 +MASTER_UPDATE_LOCK_SEL_RESERVED5 = 5 +MASTER_UPDATE_LOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE' +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE__enumvalues = { + 0: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 1: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 2: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 3: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', +} +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH = 0 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP = 1 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM = 2 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED = 3 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 2: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 3: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE = 2 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED = 3 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL' +OTG_CONTROL_OTG_DISABLE_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 1: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 2: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE', + 3: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', +} +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE = 0 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT = 1 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE = 2 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST = 3 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL' +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', +} +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY' +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', +} +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_MASTER_EN' +OTG_CONTROL_OTG_MASTER_EN__enumvalues = { + 0: 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 1: 'OTG_CONTROL_OTG_MASTER_EN_TRUE', +} +OTG_CONTROL_OTG_MASTER_EN_FALSE = 0 +OTG_CONTROL_OTG_MASTER_EN_TRUE = 1 +OTG_CONTROL_OTG_MASTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_OUT_MUX' +OTG_CONTROL_OTG_OUT_MUX__enumvalues = { + 0: 'OTG_CONTROL_OTG_OUT_MUX_0', + 1: 'OTG_CONTROL_OTG_OUT_MUX_1', + 2: 'OTG_CONTROL_OTG_OUT_MUX_2', +} +OTG_CONTROL_OTG_OUT_MUX_0 = 0 +OTG_CONTROL_OTG_OUT_MUX_1 = 1 +OTG_CONTROL_OTG_OUT_MUX_2 = 2 +OTG_CONTROL_OTG_OUT_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_START_POINT_CNTL' +OTG_CONTROL_OTG_START_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', +} +OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_START_POINT_CNTL_DP = 1 +OTG_CONTROL_OTG_START_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN' +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN__enumvalues = { + 0: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 1: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', +} +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE = 0 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE = 1 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC1_EN' +OTG_CRC_CNTL_OTG_CRC1_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC1_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC1_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC1_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC1_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC1_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_CONT_EN' +OTG_CRC_CNTL_OTG_CRC_CONT_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE' +OTG_CRC_CNTL_OTG_CRC_CONT_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET', + 1: 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET', +} +OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET = 0 +OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET = 1 +OTG_CRC_CNTL_OTG_CRC_CONT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_EN' +OTG_CRC_CNTL_OTG_CRC_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE' +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 1: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 3: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', +} +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP = 0 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM = 1 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM = 2 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD = 3 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE' +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 1: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 2: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 3: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', +} +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT = 0 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT = 1 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES = 2 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS = 3 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS' +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DIG_UPDATE_VCOUNT_MODE' +OTG_DIG_UPDATE_VCOUNT_MODE__enumvalues = { + 0: 'OTG_DIG_UPDATE_VCOUNT_0', + 1: 'OTG_DIG_UPDATE_VCOUNT_1', +} +OTG_DIG_UPDATE_VCOUNT_0 = 0 +OTG_DIG_UPDATE_VCOUNT_1 = 1 +OTG_DIG_UPDATE_VCOUNT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE' +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1', + 2: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2', + 3: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0 = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1 = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2 = 2 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3 = 3 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY' +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME' +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME__enumvalues = { + 0: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 1: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 2: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 3: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', +} +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME = 0 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME = 1 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME = 2 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME = 3 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN' +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN__enumvalues = { + 0: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 1: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', +} +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE = 0 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE = 1 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 2: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 3: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 4: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 5: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 6: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 7: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 8: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 9: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 10: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 11: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 12: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 13: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 14: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 15: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED', + 16: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 17: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 18: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 19: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0 = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1 = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA = 2 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB = 3 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC = 4 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD = 5 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE = 6 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF = 7 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1 = 8 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2 = 9 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA = 10 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK = 11 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA = 12 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK = 13 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 14 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED = 15 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK = 16 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC = 17 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA = 18 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB = 19 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 2: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 3: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT = 2 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED = 3 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL' +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL__enumvalues = { + 0: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 1: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 2: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 3: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 4: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4', + 5: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5', +} +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0 = 0 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1 = 1 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2 = 2 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3 = 3 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4 = 4 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5 = 5 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL' +OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL__enumvalues = { + 0: 'DIG_UPDATE_EYE_SEL_BOTH', + 1: 'DIG_UPDATE_EYE_SEL_LEFT', + 2: 'DIG_UPDATE_EYE_SEL_RIGHT', +} +DIG_UPDATE_EYE_SEL_BOTH = 0 +DIG_UPDATE_EYE_SEL_LEFT = 1 +DIG_UPDATE_EYE_SEL_RIGHT = 2 +OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL' +OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL__enumvalues = { + 0: 'DIG_UPDATE_FIELD_SEL_BOTH', + 1: 'DIG_UPDATE_FIELD_SEL_TOP', + 2: 'DIG_UPDATE_FIELD_SEL_BOTTOM', + 3: 'DIG_UPDATE_FIELD_SEL_RESERVED', +} +DIG_UPDATE_FIELD_SEL_BOTH = 0 +DIG_UPDATE_FIELD_SEL_TOP = 1 +DIG_UPDATE_FIELD_SEL_BOTTOM = 2 +DIG_UPDATE_FIELD_SEL_RESERVED = 3 +OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 2: 'MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM', + 3: 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', +} +MASTER_UPDATE_LOCK_DB_FIELD_BOTH = 0 +MASTER_UPDATE_LOCK_DB_FIELD_TOP = 1 +MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM = 2 +MASTER_UPDATE_LOCK_DB_FIELD_RESERVED = 3 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 2: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 3: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', +} +MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH = 0 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT = 1 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT = 2 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED = 3 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_UPDATE_LOCK_EN' +OTG_GLOBAL_UPDATE_LOCK_EN__enumvalues = { + 0: 'OTG_GLOBAL_UPDATE_LOCK_DISABLE', + 1: 'OTG_GLOBAL_UPDATE_LOCK_ENABLE', +} +OTG_GLOBAL_UPDATE_LOCK_DISABLE = 0 +OTG_GLOBAL_UPDATE_LOCK_ENABLE = 1 +OTG_GLOBAL_UPDATE_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GSL_MASTER_MODE' +OTG_GSL_MASTER_MODE__enumvalues = { + 0: 'OTG_GSL_MASTER_MODE_0', + 1: 'OTG_GSL_MASTER_MODE_1', + 2: 'OTG_GSL_MASTER_MODE_2', + 3: 'OTG_GSL_MASTER_MODE_3', +} +OTG_GSL_MASTER_MODE_0 = 0 +OTG_GSL_MASTER_MODE_1 = 1 +OTG_GSL_MASTER_MODE_2 = 2 +OTG_GSL_MASTER_MODE_3 = 3 +OTG_GSL_MASTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_HORZ_REPETITION_COUNT' +OTG_HORZ_REPETITION_COUNT__enumvalues = { + 0: 'OTG_HORZ_REPETITION_COUNT_0', + 1: 'OTG_HORZ_REPETITION_COUNT_1', + 2: 'OTG_HORZ_REPETITION_COUNT_2', + 3: 'OTG_HORZ_REPETITION_COUNT_3', + 4: 'OTG_HORZ_REPETITION_COUNT_4', + 5: 'OTG_HORZ_REPETITION_COUNT_5', + 6: 'OTG_HORZ_REPETITION_COUNT_6', + 7: 'OTG_HORZ_REPETITION_COUNT_7', + 8: 'OTG_HORZ_REPETITION_COUNT_8', + 9: 'OTG_HORZ_REPETITION_COUNT_9', + 10: 'OTG_HORZ_REPETITION_COUNT_10', + 11: 'OTG_HORZ_REPETITION_COUNT_11', + 12: 'OTG_HORZ_REPETITION_COUNT_12', + 13: 'OTG_HORZ_REPETITION_COUNT_13', + 14: 'OTG_HORZ_REPETITION_COUNT_14', + 15: 'OTG_HORZ_REPETITION_COUNT_15', +} +OTG_HORZ_REPETITION_COUNT_0 = 0 +OTG_HORZ_REPETITION_COUNT_1 = 1 +OTG_HORZ_REPETITION_COUNT_2 = 2 +OTG_HORZ_REPETITION_COUNT_3 = 3 +OTG_HORZ_REPETITION_COUNT_4 = 4 +OTG_HORZ_REPETITION_COUNT_5 = 5 +OTG_HORZ_REPETITION_COUNT_6 = 6 +OTG_HORZ_REPETITION_COUNT_7 = 7 +OTG_HORZ_REPETITION_COUNT_8 = 8 +OTG_HORZ_REPETITION_COUNT_9 = 9 +OTG_HORZ_REPETITION_COUNT_10 = 10 +OTG_HORZ_REPETITION_COUNT_11 = 11 +OTG_HORZ_REPETITION_COUNT_12 = 12 +OTG_HORZ_REPETITION_COUNT_13 = 13 +OTG_HORZ_REPETITION_COUNT_14 = 14 +OTG_HORZ_REPETITION_COUNT_15 = 15 +OTG_HORZ_REPETITION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_SYNC_A_POL' +OTG_H_SYNC_A_POL__enumvalues = { + 0: 'OTG_H_SYNC_A_POL_HIGH', + 1: 'OTG_H_SYNC_A_POL_LOW', +} +OTG_H_SYNC_A_POL_HIGH = 0 +OTG_H_SYNC_A_POL_LOW = 1 +OTG_H_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_MODE' +OTG_H_TIMING_DIV_MODE__enumvalues = { + 0: 'OTG_H_TIMING_DIV_MODE_NO_DIV', + 1: 'OTG_H_TIMING_DIV_MODE_DIV_BY2', + 2: 'OTG_H_TIMING_DIV_MODE_RESERVED', + 3: 'OTG_H_TIMING_DIV_MODE_DIV_BY4', +} +OTG_H_TIMING_DIV_MODE_NO_DIV = 0 +OTG_H_TIMING_DIV_MODE_DIV_BY2 = 1 +OTG_H_TIMING_DIV_MODE_RESERVED = 2 +OTG_H_TIMING_DIV_MODE_DIV_BY4 = 3 +OTG_H_TIMING_DIV_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_MODE_MANUAL' +OTG_H_TIMING_DIV_MODE_MANUAL__enumvalues = { + 0: 'OTG_H_TIMING_DIV_MODE_AUTO', + 1: 'OTG_H_TIMING_DIV_MODE_NOAUTO', +} +OTG_H_TIMING_DIV_MODE_AUTO = 0 +OTG_H_TIMING_DIV_MODE_NOAUTO = 1 +OTG_H_TIMING_DIV_MODE_MANUAL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 2: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 3: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP = 2 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2 = 3 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE' +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE__enumvalues = { + 0: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 1: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', +} +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE = 0 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE = 1 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_DB_EN' +OTG_MASTER_UPDATE_LOCK_DB_EN__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_DISABLE', + 1: 'OTG_MASTER_UPDATE_LOCK_ENABLE', +} +OTG_MASTER_UPDATE_LOCK_DISABLE = 0 +OTG_MASTER_UPDATE_LOCK_ENABLE = 1 +OTG_MASTER_UPDATE_LOCK_DB_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_GSL_EN' +OTG_MASTER_UPDATE_LOCK_GSL_EN__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 1: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', +} +OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE = 0 +OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE = 1 +OTG_MASTER_UPDATE_LOCK_GSL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE' +OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_VCOUNT_0', + 1: 'OTG_MASTER_UPDATE_LOCK_VCOUNT_1', +} +OTG_MASTER_UPDATE_LOCK_VCOUNT_0 = 0 +OTG_MASTER_UPDATE_LOCK_VCOUNT_1 = 1 +OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL' +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL__enumvalues = { + 0: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 1: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 2: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 3: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', +} +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE = 0 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA = 1 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB = 2 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED = 3 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR' +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR__enumvalues = { + 0: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 1: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', +} +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE = 0 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE = 1 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL' +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE', +} +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE = 0 +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE = 1 +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EN' +OTG_STEREO_CONTROL_OTG_STEREO_EN__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE' +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE__enumvalues = { + 0: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 1: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 2: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 3: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', +} +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO = 0 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT = 1 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT = 2 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED = 3 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR' +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', +} +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN' +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4 = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14', + 15: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14 = 14 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FREQUENCY_SELECT' +OTG_TRIGA_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGA_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGA_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGA_FREQUENCY_SELECT_3', +} +OTG_TRIGA_FREQUENCY_SELECT_0 = 0 +OTG_TRIGA_FREQUENCY_SELECT_1 = 1 +OTG_TRIGA_FREQUENCY_SELECT_2 = 2 +OTG_TRIGA_FREQUENCY_SELECT_3 = 3 +OTG_TRIGA_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL' +OTG_TRIGA_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR' +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', +} +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN' +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4 = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14', + 15: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14 = 14 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FREQUENCY_SELECT' +OTG_TRIGB_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGB_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGB_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGB_FREQUENCY_SELECT_3', +} +OTG_TRIGB_FREQUENCY_SELECT_0 = 0 +OTG_TRIGB_FREQUENCY_SELECT_1 = 1 +OTG_TRIGB_FREQUENCY_SELECT_2 = 2 +OTG_TRIGB_FREQUENCY_SELECT_3 = 3 +OTG_TRIGB_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL' +OTG_TRIGB_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK' +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK__enumvalues = { + 0: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 1: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', +} +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE = 0 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE = 1 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE' +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 2: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 3: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', +} +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE = 0 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA = 1 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB = 2 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED = 3 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR' +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', +} +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE = 0 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE = 1 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR' +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR__enumvalues = { + 0: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 1: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', +} +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE = 0 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE = 1 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VUPDATE_BLOCK_DISABLE' +OTG_VUPDATE_BLOCK_DISABLE__enumvalues = { + 0: 'OTG_VUPDATE_BLOCK_DISABLE_OFF', + 1: 'OTG_VUPDATE_BLOCK_DISABLE_ON', +} +OTG_VUPDATE_BLOCK_DISABLE_OFF = 0 +OTG_VUPDATE_BLOCK_DISABLE_ON = 1 +OTG_VUPDATE_BLOCK_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_SYNC_A_POL' +OTG_V_SYNC_A_POL__enumvalues = { + 0: 'OTG_V_SYNC_A_POL_HIGH', + 1: 'OTG_V_SYNC_A_POL_LOW', +} +OTG_V_SYNC_A_POL_HIGH = 0 +OTG_V_SYNC_A_POL_LOW = 1 +OTG_V_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_SYNC_MODE' +OTG_V_SYNC_MODE__enumvalues = { + 0: 'OTG_V_SYNC_MODE_HSYNC', + 1: 'OTG_V_SYNC_MODE_HBLANK', +} +OTG_V_SYNC_MODE_HSYNC = 0 +OTG_V_SYNC_MODE_HBLANK = 1 +OTG_V_SYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD' +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 1: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', +} +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0 = 0 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1 = 1 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK' +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK__enumvalues = { + 0: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE', + 1: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE', +} +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE = 0 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE = 1 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL' +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL__enumvalues = { + 0: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0', + 1: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1', + 2: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2', + 3: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3', + 4: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4', + 5: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5', +} +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0 = 0 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1 = 1 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2 = 2 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3 = 3 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4 = 4 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5 = 5 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_INT_TYPE' +DC_DMCUB_INT_TYPE__enumvalues = { + 0: 'INT_LEVEL', + 1: 'INT_PULSE', +} +INT_LEVEL = 0 +INT_PULSE = 1 +DC_DMCUB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_TIMER_WINDOW' +DC_DMCUB_TIMER_WINDOW__enumvalues = { + 0: 'BITS_31_0', + 1: 'BITS_32_1', + 2: 'BITS_33_2', + 3: 'BITS_34_3', + 4: 'BITS_35_4', + 5: 'BITS_36_5', + 6: 'BITS_37_6', + 7: 'BITS_38_7', +} +BITS_31_0 = 0 +BITS_32_1 = 1 +BITS_33_2 = 2 +BITS_34_3 = 3 +BITS_35_4 = 4 +BITS_36_5 = 5 +BITS_37_6 = 6 +BITS_38_7 = 7 +DC_DMCUB_TIMER_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'INVALID_REG_ACCESS_TYPE' +INVALID_REG_ACCESS_TYPE__enumvalues = { + 0: 'REG_UNALLOCATED_ADDR_WRITE', + 1: 'REG_UNALLOCATED_ADDR_READ', + 2: 'REG_VIRTUAL_WRITE', + 3: 'REG_VIRTUAL_READ', + 4: 'REG_SECURE_VIOLATE_WRITE', + 5: 'REG_SECURE_VIOLATE_READ', +} +REG_UNALLOCATED_ADDR_WRITE = 0 +REG_UNALLOCATED_ADDR_READ = 1 +REG_VIRTUAL_WRITE = 2 +REG_VIRTUAL_READ = 3 +REG_SECURE_VIOLATE_WRITE = 4 +REG_SECURE_VIOLATE_READ = 5 +INVALID_REG_ACCESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_READ_SELECT' +DMU_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 1: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 2: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 3: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 4: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 5: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 6: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 7: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 8: 'RESERVED_8', + 9: 'RESERVED_9', + 10: 'RESERVED_10', + 11: 'RESERVED_11', + 12: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 13: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 14: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 15: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 16: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 17: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 18: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 19: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 20: 'RESERVED_20', + 21: 'RESERVED_21', + 22: 'RESERVED_22', + 23: 'RESERVED_23', + 24: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 25: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 26: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 27: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 28: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 29: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 30: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 31: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 32: 'RESERVED_32', + 33: 'RESERVED_33', + 34: 'RESERVED_34', + 35: 'RESERVED_35', + 36: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 37: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 38: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 39: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 40: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 41: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 42: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 43: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 44: 'RESERVED_44', + 45: 'RESERVED_45', + 46: 'RESERVED_46', + 47: 'RESERVED_47', + 48: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 49: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 50: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 51: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 52: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 53: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 54: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 55: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 56: 'RESERVED_56', + 57: 'RESERVED_57', + 58: 'RESERVED_58', + 59: 'RESERVED_59', + 60: 'RESERVED_60', + 61: 'RESERVED_61', + 62: 'RESERVED_62', + 63: 'RESERVED_63', + 64: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 65: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 66: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 67: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 68: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 69: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 70: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 71: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 72: 'RESERVED_72', + 73: 'RESERVED_73', + 74: 'RESERVED_74', + 75: 'RESERVED_75', + 76: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 77: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 78: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 79: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 80: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 81: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 82: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 83: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 84: 'RESERVED_84', + 85: 'RESERVED_85', + 86: 'RESERVED_86', + 87: 'RESERVED_87', + 88: 'RESERVED_88', + 89: 'RESERVED_89', + 90: 'RESERVED_90', + 91: 'RESERVED_91', +} +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0 = 0 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1 = 1 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2 = 2 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3 = 3 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4 = 4 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5 = 5 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6 = 6 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7 = 7 +RESERVED_8 = 8 +RESERVED_9 = 9 +RESERVED_10 = 10 +RESERVED_11 = 11 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12 = 12 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13 = 13 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14 = 14 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15 = 15 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16 = 16 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17 = 17 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18 = 18 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19 = 19 +RESERVED_20 = 20 +RESERVED_21 = 21 +RESERVED_22 = 22 +RESERVED_23 = 23 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24 = 24 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25 = 25 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26 = 26 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27 = 27 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28 = 28 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29 = 29 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30 = 30 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31 = 31 +RESERVED_32 = 32 +RESERVED_33 = 33 +RESERVED_34 = 34 +RESERVED_35 = 35 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36 = 36 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37 = 37 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38 = 38 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39 = 39 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40 = 40 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41 = 41 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42 = 42 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43 = 43 +RESERVED_44 = 44 +RESERVED_45 = 45 +RESERVED_46 = 46 +RESERVED_47 = 47 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48 = 48 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49 = 49 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50 = 50 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51 = 51 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52 = 52 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53 = 53 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54 = 54 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55 = 55 +RESERVED_56 = 56 +RESERVED_57 = 57 +RESERVED_58 = 58 +RESERVED_59 = 59 +RESERVED_60 = 60 +RESERVED_61 = 61 +RESERVED_62 = 62 +RESERVED_63 = 63 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64 = 64 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65 = 65 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66 = 66 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67 = 67 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68 = 68 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69 = 69 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70 = 70 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71 = 71 +RESERVED_72 = 72 +RESERVED_73 = 73 +RESERVED_74 = 74 +RESERVED_75 = 75 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76 = 76 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77 = 77 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78 = 78 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79 = 79 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80 = 80 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81 = 81 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82 = 82 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83 = 83 +RESERVED_84 = 84 +RESERVED_85 = 85 +RESERVED_86 = 86 +RESERVED_87 = 87 +RESERVED_88 = 88 +RESERVED_89 = 89 +RESERVED_90 = 90 +RESERVED_91 = 91 +DMU_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_START_POSITION' +DMU_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DMU_GPU_TIMER_START_0_END_27', + 1: 'DMU_GPU_TIMER_START_1_END_28', + 2: 'DMU_GPU_TIMER_START_2_END_29', + 3: 'DMU_GPU_TIMER_START_3_END_30', + 4: 'DMU_GPU_TIMER_START_4_END_31', + 5: 'DMU_GPU_TIMER_START_6_END_33', + 6: 'DMU_GPU_TIMER_START_8_END_35', + 7: 'DMU_GPU_TIMER_START_10_END_37', +} +DMU_GPU_TIMER_START_0_END_27 = 0 +DMU_GPU_TIMER_START_1_END_28 = 1 +DMU_GPU_TIMER_START_2_END_29 = 2 +DMU_GPU_TIMER_START_3_END_30 = 3 +DMU_GPU_TIMER_START_4_END_31 = 4 +DMU_GPU_TIMER_START_6_END_33 = 5 +DMU_GPU_TIMER_START_8_END_35 = 6 +DMU_GPU_TIMER_START_10_END_37 = 7 +DMU_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'IHC_INTERRUPT_DEST' +IHC_INTERRUPT_DEST__enumvalues = { + 0: 'INTERRUPT_SENT_TO_IH', + 1: 'INTERRUPT_SENT_TO_DMCUB', +} +INTERRUPT_SENT_TO_IH = 0 +INTERRUPT_SENT_TO_DMCUB = 1 +IHC_INTERRUPT_DEST = ctypes.c_uint32 # enum + +# values for enumeration 'IHC_INTERRUPT_LINE_STATUS' +IHC_INTERRUPT_LINE_STATUS__enumvalues = { + 0: 'INTERRUPT_LINE_NOT_ASSERTED', + 1: 'INTERRUPT_LINE_ASSERTED', +} +INTERRUPT_LINE_NOT_ASSERTED = 0 +INTERRUPT_LINE_ASSERTED = 1 +IHC_INTERRUPT_LINE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DC_SMU_INTERRUPT_ENABLE' +DC_SMU_INTERRUPT_ENABLE__enumvalues = { + 0: 'DISABLE_THE_INTERRUPT', + 1: 'ENABLE_THE_INTERRUPT', +} +DISABLE_THE_INTERRUPT = 0 +ENABLE_THE_INTERRUPT = 1 +DC_SMU_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_CLOCK_ON' +DMU_CLOCK_ON__enumvalues = { + 0: 'DMU_CLOCK_STATUS_ON', + 1: 'DMU_CLOCK_STATUS_OFF', +} +DMU_CLOCK_STATUS_ON = 0 +DMU_CLOCK_STATUS_OFF = 1 +DMU_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'SMU_INTR' +SMU_INTR__enumvalues = { + 0: 'SMU_MSG_INTR_NOOP', + 1: 'SET_SMU_MSG_INTR', +} +SMU_MSG_INTR_NOOP = 0 +SET_SMU_MSG_INTR = 1 +SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'ALLOW_SR_ON_TRANS_REQ' +ALLOW_SR_ON_TRANS_REQ__enumvalues = { + 0: 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 1: 'ALLOW_SR_ON_TRANS_REQ_DISABLE', +} +ALLOW_SR_ON_TRANS_REQ_ENABLE = 0 +ALLOW_SR_ON_TRANS_REQ_DISABLE = 1 +ALLOW_SR_ON_TRANS_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'AMCLOCK_ENABLE' +AMCLOCK_ENABLE__enumvalues = { + 0: 'ENABLE_AMCLK0', + 1: 'ENABLE_AMCLK1', +} +ENABLE_AMCLK0 = 0 +ENABLE_AMCLK1 = 1 +AMCLOCK_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CLEAR_SMU_INTR' +CLEAR_SMU_INTR__enumvalues = { + 0: 'SMU_INTR_STATUS_NOOP', + 1: 'SMU_INTR_STATUS_CLEAR', +} +SMU_INTR_STATUS_NOOP = 0 +SMU_INTR_STATUS_CLEAR = 1 +CLEAR_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_BRANCH_SOFT_RESET' +CLOCK_BRANCH_SOFT_RESET__enumvalues = { + 0: 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 1: 'CLOCK_BRANCH_SOFT_RESET_FORCE', +} +CLOCK_BRANCH_SOFT_RESET_NOOP = 0 +CLOCK_BRANCH_SOFT_RESET_FORCE = 1 +CLOCK_BRANCH_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO0_SOURCE_SEL' +DCCG_AUDIO_DTO0_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 1: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 2: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 3: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 4: 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', +} +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0 = 0 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1 = 1 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2 = 2 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3 = 3 +DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED = 4 +DCCG_AUDIO_DTO0_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO2_SOURCE_SEL' +DCCG_AUDIO_DTO2_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 1: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2', +} +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0 = 0 +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2 = 1 +DCCG_AUDIO_DTO2_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_SEL' +DCCG_AUDIO_DTO_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', + 1: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 2: 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', + 3: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO_DTBCLK', +} +DCCG_AUDIO_DTO_SEL_AUDIO_DTO0 = 0 +DCCG_AUDIO_DTO_SEL_AUDIO_DTO1 = 1 +DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO = 2 +DCCG_AUDIO_DTO_SEL_AUDIO_DTO_DTBCLK = 3 +DCCG_AUDIO_DTO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_USE_512FBR_DTO' +DCCG_AUDIO_DTO_USE_512FBR_DTO__enumvalues = { + 0: 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 1: 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', +} +DCCG_AUDIO_DTO_USE_128FBR_FOR_DP = 0 +DCCG_AUDIO_DTO_USE_512FBR_FOR_DP = 1 +DCCG_AUDIO_DTO_USE_512FBR_DTO = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_BLOCK_SEL' +DCCG_DBG_BLOCK_SEL__enumvalues = { + 0: 'DCCG_DBG_BLOCK_SEL_DCCG', + 1: 'DCCG_DBG_BLOCK_SEL_PMON', + 2: 'DCCG_DBG_BLOCK_SEL_PMON2', +} +DCCG_DBG_BLOCK_SEL_DCCG = 0 +DCCG_DBG_BLOCK_SEL_PMON = 1 +DCCG_DBG_BLOCK_SEL_PMON2 = 2 +DCCG_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_EN' +DCCG_DBG_EN__enumvalues = { + 0: 'DCCG_DBG_EN_DISABLE', + 1: 'DCCG_DBG_EN_ENABLE', +} +DCCG_DBG_EN_DISABLE = 0 +DCCG_DBG_EN_ENABLE = 1 +DCCG_DBG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DEEP_COLOR_CNTL' +DCCG_DEEP_COLOR_CNTL__enumvalues = { + 0: 'DCCG_DEEP_COLOR_DTO_DISABLE', + 1: 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', + 2: 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 3: 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', +} +DCCG_DEEP_COLOR_DTO_DISABLE = 0 +DCCG_DEEP_COLOR_DTO_5_4_RATIO = 1 +DCCG_DEEP_COLOR_DTO_3_2_RATIO = 2 +DCCG_DEEP_COLOR_DTO_2_1_RATIO = 3 +DCCG_DEEP_COLOR_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_OVR_EN' +DCCG_FIFO_ERRDET_OVR_EN__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_OVR_DISABLE', + 1: 'DCCG_FIFO_ERRDET_OVR_ENABLE', +} +DCCG_FIFO_ERRDET_OVR_DISABLE = 0 +DCCG_FIFO_ERRDET_OVR_ENABLE = 1 +DCCG_FIFO_ERRDET_OVR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_RESET' +DCCG_FIFO_ERRDET_RESET__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_RESET_NOOP', + 1: 'DCCG_FIFO_ERRDET_RESET_FORCE', +} +DCCG_FIFO_ERRDET_RESET_NOOP = 0 +DCCG_FIFO_ERRDET_RESET_FORCE = 1 +DCCG_FIFO_ERRDET_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_STATE' +DCCG_FIFO_ERRDET_STATE__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 1: 'DCCG_FIFO_ERRDET_STATE_DETECTION', +} +DCCG_FIFO_ERRDET_STATE_CALIBRATION = 0 +DCCG_FIFO_ERRDET_STATE_DETECTION = 1 +DCCG_FIFO_ERRDET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_HSYNC' +DCCG_PERF_MODE_HSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_HSYNC_NOOP', + 1: 'DCCG_PERF_MODE_HSYNC_START', +} +DCCG_PERF_MODE_HSYNC_NOOP = 0 +DCCG_PERF_MODE_HSYNC_START = 1 +DCCG_PERF_MODE_HSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_VSYNC' +DCCG_PERF_MODE_VSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_VSYNC_NOOP', + 1: 'DCCG_PERF_MODE_VSYNC_START', +} +DCCG_PERF_MODE_VSYNC_NOOP = 0 +DCCG_PERF_MODE_VSYNC_START = 1 +DCCG_PERF_MODE_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_OTG_SELECT' +DCCG_PERF_OTG_SELECT__enumvalues = { + 0: 'DCCG_PERF_SEL_OTG0', + 1: 'DCCG_PERF_SEL_OTG1', + 2: 'DCCG_PERF_SEL_OTG2', + 3: 'DCCG_PERF_SEL_OTG3', + 4: 'DCCG_PERF_SEL_RESERVED', +} +DCCG_PERF_SEL_OTG0 = 0 +DCCG_PERF_SEL_OTG1 = 1 +DCCG_PERF_SEL_OTG2 = 2 +DCCG_PERF_SEL_OTG3 = 3 +DCCG_PERF_SEL_RESERVED = 4 +DCCG_PERF_OTG_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_RUN' +DCCG_PERF_RUN__enumvalues = { + 0: 'DCCG_PERF_RUN_NOOP', + 1: 'DCCG_PERF_RUN_START', +} +DCCG_PERF_RUN_NOOP = 0 +DCCG_PERF_RUN_START = 1 +DCCG_PERF_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'DC_MEM_GLOBAL_PWR_REQ_DIS' +DC_MEM_GLOBAL_PWR_REQ_DIS__enumvalues = { + 0: 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 1: 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', +} +DC_MEM_GLOBAL_PWR_REQ_ENABLE = 0 +DC_MEM_GLOBAL_PWR_REQ_DISABLE = 1 +DC_MEM_GLOBAL_PWR_REQ_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_FIFO_ERROR' +DIO_FIFO_ERROR__enumvalues = { + 0: 'DIO_FIFO_ERROR_00', + 1: 'DIO_FIFO_ERROR_01', + 2: 'DIO_FIFO_ERROR_10', + 3: 'DIO_FIFO_ERROR_11', +} +DIO_FIFO_ERROR_00 = 0 +DIO_FIFO_ERROR_01 = 1 +DIO_FIFO_ERROR_10 = 2 +DIO_FIFO_ERROR_11 = 3 +DIO_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING' +DISABLE_CLOCK_GATING__enumvalues = { + 0: 'CLOCK_GATING_ENABLED', + 1: 'CLOCK_GATING_DISABLED', +} +CLOCK_GATING_ENABLED = 0 +CLOCK_GATING_DISABLED = 1 +DISABLE_CLOCK_GATING = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING_IN_DCO' +DISABLE_CLOCK_GATING_IN_DCO__enumvalues = { + 0: 'CLOCK_GATING_ENABLED_IN_DCO', + 1: 'CLOCK_GATING_DISABLED_IN_DCO', +} +CLOCK_GATING_ENABLED_IN_DCO = 0 +CLOCK_GATING_DISABLED_IN_DCO = 1 +DISABLE_CLOCK_GATING_IN_DCO = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_CHG_FWD_CORR_DISABLE' +DISPCLK_CHG_FWD_CORR_DISABLE__enumvalues = { + 0: 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 1: 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', +} +DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING = 0 +DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING = 1 +DISPCLK_CHG_FWD_CORR_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_FREQ_RAMP_DONE' +DISPCLK_FREQ_RAMP_DONE__enumvalues = { + 0: 'DISPCLK_FREQ_RAMP_IN_PROGRESS', + 1: 'DISPCLK_FREQ_RAMP_COMPLETED', +} +DISPCLK_FREQ_RAMP_IN_PROGRESS = 0 +DISPCLK_FREQ_RAMP_COMPLETED = 1 +DISPCLK_FREQ_RAMP_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DPREFCLK_SRC_SEL' +DPREFCLK_SRC_SEL__enumvalues = { + 0: 'DPREFCLK_SRC_SEL_CK', + 1: 'DPREFCLK_SRC_SEL_P0PLL', + 2: 'DPREFCLK_SRC_SEL_P1PLL', + 3: 'DPREFCLK_SRC_SEL_P2PLL', +} +DPREFCLK_SRC_SEL_CK = 0 +DPREFCLK_SRC_SEL_P0PLL = 1 +DPREFCLK_SRC_SEL_P1PLL = 2 +DPREFCLK_SRC_SEL_P2PLL = 3 +DPREFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DTO_DS_DISABLE' +DP_DTO_DS_DISABLE__enumvalues = { + 0: 'DP_DTO_DESPREAD_DISABLE', + 1: 'DP_DTO_DESPREAD_ENABLE', +} +DP_DTO_DESPREAD_DISABLE = 0 +DP_DTO_DESPREAD_ENABLE = 1 +DP_DTO_DS_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_HW_CAL_ENABLE' +DS_HW_CAL_ENABLE__enumvalues = { + 0: 'DS_HW_CAL_DIS', + 1: 'DS_HW_CAL_EN', +} +DS_HW_CAL_DIS = 0 +DS_HW_CAL_EN = 1 +DS_HW_CAL_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_JITTER_COUNT_SRC_SEL' +DS_JITTER_COUNT_SRC_SEL__enumvalues = { + 0: 'DS_JITTER_COUNT_SRC_SEL0', + 1: 'DS_JITTER_COUNT_SRC_SEL1', +} +DS_JITTER_COUNT_SRC_SEL0 = 0 +DS_JITTER_COUNT_SRC_SEL1 = 1 +DS_JITTER_COUNT_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DS_REF_SRC' +DS_REF_SRC__enumvalues = { + 0: 'DS_REF_IS_XTALIN', + 1: 'DS_REF_IS_EXT_GENLOCK', + 2: 'DS_REF_IS_PCIE', +} +DS_REF_IS_XTALIN = 0 +DS_REF_IS_EXT_GENLOCK = 1 +DS_REF_IS_PCIE = 2 +DS_REF_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_IN_PHASE' +DVOACLKC_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_IN_PHASE' +DVOACLKC_MVP_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_MVP_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE' +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE__enumvalues = { + 0: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 1: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', +} +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE = 0 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE = 1 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKD_IN_PHASE' +DVOACLKD_IN_PHASE__enumvalues = { + 0: 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKD_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKD_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_COARSE_SKEW_CNTL' +DVOACLK_COARSE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 5: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 6: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 7: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 8: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 9: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 10: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 11: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 12: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 13: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 14: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 15: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 16: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 17: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 18: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 19: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 20: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 21: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 22: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 23: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 24: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 25: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 26: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 27: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 28: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 29: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 30: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', +} +DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS = 4 +DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS = 5 +DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS = 6 +DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS = 7 +DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS = 8 +DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS = 9 +DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS = 10 +DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS = 11 +DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS = 12 +DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS = 13 +DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS = 14 +DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS = 15 +DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP = 16 +DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS = 17 +DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS = 18 +DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS = 19 +DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS = 20 +DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS = 21 +DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS = 22 +DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS = 23 +DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS = 24 +DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS = 25 +DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS = 26 +DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS = 27 +DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS = 28 +DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS = 29 +DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS = 30 +DVOACLK_COARSE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_FINE_SKEW_CNTL' +DVOACLK_FINE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 5: 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 6: 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 7: 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', +} +DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP = 4 +DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS = 5 +DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS = 6 +DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS = 7 +DVOACLK_FINE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVO_ENABLE_RST' +DVO_ENABLE_RST__enumvalues = { + 0: 'DVO_ENABLE_RST_DISABLE', + 1: 'DVO_ENABLE_RST_ENABLE', +} +DVO_ENABLE_RST_DISABLE = 0 +DVO_ENABLE_RST_ENABLE = 1 +DVO_ENABLE_RST = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE' +ENABLE__enumvalues = { + 0: 'DISABLE_THE_FEATURE', + 1: 'ENABLE_THE_FEATURE', +} +DISABLE_THE_FEATURE = 0 +ENABLE_THE_FEATURE = 1 +ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_CLOCK' +ENABLE_CLOCK__enumvalues = { + 0: 'ENABLE_THE_REFCLK', + 1: 'ENABLE_THE_FUNC_CLOCK', +} +ENABLE_THE_REFCLK = 0 +ENABLE_THE_FUNC_CLOCK = 1 +ENABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'FORCE_DISABLE_CLOCK' +FORCE_DISABLE_CLOCK__enumvalues = { + 0: 'NOT_FORCE_THE_CLOCK_DISABLED', + 1: 'FORCE_THE_CLOCK_DISABLED', +} +NOT_FORCE_THE_CLOCK_DISABLED = 0 +FORCE_THE_CLOCK_DISABLED = 1 +FORCE_DISABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMICHARCLK_SRC_SEL' +HDMICHARCLK_SRC_SEL__enumvalues = { + 0: 'HDMICHARCLK_SRC_SEL_UNIPHYA', + 1: 'HDMICHARCLK_SRC_SEL_UNIPHYB', + 2: 'HDMICHARCLK_SRC_SEL_UNIPHYC', + 3: 'HDMICHARCLK_SRC_SEL_UNIPHYD', + 4: 'HDMICHARCLK_SRC_SEL_UNIPHYE', + 5: 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', +} +HDMICHARCLK_SRC_SEL_UNIPHYA = 0 +HDMICHARCLK_SRC_SEL_UNIPHYB = 1 +HDMICHARCLK_SRC_SEL_UNIPHYC = 2 +HDMICHARCLK_SRC_SEL_UNIPHYD = 3 +HDMICHARCLK_SRC_SEL_UNIPHYE = 4 +HDMICHARCLK_SRC_SEL_SRC_RESERVED = 5 +HDMICHARCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMISTREAMCLK_DTO_FORCE_DIS' +HDMISTREAMCLK_DTO_FORCE_DIS__enumvalues = { + 0: 'DTO_FORCE_NO_BYPASS', + 1: 'DTO_FORCE_BYPASS', +} +DTO_FORCE_NO_BYPASS = 0 +DTO_FORCE_BYPASS = 1 +HDMISTREAMCLK_DTO_FORCE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'HDMISTREAMCLK_SRC_SEL' +HDMISTREAMCLK_SRC_SEL__enumvalues = { + 0: 'SEL_REFCLK0', + 1: 'SEL_DTBCLK0', + 2: 'SEL_DTBCLK1', +} +SEL_REFCLK0 = 0 +SEL_DTBCLK0 = 1 +SEL_DTBCLK1 = 2 +HDMISTREAMCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'JITTER_REMOVE_DISABLE' +JITTER_REMOVE_DISABLE__enumvalues = { + 0: 'ENABLE_JITTER_REMOVAL', + 1: 'DISABLE_JITTER_REMOVAL', +} +ENABLE_JITTER_REMOVAL = 0 +DISABLE_JITTER_REMOVAL = 1 +JITTER_REMOVE_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_ADD_PIXEL' +OTG_ADD_PIXEL__enumvalues = { + 0: 'OTG_ADD_PIXEL_NOOP', + 1: 'OTG_ADD_PIXEL_FORCE', +} +OTG_ADD_PIXEL_NOOP = 0 +OTG_ADD_PIXEL_FORCE = 1 +OTG_ADD_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DROP_PIXEL' +OTG_DROP_PIXEL__enumvalues = { + 0: 'OTG_DROP_PIXEL_NOOP', + 1: 'OTG_DROP_PIXEL_FORCE', +} +OTG_DROP_PIXEL_NOOP = 0 +OTG_DROP_PIXEL_FORCE = 1 +OTG_DROP_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'PHYSYMCLK_FORCE_EN' +PHYSYMCLK_FORCE_EN__enumvalues = { + 0: 'PHYSYMCLK_FORCE_EN_DISABLE', + 1: 'PHYSYMCLK_FORCE_EN_ENABLE', +} +PHYSYMCLK_FORCE_EN_DISABLE = 0 +PHYSYMCLK_FORCE_EN_ENABLE = 1 +PHYSYMCLK_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PHYSYMCLK_FORCE_SRC_SEL' +PHYSYMCLK_FORCE_SRC_SEL__enumvalues = { + 0: 'PHYSYMCLK_FORCE_SRC_SYMCLK', + 1: 'PHYSYMCLK_FORCE_SRC_PHYD18CLK', + 2: 'PHYSYMCLK_FORCE_SRC_PHYD32CLK', +} +PHYSYMCLK_FORCE_SRC_SYMCLK = 0 +PHYSYMCLK_FORCE_SRC_PHYD18CLK = 1 +PHYSYMCLK_FORCE_SRC_PHYD32CLK = 2 +PHYSYMCLK_FORCE_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PHYPLL_PIXEL_RATE_SOURCE' +PIPE_PHYPLL_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 1: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 2: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 3: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 4: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', +} +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA = 0 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB = 1 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC = 2 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD = 3 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED = 4 +PIPE_PHYPLL_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_PLL_SOURCE' +PIPE_PIXEL_RATE_PLL_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', + 1: 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', +} +PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL = 0 +PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL = 1 +PIPE_PIXEL_RATE_PLL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_SOURCE' +PIPE_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_SOURCE_P0PLL', + 1: 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 2: 'PIPE_PIXEL_RATE_SOURCE_P2PLL', +} +PIPE_PIXEL_RATE_SOURCE_P0PLL = 0 +PIPE_PIXEL_RATE_SOURCE_P1PLL = 1 +PIPE_PIXEL_RATE_SOURCE_P2PLL = 2 +PIPE_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PLL_CFG_IF_SOFT_RESET' +PLL_CFG_IF_SOFT_RESET__enumvalues = { + 0: 'PLL_CFG_IF_SOFT_RESET_NOOP', + 1: 'PLL_CFG_IF_SOFT_RESET_FORCE', +} +PLL_CFG_IF_SOFT_RESET_NOOP = 0 +PLL_CFG_IF_SOFT_RESET_FORCE = 1 +PLL_CFG_IF_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_EN' +SYMCLK_FE_FORCE_EN__enumvalues = { + 0: 'SYMCLK_FE_FORCE_EN_DISABLE', + 1: 'SYMCLK_FE_FORCE_EN_ENABLE', +} +SYMCLK_FE_FORCE_EN_DISABLE = 0 +SYMCLK_FE_FORCE_EN_ENABLE = 1 +SYMCLK_FE_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_SRC' +SYMCLK_FE_FORCE_SRC__enumvalues = { + 0: 'SYMCLK_FE_FORCE_SRC_UNIPHYA', + 1: 'SYMCLK_FE_FORCE_SRC_UNIPHYB', + 2: 'SYMCLK_FE_FORCE_SRC_UNIPHYC', + 3: 'SYMCLK_FE_FORCE_SRC_UNIPHYD', + 4: 'SYMCLK_FE_FORCE_SRC_RESERVED', +} +SYMCLK_FE_FORCE_SRC_UNIPHYA = 0 +SYMCLK_FE_FORCE_SRC_UNIPHYB = 1 +SYMCLK_FE_FORCE_SRC_UNIPHYC = 2 +SYMCLK_FE_FORCE_SRC_UNIPHYD = 3 +SYMCLK_FE_FORCE_SRC_RESERVED = 4 +SYMCLK_FE_FORCE_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_DIV_SEL' +TEST_CLK_DIV_SEL__enumvalues = { + 0: 'NO_DIV', + 1: 'DIV_2', + 2: 'DIV_4', + 3: 'DIV_8', +} +NO_DIV = 0 +DIV_2 = 1 +DIV_4 = 2 +DIV_8 = 3 +TEST_CLK_DIV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_LATCH_MASK' +VSYNC_CNT_LATCH_MASK__enumvalues = { + 0: 'VSYNC_CNT_LATCH_MASK_0', + 1: 'VSYNC_CNT_LATCH_MASK_1', +} +VSYNC_CNT_LATCH_MASK_0 = 0 +VSYNC_CNT_LATCH_MASK_1 = 1 +VSYNC_CNT_LATCH_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_RESET_SEL' +VSYNC_CNT_RESET_SEL__enumvalues = { + 0: 'VSYNC_CNT_RESET_SEL_0', + 1: 'VSYNC_CNT_RESET_SEL_1', +} +VSYNC_CNT_RESET_SEL_0 = 0 +VSYNC_CNT_RESET_SEL_1 = 1 +VSYNC_CNT_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_CLOCK_SOURCE_SEL' +XTAL_REF_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', + 1: 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', +} +XTAL_REF_CLOCK_SOURCE_SEL_XTALIN = 0 +XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK = 1 +XTAL_REF_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_SEL' +XTAL_REF_SEL__enumvalues = { + 0: 'XTAL_REF_SEL_1X', + 1: 'XTAL_REF_SEL_2X', +} +XTAL_REF_SEL_1X = 0 +XTAL_REF_SEL_2X = 1 +XTAL_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_ACK' +HPD_INT_CONTROL_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_ACK_0', + 1: 'HPD_INT_CONTROL_ACK_1', +} +HPD_INT_CONTROL_ACK_0 = 0 +HPD_INT_CONTROL_ACK_1 = 1 +HPD_INT_CONTROL_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_POLARITY' +HPD_INT_CONTROL_POLARITY__enumvalues = { + 0: 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', + 1: 'HPD_INT_CONTROL_GEN_INT_ON_CON', +} +HPD_INT_CONTROL_GEN_INT_ON_DISCON = 0 +HPD_INT_CONTROL_GEN_INT_ON_CON = 1 +HPD_INT_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_RX_INT_ACK' +HPD_INT_CONTROL_RX_INT_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_RX_INT_ACK_0', + 1: 'HPD_INT_CONTROL_RX_INT_ACK_1', +} +HPD_INT_CONTROL_RX_INT_ACK_0 = 0 +HPD_INT_CONTROL_RX_INT_ACK_1 = 1 +HPD_INT_CONTROL_RX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_CUR_DISP' +DPHY_8B10B_CUR_DISP__enumvalues = { + 0: 'DPHY_8B10B_CUR_DISP_ZERO', + 1: 'DPHY_8B10B_CUR_DISP_ONE', +} +DPHY_8B10B_CUR_DISP_ZERO = 0 +DPHY_8B10B_CUR_DISP_ONE = 1 +DPHY_8B10B_CUR_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_RESET' +DPHY_8B10B_RESET__enumvalues = { + 0: 'DPHY_8B10B_NOT_RESET', + 1: 'DPHY_8B10B_RESETET', +} +DPHY_8B10B_NOT_RESET = 0 +DPHY_8B10B_RESETET = 1 +DPHY_8B10B_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ALT_SCRAMBLER_RESET_EN' +DPHY_ALT_SCRAMBLER_RESET_EN__enumvalues = { + 0: 'DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE', + 1: 'DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION', +} +DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE = 0 +DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION = 1 +DPHY_ALT_SCRAMBLER_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ALT_SCRAMBLER_RESET_SEL' +DPHY_ALT_SCRAMBLER_RESET_SEL__enumvalues = { + 0: 'DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE', + 1: 'DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE', +} +DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE = 0 +DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE = 1 +DPHY_ALT_SCRAMBLER_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE0' +DPHY_ATEST_SEL_LANE0__enumvalues = { + 0: 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE0_REG_PATTERN', +} +DPHY_ATEST_LANE0_PRBS_PATTERN = 0 +DPHY_ATEST_LANE0_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE0 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE1' +DPHY_ATEST_SEL_LANE1__enumvalues = { + 0: 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE1_REG_PATTERN', +} +DPHY_ATEST_LANE1_PRBS_PATTERN = 0 +DPHY_ATEST_LANE1_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE1 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE2' +DPHY_ATEST_SEL_LANE2__enumvalues = { + 0: 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE2_REG_PATTERN', +} +DPHY_ATEST_LANE2_PRBS_PATTERN = 0 +DPHY_ATEST_LANE2_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE2 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE3' +DPHY_ATEST_SEL_LANE3__enumvalues = { + 0: 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE3_REG_PATTERN', +} +DPHY_ATEST_LANE3_PRBS_PATTERN = 0 +DPHY_ATEST_LANE3_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE3 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_BYPASS' +DPHY_BYPASS__enumvalues = { + 0: 'DPHY_8B10B_OUTPUT', + 1: 'DPHY_DBG_OUTPUT', +} +DPHY_8B10B_OUTPUT = 0 +DPHY_DBG_OUTPUT = 1 +DPHY_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_CONT_EN' +DPHY_CRC_CONT_EN__enumvalues = { + 0: 'DPHY_CRC_ONE_SHOT', + 1: 'DPHY_CRC_CONTINUOUS', +} +DPHY_CRC_ONE_SHOT = 0 +DPHY_CRC_CONTINUOUS = 1 +DPHY_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_EN' +DPHY_CRC_EN__enumvalues = { + 0: 'DPHY_CRC_DISABLED', + 1: 'DPHY_CRC_ENABLED', +} +DPHY_CRC_DISABLED = 0 +DPHY_CRC_ENABLED = 1 +DPHY_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_FIELD' +DPHY_CRC_FIELD__enumvalues = { + 0: 'DPHY_CRC_START_FROM_TOP_FIELD', + 1: 'DPHY_CRC_START_FROM_BOTTOM_FIELD', +} +DPHY_CRC_START_FROM_TOP_FIELD = 0 +DPHY_CRC_START_FROM_BOTTOM_FIELD = 1 +DPHY_CRC_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_MST_PHASE_ERROR_ACK' +DPHY_CRC_MST_PHASE_ERROR_ACK__enumvalues = { + 0: 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', + 1: 'DPHY_CRC_MST_PHASE_ERROR_ACKED', +} +DPHY_CRC_MST_PHASE_ERROR_NO_ACK = 0 +DPHY_CRC_MST_PHASE_ERROR_ACKED = 1 +DPHY_CRC_MST_PHASE_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_SEL' +DPHY_CRC_SEL__enumvalues = { + 0: 'DPHY_CRC_LANE0_SELECTED', + 1: 'DPHY_CRC_LANE1_SELECTED', + 2: 'DPHY_CRC_LANE2_SELECTED', + 3: 'DPHY_CRC_LANE3_SELECTED', +} +DPHY_CRC_LANE0_SELECTED = 0 +DPHY_CRC_LANE1_SELECTED = 1 +DPHY_CRC_LANE2_SELECTED = 2 +DPHY_CRC_LANE3_SELECTED = 3 +DPHY_CRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_ENABLE' +DPHY_FEC_ENABLE__enumvalues = { + 0: 'DPHY_FEC_DISABLED', + 1: 'DPHY_FEC_ENABLED', +} +DPHY_FEC_DISABLED = 0 +DPHY_FEC_ENABLED = 1 +DPHY_FEC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_READY' +DPHY_FEC_READY__enumvalues = { + 0: 'DPHY_FEC_READY_EN', + 1: 'DPHY_FEC_READY_DIS', +} +DPHY_FEC_READY_EN = 0 +DPHY_FEC_READY_DIS = 1 +DPHY_FEC_READY = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_LOAD_BS_COUNT_START' +DPHY_LOAD_BS_COUNT_START__enumvalues = { + 0: 'DPHY_LOAD_BS_COUNT_STARTED', + 1: 'DPHY_LOAD_BS_COUNT_NOT_STARTED', +} +DPHY_LOAD_BS_COUNT_STARTED = 0 +DPHY_LOAD_BS_COUNT_NOT_STARTED = 1 +DPHY_LOAD_BS_COUNT_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_EN' +DPHY_PRBS_EN__enumvalues = { + 0: 'DPHY_PRBS_DISABLE', + 1: 'DPHY_PRBS_ENABLE', +} +DPHY_PRBS_DISABLE = 0 +DPHY_PRBS_ENABLE = 1 +DPHY_PRBS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_SEL' +DPHY_PRBS_SEL__enumvalues = { + 0: 'DPHY_PRBS7_SELECTED', + 1: 'DPHY_PRBS23_SELECTED', + 2: 'DPHY_PRBS11_SELECTED', +} +DPHY_PRBS7_SELECTED = 0 +DPHY_PRBS23_SELECTED = 1 +DPHY_PRBS11_SELECTED = 2 +DPHY_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_RX_FAST_TRAINING_CAPABLE' +DPHY_RX_FAST_TRAINING_CAPABLE__enumvalues = { + 0: 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 1: 'DPHY_FAST_TRAINING_CAPABLE', +} +DPHY_FAST_TRAINING_NOT_CAPABLE_0 = 0 +DPHY_FAST_TRAINING_CAPABLE = 1 +DPHY_RX_FAST_TRAINING_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_ADVANCE' +DPHY_SCRAMBLER_ADVANCE__enumvalues = { + 0: 'DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY', + 1: 'DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL', +} +DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY = 0 +DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL = 1 +DPHY_SCRAMBLER_ADVANCE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_DIS' +DPHY_SCRAMBLER_DIS__enumvalues = { + 0: 'DPHY_SCR_ENABLED', + 1: 'DPHY_SCR_DISABLED', +} +DPHY_SCR_ENABLED = 0 +DPHY_SCR_DISABLED = 1 +DPHY_SCRAMBLER_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_KCODE' +DPHY_SCRAMBLER_KCODE__enumvalues = { + 0: 'DPHY_SCRAMBLER_KCODE_DISABLED', + 1: 'DPHY_SCRAMBLER_KCODE_ENABLED', +} +DPHY_SCRAMBLER_KCODE_DISABLED = 0 +DPHY_SCRAMBLER_KCODE_ENABLED = 1 +DPHY_SCRAMBLER_KCODE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_SEL' +DPHY_SCRAMBLER_SEL__enumvalues = { + 0: 'DPHY_SCRAMBLER_SEL_LANE_DATA', + 1: 'DPHY_SCRAMBLER_SEL_DBG_DATA', +} +DPHY_SCRAMBLER_SEL_LANE_DATA = 0 +DPHY_SCRAMBLER_SEL_DBG_DATA = 1 +DPHY_SCRAMBLER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SKEW_BYPASS' +DPHY_SKEW_BYPASS__enumvalues = { + 0: 'DPHY_WITH_SKEW', + 1: 'DPHY_NO_SKEW', +} +DPHY_WITH_SKEW = 0 +DPHY_NO_SKEW = 1 +DPHY_SKEW_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM' +DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM__enumvalues = { + 0: 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET', + 1: 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET', +} +DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET = 0 +DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET = 1 +DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SW_FAST_TRAINING_START' +DPHY_SW_FAST_TRAINING_START__enumvalues = { + 0: 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 1: 'DPHY_SW_FAST_TRAINING_STARTED', +} +DPHY_SW_FAST_TRAINING_NOT_STARTED = 0 +DPHY_SW_FAST_TRAINING_STARTED = 1 +DPHY_SW_FAST_TRAINING_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_TRAINING_PATTERN_SEL' +DPHY_TRAINING_PATTERN_SEL__enumvalues = { + 0: 'DPHY_TRAINING_PATTERN_1', + 1: 'DPHY_TRAINING_PATTERN_2', + 2: 'DPHY_TRAINING_PATTERN_3', + 3: 'DPHY_TRAINING_PATTERN_4', +} +DPHY_TRAINING_PATTERN_1 = 0 +DPHY_TRAINING_PATTERN_2 = 1 +DPHY_TRAINING_PATTERN_3 = 2 +DPHY_TRAINING_PATTERN_4 = 3 +DPHY_TRAINING_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMPONENT_DEPTH' +DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_COMPONENT_DEPTH_6BPC', + 1: 'DP_COMPONENT_DEPTH_8BPC', + 2: 'DP_COMPONENT_DEPTH_10BPC', + 3: 'DP_COMPONENT_DEPTH_12BPC', + 4: 'DP_COMPONENT_DEPTH_16BPC', +} +DP_COMPONENT_DEPTH_6BPC = 0 +DP_COMPONENT_DEPTH_8BPC = 1 +DP_COMPONENT_DEPTH_10BPC = 2 +DP_COMPONENT_DEPTH_12BPC = 3 +DP_COMPONENT_DEPTH_16BPC = 4 +DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DP_CP_ENCRYPTION_TYPE' +DP_CP_ENCRYPTION_TYPE__enumvalues = { + 0: 'DP_CP_ENCRYPTION_TYPE_0', + 1: 'DP_CP_ENCRYPTION_TYPE_1', +} +DP_CP_ENCRYPTION_TYPE_0 = 0 +DP_CP_ENCRYPTION_TYPE_1 = 1 +DP_CP_ENCRYPTION_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_8B10B_EXT_DISP' +DP_DPHY_8B10B_EXT_DISP__enumvalues = { + 0: 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 1: 'DP_DPHY_8B10B_EXT_DISP_ONE', +} +DP_DPHY_8B10B_EXT_DISP_ZERO = 0 +DP_DPHY_8B10B_EXT_DISP_ONE = 1 +DP_DPHY_8B10B_EXT_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK' +DP_DPHY_FAST_TRAINING_COMPLETE_ACK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_ACKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK' +DP_DPHY_FAST_TRAINING_COMPLETE_MASK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_MASKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN' +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 1: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', +} +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED = 0 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED = 1 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE' +DP_DPHY_HBR2_PATTERN_CONTROL_MODE__enumvalues = { + 0: 'DP_DPHY_HBR2_PASS_THROUGH', + 1: 'DP_DPHY_HBR2_PATTERN_1', + 2: 'DP_DPHY_HBR2_PATTERN_2_NEG', + 3: 'DP_DPHY_HBR2_PATTERN_3', + 6: 'DP_DPHY_HBR2_PATTERN_2_POS', +} +DP_DPHY_HBR2_PASS_THROUGH = 0 +DP_DPHY_HBR2_PATTERN_1 = 1 +DP_DPHY_HBR2_PATTERN_2_NEG = 2 +DP_DPHY_HBR2_PATTERN_3 = 3 +DP_DPHY_HBR2_PATTERN_2_POS = 6 +DP_DPHY_HBR2_PATTERN_CONTROL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DSC_MODE' +DP_DSC_MODE__enumvalues = { + 0: 'DP_DSC_DISABLE', + 1: 'DP_DSC_444_SIMPLE_422', + 2: 'DP_DSC_NATIVE_422_420', +} +DP_DSC_DISABLE = 0 +DP_DSC_444_SIMPLE_422 = 1 +DP_DSC_NATIVE_422_420 = 2 +DP_DSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_EMBEDDED_PANEL_MODE' +DP_EMBEDDED_PANEL_MODE__enumvalues = { + 0: 'DP_EXTERNAL_PANEL', + 1: 'DP_EMBEDDED_PANEL', +} +DP_EXTERNAL_PANEL = 0 +DP_EMBEDDED_PANEL = 1 +DP_EMBEDDED_PANEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_COMPLETE' +DP_LINK_TRAINING_COMPLETE__enumvalues = { + 0: 'DP_LINK_TRAINING_NOT_COMPLETE', + 1: 'DP_LINK_TRAINING_ALREADY_COMPLETE', +} +DP_LINK_TRAINING_NOT_COMPLETE = 0 +DP_LINK_TRAINING_ALREADY_COMPLETE = 1 +DP_LINK_TRAINING_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_SWITCH_MODE' +DP_LINK_TRAINING_SWITCH_MODE__enumvalues = { + 0: 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 1: 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', +} +DP_LINK_TRAINING_SWITCH_TO_IDLE = 0 +DP_LINK_TRAINING_SWITCH_TO_VIDEO = 1 +DP_LINK_TRAINING_SWITCH_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_ML_PHY_SEQ_MODE' +DP_ML_PHY_SEQ_MODE__enumvalues = { + 0: 'DP_ML_PHY_SEQ_LINE_NUM', + 1: 'DP_ML_PHY_SEQ_IMMEDIATE', +} +DP_ML_PHY_SEQ_LINE_NUM = 0 +DP_ML_PHY_SEQ_IMMEDIATE = 1 +DP_ML_PHY_SEQ_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_V_TIMING_OVERRIDE_EN' +DP_MSA_V_TIMING_OVERRIDE_EN__enumvalues = { + 0: 'MSA_V_TIMING_OVERRIDE_DISABLED', + 1: 'MSA_V_TIMING_OVERRIDE_ENABLED', +} +MSA_V_TIMING_OVERRIDE_DISABLED = 0 +MSA_V_TIMING_OVERRIDE_ENABLED = 1 +DP_MSA_V_TIMING_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_BLANK_CODE' +DP_MSE_BLANK_CODE__enumvalues = { + 0: 'DP_MSE_BLANK_CODE_SF_FILLED', + 1: 'DP_MSE_BLANK_CODE_ZERO_FILLED', +} +DP_MSE_BLANK_CODE_SF_FILLED = 0 +DP_MSE_BLANK_CODE_ZERO_FILLED = 1 +DP_MSE_BLANK_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_LINK_LINE' +DP_MSE_LINK_LINE__enumvalues = { + 0: 'DP_MSE_LINK_LINE_32_MTP_LONG', + 1: 'DP_MSE_LINK_LINE_64_MTP_LONG', + 2: 'DP_MSE_LINK_LINE_128_MTP_LONG', + 3: 'DP_MSE_LINK_LINE_256_MTP_LONG', +} +DP_MSE_LINK_LINE_32_MTP_LONG = 0 +DP_MSE_LINK_LINE_64_MTP_LONG = 1 +DP_MSE_LINK_LINE_128_MTP_LONG = 2 +DP_MSE_LINK_LINE_256_MTP_LONG = 3 +DP_MSE_LINK_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT0' +DP_MSE_SAT_ENCRYPT0__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT0_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT0_ENABLED', +} +DP_MSE_SAT_ENCRYPT0_DISABLED = 0 +DP_MSE_SAT_ENCRYPT0_ENABLED = 1 +DP_MSE_SAT_ENCRYPT0 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT1' +DP_MSE_SAT_ENCRYPT1__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT1_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT1_ENABLED', +} +DP_MSE_SAT_ENCRYPT1_DISABLED = 0 +DP_MSE_SAT_ENCRYPT1_ENABLED = 1 +DP_MSE_SAT_ENCRYPT1 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT2' +DP_MSE_SAT_ENCRYPT2__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT2_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT2_ENABLED', +} +DP_MSE_SAT_ENCRYPT2_DISABLED = 0 +DP_MSE_SAT_ENCRYPT2_ENABLED = 1 +DP_MSE_SAT_ENCRYPT2 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT3' +DP_MSE_SAT_ENCRYPT3__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT3_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT3_ENABLED', +} +DP_MSE_SAT_ENCRYPT3_DISABLED = 0 +DP_MSE_SAT_ENCRYPT3_ENABLED = 1 +DP_MSE_SAT_ENCRYPT3 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT4' +DP_MSE_SAT_ENCRYPT4__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT4_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT4_ENABLED', +} +DP_MSE_SAT_ENCRYPT4_DISABLED = 0 +DP_MSE_SAT_ENCRYPT4_ENABLED = 1 +DP_MSE_SAT_ENCRYPT4 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_ENCRYPT5' +DP_MSE_SAT_ENCRYPT5__enumvalues = { + 0: 'DP_MSE_SAT_ENCRYPT5_DISABLED', + 1: 'DP_MSE_SAT_ENCRYPT5_ENABLED', +} +DP_MSE_SAT_ENCRYPT5_DISABLED = 0 +DP_MSE_SAT_ENCRYPT5_ENABLED = 1 +DP_MSE_SAT_ENCRYPT5 = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_UPDATE_ACT' +DP_MSE_SAT_UPDATE_ACT__enumvalues = { + 0: 'DP_MSE_SAT_UPDATE_NO_ACTION', + 1: 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 2: 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', +} +DP_MSE_SAT_UPDATE_NO_ACTION = 0 +DP_MSE_SAT_UPDATE_WITH_TRIGGER = 1 +DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER = 2 +DP_MSE_SAT_UPDATE_ACT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_TIMESTAMP_MODE' +DP_MSE_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 1: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', +} +DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE = 0 +DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE = 1 +DP_MSE_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_ZERO_ENCODER' +DP_MSE_ZERO_ENCODER__enumvalues = { + 0: 'DP_MSE_NOT_ZERO_FE_ENCODER', + 1: 'DP_MSE_ZERO_FE_ENCODER', +} +DP_MSE_NOT_ZERO_FE_ENCODER = 0 +DP_MSE_ZERO_FE_ENCODER = 1 +DP_MSE_ZERO_ENCODER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSO_NUM_OF_SST_LINKS' +DP_MSO_NUM_OF_SST_LINKS__enumvalues = { + 0: 'DP_MSO_ONE_SSTLINK', + 1: 'DP_MSO_TWO_SSTLINK', + 2: 'DP_MSO_FOUR_SSTLINK', +} +DP_MSO_ONE_SSTLINK = 0 +DP_MSO_TWO_SSTLINK = 1 +DP_MSO_FOUR_SSTLINK = 2 +DP_MSO_NUM_OF_SST_LINKS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_ENCODING' +DP_PIXEL_ENCODING__enumvalues = { + 0: 'DP_PIXEL_ENCODING_RGB444', + 1: 'DP_PIXEL_ENCODING_YCBCR422', + 2: 'DP_PIXEL_ENCODING_YCBCR444', + 3: 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', + 4: 'DP_PIXEL_ENCODING_Y_ONLY', + 5: 'DP_PIXEL_ENCODING_YCBCR420', +} +DP_PIXEL_ENCODING_RGB444 = 0 +DP_PIXEL_ENCODING_YCBCR422 = 1 +DP_PIXEL_ENCODING_YCBCR444 = 2 +DP_PIXEL_ENCODING_RGB_WIDE_GAMUT = 3 +DP_PIXEL_ENCODING_Y_ONLY = 4 +DP_PIXEL_ENCODING_YCBCR420 = 5 +DP_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_PER_CYCLE_PROCESSING_NUM' +DP_PIXEL_PER_CYCLE_PROCESSING_NUM__enumvalues = { + 0: 'DP_ONE_PIXEL_PER_CYCLE', + 1: 'DP_TWO_PIXEL_PER_CYCLE', +} +DP_ONE_PIXEL_PER_CYCLE = 0 +DP_TWO_PIXEL_PER_CYCLE = 1 +DP_PIXEL_PER_CYCLE_PROCESSING_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE' +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ = 0 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_PRIORITY' +DP_SEC_ASP_PRIORITY__enumvalues = { + 0: 'DP_SEC_ASP_LOW_PRIORITY', + 1: 'DP_SEC_ASP_HIGH_PRIORITY', +} +DP_SEC_ASP_LOW_PRIORITY = 0 +DP_SEC_ASP_HIGH_PRIORITY = 1 +DP_SEC_ASP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_AUDIO_MUTE' +DP_SEC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SEC_AUDIO_MUTE_HW_CTRL', + 1: 'DP_SEC_AUDIO_MUTE_SW_CTRL', +} +DP_SEC_AUDIO_MUTE_HW_CTRL = 0 +DP_SEC_AUDIO_MUTE_SW_CTRL = 1 +DP_SEC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_COLLISION_ACK' +DP_SEC_COLLISION_ACK__enumvalues = { + 0: 'DP_SEC_COLLISION_ACK_NO_EFFECT', + 1: 'DP_SEC_COLLISION_ACK_CLR_FLAG', +} +DP_SEC_COLLISION_ACK_NO_EFFECT = 0 +DP_SEC_COLLISION_ACK_CLR_FLAG = 1 +DP_SEC_COLLISION_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP0_PRIORITY' +DP_SEC_GSP0_PRIORITY__enumvalues = { + 0: 'SEC_GSP0_PRIORITY_LOW', + 1: 'SEC_GSP0_PRIORITY_HIGH', +} +SEC_GSP0_PRIORITY_LOW = 0 +SEC_GSP0_PRIORITY_HIGH = 1 +DP_SEC_GSP0_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND' +DP_SEC_GSP_SEND__enumvalues = { + 0: 'NOT_SENT', + 1: 'FORCE_SENT', +} +NOT_SENT = 0 +FORCE_SENT = 1 +DP_SEC_GSP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_ANY_LINE' +DP_SEC_GSP_SEND_ANY_LINE__enumvalues = { + 0: 'SEND_AT_LINK_NUMBER', + 1: 'SEND_AT_EARLIEST_TIME', +} +SEND_AT_LINK_NUMBER = 0 +SEND_AT_EARLIEST_TIME = 1 +DP_SEC_GSP_SEND_ANY_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_PPS' +DP_SEC_GSP_SEND_PPS__enumvalues = { + 0: 'SEND_NORMAL_PACKET', + 1: 'SEND_PPS_PACKET', +} +SEND_NORMAL_PACKET = 0 +SEND_PPS_PACKET = 1 +DP_SEC_GSP_SEND_PPS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_LINE_REFERENCE' +DP_SEC_LINE_REFERENCE__enumvalues = { + 0: 'REFER_TO_DP_SOF', + 1: 'REFER_TO_OTG_SOF', +} +REFER_TO_DP_SOF = 0 +REFER_TO_OTG_SOF = 1 +DP_SEC_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_TIMESTAMP_MODE' +DP_SEC_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', + 1: 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', +} +DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE = 0 +DP_SEC_TIMESTAMP_AUTO_CALC_MODE = 1 +DP_SEC_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_ACK' +DP_STEER_OVERFLOW_ACK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_STEER_OVERFLOW_ACK_NO_EFFECT = 0 +DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_STEER_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_MASK' +DP_STEER_OVERFLOW_MASK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_MASKED', + 1: 'DP_STEER_OVERFLOW_UNMASK', +} +DP_STEER_OVERFLOW_MASKED = 0 +DP_STEER_OVERFLOW_UNMASK = 1 +DP_STEER_OVERFLOW_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SYNC_POLARITY' +DP_SYNC_POLARITY__enumvalues = { + 0: 'DP_SYNC_POLARITY_ACTIVE_HIGH', + 1: 'DP_SYNC_POLARITY_ACTIVE_LOW', +} +DP_SYNC_POLARITY_ACTIVE_HIGH = 0 +DP_SYNC_POLARITY_ACTIVE_LOW = 1 +DP_SYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_TU_OVERFLOW_ACK' +DP_TU_OVERFLOW_ACK__enumvalues = { + 0: 'DP_TU_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_TU_OVERFLOW_ACK_NO_EFFECT = 0 +DP_TU_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_TU_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_UDI_LANES' +DP_UDI_LANES__enumvalues = { + 0: 'DP_UDI_1_LANE', + 1: 'DP_UDI_2_LANES', + 2: 'DP_UDI_LANES_RESERVED', + 3: 'DP_UDI_4_LANES', +} +DP_UDI_1_LANE = 0 +DP_UDI_2_LANES = 1 +DP_UDI_LANES_RESERVED = 2 +DP_UDI_4_LANES = 3 +DP_UDI_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_ENHANCED_FRAME_MODE' +DP_VID_ENHANCED_FRAME_MODE__enumvalues = { + 0: 'VID_NORMAL_FRAME_MODE', + 1: 'VID_ENHANCED_MODE', +} +VID_NORMAL_FRAME_MODE = 0 +VID_ENHANCED_MODE = 1 +DP_VID_ENHANCED_FRAME_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_DOUBLE_BUFFER_MODE' +DP_VID_M_N_DOUBLE_BUFFER_MODE__enumvalues = { + 0: 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 1: 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', +} +DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE = 0 +DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START = 1 +DP_VID_M_N_DOUBLE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_GEN_EN' +DP_VID_M_N_GEN_EN__enumvalues = { + 0: 'DP_VID_M_N_PROGRAMMED_VIA_REG', + 1: 'DP_VID_M_N_CALC_AUTO', +} +DP_VID_M_N_PROGRAMMED_VIA_REG = 0 +DP_VID_M_N_CALC_AUTO = 1 +DP_VID_M_N_GEN_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_N_MUL' +DP_VID_N_MUL__enumvalues = { + 0: 'DP_VID_M_1X_INPUT_PIXEL_RATE', + 1: 'DP_VID_M_2X_INPUT_PIXEL_RATE', + 2: 'DP_VID_M_4X_INPUT_PIXEL_RATE', + 3: 'DP_VID_M_8X_INPUT_PIXEL_RATE', +} +DP_VID_M_1X_INPUT_PIXEL_RATE = 0 +DP_VID_M_2X_INPUT_PIXEL_RATE = 1 +DP_VID_M_4X_INPUT_PIXEL_RATE = 2 +DP_VID_M_8X_INPUT_PIXEL_RATE = 3 +DP_VID_N_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_ACK' +DP_VID_STREAM_DISABLE_ACK__enumvalues = { + 0: 'ID_STREAM_DISABLE_NO_ACK', + 1: 'ID_STREAM_DISABLE_ACKED', +} +ID_STREAM_DISABLE_NO_ACK = 0 +ID_STREAM_DISABLE_ACKED = 1 +DP_VID_STREAM_DISABLE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_MASK' +DP_VID_STREAM_DISABLE_MASK__enumvalues = { + 0: 'VID_STREAM_DISABLE_MASKED', + 1: 'VID_STREAM_DISABLE_UNMASK', +} +VID_STREAM_DISABLE_MASKED = 0 +VID_STREAM_DISABLE_UNMASK = 1 +DP_VID_STREAM_DISABLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DIS_DEFER' +DP_VID_STREAM_DIS_DEFER__enumvalues = { + 0: 'DP_VID_STREAM_DIS_NO_DEFER', + 1: 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 2: 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', +} +DP_VID_STREAM_DIS_NO_DEFER = 0 +DP_VID_STREAM_DIS_DEFER_TO_HBLANK = 1 +DP_VID_STREAM_DIS_DEFER_TO_VBLANK = 2 +DP_VID_STREAM_DIS_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_VBID_FIELD_POL' +DP_VID_VBID_FIELD_POL__enumvalues = { + 0: 'DP_VID_VBID_FIELD_POL_NORMAL', + 1: 'DP_VID_VBID_FIELD_POL_INV', +} +DP_VID_VBID_FIELD_POL_NORMAL = 0 +DP_VID_VBID_FIELD_POL_INV = 1 +DP_VID_VBID_FIELD_POL = ctypes.c_uint32 # enum + +# values for enumeration 'FEC_ACTIVE_STATUS' +FEC_ACTIVE_STATUS__enumvalues = { + 0: 'DPHY_FEC_NOT_ACTIVE', + 1: 'DPHY_FEC_ACTIVE', +} +DPHY_FEC_NOT_ACTIVE = 0 +DPHY_FEC_ACTIVE = 1 +FEC_ACTIVE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_HPD_SELECT' +DIG_BE_CNTL_HPD_SELECT__enumvalues = { + 0: 'DIG_BE_CNTL_HPD1', + 1: 'DIG_BE_CNTL_HPD2', + 2: 'DIG_BE_CNTL_HPD3', + 3: 'DIG_BE_CNTL_HPD4', + 4: 'DIG_BE_CNTL_HPD5', + 5: 'DIG_BE_CNTL_NO_HPD', +} +DIG_BE_CNTL_HPD1 = 0 +DIG_BE_CNTL_HPD2 = 1 +DIG_BE_CNTL_HPD3 = 2 +DIG_BE_CNTL_HPD4 = 3 +DIG_BE_CNTL_HPD5 = 4 +DIG_BE_CNTL_NO_HPD = 5 +DIG_BE_CNTL_HPD_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_MODE' +DIG_BE_CNTL_MODE__enumvalues = { + 0: 'DIG_BE_DP_SST_MODE', + 1: 'DIG_BE_RESERVED1', + 2: 'DIG_BE_TMDS_DVI_MODE', + 3: 'DIG_BE_TMDS_HDMI_MODE', + 4: 'DIG_BE_RESERVED4', + 5: 'DIG_BE_DP_MST_MODE', + 6: 'DIG_BE_RESERVED2', + 7: 'DIG_BE_RESERVED3', +} +DIG_BE_DP_SST_MODE = 0 +DIG_BE_RESERVED1 = 1 +DIG_BE_TMDS_DVI_MODE = 2 +DIG_BE_TMDS_HDMI_MODE = 3 +DIG_BE_RESERVED4 = 4 +DIG_BE_DP_MST_MODE = 5 +DIG_BE_RESERVED2 = 6 +DIG_BE_RESERVED3 = 7 +DIG_BE_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_DIGITAL_BYPASS_ENABLE' +DIG_DIGITAL_BYPASS_ENABLE__enumvalues = { + 0: 'DIG_DIGITAL_BYPASS_OFF', + 1: 'DIG_DIGITAL_BYPASS_ON', +} +DIG_DIGITAL_BYPASS_OFF = 0 +DIG_DIGITAL_BYPASS_ON = 1 +DIG_DIGITAL_BYPASS_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_DIGITAL_BYPASS_SEL' +DIG_DIGITAL_BYPASS_SEL__enumvalues = { + 0: 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 1: 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 2: 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 3: 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 4: 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 5: 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 6: 'DIG_DIGITAL_BYPASS_SEL_ALPHA', +} +DIG_DIGITAL_BYPASS_SEL_BYPASS = 0 +DIG_DIGITAL_BYPASS_SEL_36BPP = 1 +DIG_DIGITAL_BYPASS_SEL_48BPP_LSB = 2 +DIG_DIGITAL_BYPASS_SEL_48BPP_MSB = 3 +DIG_DIGITAL_BYPASS_SEL_10BPP_LSB = 4 +DIG_DIGITAL_BYPASS_SEL_12BPC_LSB = 5 +DIG_DIGITAL_BYPASS_SEL_ALPHA = 6 +DIG_DIGITAL_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_SOURCE_SELECT' +DIG_FE_CNTL_SOURCE_SELECT__enumvalues = { + 0: 'DIG_FE_SOURCE_FROM_OTG0', + 1: 'DIG_FE_SOURCE_FROM_OTG1', + 2: 'DIG_FE_SOURCE_FROM_OTG2', + 3: 'DIG_FE_SOURCE_FROM_OTG3', + 4: 'DIG_FE_SOURCE_RESERVED', +} +DIG_FE_SOURCE_FROM_OTG0 = 0 +DIG_FE_SOURCE_FROM_OTG1 = 1 +DIG_FE_SOURCE_FROM_OTG2 = 2 +DIG_FE_SOURCE_FROM_OTG3 = 3 +DIG_FE_SOURCE_RESERVED = 4 +DIG_FE_CNTL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_STEREOSYNC_SELECT' +DIG_FE_CNTL_STEREOSYNC_SELECT__enumvalues = { + 0: 'DIG_FE_STEREOSYNC_FROM_OTG0', + 1: 'DIG_FE_STEREOSYNC_FROM_OTG1', + 2: 'DIG_FE_STEREOSYNC_FROM_OTG2', + 3: 'DIG_FE_STEREOSYNC_FROM_OTG3', + 4: 'DIG_FE_STEREOSYNC_RESERVED', +} +DIG_FE_STEREOSYNC_FROM_OTG0 = 0 +DIG_FE_STEREOSYNC_FROM_OTG1 = 1 +DIG_FE_STEREOSYNC_FROM_OTG2 = 2 +DIG_FE_STEREOSYNC_FROM_OTG3 = 3 +DIG_FE_STEREOSYNC_RESERVED = 4 +DIG_FE_CNTL_STEREOSYNC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX' +DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', + 1: 'DIG_FIFO_FORCE_RECOMP_MINMAX', +} +DIG_FIFO_NOT_FORCE_RECOMP_MINMAX = 0 +DIG_FIFO_FORCE_RECOMP_MINMAX = 1 +DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL' +DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL__enumvalues = { + 0: 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 1: 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', +} +DIG_FIFO_USE_OVERWRITE_LEVEL = 0 +DIG_FIFO_USE_CAL_AVERAGE_LEVEL = 1 +DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_FORCE_RECAL_AVERAGE' +DIG_FIFO_FORCE_RECAL_AVERAGE__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 1: 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', +} +DIG_FIFO_NOT_FORCE_RECAL_AVERAGE = 0 +DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL = 1 +DIG_FIFO_FORCE_RECAL_AVERAGE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_OUTPUT_PROCESSING_MODE' +DIG_FIFO_OUTPUT_PROCESSING_MODE__enumvalues = { + 0: 'DIG_FIFO_1_PIX_PER_CYCLE', + 1: 'DIG_FIFO_2_PIX_PER_CYCLE', +} +DIG_FIFO_1_PIX_PER_CYCLE = 0 +DIG_FIFO_2_PIX_PER_CYCLE = 1 +DIG_FIFO_OUTPUT_PROCESSING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR' +DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR__enumvalues = { + 0: 'DIG_FIFO_NO_ERROR_OCCURRED', + 1: 'DIG_FIFO_UNDERFLOW_OCCURRED', + 2: 'DIG_FIFO_OVERFLOW_OCCURRED', +} +DIG_FIFO_NO_ERROR_OCCURRED = 0 +DIG_FIFO_UNDERFLOW_OCCURRED = 1 +DIG_FIFO_OVERFLOW_OCCURRED = 2 +DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_READ_CLOCK_SRC' +DIG_FIFO_READ_CLOCK_SRC__enumvalues = { + 0: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 1: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', +} +DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG = 0 +DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE = 1 +DIG_FIFO_READ_CLOCK_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_INPUT_PIXEL_SEL' +DIG_INPUT_PIXEL_SEL__enumvalues = { + 0: 'DIG_ALL_PIXEL', + 1: 'DIG_EVEN_PIXEL_ONLY', + 2: 'DIG_ODD_PIXEL_ONLY', +} +DIG_ALL_PIXEL = 0 +DIG_EVEN_PIXEL_ONLY = 1 +DIG_ODD_PIXEL_ONLY = 2 +DIG_INPUT_PIXEL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_CNTL_LINK_SEL' +DIG_OUTPUT_CRC_CNTL_LINK_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_ON_LINK0', + 1: 'DIG_OUTPUT_CRC_ON_LINK1', +} +DIG_OUTPUT_CRC_ON_LINK0 = 0 +DIG_OUTPUT_CRC_ON_LINK1 = 1 +DIG_OUTPUT_CRC_CNTL_LINK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_DATA_SEL' +DIG_OUTPUT_CRC_DATA_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_FOR_FULLFRAME', + 1: 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', + 2: 'DIG_OUTPUT_CRC_FOR_VBI', + 3: 'DIG_OUTPUT_CRC_FOR_AUDIO', +} +DIG_OUTPUT_CRC_FOR_FULLFRAME = 0 +DIG_OUTPUT_CRC_FOR_ACTIVEONLY = 1 +DIG_OUTPUT_CRC_FOR_VBI = 2 +DIG_OUTPUT_CRC_FOR_AUDIO = 3 +DIG_OUTPUT_CRC_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_RANDOM_PATTERN_SEED_RAN_PAT' +DIG_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 1: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', +} +DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS = 0 +DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH = 1 +DIG_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_SL_PIXEL_GROUPING' +DIG_SL_PIXEL_GROUPING__enumvalues = { + 0: 'DIG_SINGLETON_PIXELS', + 1: 'DIG_PAIR_PIXELS', +} +DIG_SINGLETON_PIXELS = 0 +DIG_PAIR_PIXELS = 1 +DIG_SL_PIXEL_GROUPING = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN' +DIG_TEST_PATTERN_EXTERNAL_RESET_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 1: 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', +} +DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE = 0 +DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG = 1 +DIG_TEST_PATTERN_EXTERNAL_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL' +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL__enumvalues = { + 0: 'DIG_10BIT_TEST_PATTERN', + 1: 'DIG_ALTERNATING_TEST_PATTERN', +} +DIG_10BIT_TEST_PATTERN = 0 +DIG_ALTERNATING_TEST_PATTERN = 1 +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN' +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_NORMAL', + 1: 'DIG_TEST_PATTERN_RANDOM', +} +DIG_TEST_PATTERN_NORMAL = 0 +DIG_TEST_PATTERN_RANDOM = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET' +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_ENABLED', + 1: 'DIG_RANDOM_PATTERN_RESETED', +} +DIG_RANDOM_PATTERN_ENABLED = 0 +DIG_RANDOM_PATTERN_RESETED = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN' +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_IN_NORMAL_OPERATION', + 1: 'DIG_IN_DEBUG_MODE', +} +DIG_IN_NORMAL_OPERATION = 0 +DIG_IN_DEBUG_MODE = 1 +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOLBY_VISION_ENABLE' +DOLBY_VISION_ENABLE__enumvalues = { + 0: 'DOLBY_VISION_DISABLED', + 1: 'DOLBY_VISION_ENABLED', +} +DOLBY_VISION_DISABLED = 0 +DOLBY_VISION_ENABLED = 1 +DOLBY_VISION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACP_SEND' +HDMI_ACP_SEND__enumvalues = { + 0: 'HDMI_ACP_NOT_SEND', + 1: 'HDMI_ACP_PKT_SEND', +} +HDMI_ACP_NOT_SEND = 0 +HDMI_ACP_PKT_SEND = 1 +HDMI_ACP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_AUDIO_PRIORITY' +HDMI_ACR_AUDIO_PRIORITY__enumvalues = { + 0: 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 1: 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', +} +HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE = 0 +HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT = 1 +HDMI_ACR_AUDIO_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_CONT' +HDMI_ACR_CONT__enumvalues = { + 0: 'HDMI_ACR_CONT_DISABLE', + 1: 'HDMI_ACR_CONT_ENABLE', +} +HDMI_ACR_CONT_DISABLE = 0 +HDMI_ACR_CONT_ENABLE = 1 +HDMI_ACR_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_N_MULTIPLE' +HDMI_ACR_N_MULTIPLE__enumvalues = { + 0: 'HDMI_ACR_0_MULTIPLE_RESERVED', + 1: 'HDMI_ACR_1_MULTIPLE', + 2: 'HDMI_ACR_2_MULTIPLE', + 3: 'HDMI_ACR_3_MULTIPLE_RESERVED', + 4: 'HDMI_ACR_4_MULTIPLE', + 5: 'HDMI_ACR_5_MULTIPLE_RESERVED', + 6: 'HDMI_ACR_6_MULTIPLE_RESERVED', + 7: 'HDMI_ACR_7_MULTIPLE_RESERVED', +} +HDMI_ACR_0_MULTIPLE_RESERVED = 0 +HDMI_ACR_1_MULTIPLE = 1 +HDMI_ACR_2_MULTIPLE = 2 +HDMI_ACR_3_MULTIPLE_RESERVED = 3 +HDMI_ACR_4_MULTIPLE = 4 +HDMI_ACR_5_MULTIPLE_RESERVED = 5 +HDMI_ACR_6_MULTIPLE_RESERVED = 6 +HDMI_ACR_7_MULTIPLE_RESERVED = 7 +HDMI_ACR_N_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SELECT' +HDMI_ACR_SELECT__enumvalues = { + 0: 'HDMI_ACR_SELECT_HW', + 1: 'HDMI_ACR_SELECT_32K', + 2: 'HDMI_ACR_SELECT_44K', + 3: 'HDMI_ACR_SELECT_48K', +} +HDMI_ACR_SELECT_HW = 0 +HDMI_ACR_SELECT_32K = 1 +HDMI_ACR_SELECT_44K = 2 +HDMI_ACR_SELECT_48K = 3 +HDMI_ACR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SEND' +HDMI_ACR_SEND__enumvalues = { + 0: 'HDMI_ACR_NOT_SEND', + 1: 'HDMI_ACR_PKT_SEND', +} +HDMI_ACR_NOT_SEND = 0 +HDMI_ACR_PKT_SEND = 1 +HDMI_ACR_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SOURCE' +HDMI_ACR_SOURCE__enumvalues = { + 0: 'HDMI_ACR_SOURCE_HW', + 1: 'HDMI_ACR_SOURCE_SW', +} +HDMI_ACR_SOURCE_HW = 0 +HDMI_ACR_SOURCE_SW = 1 +HDMI_ACR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_DELAY_EN' +HDMI_AUDIO_DELAY_EN__enumvalues = { + 0: 'HDMI_AUDIO_DELAY_DISABLE', + 1: 'HDMI_AUDIO_DELAY_58CLK', + 2: 'HDMI_AUDIO_DELAY_56CLK', + 3: 'HDMI_AUDIO_DELAY_RESERVED', +} +HDMI_AUDIO_DELAY_DISABLE = 0 +HDMI_AUDIO_DELAY_58CLK = 1 +HDMI_AUDIO_DELAY_56CLK = 2 +HDMI_AUDIO_DELAY_RESERVED = 3 +HDMI_AUDIO_DELAY_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_CONT' +HDMI_AUDIO_INFO_CONT__enumvalues = { + 0: 'HDMI_AUDIO_INFO_CONT_DISABLE', + 1: 'HDMI_AUDIO_INFO_CONT_ENABLE', +} +HDMI_AUDIO_INFO_CONT_DISABLE = 0 +HDMI_AUDIO_INFO_CONT_ENABLE = 1 +HDMI_AUDIO_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_SEND' +HDMI_AUDIO_INFO_SEND__enumvalues = { + 0: 'HDMI_AUDIO_INFO_NOT_SEND', + 1: 'HDMI_AUDIO_INFO_PKT_SEND', +} +HDMI_AUDIO_INFO_NOT_SEND = 0 +HDMI_AUDIO_INFO_PKT_SEND = 1 +HDMI_AUDIO_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_CLOCK_CHANNEL_RATE' +HDMI_CLOCK_CHANNEL_RATE__enumvalues = { + 0: 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 1: 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', +} +HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE = 0 +HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE = 1 +HDMI_CLOCK_CHANNEL_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DATA_SCRAMBLE_EN' +HDMI_DATA_SCRAMBLE_EN__enumvalues = { + 0: 'HDMI_DATA_SCRAMBLE_DISABLE', + 1: 'HDMI_DATA_SCRAMBLE_ENABLE', +} +HDMI_DATA_SCRAMBLE_DISABLE = 0 +HDMI_DATA_SCRAMBLE_ENABLE = 1 +HDMI_DATA_SCRAMBLE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEEP_COLOR_DEPTH' +HDMI_DEEP_COLOR_DEPTH__enumvalues = { + 0: 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 1: 'HDMI_DEEP_COLOR_DEPTH_30BPP', + 2: 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 3: 'HDMI_DEEP_COLOR_DEPTH_48BPP', +} +HDMI_DEEP_COLOR_DEPTH_24BPP = 0 +HDMI_DEEP_COLOR_DEPTH_30BPP = 1 +HDMI_DEEP_COLOR_DEPTH_36BPP = 2 +HDMI_DEEP_COLOR_DEPTH_48BPP = 3 +HDMI_DEEP_COLOR_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEFAULT_PAHSE' +HDMI_DEFAULT_PAHSE__enumvalues = { + 0: 'HDMI_DEFAULT_PHASE_IS_0', + 1: 'HDMI_DEFAULT_PHASE_IS_1', +} +HDMI_DEFAULT_PHASE_IS_0 = 0 +HDMI_DEFAULT_PHASE_IS_1 = 1 +HDMI_DEFAULT_PAHSE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_ACK' +HDMI_ERROR_ACK__enumvalues = { + 0: 'HDMI_ERROR_ACK_INT', + 1: 'HDMI_ERROR_NOT_ACK', +} +HDMI_ERROR_ACK_INT = 0 +HDMI_ERROR_NOT_ACK = 1 +HDMI_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_MASK' +HDMI_ERROR_MASK__enumvalues = { + 0: 'HDMI_ERROR_MASK_INT', + 1: 'HDMI_ERROR_NOT_MASK', +} +HDMI_ERROR_MASK_INT = 0 +HDMI_ERROR_NOT_MASK = 1 +HDMI_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE' +HDMI_GC_AVMUTE__enumvalues = { + 0: 'HDMI_GC_AVMUTE_SET', + 1: 'HDMI_GC_AVMUTE_UNSET', +} +HDMI_GC_AVMUTE_SET = 0 +HDMI_GC_AVMUTE_UNSET = 1 +HDMI_GC_AVMUTE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE_CONT' +HDMI_GC_AVMUTE_CONT__enumvalues = { + 0: 'HDMI_GC_AVMUTE_CONT_DISABLE', + 1: 'HDMI_GC_AVMUTE_CONT_ENABLE', +} +HDMI_GC_AVMUTE_CONT_DISABLE = 0 +HDMI_GC_AVMUTE_CONT_ENABLE = 1 +HDMI_GC_AVMUTE_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_CONT' +HDMI_GC_CONT__enumvalues = { + 0: 'HDMI_GC_CONT_DISABLE', + 1: 'HDMI_GC_CONT_ENABLE', +} +HDMI_GC_CONT_DISABLE = 0 +HDMI_GC_CONT_ENABLE = 1 +HDMI_GC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_SEND' +HDMI_GC_SEND__enumvalues = { + 0: 'HDMI_GC_NOT_SEND', + 1: 'HDMI_GC_PKT_SEND', +} +HDMI_GC_NOT_SEND = 0 +HDMI_GC_PKT_SEND = 1 +HDMI_GC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_CONT' +HDMI_GENERIC_CONT__enumvalues = { + 0: 'HDMI_GENERIC_CONT_DISABLE', + 1: 'HDMI_GENERIC_CONT_ENABLE', +} +HDMI_GENERIC_CONT_DISABLE = 0 +HDMI_GENERIC_CONT_ENABLE = 1 +HDMI_GENERIC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_SEND' +HDMI_GENERIC_SEND__enumvalues = { + 0: 'HDMI_GENERIC_NOT_SEND', + 1: 'HDMI_GENERIC_PKT_SEND', +} +HDMI_GENERIC_NOT_SEND = 0 +HDMI_GENERIC_PKT_SEND = 1 +HDMI_GENERIC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_CONT' +HDMI_ISRC_CONT__enumvalues = { + 0: 'HDMI_ISRC_CONT_DISABLE', + 1: 'HDMI_ISRC_CONT_ENABLE', +} +HDMI_ISRC_CONT_DISABLE = 0 +HDMI_ISRC_CONT_ENABLE = 1 +HDMI_ISRC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_SEND' +HDMI_ISRC_SEND__enumvalues = { + 0: 'HDMI_ISRC_NOT_SEND', + 1: 'HDMI_ISRC_PKT_SEND', +} +HDMI_ISRC_NOT_SEND = 0 +HDMI_ISRC_PKT_SEND = 1 +HDMI_ISRC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_KEEPOUT_MODE' +HDMI_KEEPOUT_MODE__enumvalues = { + 0: 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 1: 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', +} +HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC = 0 +HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC = 1 +HDMI_KEEPOUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_METADATA_ENABLE' +HDMI_METADATA_ENABLE__enumvalues = { + 0: 'HDMI_METADATA_NOT_SEND', + 1: 'HDMI_METADATA_PKT_SEND', +} +HDMI_METADATA_NOT_SEND = 0 +HDMI_METADATA_PKT_SEND = 1 +HDMI_METADATA_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_CONT' +HDMI_MPEG_INFO_CONT__enumvalues = { + 0: 'HDMI_MPEG_INFO_CONT_DISABLE', + 1: 'HDMI_MPEG_INFO_CONT_ENABLE', +} +HDMI_MPEG_INFO_CONT_DISABLE = 0 +HDMI_MPEG_INFO_CONT_ENABLE = 1 +HDMI_MPEG_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_SEND' +HDMI_MPEG_INFO_SEND__enumvalues = { + 0: 'HDMI_MPEG_INFO_NOT_SEND', + 1: 'HDMI_MPEG_INFO_PKT_SEND', +} +HDMI_MPEG_INFO_NOT_SEND = 0 +HDMI_MPEG_INFO_PKT_SEND = 1 +HDMI_MPEG_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NO_EXTRA_NULL_PACKET_FILLED' +HDMI_NO_EXTRA_NULL_PACKET_FILLED__enumvalues = { + 0: 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', + 1: 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', +} +HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE = 0 +HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE = 1 +HDMI_NO_EXTRA_NULL_PACKET_FILLED = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NULL_SEND' +HDMI_NULL_SEND__enumvalues = { + 0: 'HDMI_NULL_NOT_SEND', + 1: 'HDMI_NULL_PKT_SEND', +} +HDMI_NULL_NOT_SEND = 0 +HDMI_NULL_PKT_SEND = 1 +HDMI_NULL_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_GEN_VERSION' +HDMI_PACKET_GEN_VERSION__enumvalues = { + 0: 'HDMI_PACKET_GEN_VERSION_OLD', + 1: 'HDMI_PACKET_GEN_VERSION_NEW', +} +HDMI_PACKET_GEN_VERSION_OLD = 0 +HDMI_PACKET_GEN_VERSION_NEW = 1 +HDMI_PACKET_GEN_VERSION = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_LINE_REFERENCE' +HDMI_PACKET_LINE_REFERENCE__enumvalues = { + 0: 'HDMI_PKT_LINE_REF_VSYNC', + 1: 'HDMI_PKT_LINE_REF_OTGSOF', +} +HDMI_PKT_LINE_REF_VSYNC = 0 +HDMI_PKT_LINE_REF_OTGSOF = 1 +HDMI_PACKET_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKING_PHASE_OVERRIDE' +HDMI_PACKING_PHASE_OVERRIDE__enumvalues = { + 0: 'HDMI_PACKING_PHASE_SET_BY_HW', + 1: 'HDMI_PACKING_PHASE_SET_BY_SW', +} +HDMI_PACKING_PHASE_SET_BY_HW = 0 +HDMI_PACKING_PHASE_SET_BY_SW = 1 +HDMI_PACKING_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT' +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 1: 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', +} +LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS = 0 +LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH = 1 +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_COLOR_FORMAT' +TMDS_COLOR_FORMAT__enumvalues = { + 0: 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 1: 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 2: 'TMDS_COLOR_FORMAT_DUAL30BPP', + 3: 'TMDS_COLOR_FORMAT_RESERVED', +} +TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP = 0 +TMDS_COLOR_FORMAT_TWIN30BPP_LSB = 1 +TMDS_COLOR_FORMAT_DUAL30BPP = 2 +TMDS_COLOR_FORMAT_RESERVED = 3 +TMDS_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_INVERT' +TMDS_CTL0_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL0_DATA_NORMAL', + 1: 'TMDS_CTL0_DATA_INVERT_EN', +} +TMDS_CTL0_DATA_NORMAL = 0 +TMDS_CTL0_DATA_INVERT_EN = 1 +TMDS_CTL0_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_MODULATION' +TMDS_CTL0_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL0_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL0_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL0_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL0_DATA_MODULATION_BIT2', +} +TMDS_CTL0_DATA_MODULATION_DISABLE = 0 +TMDS_CTL0_DATA_MODULATION_BIT0 = 1 +TMDS_CTL0_DATA_MODULATION_BIT1 = 2 +TMDS_CTL0_DATA_MODULATION_BIT2 = 3 +TMDS_CTL0_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_SEL' +TMDS_CTL0_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL0_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL0_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL0_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL0_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 7: 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', +} +TMDS_CTL0_DATA_SEL0_RESERVED = 0 +TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL0_DATA_SEL2_VSYNC = 2 +TMDS_CTL0_DATA_SEL3_RESERVED = 3 +TMDS_CTL0_DATA_SEL4_HSYNC = 4 +TMDS_CTL0_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL0_DATA_SEL8_RANDOM_DATA = 6 +TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA = 7 +TMDS_CTL0_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_PATTERN_OUT_EN' +TMDS_CTL0_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL0_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL0_PATTERN_OUT_ENABLE', +} +TMDS_CTL0_PATTERN_OUT_DISABLE = 0 +TMDS_CTL0_PATTERN_OUT_ENABLE = 1 +TMDS_CTL0_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_INVERT' +TMDS_CTL1_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL1_DATA_NORMAL', + 1: 'TMDS_CTL1_DATA_INVERT_EN', +} +TMDS_CTL1_DATA_NORMAL = 0 +TMDS_CTL1_DATA_INVERT_EN = 1 +TMDS_CTL1_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_MODULATION' +TMDS_CTL1_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL1_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL1_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL1_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL1_DATA_MODULATION_BIT2', +} +TMDS_CTL1_DATA_MODULATION_DISABLE = 0 +TMDS_CTL1_DATA_MODULATION_BIT0 = 1 +TMDS_CTL1_DATA_MODULATION_BIT1 = 2 +TMDS_CTL1_DATA_MODULATION_BIT2 = 3 +TMDS_CTL1_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_SEL' +TMDS_CTL1_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL1_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL1_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL1_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL1_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL1_DATA_SEL0_RESERVED = 0 +TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL1_DATA_SEL2_VSYNC = 2 +TMDS_CTL1_DATA_SEL3_RESERVED = 3 +TMDS_CTL1_DATA_SEL4_HSYNC = 4 +TMDS_CTL1_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL1_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL1_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL1_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_PATTERN_OUT_EN' +TMDS_CTL1_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL1_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL1_PATTERN_OUT_ENABLE', +} +TMDS_CTL1_PATTERN_OUT_DISABLE = 0 +TMDS_CTL1_PATTERN_OUT_ENABLE = 1 +TMDS_CTL1_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_INVERT' +TMDS_CTL2_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL2_DATA_NORMAL', + 1: 'TMDS_CTL2_DATA_INVERT_EN', +} +TMDS_CTL2_DATA_NORMAL = 0 +TMDS_CTL2_DATA_INVERT_EN = 1 +TMDS_CTL2_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_MODULATION' +TMDS_CTL2_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL2_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL2_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL2_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL2_DATA_MODULATION_BIT2', +} +TMDS_CTL2_DATA_MODULATION_DISABLE = 0 +TMDS_CTL2_DATA_MODULATION_BIT0 = 1 +TMDS_CTL2_DATA_MODULATION_BIT1 = 2 +TMDS_CTL2_DATA_MODULATION_BIT2 = 3 +TMDS_CTL2_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_SEL' +TMDS_CTL2_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL2_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL2_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL2_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL2_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL2_DATA_SEL0_RESERVED = 0 +TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL2_DATA_SEL2_VSYNC = 2 +TMDS_CTL2_DATA_SEL3_RESERVED = 3 +TMDS_CTL2_DATA_SEL4_HSYNC = 4 +TMDS_CTL2_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL2_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL2_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL2_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_PATTERN_OUT_EN' +TMDS_CTL2_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL2_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL2_PATTERN_OUT_ENABLE', +} +TMDS_CTL2_PATTERN_OUT_DISABLE = 0 +TMDS_CTL2_PATTERN_OUT_ENABLE = 1 +TMDS_CTL2_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_INVERT' +TMDS_CTL3_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL3_DATA_NORMAL', + 1: 'TMDS_CTL3_DATA_INVERT_EN', +} +TMDS_CTL3_DATA_NORMAL = 0 +TMDS_CTL3_DATA_INVERT_EN = 1 +TMDS_CTL3_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_MODULATION' +TMDS_CTL3_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL3_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL3_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL3_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL3_DATA_MODULATION_BIT2', +} +TMDS_CTL3_DATA_MODULATION_DISABLE = 0 +TMDS_CTL3_DATA_MODULATION_BIT0 = 1 +TMDS_CTL3_DATA_MODULATION_BIT1 = 2 +TMDS_CTL3_DATA_MODULATION_BIT2 = 3 +TMDS_CTL3_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_SEL' +TMDS_CTL3_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL3_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL3_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL3_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL3_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL3_DATA_SEL0_RESERVED = 0 +TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL3_DATA_SEL2_VSYNC = 2 +TMDS_CTL3_DATA_SEL3_RESERVED = 3 +TMDS_CTL3_DATA_SEL4_HSYNC = 4 +TMDS_CTL3_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL3_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL3_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL3_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_PATTERN_OUT_EN' +TMDS_CTL3_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL3_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL3_PATTERN_OUT_ENABLE', +} +TMDS_CTL3_PATTERN_OUT_DISABLE = 0 +TMDS_CTL3_PATTERN_OUT_ENABLE = 1 +TMDS_CTL3_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL' +TMDS_DATA_SYNCHRONIZATION_DSINTSEL__enumvalues = { + 0: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 1: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', +} +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS = 0 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL = 1 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_PIXEL_ENCODING' +TMDS_PIXEL_ENCODING__enumvalues = { + 0: 'TMDS_PIXEL_ENCODING_444_OR_420', + 1: 'TMDS_PIXEL_ENCODING_422', +} +TMDS_PIXEL_ENCODING_444_OR_420 = 0 +TMDS_PIXEL_ENCODING_422 = 1 +TMDS_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTA_CNTLA' +TMDS_REG_TEST_OUTPUTA_CNTLA__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 1: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 2: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 3: 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', +} +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0 = 0 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1 = 1 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2 = 2 +TMDS_REG_TEST_OUTPUTA_CNTLA_NA = 3 +TMDS_REG_TEST_OUTPUTA_CNTLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTB_CNTLB' +TMDS_REG_TEST_OUTPUTB_CNTLB__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 1: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 2: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', + 3: 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', +} +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0 = 0 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1 = 1 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2 = 2 +TMDS_REG_TEST_OUTPUTB_CNTLB_NA = 3 +TMDS_REG_TEST_OUTPUTB_CNTLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_STEREOSYNC_CTL_SEL_REG' +TMDS_STEREOSYNC_CTL_SEL_REG__enumvalues = { + 0: 'TMDS_STEREOSYNC_CTL0', + 1: 'TMDS_STEREOSYNC_CTL1', + 2: 'TMDS_STEREOSYNC_CTL2', + 3: 'TMDS_STEREOSYNC_CTL3', +} +TMDS_STEREOSYNC_CTL0 = 0 +TMDS_STEREOSYNC_CTL1 = 1 +TMDS_STEREOSYNC_CTL2 = 2 +TMDS_STEREOSYNC_CTL3 = 3 +TMDS_STEREOSYNC_CTL_SEL_REG = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_SYNC_PHASE' +TMDS_SYNC_PHASE__enumvalues = { + 0: 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 1: 'TMDS_SYNC_PHASE_ON_FRAME_START', +} +TMDS_NOT_SYNC_PHASE_ON_FRAME_START = 0 +TMDS_SYNC_PHASE_ON_FRAME_START = 1 +TMDS_SYNC_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA' +TMDS_TRANSMITTER_CONTROL_IDSCKSELA__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB' +TMDS_TRANSMITTER_CONTROL_IDSCKSELB__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN' +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 1: 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', +} +TMDS_TRANSMITTER_PLLSEL_BY_HW = 0 +TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW = 1 +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 1: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 2: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 3: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', +} +TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE = 0 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON = 1 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON = 2 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE = 3 +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN' +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 1: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', +} +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE = 0 +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE = 1 +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 1: 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', +} +TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD = 0 +TMDS_TRANSMITTER_PLL_RST_ON_HPD = 1 +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 1: 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK = 0 +TMDS_TRANSMITTER_TDCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 1: 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK = 0 +TMDS_TRANSMITTER_TMCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_ARB_PRIORITY' +DP_AUX_ARB_CONTROL_ARB_PRIORITY__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 1: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 2: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 3: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', +} +DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW = 0 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW = 1 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC = 2 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS = 3 +DP_AUX_ARB_CONTROL_ARB_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG' +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 1: 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', +} +DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG = 0 +DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG = 1 +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ' +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 1: 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', +} +DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ = 0 +DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ = 1 +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_STATUS' +DP_AUX_ARB_STATUS__enumvalues = { + 0: 'DP_AUX_IDLE', + 1: 'DP_AUX_IN_USE_LS', + 2: 'DP_AUX_IN_USE_GTC', + 3: 'DP_AUX_IN_USE_SW', + 4: 'DP_AUX_IN_USE_PHYWAKE', +} +DP_AUX_IDLE = 0 +DP_AUX_IN_USE_LS = 1 +DP_AUX_IN_USE_GTC = 2 +DP_AUX_IN_USE_SW = 3 +DP_AUX_IN_USE_PHYWAKE = 4 +DP_AUX_ARB_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_HPD_SEL' +DP_AUX_CONTROL_HPD_SEL__enumvalues = { + 0: 'DP_AUX_CONTROL_HPD1_SELECTED', + 1: 'DP_AUX_CONTROL_HPD2_SELECTED', + 2: 'DP_AUX_CONTROL_HPD3_SELECTED', + 3: 'DP_AUX_CONTROL_HPD4_SELECTED', + 4: 'DP_AUX_CONTROL_HPD5_SELECTED', + 5: 'DP_AUX_CONTROL_NO_HPD_SELECTED', +} +DP_AUX_CONTROL_HPD1_SELECTED = 0 +DP_AUX_CONTROL_HPD2_SELECTED = 1 +DP_AUX_CONTROL_HPD3_SELECTED = 2 +DP_AUX_CONTROL_HPD4_SELECTED = 3 +DP_AUX_CONTROL_HPD5_SELECTED = 4 +DP_AUX_CONTROL_NO_HPD_SELECTED = 5 +DP_AUX_CONTROL_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_TEST_MODE' +DP_AUX_CONTROL_TEST_MODE__enumvalues = { + 0: 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 1: 'DP_AUX_CONTROL_TEST_MODE_ENABLE', +} +DP_AUX_CONTROL_TEST_MODE_DISABLE = 0 +DP_AUX_CONTROL_TEST_MODE_ENABLE = 1 +DP_AUX_CONTROL_TEST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DEFINITE_ERR_REACHED_ACK' +DP_AUX_DEFINITE_ERR_REACHED_ACK__enumvalues = { + 0: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', + 1: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', +} +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK = 0 +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK = 1 +DP_AUX_DEFINITE_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 1: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 2: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 3: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', +} +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES = 0 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES = 1 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES = 2 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED = 3 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 1: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 2: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 3: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', +} +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS = 0 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS = 1 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS = 2 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS = 3 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW' +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW' +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD' +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__enumvalues = { + 0: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 1: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 2: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 3: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 4: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 5: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 6: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 7: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', +} +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2 = 0 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4 = 1 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8 = 2 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16 = 3 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32 = 4 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64 = 5 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128 = 6 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256 = 7 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY' +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__enumvalues = { + 0: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 1: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 2: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 3: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 4: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 5: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', +} +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0 = 0 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US = 1 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US = 2 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US = 3 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US = 4 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US = 5 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE' +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 2: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 3: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ = 2 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ = 3 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL' +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ERR_OCCURRED_ACK' +DP_AUX_ERR_OCCURRED_ACK__enumvalues = { + 0: 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 1: 'DP_AUX_ERR_OCCURRED__ACK', +} +DP_AUX_ERR_OCCURRED__NOT_ACK = 0 +DP_AUX_ERR_OCCURRED__ACK = 1 +DP_AUX_ERR_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ' +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 1: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', +} +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX = 0 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX = 1 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW' +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 1: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 2: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 3: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', +} +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US = 0 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US = 1 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US = 2 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US = 3 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT' +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 1: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 2: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 3: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', +} +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS = 0 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS = 1 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS = 2 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED = 3 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN' +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 1: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 2: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 3: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', +} +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0 = 0 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64 = 1 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128 = 2 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256 = 3 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_INT_ACK' +DP_AUX_INT_ACK__enumvalues = { + 0: 'DP_AUX_INT__NOT_ACK', + 1: 'DP_AUX_INT__ACK', +} +DP_AUX_INT__NOT_ACK = 0 +DP_AUX_INT__ACK = 1 +DP_AUX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_LS_UPDATE_ACK' +DP_AUX_LS_UPDATE_ACK__enumvalues = { + 0: 'DP_AUX_INT_LS_UPDATE_NOT_ACK', + 1: 'DP_AUX_INT_LS_UPDATE_ACK', +} +DP_AUX_INT_LS_UPDATE_NOT_ACK = 0 +DP_AUX_INT_LS_UPDATE_ACK = 1 +DP_AUX_LS_UPDATE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_PHY_WAKE_PRIORITY' +DP_AUX_PHY_WAKE_PRIORITY__enumvalues = { + 0: 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', + 1: 'DP_AUX_PHY_WAKE_LOW_PRIORITY', +} +DP_AUX_PHY_WAKE_HIGH_PRIORITY = 0 +DP_AUX_PHY_WAKE_LOW_PRIORITY = 1 +DP_AUX_PHY_WAKE_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_POTENTIAL_ERR_REACHED_ACK' +DP_AUX_POTENTIAL_ERR_REACHED_ACK__enumvalues = { + 0: 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', + 1: 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', +} +DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK = 0 +DP_AUX_POTENTIAL_ERR_REACHED__ACK = 1 +DP_AUX_POTENTIAL_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET' +DP_AUX_RESET__enumvalues = { + 0: 'DP_AUX_RESET_DEASSERTED', + 1: 'DP_AUX_RESET_ASSERTED', +} +DP_AUX_RESET_DEASSERTED = 0 +DP_AUX_RESET_ASSERTED = 1 +DP_AUX_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET_DONE' +DP_AUX_RESET_DONE__enumvalues = { + 0: 'DP_AUX_RESET_SEQUENCE_NOT_DONE', + 1: 'DP_AUX_RESET_SEQUENCE_DONE', +} +DP_AUX_RESET_SEQUENCE_NOT_DONE = 0 +DP_AUX_RESET_SEQUENCE_DONE = 1 +DP_AUX_RESET_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RX_TIMEOUT_LEN_MUL' +DP_AUX_RX_TIMEOUT_LEN_MUL__enumvalues = { + 0: 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 1: 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', + 2: 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 3: 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', +} +DP_AUX_RX_TIMEOUT_LEN_NO_MUL = 0 +DP_AUX_RX_TIMEOUT_LEN_MUL_2 = 1 +DP_AUX_RX_TIMEOUT_LEN_MUL_4 = 2 +DP_AUX_RX_TIMEOUT_LEN_MUL_8 = 3 +DP_AUX_RX_TIMEOUT_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_LS_READ_TRIG' +DP_AUX_SW_CONTROL_LS_READ_TRIG__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 1: 'DP_AUX_SW_CONTROL_LS_READ__TRIG', +} +DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG = 0 +DP_AUX_SW_CONTROL_LS_READ__TRIG = 1 +DP_AUX_SW_CONTROL_LS_READ_TRIG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_SW_GO' +DP_AUX_SW_CONTROL_SW_GO__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 1: 'DP_AUX_SW_CONTROL_SW__GO', +} +DP_AUX_SW_CONTROL_SW__NOT_GO = 0 +DP_AUX_SW_CONTROL_SW__GO = 1 +DP_AUX_SW_CONTROL_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_TX_PRECHARGE_LEN_MUL' +DP_AUX_TX_PRECHARGE_LEN_MUL__enumvalues = { + 0: 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', + 1: 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 2: 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', + 3: 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', +} +DP_AUX_TX_PRECHARGE_LEN_NO_MUL = 0 +DP_AUX_TX_PRECHARGE_LEN_MUL_2 = 1 +DP_AUX_TX_PRECHARGE_LEN_MUL_4 = 2 +DP_AUX_TX_PRECHARGE_LEN_MUL_8 = 3 +DP_AUX_TX_PRECHARGE_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ACK' +DOUT_I2C_ACK__enumvalues = { + 0: 'DOUT_I2C_NO_ACK', + 1: 'DOUT_I2C_ACK_TO_CLEAN', +} +DOUT_I2C_NO_ACK = 0 +DOUT_I2C_ACK_TO_CLEAN = 1 +DOUT_I2C_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_ABORT_XFER' +DOUT_I2C_ARBITRATION_ABORT_XFER__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 1: 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', +} +DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER = 0 +DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER = 1 +DOUT_I2C_ARBITRATION_ABORT_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG' +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 1: 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', +} +DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG = 0 +DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG = 1 +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO' +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 1: 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', +} +DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED = 0 +DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED = 1 +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_SW_PRIORITY' +DOUT_I2C_ARBITRATION_SW_PRIORITY__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 1: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 2: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 3: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', +} +DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL = 0 +DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH = 1 +DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED = 2 +DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED = 3 +DOUT_I2C_ARBITRATION_SW_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ' +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 1: 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', +} +DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ = 0 +DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ = 1 +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DBG_REF_SEL' +DOUT_I2C_CONTROL_DBG_REF_SEL__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 1: 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', +} +DOUT_I2C_CONTROL_NORMAL_DEBUG = 0 +DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG = 1 +DOUT_I2C_CONTROL_DBG_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DDC_SELECT' +DOUT_I2C_CONTROL_DDC_SELECT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_SELECT_DDC1', + 1: 'DOUT_I2C_CONTROL_SELECT_DDC2', + 2: 'DOUT_I2C_CONTROL_SELECT_DDC3', + 3: 'DOUT_I2C_CONTROL_SELECT_DDC4', + 4: 'DOUT_I2C_CONTROL_SELECT_DDC5', + 5: 'DOUT_I2C_CONTROL_SELECT_DDCVGA', +} +DOUT_I2C_CONTROL_SELECT_DDC1 = 0 +DOUT_I2C_CONTROL_SELECT_DDC2 = 1 +DOUT_I2C_CONTROL_SELECT_DDC3 = 2 +DOUT_I2C_CONTROL_SELECT_DDC4 = 3 +DOUT_I2C_CONTROL_SELECT_DDC5 = 4 +DOUT_I2C_CONTROL_SELECT_DDCVGA = 5 +DOUT_I2C_CONTROL_DDC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_GO' +DOUT_I2C_CONTROL_GO__enumvalues = { + 0: 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 1: 'DOUT_I2C_CONTROL_START_TRANSFER', +} +DOUT_I2C_CONTROL_STOP_TRANSFER = 0 +DOUT_I2C_CONTROL_START_TRANSFER = 1 +DOUT_I2C_CONTROL_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET' +DOUT_I2C_CONTROL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 1: 'DOUT_I2C_CONTROL__SEND_RESET', +} +DOUT_I2C_CONTROL__NOT_SEND_RESET = 0 +DOUT_I2C_CONTROL__SEND_RESET = 1 +DOUT_I2C_CONTROL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH' +DOUT_I2C_CONTROL_SEND_RESET_LENGTH__enumvalues = { + 0: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 1: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', +} +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9 = 0 +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10 = 1 +DOUT_I2C_CONTROL_SEND_RESET_LENGTH = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SOFT_RESET' +DOUT_I2C_CONTROL_SOFT_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 1: 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', +} +DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER = 0 +DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER = 1 +DOUT_I2C_CONTROL_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SW_STATUS_RESET' +DOUT_I2C_CONTROL_SW_STATUS_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 1: 'DOUT_I2C_CONTROL_RESET_SW_STATUS', +} +DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS = 0 +DOUT_I2C_CONTROL_RESET_SW_STATUS = 1 +DOUT_I2C_CONTROL_SW_STATUS_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_TRANSACTION_COUNT' +DOUT_I2C_CONTROL_TRANSACTION_COUNT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_TRANS0', + 1: 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 2: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 3: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', +} +DOUT_I2C_CONTROL_TRANS0 = 0 +DOUT_I2C_CONTROL_TRANS0_TRANS1 = 1 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2 = 2 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3 = 3 +DOUT_I2C_CONTROL_TRANSACTION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DATA_INDEX_WRITE' +DOUT_I2C_DATA_INDEX_WRITE__enumvalues = { + 0: 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 1: 'DOUT_I2C_DATA__INDEX_WRITE', +} +DOUT_I2C_DATA__NOT_INDEX_WRITE = 0 +DOUT_I2C_DATA__INDEX_WRITE = 1 +DOUT_I2C_DATA_INDEX_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN' +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', +} +DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL = 1 +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 1: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS = 0 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE' +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 1: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', +} +DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT = 0 +DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT = 1 +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SPEED_THRESHOLD' +DOUT_I2C_DDC_SPEED_THRESHOLD__enumvalues = { + 0: 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 1: 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 2: 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 3: 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', +} +DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO = 0 +DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE = 1 +DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE = 2 +DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE = 3 +DOUT_I2C_DDC_SPEED_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET' +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 1: 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', +} +DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION = 0 +DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION = 1 +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE' +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__enumvalues = { + 0: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 1: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', +} +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL = 0 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE = 1 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_TRANSACTION_STOP_ON_NACK' +DOUT_I2C_TRANSACTION_STOP_ON_NACK__enumvalues = { + 0: 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 1: 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', +} +DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS = 0 +DOUT_I2C_TRANSACTION_STOP_ALL_TRANS = 1 +DOUT_I2C_TRANSACTION_STOP_ON_NACK = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_EN' +CLOCK_GATING_EN__enumvalues = { + 0: 'CLOCK_GATING_ENABLE', + 1: 'CLOCK_GATING_DISABLE', +} +CLOCK_GATING_ENABLE = 0 +CLOCK_GATING_DISABLE = 1 +CLOCK_GATING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DAC_MUX_SELECT' +DAC_MUX_SELECT__enumvalues = { + 0: 'DAC_MUX_SELECT_DACA', + 1: 'DAC_MUX_SELECT_DACB', +} +DAC_MUX_SELECT_DACA = 0 +DAC_MUX_SELECT_DACB = 1 +DAC_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_DIS_CTRL' +DIOMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 1: 'DIOMEM_DISABLE_MEM_PWR_CTRL', +} +DIOMEM_ENABLE_MEM_PWR_CTRL = 0 +DIOMEM_DISABLE_MEM_PWR_CTRL = 1 +DIOMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL' +DIOMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQUEST', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', +} +DIOMEM_NO_FORCE_REQUEST = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DIOMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +DIOMEM_FORCE_SHUT_DOWN_REQUEST = 3 +DIOMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL2' +DIOMEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQ', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', +} +DIOMEM_NO_FORCE_REQ = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQ = 1 +DIOMEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL' +DIOMEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE = 0 +DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +DIOMEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL2' +DIOMEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 1: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', +} +DIOMEM_DYNAMIC_DEEP_SLEEP_EN = 0 +DIOMEM_DYNAMIC_LIGHT_SLEEP_EN = 1 +DIOMEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_DBG_BLOCK_SEL' +DIO_DBG_BLOCK_SEL__enumvalues = { + 0: 'DIO_DBG_BLOCK_SEL_DIO', + 11: 'DIO_DBG_BLOCK_SEL_DIGFE_A', + 12: 'DIO_DBG_BLOCK_SEL_DIGFE_B', + 13: 'DIO_DBG_BLOCK_SEL_DIGFE_C', + 14: 'DIO_DBG_BLOCK_SEL_DIGFE_D', + 15: 'DIO_DBG_BLOCK_SEL_DIGFE_E', + 18: 'DIO_DBG_BLOCK_SEL_DIGA', + 19: 'DIO_DBG_BLOCK_SEL_DIGB', + 20: 'DIO_DBG_BLOCK_SEL_DIGC', + 21: 'DIO_DBG_BLOCK_SEL_DIGD', + 22: 'DIO_DBG_BLOCK_SEL_DIGE', + 25: 'DIO_DBG_BLOCK_SEL_DPFE_A', + 26: 'DIO_DBG_BLOCK_SEL_DPFE_B', + 27: 'DIO_DBG_BLOCK_SEL_DPFE_C', + 28: 'DIO_DBG_BLOCK_SEL_DPFE_D', + 29: 'DIO_DBG_BLOCK_SEL_DPFE_E', + 32: 'DIO_DBG_BLOCK_SEL_DPA', + 33: 'DIO_DBG_BLOCK_SEL_DPB', + 34: 'DIO_DBG_BLOCK_SEL_DPC', + 35: 'DIO_DBG_BLOCK_SEL_DPD', + 36: 'DIO_DBG_BLOCK_SEL_DPE', + 39: 'DIO_DBG_BLOCK_SEL_AUX0', + 40: 'DIO_DBG_BLOCK_SEL_AUX1', + 41: 'DIO_DBG_BLOCK_SEL_AUX2', + 42: 'DIO_DBG_BLOCK_SEL_AUX3', + 43: 'DIO_DBG_BLOCK_SEL_AUX4', + 45: 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', + 46: 'DIO_DBG_BLOCK_SEL_RESERVED', +} +DIO_DBG_BLOCK_SEL_DIO = 0 +DIO_DBG_BLOCK_SEL_DIGFE_A = 11 +DIO_DBG_BLOCK_SEL_DIGFE_B = 12 +DIO_DBG_BLOCK_SEL_DIGFE_C = 13 +DIO_DBG_BLOCK_SEL_DIGFE_D = 14 +DIO_DBG_BLOCK_SEL_DIGFE_E = 15 +DIO_DBG_BLOCK_SEL_DIGA = 18 +DIO_DBG_BLOCK_SEL_DIGB = 19 +DIO_DBG_BLOCK_SEL_DIGC = 20 +DIO_DBG_BLOCK_SEL_DIGD = 21 +DIO_DBG_BLOCK_SEL_DIGE = 22 +DIO_DBG_BLOCK_SEL_DPFE_A = 25 +DIO_DBG_BLOCK_SEL_DPFE_B = 26 +DIO_DBG_BLOCK_SEL_DPFE_C = 27 +DIO_DBG_BLOCK_SEL_DPFE_D = 28 +DIO_DBG_BLOCK_SEL_DPFE_E = 29 +DIO_DBG_BLOCK_SEL_DPA = 32 +DIO_DBG_BLOCK_SEL_DPB = 33 +DIO_DBG_BLOCK_SEL_DPC = 34 +DIO_DBG_BLOCK_SEL_DPD = 35 +DIO_DBG_BLOCK_SEL_DPE = 36 +DIO_DBG_BLOCK_SEL_AUX0 = 39 +DIO_DBG_BLOCK_SEL_AUX1 = 40 +DIO_DBG_BLOCK_SEL_AUX2 = 41 +DIO_DBG_BLOCK_SEL_AUX3 = 42 +DIO_DBG_BLOCK_SEL_AUX4 = 43 +DIO_DBG_BLOCK_SEL_PERFMON_DIO = 45 +DIO_DBG_BLOCK_SEL_RESERVED = 46 +DIO_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE' +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE__enumvalues = { + 0: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 1: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', +} +DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL = 0 +DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE = 1 +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE' +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE__enumvalues = { + 0: 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0', + 1: 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1', +} +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0 = 0 +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1 = 1 +DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DIO_DCN_ACTIVE_STATUS' +ENUM_DIO_DCN_ACTIVE_STATUS__enumvalues = { + 0: 'ENUM_DCN_NOT_ACTIVE', + 1: 'ENUM_DCN_ACTIVE', +} +ENUM_DCN_NOT_ACTIVE = 0 +ENUM_DCN_ACTIVE = 1 +ENUM_DIO_DCN_ACTIVE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_STEREOSYNC_SEL' +GENERIC_STEREOSYNC_SEL__enumvalues = { + 0: 'GENERIC_STEREOSYNC_SEL_D1', + 1: 'GENERIC_STEREOSYNC_SEL_D2', + 2: 'GENERIC_STEREOSYNC_SEL_D3', + 3: 'GENERIC_STEREOSYNC_SEL_D4', + 4: 'GENERIC_STEREOSYNC_SEL_RESERVED', +} +GENERIC_STEREOSYNC_SEL_D1 = 0 +GENERIC_STEREOSYNC_SEL_D2 = 1 +GENERIC_STEREOSYNC_SEL_D3 = 2 +GENERIC_STEREOSYNC_SEL_D4 = 3 +GENERIC_STEREOSYNC_SEL_RESERVED = 4 +GENERIC_STEREOSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PM_ASSERT_RESET' +PM_ASSERT_RESET__enumvalues = { + 0: 'PM_ASSERT_RESET_0', + 1: 'PM_ASSERT_RESET_1', +} +PM_ASSERT_RESET_0 = 0 +PM_ASSERT_RESET_1 = 1 +PM_ASSERT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'SOFT_RESET' +SOFT_RESET__enumvalues = { + 0: 'SOFT_RESET_0', + 1: 'SOFT_RESET_1', +} +SOFT_RESET_0 = 0 +SOFT_RESET_1 = 1 +SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_MUX_SELECT' +TMDS_MUX_SELECT__enumvalues = { + 0: 'TMDS_MUX_SELECT_B', + 1: 'TMDS_MUX_SELECT_G', + 2: 'TMDS_MUX_SELECT_R', + 3: 'TMDS_MUX_SELECT_RESERVED', +} +TMDS_MUX_SELECT_B = 0 +TMDS_MUX_SELECT_G = 1 +TMDS_MUX_SELECT_R = 2 +TMDS_MUX_SELECT_RESERVED = 3 +TMDS_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_POWER_STATE_ENUM' +DME_MEM_POWER_STATE_ENUM__enumvalues = { + 0: 'DME_MEM_POWER_STATE_ENUM_ON', + 1: 'DME_MEM_POWER_STATE_ENUM_LS', + 2: 'DME_MEM_POWER_STATE_ENUM_DS', + 3: 'DME_MEM_POWER_STATE_ENUM_SD', +} +DME_MEM_POWER_STATE_ENUM_ON = 0 +DME_MEM_POWER_STATE_ENUM_LS = 1 +DME_MEM_POWER_STATE_ENUM_DS = 2 +DME_MEM_POWER_STATE_ENUM_SD = 3 +DME_MEM_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_PWR_DIS_CTRL' +DME_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'DME_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'DME_MEM_DISABLE_MEM_PWR_CTRL', +} +DME_MEM_ENABLE_MEM_PWR_CTRL = 0 +DME_MEM_DISABLE_MEM_PWR_CTRL = 1 +DME_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_PWR_FORCE_CTRL' +DME_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'DME_MEM_NO_FORCE_REQUEST', + 1: 'DME_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DME_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DME_MEM_FORCE_SHUT_DOWN_REQUEST', +} +DME_MEM_NO_FORCE_REQUEST = 0 +DME_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DME_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +DME_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +DME_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_HUBP_SEL' +METADATA_HUBP_SEL__enumvalues = { + 0: 'METADATA_HUBP_SEL_0', + 1: 'METADATA_HUBP_SEL_1', + 2: 'METADATA_HUBP_SEL_2', + 3: 'METADATA_HUBP_SEL_3', + 4: 'METADATA_HUBP_SEL_RESERVED', +} +METADATA_HUBP_SEL_0 = 0 +METADATA_HUBP_SEL_1 = 1 +METADATA_HUBP_SEL_2 = 2 +METADATA_HUBP_SEL_3 = 3 +METADATA_HUBP_SEL_RESERVED = 4 +METADATA_HUBP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_STREAM_TYPE_SEL' +METADATA_STREAM_TYPE_SEL__enumvalues = { + 0: 'METADATA_STREAM_DP', + 1: 'METADATA_STREAM_DVE', +} +METADATA_STREAM_DP = 0 +METADATA_STREAM_DVE = 1 +METADATA_STREAM_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VPG_MEM_PWR_DIS_CTRL' +VPG_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'VPG_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'VPG_MEM_DISABLE_MEM_PWR_CTRL', +} +VPG_MEM_ENABLE_MEM_PWR_CTRL = 0 +VPG_MEM_DISABLE_MEM_PWR_CTRL = 1 +VPG_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'VPG_MEM_PWR_FORCE_CTRL' +VPG_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'VPG_MEM_NO_FORCE_REQ', + 1: 'VPG_MEM_FORCE_LIGHT_SLEEP_REQ', +} +VPG_MEM_NO_FORCE_REQ = 0 +VPG_MEM_FORCE_LIGHT_SLEEP_REQ = 1 +VPG_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_ACP_TYPE' +AFMT_ACP_TYPE__enumvalues = { + 0: 'ACP_TYPE_GENERIC_AUDIO', + 1: 'ACP_TYPE_ICE60958_AUDIO', + 2: 'ACP_TYPE_DVD_AUDIO', + 3: 'ACP_TYPE_SUPER_AUDIO_CD', +} +ACP_TYPE_GENERIC_AUDIO = 0 +ACP_TYPE_ICE60958_AUDIO = 1 +ACP_TYPE_DVD_AUDIO = 2 +ACP_TYPE_SUPER_AUDIO_CD = 3 +AFMT_ACP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CH_SEL' +AFMT_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'AFMT_AUDIO_CRC_CH0_SIG', + 1: 'AFMT_AUDIO_CRC_CH1_SIG', + 2: 'AFMT_AUDIO_CRC_CH2_SIG', + 3: 'AFMT_AUDIO_CRC_CH3_SIG', + 4: 'AFMT_AUDIO_CRC_CH4_SIG', + 5: 'AFMT_AUDIO_CRC_CH5_SIG', + 6: 'AFMT_AUDIO_CRC_CH6_SIG', + 7: 'AFMT_AUDIO_CRC_CH7_SIG', + 8: 'AFMT_AUDIO_CRC_RESERVED_8', + 9: 'AFMT_AUDIO_CRC_RESERVED_9', + 10: 'AFMT_AUDIO_CRC_RESERVED_10', + 11: 'AFMT_AUDIO_CRC_RESERVED_11', + 12: 'AFMT_AUDIO_CRC_RESERVED_12', + 13: 'AFMT_AUDIO_CRC_RESERVED_13', + 14: 'AFMT_AUDIO_CRC_RESERVED_14', + 15: 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', +} +AFMT_AUDIO_CRC_CH0_SIG = 0 +AFMT_AUDIO_CRC_CH1_SIG = 1 +AFMT_AUDIO_CRC_CH2_SIG = 2 +AFMT_AUDIO_CRC_CH3_SIG = 3 +AFMT_AUDIO_CRC_CH4_SIG = 4 +AFMT_AUDIO_CRC_CH5_SIG = 5 +AFMT_AUDIO_CRC_CH6_SIG = 6 +AFMT_AUDIO_CRC_CH7_SIG = 7 +AFMT_AUDIO_CRC_RESERVED_8 = 8 +AFMT_AUDIO_CRC_RESERVED_9 = 9 +AFMT_AUDIO_CRC_RESERVED_10 = 10 +AFMT_AUDIO_CRC_RESERVED_11 = 11 +AFMT_AUDIO_CRC_RESERVED_12 = 12 +AFMT_AUDIO_CRC_RESERVED_13 = 13 +AFMT_AUDIO_CRC_RESERVED_14 = 14 +AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT = 15 +AFMT_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CONT' +AFMT_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'AFMT_AUDIO_CRC_ONESHOT', + 1: 'AFMT_AUDIO_CRC_AUTO_RESTART', +} +AFMT_AUDIO_CRC_ONESHOT = 0 +AFMT_AUDIO_CRC_AUTO_RESTART = 1 +AFMT_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_SOURCE' +AFMT_AUDIO_CRC_CONTROL_SOURCE__enumvalues = { + 0: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 1: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', +} +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT = 0 +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT = 1 +AFMT_AUDIO_CRC_CONTROL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD' +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD__enumvalues = { + 0: 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 1: 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', +} +AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS = 0 +AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER = 1 +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND' +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND__enumvalues = { + 0: 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 1: 'AFMT_AUDIO_PACKET_SENT_ENABLED', +} +AFMT_AUDIO_PACKET_SENT_DISABLED = 0 +AFMT_AUDIO_PACKET_SENT_ENABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS' +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS__enumvalues = { + 0: 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 1: 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', +} +AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED = 0 +AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_SRC_CONTROL_SELECT' +AFMT_AUDIO_SRC_CONTROL_SELECT__enumvalues = { + 0: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 1: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 2: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 3: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 4: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 5: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', +} +AFMT_AUDIO_SRC_FROM_AZ_STREAM0 = 0 +AFMT_AUDIO_SRC_FROM_AZ_STREAM1 = 1 +AFMT_AUDIO_SRC_FROM_AZ_STREAM2 = 2 +AFMT_AUDIO_SRC_FROM_AZ_STREAM3 = 3 +AFMT_AUDIO_SRC_FROM_AZ_STREAM4 = 4 +AFMT_AUDIO_SRC_FROM_AZ_STREAM5 = 5 +AFMT_AUDIO_SRC_CONTROL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_HDMI_AUDIO_SEND_MAX_PACKETS' +AFMT_HDMI_AUDIO_SEND_MAX_PACKETS__enumvalues = { + 0: 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 1: 'HDMI_SEND_MAX_AUDIO_PACKETS', +} +HDMI_NOT_SEND_MAX_AUDIO_PACKETS = 0 +HDMI_SEND_MAX_AUDIO_PACKETS = 1 +AFMT_HDMI_AUDIO_SEND_MAX_PACKETS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE' +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 1: 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK = 0 +AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INTERRUPT_STATUS_CHG_MASK' +AFMT_INTERRUPT_STATUS_CHG_MASK__enumvalues = { + 0: 'AFMT_INTERRUPT_DISABLE', + 1: 'AFMT_INTERRUPT_ENABLE', +} +AFMT_INTERRUPT_DISABLE = 0 +AFMT_INTERRUPT_ENABLE = 1 +AFMT_INTERRUPT_STATUS_CHG_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_MEM_PWR_DIS_CTRL' +AFMT_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'AFMT_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'AFMT_MEM_DISABLE_MEM_PWR_CTRL', +} +AFMT_MEM_ENABLE_MEM_PWR_CTRL = 0 +AFMT_MEM_DISABLE_MEM_PWR_CTRL = 1 +AFMT_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_MEM_PWR_FORCE_CTRL' +AFMT_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'AFMT_MEM_NO_FORCE_REQUEST', + 1: 'AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'AFMT_MEM_FORCE_SHUT_DOWN_REQUEST', +} +AFMT_MEM_NO_FORCE_REQUEST = 0 +AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +AFMT_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +AFMT_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_RAMP_CONTROL0_SIGN' +AFMT_RAMP_CONTROL0_SIGN__enumvalues = { + 0: 'AFMT_RAMP_SIGNED', + 1: 'AFMT_RAMP_UNSIGNED', +} +AFMT_RAMP_SIGNED = 0 +AFMT_RAMP_UNSIGNED = 1 +AFMT_RAMP_CONTROL0_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_VBI_PACKET_CONTROL_ACP_SOURCE' +AFMT_VBI_PACKET_CONTROL_ACP_SOURCE__enumvalues = { + 0: 'AFMT_ACP_SOURCE_FROM_AZALIA', + 1: 'AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_ACP_SOURCE_FROM_AZALIA = 0 +AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_VBI_PACKET_CONTROL_ACP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AUDIO_LAYOUT_SELECT' +AUDIO_LAYOUT_SELECT__enumvalues = { + 0: 'AUDIO_LAYOUT_0', + 1: 'AUDIO_LAYOUT_1', +} +AUDIO_LAYOUT_0 = 0 +AUDIO_LAYOUT_1 = 1 +AUDIO_LAYOUT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HPO_TOP_CLOCK_GATING_DISABLE' +HPO_TOP_CLOCK_GATING_DISABLE__enumvalues = { + 0: 'HPO_TOP_CLOCK_GATING_EN', + 1: 'HPO_TOP_CLOCK_GATING_DIS', +} +HPO_TOP_CLOCK_GATING_EN = 0 +HPO_TOP_CLOCK_GATING_DIS = 1 +HPO_TOP_CLOCK_GATING_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HPO_TOP_TEST_CLK_SEL' +HPO_TOP_TEST_CLK_SEL__enumvalues = { + 0: 'HPO_TOP_PERMANENT_DISPCLK', + 1: 'HPO_TOP_REGISTER_GATED_DISPCLK', + 2: 'HPO_TOP_PERMANENT_SOCCLK', + 3: 'HPO_TOP_TEST_CLOCK_RESERVED', + 4: 'HPO_TOP_PERMANENT_HDMISTREAMCLK0', + 5: 'HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0', + 6: 'HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0', + 7: 'HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0', + 8: 'HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0', + 9: 'HPO_TOP_PERMANENT_HDMICHARCLK0', + 10: 'HPO_TOP_FEATURE_GATED_HDMICHARCLK0', + 11: 'HPO_TOP_REGISTER_GATED_HDMICHARCLK0', +} +HPO_TOP_PERMANENT_DISPCLK = 0 +HPO_TOP_REGISTER_GATED_DISPCLK = 1 +HPO_TOP_PERMANENT_SOCCLK = 2 +HPO_TOP_TEST_CLOCK_RESERVED = 3 +HPO_TOP_PERMANENT_HDMISTREAMCLK0 = 4 +HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0 = 5 +HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0 = 6 +HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0 = 7 +HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0 = 8 +HPO_TOP_PERMANENT_HDMICHARCLK0 = 9 +HPO_TOP_FEATURE_GATED_HDMICHARCLK0 = 10 +HPO_TOP_REGISTER_GATED_HDMICHARCLK0 = 11 +HPO_TOP_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET' +DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET__enumvalues = { + 0: 'DP_STREAM_MAPPER_LINK0', + 1: 'DP_STREAM_MAPPER_LINK1', + 2: 'DP_STREAM_MAPPER_RESERVED', +} +DP_STREAM_MAPPER_LINK0 = 0 +DP_STREAM_MAPPER_LINK1 = 1 +DP_STREAM_MAPPER_RESERVED = 2 +DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_DB_DISABLE_CONTROL' +HDMI_STREAM_ENC_DB_DISABLE_CONTROL__enumvalues = { + 0: 'HDMI_STREAM_ENC_DB_ENABLE', + 1: 'HDMI_STREAM_ENC_DB_DISABLE', +} +HDMI_STREAM_ENC_DB_ENABLE = 0 +HDMI_STREAM_ENC_DB_DISABLE = 1 +HDMI_STREAM_ENC_DB_DISABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_DSC_MODE' +HDMI_STREAM_ENC_DSC_MODE__enumvalues = { + 0: 'STREAM_DSC_DISABLE', + 1: 'STREAM_DSC_444_RGB', + 2: 'STREAM_DSC_NATIVE_422_420', +} +STREAM_DSC_DISABLE = 0 +STREAM_DSC_444_RGB = 1 +STREAM_DSC_NATIVE_422_420 = 2 +HDMI_STREAM_ENC_DSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_ENABLE_CONTROL' +HDMI_STREAM_ENC_ENABLE_CONTROL__enumvalues = { + 0: 'HDMI_STREAM_ENC_DISABLE', + 1: 'HDMI_STREAM_ENC_ENABLE', +} +HDMI_STREAM_ENC_DISABLE = 0 +HDMI_STREAM_ENC_ENABLE = 1 +HDMI_STREAM_ENC_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_ODM_COMBINE_MODE' +HDMI_STREAM_ENC_ODM_COMBINE_MODE__enumvalues = { + 0: 'STREAM_ODM_COMBINE_1_SEGMENT', + 1: 'STREAM_ODM_COMBINE_2_SEGMENT', + 2: 'STREAM_ODM_COMBINE_RESERVED', + 3: 'STREAM_ODM_COMBINE_4_SEGMENT', +} +STREAM_ODM_COMBINE_1_SEGMENT = 0 +STREAM_ODM_COMBINE_2_SEGMENT = 1 +STREAM_ODM_COMBINE_RESERVED = 2 +STREAM_ODM_COMBINE_4_SEGMENT = 3 +HDMI_STREAM_ENC_ODM_COMBINE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR' +HDMI_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR__enumvalues = { + 0: 'HDMI_STREAM_ENC_NO_ERROR_OCCURRED', + 1: 'HDMI_STREAM_ENC_UNDERFLOW_OCCURRED', + 2: 'HDMI_STREAM_ENC_OVERFLOW_OCCURRED', +} +HDMI_STREAM_ENC_NO_ERROR_OCCURRED = 0 +HDMI_STREAM_ENC_UNDERFLOW_OCCURRED = 1 +HDMI_STREAM_ENC_OVERFLOW_OCCURRED = 2 +HDMI_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_OVERWRITE_LEVEL_SELECT' +HDMI_STREAM_ENC_OVERWRITE_LEVEL_SELECT__enumvalues = { + 0: 'HDMI_STREAM_ENC_HARDWARE', + 1: 'HDMI_STREAM_ENC_PROGRAMMABLE', +} +HDMI_STREAM_ENC_HARDWARE = 0 +HDMI_STREAM_ENC_PROGRAMMABLE = 1 +HDMI_STREAM_ENC_OVERWRITE_LEVEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_PIXEL_ENCODING' +HDMI_STREAM_ENC_PIXEL_ENCODING__enumvalues = { + 0: 'STREAM_PIXEL_ENCODING_444_RGB', + 1: 'STREAM_PIXEL_ENCODING_422', + 2: 'STREAM_PIXEL_ENCODING_420', +} +STREAM_PIXEL_ENCODING_444_RGB = 0 +STREAM_PIXEL_ENCODING_422 = 1 +STREAM_PIXEL_ENCODING_420 = 2 +HDMI_STREAM_ENC_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_READ_CLOCK_CONTROL' +HDMI_STREAM_ENC_READ_CLOCK_CONTROL__enumvalues = { + 0: 'HDMI_STREAM_ENC_DCCG', + 1: 'HDMI_STREAM_ENC_DISPLAY_PIPE', +} +HDMI_STREAM_ENC_DCCG = 0 +HDMI_STREAM_ENC_DISPLAY_PIPE = 1 +HDMI_STREAM_ENC_READ_CLOCK_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_RESET_CONTROL' +HDMI_STREAM_ENC_RESET_CONTROL__enumvalues = { + 0: 'HDMI_STREAM_ENC_NOT_RESET', + 1: 'HDMI_STREAM_ENC_RESET', +} +HDMI_STREAM_ENC_NOT_RESET = 0 +HDMI_STREAM_ENC_RESET = 1 +HDMI_STREAM_ENC_RESET_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_STREAM_ENC_STREAM_ACTIVE' +HDMI_STREAM_ENC_STREAM_ACTIVE__enumvalues = { + 0: 'HDMI_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', + 1: 'HDMI_STREAM_ENC_VIDEO_STREAM_ACTIVE', +} +HDMI_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE = 0 +HDMI_STREAM_ENC_VIDEO_STREAM_ACTIVE = 1 +HDMI_STREAM_ENC_STREAM_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'BORROWBUFFER_MEM_POWER_STATE_ENUM' +BORROWBUFFER_MEM_POWER_STATE_ENUM__enumvalues = { + 0: 'BORROWBUFFER_MEM_POWER_STATE_ENUM_ON', + 1: 'BORROWBUFFER_MEM_POWER_STATE_ENUM_LS', + 2: 'BORROWBUFFER_MEM_POWER_STATE_ENUM_DS', + 3: 'BORROWBUFFER_MEM_POWER_STATE_ENUM_SD', +} +BORROWBUFFER_MEM_POWER_STATE_ENUM_ON = 0 +BORROWBUFFER_MEM_POWER_STATE_ENUM_LS = 1 +BORROWBUFFER_MEM_POWER_STATE_ENUM_DS = 2 +BORROWBUFFER_MEM_POWER_STATE_ENUM_SD = 3 +BORROWBUFFER_MEM_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_BORROW_MODE' +HDMI_BORROW_MODE__enumvalues = { + 0: 'TB_BORROW_MODE_NONE', + 1: 'TB_BORROW_MODE_ACTIVE', + 2: 'TB_BORROW_MODE_BLANK', + 3: 'TB_BORROW_MODE_RESERVED', +} +TB_BORROW_MODE_NONE = 0 +TB_BORROW_MODE_ACTIVE = 1 +TB_BORROW_MODE_BLANK = 2 +TB_BORROW_MODE_RESERVED = 3 +HDMI_BORROW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACP_SEND' +HDMI_TB_ENC_ACP_SEND__enumvalues = { + 0: 'TB_ACP_NOT_SEND', + 1: 'TB_ACP_PKT_SEND', +} +TB_ACP_NOT_SEND = 0 +TB_ACP_PKT_SEND = 1 +HDMI_TB_ENC_ACP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_AUDIO_PRIORITY' +HDMI_TB_ENC_ACR_AUDIO_PRIORITY__enumvalues = { + 0: 'TB_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 1: 'TB_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', +} +TB_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE = 0 +TB_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT = 1 +HDMI_TB_ENC_ACR_AUDIO_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_CONT' +HDMI_TB_ENC_ACR_CONT__enumvalues = { + 0: 'TB_ACR_CONT_DISABLE', + 1: 'TB_ACR_CONT_ENABLE', +} +TB_ACR_CONT_DISABLE = 0 +TB_ACR_CONT_ENABLE = 1 +HDMI_TB_ENC_ACR_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_N_MULTIPLE' +HDMI_TB_ENC_ACR_N_MULTIPLE__enumvalues = { + 0: 'TB_ACR_0_MULTIPLE_RESERVED', + 1: 'TB_ACR_1_MULTIPLE', + 2: 'TB_ACR_2_MULTIPLE', + 3: 'TB_ACR_3_MULTIPLE_RESERVED', + 4: 'TB_ACR_4_MULTIPLE', + 5: 'TB_ACR_5_MULTIPLE_RESERVED', + 6: 'TB_ACR_6_MULTIPLE_RESERVED', + 7: 'TB_ACR_7_MULTIPLE_RESERVED', +} +TB_ACR_0_MULTIPLE_RESERVED = 0 +TB_ACR_1_MULTIPLE = 1 +TB_ACR_2_MULTIPLE = 2 +TB_ACR_3_MULTIPLE_RESERVED = 3 +TB_ACR_4_MULTIPLE = 4 +TB_ACR_5_MULTIPLE_RESERVED = 5 +TB_ACR_6_MULTIPLE_RESERVED = 6 +TB_ACR_7_MULTIPLE_RESERVED = 7 +HDMI_TB_ENC_ACR_N_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_SELECT' +HDMI_TB_ENC_ACR_SELECT__enumvalues = { + 0: 'TB_ACR_SELECT_HW', + 1: 'TB_ACR_SELECT_32K', + 2: 'TB_ACR_SELECT_44K', + 3: 'TB_ACR_SELECT_48K', +} +TB_ACR_SELECT_HW = 0 +TB_ACR_SELECT_32K = 1 +TB_ACR_SELECT_44K = 2 +TB_ACR_SELECT_48K = 3 +HDMI_TB_ENC_ACR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_SEND' +HDMI_TB_ENC_ACR_SEND__enumvalues = { + 0: 'TB_ACR_NOT_SEND', + 1: 'TB_ACR_PKT_SEND', +} +TB_ACR_NOT_SEND = 0 +TB_ACR_PKT_SEND = 1 +HDMI_TB_ENC_ACR_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ACR_SOURCE' +HDMI_TB_ENC_ACR_SOURCE__enumvalues = { + 0: 'TB_ACR_SOURCE_HW', + 1: 'TB_ACR_SOURCE_SW', +} +TB_ACR_SOURCE_HW = 0 +TB_ACR_SOURCE_SW = 1 +HDMI_TB_ENC_ACR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_AUDIO_INFO_CONT' +HDMI_TB_ENC_AUDIO_INFO_CONT__enumvalues = { + 0: 'TB_AUDIO_INFO_CONT_DISABLE', + 1: 'TB_AUDIO_INFO_CONT_ENABLE', +} +TB_AUDIO_INFO_CONT_DISABLE = 0 +TB_AUDIO_INFO_CONT_ENABLE = 1 +HDMI_TB_ENC_AUDIO_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_AUDIO_INFO_SEND' +HDMI_TB_ENC_AUDIO_INFO_SEND__enumvalues = { + 0: 'TB_AUDIO_INFO_NOT_SEND', + 1: 'TB_AUDIO_INFO_PKT_SEND', +} +TB_AUDIO_INFO_NOT_SEND = 0 +TB_AUDIO_INFO_PKT_SEND = 1 +HDMI_TB_ENC_AUDIO_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_CRC_SRC_SEL' +HDMI_TB_ENC_CRC_SRC_SEL__enumvalues = { + 0: 'TB_CRC_TB_ENC_INPUT', + 1: 'TB_CRC_DSC_PACKER', + 2: 'TB_CRC_DEEP_COLOR_PACKER', + 3: 'TB_CRC_ENCRYPTOR_INPUT', +} +TB_CRC_TB_ENC_INPUT = 0 +TB_CRC_DSC_PACKER = 1 +TB_CRC_DEEP_COLOR_PACKER = 2 +TB_CRC_ENCRYPTOR_INPUT = 3 +HDMI_TB_ENC_CRC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_CRC_TYPE' +HDMI_TB_ENC_CRC_TYPE__enumvalues = { + 0: 'TB_CRC_ALL_TRIBYTES', + 1: 'TB_CRC_ACTIVE_TRIBYTES', + 2: 'TB_CRC_DATAISLAND_TRIBYTES', + 3: 'TB_CRC_ACTIVE_AND_DATAISLAND_TRIBYTES', +} +TB_CRC_ALL_TRIBYTES = 0 +TB_CRC_ACTIVE_TRIBYTES = 1 +TB_CRC_DATAISLAND_TRIBYTES = 2 +TB_CRC_ACTIVE_AND_DATAISLAND_TRIBYTES = 3 +HDMI_TB_ENC_CRC_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_DEEP_COLOR_DEPTH' +HDMI_TB_ENC_DEEP_COLOR_DEPTH__enumvalues = { + 0: 'TB_DEEP_COLOR_DEPTH_24BPP', + 1: 'TB_DEEP_COLOR_DEPTH_30BPP', + 2: 'TB_DEEP_COLOR_DEPTH_36BPP', + 3: 'TB_DEEP_COLOR_DEPTH_RESERVED', +} +TB_DEEP_COLOR_DEPTH_24BPP = 0 +TB_DEEP_COLOR_DEPTH_30BPP = 1 +TB_DEEP_COLOR_DEPTH_36BPP = 2 +TB_DEEP_COLOR_DEPTH_RESERVED = 3 +HDMI_TB_ENC_DEEP_COLOR_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_DEFAULT_PAHSE' +HDMI_TB_ENC_DEFAULT_PAHSE__enumvalues = { + 0: 'TB_DEFAULT_PHASE_IS_0', + 1: 'TB_DEFAULT_PHASE_IS_1', +} +TB_DEFAULT_PHASE_IS_0 = 0 +TB_DEFAULT_PHASE_IS_1 = 1 +HDMI_TB_ENC_DEFAULT_PAHSE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_DSC_MODE' +HDMI_TB_ENC_DSC_MODE__enumvalues = { + 0: 'TB_DSC_DISABLE', + 1: 'TB_DSC_444_RGB', + 2: 'TB_DSC_NATIVE_422_420', +} +TB_DSC_DISABLE = 0 +TB_DSC_444_RGB = 1 +TB_DSC_NATIVE_422_420 = 2 +HDMI_TB_ENC_DSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ENABLE' +HDMI_TB_ENC_ENABLE__enumvalues = { + 0: 'TB_DISABLE', + 1: 'TB_ENABLE', +} +TB_DISABLE = 0 +TB_ENABLE = 1 +HDMI_TB_ENC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GC_AVMUTE' +HDMI_TB_ENC_GC_AVMUTE__enumvalues = { + 0: 'TB_GC_AVMUTE_SET', + 1: 'TB_GC_AVMUTE_UNSET', +} +TB_GC_AVMUTE_SET = 0 +TB_GC_AVMUTE_UNSET = 1 +HDMI_TB_ENC_GC_AVMUTE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GC_AVMUTE_CONT' +HDMI_TB_ENC_GC_AVMUTE_CONT__enumvalues = { + 0: 'TB_GC_AVMUTE_CONT_DISABLE', + 1: 'TB_GC_AVMUTE_CONT_ENABLE', +} +TB_GC_AVMUTE_CONT_DISABLE = 0 +TB_GC_AVMUTE_CONT_ENABLE = 1 +HDMI_TB_ENC_GC_AVMUTE_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GC_CONT' +HDMI_TB_ENC_GC_CONT__enumvalues = { + 0: 'TB_GC_CONT_DISABLE', + 1: 'TB_GC_CONT_ENABLE', +} +TB_GC_CONT_DISABLE = 0 +TB_GC_CONT_ENABLE = 1 +HDMI_TB_ENC_GC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GC_SEND' +HDMI_TB_ENC_GC_SEND__enumvalues = { + 0: 'TB_GC_NOT_SEND', + 1: 'TB_GC_PKT_SEND', +} +TB_GC_NOT_SEND = 0 +TB_GC_PKT_SEND = 1 +HDMI_TB_ENC_GC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GENERIC_CONT' +HDMI_TB_ENC_GENERIC_CONT__enumvalues = { + 0: 'TB_GENERIC_CONT_DISABLE', + 1: 'TB_GENERIC_CONT_ENABLE', +} +TB_GENERIC_CONT_DISABLE = 0 +TB_GENERIC_CONT_ENABLE = 1 +HDMI_TB_ENC_GENERIC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GENERIC_LOCK_EN' +HDMI_TB_ENC_GENERIC_LOCK_EN__enumvalues = { + 0: 'HDMI_TB_ENC_GENERIC_LOCK_DISABLE', + 1: 'HDMI_TB_ENC_GENERIC_LOCK_ENABLE', +} +HDMI_TB_ENC_GENERIC_LOCK_DISABLE = 0 +HDMI_TB_ENC_GENERIC_LOCK_ENABLE = 1 +HDMI_TB_ENC_GENERIC_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_GENERIC_SEND' +HDMI_TB_ENC_GENERIC_SEND__enumvalues = { + 0: 'TB_GENERIC_NOT_SEND', + 1: 'TB_GENERIC_PKT_SEND', +} +TB_GENERIC_NOT_SEND = 0 +TB_GENERIC_PKT_SEND = 1 +HDMI_TB_ENC_GENERIC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ISRC_CONT' +HDMI_TB_ENC_ISRC_CONT__enumvalues = { + 0: 'TB_ISRC_CONT_DISABLE', + 1: 'TB_ISRC_CONT_ENABLE', +} +TB_ISRC_CONT_DISABLE = 0 +TB_ISRC_CONT_ENABLE = 1 +HDMI_TB_ENC_ISRC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_ISRC_SEND' +HDMI_TB_ENC_ISRC_SEND__enumvalues = { + 0: 'TB_ISRC_NOT_SEND', + 1: 'TB_ISRC_PKT_SEND', +} +TB_ISRC_NOT_SEND = 0 +TB_ISRC_PKT_SEND = 1 +HDMI_TB_ENC_ISRC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_METADATA_ENABLE' +HDMI_TB_ENC_METADATA_ENABLE__enumvalues = { + 0: 'TB_METADATA_NOT_SEND', + 1: 'TB_METADATA_PKT_SEND', +} +TB_METADATA_NOT_SEND = 0 +TB_METADATA_PKT_SEND = 1 +HDMI_TB_ENC_METADATA_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_PACKET_LINE_REFERENCE' +HDMI_TB_ENC_PACKET_LINE_REFERENCE__enumvalues = { + 0: 'TB_PKT_LINE_REF_END_OF_ACTIVE', + 1: 'TB_PKT_LINE_REF_OTGSOF', +} +TB_PKT_LINE_REF_END_OF_ACTIVE = 0 +TB_PKT_LINE_REF_OTGSOF = 1 +HDMI_TB_ENC_PACKET_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_PIXEL_ENCODING' +HDMI_TB_ENC_PIXEL_ENCODING__enumvalues = { + 0: 'TB_PIXEL_ENCODING_444_RGB', + 1: 'TB_PIXEL_ENCODING_422', + 2: 'TB_PIXEL_ENCODING_420', +} +TB_PIXEL_ENCODING_444_RGB = 0 +TB_PIXEL_ENCODING_422 = 1 +TB_PIXEL_ENCODING_420 = 2 +HDMI_TB_ENC_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_RESET' +HDMI_TB_ENC_RESET__enumvalues = { + 0: 'TB_NOT_RESET', + 1: 'TB_RESET', +} +TB_NOT_RESET = 0 +TB_RESET = 1 +HDMI_TB_ENC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_TB_ENC_SYNC_PHASE' +HDMI_TB_ENC_SYNC_PHASE__enumvalues = { + 0: 'TB_NOT_SYNC_PHASE_ON_FRAME_START', + 1: 'TB_SYNC_PHASE_ON_FRAME_START', +} +TB_NOT_SYNC_PHASE_ON_FRAME_START = 0 +TB_SYNC_PHASE_ON_FRAME_START = 1 +HDMI_TB_ENC_SYNC_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'INPUT_FIFO_ERROR_TYPE' +INPUT_FIFO_ERROR_TYPE__enumvalues = { + 0: 'TB_NO_ERROR_OCCURRED', + 1: 'TB_OVERFLOW_OCCURRED', +} +TB_NO_ERROR_OCCURRED = 0 +TB_OVERFLOW_OCCURRED = 1 +INPUT_FIFO_ERROR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR' +DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR__enumvalues = { + 0: 'DP_STREAM_ENC_NO_ERROR_OCCURRED', + 1: 'DP_STREAM_ENC_UNDERFLOW_OCCURRED', + 2: 'DP_STREAM_ENC_OVERFLOW_OCCURRED', +} +DP_STREAM_ENC_NO_ERROR_OCCURRED = 0 +DP_STREAM_ENC_UNDERFLOW_OCCURRED = 1 +DP_STREAM_ENC_OVERFLOW_OCCURRED = 2 +DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT' +DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT__enumvalues = { + 0: 'DP_STREAM_ENC_HARDWARE', + 1: 'DP_STREAM_ENC_PROGRAMMABLE', +} +DP_STREAM_ENC_HARDWARE = 0 +DP_STREAM_ENC_PROGRAMMABLE = 1 +DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_READ_CLOCK_CONTROL' +DP_STREAM_ENC_READ_CLOCK_CONTROL__enumvalues = { + 0: 'DP_STREAM_ENC_DCCG', + 1: 'DP_STREAM_ENC_DISPLAY_PIPE', +} +DP_STREAM_ENC_DCCG = 0 +DP_STREAM_ENC_DISPLAY_PIPE = 1 +DP_STREAM_ENC_READ_CLOCK_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_RESET_CONTROL' +DP_STREAM_ENC_RESET_CONTROL__enumvalues = { + 0: 'DP_STREAM_ENC_NOT_RESET', + 1: 'DP_STREAM_ENC_RESET', +} +DP_STREAM_ENC_NOT_RESET = 0 +DP_STREAM_ENC_RESET = 1 +DP_STREAM_ENC_RESET_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_STREAM_ACTIVE' +DP_STREAM_ENC_STREAM_ACTIVE__enumvalues = { + 0: 'DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', + 1: 'DP_STREAM_ENC_VIDEO_STREAM_ACTIVE', +} +DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE = 0 +DP_STREAM_ENC_VIDEO_STREAM_ACTIVE = 1 +DP_STREAM_ENC_STREAM_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_AUDIO_MUTE' +ENUM_DP_SYM32_ENC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED', + 1: 'DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED', +} +DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED = 0 +DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED = 1 +ENUM_DP_SYM32_ENC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_CONTINUOUS_MODE' +ENUM_DP_SYM32_ENC_CONTINUOUS_MODE__enumvalues = { + 0: 'DP_SYM32_ENC_ONE_SHOT_MODE', + 1: 'DP_SYM32_ENC_CONTINUOUS_MODE', +} +DP_SYM32_ENC_ONE_SHOT_MODE = 0 +DP_SYM32_ENC_CONTINUOUS_MODE = 1 +ENUM_DP_SYM32_ENC_CONTINUOUS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_CRC_VALID' +ENUM_DP_SYM32_ENC_CRC_VALID__enumvalues = { + 0: 'DP_SYM32_ENC_CRC_NOT_VALID', + 1: 'DP_SYM32_ENC_CRC_VALID', +} +DP_SYM32_ENC_CRC_NOT_VALID = 0 +DP_SYM32_ENC_CRC_VALID = 1 +ENUM_DP_SYM32_ENC_CRC_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH' +ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_SYM32_ENC_COMPONENT_DEPTH_6BPC', + 1: 'DP_SYM32_ENC_COMPONENT_DEPTH_8BPC', + 2: 'DP_SYM32_ENC_COMPONENT_DEPTH_10BPC', + 3: 'DP_SYM32_ENC_COMPONENT_DEPTH_12BPC', +} +DP_SYM32_ENC_COMPONENT_DEPTH_6BPC = 0 +DP_SYM32_ENC_COMPONENT_DEPTH_8BPC = 1 +DP_SYM32_ENC_COMPONENT_DEPTH_10BPC = 2 +DP_SYM32_ENC_COMPONENT_DEPTH_12BPC = 3 +ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_ENABLE' +ENUM_DP_SYM32_ENC_ENABLE__enumvalues = { + 0: 'DP_SYM32_ENC_DISABLE', + 1: 'DP_SYM32_ENC_ENABLE', +} +DP_SYM32_ENC_DISABLE = 0 +DP_SYM32_ENC_ENABLE = 1 +ENUM_DP_SYM32_ENC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED' +ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED', + 1: 'DP_SYM32_ENC_GSP_DEADLINE_MISSED', +} +DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED = 0 +DP_SYM32_ENC_GSP_DEADLINE_MISSED = 1 +ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION' +ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER', + 1: 'DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME', +} +DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER = 0 +DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME = 1 +ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE' +ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32', + 1: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0', + 2: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1', + 3: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128', +} +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32 = 0 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0 = 1 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1 = 2 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128 = 3 +ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING' +ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING', + 1: 'DP_SYM32_ENC_GSP_TRIGGER_PENDING', +} +DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING = 0 +DP_SYM32_ENC_GSP_TRIGGER_PENDING = 1 +ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM' +ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST', + 1: 'DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST', +} +DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST = 0 +DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST = 1 +DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST = 2 +DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST = 3 +ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_OVERFLOW_STATUS' +ENUM_DP_SYM32_ENC_OVERFLOW_STATUS__enumvalues = { + 0: 'DP_SYM32_ENC_NO_OVERFLOW_OCCURRED', + 1: 'DP_SYM32_ENC_OVERFLOW_OCCURRED', +} +DP_SYM32_ENC_NO_OVERFLOW_OCCURRED = 0 +DP_SYM32_ENC_OVERFLOW_OCCURRED = 1 +ENUM_DP_SYM32_ENC_OVERFLOW_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PENDING' +ENUM_DP_SYM32_ENC_PENDING__enumvalues = { + 0: 'DP_SYM32_ENC_NOT_PENDING', + 1: 'DP_SYM32_ENC_PENDING', +} +DP_SYM32_ENC_NOT_PENDING = 0 +DP_SYM32_ENC_PENDING = 1 +ENUM_DP_SYM32_ENC_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING' +ENUM_DP_SYM32_ENC_PIXEL_ENCODING__enumvalues = { + 0: 'DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444', + 1: 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422', + 2: 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420', + 3: 'DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY', +} +DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444 = 0 +DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422 = 1 +DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420 = 2 +DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY = 3 +ENUM_DP_SYM32_ENC_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE' +ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE__enumvalues = { + 0: 'DP_SYM32_ENC_UNCOMPRESSED_FORMAT', + 1: 'DP_SYM32_ENC_COMPRESSED_FORMAT', +} +DP_SYM32_ENC_UNCOMPRESSED_FORMAT = 0 +DP_SYM32_ENC_COMPRESSED_FORMAT = 1 +ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_POWER_STATE_ENUM' +ENUM_DP_SYM32_ENC_POWER_STATE_ENUM__enumvalues = { + 0: 'DP_SYM32_ENC_POWER_STATE_ENUM_ON', + 1: 'DP_SYM32_ENC_POWER_STATE_ENUM_LS', + 2: 'DP_SYM32_ENC_POWER_STATE_ENUM_DS', + 3: 'DP_SYM32_ENC_POWER_STATE_ENUM_SD', +} +DP_SYM32_ENC_POWER_STATE_ENUM_ON = 0 +DP_SYM32_ENC_POWER_STATE_ENUM_LS = 1 +DP_SYM32_ENC_POWER_STATE_ENUM_DS = 2 +DP_SYM32_ENC_POWER_STATE_ENUM_SD = 3 +ENUM_DP_SYM32_ENC_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_RESET' +ENUM_DP_SYM32_ENC_RESET__enumvalues = { + 0: 'DP_SYM32_ENC_NOT_RESET', + 1: 'DP_SYM32_ENC_RESET', +} +DP_SYM32_ENC_NOT_RESET = 0 +DP_SYM32_ENC_RESET = 1 +ENUM_DP_SYM32_ENC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_SDP_PRIORITY' +ENUM_DP_SYM32_ENC_SDP_PRIORITY__enumvalues = { + 0: 'DP_SYM32_ENC_SDP_LOW_PRIORITY', + 1: 'DP_SYM32_ENC_SDP_HIGH_PRIORITY', +} +DP_SYM32_ENC_SDP_LOW_PRIORITY = 0 +DP_SYM32_ENC_SDP_HIGH_PRIORITY = 1 +ENUM_DP_SYM32_ENC_SDP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_SOF_REFERENCE' +ENUM_DP_SYM32_ENC_SOF_REFERENCE__enumvalues = { + 0: 'DP_SYM32_ENC_DP_SOF', + 1: 'DP_SYM32_ENC_OTG_SOF', +} +DP_SYM32_ENC_DP_SOF = 0 +DP_SYM32_ENC_OTG_SOF = 1 +ENUM_DP_SYM32_ENC_SOF_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_VID_STREAM_DEFER' +ENUM_DP_SYM32_ENC_VID_STREAM_DEFER__enumvalues = { + 0: 'DP_SYM32_ENC_VID_STREAM_NO_DEFER', + 1: 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK', + 2: 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK', +} +DP_SYM32_ENC_VID_STREAM_NO_DEFER = 0 +DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK = 1 +DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK = 2 +ENUM_DP_SYM32_ENC_VID_STREAM_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_END_EVENT' +ENUM_DP_DPHY_SYM32_CRC_END_EVENT__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_END_LLCP', + 1: 'DP_DPHY_SYM32_CRC_END_PS_ONLY', + 2: 'DP_DPHY_SYM32_CRC_END_PS_LT_SR', + 3: 'DP_DPHY_SYM32_CRC_END_PS_ANY', +} +DP_DPHY_SYM32_CRC_END_LLCP = 0 +DP_DPHY_SYM32_CRC_END_PS_ONLY = 1 +DP_DPHY_SYM32_CRC_END_PS_LT_SR = 2 +DP_DPHY_SYM32_CRC_END_PS_ANY = 3 +ENUM_DP_DPHY_SYM32_CRC_END_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_START_EVENT' +ENUM_DP_DPHY_SYM32_CRC_START_EVENT__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_START_LLCP', + 1: 'DP_DPHY_SYM32_CRC_START_PS_ONLY', + 2: 'DP_DPHY_SYM32_CRC_START_PS_LT_SR', + 3: 'DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR', + 4: 'DP_DPHY_SYM32_CRC_START_TP_START', +} +DP_DPHY_SYM32_CRC_START_LLCP = 0 +DP_DPHY_SYM32_CRC_START_PS_ONLY = 1 +DP_DPHY_SYM32_CRC_START_PS_LT_SR = 2 +DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR = 3 +DP_DPHY_SYM32_CRC_START_TP_START = 4 +ENUM_DP_DPHY_SYM32_CRC_START_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE' +ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER', + 1: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER', + 2: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX', +} +DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER = 0 +DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER = 1 +DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX = 2 +ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS' +ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_USE_END_EVENT', + 1: 'DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', +} +DP_DPHY_SYM32_CRC_USE_END_EVENT = 0 +DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS = 1 +ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_ENABLE' +ENUM_DP_DPHY_SYM32_ENABLE__enumvalues = { + 0: 'DP_DPHY_SYM32_DISABLE', + 1: 'DP_DPHY_SYM32_ENABLE', +} +DP_DPHY_SYM32_DISABLE = 0 +DP_DPHY_SYM32_ENABLE = 1 +ENUM_DP_DPHY_SYM32_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_ENCRYPT_TYPE' +ENUM_DP_DPHY_SYM32_ENCRYPT_TYPE__enumvalues = { + 0: 'DP_DPHY_SYM32_ENCRYPT_TYPE0', + 1: 'DP_DPHY_SYM32_ENCRYPT_TYPE1', +} +DP_DPHY_SYM32_ENCRYPT_TYPE0 = 0 +DP_DPHY_SYM32_ENCRYPT_TYPE1 = 1 +ENUM_DP_DPHY_SYM32_ENCRYPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_MODE' +ENUM_DP_DPHY_SYM32_MODE__enumvalues = { + 0: 'DP_DPHY_SYM32_LT_TPS1', + 1: 'DP_DPHY_SYM32_LT_TPS2', + 2: 'DP_DPHY_SYM32_ACTIVE', + 3: 'DP_DPHY_SYM32_TEST', +} +DP_DPHY_SYM32_LT_TPS1 = 0 +DP_DPHY_SYM32_LT_TPS2 = 1 +DP_DPHY_SYM32_ACTIVE = 2 +DP_DPHY_SYM32_TEST = 3 +ENUM_DP_DPHY_SYM32_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_NUM_LANES' +ENUM_DP_DPHY_SYM32_NUM_LANES__enumvalues = { + 0: 'DP_DPHY_SYM32_1LANE', + 1: 'DP_DPHY_SYM32_2LANE', + 2: 'DP_DPHY_SYM32_RESERVED', + 3: 'DP_DPHY_SYM32_4LANE', +} +DP_DPHY_SYM32_1LANE = 0 +DP_DPHY_SYM32_2LANE = 1 +DP_DPHY_SYM32_RESERVED = 2 +DP_DPHY_SYM32_4LANE = 3 +ENUM_DP_DPHY_SYM32_NUM_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING' +ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING__enumvalues = { + 0: 'DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING', + 1: 'DP_DPHY_SYM32_RATE_UPDATE_PENDING', +} +DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING = 0 +DP_DPHY_SYM32_RATE_UPDATE_PENDING = 1 +ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RESET' +ENUM_DP_DPHY_SYM32_RESET__enumvalues = { + 0: 'DP_DPHY_SYM32_NOT_RESET', + 1: 'DP_DPHY_SYM32_RESET', +} +DP_DPHY_SYM32_NOT_RESET = 0 +DP_DPHY_SYM32_RESET = 1 +ENUM_DP_DPHY_SYM32_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RESET_STATUS' +ENUM_DP_DPHY_SYM32_RESET_STATUS__enumvalues = { + 0: 'DP_DPHY_SYM32_RESET_STATUS_DEASSERTED', + 1: 'DP_DPHY_SYM32_RESET_STATUS_ASSERTED', +} +DP_DPHY_SYM32_RESET_STATUS_DEASSERTED = 0 +DP_DPHY_SYM32_RESET_STATUS_ASSERTED = 1 +ENUM_DP_DPHY_SYM32_RESET_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_SAT_UPDATE' +ENUM_DP_DPHY_SYM32_SAT_UPDATE__enumvalues = { + 0: 'DP_DPHY_SYM32_SAT_NO_UPDATE', + 1: 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE', + 2: 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE', +} +DP_DPHY_SYM32_SAT_NO_UPDATE = 0 +DP_DPHY_SYM32_SAT_TRIGGER_UPDATE = 1 +DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE = 2 +ENUM_DP_DPHY_SYM32_SAT_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING' +ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING__enumvalues = { + 0: 'DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING', + 1: 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING', + 2: 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING', +} +DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING = 0 +DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING = 1 +DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING = 2 +ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STATUS' +ENUM_DP_DPHY_SYM32_STATUS__enumvalues = { + 0: 'DP_DPHY_SYM32_STATUS_IDLE', + 1: 'DP_DPHY_SYM32_STATUS_ENABLED', +} +DP_DPHY_SYM32_STATUS_IDLE = 0 +DP_DPHY_SYM32_STATUS_ENABLED = 1 +ENUM_DP_DPHY_SYM32_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE' +ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE__enumvalues = { + 0: 'DP_DPHY_SYM32_STREAM_OVR_NONE', + 1: 'DP_DPHY_SYM32_STREAM_OVR_REPLACE', + 2: 'DP_DPHY_SYM32_STREAM_OVR_ALWAYS', +} +DP_DPHY_SYM32_STREAM_OVR_NONE = 0 +DP_DPHY_SYM32_STREAM_OVR_REPLACE = 1 +DP_DPHY_SYM32_STREAM_OVR_ALWAYS = 2 +ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE' +ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE__enumvalues = { + 0: 'DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA', + 1: 'DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL', +} +DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA = 0 +DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL = 1 +ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_TP_PRBS_SEL' +ENUM_DP_DPHY_SYM32_TP_PRBS_SEL__enumvalues = { + 0: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7', + 1: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9', + 2: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11', + 3: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15', + 4: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23', + 5: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31', +} +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7 = 0 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9 = 1 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11 = 2 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15 = 3 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23 = 4 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31 = 5 +ENUM_DP_DPHY_SYM32_TP_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_TP_SELECT' +ENUM_DP_DPHY_SYM32_TP_SELECT__enumvalues = { + 0: 'DP_DPHY_SYM32_TP_SELECT_TPS1', + 1: 'DP_DPHY_SYM32_TP_SELECT_TPS2', + 2: 'DP_DPHY_SYM32_TP_SELECT_PRBS', + 3: 'DP_DPHY_SYM32_TP_SELECT_CUSTOM', + 4: 'DP_DPHY_SYM32_TP_SELECT_SQUARE', +} +DP_DPHY_SYM32_TP_SELECT_TPS1 = 0 +DP_DPHY_SYM32_TP_SELECT_TPS2 = 1 +DP_DPHY_SYM32_TP_SELECT_PRBS = 2 +DP_DPHY_SYM32_TP_SELECT_CUSTOM = 3 +DP_DPHY_SYM32_TP_SELECT_SQUARE = 4 +ENUM_DP_DPHY_SYM32_TP_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'APG_AUDIO_CRC_CONTROL_CH_SEL' +APG_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'APG_AUDIO_CRC_CH0_SIG', + 1: 'APG_AUDIO_CRC_CH1_SIG', + 2: 'APG_AUDIO_CRC_CH2_SIG', + 3: 'APG_AUDIO_CRC_CH3_SIG', + 4: 'APG_AUDIO_CRC_CH4_SIG', + 5: 'APG_AUDIO_CRC_CH5_SIG', + 6: 'APG_AUDIO_CRC_CH6_SIG', + 7: 'APG_AUDIO_CRC_CH7_SIG', + 8: 'APG_AUDIO_CRC_RESERVED_8', + 9: 'APG_AUDIO_CRC_RESERVED_9', + 10: 'APG_AUDIO_CRC_RESERVED_10', + 11: 'APG_AUDIO_CRC_RESERVED_11', + 12: 'APG_AUDIO_CRC_RESERVED_12', + 13: 'APG_AUDIO_CRC_RESERVED_13', + 14: 'APG_AUDIO_CRC_RESERVED_14', + 15: 'APG_AUDIO_CRC_RESERVED_15', +} +APG_AUDIO_CRC_CH0_SIG = 0 +APG_AUDIO_CRC_CH1_SIG = 1 +APG_AUDIO_CRC_CH2_SIG = 2 +APG_AUDIO_CRC_CH3_SIG = 3 +APG_AUDIO_CRC_CH4_SIG = 4 +APG_AUDIO_CRC_CH5_SIG = 5 +APG_AUDIO_CRC_CH6_SIG = 6 +APG_AUDIO_CRC_CH7_SIG = 7 +APG_AUDIO_CRC_RESERVED_8 = 8 +APG_AUDIO_CRC_RESERVED_9 = 9 +APG_AUDIO_CRC_RESERVED_10 = 10 +APG_AUDIO_CRC_RESERVED_11 = 11 +APG_AUDIO_CRC_RESERVED_12 = 12 +APG_AUDIO_CRC_RESERVED_13 = 13 +APG_AUDIO_CRC_RESERVED_14 = 14 +APG_AUDIO_CRC_RESERVED_15 = 15 +APG_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_AUDIO_CRC_CONTROL_CONT' +APG_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'APG_AUDIO_CRC_ONESHOT', + 1: 'APG_AUDIO_CRC_CONTINUOUS', +} +APG_AUDIO_CRC_ONESHOT = 0 +APG_AUDIO_CRC_CONTINUOUS = 1 +APG_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_ACP_TYPE' +APG_DBG_ACP_TYPE__enumvalues = { + 0: 'APG_ACP_TYPE_GENERIC_AUDIO', + 1: 'APG_ACP_TYPE_ICE60958_AUDIO', + 2: 'APG_ACP_TYPE_DVD_AUDIO', + 3: 'APG_ACP_TYPE_SUPER_AUDIO_CD', +} +APG_ACP_TYPE_GENERIC_AUDIO = 0 +APG_ACP_TYPE_ICE60958_AUDIO = 1 +APG_ACP_TYPE_DVD_AUDIO = 2 +APG_ACP_TYPE_SUPER_AUDIO_CD = 3 +APG_DBG_ACP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_BASE' +APG_DBG_AUDIO_DTO_BASE__enumvalues = { + 0: 'BASE_RATE_48KHZ', + 1: 'BASE_RATE_44P1KHZ', +} +BASE_RATE_48KHZ = 0 +BASE_RATE_44P1KHZ = 1 +APG_DBG_AUDIO_DTO_BASE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_DIV' +APG_DBG_AUDIO_DTO_DIV__enumvalues = { + 0: 'DIVISOR_BY1', + 1: 'DIVISOR_BY2_RESERVED', + 2: 'DIVISOR_BY3', + 3: 'DIVISOR_BY4_RESERVED', + 4: 'DIVISOR_BY5_RESERVED', + 5: 'DIVISOR_BY6_RESERVED', + 6: 'DIVISOR_BY7_RESERVED', + 7: 'DIVISOR_BY8_RESERVED', +} +DIVISOR_BY1 = 0 +DIVISOR_BY2_RESERVED = 1 +DIVISOR_BY3 = 2 +DIVISOR_BY4_RESERVED = 3 +DIVISOR_BY5_RESERVED = 4 +DIVISOR_BY6_RESERVED = 5 +DIVISOR_BY7_RESERVED = 6 +DIVISOR_BY8_RESERVED = 7 +APG_DBG_AUDIO_DTO_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_MULTI' +APG_DBG_AUDIO_DTO_MULTI__enumvalues = { + 0: 'MULTIPLE_BY1', + 1: 'MULTIPLE_BY2', + 2: 'MULTIPLE_BY3_RESERVED', + 3: 'MULTIPLE_BY4', + 4: 'MULTIPLE_RESERVED', +} +MULTIPLE_BY1 = 0 +MULTIPLE_BY2 = 1 +MULTIPLE_BY3_RESERVED = 2 +MULTIPLE_BY4 = 3 +MULTIPLE_RESERVED = 4 +APG_DBG_AUDIO_DTO_MULTI = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_MUX_SEL' +APG_DBG_MUX_SEL__enumvalues = { + 0: 'APG_FUNCTIONAL_MODE', + 1: 'APG_DEBUG_AUDIO_MODE', +} +APG_FUNCTIONAL_MODE = 0 +APG_DEBUG_AUDIO_MODE = 1 +APG_DBG_MUX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE' +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'APG_DP_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +APG_DP_ASP_CHANNEL_COUNT_FROM_AZ = 0 +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_POWER_STATE' +APG_MEM_POWER_STATE__enumvalues = { + 0: 'APG_MEM_POWER_STATE_ON', + 1: 'APG_MEM_POWER_STATE_LS', + 2: 'APG_MEM_POWER_STATE_DS', + 3: 'APG_MEM_POWER_STATE_SD', +} +APG_MEM_POWER_STATE_ON = 0 +APG_MEM_POWER_STATE_LS = 1 +APG_MEM_POWER_STATE_DS = 2 +APG_MEM_POWER_STATE_SD = 3 +APG_MEM_POWER_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_PWR_DIS_CTRL' +APG_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'APG_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'APG_MEM_DISABLE_MEM_PWR_CTRL', +} +APG_MEM_ENABLE_MEM_PWR_CTRL = 0 +APG_MEM_DISABLE_MEM_PWR_CTRL = 1 +APG_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_PWR_FORCE_CTRL' +APG_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'APG_MEM_NO_FORCE_REQUEST', + 1: 'APG_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'APG_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'APG_MEM_FORCE_SHUT_DOWN_REQUEST', +} +APG_MEM_NO_FORCE_REQUEST = 0 +APG_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +APG_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +APG_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +APG_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_PACKET_CONTROL_ACP_SOURCE' +APG_PACKET_CONTROL_ACP_SOURCE__enumvalues = { + 0: 'APG_ACP_SOURCE_NO_OVERRIDE', + 1: 'APG_ACP_OVERRIDE', +} +APG_ACP_SOURCE_NO_OVERRIDE = 0 +APG_ACP_OVERRIDE = 1 +APG_PACKET_CONTROL_ACP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_PACKET_CONTROL_AUDIO_INFO_SOURCE' +APG_PACKET_CONTROL_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'APG_INFOFRAME_SOURCE_NO_OVERRIDE', + 1: 'APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS', +} +APG_INFOFRAME_SOURCE_NO_OVERRIDE = 0 +APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS = 1 +APG_PACKET_CONTROL_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_RAMP_CONTROL_SIGN' +APG_RAMP_CONTROL_SIGN__enumvalues = { + 0: 'APG_RAMP_SIGNED', + 1: 'APG_RAMP_UNSIGNED', +} +APG_RAMP_SIGNED = 0 +APG_RAMP_UNSIGNED = 1 +APG_RAMP_CONTROL_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL' +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 1: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 2: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 3: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 4: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 5: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', +} +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1 = 0 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2 = 1 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3 = 2 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4 = 3 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5 = 4 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6 = 5 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL' +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL__enumvalues = { + 0: 'DCIO_TEST_CLK_SEL_DISPCLK', + 1: 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', + 2: 'DCIO_TEST_CLK_SEL_SOCCLK', +} +DCIO_TEST_CLK_SEL_DISPCLK = 0 +DCIO_TEST_CLK_SEL_GATED_DISPCLK = 1 +DCIO_TEST_CLK_SEL_SOCCLK = 2 +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS' +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS__enumvalues = { + 0: 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 1: 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', +} +DCIO_DISPCLK_R_DCIO_GATE_DISABLE = 0 +DCIO_DISPCLK_R_DCIO_GATE_ENABLE = 1 +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_4BIT_SEL' +DCIO_DBG_ASYNC_4BIT_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 1: 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', + 2: 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 3: 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 4: 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 5: 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 6: 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 7: 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', +} +DCIO_DBG_ASYNC_4BIT_SEL_3TO0 = 0 +DCIO_DBG_ASYNC_4BIT_SEL_7TO4 = 1 +DCIO_DBG_ASYNC_4BIT_SEL_11TO8 = 2 +DCIO_DBG_ASYNC_4BIT_SEL_15TO12 = 3 +DCIO_DBG_ASYNC_4BIT_SEL_19TO16 = 4 +DCIO_DBG_ASYNC_4BIT_SEL_23TO20 = 5 +DCIO_DBG_ASYNC_4BIT_SEL_27TO24 = 6 +DCIO_DBG_ASYNC_4BIT_SEL_31TO28 = 7 +DCIO_DBG_ASYNC_4BIT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_BLOCK_SEL' +DCIO_DBG_ASYNC_BLOCK_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', + 1: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', + 2: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 3: 'DCIO_DBG_ASYNC_BLOCK_SEL_DIO', +} +DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE = 0 +DCIO_DBG_ASYNC_BLOCK_SEL_DCCG = 1 +DCIO_DBG_ASYNC_BLOCK_SEL_DCIO = 2 +DCIO_DBG_ASYNC_BLOCK_SEL_DIO = 3 +DCIO_DBG_ASYNC_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCRXPHY_SOFT_RESET' +DCIO_DCRXPHY_SOFT_RESET__enumvalues = { + 0: 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 1: 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', +} +DCIO_DCRXPHY_SOFT_RESET_DEASSERT = 0 +DCIO_DCRXPHY_SOFT_RESET_ASSERT = 1 +DCIO_DCRXPHY_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICA_SEL' +DCIO_DC_GENERICA_SEL__enumvalues = { + 1: 'DCIO_GENERICA_SEL_STEREOSYNC', + 10: 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 11: 'DCIO_GENERICA_SEL_SYNCEN', +} +DCIO_GENERICA_SEL_STEREOSYNC = 1 +DCIO_GENERICA_SEL_GENERICA_DCCG = 10 +DCIO_GENERICA_SEL_SYNCEN = 11 +DCIO_DC_GENERICA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICB_SEL' +DCIO_DC_GENERICB_SEL__enumvalues = { + 1: 'DCIO_GENERICB_SEL_STEREOSYNC', + 10: 'DCIO_GENERICB_SEL_GENERICB_DCCG', + 11: 'DCIO_GENERICB_SEL_SYNCEN', +} +DCIO_GENERICB_SEL_STEREOSYNC = 1 +DCIO_GENERICB_SEL_GENERICB_DCCG = 10 +DCIO_GENERICB_SEL_SYNCEN = 11 +DCIO_DC_GENERICB_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 1: 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 2: 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 3: 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 4: 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 5: 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 6: 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', +} +DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2 = 0 +DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2 = 1 +DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2 = 2 +DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2 = 3 +DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2 = 4 +DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2 = 5 +DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2 = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_CLK', +} +DCIO_UNIPHYA_FBDIV_CLK = 0 +DCIO_UNIPHYB_FBDIV_CLK = 1 +DCIO_UNIPHYC_FBDIV_CLK = 2 +DCIO_UNIPHYD_FBDIV_CLK = 3 +DCIO_UNIPHYE_FBDIV_CLK = 4 +DCIO_UNIPHYF_FBDIV_CLK = 5 +DCIO_UNIPHYG_FBDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_SSC_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_SSC_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_SSC_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_SSC_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_SSC_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_SSC_CLK', +} +DCIO_UNIPHYA_FBDIV_SSC_CLK = 0 +DCIO_UNIPHYB_FBDIV_SSC_CLK = 1 +DCIO_UNIPHYC_FBDIV_SSC_CLK = 2 +DCIO_UNIPHYD_FBDIV_SSC_CLK = 3 +DCIO_UNIPHYE_FBDIV_SSC_CLK = 4 +DCIO_UNIPHYF_FBDIV_SSC_CLK = 5 +DCIO_UNIPHYG_FBDIV_SSC_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_REFDIV_CLK', + 1: 'DCIO_UNIPHYB_TEST_REFDIV_CLK', + 2: 'DCIO_UNIPHYC_TEST_REFDIV_CLK', + 3: 'DCIO_UNIPHYD_TEST_REFDIV_CLK', + 4: 'DCIO_UNIPHYE_TEST_REFDIV_CLK', + 5: 'DCIO_UNIPHYF_TEST_REFDIV_CLK', + 6: 'DCIO_UNIPHYG_TEST_REFDIV_CLK', +} +DCIO_UNIPHYA_TEST_REFDIV_CLK = 0 +DCIO_UNIPHYB_TEST_REFDIV_CLK = 1 +DCIO_UNIPHYC_TEST_REFDIV_CLK = 2 +DCIO_UNIPHYD_TEST_REFDIV_CLK = 3 +DCIO_UNIPHYE_TEST_REFDIV_CLK = 4 +DCIO_UNIPHYF_TEST_REFDIV_CLK = 5 +DCIO_UNIPHYG_TEST_REFDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE' +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE__enumvalues = { + 0: 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', + 1: 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', +} +DCIO_DPRX_LOOPBACK_ENABLE_NORMAL = 0 +DCIO_DPRX_LOOPBACK_ENABLE_LOOP = 1 +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_READ_SELECT' +DCIO_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 1: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 2: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 3: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 4: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 5: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', +} +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE = 0 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE = 1 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP = 2 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP = 3 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM = 4 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM = 5 +DCIO_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_START_POSITION' +DCIO_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DCIO_GPU_TIMER_START_0_END_27', + 1: 'DCIO_GPU_TIMER_START_1_END_28', + 2: 'DCIO_GPU_TIMER_START_2_END_29', + 3: 'DCIO_GPU_TIMER_START_3_END_30', + 4: 'DCIO_GPU_TIMER_START_4_END_31', + 5: 'DCIO_GPU_TIMER_START_6_END_33', + 6: 'DCIO_GPU_TIMER_START_8_END_35', + 7: 'DCIO_GPU_TIMER_START_10_END_37', +} +DCIO_GPU_TIMER_START_0_END_27 = 0 +DCIO_GPU_TIMER_START_1_END_28 = 1 +DCIO_GPU_TIMER_START_2_END_29 = 2 +DCIO_GPU_TIMER_START_3_END_30 = 3 +DCIO_GPU_TIMER_START_4_END_31 = 4 +DCIO_GPU_TIMER_START_6_END_33 = 5 +DCIO_GPU_TIMER_START_8_END_35 = 6 +DCIO_GPU_TIMER_START_10_END_37 = 7 +DCIO_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 1: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 2: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 3: 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', +} +DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE = 0 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1 = 1 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2 = 2 +DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3 = 3 +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', + 1: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', + 2: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', + 3: 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', +} +DCIO_HSYNCA_OUTPUT_SEL_DISABLE = 0 +DCIO_HSYNCA_OUTPUT_SEL_PPLL1 = 1 +DCIO_HSYNCA_OUTPUT_SEL_PPLL2 = 2 +DCIO_HSYNCA_OUTPUT_SEL_RESERVED = 3 +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_EXT_VSYNC_MASK' +DCIO_DIO_EXT_VSYNC_MASK__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MASK_NONE', + 1: 'DCIO_EXT_VSYNC_MASK_PIPE0', + 2: 'DCIO_EXT_VSYNC_MASK_PIPE1', + 3: 'DCIO_EXT_VSYNC_MASK_PIPE2', + 4: 'DCIO_EXT_VSYNC_MASK_PIPE3', + 5: 'DCIO_EXT_VSYNC_MASK_PIPE4', + 6: 'DCIO_EXT_VSYNC_MASK_PIPE5', + 7: 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', +} +DCIO_EXT_VSYNC_MASK_NONE = 0 +DCIO_EXT_VSYNC_MASK_PIPE0 = 1 +DCIO_EXT_VSYNC_MASK_PIPE1 = 2 +DCIO_EXT_VSYNC_MASK_PIPE2 = 3 +DCIO_EXT_VSYNC_MASK_PIPE3 = 4 +DCIO_EXT_VSYNC_MASK_PIPE4 = 5 +DCIO_EXT_VSYNC_MASK_PIPE5 = 6 +DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE = 7 +DCIO_DIO_EXT_VSYNC_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_OTG_EXT_VSYNC_MUX' +DCIO_DIO_OTG_EXT_VSYNC_MUX__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 1: 'DCIO_EXT_VSYNC_MUX_OTG0', + 2: 'DCIO_EXT_VSYNC_MUX_OTG1', + 3: 'DCIO_EXT_VSYNC_MUX_OTG2', + 4: 'DCIO_EXT_VSYNC_MUX_OTG3', + 5: 'DCIO_EXT_VSYNC_MUX_OTG4', + 6: 'DCIO_EXT_VSYNC_MUX_OTG5', + 7: 'DCIO_EXT_VSYNC_MUX_GENERICB', +} +DCIO_EXT_VSYNC_MUX_SWAPLOCKB = 0 +DCIO_EXT_VSYNC_MUX_OTG0 = 1 +DCIO_EXT_VSYNC_MUX_OTG1 = 2 +DCIO_EXT_VSYNC_MUX_OTG2 = 3 +DCIO_EXT_VSYNC_MUX_OTG3 = 4 +DCIO_EXT_VSYNC_MUX_OTG4 = 5 +DCIO_EXT_VSYNC_MUX_OTG5 = 6 +DCIO_EXT_VSYNC_MUX_GENERICB = 7 +DCIO_DIO_OTG_EXT_VSYNC_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_MASK' +DCIO_DPCS_INTERRUPT_MASK__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_DISABLE', + 1: 'DCIO_DPCS_INTERRUPT_ENABLE', +} +DCIO_DPCS_INTERRUPT_DISABLE = 0 +DCIO_DPCS_INTERRUPT_ENABLE = 1 +DCIO_DPCS_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_TYPE' +DCIO_DPCS_INTERRUPT_TYPE__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', +} +DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED = 0 +DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED = 1 +DCIO_DPCS_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DSYNC_SOFT_RESET' +DCIO_DSYNC_SOFT_RESET__enumvalues = { + 0: 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 1: 'DCIO_DSYNC_SOFT_RESET_ASSERT', +} +DCIO_DSYNC_SOFT_RESET_DEASSERT = 0 +DCIO_DSYNC_SOFT_RESET_ASSERT = 1 +DCIO_DSYNC_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_CLK_GSL_MASK' +DCIO_GENLK_CLK_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_CLK_GSL_MASK_NO', + 1: 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_CLK_GSL_MASK_STEREO', +} +DCIO_GENLK_CLK_GSL_MASK_NO = 0 +DCIO_GENLK_CLK_GSL_MASK_TIMING = 1 +DCIO_GENLK_CLK_GSL_MASK_STEREO = 2 +DCIO_GENLK_CLK_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_VSYNC_GSL_MASK' +DCIO_GENLK_VSYNC_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 1: 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', +} +DCIO_GENLK_VSYNC_GSL_MASK_NO = 0 +DCIO_GENLK_VSYNC_GSL_MASK_TIMING = 1 +DCIO_GENLK_VSYNC_GSL_MASK_STEREO = 2 +DCIO_GENLK_VSYNC_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL_SEL' +DCIO_GSL_SEL__enumvalues = { + 0: 'DCIO_GSL_SEL_GROUP_0', + 1: 'DCIO_GSL_SEL_GROUP_1', + 2: 'DCIO_GSL_SEL_GROUP_2', +} +DCIO_GSL_SEL_GROUP_0 = 0 +DCIO_GSL_SEL_GROUP_1 = 1 +DCIO_GSL_SEL_GROUP_2 = 2 +DCIO_GSL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_PHY_HPO_ENC_SRC_SEL' +DCIO_PHY_HPO_ENC_SRC_SEL__enumvalues = { + 0: 'HPO_SRC0', + 1: 'HPO_SRC_RESERVED', +} +HPO_SRC0 = 0 +HPO_SRC_RESERVED = 1 +DCIO_PHY_HPO_ENC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_A_GSL_MASK' +DCIO_SWAPLOCK_A_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_A_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_A_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_A_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_A_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_B_GSL_MASK' +DCIO_SWAPLOCK_B_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_B_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_B_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_B_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_B_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_B_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE' +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 1: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 2: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 3: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', +} +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0 = 0 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1 = 1 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2 = 2 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3 = 3 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_IMPCAL_SEL' +DCIO_UNIPHY_IMPCAL_SEL__enumvalues = { + 0: 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 1: 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', +} +DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE = 0 +DCIO_UNIPHY_IMPCAL_SEL_BINARY = 1 +DCIO_UNIPHY_IMPCAL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT' +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 1: 'DCIO_UNIPHY_CHANNEL_INVERTED', +} +DCIO_UNIPHY_CHANNEL_NO_INVERSION = 0 +DCIO_UNIPHY_CHANNEL_INVERTED = 1 +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK' +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK__enumvalues = { + 0: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 1: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 2: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 3: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', +} +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW = 0 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW = 1 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED = 2 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED = 3 +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_ALL_PWR_OK' +DCIOCHIP_AUX_ALL_PWR_OK__enumvalues = { + 0: 'DCIOCHIP_AUX_ALL_PWR_OK_0', + 1: 'DCIOCHIP_AUX_ALL_PWR_OK_1', +} +DCIOCHIP_AUX_ALL_PWR_OK_0 = 0 +DCIOCHIP_AUX_ALL_PWR_OK_1 = 1 +DCIOCHIP_AUX_ALL_PWR_OK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL0P9' +DCIOCHIP_AUX_CSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_CSEL_DEC0P9', +} +DCIOCHIP_AUX_CSEL_DEC1P0 = 0 +DCIOCHIP_AUX_CSEL_DEC0P9 = 1 +DCIOCHIP_AUX_CSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL1P1' +DCIOCHIP_AUX_CSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_INC1P0', + 1: 'DCIOCHIP_AUX_CSEL_INC1P1', +} +DCIOCHIP_AUX_CSEL_INC1P0 = 0 +DCIOCHIP_AUX_CSEL_INC1P1 = 1 +DCIOCHIP_AUX_CSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_FALLSLEWSEL' +DCIOCHIP_AUX_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 1: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 2: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', + 3: 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', +} +DCIOCHIP_AUX_FALLSLEWSEL_LOW = 0 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH0 = 1 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH1 = 2 +DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH = 3 +DCIOCHIP_AUX_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_HYS_TUNE' +DCIOCHIP_AUX_HYS_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_HYS_TUNE_0', + 1: 'DCIOCHIP_AUX_HYS_TUNE_1', + 2: 'DCIOCHIP_AUX_HYS_TUNE_2', + 3: 'DCIOCHIP_AUX_HYS_TUNE_3', +} +DCIOCHIP_AUX_HYS_TUNE_0 = 0 +DCIOCHIP_AUX_HYS_TUNE_1 = 1 +DCIOCHIP_AUX_HYS_TUNE_2 = 2 +DCIOCHIP_AUX_HYS_TUNE_3 = 3 +DCIOCHIP_AUX_HYS_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RECEIVER_SEL' +DCIOCHIP_AUX_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 1: 'DCIOCHIP_AUX_RECEIVER_SEL_1', + 2: 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 3: 'DCIOCHIP_AUX_RECEIVER_SEL_3', +} +DCIOCHIP_AUX_RECEIVER_SEL_0 = 0 +DCIOCHIP_AUX_RECEIVER_SEL_1 = 1 +DCIOCHIP_AUX_RECEIVER_SEL_2 = 2 +DCIOCHIP_AUX_RECEIVER_SEL_3 = 3 +DCIOCHIP_AUX_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL0P9' +DCIOCHIP_AUX_RSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_RSEL_DEC0P9', +} +DCIOCHIP_AUX_RSEL_DEC1P0 = 0 +DCIOCHIP_AUX_RSEL_DEC0P9 = 1 +DCIOCHIP_AUX_RSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL1P1' +DCIOCHIP_AUX_RSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_INC1P0', + 1: 'DCIOCHIP_AUX_RSEL_INC1P1', +} +DCIOCHIP_AUX_RSEL_INC1P0 = 0 +DCIOCHIP_AUX_RSEL_INC1P1 = 1 +DCIOCHIP_AUX_RSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_SPIKESEL' +DCIOCHIP_AUX_SPIKESEL__enumvalues = { + 0: 'DCIOCHIP_AUX_SPIKESEL_50NS', + 1: 'DCIOCHIP_AUX_SPIKESEL_10NS', +} +DCIOCHIP_AUX_SPIKESEL_50NS = 0 +DCIOCHIP_AUX_SPIKESEL_10NS = 1 +DCIOCHIP_AUX_SPIKESEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_VOD_TUNE' +DCIOCHIP_AUX_VOD_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_VOD_TUNE_0', + 1: 'DCIOCHIP_AUX_VOD_TUNE_1', + 2: 'DCIOCHIP_AUX_VOD_TUNE_2', + 3: 'DCIOCHIP_AUX_VOD_TUNE_3', +} +DCIOCHIP_AUX_VOD_TUNE_0 = 0 +DCIOCHIP_AUX_VOD_TUNE_1 = 1 +DCIOCHIP_AUX_VOD_TUNE_2 = 2 +DCIOCHIP_AUX_VOD_TUNE_3 = 3 +DCIOCHIP_AUX_VOD_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_MASK_EN' +DCIOCHIP_GPIO_MASK_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 1: 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', +} +DCIOCHIP_GPIO_MASK_EN_HARDWARE = 0 +DCIOCHIP_GPIO_MASK_EN_SOFTWARE = 1 +DCIOCHIP_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_HPD_SEL' +DCIOCHIP_HPD_SEL__enumvalues = { + 0: 'DCIOCHIP_HPD_SEL_ASYNC', + 1: 'DCIOCHIP_HPD_SEL_CLOCKED', +} +DCIOCHIP_HPD_SEL_ASYNC = 0 +DCIOCHIP_HPD_SEL_CLOCKED = 1 +DCIOCHIP_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_COMPSEL' +DCIOCHIP_I2C_COMPSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_REC_SCHMIT', + 1: 'DCIOCHIP_I2C_REC_COMPARATOR', +} +DCIOCHIP_I2C_REC_SCHMIT = 0 +DCIOCHIP_I2C_REC_COMPARATOR = 1 +DCIOCHIP_I2C_COMPSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_FALLSLEWSEL' +DCIOCHIP_I2C_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_FALLSLEWSEL_00', + 1: 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 2: 'DCIOCHIP_I2C_FALLSLEWSEL_10', + 3: 'DCIOCHIP_I2C_FALLSLEWSEL_11', +} +DCIOCHIP_I2C_FALLSLEWSEL_00 = 0 +DCIOCHIP_I2C_FALLSLEWSEL_01 = 1 +DCIOCHIP_I2C_FALLSLEWSEL_10 = 2 +DCIOCHIP_I2C_FALLSLEWSEL_11 = 3 +DCIOCHIP_I2C_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_RECEIVER_SEL' +DCIOCHIP_I2C_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 1: 'DCIOCHIP_I2C_RECEIVER_SEL_1', + 2: 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 3: 'DCIOCHIP_I2C_RECEIVER_SEL_3', +} +DCIOCHIP_I2C_RECEIVER_SEL_0 = 0 +DCIOCHIP_I2C_RECEIVER_SEL_1 = 1 +DCIOCHIP_I2C_RECEIVER_SEL_2 = 2 +DCIOCHIP_I2C_RECEIVER_SEL_3 = 3 +DCIOCHIP_I2C_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_VPH_1V2_EN' +DCIOCHIP_I2C_VPH_1V2_EN__enumvalues = { + 0: 'DCIOCHIP_I2C_VPH_1V2_EN_0', + 1: 'DCIOCHIP_I2C_VPH_1V2_EN_1', +} +DCIOCHIP_I2C_VPH_1V2_EN_0 = 0 +DCIOCHIP_I2C_VPH_1V2_EN_1 = 1 +DCIOCHIP_I2C_VPH_1V2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_INVERT' +DCIOCHIP_INVERT__enumvalues = { + 0: 'DCIOCHIP_POL_NON_INVERT', + 1: 'DCIOCHIP_POL_INVERT', +} +DCIOCHIP_POL_NON_INVERT = 0 +DCIOCHIP_POL_INVERT = 1 +DCIOCHIP_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK' +DCIOCHIP_MASK__enumvalues = { + 0: 'DCIOCHIP_MASK_DISABLE', + 1: 'DCIOCHIP_MASK_ENABLE', +} +DCIOCHIP_MASK_DISABLE = 0 +DCIOCHIP_MASK_ENABLE = 1 +DCIOCHIP_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PAD_MODE' +DCIOCHIP_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_PAD_MODE_DDC', + 1: 'DCIOCHIP_PAD_MODE_DP', +} +DCIOCHIP_PAD_MODE_DDC = 0 +DCIOCHIP_PAD_MODE_DP = 1 +DCIOCHIP_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PD_EN' +DCIOCHIP_PD_EN__enumvalues = { + 0: 'DCIOCHIP_PD_EN_NOTALLOW', + 1: 'DCIOCHIP_PD_EN_ALLOW', +} +DCIOCHIP_PD_EN_NOTALLOW = 0 +DCIOCHIP_PD_EN_ALLOW = 1 +DCIOCHIP_PD_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_REF_27_SRC_SEL' +DCIOCHIP_REF_27_SRC_SEL__enumvalues = { + 0: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 1: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 2: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 3: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', +} +DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER = 0 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER = 1 +DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS = 2 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS = 3 +DCIOCHIP_REF_27_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE' +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE__enumvalues = { + 0: 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 1: 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE', +} +PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE = 0 +PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN' +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL', + 1: 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM', +} +PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL = 0 +PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM = 1 +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT' +PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT__enumvalues = { + 0: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 1: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 2: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 3: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', +} +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL = 0 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1 = 1 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2 = 2 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3 = 3 +PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL_BL_PWM_EN' +PWRSEQ_BL_PWM_CNTL_BL_PWM_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_DISABLE', + 1: 'PWRSEQ_BL_PWM_ENABLE', +} +PWRSEQ_BL_PWM_DISABLE = 0 +PWRSEQ_BL_PWM_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL_BL_PWM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN' +PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_FRACTIONAL_DISABLE', + 1: 'PWRSEQ_BL_PWM_FRACTIONAL_ENABLE', +} +PWRSEQ_BL_PWM_FRACTIONAL_DISABLE = 0 +PWRSEQ_BL_PWM_FRACTIONAL_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN' +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', +} +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE = 0 +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE = 1 +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN' +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 1: 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', +} +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM = 0 +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM = 1 +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_REG_LOCK' +PWRSEQ_BL_PWM_GRP1_REG_LOCK__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE', +} +PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE = 0 +PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE = 1 +PWRSEQ_BL_PWM_GRP1_REG_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START' +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', +} +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE = 0 +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE = 1 +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_GPIO_MASK_EN' +PWRSEQ_GPIO_MASK_EN__enumvalues = { + 0: 'PWRSEQ_GPIO_MASK_EN_HARDWARE', + 1: 'PWRSEQ_GPIO_MASK_EN_SOFTWARE', +} +PWRSEQ_GPIO_MASK_EN_HARDWARE = 0 +PWRSEQ_GPIO_MASK_EN_SOFTWARE = 1 +PWRSEQ_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON__enumvalues = { + 0: 'PWRSEQ_PANEL_BLON_OFF', + 1: 'PWRSEQ_PANEL_BLON_ON', +} +PWRSEQ_PANEL_BLON_OFF = 0 +PWRSEQ_PANEL_BLON_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_BLON_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_BLON_POL_INVERT', +} +PWRSEQ_PANEL_BLON_POL_NON_INVERT = 0 +PWRSEQ_PANEL_BLON_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON__enumvalues = { + 0: 'PWRSEQ_PANEL_DIGON_OFF', + 1: 'PWRSEQ_PANEL_DIGON_ON', +} +PWRSEQ_PANEL_DIGON_OFF = 0 +PWRSEQ_PANEL_DIGON_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_DIGON_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_DIGON_POL_INVERT', +} +PWRSEQ_PANEL_DIGON_POL_NON_INVERT = 0 +PWRSEQ_PANEL_DIGON_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_SYNCEN_POL_INVERT', +} +PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT = 0 +PWRSEQ_PANEL_SYNCEN_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE' +PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE__enumvalues = { + 0: 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF', + 1: 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON', +} +PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF = 0 +PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN' +PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN__enumvalues = { + 0: 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON', + 1: 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE', +} +PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON = 0 +PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE = 1 +PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_CORB_SIZE' +AZ_CORB_SIZE__enumvalues = { + 0: 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_CORB_SIZE_256ENTRIES', + 3: 'AZ_CORB_SIZE_RESERVED', +} +AZ_CORB_SIZE_2ENTRIES_RESERVED = 0 +AZ_CORB_SIZE_16ENTRIES_RESERVED = 1 +AZ_CORB_SIZE_256ENTRIES = 2 +AZ_CORB_SIZE_RESERVED = 3 +AZ_CORB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_GLOBAL_CAPABILITIES' +AZ_GLOBAL_CAPABILITIES__enumvalues = { + 0: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 1: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', +} +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED = 0 +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED = 1 +AZ_GLOBAL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_SIZE' +AZ_RIRB_SIZE__enumvalues = { + 0: 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_RIRB_SIZE_256ENTRIES', + 3: 'AZ_RIRB_SIZE_UNDEFINED', +} +AZ_RIRB_SIZE_2ENTRIES_RESERVED = 0 +AZ_RIRB_SIZE_16ENTRIES_RESERVED = 1 +AZ_RIRB_SIZE_256ENTRIES = 2 +AZ_RIRB_SIZE_UNDEFINED = 3 +AZ_RIRB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_WRITE_POINTER_RESET' +AZ_RIRB_WRITE_POINTER_RESET__enumvalues = { + 0: 'AZ_RIRB_WRITE_POINTER_NOT_RESET', + 1: 'AZ_RIRB_WRITE_POINTER_DO_RESET', +} +AZ_RIRB_WRITE_POINTER_NOT_RESET = 0 +AZ_RIRB_WRITE_POINTER_DO_RESET = 1 +AZ_RIRB_WRITE_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_STATE_CHANGE_STATUS' +AZ_STATE_CHANGE_STATUS__enumvalues = { + 0: 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 1: 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', +} +AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT = 0 +AZ_STATE_CHANGE_STATUS_CODEC_PRESENT = 1 +AZ_STATE_CHANGE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'CORB_READ_POINTER_RESET' +CORB_READ_POINTER_RESET__enumvalues = { + 0: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 1: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', +} +CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET = 0 +CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET = 1 +CORB_READ_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE' +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE__enumvalues = { + 0: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 1: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', +} +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE = 0 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE = 1 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE' +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE__enumvalues = { + 0: 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', + 1: 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', +} +ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE = 0 +ACCEPT_UNSOLICITED_RESPONSE_ENABLE = 1 +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_CONTROLLER_RESET' +GLOBAL_CONTROL_CONTROLLER_RESET__enumvalues = { + 0: 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 1: 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', +} +CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET = 0 +CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET = 1 +GLOBAL_CONTROL_CONTROLLER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_FLUSH_CONTROL' +GLOBAL_CONTROL_FLUSH_CONTROL__enumvalues = { + 0: 'FLUSH_CONTROL_FLUSH_NOT_STARTED', + 1: 'FLUSH_CONTROL_FLUSH_STARTED', +} +FLUSH_CONTROL_FLUSH_NOT_STARTED = 0 +FLUSH_CONTROL_FLUSH_STARTED = 1 +GLOBAL_CONTROL_FLUSH_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_STATUS_FLUSH_STATUS' +GLOBAL_STATUS_FLUSH_STATUS__enumvalues = { + 0: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 1: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', +} +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED = 0 +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED = 1 +GLOBAL_STATUS_FLUSH_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_0_SYNCHRONIZATION' +STREAM_0_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_0_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_0_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_10_SYNCHRONIZATION' +STREAM_10_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_10_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_11_SYNCHRONIZATION' +STREAM_11_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_11_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_12_SYNCHRONIZATION' +STREAM_12_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_12_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_13_SYNCHRONIZATION' +STREAM_13_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_13_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_14_SYNCHRONIZATION' +STREAM_14_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_14_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_15_SYNCHRONIZATION' +STREAM_15_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_15_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_1_SYNCHRONIZATION' +STREAM_1_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_1_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_1_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_2_SYNCHRONIZATION' +STREAM_2_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_2_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_2_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_3_SYNCHRONIZATION' +STREAM_3_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_3_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_3_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_4_SYNCHRONIZATION' +STREAM_4_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_4_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_5_SYNCHRONIZATION' +STREAM_5_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_5_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_6_SYNCHRONIZATION' +STREAM_6_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_6_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_7_SYNCHRONIZATION' +STREAM_7_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_7_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_8_SYNCHRONIZATION' +STREAM_8_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_8_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_9_SYNCHRONIZATION' +STREAM_9_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_9_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE' +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 2: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 3: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 4: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 5: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 6: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 7: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 8: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 9: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 10: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 11: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 12: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 13: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 14: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 15: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', +} +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0 = 0 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1 = 1 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2 = 2 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3 = 3 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4 = 4 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5 = 5 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6 = 6 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7 = 7 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8 = 8 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9 = 9 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10 = 10 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11 = 11 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12 = 12 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13 = 13 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14 = 14 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15 = 15 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT' +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET' +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET__enumvalues = { + 0: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 1: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', +} +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET = 0 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC = 1 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_CTRL' +MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'ENABLE_MEM_PWR_CTRL', + 1: 'DISABLE_MEM_PWR_CTRL', +} +ENABLE_MEM_PWR_CTRL = 0 +DISABLE_MEM_PWR_CTRL = 1 +MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL' +MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'NO_FORCE_REQUEST', + 1: 'FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FORCE_DEEP_SLEEP_REQUEST', + 3: 'FORCE_SHUT_DOWN_REQUEST', +} +NO_FORCE_REQUEST = 0 +FORCE_LIGHT_SLEEP_REQUEST = 1 +FORCE_DEEP_SLEEP_REQUEST = 2 +FORCE_SHUT_DOWN_REQUEST = 3 +MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL2' +MEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'NO_FORCE_REQ', + 1: 'FORCE_LIGHT_SLEEP_REQ', +} +NO_FORCE_REQ = 0 +FORCE_LIGHT_SLEEP_REQ = 1 +MEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL' +MEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DYNAMIC_SHUT_DOWN_ENABLE = 0 +DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +MEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL2' +MEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DYNAMIC_DEEP_SLEEP_EN', + 1: 'DYNAMIC_LIGHT_SLEEP_EN', +} +DYNAMIC_DEEP_SLEEP_EN = 0 +DYNAMIC_LIGHT_SLEEP_EN = 1 +MEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET' +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET__enumvalues = { + 0: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 1: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', +} +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET = 0 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET = 1 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_LATENCY_COUNTER_CONTROL' +AZ_LATENCY_COUNTER_CONTROL__enumvalues = { + 0: 'AZ_LATENCY_COUNTER_NO_RESET', + 1: 'AZ_LATENCY_COUNTER_RESET_DONE', +} +AZ_LATENCY_COUNTER_NO_RESET = 0 +AZ_LATENCY_COUNTER_RESET_DONE = 1 +AZ_LATENCY_COUNTER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 9: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 10: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 11: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 12: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 13: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 14: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 15: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED = 8 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED = 9 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED = 10 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED = 11 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED = 12 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED = 13 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED = 14 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED = 15 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', +} +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY = 0 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY = 1 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_BITS_PER_COMPONENT_ENUM' +DSCC_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCC_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MAJOR_ENUM' +DSCC_DSC_VERSION_MAJOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', +} +DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION = 1 +DSCC_DSC_VERSION_MAJOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MINOR_ENUM' +DSCC_DSC_VERSION_MINOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 2: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', +} +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION = 1 +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION = 2 +DSCC_DSC_VERSION_MINOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ENABLE_ENUM' +DSCC_ENABLE_ENUM__enumvalues = { + 0: 'DSCC_ENABLE_ENUM_DISABLED', + 1: 'DSCC_ENABLE_ENUM_ENABLED', +} +DSCC_ENABLE_ENUM_DISABLED = 0 +DSCC_ENABLE_ENUM_ENABLED = 1 +DSCC_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ICH_RESET_ENUM' +DSCC_ICH_RESET_ENUM__enumvalues = { + 1: 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 2: 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 4: 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 8: 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', +} +DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET = 1 +DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET = 2 +DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET = 4 +DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET = 8 +DSCC_ICH_RESET_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_LINEBUF_DEPTH_ENUM' +DSCC_LINEBUF_DEPTH_ENUM__enumvalues = { + 8: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 9: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 10: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 11: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 12: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 13: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', +} +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT = 8 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT = 9 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT = 10 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT = 11 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT = 12 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT = 13 +DSCC_LINEBUF_DEPTH_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_DIS_ENUM' +DSCC_MEM_PWR_DIS_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', + 1: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', +} +DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN = 0 +DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS = 1 +DSCC_MEM_PWR_DIS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_FORCE_ENUM' +DSCC_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 1: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', +} +DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST = 0 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST = 2 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST = 3 +DSCC_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'POWER_STATE_ENUM' +POWER_STATE_ENUM__enumvalues = { + 0: 'POWER_STATE_ENUM_ON', + 1: 'POWER_STATE_ENUM_LS', + 2: 'POWER_STATE_ENUM_DS', + 3: 'POWER_STATE_ENUM_SD', +} +POWER_STATE_ENUM_ON = 0 +POWER_STATE_ENUM_LS = 1 +POWER_STATE_ENUM_DS = 2 +POWER_STATE_ENUM_SD = 3 +POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_BITS_PER_COMPONENT_ENUM' +DSCCIF_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCCIF_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_ENABLE_ENUM' +DSCCIF_ENABLE_ENUM__enumvalues = { + 0: 'DSCCIF_ENABLE_ENUM_DISABLED', + 1: 'DSCCIF_ENABLE_ENUM_ENABLED', +} +DSCCIF_ENABLE_ENUM_DISABLED = 0 +DSCCIF_ENABLE_ENUM_ENABLED = 1 +DSCCIF_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM' +DSCCIF_INPUT_PIXEL_FORMAT_ENUM__enumvalues = { + 0: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 1: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 2: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 3: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 4: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', +} +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB = 0 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444 = 1 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422 = 2 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422 = 3 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420 = 4 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_DISABLE_ENUM' +CLOCK_GATING_DISABLE_ENUM__enumvalues = { + 0: 'CLOCK_GATING_DISABLE_ENUM_ENABLED', + 1: 'CLOCK_GATING_DISABLE_ENUM_DISABLED', +} +CLOCK_GATING_DISABLE_ENUM_ENABLED = 0 +CLOCK_GATING_DISABLE_ENUM_DISABLED = 1 +CLOCK_GATING_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_ENUM' +ENABLE_ENUM__enumvalues = { + 0: 'ENABLE_ENUM_DISABLED', + 1: 'ENABLE_ENUM_ENABLED', +} +ENABLE_ENUM_DISABLED = 0 +ENABLE_ENUM_ENABLED = 1 +ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLOCK_MUX_SELECT_ENUM' +TEST_CLOCK_MUX_SELECT_ENUM__enumvalues = { + 0: 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 1: 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 2: 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 3: 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 4: 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 5: 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', +} +TEST_CLOCK_MUX_SELECT_DISPCLK_P = 0 +TEST_CLOCK_MUX_SELECT_DISPCLK_G = 1 +TEST_CLOCK_MUX_SELECT_DISPCLK_R = 2 +TEST_CLOCK_MUX_SELECT_DSCCLK_P = 3 +TEST_CLOCK_MUX_SELECT_DSCCLK_G = 4 +TEST_CLOCK_MUX_SELECT_DSCCLK_R = 5 +TEST_CLOCK_MUX_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_CRC_CONT_EN_ENUM' +DWB_CRC_CONT_EN_ENUM__enumvalues = { + 0: 'DWB_CRC_CONT_EN_ONE_SHOT', + 1: 'DWB_CRC_CONT_EN_CONT', +} +DWB_CRC_CONT_EN_ONE_SHOT = 0 +DWB_CRC_CONT_EN_CONT = 1 +DWB_CRC_CONT_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_CRC_SRC_SEL_ENUM' +DWB_CRC_SRC_SEL_ENUM__enumvalues = { + 0: 'DWB_CRC_SRC_SEL_DWB_IN', + 1: 'DWB_CRC_SRC_SEL_OGAM_OUT', + 2: 'DWB_CRC_SRC_SEL_DWB_OUT', +} +DWB_CRC_SRC_SEL_DWB_IN = 0 +DWB_CRC_SRC_SEL_OGAM_OUT = 1 +DWB_CRC_SRC_SEL_DWB_OUT = 2 +DWB_CRC_SRC_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DATA_OVERFLOW_INT_TYPE_ENUM' +DWB_DATA_OVERFLOW_INT_TYPE_ENUM__enumvalues = { + 0: 'DWB_DATA_OVERFLOW_INT_TYPE_0', + 1: 'DWB_DATA_OVERFLOW_INT_TYPE_1', +} +DWB_DATA_OVERFLOW_INT_TYPE_0 = 0 +DWB_DATA_OVERFLOW_INT_TYPE_1 = 1 +DWB_DATA_OVERFLOW_INT_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DATA_OVERFLOW_TYPE_ENUM' +DWB_DATA_OVERFLOW_TYPE_ENUM__enumvalues = { + 0: 'DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW', + 1: 'DWB_DATA_OVERFLOW_TYPE_BUFFER', + 2: 'DWB_DATA_OVERFLOW_TYPE_VUPDATE', + 3: 'DWB_DATA_OVERFLOW_TYPE_VREADY', +} +DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW = 0 +DWB_DATA_OVERFLOW_TYPE_BUFFER = 1 +DWB_DATA_OVERFLOW_TYPE_VUPDATE = 2 +DWB_DATA_OVERFLOW_TYPE_VREADY = 3 +DWB_DATA_OVERFLOW_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DEBUG_SEL_ENUM' +DWB_DEBUG_SEL_ENUM__enumvalues = { + 0: 'DWB_DEBUG_SEL_FC', + 1: 'DWB_DEBUG_SEL_RESERVED', + 2: 'DWB_DEBUG_SEL_DWBCP', + 3: 'DWB_DEBUG_SEL_PERFMON', +} +DWB_DEBUG_SEL_FC = 0 +DWB_DEBUG_SEL_RESERVED = 1 +DWB_DEBUG_SEL_DWBCP = 2 +DWB_DEBUG_SEL_PERFMON = 3 +DWB_DEBUG_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_MEM_PWR_FORCE_ENUM' +DWB_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DWB_MEM_PWR_FORCE_DIS', + 1: 'DWB_MEM_PWR_FORCE_LS', + 2: 'DWB_MEM_PWR_FORCE_DS', + 3: 'DWB_MEM_PWR_FORCE_SD', +} +DWB_MEM_PWR_FORCE_DIS = 0 +DWB_MEM_PWR_FORCE_LS = 1 +DWB_MEM_PWR_FORCE_DS = 2 +DWB_MEM_PWR_FORCE_SD = 3 +DWB_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_MEM_PWR_STATE_ENUM' +DWB_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'DWB_MEM_PWR_STATE_ON', + 1: 'DWB_MEM_PWR_STATE_LS', + 2: 'DWB_MEM_PWR_STATE_DS', + 3: 'DWB_MEM_PWR_STATE_SD', +} +DWB_MEM_PWR_STATE_ON = 0 +DWB_MEM_PWR_STATE_LS = 1 +DWB_MEM_PWR_STATE_DS = 2 +DWB_MEM_PWR_STATE_SD = 3 +DWB_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_TEST_CLK_SEL_ENUM' +DWB_TEST_CLK_SEL_ENUM__enumvalues = { + 0: 'DWB_TEST_CLK_SEL_R', + 1: 'DWB_TEST_CLK_SEL_G', + 2: 'DWB_TEST_CLK_SEL_P', +} +DWB_TEST_CLK_SEL_R = 0 +DWB_TEST_CLK_SEL_G = 1 +DWB_TEST_CLK_SEL_P = 2 +DWB_TEST_CLK_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_EYE_SELECTION_ENUM' +FC_EYE_SELECTION_ENUM__enumvalues = { + 0: 'FC_EYE_SELECTION_STEREO_DIS', + 1: 'FC_EYE_SELECTION_LEFT_EYE', + 2: 'FC_EYE_SELECTION_RIGHT_EYE', +} +FC_EYE_SELECTION_STEREO_DIS = 0 +FC_EYE_SELECTION_LEFT_EYE = 1 +FC_EYE_SELECTION_RIGHT_EYE = 2 +FC_EYE_SELECTION_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_FRAME_CAPTURE_RATE_ENUM' +FC_FRAME_CAPTURE_RATE_ENUM__enumvalues = { + 0: 'FC_FRAME_CAPTURE_RATE_FULL', + 1: 'FC_FRAME_CAPTURE_RATE_HALF', + 2: 'FC_FRAME_CAPTURE_RATE_THIRD', + 3: 'FC_FRAME_CAPTURE_RATE_QUARTER', +} +FC_FRAME_CAPTURE_RATE_FULL = 0 +FC_FRAME_CAPTURE_RATE_HALF = 1 +FC_FRAME_CAPTURE_RATE_THIRD = 2 +FC_FRAME_CAPTURE_RATE_QUARTER = 3 +FC_FRAME_CAPTURE_RATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_STEREO_EYE_POLARITY_ENUM' +FC_STEREO_EYE_POLARITY_ENUM__enumvalues = { + 0: 'FC_STEREO_EYE_POLARITY_LEFT', + 1: 'FC_STEREO_EYE_POLARITY_RIGHT', +} +FC_STEREO_EYE_POLARITY_LEFT = 0 +FC_STEREO_EYE_POLARITY_RIGHT = 1 +FC_STEREO_EYE_POLARITY_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_GAMUT_REMAP_COEF_FORMAT_ENUM' +DWB_GAMUT_REMAP_COEF_FORMAT_ENUM__enumvalues = { + 0: 'DWB_GAMUT_REMAP_COEF_FORMAT_S2_13', + 1: 'DWB_GAMUT_REMAP_COEF_FORMAT_S3_12', +} +DWB_GAMUT_REMAP_COEF_FORMAT_S2_13 = 0 +DWB_GAMUT_REMAP_COEF_FORMAT_S3_12 = 1 +DWB_GAMUT_REMAP_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_GAMUT_REMAP_MODE_ENUM' +DWB_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'DWB_GAMUT_REMAP_MODE_BYPASS', + 1: 'DWB_GAMUT_REMAP_MODE_COEF_A', + 2: 'DWB_GAMUT_REMAP_MODE_COEF_B', + 3: 'DWB_GAMUT_REMAP_MODE_RESERVED', +} +DWB_GAMUT_REMAP_MODE_BYPASS = 0 +DWB_GAMUT_REMAP_MODE_COEF_A = 1 +DWB_GAMUT_REMAP_MODE_COEF_B = 2 +DWB_GAMUT_REMAP_MODE_RESERVED = 3 +DWB_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_LUT_NUM_SEG' +DWB_LUT_NUM_SEG__enumvalues = { + 0: 'DWB_SEGMENTS_1', + 1: 'DWB_SEGMENTS_2', + 2: 'DWB_SEGMENTS_4', + 3: 'DWB_SEGMENTS_8', + 4: 'DWB_SEGMENTS_16', + 5: 'DWB_SEGMENTS_32', + 6: 'DWB_SEGMENTS_64', + 7: 'DWB_SEGMENTS_128', +} +DWB_SEGMENTS_1 = 0 +DWB_SEGMENTS_2 = 1 +DWB_SEGMENTS_4 = 2 +DWB_SEGMENTS_8 = 3 +DWB_SEGMENTS_16 = 4 +DWB_SEGMENTS_32 = 5 +DWB_SEGMENTS_64 = 6 +DWB_SEGMENTS_128 = 7 +DWB_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_CONFIG_MODE_ENUM' +DWB_OGAM_LUT_CONFIG_MODE_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_CONFIG_MODE_DIFF', + 1: 'DWB_OGAM_LUT_CONFIG_MODE_SAME', +} +DWB_OGAM_LUT_CONFIG_MODE_DIFF = 0 +DWB_OGAM_LUT_CONFIG_MODE_SAME = 1 +DWB_OGAM_LUT_CONFIG_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_HOST_SEL_ENUM' +DWB_OGAM_LUT_HOST_SEL_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_HOST_SEL_RAMA', + 1: 'DWB_OGAM_LUT_HOST_SEL_RAMB', +} +DWB_OGAM_LUT_HOST_SEL_RAMA = 0 +DWB_OGAM_LUT_HOST_SEL_RAMB = 1 +DWB_OGAM_LUT_HOST_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_READ_COLOR_SEL_ENUM' +DWB_OGAM_LUT_READ_COLOR_SEL_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_READ_COLOR_SEL_B', + 1: 'DWB_OGAM_LUT_READ_COLOR_SEL_G', + 2: 'DWB_OGAM_LUT_READ_COLOR_SEL_R', + 3: 'DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED', +} +DWB_OGAM_LUT_READ_COLOR_SEL_B = 0 +DWB_OGAM_LUT_READ_COLOR_SEL_G = 1 +DWB_OGAM_LUT_READ_COLOR_SEL_R = 2 +DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED = 3 +DWB_OGAM_LUT_READ_COLOR_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_READ_DBG_ENUM' +DWB_OGAM_LUT_READ_DBG_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_READ_DBG_DISABLE', + 1: 'DWB_OGAM_LUT_READ_DBG_ENABLE', +} +DWB_OGAM_LUT_READ_DBG_DISABLE = 0 +DWB_OGAM_LUT_READ_DBG_ENABLE = 1 +DWB_OGAM_LUT_READ_DBG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_MODE_ENUM' +DWB_OGAM_MODE_ENUM__enumvalues = { + 0: 'DWB_OGAM_MODE_BYPASS', + 1: 'DWB_OGAM_MODE_RESERVED', + 2: 'DWB_OGAM_MODE_RAM_LUT_ENABLED', +} +DWB_OGAM_MODE_BYPASS = 0 +DWB_OGAM_MODE_RESERVED = 1 +DWB_OGAM_MODE_RAM_LUT_ENABLED = 2 +DWB_OGAM_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_PWL_DISABLE_ENUM' +DWB_OGAM_PWL_DISABLE_ENUM__enumvalues = { + 0: 'DWB_OGAM_PWL_DISABLE_FALSE', + 1: 'DWB_OGAM_PWL_DISABLE_TRUE', +} +DWB_OGAM_PWL_DISABLE_FALSE = 0 +DWB_OGAM_PWL_DISABLE_TRUE = 1 +DWB_OGAM_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_SELECT_ENUM' +DWB_OGAM_SELECT_ENUM__enumvalues = { + 0: 'DWB_OGAM_SELECT_A', + 1: 'DWB_OGAM_SELECT_B', +} +DWB_OGAM_SELECT_A = 0 +DWB_OGAM_SELECT_B = 1 +DWB_OGAM_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_LANE_CLK_EN' +RDPCSPIPE_CLOCK_CNTL_LANE_CLK_EN__enumvalues = { + 0: 'RDPCSPIPE_EXT_PCLK_EN_DISABLE', + 1: 'RDPCSPIPE_EXT_PCLK_EN_ENABLE', +} +RDPCSPIPE_EXT_PCLK_EN_DISABLE = 0 +RDPCSPIPE_EXT_PCLK_EN_ENABLE = 1 +RDPCSPIPE_CLOCK_CNTL_LANE_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_APBCLK_EN' +RDPCSPIPE_CLOCK_CNTL_RDPCS_APBCLK_EN__enumvalues = { + 0: 'RDPCSPIPE_APBCLK_DISABLE', + 1: 'RDPCSPIPE_APBCLK_ENABLE', +} +RDPCSPIPE_APBCLK_DISABLE = 0 +RDPCSPIPE_APBCLK_ENABLE = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_APBCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_CLOCK_ON' +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_PIPE_CLK_CLOCK_OFF', + 1: 'RDPCS_PIPE_CLK_CLOCK_ON', +} +RDPCS_PIPE_CLK_CLOCK_OFF = 0 +RDPCS_PIPE_CLK_CLOCK_ON = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_EN' +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_EN__enumvalues = { + 0: 'RDPCS_PIPE_CLK_DISABLE', + 1: 'RDPCS_PIPE_CLK_ENABLE', +} +RDPCS_PIPE_CLK_DISABLE = 0 +RDPCS_PIPE_CLK_ENABLE = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_GATE_DIS' +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_GATE_DIS__enumvalues = { + 0: 'RDPCS_PIPE_CLK_GATE_ENABLE', + 1: 'RDPCS_PIPE_CLK_GATE_DISABLE', +} +RDPCS_PIPE_CLK_GATE_ENABLE = 0 +RDPCS_PIPE_CLK_GATE_DISABLE = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_PHYD32CLK_CLOCK_ON' +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_PHYD32CLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_PIPE_PHYD32CLK_CLOCK_OFF', + 1: 'RDPCS_PIPE_PHYD32CLK_CLOCK_ON', +} +RDPCS_PIPE_PHYD32CLK_CLOCK_OFF = 0 +RDPCS_PIPE_PHYD32CLK_CLOCK_ON = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_PHYD32CLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON' +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON__enumvalues = { + 0: 'RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_OFF', + 1: 'RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_ON', +} +RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_OFF = 0 +RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_ON = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_EN' +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_EN__enumvalues = { + 0: 'RDPCSPIPE_SRAMCLK_DISABLE', + 1: 'RDPCSPIPE_SRAMCLK_ENABLE', +} +RDPCSPIPE_SRAMCLK_DISABLE = 0 +RDPCSPIPE_SRAMCLK_ENABLE = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS' +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS__enumvalues = { + 0: 'RDPCSPIPE_SRAMCLK_GATE_ENABLE', + 1: 'RDPCSPIPE_SRAMCLK_GATE_DISABLE', +} +RDPCSPIPE_SRAMCLK_GATE_ENABLE = 0 +RDPCSPIPE_SRAMCLK_GATE_DISABLE = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_PASS' +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_PASS__enumvalues = { + 0: 'RDPCSPIPE_SRAMCLK_NOT_PASS', + 1: 'RDPCSPIPE_SRAMCLK_PASS', +} +RDPCSPIPE_SRAMCLK_NOT_PASS = 0 +RDPCSPIPE_SRAMCLK_PASS = 1 +RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_PASS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_EN' +RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_EN__enumvalues = { + 0: 'RDPCS_PIPE_FIFO_DISABLE', + 1: 'RDPCS_PIPE_FIFO_ENABLE', +} +RDPCS_PIPE_FIFO_DISABLE = 0 +RDPCS_PIPE_FIFO_ENABLE = 1 +RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_LANE_EN' +RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_LANE_EN__enumvalues = { + 0: 'RDPCS_PIPE_FIFO_LANE_DISABLE', + 1: 'RDPCS_PIPE_FIFO_LANE_ENABLE', +} +RDPCS_PIPE_FIFO_LANE_DISABLE = 0 +RDPCS_PIPE_FIFO_LANE_ENABLE = 1 +RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_LANE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CNTL_RDPCS_PIPE_SOFT_RESET' +RDPCSPIPE_CNTL_RDPCS_PIPE_SOFT_RESET__enumvalues = { + 0: 'RDPCS_PIPE_SOFT_RESET_DISABLE', + 1: 'RDPCS_PIPE_SOFT_RESET_ENABLE', +} +RDPCS_PIPE_SOFT_RESET_DISABLE = 0 +RDPCS_PIPE_SOFT_RESET_ENABLE = 1 +RDPCSPIPE_CNTL_RDPCS_PIPE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_CNTL_RDPCS_SRAM_SOFT_RESET' +RDPCSPIPE_CNTL_RDPCS_SRAM_SOFT_RESET__enumvalues = { + 0: 'RDPCSPIPE_SRAM_SRAM_RESET_DISABLE', + 1: 'RDPCSPIPE_SRAM_SRAM_RESET_ENABLE', +} +RDPCSPIPE_SRAM_SRAM_RESET_DISABLE = 0 +RDPCSPIPE_SRAM_SRAM_RESET_ENABLE = 1 +RDPCSPIPE_CNTL_RDPCS_SRAM_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK' +RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK__enumvalues = { + 0: 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_DISABLE', + 1: 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_ENABLE', +} +RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_DISABLE = 0 +RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_ENABLE = 1 +RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_DBG_OCLA_SEL' +RDPCSPIPE_DBG_OCLA_SEL__enumvalues = { + 0: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_7_0', + 1: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_15_8', + 2: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_23_16', + 3: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_31_24', + 4: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_39_32', + 5: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_47_40', + 6: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_55_48', + 7: 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_63_56', +} +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_7_0 = 0 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_15_8 = 1 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_23_16 = 2 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_31_24 = 3 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_39_32 = 4 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_47_40 = 5 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_55_48 = 6 +RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_63_56 = 7 +RDPCSPIPE_DBG_OCLA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_ENC_TYPE' +RDPCSPIPE_ENC_TYPE__enumvalues = { + 0: 'HDMI_TMDS_OR_DP_8B10B', + 1: 'HDMI_FRL', + 2: 'DP_128B132B', +} +HDMI_TMDS_OR_DP_8B10B = 0 +HDMI_FRL = 1 +DP_128B132B = 2 +RDPCSPIPE_ENC_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_FIFO_EMPTY' +RDPCSPIPE_FIFO_EMPTY__enumvalues = { + 0: 'RDPCSPIPE_FIFO_NOT_EMPTY', + 1: 'RDPCSPIPE_FIFO_IS_EMPTY', +} +RDPCSPIPE_FIFO_NOT_EMPTY = 0 +RDPCSPIPE_FIFO_IS_EMPTY = 1 +RDPCSPIPE_FIFO_EMPTY = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_FIFO_FULL' +RDPCSPIPE_FIFO_FULL__enumvalues = { + 0: 'RDPCSPIPE_FIFO_NOT_FULL', + 1: 'RDPCSPIPE_FIFO_IS_FULL', +} +RDPCSPIPE_FIFO_NOT_FULL = 0 +RDPCSPIPE_FIFO_IS_FULL = 1 +RDPCSPIPE_FIFO_FULL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_APB_PSLVERR_MASK' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_APB_PSLVERR_MASK__enumvalues = { + 0: 'RDPCSPIPE_APB_PSLVERR_MASK_DISABLE', + 1: 'RDPCSPIPE_APB_PSLVERR_MASK_ENABLE', +} +RDPCSPIPE_APB_PSLVERR_MASK_DISABLE = 0 +RDPCSPIPE_APB_PSLVERR_MASK_ENABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_APB_PSLVERR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE__enumvalues = { + 0: 'RDPCSPIPE_DPALT_4LANE_TOGGLE_2LANE', + 1: 'RDPCSPIPE_DPALT_4LANE_TOGGLE_4LANE', +} +RDPCSPIPE_DPALT_4LANE_TOGGLE_2LANE = 0 +RDPCSPIPE_DPALT_4LANE_TOGGLE_4LANE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 1: 'RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_ENABLE', +} +RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_DISABLE = 0 +RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_ENABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE__enumvalues = { + 0: 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_ENABLE', + 1: 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_DISABLE', +} +RDPCSPIPE_DPALT_DISABLE_TOGGLE_ENABLE = 0 +RDPCSPIPE_DPALT_DISABLE_TOGGLE_DISABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 1: 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_ENABLE', +} +RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_DISABLE = 0 +RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_ENABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_PIPE_FIFO_ERROR_MASK' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_PIPE_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCSPIPE_PIPE_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCSPIPE_PIPE_FIFO_ERROR_MASK_ENABLE', +} +RDPCSPIPE_PIPE_FIFO_ERROR_MASK_DISABLE = 0 +RDPCSPIPE_PIPE_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_PIPE_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK' +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCSPIPE_REG_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCSPIPE_REG_FIFO_ERROR_MASK_ENABLE', +} +RDPCSPIPE_REG_FIFO_ERROR_MASK_DISABLE = 0 +RDPCSPIPE_REG_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK' +RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK__enumvalues = { + 0: 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_DISABLE', + 1: 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_ENABLE', +} +RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_DISABLE = 0 +RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_ENABLE = 1 +RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PACK_MODE' +RDPCSPIPE_PACK_MODE__enumvalues = { + 0: 'TIGHT_PACK', + 1: 'LOOSE_PACK', +} +TIGHT_PACK = 0 +LOOSE_PACK = 1 +RDPCSPIPE_PACK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL' +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL__enumvalues = { + 0: 'RDPCSPIPE_PHY_CR_MUX_SEL_FOR_USB', + 1: 'RDPCSPIPE_PHY_CR_MUX_SEL_FOR_DC', +} +RDPCSPIPE_PHY_CR_MUX_SEL_FOR_USB = 0 +RDPCSPIPE_PHY_CR_MUX_SEL_FOR_DC = 1 +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL' +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL__enumvalues = { + 0: 'RDPCSPIPE_PHY_CR_PARA_SEL_JTAG', + 1: 'RDPCSPIPE_PHY_CR_PARA_SEL_CR', +} +RDPCSPIPE_PHY_CR_PARA_SEL_JTAG = 0 +RDPCSPIPE_PHY_CR_PARA_SEL_CR = 1 +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_REF_RANGE' +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_REF_RANGE__enumvalues = { + 0: 'RDPCSPIPE_PHY_REF_RANGE_0', + 1: 'RDPCSPIPE_PHY_REF_RANGE_1', + 2: 'RDPCSPIPE_PHY_REF_RANGE_2', + 3: 'RDPCSPIPE_PHY_REF_RANGE_3', + 4: 'RDPCSPIPE_PHY_REF_RANGE_4', + 5: 'RDPCSPIPE_PHY_REF_RANGE_5', + 6: 'RDPCSPIPE_PHY_REF_RANGE_6', + 7: 'RDPCSPIPE_PHY_REF_RANGE_7', +} +RDPCSPIPE_PHY_REF_RANGE_0 = 0 +RDPCSPIPE_PHY_REF_RANGE_1 = 1 +RDPCSPIPE_PHY_REF_RANGE_2 = 2 +RDPCSPIPE_PHY_REF_RANGE_3 = 3 +RDPCSPIPE_PHY_REF_RANGE_4 = 4 +RDPCSPIPE_PHY_REF_RANGE_5 = 5 +RDPCSPIPE_PHY_REF_RANGE_6 = 6 +RDPCSPIPE_PHY_REF_RANGE_7 = 7 +RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_REF_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE' +RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE__enumvalues = { + 0: 'RDPCSPIPE_SRAM_EXT_LD_NOT_DONE', + 1: 'RDPCSPIPE_SRAM_EXT_LD_DONE', +} +RDPCSPIPE_SRAM_EXT_LD_NOT_DONE = 0 +RDPCSPIPE_SRAM_EXT_LD_DONE = 1 +RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_INIT_DONE' +RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_INIT_DONE__enumvalues = { + 0: 'RDPCSPIPE_SRAM_INIT_NOT_DONE', + 1: 'RDPCSPIPE_SRAM_INIT_DONE', +} +RDPCSPIPE_SRAM_INIT_NOT_DONE = 0 +RDPCSPIPE_SRAM_INIT_DONE = 1 +RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_INIT_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV' +RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV1', + 1: 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV2', + 2: 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV3', + 3: 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV8', + 4: 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV16', +} +RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV1 = 0 +RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV2 = 1 +RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV3 = 2 +RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV8 = 3 +RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV16 = 4 +RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV' +RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV__enumvalues = { + 0: 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 1: 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 2: 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 3: 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', +} +RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0 = 0 +RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1 = 1 +RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2 = 2 +RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3 = 3 +RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV' +RDPCSPIPE_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV', + 1: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV2', + 2: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV4', + 3: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV8', + 4: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV3', + 5: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV5', + 6: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV6', + 7: 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV10', +} +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV = 0 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV2 = 1 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV4 = 2 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV8 = 3 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV3 = 4 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV5 = 5 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV6 = 6 +RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV10 = 7 +RDPCSPIPE_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL' +RDPCSPIPE_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_54', + 1: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_52', + 2: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_50', + 3: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_48', + 4: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_46', + 5: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_44', + 6: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_42', + 7: 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_40', +} +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_54 = 0 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_52 = 1 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_50 = 2 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_48 = 3 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_46 = 4 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_44 = 5 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_42 = 6 +RDPCSPIPE_PHY_DP_TX_TERM_CTRL_40 = 7 +RDPCSPIPE_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT' +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_NO_DETECT', + 1: 'RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_DETECT', +} +RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_NO_DETECT = 0 +RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_DETECT = 1 +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_RATE' +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_RATE__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_TX_RATE', + 1: 'RDPCSPIPE_PHY_DP_TX_RATE_DIV2', + 2: 'RDPCSPIPE_PHY_DP_TX_RATE_DIV4', +} +RDPCSPIPE_PHY_DP_TX_RATE = 0 +RDPCSPIPE_PHY_DP_TX_RATE_DIV2 = 1 +RDPCSPIPE_PHY_DP_TX_RATE_DIV4 = 2 +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH' +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH__enumvalues = { + 0: 'RDPCSPIPE_PHY_DP_TX_WIDTH_8', + 1: 'RDPCSPIPE_PHY_DP_TX_WIDTH_10', + 2: 'RDPCSPIPE_PHY_DP_TX_WIDTH_16', + 3: 'RDPCSPIPE_PHY_DP_TX_WIDTH_20', +} +RDPCSPIPE_PHY_DP_TX_WIDTH_8 = 0 +RDPCSPIPE_PHY_DP_TX_WIDTH_10 = 1 +RDPCSPIPE_PHY_DP_TX_WIDTH_16 = 2 +RDPCSPIPE_PHY_DP_TX_WIDTH_20 = 3 +RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE' +RDPCSPIPE_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE__enumvalues = { + 0: 'RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_UP', + 1: 'RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD', + 2: 'RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD_OFF', + 3: 'RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_DOWN', +} +RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_UP = 0 +RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD = 1 +RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD_OFF = 2 +RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_DOWN = 3 +RDPCSPIPE_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_IF_WIDTH' +RDPCSPIPE_PHY_IF_WIDTH__enumvalues = { + 0: 'PHY_IF_WIDTH_10BIT', + 1: 'PHY_IF_WIDTH_20BIT', + 2: 'PHY_IF_WIDTH_40BIT', + 3: 'PHY_IF_WIDTH_80BIT', +} +PHY_IF_WIDTH_10BIT = 0 +PHY_IF_WIDTH_20BIT = 1 +PHY_IF_WIDTH_40BIT = 2 +PHY_IF_WIDTH_80BIT = 3 +RDPCSPIPE_PHY_IF_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_RATE' +RDPCSPIPE_PHY_RATE__enumvalues = { + 0: 'PHY_DP_RATE_1P62', + 1: 'PHY_DP_RATE_2P7', + 2: 'PHY_DP_RATE_5P4', + 3: 'PHY_DP_RATE_8P1', + 4: 'PHY_DP_RATE_2P16', + 5: 'PHY_DP_RATE_2P43', + 6: 'PHY_DP_RATE_3P24', + 7: 'PHY_DP_RATE_4P32', + 8: 'PHY_DP_RATE_10P', + 9: 'PHY_DP_RATE_13P5', + 10: 'PHY_DP_RATE_20P', + 15: 'PHY_CUSTOM_RATE', +} +PHY_DP_RATE_1P62 = 0 +PHY_DP_RATE_2P7 = 1 +PHY_DP_RATE_5P4 = 2 +PHY_DP_RATE_8P1 = 3 +PHY_DP_RATE_2P16 = 4 +PHY_DP_RATE_2P43 = 5 +PHY_DP_RATE_3P24 = 6 +PHY_DP_RATE_4P32 = 7 +PHY_DP_RATE_10P = 8 +PHY_DP_RATE_13P5 = 9 +PHY_DP_RATE_20P = 10 +PHY_CUSTOM_RATE = 15 +RDPCSPIPE_PHY_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_PHY_REF_ALT_CLK_EN' +RDPCSPIPE_PHY_REF_ALT_CLK_EN__enumvalues = { + 0: 'RDPCSPIPE_PHY_REF_ALT_CLK_DISABLE', + 1: 'RDPCSPIPE_PHY_REF_ALT_CLK_ENABLE', +} +RDPCSPIPE_PHY_REF_ALT_CLK_DISABLE = 0 +RDPCSPIPE_PHY_REF_ALT_CLK_ENABLE = 1 +RDPCSPIPE_PHY_REF_ALT_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSPIPE_TEST_CLK_SEL' +RDPCSPIPE_TEST_CLK_SEL__enumvalues = { + 0: 'RDPCSPIPE_TEST_CLK_SEL_NONE', + 1: 'RDPCSPIPE_TEST_CLK_SEL_CFGCLK', + 2: 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 3: 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 4: 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 5: 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 6: 'RDPCSPIPE_TEST_CLK_SEL_SRAMCLK', + 7: 'RDPCSPIPE_TEST_CLK_SEL_EXT_CR_CLK', + 8: 'RDPCSPIPE_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 9: 'RDPCSPIPE_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 10: 'RDPCSPIPE_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 11: 'RDPCSPIPE_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 12: 'RDPCSPIPE_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 13: 'RDPCSPIPE_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 14: 'RDPCSPIPE_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 15: 'RDPCSPIPE_TEST_CLK_SEL_REF_DIG_FR_clk', + 16: 'RDPCSPIPE_TEST_CLK_SEL_dtb_out0', + 17: 'RDPCSPIPE_TEST_CLK_SEL_dtb_out1', +} +RDPCSPIPE_TEST_CLK_SEL_NONE = 0 +RDPCSPIPE_TEST_CLK_SEL_CFGCLK = 1 +RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS = 2 +RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS = 3 +RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4 = 4 +RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4 = 5 +RDPCSPIPE_TEST_CLK_SEL_SRAMCLK = 6 +RDPCSPIPE_TEST_CLK_SEL_EXT_CR_CLK = 7 +RDPCSPIPE_TEST_CLK_SEL_DP_TX0_WORD_CLK = 8 +RDPCSPIPE_TEST_CLK_SEL_DP_TX1_WORD_CLK = 9 +RDPCSPIPE_TEST_CLK_SEL_DP_TX2_WORD_CLK = 10 +RDPCSPIPE_TEST_CLK_SEL_DP_TX3_WORD_CLK = 11 +RDPCSPIPE_TEST_CLK_SEL_DP_MPLLB_DIV_CLK = 12 +RDPCSPIPE_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK = 13 +RDPCSPIPE_TEST_CLK_SEL_PHY_REF_DIG_CLK = 14 +RDPCSPIPE_TEST_CLK_SEL_REF_DIG_FR_clk = 15 +RDPCSPIPE_TEST_CLK_SEL_dtb_out0 = 16 +RDPCSPIPE_TEST_CLK_SEL_dtb_out1 = 17 +RDPCSPIPE_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_PIPE_CNTL_TX_LANE_PACK_FROM_MSB' +RDPCS_PIPE_CNTL_TX_LANE_PACK_FROM_MSB__enumvalues = { + 0: 'RDPCSPIPE_LANE_PACK_FROM_MSB_DISABLE', + 1: 'RDPCSPIPE_LANE_PACK_FROM_MSB_ENABLE', +} +RDPCSPIPE_LANE_PACK_FROM_MSB_DISABLE = 0 +RDPCSPIPE_LANE_PACK_FROM_MSB_ENABLE = 1 +RDPCS_PIPE_CNTL_TX_LANE_PACK_FROM_MSB = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_FORCE' +RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_FORCE__enumvalues = { + 0: 'RDPCSPIPE_MEM_PWR_NO_FORCE', + 1: 'RDPCSPIPE_MEM_PWR_LIGHT_SLEEP', + 2: 'RDPCSPIPE_MEM_PWR_DEEP_SLEEP', + 3: 'RDPCSPIPE_MEM_PWR_SHUT_DOWN', +} +RDPCSPIPE_MEM_PWR_NO_FORCE = 0 +RDPCSPIPE_MEM_PWR_LIGHT_SLEEP = 1 +RDPCSPIPE_MEM_PWR_DEEP_SLEEP = 2 +RDPCSPIPE_MEM_PWR_SHUT_DOWN = 3 +RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_FORCE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE' +RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE__enumvalues = { + 0: 'RDPCSPIPE_MEM_PWR_PWR_STATE_ON', + 1: 'RDPCSPIPE_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 2: 'RDPCSPIPE_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 3: 'RDPCSPIPE_MEM_PWR_PWR_STATE_SHUT_DOWN', +} +RDPCSPIPE_MEM_PWR_PWR_STATE_ON = 0 +RDPCSPIPE_MEM_PWR_PWR_STATE_LIGHT_SLEEP = 1 +RDPCSPIPE_MEM_PWR_PWR_STATE_DEEP_SLEEP = 2 +RDPCSPIPE_MEM_PWR_PWR_STATE_SHUT_DOWN = 3 +RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'RPDCSPIPE_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK' +RPDCSPIPE_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK__enumvalues = { + 0: 'RDPCSPIPE_LANE_BIT_ORDER_REVERSE_DISABLE', + 1: 'RDPCSPIPE_LANE_BIT_ORDER_REVERSE_ENABLE', +} +RDPCSPIPE_LANE_BIT_ORDER_REVERSE_DISABLE = 0 +RDPCSPIPE_LANE_BIT_ORDER_REVERSE_ENABLE = 1 +RPDCSPIPE_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK = ctypes.c_uint32 # enum + +# values for enumeration 'GDS_PERFCOUNT_SELECT' +GDS_PERFCOUNT_SELECT__enumvalues = { + 0: 'GDS_PERF_SEL_WR_COMP', + 1: 'GDS_PERF_SEL_WBUF_WR', + 2: 'GDS_PERF_SEL_SE0_NORET', + 3: 'GDS_PERF_SEL_SE0_RET', + 4: 'GDS_PERF_SEL_SE0_ORD_CNT', + 5: 'GDS_PERF_SEL_SE0_2COMP_REQ', + 6: 'GDS_PERF_SEL_SE0_ORD_WAVE_VALID', + 7: 'GDS_PERF_SEL_SE0_GDS_STALL_BY_ORD', + 8: 'GDS_PERF_SEL_SE0_GDS_WR_OP', + 9: 'GDS_PERF_SEL_SE0_GDS_RD_OP', + 10: 'GDS_PERF_SEL_SE0_GDS_ATOM_OP', + 11: 'GDS_PERF_SEL_SE0_GDS_REL_OP', + 12: 'GDS_PERF_SEL_SE0_GDS_CMPXCH_OP', + 13: 'GDS_PERF_SEL_SE0_GDS_BYTE_OP', + 14: 'GDS_PERF_SEL_SE0_GDS_SHORT_OP', + 15: 'GDS_PERF_SEL_SE1_NORET', + 16: 'GDS_PERF_SEL_SE1_RET', + 17: 'GDS_PERF_SEL_SE1_ORD_CNT', + 18: 'GDS_PERF_SEL_SE1_2COMP_REQ', + 19: 'GDS_PERF_SEL_SE1_ORD_WAVE_VALID', + 20: 'GDS_PERF_SEL_SE1_GDS_STALL_BY_ORD', + 21: 'GDS_PERF_SEL_SE1_GDS_WR_OP', + 22: 'GDS_PERF_SEL_SE1_GDS_RD_OP', + 23: 'GDS_PERF_SEL_SE1_GDS_ATOM_OP', + 24: 'GDS_PERF_SEL_SE1_GDS_REL_OP', + 25: 'GDS_PERF_SEL_SE1_GDS_CMPXCH_OP', + 26: 'GDS_PERF_SEL_SE1_GDS_BYTE_OP', + 27: 'GDS_PERF_SEL_SE1_GDS_SHORT_OP', + 28: 'GDS_PERF_SEL_SE2_NORET', + 29: 'GDS_PERF_SEL_SE2_RET', + 30: 'GDS_PERF_SEL_SE2_ORD_CNT', + 31: 'GDS_PERF_SEL_SE2_2COMP_REQ', + 32: 'GDS_PERF_SEL_SE2_ORD_WAVE_VALID', + 33: 'GDS_PERF_SEL_SE2_GDS_STALL_BY_ORD', + 34: 'GDS_PERF_SEL_SE2_GDS_WR_OP', + 35: 'GDS_PERF_SEL_SE2_GDS_RD_OP', + 36: 'GDS_PERF_SEL_SE2_GDS_ATOM_OP', + 37: 'GDS_PERF_SEL_SE2_GDS_REL_OP', + 38: 'GDS_PERF_SEL_SE2_GDS_CMPXCH_OP', + 39: 'GDS_PERF_SEL_SE2_GDS_BYTE_OP', + 40: 'GDS_PERF_SEL_SE2_GDS_SHORT_OP', + 41: 'GDS_PERF_SEL_SE3_NORET', + 42: 'GDS_PERF_SEL_SE3_RET', + 43: 'GDS_PERF_SEL_SE3_ORD_CNT', + 44: 'GDS_PERF_SEL_SE3_2COMP_REQ', + 45: 'GDS_PERF_SEL_SE3_ORD_WAVE_VALID', + 46: 'GDS_PERF_SEL_SE3_GDS_STALL_BY_ORD', + 47: 'GDS_PERF_SEL_SE3_GDS_WR_OP', + 48: 'GDS_PERF_SEL_SE3_GDS_RD_OP', + 49: 'GDS_PERF_SEL_SE3_GDS_ATOM_OP', + 50: 'GDS_PERF_SEL_SE3_GDS_REL_OP', + 51: 'GDS_PERF_SEL_SE3_GDS_CMPXCH_OP', + 52: 'GDS_PERF_SEL_SE3_GDS_BYTE_OP', + 53: 'GDS_PERF_SEL_SE3_GDS_SHORT_OP', + 54: 'GDS_PERF_SEL_SE4_NORET', + 55: 'GDS_PERF_SEL_SE4_RET', + 56: 'GDS_PERF_SEL_SE4_ORD_CNT', + 57: 'GDS_PERF_SEL_SE4_2COMP_REQ', + 58: 'GDS_PERF_SEL_SE4_ORD_WAVE_VALID', + 59: 'GDS_PERF_SEL_SE4_GDS_STALL_BY_ORD', + 60: 'GDS_PERF_SEL_SE4_GDS_WR_OP', + 61: 'GDS_PERF_SEL_SE4_GDS_RD_OP', + 62: 'GDS_PERF_SEL_SE4_GDS_ATOM_OP', + 63: 'GDS_PERF_SEL_SE4_GDS_REL_OP', + 64: 'GDS_PERF_SEL_SE4_GDS_CMPXCH_OP', + 65: 'GDS_PERF_SEL_SE4_GDS_BYTE_OP', + 66: 'GDS_PERF_SEL_SE4_GDS_SHORT_OP', + 67: 'GDS_PERF_SEL_SE5_NORET', + 68: 'GDS_PERF_SEL_SE5_RET', + 69: 'GDS_PERF_SEL_SE5_ORD_CNT', + 70: 'GDS_PERF_SEL_SE5_2COMP_REQ', + 71: 'GDS_PERF_SEL_SE5_ORD_WAVE_VALID', + 72: 'GDS_PERF_SEL_SE5_GDS_STALL_BY_ORD', + 73: 'GDS_PERF_SEL_SE5_GDS_WR_OP', + 74: 'GDS_PERF_SEL_SE5_GDS_RD_OP', + 75: 'GDS_PERF_SEL_SE5_GDS_ATOM_OP', + 76: 'GDS_PERF_SEL_SE5_GDS_REL_OP', + 77: 'GDS_PERF_SEL_SE5_GDS_CMPXCH_OP', + 78: 'GDS_PERF_SEL_SE5_GDS_BYTE_OP', + 79: 'GDS_PERF_SEL_SE5_GDS_SHORT_OP', + 80: 'GDS_PERF_SEL_SE6_NORET', + 81: 'GDS_PERF_SEL_SE6_RET', + 82: 'GDS_PERF_SEL_SE6_ORD_CNT', + 83: 'GDS_PERF_SEL_SE6_2COMP_REQ', + 84: 'GDS_PERF_SEL_SE6_ORD_WAVE_VALID', + 85: 'GDS_PERF_SEL_SE6_GDS_STALL_BY_ORD', + 86: 'GDS_PERF_SEL_SE6_GDS_WR_OP', + 87: 'GDS_PERF_SEL_SE6_GDS_RD_OP', + 88: 'GDS_PERF_SEL_SE6_GDS_ATOM_OP', + 89: 'GDS_PERF_SEL_SE6_GDS_REL_OP', + 90: 'GDS_PERF_SEL_SE6_GDS_CMPXCH_OP', + 91: 'GDS_PERF_SEL_SE6_GDS_BYTE_OP', + 92: 'GDS_PERF_SEL_SE6_GDS_SHORT_OP', + 93: 'GDS_PERF_SEL_SE7_NORET', + 94: 'GDS_PERF_SEL_SE7_RET', + 95: 'GDS_PERF_SEL_SE7_ORD_CNT', + 96: 'GDS_PERF_SEL_SE7_2COMP_REQ', + 97: 'GDS_PERF_SEL_SE7_ORD_WAVE_VALID', + 98: 'GDS_PERF_SEL_SE7_GDS_STALL_BY_ORD', + 99: 'GDS_PERF_SEL_SE7_GDS_WR_OP', + 100: 'GDS_PERF_SEL_SE7_GDS_RD_OP', + 101: 'GDS_PERF_SEL_SE7_GDS_ATOM_OP', + 102: 'GDS_PERF_SEL_SE7_GDS_REL_OP', + 103: 'GDS_PERF_SEL_SE7_GDS_CMPXCH_OP', + 104: 'GDS_PERF_SEL_SE7_GDS_BYTE_OP', + 105: 'GDS_PERF_SEL_SE7_GDS_SHORT_OP', + 106: 'GDS_PERF_SEL_GWS_RELEASED', + 107: 'GDS_PERF_SEL_GWS_BYPASS', +} +GDS_PERF_SEL_WR_COMP = 0 +GDS_PERF_SEL_WBUF_WR = 1 +GDS_PERF_SEL_SE0_NORET = 2 +GDS_PERF_SEL_SE0_RET = 3 +GDS_PERF_SEL_SE0_ORD_CNT = 4 +GDS_PERF_SEL_SE0_2COMP_REQ = 5 +GDS_PERF_SEL_SE0_ORD_WAVE_VALID = 6 +GDS_PERF_SEL_SE0_GDS_STALL_BY_ORD = 7 +GDS_PERF_SEL_SE0_GDS_WR_OP = 8 +GDS_PERF_SEL_SE0_GDS_RD_OP = 9 +GDS_PERF_SEL_SE0_GDS_ATOM_OP = 10 +GDS_PERF_SEL_SE0_GDS_REL_OP = 11 +GDS_PERF_SEL_SE0_GDS_CMPXCH_OP = 12 +GDS_PERF_SEL_SE0_GDS_BYTE_OP = 13 +GDS_PERF_SEL_SE0_GDS_SHORT_OP = 14 +GDS_PERF_SEL_SE1_NORET = 15 +GDS_PERF_SEL_SE1_RET = 16 +GDS_PERF_SEL_SE1_ORD_CNT = 17 +GDS_PERF_SEL_SE1_2COMP_REQ = 18 +GDS_PERF_SEL_SE1_ORD_WAVE_VALID = 19 +GDS_PERF_SEL_SE1_GDS_STALL_BY_ORD = 20 +GDS_PERF_SEL_SE1_GDS_WR_OP = 21 +GDS_PERF_SEL_SE1_GDS_RD_OP = 22 +GDS_PERF_SEL_SE1_GDS_ATOM_OP = 23 +GDS_PERF_SEL_SE1_GDS_REL_OP = 24 +GDS_PERF_SEL_SE1_GDS_CMPXCH_OP = 25 +GDS_PERF_SEL_SE1_GDS_BYTE_OP = 26 +GDS_PERF_SEL_SE1_GDS_SHORT_OP = 27 +GDS_PERF_SEL_SE2_NORET = 28 +GDS_PERF_SEL_SE2_RET = 29 +GDS_PERF_SEL_SE2_ORD_CNT = 30 +GDS_PERF_SEL_SE2_2COMP_REQ = 31 +GDS_PERF_SEL_SE2_ORD_WAVE_VALID = 32 +GDS_PERF_SEL_SE2_GDS_STALL_BY_ORD = 33 +GDS_PERF_SEL_SE2_GDS_WR_OP = 34 +GDS_PERF_SEL_SE2_GDS_RD_OP = 35 +GDS_PERF_SEL_SE2_GDS_ATOM_OP = 36 +GDS_PERF_SEL_SE2_GDS_REL_OP = 37 +GDS_PERF_SEL_SE2_GDS_CMPXCH_OP = 38 +GDS_PERF_SEL_SE2_GDS_BYTE_OP = 39 +GDS_PERF_SEL_SE2_GDS_SHORT_OP = 40 +GDS_PERF_SEL_SE3_NORET = 41 +GDS_PERF_SEL_SE3_RET = 42 +GDS_PERF_SEL_SE3_ORD_CNT = 43 +GDS_PERF_SEL_SE3_2COMP_REQ = 44 +GDS_PERF_SEL_SE3_ORD_WAVE_VALID = 45 +GDS_PERF_SEL_SE3_GDS_STALL_BY_ORD = 46 +GDS_PERF_SEL_SE3_GDS_WR_OP = 47 +GDS_PERF_SEL_SE3_GDS_RD_OP = 48 +GDS_PERF_SEL_SE3_GDS_ATOM_OP = 49 +GDS_PERF_SEL_SE3_GDS_REL_OP = 50 +GDS_PERF_SEL_SE3_GDS_CMPXCH_OP = 51 +GDS_PERF_SEL_SE3_GDS_BYTE_OP = 52 +GDS_PERF_SEL_SE3_GDS_SHORT_OP = 53 +GDS_PERF_SEL_SE4_NORET = 54 +GDS_PERF_SEL_SE4_RET = 55 +GDS_PERF_SEL_SE4_ORD_CNT = 56 +GDS_PERF_SEL_SE4_2COMP_REQ = 57 +GDS_PERF_SEL_SE4_ORD_WAVE_VALID = 58 +GDS_PERF_SEL_SE4_GDS_STALL_BY_ORD = 59 +GDS_PERF_SEL_SE4_GDS_WR_OP = 60 +GDS_PERF_SEL_SE4_GDS_RD_OP = 61 +GDS_PERF_SEL_SE4_GDS_ATOM_OP = 62 +GDS_PERF_SEL_SE4_GDS_REL_OP = 63 +GDS_PERF_SEL_SE4_GDS_CMPXCH_OP = 64 +GDS_PERF_SEL_SE4_GDS_BYTE_OP = 65 +GDS_PERF_SEL_SE4_GDS_SHORT_OP = 66 +GDS_PERF_SEL_SE5_NORET = 67 +GDS_PERF_SEL_SE5_RET = 68 +GDS_PERF_SEL_SE5_ORD_CNT = 69 +GDS_PERF_SEL_SE5_2COMP_REQ = 70 +GDS_PERF_SEL_SE5_ORD_WAVE_VALID = 71 +GDS_PERF_SEL_SE5_GDS_STALL_BY_ORD = 72 +GDS_PERF_SEL_SE5_GDS_WR_OP = 73 +GDS_PERF_SEL_SE5_GDS_RD_OP = 74 +GDS_PERF_SEL_SE5_GDS_ATOM_OP = 75 +GDS_PERF_SEL_SE5_GDS_REL_OP = 76 +GDS_PERF_SEL_SE5_GDS_CMPXCH_OP = 77 +GDS_PERF_SEL_SE5_GDS_BYTE_OP = 78 +GDS_PERF_SEL_SE5_GDS_SHORT_OP = 79 +GDS_PERF_SEL_SE6_NORET = 80 +GDS_PERF_SEL_SE6_RET = 81 +GDS_PERF_SEL_SE6_ORD_CNT = 82 +GDS_PERF_SEL_SE6_2COMP_REQ = 83 +GDS_PERF_SEL_SE6_ORD_WAVE_VALID = 84 +GDS_PERF_SEL_SE6_GDS_STALL_BY_ORD = 85 +GDS_PERF_SEL_SE6_GDS_WR_OP = 86 +GDS_PERF_SEL_SE6_GDS_RD_OP = 87 +GDS_PERF_SEL_SE6_GDS_ATOM_OP = 88 +GDS_PERF_SEL_SE6_GDS_REL_OP = 89 +GDS_PERF_SEL_SE6_GDS_CMPXCH_OP = 90 +GDS_PERF_SEL_SE6_GDS_BYTE_OP = 91 +GDS_PERF_SEL_SE6_GDS_SHORT_OP = 92 +GDS_PERF_SEL_SE7_NORET = 93 +GDS_PERF_SEL_SE7_RET = 94 +GDS_PERF_SEL_SE7_ORD_CNT = 95 +GDS_PERF_SEL_SE7_2COMP_REQ = 96 +GDS_PERF_SEL_SE7_ORD_WAVE_VALID = 97 +GDS_PERF_SEL_SE7_GDS_STALL_BY_ORD = 98 +GDS_PERF_SEL_SE7_GDS_WR_OP = 99 +GDS_PERF_SEL_SE7_GDS_RD_OP = 100 +GDS_PERF_SEL_SE7_GDS_ATOM_OP = 101 +GDS_PERF_SEL_SE7_GDS_REL_OP = 102 +GDS_PERF_SEL_SE7_GDS_CMPXCH_OP = 103 +GDS_PERF_SEL_SE7_GDS_BYTE_OP = 104 +GDS_PERF_SEL_SE7_GDS_SHORT_OP = 105 +GDS_PERF_SEL_GWS_RELEASED = 106 +GDS_PERF_SEL_GWS_BYPASS = 107 +GDS_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOp' +BlendOp__enumvalues = { + 0: 'BLEND_ZERO', + 1: 'BLEND_ONE', + 2: 'BLEND_SRC_COLOR', + 3: 'BLEND_ONE_MINUS_SRC_COLOR', + 4: 'BLEND_SRC_ALPHA', + 5: 'BLEND_ONE_MINUS_SRC_ALPHA', + 6: 'BLEND_DST_ALPHA', + 7: 'BLEND_ONE_MINUS_DST_ALPHA', + 8: 'BLEND_DST_COLOR', + 9: 'BLEND_ONE_MINUS_DST_COLOR', + 10: 'BLEND_SRC_ALPHA_SATURATE', + 11: 'BLEND_CONSTANT_COLOR', + 12: 'BLEND_ONE_MINUS_CONSTANT_COLOR', + 13: 'BLEND_SRC1_COLOR', + 14: 'BLEND_INV_SRC1_COLOR', + 15: 'BLEND_SRC1_ALPHA', + 16: 'BLEND_INV_SRC1_ALPHA', + 17: 'BLEND_CONSTANT_ALPHA', + 18: 'BLEND_ONE_MINUS_CONSTANT_ALPHA', +} +BLEND_ZERO = 0 +BLEND_ONE = 1 +BLEND_SRC_COLOR = 2 +BLEND_ONE_MINUS_SRC_COLOR = 3 +BLEND_SRC_ALPHA = 4 +BLEND_ONE_MINUS_SRC_ALPHA = 5 +BLEND_DST_ALPHA = 6 +BLEND_ONE_MINUS_DST_ALPHA = 7 +BLEND_DST_COLOR = 8 +BLEND_ONE_MINUS_DST_COLOR = 9 +BLEND_SRC_ALPHA_SATURATE = 10 +BLEND_CONSTANT_COLOR = 11 +BLEND_ONE_MINUS_CONSTANT_COLOR = 12 +BLEND_SRC1_COLOR = 13 +BLEND_INV_SRC1_COLOR = 14 +BLEND_SRC1_ALPHA = 15 +BLEND_INV_SRC1_ALPHA = 16 +BLEND_CONSTANT_ALPHA = 17 +BLEND_ONE_MINUS_CONSTANT_ALPHA = 18 +BlendOp = ctypes.c_uint32 # enum +GL__ZERO = BLEND_ZERO # macro +GL__ONE = BLEND_ONE # macro +GL__SRC_COLOR = BLEND_SRC_COLOR # macro +GL__ONE_MINUS_SRC_COLOR = BLEND_ONE_MINUS_SRC_COLOR # macro +GL__DST_COLOR = BLEND_DST_COLOR # macro +GL__ONE_MINUS_DST_COLOR = BLEND_ONE_MINUS_DST_COLOR # macro +GL__SRC_ALPHA = BLEND_SRC_ALPHA # macro +GL__ONE_MINUS_SRC_ALPHA = BLEND_ONE_MINUS_SRC_ALPHA # macro +GL__DST_ALPHA = BLEND_DST_ALPHA # macro +GL__ONE_MINUS_DST_ALPHA = BLEND_ONE_MINUS_DST_ALPHA # macro +GL__SRC_ALPHA_SATURATE = BLEND_SRC_ALPHA_SATURATE # macro +GL__CONSTANT_COLOR = BLEND_CONSTANT_COLOR # macro +GL__ONE_MINUS_CONSTANT_COLOR = BLEND_ONE_MINUS_CONSTANT_COLOR # macro +GL__CONSTANT_ALPHA = BLEND_CONSTANT_ALPHA # macro +GL__ONE_MINUS_CONSTANT_ALPHA = BLEND_ONE_MINUS_CONSTANT_ALPHA # macro + +# values for enumeration 'BlendOpt' +BlendOpt__enumvalues = { + 0: 'FORCE_OPT_AUTO', + 1: 'FORCE_OPT_DISABLE', + 2: 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 3: 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 4: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 5: 'FORCE_OPT_ENABLE_IF_SRC_A_1', + 6: 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', + 7: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', +} +FORCE_OPT_AUTO = 0 +FORCE_OPT_DISABLE = 1 +FORCE_OPT_ENABLE_IF_SRC_A_0 = 2 +FORCE_OPT_ENABLE_IF_SRC_RGB_0 = 3 +FORCE_OPT_ENABLE_IF_SRC_ARGB_0 = 4 +FORCE_OPT_ENABLE_IF_SRC_A_1 = 5 +FORCE_OPT_ENABLE_IF_SRC_RGB_1 = 6 +FORCE_OPT_ENABLE_IF_SRC_ARGB_1 = 7 +BlendOpt = ctypes.c_uint32 # enum + +# values for enumeration 'CBMode' +CBMode__enumvalues = { + 0: 'CB_DISABLE', + 1: 'CB_NORMAL', + 2: 'CB_ELIMINATE_FAST_CLEAR', + 3: 'CB_DCC_DECOMPRESS', + 4: 'CB_RESERVED', +} +CB_DISABLE = 0 +CB_NORMAL = 1 +CB_ELIMINATE_FAST_CLEAR = 2 +CB_DCC_DECOMPRESS = 3 +CB_RESERVED = 4 +CBMode = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfClearFilterSel' +CBPerfClearFilterSel__enumvalues = { + 0: 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 1: 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', +} +CB_PERF_CLEAR_FILTER_SEL_NONCLEAR = 0 +CB_PERF_CLEAR_FILTER_SEL_CLEAR = 1 +CBPerfClearFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfOpFilterSel' +CBPerfOpFilterSel__enumvalues = { + 0: 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 1: 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 2: 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 3: 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 4: 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 5: 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', +} +CB_PERF_OP_FILTER_SEL_WRITE_ONLY = 0 +CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION = 1 +CB_PERF_OP_FILTER_SEL_RESOLVE = 2 +CB_PERF_OP_FILTER_SEL_DECOMPRESS = 3 +CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS = 4 +CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR = 5 +CBPerfOpFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfSel' +CBPerfSel__enumvalues = { + 0: 'CB_PERF_SEL_NONE', + 1: 'CB_PERF_SEL_DRAWN_PIXEL', + 2: 'CB_PERF_SEL_DRAWN_QUAD', + 3: 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', + 4: 'CB_PERF_SEL_DRAWN_TILE', + 5: 'CB_PERF_SEL_FILTER_DRAWN_PIXEL', + 6: 'CB_PERF_SEL_FILTER_DRAWN_QUAD', + 7: 'CB_PERF_SEL_FILTER_DRAWN_QUAD_FRAGMENT', + 8: 'CB_PERF_SEL_FILTER_DRAWN_TILE', + 9: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_IN', + 10: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_OUT', + 11: 'CB_PERF_SEL_CC_DCC_COMPRESS_TID_IN', + 12: 'CB_PERF_SEL_CC_DCC_COMPRESS_TID_OUT', + 13: 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 14: 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 15: 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 16: 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 17: 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READY', + 18: 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB', + 19: 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY', + 20: 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB', + 21: 'CB_PERF_SEL_RESERVED_21', + 22: 'CB_PERF_SEL_RESERVED_22', + 23: 'CB_PERF_SEL_RESERVED_23', + 24: 'CB_PERF_SEL_RESERVED_24', + 25: 'CB_PERF_SEL_RESERVED_25', + 26: 'CB_PERF_SEL_RESERVED_26', + 27: 'CB_PERF_SEL_RESERVED_27', + 28: 'CB_PERF_SEL_RESERVED_28', + 29: 'CB_PERF_SEL_RESERVED_29', + 30: 'CB_PERF_SEL_CB_RMI_WRREQ_VALID_READY', + 31: 'CB_PERF_SEL_CB_RMI_WRREQ_VALID_READYB', + 32: 'CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READY', + 33: 'CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READYB', + 34: 'CB_PERF_SEL_CB_RMI_RDREQ_VALID_READY', + 35: 'CB_PERF_SEL_CB_RMI_RDREQ_VALID_READYB', + 36: 'CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READY', + 37: 'CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READYB', + 38: 'CB_PERF_SEL_RESERVED_38', + 39: 'CB_PERF_SEL_RESERVED_39', + 40: 'CB_PERF_SEL_RESERVED_40', + 41: 'CB_PERF_SEL_RESERVED_41', + 42: 'CB_PERF_SEL_RESERVED_42', + 43: 'CB_PERF_SEL_RESERVED_43', + 44: 'CB_PERF_SEL_RESERVED_44', + 45: 'CB_PERF_SEL_RESERVED_45', + 46: 'CB_PERF_SEL_RESERVED_46', + 47: 'CB_PERF_SEL_RESERVED_47', + 48: 'CB_PERF_SEL_RESERVED_48', + 49: 'CB_PERF_SEL_RESERVED_49', + 50: 'CB_PERF_SEL_STATIC_CLOCK_EN', + 51: 'CB_PERF_SEL_PERFMON_CLOCK_EN', + 52: 'CB_PERF_SEL_BLEND_CLOCK_EN', + 53: 'CB_PERF_SEL_COLOR_STORE_CLOCK_EN', + 54: 'CB_PERF_SEL_BACKEND_READ_CLOCK_EN', + 55: 'CB_PERF_SEL_GRBM_CLOCK_EN', + 56: 'CB_PERF_SEL_MEMARB_CLOCK_EN', + 57: 'CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN', + 58: 'CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN', + 59: 'CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN', + 60: 'CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN', + 61: 'CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN', + 62: 'CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN', + 63: 'CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN', + 64: 'CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN', + 65: 'CB_PERF_SEL_RESERVED_65', + 66: 'CB_PERF_SEL_RESERVED_66', + 67: 'CB_PERF_SEL_RESERVED_67', + 68: 'CB_PERF_SEL_RESERVED_68', + 69: 'CB_PERF_SEL_RESERVED_69', + 70: 'CB_PERF_SEL_RESERVED_70', + 71: 'CB_PERF_SEL_RESERVED_71', + 72: 'CB_PERF_SEL_RESERVED_72', + 73: 'CB_PERF_SEL_RESERVED_73', + 74: 'CB_PERF_SEL_RESERVED_74', + 75: 'CB_PERF_SEL_RESERVED_75', + 76: 'CB_PERF_SEL_RESERVED_76', + 77: 'CB_PERF_SEL_RESERVED_77', + 78: 'CB_PERF_SEL_RESERVED_78', + 79: 'CB_PERF_SEL_RESERVED_79', + 80: 'CB_PERF_SEL_RESERVED_80', + 81: 'CB_PERF_SEL_RESERVED_81', + 82: 'CB_PERF_SEL_RESERVED_82', + 83: 'CB_PERF_SEL_RESERVED_83', + 84: 'CB_PERF_SEL_RESERVED_84', + 85: 'CB_PERF_SEL_RESERVED_85', + 86: 'CB_PERF_SEL_RESERVED_86', + 87: 'CB_PERF_SEL_RESERVED_87', + 88: 'CB_PERF_SEL_RESERVED_88', + 89: 'CB_PERF_SEL_RESERVED_89', + 90: 'CB_PERF_SEL_RESERVED_90', + 91: 'CB_PERF_SEL_RESERVED_91', + 92: 'CB_PERF_SEL_RESERVED_92', + 93: 'CB_PERF_SEL_RESERVED_93', + 94: 'CB_PERF_SEL_RESERVED_94', + 95: 'CB_PERF_SEL_RESERVED_95', + 96: 'CB_PERF_SEL_RESERVED_96', + 97: 'CB_PERF_SEL_RESERVED_97', + 98: 'CB_PERF_SEL_RESERVED_98', + 99: 'CB_PERF_SEL_RESERVED_99', + 100: 'CB_PERF_SEL_CC_TAG_HIT', + 101: 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 102: 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', + 103: 'CB_PERF_SEL_CC_CACHE_SECTOR_HIT', + 104: 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 105: 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 106: 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 107: 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 108: 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 109: 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 110: 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 111: 'CB_PERF_SEL_CC_CACHE_STALL', + 112: 'CB_PERF_SEL_CC_CACHE_FLUSH', + 113: 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 114: 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 115: 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 116: 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 117: 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 118: 'CB_PERF_SEL_RESERVED_118', + 119: 'CB_PERF_SEL_RESERVED_119', + 120: 'CB_PERF_SEL_RESERVED_120', + 121: 'CB_PERF_SEL_RESERVED_121', + 122: 'CB_PERF_SEL_RESERVED_122', + 123: 'CB_PERF_SEL_RESERVED_123', + 124: 'CB_PERF_SEL_RESERVED_124', + 125: 'CB_PERF_SEL_RESERVED_125', + 126: 'CB_PERF_SEL_RESERVED_126', + 127: 'CB_PERF_SEL_RESERVED_127', + 128: 'CB_PERF_SEL_RESERVED_128', + 129: 'CB_PERF_SEL_RESERVED_129', + 130: 'CB_PERF_SEL_RESERVED_130', + 131: 'CB_PERF_SEL_RESERVED_131', + 132: 'CB_PERF_SEL_RESERVED_132', + 133: 'CB_PERF_SEL_RESERVED_133', + 134: 'CB_PERF_SEL_RESERVED_134', + 135: 'CB_PERF_SEL_RESERVED_135', + 136: 'CB_PERF_SEL_RESERVED_136', + 137: 'CB_PERF_SEL_RESERVED_137', + 138: 'CB_PERF_SEL_RESERVED_138', + 139: 'CB_PERF_SEL_RESERVED_139', + 140: 'CB_PERF_SEL_RESERVED_140', + 141: 'CB_PERF_SEL_RESERVED_141', + 142: 'CB_PERF_SEL_RESERVED_142', + 143: 'CB_PERF_SEL_RESERVED_143', + 144: 'CB_PERF_SEL_RESERVED_144', + 145: 'CB_PERF_SEL_RESERVED_145', + 146: 'CB_PERF_SEL_RESERVED_146', + 147: 'CB_PERF_SEL_RESERVED_147', + 148: 'CB_PERF_SEL_RESERVED_148', + 149: 'CB_PERF_SEL_RESERVED_149', + 150: 'CB_PERF_SEL_DCC_CACHE_PERF_HIT', + 151: 'CB_PERF_SEL_DCC_CACHE_TAG_MISS', + 152: 'CB_PERF_SEL_DCC_CACHE_SECTOR_MISS', + 153: 'CB_PERF_SEL_DCC_CACHE_REEVICTION_STALL', + 154: 'CB_PERF_SEL_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 155: 'CB_PERF_SEL_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 156: 'CB_PERF_SEL_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 157: 'CB_PERF_SEL_DCC_CACHE_READ_OUTPUT_STALL', + 158: 'CB_PERF_SEL_DCC_CACHE_WRITE_OUTPUT_STALL', + 159: 'CB_PERF_SEL_DCC_CACHE_ACK_OUTPUT_STALL', + 160: 'CB_PERF_SEL_DCC_CACHE_STALL', + 161: 'CB_PERF_SEL_DCC_CACHE_FLUSH', + 162: 'CB_PERF_SEL_DCC_CACHE_SECTORS_FLUSHED', + 163: 'CB_PERF_SEL_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 164: 'CB_PERF_SEL_DCC_CACHE_TAGS_FLUSHED', + 165: 'CB_PERF_SEL_RESERVED_165', + 166: 'CB_PERF_SEL_RESERVED_166', + 167: 'CB_PERF_SEL_RESERVED_167', + 168: 'CB_PERF_SEL_RESERVED_168', + 169: 'CB_PERF_SEL_RESERVED_169', + 170: 'CB_PERF_SEL_RESERVED_170', + 171: 'CB_PERF_SEL_RESERVED_171', + 172: 'CB_PERF_SEL_RESERVED_172', + 173: 'CB_PERF_SEL_RESERVED_173', + 174: 'CB_PERF_SEL_RESERVED_174', + 175: 'CB_PERF_SEL_RESERVED_175', + 176: 'CB_PERF_SEL_RESERVED_176', + 177: 'CB_PERF_SEL_RESERVED_177', + 178: 'CB_PERF_SEL_RESERVED_178', + 179: 'CB_PERF_SEL_RESERVED_179', + 180: 'CB_PERF_SEL_RESERVED_180', + 181: 'CB_PERF_SEL_RESERVED_181', + 182: 'CB_PERF_SEL_RESERVED_182', + 183: 'CB_PERF_SEL_RESERVED_183', + 184: 'CB_PERF_SEL_RESERVED_184', + 185: 'CB_PERF_SEL_RESERVED_185', + 186: 'CB_PERF_SEL_RESERVED_186', + 187: 'CB_PERF_SEL_RESERVED_187', + 188: 'CB_PERF_SEL_RESERVED_188', + 189: 'CB_PERF_SEL_RESERVED_189', + 190: 'CB_PERF_SEL_RESERVED_190', + 191: 'CB_PERF_SEL_RESERVED_191', + 192: 'CB_PERF_SEL_RESERVED_192', + 193: 'CB_PERF_SEL_RESERVED_193', + 194: 'CB_PERF_SEL_RESERVED_194', + 195: 'CB_PERF_SEL_RESERVED_195', + 196: 'CB_PERF_SEL_RESERVED_196', + 197: 'CB_PERF_SEL_RESERVED_197', + 198: 'CB_PERF_SEL_RESERVED_198', + 199: 'CB_PERF_SEL_RESERVED_199', + 200: 'CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 201: 'CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 202: 'CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED', + 203: 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 204: 'CB_PERF_SEL_BLEND_STALL_AT_OUTPUT', + 205: 'CB_PERF_SEL_RESERVED_205', + 206: 'CB_PERF_SEL_RESERVED_206', + 207: 'CB_PERF_SEL_RESERVED_207', + 208: 'CB_PERF_SEL_RESERVED_208', + 209: 'CB_PERF_SEL_RESERVED_209', + 210: 'CB_PERF_SEL_RESERVED_210', + 211: 'CB_PERF_SEL_RESERVED_211', + 212: 'CB_PERF_SEL_RESERVED_212', + 213: 'CB_PERF_SEL_RESERVED_213', + 214: 'CB_PERF_SEL_RESERVED_214', + 215: 'CB_PERF_SEL_RESERVED_215', + 216: 'CB_PERF_SEL_RESERVED_216', + 217: 'CB_PERF_SEL_RESERVED_217', + 218: 'CB_PERF_SEL_RESERVED_218', + 219: 'CB_PERF_SEL_RESERVED_219', + 220: 'CB_PERF_SEL_RESERVED_220', + 221: 'CB_PERF_SEL_RESERVED_221', + 222: 'CB_PERF_SEL_RESERVED_222', + 223: 'CB_PERF_SEL_RESERVED_223', + 224: 'CB_PERF_SEL_RESERVED_224', + 225: 'CB_PERF_SEL_RESERVED_225', + 226: 'CB_PERF_SEL_RESERVED_226', + 227: 'CB_PERF_SEL_RESERVED_227', + 228: 'CB_PERF_SEL_RESERVED_228', + 229: 'CB_PERF_SEL_RESERVED_229', + 230: 'CB_PERF_SEL_RESERVED_230', + 231: 'CB_PERF_SEL_RESERVED_231', + 232: 'CB_PERF_SEL_RESERVED_232', + 233: 'CB_PERF_SEL_RESERVED_233', + 234: 'CB_PERF_SEL_RESERVED_234', + 235: 'CB_PERF_SEL_RESERVED_235', + 236: 'CB_PERF_SEL_RESERVED_236', + 237: 'CB_PERF_SEL_RESERVED_237', + 238: 'CB_PERF_SEL_RESERVED_238', + 239: 'CB_PERF_SEL_RESERVED_239', + 240: 'CB_PERF_SEL_RESERVED_240', + 241: 'CB_PERF_SEL_RESERVED_241', + 242: 'CB_PERF_SEL_RESERVED_242', + 243: 'CB_PERF_SEL_RESERVED_243', + 244: 'CB_PERF_SEL_RESERVED_244', + 245: 'CB_PERF_SEL_RESERVED_245', + 246: 'CB_PERF_SEL_RESERVED_246', + 247: 'CB_PERF_SEL_RESERVED_247', + 248: 'CB_PERF_SEL_RESERVED_248', + 249: 'CB_PERF_SEL_RESERVED_249', + 250: 'CB_PERF_SEL_EVENT', + 251: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 252: 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 253: 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 254: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 255: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 256: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 257: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 258: 'CB_PERF_SEL_CC_SURFACE_SYNC', + 259: 'CB_PERF_SEL_RESERVED_259', + 260: 'CB_PERF_SEL_RESERVED_260', + 261: 'CB_PERF_SEL_RESERVED_261', + 262: 'CB_PERF_SEL_RESERVED_262', + 263: 'CB_PERF_SEL_RESERVED_263', + 264: 'CB_PERF_SEL_RESERVED_264', + 265: 'CB_PERF_SEL_RESERVED_265', + 266: 'CB_PERF_SEL_RESERVED_266', + 267: 'CB_PERF_SEL_RESERVED_267', + 268: 'CB_PERF_SEL_RESERVED_268', + 269: 'CB_PERF_SEL_RESERVED_269', + 270: 'CB_PERF_SEL_RESERVED_270', + 271: 'CB_PERF_SEL_RESERVED_271', + 272: 'CB_PERF_SEL_RESERVED_272', + 273: 'CB_PERF_SEL_RESERVED_273', + 274: 'CB_PERF_SEL_RESERVED_274', + 275: 'CB_PERF_SEL_RESERVED_275', + 276: 'CB_PERF_SEL_RESERVED_276', + 277: 'CB_PERF_SEL_RESERVED_277', + 278: 'CB_PERF_SEL_RESERVED_278', + 279: 'CB_PERF_SEL_RESERVED_279', + 280: 'CB_PERF_SEL_RESERVED_280', + 281: 'CB_PERF_SEL_RESERVED_281', + 282: 'CB_PERF_SEL_RESERVED_282', + 283: 'CB_PERF_SEL_RESERVED_283', + 284: 'CB_PERF_SEL_RESERVED_284', + 285: 'CB_PERF_SEL_RESERVED_285', + 286: 'CB_PERF_SEL_RESERVED_286', + 287: 'CB_PERF_SEL_RESERVED_287', + 288: 'CB_PERF_SEL_RESERVED_288', + 289: 'CB_PERF_SEL_RESERVED_289', + 290: 'CB_PERF_SEL_RESERVED_290', + 291: 'CB_PERF_SEL_RESERVED_291', + 292: 'CB_PERF_SEL_RESERVED_292', + 293: 'CB_PERF_SEL_RESERVED_293', + 294: 'CB_PERF_SEL_RESERVED_294', + 295: 'CB_PERF_SEL_RESERVED_295', + 296: 'CB_PERF_SEL_RESERVED_296', + 297: 'CB_PERF_SEL_RESERVED_297', + 298: 'CB_PERF_SEL_RESERVED_298', + 299: 'CB_PERF_SEL_RESERVED_299', + 300: 'CB_PERF_SEL_NACK_CC_READ', + 301: 'CB_PERF_SEL_NACK_CC_WRITE', + 302: 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 303: 'CB_PERF_SEL_RESERVED_303', + 304: 'CB_PERF_SEL_RESERVED_304', + 305: 'CB_PERF_SEL_RESERVED_305', + 306: 'CB_PERF_SEL_RESERVED_306', + 307: 'CB_PERF_SEL_RESERVED_307', + 308: 'CB_PERF_SEL_RESERVED_308', + 309: 'CB_PERF_SEL_RESERVED_309', + 310: 'CB_PERF_SEL_RESERVED_310', + 311: 'CB_PERF_SEL_RESERVED_311', + 312: 'CB_PERF_SEL_RESERVED_312', + 313: 'CB_PERF_SEL_RESERVED_313', + 314: 'CB_PERF_SEL_RESERVED_314', + 315: 'CB_PERF_SEL_RESERVED_315', + 316: 'CB_PERF_SEL_RESERVED_316', + 317: 'CB_PERF_SEL_RESERVED_317', + 318: 'CB_PERF_SEL_RESERVED_318', + 319: 'CB_PERF_SEL_RESERVED_319', + 320: 'CB_PERF_SEL_RESERVED_320', + 321: 'CB_PERF_SEL_RESERVED_321', + 322: 'CB_PERF_SEL_RESERVED_322', + 323: 'CB_PERF_SEL_RESERVED_323', + 324: 'CB_PERF_SEL_RESERVED_324', + 325: 'CB_PERF_SEL_RESERVED_325', + 326: 'CB_PERF_SEL_RESERVED_326', + 327: 'CB_PERF_SEL_RESERVED_327', + 328: 'CB_PERF_SEL_RESERVED_328', + 329: 'CB_PERF_SEL_RESERVED_329', + 330: 'CB_PERF_SEL_RESERVED_330', + 331: 'CB_PERF_SEL_RESERVED_331', + 332: 'CB_PERF_SEL_RESERVED_332', + 333: 'CB_PERF_SEL_RESERVED_333', + 334: 'CB_PERF_SEL_RESERVED_334', + 335: 'CB_PERF_SEL_RESERVED_335', + 336: 'CB_PERF_SEL_RESERVED_336', + 337: 'CB_PERF_SEL_RESERVED_337', + 338: 'CB_PERF_SEL_RESERVED_338', + 339: 'CB_PERF_SEL_RESERVED_339', + 340: 'CB_PERF_SEL_RESERVED_340', + 341: 'CB_PERF_SEL_RESERVED_341', + 342: 'CB_PERF_SEL_RESERVED_342', + 343: 'CB_PERF_SEL_RESERVED_343', + 344: 'CB_PERF_SEL_RESERVED_344', + 345: 'CB_PERF_SEL_RESERVED_345', + 346: 'CB_PERF_SEL_RESERVED_346', + 347: 'CB_PERF_SEL_RESERVED_347', + 348: 'CB_PERF_SEL_RESERVED_348', + 349: 'CB_PERF_SEL_RESERVED_349', + 350: 'CB_PERF_SEL_RESERVED_350', + 351: 'CB_PERF_SEL_RESERVED_351', + 352: 'CB_PERF_SEL_RESERVED_352', + 353: 'CB_PERF_SEL_RESERVED_353', + 354: 'CB_PERF_SEL_RESERVED_354', + 355: 'CB_PERF_SEL_RESERVED_355', + 356: 'CB_PERF_SEL_RESERVED_356', + 357: 'CB_PERF_SEL_RESERVED_357', + 358: 'CB_PERF_SEL_RESERVED_358', + 359: 'CB_PERF_SEL_RESERVED_359', + 360: 'CB_PERF_SEL_RESERVED_360', + 361: 'CB_PERF_SEL_RESERVED_361', + 362: 'CB_PERF_SEL_RESERVED_362', + 363: 'CB_PERF_SEL_RESERVED_363', + 364: 'CB_PERF_SEL_RESERVED_364', + 365: 'CB_PERF_SEL_RESERVED_365', + 366: 'CB_PERF_SEL_RESERVED_366', + 367: 'CB_PERF_SEL_RESERVED_367', + 368: 'CB_PERF_SEL_RESERVED_368', + 369: 'CB_PERF_SEL_RESERVED_369', + 370: 'CB_PERF_SEL_RESERVED_370', + 371: 'CB_PERF_SEL_RESERVED_371', + 372: 'CB_PERF_SEL_RESERVED_372', + 373: 'CB_PERF_SEL_RESERVED_373', + 374: 'CB_PERF_SEL_RESERVED_374', + 375: 'CB_PERF_SEL_RESERVED_375', + 376: 'CB_PERF_SEL_RESERVED_376', + 377: 'CB_PERF_SEL_RESERVED_377', + 378: 'CB_PERF_SEL_RESERVED_378', + 379: 'CB_PERF_SEL_RESERVED_379', + 380: 'CB_PERF_SEL_RESERVED_380', + 381: 'CB_PERF_SEL_RESERVED_381', + 382: 'CB_PERF_SEL_RESERVED_382', + 383: 'CB_PERF_SEL_RESERVED_383', + 384: 'CB_PERF_SEL_RESERVED_384', + 385: 'CB_PERF_SEL_RESERVED_385', + 386: 'CB_PERF_SEL_RESERVED_386', + 387: 'CB_PERF_SEL_RESERVED_387', + 388: 'CB_PERF_SEL_RESERVED_388', + 389: 'CB_PERF_SEL_RESERVED_389', + 390: 'CB_PERF_SEL_RESERVED_390', + 391: 'CB_PERF_SEL_RESERVED_391', + 392: 'CB_PERF_SEL_RESERVED_392', + 393: 'CB_PERF_SEL_RESERVED_393', + 394: 'CB_PERF_SEL_RESERVED_394', + 395: 'CB_PERF_SEL_RESERVED_395', + 396: 'CB_PERF_SEL_RESERVED_396', + 397: 'CB_PERF_SEL_RESERVED_397', + 398: 'CB_PERF_SEL_RESERVED_398', + 399: 'CB_PERF_SEL_RESERVED_399', + 400: 'CB_PERF_SEL_RESERVED_400', + 401: 'CB_PERF_SEL_RESERVED_401', + 402: 'CB_PERF_SEL_RESERVED_402', + 403: 'CB_PERF_SEL_RESERVED_403', + 404: 'CB_PERF_SEL_RESERVED_404', + 405: 'CB_PERF_SEL_RESERVED_405', + 406: 'CB_PERF_SEL_RESERVED_406', + 407: 'CB_PERF_SEL_RESERVED_407', + 408: 'CB_PERF_SEL_RESERVED_408', + 409: 'CB_PERF_SEL_RESERVED_409', + 410: 'CB_PERF_SEL_RESERVED_410', + 411: 'CB_PERF_SEL_RESERVED_411', + 412: 'CB_PERF_SEL_RESERVED_412', + 413: 'CB_PERF_SEL_RESERVED_413', + 414: 'CB_PERF_SEL_RESERVED_414', + 415: 'CB_PERF_SEL_RESERVED_415', + 416: 'CB_PERF_SEL_RESERVED_416', + 417: 'CB_PERF_SEL_RESERVED_417', + 418: 'CB_PERF_SEL_RESERVED_418', + 419: 'CB_PERF_SEL_RESERVED_419', + 420: 'CB_PERF_SEL_RESERVED_420', + 421: 'CB_PERF_SEL_RESERVED_421', + 422: 'CB_PERF_SEL_RESERVED_422', + 423: 'CB_PERF_SEL_RESERVED_423', + 424: 'CB_PERF_SEL_RESERVED_424', + 425: 'CB_PERF_SEL_RESERVED_425', + 426: 'CB_PERF_SEL_RESERVED_426', + 427: 'CB_PERF_SEL_RESERVED_427', + 428: 'CB_PERF_SEL_RESERVED_428', + 429: 'CB_PERF_SEL_RESERVED_429', + 430: 'CB_PERF_SEL_RESERVED_430', + 431: 'CB_PERF_SEL_RESERVED_431', + 432: 'CB_PERF_SEL_RESERVED_432', + 433: 'CB_PERF_SEL_RESERVED_433', + 434: 'CB_PERF_SEL_RESERVED_434', + 435: 'CB_PERF_SEL_RESERVED_435', + 436: 'CB_PERF_SEL_RESERVED_436', + 437: 'CB_PERF_SEL_RESERVED_437', + 438: 'CB_PERF_SEL_RESERVED_438', + 439: 'CB_PERF_SEL_RESERVED_439', + 440: 'CB_PERF_SEL_RESERVED_440', + 441: 'CB_PERF_SEL_RESERVED_441', + 442: 'CB_PERF_SEL_RESERVED_442', + 443: 'CB_PERF_SEL_RESERVED_443', + 444: 'CB_PERF_SEL_RESERVED_444', + 445: 'CB_PERF_SEL_RESERVED_445', + 446: 'CB_PERF_SEL_RESERVED_446', + 447: 'CB_PERF_SEL_RESERVED_447', + 448: 'CB_PERF_SEL_RESERVED_448', + 449: 'CB_PERF_SEL_RESERVED_449', + 450: 'CB_PERF_SEL_RESERVED_450', + 451: 'CB_PERF_SEL_RESERVED_451', + 452: 'CB_PERF_SEL_RESERVED_452', + 453: 'CB_PERF_SEL_RESERVED_453', + 454: 'CB_PERF_SEL_RESERVED_454', + 455: 'CB_PERF_SEL_RESERVED_455', + 456: 'CB_PERF_SEL_RESERVED_456', + 457: 'CB_PERF_SEL_RESERVED_457', + 458: 'CB_PERF_SEL_RESERVED_458', + 459: 'CB_PERF_SEL_RESERVED_459', + 460: 'CB_PERF_SEL_RESERVED_460', + 461: 'CB_PERF_SEL_RESERVED_461', + 462: 'CB_PERF_SEL_RESERVED_462', + 463: 'CB_PERF_SEL_RESERVED_463', + 464: 'CB_PERF_SEL_RESERVED_464', + 465: 'CB_PERF_SEL_RESERVED_465', +} +CB_PERF_SEL_NONE = 0 +CB_PERF_SEL_DRAWN_PIXEL = 1 +CB_PERF_SEL_DRAWN_QUAD = 2 +CB_PERF_SEL_DRAWN_QUAD_FRAGMENT = 3 +CB_PERF_SEL_DRAWN_TILE = 4 +CB_PERF_SEL_FILTER_DRAWN_PIXEL = 5 +CB_PERF_SEL_FILTER_DRAWN_QUAD = 6 +CB_PERF_SEL_FILTER_DRAWN_QUAD_FRAGMENT = 7 +CB_PERF_SEL_FILTER_DRAWN_TILE = 8 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_IN = 9 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_OUT = 10 +CB_PERF_SEL_CC_DCC_COMPRESS_TID_IN = 11 +CB_PERF_SEL_CC_DCC_COMPRESS_TID_OUT = 12 +CB_PERF_SEL_CC_MC_WRITE_REQUEST = 13 +CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT = 14 +CB_PERF_SEL_CC_MC_READ_REQUEST = 15 +CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT = 16 +CB_PERF_SEL_DB_CB_EXPORT_VALID_READY = 17 +CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB = 18 +CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY = 19 +CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB = 20 +CB_PERF_SEL_RESERVED_21 = 21 +CB_PERF_SEL_RESERVED_22 = 22 +CB_PERF_SEL_RESERVED_23 = 23 +CB_PERF_SEL_RESERVED_24 = 24 +CB_PERF_SEL_RESERVED_25 = 25 +CB_PERF_SEL_RESERVED_26 = 26 +CB_PERF_SEL_RESERVED_27 = 27 +CB_PERF_SEL_RESERVED_28 = 28 +CB_PERF_SEL_RESERVED_29 = 29 +CB_PERF_SEL_CB_RMI_WRREQ_VALID_READY = 30 +CB_PERF_SEL_CB_RMI_WRREQ_VALID_READYB = 31 +CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READY = 32 +CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READYB = 33 +CB_PERF_SEL_CB_RMI_RDREQ_VALID_READY = 34 +CB_PERF_SEL_CB_RMI_RDREQ_VALID_READYB = 35 +CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READY = 36 +CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READYB = 37 +CB_PERF_SEL_RESERVED_38 = 38 +CB_PERF_SEL_RESERVED_39 = 39 +CB_PERF_SEL_RESERVED_40 = 40 +CB_PERF_SEL_RESERVED_41 = 41 +CB_PERF_SEL_RESERVED_42 = 42 +CB_PERF_SEL_RESERVED_43 = 43 +CB_PERF_SEL_RESERVED_44 = 44 +CB_PERF_SEL_RESERVED_45 = 45 +CB_PERF_SEL_RESERVED_46 = 46 +CB_PERF_SEL_RESERVED_47 = 47 +CB_PERF_SEL_RESERVED_48 = 48 +CB_PERF_SEL_RESERVED_49 = 49 +CB_PERF_SEL_STATIC_CLOCK_EN = 50 +CB_PERF_SEL_PERFMON_CLOCK_EN = 51 +CB_PERF_SEL_BLEND_CLOCK_EN = 52 +CB_PERF_SEL_COLOR_STORE_CLOCK_EN = 53 +CB_PERF_SEL_BACKEND_READ_CLOCK_EN = 54 +CB_PERF_SEL_GRBM_CLOCK_EN = 55 +CB_PERF_SEL_MEMARB_CLOCK_EN = 56 +CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN = 57 +CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN = 58 +CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN = 59 +CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN = 60 +CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN = 61 +CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN = 62 +CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN = 63 +CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN = 64 +CB_PERF_SEL_RESERVED_65 = 65 +CB_PERF_SEL_RESERVED_66 = 66 +CB_PERF_SEL_RESERVED_67 = 67 +CB_PERF_SEL_RESERVED_68 = 68 +CB_PERF_SEL_RESERVED_69 = 69 +CB_PERF_SEL_RESERVED_70 = 70 +CB_PERF_SEL_RESERVED_71 = 71 +CB_PERF_SEL_RESERVED_72 = 72 +CB_PERF_SEL_RESERVED_73 = 73 +CB_PERF_SEL_RESERVED_74 = 74 +CB_PERF_SEL_RESERVED_75 = 75 +CB_PERF_SEL_RESERVED_76 = 76 +CB_PERF_SEL_RESERVED_77 = 77 +CB_PERF_SEL_RESERVED_78 = 78 +CB_PERF_SEL_RESERVED_79 = 79 +CB_PERF_SEL_RESERVED_80 = 80 +CB_PERF_SEL_RESERVED_81 = 81 +CB_PERF_SEL_RESERVED_82 = 82 +CB_PERF_SEL_RESERVED_83 = 83 +CB_PERF_SEL_RESERVED_84 = 84 +CB_PERF_SEL_RESERVED_85 = 85 +CB_PERF_SEL_RESERVED_86 = 86 +CB_PERF_SEL_RESERVED_87 = 87 +CB_PERF_SEL_RESERVED_88 = 88 +CB_PERF_SEL_RESERVED_89 = 89 +CB_PERF_SEL_RESERVED_90 = 90 +CB_PERF_SEL_RESERVED_91 = 91 +CB_PERF_SEL_RESERVED_92 = 92 +CB_PERF_SEL_RESERVED_93 = 93 +CB_PERF_SEL_RESERVED_94 = 94 +CB_PERF_SEL_RESERVED_95 = 95 +CB_PERF_SEL_RESERVED_96 = 96 +CB_PERF_SEL_RESERVED_97 = 97 +CB_PERF_SEL_RESERVED_98 = 98 +CB_PERF_SEL_RESERVED_99 = 99 +CB_PERF_SEL_CC_TAG_HIT = 100 +CB_PERF_SEL_CC_CACHE_TAG_MISS = 101 +CB_PERF_SEL_CC_CACHE_SECTOR_MISS = 102 +CB_PERF_SEL_CC_CACHE_SECTOR_HIT = 103 +CB_PERF_SEL_CC_CACHE_REEVICTION_STALL = 104 +CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 105 +CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL = 106 +CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 107 +CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL = 108 +CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL = 109 +CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL = 110 +CB_PERF_SEL_CC_CACHE_STALL = 111 +CB_PERF_SEL_CC_CACHE_FLUSH = 112 +CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED = 113 +CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION = 114 +CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED = 115 +CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED = 116 +CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC = 117 +CB_PERF_SEL_RESERVED_118 = 118 +CB_PERF_SEL_RESERVED_119 = 119 +CB_PERF_SEL_RESERVED_120 = 120 +CB_PERF_SEL_RESERVED_121 = 121 +CB_PERF_SEL_RESERVED_122 = 122 +CB_PERF_SEL_RESERVED_123 = 123 +CB_PERF_SEL_RESERVED_124 = 124 +CB_PERF_SEL_RESERVED_125 = 125 +CB_PERF_SEL_RESERVED_126 = 126 +CB_PERF_SEL_RESERVED_127 = 127 +CB_PERF_SEL_RESERVED_128 = 128 +CB_PERF_SEL_RESERVED_129 = 129 +CB_PERF_SEL_RESERVED_130 = 130 +CB_PERF_SEL_RESERVED_131 = 131 +CB_PERF_SEL_RESERVED_132 = 132 +CB_PERF_SEL_RESERVED_133 = 133 +CB_PERF_SEL_RESERVED_134 = 134 +CB_PERF_SEL_RESERVED_135 = 135 +CB_PERF_SEL_RESERVED_136 = 136 +CB_PERF_SEL_RESERVED_137 = 137 +CB_PERF_SEL_RESERVED_138 = 138 +CB_PERF_SEL_RESERVED_139 = 139 +CB_PERF_SEL_RESERVED_140 = 140 +CB_PERF_SEL_RESERVED_141 = 141 +CB_PERF_SEL_RESERVED_142 = 142 +CB_PERF_SEL_RESERVED_143 = 143 +CB_PERF_SEL_RESERVED_144 = 144 +CB_PERF_SEL_RESERVED_145 = 145 +CB_PERF_SEL_RESERVED_146 = 146 +CB_PERF_SEL_RESERVED_147 = 147 +CB_PERF_SEL_RESERVED_148 = 148 +CB_PERF_SEL_RESERVED_149 = 149 +CB_PERF_SEL_DCC_CACHE_PERF_HIT = 150 +CB_PERF_SEL_DCC_CACHE_TAG_MISS = 151 +CB_PERF_SEL_DCC_CACHE_SECTOR_MISS = 152 +CB_PERF_SEL_DCC_CACHE_REEVICTION_STALL = 153 +CB_PERF_SEL_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 154 +CB_PERF_SEL_DCC_CACHE_REPLACE_PENDING_EVICT_STALL = 155 +CB_PERF_SEL_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 156 +CB_PERF_SEL_DCC_CACHE_READ_OUTPUT_STALL = 157 +CB_PERF_SEL_DCC_CACHE_WRITE_OUTPUT_STALL = 158 +CB_PERF_SEL_DCC_CACHE_ACK_OUTPUT_STALL = 159 +CB_PERF_SEL_DCC_CACHE_STALL = 160 +CB_PERF_SEL_DCC_CACHE_FLUSH = 161 +CB_PERF_SEL_DCC_CACHE_SECTORS_FLUSHED = 162 +CB_PERF_SEL_DCC_CACHE_DIRTY_SECTORS_FLUSHED = 163 +CB_PERF_SEL_DCC_CACHE_TAGS_FLUSHED = 164 +CB_PERF_SEL_RESERVED_165 = 165 +CB_PERF_SEL_RESERVED_166 = 166 +CB_PERF_SEL_RESERVED_167 = 167 +CB_PERF_SEL_RESERVED_168 = 168 +CB_PERF_SEL_RESERVED_169 = 169 +CB_PERF_SEL_RESERVED_170 = 170 +CB_PERF_SEL_RESERVED_171 = 171 +CB_PERF_SEL_RESERVED_172 = 172 +CB_PERF_SEL_RESERVED_173 = 173 +CB_PERF_SEL_RESERVED_174 = 174 +CB_PERF_SEL_RESERVED_175 = 175 +CB_PERF_SEL_RESERVED_176 = 176 +CB_PERF_SEL_RESERVED_177 = 177 +CB_PERF_SEL_RESERVED_178 = 178 +CB_PERF_SEL_RESERVED_179 = 179 +CB_PERF_SEL_RESERVED_180 = 180 +CB_PERF_SEL_RESERVED_181 = 181 +CB_PERF_SEL_RESERVED_182 = 182 +CB_PERF_SEL_RESERVED_183 = 183 +CB_PERF_SEL_RESERVED_184 = 184 +CB_PERF_SEL_RESERVED_185 = 185 +CB_PERF_SEL_RESERVED_186 = 186 +CB_PERF_SEL_RESERVED_187 = 187 +CB_PERF_SEL_RESERVED_188 = 188 +CB_PERF_SEL_RESERVED_189 = 189 +CB_PERF_SEL_RESERVED_190 = 190 +CB_PERF_SEL_RESERVED_191 = 191 +CB_PERF_SEL_RESERVED_192 = 192 +CB_PERF_SEL_RESERVED_193 = 193 +CB_PERF_SEL_RESERVED_194 = 194 +CB_PERF_SEL_RESERVED_195 = 195 +CB_PERF_SEL_RESERVED_196 = 196 +CB_PERF_SEL_RESERVED_197 = 197 +CB_PERF_SEL_RESERVED_198 = 198 +CB_PERF_SEL_RESERVED_199 = 199 +CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED = 200 +CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED = 201 +CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED = 202 +CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST = 203 +CB_PERF_SEL_BLEND_STALL_AT_OUTPUT = 204 +CB_PERF_SEL_RESERVED_205 = 205 +CB_PERF_SEL_RESERVED_206 = 206 +CB_PERF_SEL_RESERVED_207 = 207 +CB_PERF_SEL_RESERVED_208 = 208 +CB_PERF_SEL_RESERVED_209 = 209 +CB_PERF_SEL_RESERVED_210 = 210 +CB_PERF_SEL_RESERVED_211 = 211 +CB_PERF_SEL_RESERVED_212 = 212 +CB_PERF_SEL_RESERVED_213 = 213 +CB_PERF_SEL_RESERVED_214 = 214 +CB_PERF_SEL_RESERVED_215 = 215 +CB_PERF_SEL_RESERVED_216 = 216 +CB_PERF_SEL_RESERVED_217 = 217 +CB_PERF_SEL_RESERVED_218 = 218 +CB_PERF_SEL_RESERVED_219 = 219 +CB_PERF_SEL_RESERVED_220 = 220 +CB_PERF_SEL_RESERVED_221 = 221 +CB_PERF_SEL_RESERVED_222 = 222 +CB_PERF_SEL_RESERVED_223 = 223 +CB_PERF_SEL_RESERVED_224 = 224 +CB_PERF_SEL_RESERVED_225 = 225 +CB_PERF_SEL_RESERVED_226 = 226 +CB_PERF_SEL_RESERVED_227 = 227 +CB_PERF_SEL_RESERVED_228 = 228 +CB_PERF_SEL_RESERVED_229 = 229 +CB_PERF_SEL_RESERVED_230 = 230 +CB_PERF_SEL_RESERVED_231 = 231 +CB_PERF_SEL_RESERVED_232 = 232 +CB_PERF_SEL_RESERVED_233 = 233 +CB_PERF_SEL_RESERVED_234 = 234 +CB_PERF_SEL_RESERVED_235 = 235 +CB_PERF_SEL_RESERVED_236 = 236 +CB_PERF_SEL_RESERVED_237 = 237 +CB_PERF_SEL_RESERVED_238 = 238 +CB_PERF_SEL_RESERVED_239 = 239 +CB_PERF_SEL_RESERVED_240 = 240 +CB_PERF_SEL_RESERVED_241 = 241 +CB_PERF_SEL_RESERVED_242 = 242 +CB_PERF_SEL_RESERVED_243 = 243 +CB_PERF_SEL_RESERVED_244 = 244 +CB_PERF_SEL_RESERVED_245 = 245 +CB_PERF_SEL_RESERVED_246 = 246 +CB_PERF_SEL_RESERVED_247 = 247 +CB_PERF_SEL_RESERVED_248 = 248 +CB_PERF_SEL_RESERVED_249 = 249 +CB_PERF_SEL_EVENT = 250 +CB_PERF_SEL_EVENT_CACHE_FLUSH_TS = 251 +CB_PERF_SEL_EVENT_CONTEXT_DONE = 252 +CB_PERF_SEL_EVENT_CACHE_FLUSH = 253 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT = 254 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT = 255 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS = 256 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META = 257 +CB_PERF_SEL_CC_SURFACE_SYNC = 258 +CB_PERF_SEL_RESERVED_259 = 259 +CB_PERF_SEL_RESERVED_260 = 260 +CB_PERF_SEL_RESERVED_261 = 261 +CB_PERF_SEL_RESERVED_262 = 262 +CB_PERF_SEL_RESERVED_263 = 263 +CB_PERF_SEL_RESERVED_264 = 264 +CB_PERF_SEL_RESERVED_265 = 265 +CB_PERF_SEL_RESERVED_266 = 266 +CB_PERF_SEL_RESERVED_267 = 267 +CB_PERF_SEL_RESERVED_268 = 268 +CB_PERF_SEL_RESERVED_269 = 269 +CB_PERF_SEL_RESERVED_270 = 270 +CB_PERF_SEL_RESERVED_271 = 271 +CB_PERF_SEL_RESERVED_272 = 272 +CB_PERF_SEL_RESERVED_273 = 273 +CB_PERF_SEL_RESERVED_274 = 274 +CB_PERF_SEL_RESERVED_275 = 275 +CB_PERF_SEL_RESERVED_276 = 276 +CB_PERF_SEL_RESERVED_277 = 277 +CB_PERF_SEL_RESERVED_278 = 278 +CB_PERF_SEL_RESERVED_279 = 279 +CB_PERF_SEL_RESERVED_280 = 280 +CB_PERF_SEL_RESERVED_281 = 281 +CB_PERF_SEL_RESERVED_282 = 282 +CB_PERF_SEL_RESERVED_283 = 283 +CB_PERF_SEL_RESERVED_284 = 284 +CB_PERF_SEL_RESERVED_285 = 285 +CB_PERF_SEL_RESERVED_286 = 286 +CB_PERF_SEL_RESERVED_287 = 287 +CB_PERF_SEL_RESERVED_288 = 288 +CB_PERF_SEL_RESERVED_289 = 289 +CB_PERF_SEL_RESERVED_290 = 290 +CB_PERF_SEL_RESERVED_291 = 291 +CB_PERF_SEL_RESERVED_292 = 292 +CB_PERF_SEL_RESERVED_293 = 293 +CB_PERF_SEL_RESERVED_294 = 294 +CB_PERF_SEL_RESERVED_295 = 295 +CB_PERF_SEL_RESERVED_296 = 296 +CB_PERF_SEL_RESERVED_297 = 297 +CB_PERF_SEL_RESERVED_298 = 298 +CB_PERF_SEL_RESERVED_299 = 299 +CB_PERF_SEL_NACK_CC_READ = 300 +CB_PERF_SEL_NACK_CC_WRITE = 301 +CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT = 302 +CB_PERF_SEL_RESERVED_303 = 303 +CB_PERF_SEL_RESERVED_304 = 304 +CB_PERF_SEL_RESERVED_305 = 305 +CB_PERF_SEL_RESERVED_306 = 306 +CB_PERF_SEL_RESERVED_307 = 307 +CB_PERF_SEL_RESERVED_308 = 308 +CB_PERF_SEL_RESERVED_309 = 309 +CB_PERF_SEL_RESERVED_310 = 310 +CB_PERF_SEL_RESERVED_311 = 311 +CB_PERF_SEL_RESERVED_312 = 312 +CB_PERF_SEL_RESERVED_313 = 313 +CB_PERF_SEL_RESERVED_314 = 314 +CB_PERF_SEL_RESERVED_315 = 315 +CB_PERF_SEL_RESERVED_316 = 316 +CB_PERF_SEL_RESERVED_317 = 317 +CB_PERF_SEL_RESERVED_318 = 318 +CB_PERF_SEL_RESERVED_319 = 319 +CB_PERF_SEL_RESERVED_320 = 320 +CB_PERF_SEL_RESERVED_321 = 321 +CB_PERF_SEL_RESERVED_322 = 322 +CB_PERF_SEL_RESERVED_323 = 323 +CB_PERF_SEL_RESERVED_324 = 324 +CB_PERF_SEL_RESERVED_325 = 325 +CB_PERF_SEL_RESERVED_326 = 326 +CB_PERF_SEL_RESERVED_327 = 327 +CB_PERF_SEL_RESERVED_328 = 328 +CB_PERF_SEL_RESERVED_329 = 329 +CB_PERF_SEL_RESERVED_330 = 330 +CB_PERF_SEL_RESERVED_331 = 331 +CB_PERF_SEL_RESERVED_332 = 332 +CB_PERF_SEL_RESERVED_333 = 333 +CB_PERF_SEL_RESERVED_334 = 334 +CB_PERF_SEL_RESERVED_335 = 335 +CB_PERF_SEL_RESERVED_336 = 336 +CB_PERF_SEL_RESERVED_337 = 337 +CB_PERF_SEL_RESERVED_338 = 338 +CB_PERF_SEL_RESERVED_339 = 339 +CB_PERF_SEL_RESERVED_340 = 340 +CB_PERF_SEL_RESERVED_341 = 341 +CB_PERF_SEL_RESERVED_342 = 342 +CB_PERF_SEL_RESERVED_343 = 343 +CB_PERF_SEL_RESERVED_344 = 344 +CB_PERF_SEL_RESERVED_345 = 345 +CB_PERF_SEL_RESERVED_346 = 346 +CB_PERF_SEL_RESERVED_347 = 347 +CB_PERF_SEL_RESERVED_348 = 348 +CB_PERF_SEL_RESERVED_349 = 349 +CB_PERF_SEL_RESERVED_350 = 350 +CB_PERF_SEL_RESERVED_351 = 351 +CB_PERF_SEL_RESERVED_352 = 352 +CB_PERF_SEL_RESERVED_353 = 353 +CB_PERF_SEL_RESERVED_354 = 354 +CB_PERF_SEL_RESERVED_355 = 355 +CB_PERF_SEL_RESERVED_356 = 356 +CB_PERF_SEL_RESERVED_357 = 357 +CB_PERF_SEL_RESERVED_358 = 358 +CB_PERF_SEL_RESERVED_359 = 359 +CB_PERF_SEL_RESERVED_360 = 360 +CB_PERF_SEL_RESERVED_361 = 361 +CB_PERF_SEL_RESERVED_362 = 362 +CB_PERF_SEL_RESERVED_363 = 363 +CB_PERF_SEL_RESERVED_364 = 364 +CB_PERF_SEL_RESERVED_365 = 365 +CB_PERF_SEL_RESERVED_366 = 366 +CB_PERF_SEL_RESERVED_367 = 367 +CB_PERF_SEL_RESERVED_368 = 368 +CB_PERF_SEL_RESERVED_369 = 369 +CB_PERF_SEL_RESERVED_370 = 370 +CB_PERF_SEL_RESERVED_371 = 371 +CB_PERF_SEL_RESERVED_372 = 372 +CB_PERF_SEL_RESERVED_373 = 373 +CB_PERF_SEL_RESERVED_374 = 374 +CB_PERF_SEL_RESERVED_375 = 375 +CB_PERF_SEL_RESERVED_376 = 376 +CB_PERF_SEL_RESERVED_377 = 377 +CB_PERF_SEL_RESERVED_378 = 378 +CB_PERF_SEL_RESERVED_379 = 379 +CB_PERF_SEL_RESERVED_380 = 380 +CB_PERF_SEL_RESERVED_381 = 381 +CB_PERF_SEL_RESERVED_382 = 382 +CB_PERF_SEL_RESERVED_383 = 383 +CB_PERF_SEL_RESERVED_384 = 384 +CB_PERF_SEL_RESERVED_385 = 385 +CB_PERF_SEL_RESERVED_386 = 386 +CB_PERF_SEL_RESERVED_387 = 387 +CB_PERF_SEL_RESERVED_388 = 388 +CB_PERF_SEL_RESERVED_389 = 389 +CB_PERF_SEL_RESERVED_390 = 390 +CB_PERF_SEL_RESERVED_391 = 391 +CB_PERF_SEL_RESERVED_392 = 392 +CB_PERF_SEL_RESERVED_393 = 393 +CB_PERF_SEL_RESERVED_394 = 394 +CB_PERF_SEL_RESERVED_395 = 395 +CB_PERF_SEL_RESERVED_396 = 396 +CB_PERF_SEL_RESERVED_397 = 397 +CB_PERF_SEL_RESERVED_398 = 398 +CB_PERF_SEL_RESERVED_399 = 399 +CB_PERF_SEL_RESERVED_400 = 400 +CB_PERF_SEL_RESERVED_401 = 401 +CB_PERF_SEL_RESERVED_402 = 402 +CB_PERF_SEL_RESERVED_403 = 403 +CB_PERF_SEL_RESERVED_404 = 404 +CB_PERF_SEL_RESERVED_405 = 405 +CB_PERF_SEL_RESERVED_406 = 406 +CB_PERF_SEL_RESERVED_407 = 407 +CB_PERF_SEL_RESERVED_408 = 408 +CB_PERF_SEL_RESERVED_409 = 409 +CB_PERF_SEL_RESERVED_410 = 410 +CB_PERF_SEL_RESERVED_411 = 411 +CB_PERF_SEL_RESERVED_412 = 412 +CB_PERF_SEL_RESERVED_413 = 413 +CB_PERF_SEL_RESERVED_414 = 414 +CB_PERF_SEL_RESERVED_415 = 415 +CB_PERF_SEL_RESERVED_416 = 416 +CB_PERF_SEL_RESERVED_417 = 417 +CB_PERF_SEL_RESERVED_418 = 418 +CB_PERF_SEL_RESERVED_419 = 419 +CB_PERF_SEL_RESERVED_420 = 420 +CB_PERF_SEL_RESERVED_421 = 421 +CB_PERF_SEL_RESERVED_422 = 422 +CB_PERF_SEL_RESERVED_423 = 423 +CB_PERF_SEL_RESERVED_424 = 424 +CB_PERF_SEL_RESERVED_425 = 425 +CB_PERF_SEL_RESERVED_426 = 426 +CB_PERF_SEL_RESERVED_427 = 427 +CB_PERF_SEL_RESERVED_428 = 428 +CB_PERF_SEL_RESERVED_429 = 429 +CB_PERF_SEL_RESERVED_430 = 430 +CB_PERF_SEL_RESERVED_431 = 431 +CB_PERF_SEL_RESERVED_432 = 432 +CB_PERF_SEL_RESERVED_433 = 433 +CB_PERF_SEL_RESERVED_434 = 434 +CB_PERF_SEL_RESERVED_435 = 435 +CB_PERF_SEL_RESERVED_436 = 436 +CB_PERF_SEL_RESERVED_437 = 437 +CB_PERF_SEL_RESERVED_438 = 438 +CB_PERF_SEL_RESERVED_439 = 439 +CB_PERF_SEL_RESERVED_440 = 440 +CB_PERF_SEL_RESERVED_441 = 441 +CB_PERF_SEL_RESERVED_442 = 442 +CB_PERF_SEL_RESERVED_443 = 443 +CB_PERF_SEL_RESERVED_444 = 444 +CB_PERF_SEL_RESERVED_445 = 445 +CB_PERF_SEL_RESERVED_446 = 446 +CB_PERF_SEL_RESERVED_447 = 447 +CB_PERF_SEL_RESERVED_448 = 448 +CB_PERF_SEL_RESERVED_449 = 449 +CB_PERF_SEL_RESERVED_450 = 450 +CB_PERF_SEL_RESERVED_451 = 451 +CB_PERF_SEL_RESERVED_452 = 452 +CB_PERF_SEL_RESERVED_453 = 453 +CB_PERF_SEL_RESERVED_454 = 454 +CB_PERF_SEL_RESERVED_455 = 455 +CB_PERF_SEL_RESERVED_456 = 456 +CB_PERF_SEL_RESERVED_457 = 457 +CB_PERF_SEL_RESERVED_458 = 458 +CB_PERF_SEL_RESERVED_459 = 459 +CB_PERF_SEL_RESERVED_460 = 460 +CB_PERF_SEL_RESERVED_461 = 461 +CB_PERF_SEL_RESERVED_462 = 462 +CB_PERF_SEL_RESERVED_463 = 463 +CB_PERF_SEL_RESERVED_464 = 464 +CB_PERF_SEL_RESERVED_465 = 465 +CBPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBRamList' +CBRamList__enumvalues = { + 0: 'CB_DCG_CCC_CAS_TAG_ARRAY', + 1: 'CB_DCG_CCC_CAS_FRAG_PTR', + 2: 'CB_DCG_CCC_CAS_COLOR_PTR', + 3: 'CB_DCG_CCC_CAS_SURF_PARAM', + 4: 'CB_DCG_CCC_CAS_KEYID', + 5: 'CB_DCG_BACKEND_RDLAT_FIFO', + 6: 'CB_DCG_FRONTEND_RDLAT_FIFO', + 7: 'CB_DCG_SRC_FIFO', + 8: 'CB_DCG_COLOR_STORE', + 9: 'CB_DCG_COLOR_STORE_DIRTY_BYTE', + 10: 'CB_DCG_FMASK_CACHE_STORE', + 11: 'CB_DCG_READ_SKID_FIFO', + 12: 'CB_DCG_QUAD_PTR_FIFO', + 13: 'CB_DCG_OUTPUT_FIFO', + 14: 'CB_DCG_DCC_CACHE', + 15: 'CB_DCG_DCC_DIRTY_BITS', + 16: 'CB_DCG_QBLOCK_ALLOC', +} +CB_DCG_CCC_CAS_TAG_ARRAY = 0 +CB_DCG_CCC_CAS_FRAG_PTR = 1 +CB_DCG_CCC_CAS_COLOR_PTR = 2 +CB_DCG_CCC_CAS_SURF_PARAM = 3 +CB_DCG_CCC_CAS_KEYID = 4 +CB_DCG_BACKEND_RDLAT_FIFO = 5 +CB_DCG_FRONTEND_RDLAT_FIFO = 6 +CB_DCG_SRC_FIFO = 7 +CB_DCG_COLOR_STORE = 8 +CB_DCG_COLOR_STORE_DIRTY_BYTE = 9 +CB_DCG_FMASK_CACHE_STORE = 10 +CB_DCG_READ_SKID_FIFO = 11 +CB_DCG_QUAD_PTR_FIFO = 12 +CB_DCG_OUTPUT_FIFO = 13 +CB_DCG_DCC_CACHE = 14 +CB_DCG_DCC_DIRTY_BITS = 15 +CB_DCG_QBLOCK_ALLOC = 16 +CBRamList = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskCode' +CmaskCode__enumvalues = { + 0: 'CMASK_CLR00_F0', + 1: 'CMASK_CLR00_F1', + 2: 'CMASK_CLR00_F2', + 3: 'CMASK_CLR00_FX', + 4: 'CMASK_CLR01_F0', + 5: 'CMASK_CLR01_F1', + 6: 'CMASK_CLR01_F2', + 7: 'CMASK_CLR01_FX', + 8: 'CMASK_CLR10_F0', + 9: 'CMASK_CLR10_F1', + 10: 'CMASK_CLR10_F2', + 11: 'CMASK_CLR10_FX', + 12: 'CMASK_CLR11_F0', + 13: 'CMASK_CLR11_F1', + 14: 'CMASK_CLR11_F2', + 15: 'CMASK_CLR11_FX', +} +CMASK_CLR00_F0 = 0 +CMASK_CLR00_F1 = 1 +CMASK_CLR00_F2 = 2 +CMASK_CLR00_FX = 3 +CMASK_CLR01_F0 = 4 +CMASK_CLR01_F1 = 5 +CMASK_CLR01_F2 = 6 +CMASK_CLR01_FX = 7 +CMASK_CLR10_F0 = 8 +CMASK_CLR10_F1 = 9 +CMASK_CLR10_F2 = 10 +CMASK_CLR10_FX = 11 +CMASK_CLR11_F0 = 12 +CMASK_CLR11_F1 = 13 +CMASK_CLR11_F2 = 14 +CMASK_CLR11_FX = 15 +CmaskCode = ctypes.c_uint32 # enum + +# values for enumeration 'CombFunc' +CombFunc__enumvalues = { + 0: 'COMB_DST_PLUS_SRC', + 1: 'COMB_SRC_MINUS_DST', + 2: 'COMB_MIN_DST_SRC', + 3: 'COMB_MAX_DST_SRC', + 4: 'COMB_DST_MINUS_SRC', +} +COMB_DST_PLUS_SRC = 0 +COMB_SRC_MINUS_DST = 1 +COMB_MIN_DST_SRC = 2 +COMB_MAX_DST_SRC = 3 +COMB_DST_MINUS_SRC = 4 +CombFunc = ctypes.c_uint32 # enum + +# values for enumeration 'MemArbMode' +MemArbMode__enumvalues = { + 0: 'MEM_ARB_MODE_FIXED', + 1: 'MEM_ARB_MODE_AGE', + 2: 'MEM_ARB_MODE_WEIGHT', + 3: 'MEM_ARB_MODE_BOTH', +} +MEM_ARB_MODE_FIXED = 0 +MEM_ARB_MODE_AGE = 1 +MEM_ARB_MODE_WEIGHT = 2 +MEM_ARB_MODE_BOTH = 3 +MemArbMode = ctypes.c_uint32 # enum + +# values for enumeration 'SourceFormat' +SourceFormat__enumvalues = { + 0: 'EXPORT_4C_32BPC', + 1: 'EXPORT_4C_16BPC', + 2: 'EXPORT_2C_32BPC_GR', + 3: 'EXPORT_2C_32BPC_AR', +} +EXPORT_4C_32BPC = 0 +EXPORT_4C_16BPC = 1 +EXPORT_2C_32BPC_GR = 2 +EXPORT_2C_32BPC_AR = 3 +SourceFormat = ctypes.c_uint32 # enum + +# values for enumeration 'BinEventCntl' +BinEventCntl__enumvalues = { + 0: 'BINNER_BREAK_BATCH', + 1: 'BINNER_PIPELINE', + 2: 'BINNER_DROP', + 3: 'BINNER_PIPELINE_BREAK', +} +BINNER_BREAK_BATCH = 0 +BINNER_PIPELINE = 1 +BINNER_DROP = 2 +BINNER_PIPELINE_BREAK = 3 +BinEventCntl = ctypes.c_uint32 # enum + +# values for enumeration 'BinMapMode' +BinMapMode__enumvalues = { + 0: 'BIN_MAP_MODE_NONE', + 1: 'BIN_MAP_MODE_RTA_INDEX', + 2: 'BIN_MAP_MODE_POPS', +} +BIN_MAP_MODE_NONE = 0 +BIN_MAP_MODE_RTA_INDEX = 1 +BIN_MAP_MODE_POPS = 2 +BinMapMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinSizeExtend' +BinSizeExtend__enumvalues = { + 0: 'BIN_SIZE_32_PIXELS', + 1: 'BIN_SIZE_64_PIXELS', + 2: 'BIN_SIZE_128_PIXELS', + 3: 'BIN_SIZE_256_PIXELS', + 4: 'BIN_SIZE_512_PIXELS', +} +BIN_SIZE_32_PIXELS = 0 +BIN_SIZE_64_PIXELS = 1 +BIN_SIZE_128_PIXELS = 2 +BIN_SIZE_256_PIXELS = 3 +BIN_SIZE_512_PIXELS = 4 +BinSizeExtend = ctypes.c_uint32 # enum + +# values for enumeration 'BinningMode' +BinningMode__enumvalues = { + 0: 'BINNING_ALLOWED', + 1: 'FORCE_BINNING_ON', + 2: 'DISABLE_BINNING_USE_NEW_SC', + 3: 'DISABLE_BINNING_USE_LEGACY_SC', +} +BINNING_ALLOWED = 0 +FORCE_BINNING_ON = 1 +DISABLE_BINNING_USE_NEW_SC = 2 +DISABLE_BINNING_USE_LEGACY_SC = 3 +BinningMode = ctypes.c_uint32 # enum + +# values for enumeration 'CovToShaderSel' +CovToShaderSel__enumvalues = { + 0: 'INPUT_COVERAGE', + 1: 'INPUT_INNER_COVERAGE', + 2: 'INPUT_DEPTH_COVERAGE', + 3: 'RAW', +} +INPUT_COVERAGE = 0 +INPUT_INNER_COVERAGE = 1 +INPUT_DEPTH_COVERAGE = 2 +RAW = 3 +CovToShaderSel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrMap' +PkrMap__enumvalues = { + 0: 'RASTER_CONFIG_PKR_MAP_0', + 1: 'RASTER_CONFIG_PKR_MAP_1', + 2: 'RASTER_CONFIG_PKR_MAP_2', + 3: 'RASTER_CONFIG_PKR_MAP_3', +} +RASTER_CONFIG_PKR_MAP_0 = 0 +RASTER_CONFIG_PKR_MAP_1 = 1 +RASTER_CONFIG_PKR_MAP_2 = 2 +RASTER_CONFIG_PKR_MAP_3 = 3 +PkrMap = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel' +PkrXsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL_0', + 1: 'RASTER_CONFIG_PKR_XSEL_1', + 2: 'RASTER_CONFIG_PKR_XSEL_2', + 3: 'RASTER_CONFIG_PKR_XSEL_3', +} +RASTER_CONFIG_PKR_XSEL_0 = 0 +RASTER_CONFIG_PKR_XSEL_1 = 1 +RASTER_CONFIG_PKR_XSEL_2 = 2 +RASTER_CONFIG_PKR_XSEL_3 = 3 +PkrXsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel2' +PkrXsel2__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL2_0', + 1: 'RASTER_CONFIG_PKR_XSEL2_1', + 2: 'RASTER_CONFIG_PKR_XSEL2_2', + 3: 'RASTER_CONFIG_PKR_XSEL2_3', +} +RASTER_CONFIG_PKR_XSEL2_0 = 0 +RASTER_CONFIG_PKR_XSEL2_1 = 1 +RASTER_CONFIG_PKR_XSEL2_2 = 2 +RASTER_CONFIG_PKR_XSEL2_3 = 3 +PkrXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'PkrYsel' +PkrYsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_YSEL_0', + 1: 'RASTER_CONFIG_PKR_YSEL_1', + 2: 'RASTER_CONFIG_PKR_YSEL_2', + 3: 'RASTER_CONFIG_PKR_YSEL_3', +} +RASTER_CONFIG_PKR_YSEL_0 = 0 +RASTER_CONFIG_PKR_YSEL_1 = 1 +RASTER_CONFIG_PKR_YSEL_2 = 2 +RASTER_CONFIG_PKR_YSEL_3 = 3 +PkrYsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbMap' +RbMap__enumvalues = { + 0: 'RASTER_CONFIG_RB_MAP_0', + 1: 'RASTER_CONFIG_RB_MAP_1', + 2: 'RASTER_CONFIG_RB_MAP_2', + 3: 'RASTER_CONFIG_RB_MAP_3', +} +RASTER_CONFIG_RB_MAP_0 = 0 +RASTER_CONFIG_RB_MAP_1 = 1 +RASTER_CONFIG_RB_MAP_2 = 2 +RASTER_CONFIG_RB_MAP_3 = 3 +RbMap = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel' +RbXsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL_0', + 1: 'RASTER_CONFIG_RB_XSEL_1', +} +RASTER_CONFIG_RB_XSEL_0 = 0 +RASTER_CONFIG_RB_XSEL_1 = 1 +RbXsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel2' +RbXsel2__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL2_0', + 1: 'RASTER_CONFIG_RB_XSEL2_1', + 2: 'RASTER_CONFIG_RB_XSEL2_2', + 3: 'RASTER_CONFIG_RB_XSEL2_3', +} +RASTER_CONFIG_RB_XSEL2_0 = 0 +RASTER_CONFIG_RB_XSEL2_1 = 1 +RASTER_CONFIG_RB_XSEL2_2 = 2 +RASTER_CONFIG_RB_XSEL2_3 = 3 +RbXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'RbYsel' +RbYsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_YSEL_0', + 1: 'RASTER_CONFIG_RB_YSEL_1', +} +RASTER_CONFIG_RB_YSEL_0 = 0 +RASTER_CONFIG_RB_YSEL_1 = 1 +RbYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SC_PERFCNT_SEL' +SC_PERFCNT_SEL__enumvalues = { + 0: 'SC_SRPS_WINDOW_VALID', + 1: 'SC_PSSW_WINDOW_VALID', + 2: 'SC_TPQZ_WINDOW_VALID', + 3: 'SC_QZQP_WINDOW_VALID', + 4: 'SC_TRPK_WINDOW_VALID', + 5: 'SC_SRPS_WINDOW_VALID_BUSY', + 6: 'SC_PSSW_WINDOW_VALID_BUSY', + 7: 'SC_TPQZ_WINDOW_VALID_BUSY', + 8: 'SC_QZQP_WINDOW_VALID_BUSY', + 9: 'SC_TRPK_WINDOW_VALID_BUSY', + 10: 'SC_STARVED_BY_PA', + 11: 'SC_STALLED_BY_PRIMFIFO', + 12: 'SC_STALLED_BY_DB_TILE', + 13: 'SC_STARVED_BY_DB_TILE', + 14: 'SC_STALLED_BY_TILEORDERFIFO', + 15: 'SC_STALLED_BY_TILEFIFO', + 16: 'SC_STALLED_BY_DB_QUAD', + 17: 'SC_STARVED_BY_DB_QUAD', + 18: 'SC_STALLED_BY_QUADFIFO', + 19: 'SC_STALLED_BY_BCI', + 20: 'SC_STALLED_BY_SPI', + 21: 'SC_SCISSOR_DISCARD', + 22: 'SC_BB_DISCARD', + 23: 'SC_SUPERTILE_COUNT', + 24: 'SC_SUPERTILE_PER_PRIM_H0', + 25: 'SC_SUPERTILE_PER_PRIM_H1', + 26: 'SC_SUPERTILE_PER_PRIM_H2', + 27: 'SC_SUPERTILE_PER_PRIM_H3', + 28: 'SC_SUPERTILE_PER_PRIM_H4', + 29: 'SC_SUPERTILE_PER_PRIM_H5', + 30: 'SC_SUPERTILE_PER_PRIM_H6', + 31: 'SC_SUPERTILE_PER_PRIM_H7', + 32: 'SC_SUPERTILE_PER_PRIM_H8', + 33: 'SC_SUPERTILE_PER_PRIM_H9', + 34: 'SC_SUPERTILE_PER_PRIM_H10', + 35: 'SC_SUPERTILE_PER_PRIM_H11', + 36: 'SC_SUPERTILE_PER_PRIM_H12', + 37: 'SC_SUPERTILE_PER_PRIM_H13', + 38: 'SC_SUPERTILE_PER_PRIM_H14', + 39: 'SC_SUPERTILE_PER_PRIM_H15', + 40: 'SC_SUPERTILE_PER_PRIM_H16', + 41: 'SC_TILE_PER_PRIM_H0', + 42: 'SC_TILE_PER_PRIM_H1', + 43: 'SC_TILE_PER_PRIM_H2', + 44: 'SC_TILE_PER_PRIM_H3', + 45: 'SC_TILE_PER_PRIM_H4', + 46: 'SC_TILE_PER_PRIM_H5', + 47: 'SC_TILE_PER_PRIM_H6', + 48: 'SC_TILE_PER_PRIM_H7', + 49: 'SC_TILE_PER_PRIM_H8', + 50: 'SC_TILE_PER_PRIM_H9', + 51: 'SC_TILE_PER_PRIM_H10', + 52: 'SC_TILE_PER_PRIM_H11', + 53: 'SC_TILE_PER_PRIM_H12', + 54: 'SC_TILE_PER_PRIM_H13', + 55: 'SC_TILE_PER_PRIM_H14', + 56: 'SC_TILE_PER_PRIM_H15', + 57: 'SC_TILE_PER_PRIM_H16', + 58: 'SC_TILE_PER_SUPERTILE_H0', + 59: 'SC_TILE_PER_SUPERTILE_H1', + 60: 'SC_TILE_PER_SUPERTILE_H2', + 61: 'SC_TILE_PER_SUPERTILE_H3', + 62: 'SC_TILE_PER_SUPERTILE_H4', + 63: 'SC_TILE_PER_SUPERTILE_H5', + 64: 'SC_TILE_PER_SUPERTILE_H6', + 65: 'SC_TILE_PER_SUPERTILE_H7', + 66: 'SC_TILE_PER_SUPERTILE_H8', + 67: 'SC_TILE_PER_SUPERTILE_H9', + 68: 'SC_TILE_PER_SUPERTILE_H10', + 69: 'SC_TILE_PER_SUPERTILE_H11', + 70: 'SC_TILE_PER_SUPERTILE_H12', + 71: 'SC_TILE_PER_SUPERTILE_H13', + 72: 'SC_TILE_PER_SUPERTILE_H14', + 73: 'SC_TILE_PER_SUPERTILE_H15', + 74: 'SC_TILE_PER_SUPERTILE_H16', + 75: 'SC_TILE_PICKED_H1', + 76: 'SC_TILE_PICKED_H2', + 77: 'SC_TILE_PICKED_H3', + 78: 'SC_TILE_PICKED_H4', + 79: 'SC_QZ0_TILE_COUNT', + 80: 'SC_QZ1_TILE_COUNT', + 81: 'SC_QZ2_TILE_COUNT', + 82: 'SC_QZ3_TILE_COUNT', + 83: 'SC_QZ0_TILE_COVERED_COUNT', + 84: 'SC_QZ1_TILE_COVERED_COUNT', + 85: 'SC_QZ2_TILE_COVERED_COUNT', + 86: 'SC_QZ3_TILE_COVERED_COUNT', + 87: 'SC_QZ0_TILE_NOT_COVERED_COUNT', + 88: 'SC_QZ1_TILE_NOT_COVERED_COUNT', + 89: 'SC_QZ2_TILE_NOT_COVERED_COUNT', + 90: 'SC_QZ3_TILE_NOT_COVERED_COUNT', + 91: 'SC_QZ0_QUAD_PER_TILE_H0', + 92: 'SC_QZ0_QUAD_PER_TILE_H1', + 93: 'SC_QZ0_QUAD_PER_TILE_H2', + 94: 'SC_QZ0_QUAD_PER_TILE_H3', + 95: 'SC_QZ0_QUAD_PER_TILE_H4', + 96: 'SC_QZ0_QUAD_PER_TILE_H5', + 97: 'SC_QZ0_QUAD_PER_TILE_H6', + 98: 'SC_QZ0_QUAD_PER_TILE_H7', + 99: 'SC_QZ0_QUAD_PER_TILE_H8', + 100: 'SC_QZ0_QUAD_PER_TILE_H9', + 101: 'SC_QZ0_QUAD_PER_TILE_H10', + 102: 'SC_QZ0_QUAD_PER_TILE_H11', + 103: 'SC_QZ0_QUAD_PER_TILE_H12', + 104: 'SC_QZ0_QUAD_PER_TILE_H13', + 105: 'SC_QZ0_QUAD_PER_TILE_H14', + 106: 'SC_QZ0_QUAD_PER_TILE_H15', + 107: 'SC_QZ0_QUAD_PER_TILE_H16', + 108: 'SC_QZ1_QUAD_PER_TILE_H0', + 109: 'SC_QZ1_QUAD_PER_TILE_H1', + 110: 'SC_QZ1_QUAD_PER_TILE_H2', + 111: 'SC_QZ1_QUAD_PER_TILE_H3', + 112: 'SC_QZ1_QUAD_PER_TILE_H4', + 113: 'SC_QZ1_QUAD_PER_TILE_H5', + 114: 'SC_QZ1_QUAD_PER_TILE_H6', + 115: 'SC_QZ1_QUAD_PER_TILE_H7', + 116: 'SC_QZ1_QUAD_PER_TILE_H8', + 117: 'SC_QZ1_QUAD_PER_TILE_H9', + 118: 'SC_QZ1_QUAD_PER_TILE_H10', + 119: 'SC_QZ1_QUAD_PER_TILE_H11', + 120: 'SC_QZ1_QUAD_PER_TILE_H12', + 121: 'SC_QZ1_QUAD_PER_TILE_H13', + 122: 'SC_QZ1_QUAD_PER_TILE_H14', + 123: 'SC_QZ1_QUAD_PER_TILE_H15', + 124: 'SC_QZ1_QUAD_PER_TILE_H16', + 125: 'SC_QZ2_QUAD_PER_TILE_H0', + 126: 'SC_QZ2_QUAD_PER_TILE_H1', + 127: 'SC_QZ2_QUAD_PER_TILE_H2', + 128: 'SC_QZ2_QUAD_PER_TILE_H3', + 129: 'SC_QZ2_QUAD_PER_TILE_H4', + 130: 'SC_QZ2_QUAD_PER_TILE_H5', + 131: 'SC_QZ2_QUAD_PER_TILE_H6', + 132: 'SC_QZ2_QUAD_PER_TILE_H7', + 133: 'SC_QZ2_QUAD_PER_TILE_H8', + 134: 'SC_QZ2_QUAD_PER_TILE_H9', + 135: 'SC_QZ2_QUAD_PER_TILE_H10', + 136: 'SC_QZ2_QUAD_PER_TILE_H11', + 137: 'SC_QZ2_QUAD_PER_TILE_H12', + 138: 'SC_QZ2_QUAD_PER_TILE_H13', + 139: 'SC_QZ2_QUAD_PER_TILE_H14', + 140: 'SC_QZ2_QUAD_PER_TILE_H15', + 141: 'SC_QZ2_QUAD_PER_TILE_H16', + 142: 'SC_QZ3_QUAD_PER_TILE_H0', + 143: 'SC_QZ3_QUAD_PER_TILE_H1', + 144: 'SC_QZ3_QUAD_PER_TILE_H2', + 145: 'SC_QZ3_QUAD_PER_TILE_H3', + 146: 'SC_QZ3_QUAD_PER_TILE_H4', + 147: 'SC_QZ3_QUAD_PER_TILE_H5', + 148: 'SC_QZ3_QUAD_PER_TILE_H6', + 149: 'SC_QZ3_QUAD_PER_TILE_H7', + 150: 'SC_QZ3_QUAD_PER_TILE_H8', + 151: 'SC_QZ3_QUAD_PER_TILE_H9', + 152: 'SC_QZ3_QUAD_PER_TILE_H10', + 153: 'SC_QZ3_QUAD_PER_TILE_H11', + 154: 'SC_QZ3_QUAD_PER_TILE_H12', + 155: 'SC_QZ3_QUAD_PER_TILE_H13', + 156: 'SC_QZ3_QUAD_PER_TILE_H14', + 157: 'SC_QZ3_QUAD_PER_TILE_H15', + 158: 'SC_QZ3_QUAD_PER_TILE_H16', + 159: 'SC_QZ0_QUAD_COUNT', + 160: 'SC_QZ1_QUAD_COUNT', + 161: 'SC_QZ2_QUAD_COUNT', + 162: 'SC_QZ3_QUAD_COUNT', + 163: 'SC_P0_HIZ_TILE_COUNT', + 164: 'SC_P1_HIZ_TILE_COUNT', + 165: 'SC_P2_HIZ_TILE_COUNT', + 166: 'SC_P3_HIZ_TILE_COUNT', + 167: 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 168: 'SC_P0_HIZ_QUAD_PER_TILE_H1', + 169: 'SC_P0_HIZ_QUAD_PER_TILE_H2', + 170: 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 171: 'SC_P0_HIZ_QUAD_PER_TILE_H4', + 172: 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 173: 'SC_P0_HIZ_QUAD_PER_TILE_H6', + 174: 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 175: 'SC_P0_HIZ_QUAD_PER_TILE_H8', + 176: 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 177: 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 178: 'SC_P0_HIZ_QUAD_PER_TILE_H11', + 179: 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 180: 'SC_P0_HIZ_QUAD_PER_TILE_H13', + 181: 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 182: 'SC_P0_HIZ_QUAD_PER_TILE_H15', + 183: 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 184: 'SC_P1_HIZ_QUAD_PER_TILE_H0', + 185: 'SC_P1_HIZ_QUAD_PER_TILE_H1', + 186: 'SC_P1_HIZ_QUAD_PER_TILE_H2', + 187: 'SC_P1_HIZ_QUAD_PER_TILE_H3', + 188: 'SC_P1_HIZ_QUAD_PER_TILE_H4', + 189: 'SC_P1_HIZ_QUAD_PER_TILE_H5', + 190: 'SC_P1_HIZ_QUAD_PER_TILE_H6', + 191: 'SC_P1_HIZ_QUAD_PER_TILE_H7', + 192: 'SC_P1_HIZ_QUAD_PER_TILE_H8', + 193: 'SC_P1_HIZ_QUAD_PER_TILE_H9', + 194: 'SC_P1_HIZ_QUAD_PER_TILE_H10', + 195: 'SC_P1_HIZ_QUAD_PER_TILE_H11', + 196: 'SC_P1_HIZ_QUAD_PER_TILE_H12', + 197: 'SC_P1_HIZ_QUAD_PER_TILE_H13', + 198: 'SC_P1_HIZ_QUAD_PER_TILE_H14', + 199: 'SC_P1_HIZ_QUAD_PER_TILE_H15', + 200: 'SC_P1_HIZ_QUAD_PER_TILE_H16', + 201: 'SC_P2_HIZ_QUAD_PER_TILE_H0', + 202: 'SC_P2_HIZ_QUAD_PER_TILE_H1', + 203: 'SC_P2_HIZ_QUAD_PER_TILE_H2', + 204: 'SC_P2_HIZ_QUAD_PER_TILE_H3', + 205: 'SC_P2_HIZ_QUAD_PER_TILE_H4', + 206: 'SC_P2_HIZ_QUAD_PER_TILE_H5', + 207: 'SC_P2_HIZ_QUAD_PER_TILE_H6', + 208: 'SC_P2_HIZ_QUAD_PER_TILE_H7', + 209: 'SC_P2_HIZ_QUAD_PER_TILE_H8', + 210: 'SC_P2_HIZ_QUAD_PER_TILE_H9', + 211: 'SC_P2_HIZ_QUAD_PER_TILE_H10', + 212: 'SC_P2_HIZ_QUAD_PER_TILE_H11', + 213: 'SC_P2_HIZ_QUAD_PER_TILE_H12', + 214: 'SC_P2_HIZ_QUAD_PER_TILE_H13', + 215: 'SC_P2_HIZ_QUAD_PER_TILE_H14', + 216: 'SC_P2_HIZ_QUAD_PER_TILE_H15', + 217: 'SC_P2_HIZ_QUAD_PER_TILE_H16', + 218: 'SC_P3_HIZ_QUAD_PER_TILE_H0', + 219: 'SC_P3_HIZ_QUAD_PER_TILE_H1', + 220: 'SC_P3_HIZ_QUAD_PER_TILE_H2', + 221: 'SC_P3_HIZ_QUAD_PER_TILE_H3', + 222: 'SC_P3_HIZ_QUAD_PER_TILE_H4', + 223: 'SC_P3_HIZ_QUAD_PER_TILE_H5', + 224: 'SC_P3_HIZ_QUAD_PER_TILE_H6', + 225: 'SC_P3_HIZ_QUAD_PER_TILE_H7', + 226: 'SC_P3_HIZ_QUAD_PER_TILE_H8', + 227: 'SC_P3_HIZ_QUAD_PER_TILE_H9', + 228: 'SC_P3_HIZ_QUAD_PER_TILE_H10', + 229: 'SC_P3_HIZ_QUAD_PER_TILE_H11', + 230: 'SC_P3_HIZ_QUAD_PER_TILE_H12', + 231: 'SC_P3_HIZ_QUAD_PER_TILE_H13', + 232: 'SC_P3_HIZ_QUAD_PER_TILE_H14', + 233: 'SC_P3_HIZ_QUAD_PER_TILE_H15', + 234: 'SC_P3_HIZ_QUAD_PER_TILE_H16', + 235: 'SC_P0_HIZ_QUAD_COUNT', + 236: 'SC_P1_HIZ_QUAD_COUNT', + 237: 'SC_P2_HIZ_QUAD_COUNT', + 238: 'SC_P3_HIZ_QUAD_COUNT', + 239: 'SC_P0_DETAIL_QUAD_COUNT', + 240: 'SC_P1_DETAIL_QUAD_COUNT', + 241: 'SC_P2_DETAIL_QUAD_COUNT', + 242: 'SC_P3_DETAIL_QUAD_COUNT', + 243: 'SC_P0_DETAIL_QUAD_WITH_1_PIX', + 244: 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 245: 'SC_P0_DETAIL_QUAD_WITH_3_PIX', + 246: 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 247: 'SC_P1_DETAIL_QUAD_WITH_1_PIX', + 248: 'SC_P1_DETAIL_QUAD_WITH_2_PIX', + 249: 'SC_P1_DETAIL_QUAD_WITH_3_PIX', + 250: 'SC_P1_DETAIL_QUAD_WITH_4_PIX', + 251: 'SC_P2_DETAIL_QUAD_WITH_1_PIX', + 252: 'SC_P2_DETAIL_QUAD_WITH_2_PIX', + 253: 'SC_P2_DETAIL_QUAD_WITH_3_PIX', + 254: 'SC_P2_DETAIL_QUAD_WITH_4_PIX', + 255: 'SC_P3_DETAIL_QUAD_WITH_1_PIX', + 256: 'SC_P3_DETAIL_QUAD_WITH_2_PIX', + 257: 'SC_P3_DETAIL_QUAD_WITH_3_PIX', + 258: 'SC_P3_DETAIL_QUAD_WITH_4_PIX', + 259: 'SC_EARLYZ_QUAD_COUNT', + 260: 'SC_EARLYZ_QUAD_WITH_1_PIX', + 261: 'SC_EARLYZ_QUAD_WITH_2_PIX', + 262: 'SC_EARLYZ_QUAD_WITH_3_PIX', + 263: 'SC_EARLYZ_QUAD_WITH_4_PIX', + 264: 'SC_PKR_QUAD_PER_ROW_H1', + 265: 'SC_PKR_QUAD_PER_ROW_H2', + 266: 'SC_PKR_4X2_QUAD_SPLIT', + 267: 'SC_PKR_4X2_FILL_QUAD', + 268: 'SC_PKR_END_OF_VECTOR', + 269: 'SC_PKR_CONTROL_XFER', + 270: 'SC_PKR_DBHANG_FORCE_EOV', + 271: 'SC_REG_SCLK_BUSY', + 272: 'SC_GRP0_DYN_SCLK_BUSY', + 273: 'SC_GRP1_DYN_SCLK_BUSY', + 274: 'SC_GRP2_DYN_SCLK_BUSY', + 275: 'SC_GRP3_DYN_SCLK_BUSY', + 276: 'SC_GRP4_DYN_SCLK_BUSY', + 277: 'SC_PA0_SC_DATA_FIFO_RD', + 278: 'SC_PA0_SC_DATA_FIFO_WE', + 279: 'SC_PA1_SC_DATA_FIFO_RD', + 280: 'SC_PA1_SC_DATA_FIFO_WE', + 281: 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 282: 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', + 283: 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 284: 'SC_PS_ARB_STALLED_FROM_BELOW', + 285: 'SC_PS_ARB_STARVED_FROM_ABOVE', + 286: 'SC_PS_ARB_SC_BUSY', + 287: 'SC_PS_ARB_PA_SC_BUSY', + 288: 'SC_PA2_SC_DATA_FIFO_RD', + 289: 'SC_PA2_SC_DATA_FIFO_WE', + 290: 'SC_PA3_SC_DATA_FIFO_RD', + 291: 'SC_PA3_SC_DATA_FIFO_WE', + 292: 'SC_PA_SC_DEALLOC_0_0_WE', + 293: 'SC_PA_SC_DEALLOC_0_1_WE', + 294: 'SC_PA_SC_DEALLOC_1_0_WE', + 295: 'SC_PA_SC_DEALLOC_1_1_WE', + 296: 'SC_PA_SC_DEALLOC_2_0_WE', + 297: 'SC_PA_SC_DEALLOC_2_1_WE', + 298: 'SC_PA_SC_DEALLOC_3_0_WE', + 299: 'SC_PA_SC_DEALLOC_3_1_WE', + 300: 'SC_PA0_SC_EOP_WE', + 301: 'SC_PA0_SC_EOPG_WE', + 302: 'SC_PA0_SC_EVENT_WE', + 303: 'SC_PA1_SC_EOP_WE', + 304: 'SC_PA1_SC_EOPG_WE', + 305: 'SC_PA1_SC_EVENT_WE', + 306: 'SC_PA2_SC_EOP_WE', + 307: 'SC_PA2_SC_EOPG_WE', + 308: 'SC_PA2_SC_EVENT_WE', + 309: 'SC_PA3_SC_EOP_WE', + 310: 'SC_PA3_SC_EOPG_WE', + 311: 'SC_PA3_SC_EVENT_WE', + 312: 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 313: 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 314: 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 315: 'SC_PS_ARB_EOP_POP_SYNC_POP', + 316: 'SC_PS_ARB_EVENT_SYNC_POP', + 317: 'SC_PS_ENG_MULTICYCLE_BUBBLE', + 318: 'SC_PA0_SC_FPOV_WE', + 319: 'SC_PA1_SC_FPOV_WE', + 320: 'SC_PA2_SC_FPOV_WE', + 321: 'SC_PA3_SC_FPOV_WE', + 322: 'SC_PA0_SC_LPOV_WE', + 323: 'SC_PA1_SC_LPOV_WE', + 324: 'SC_PA2_SC_LPOV_WE', + 325: 'SC_PA3_SC_LPOV_WE', + 326: 'SC_SPI_DEALLOC_0_0', + 327: 'SC_SPI_DEALLOC_0_1', + 328: 'SC_SPI_DEALLOC_0_2', + 329: 'SC_SPI_DEALLOC_1_0', + 330: 'SC_SPI_DEALLOC_1_1', + 331: 'SC_SPI_DEALLOC_1_2', + 332: 'SC_SPI_DEALLOC_2_0', + 333: 'SC_SPI_DEALLOC_2_1', + 334: 'SC_SPI_DEALLOC_2_2', + 335: 'SC_SPI_DEALLOC_3_0', + 336: 'SC_SPI_DEALLOC_3_1', + 337: 'SC_SPI_DEALLOC_3_2', + 338: 'SC_SPI_FPOV_0', + 339: 'SC_SPI_FPOV_1', + 340: 'SC_SPI_FPOV_2', + 341: 'SC_SPI_FPOV_3', + 342: 'SC_SPI_EVENT', + 343: 'SC_PS_TS_EVENT_FIFO_PUSH', + 344: 'SC_PS_TS_EVENT_FIFO_POP', + 345: 'SC_PS_CTX_DONE_FIFO_PUSH', + 346: 'SC_PS_CTX_DONE_FIFO_POP', + 347: 'SC_MULTICYCLE_BUBBLE_FREEZE', + 348: 'SC_EOP_SYNC_WINDOW', + 349: 'SC_PA0_SC_NULL_WE', + 350: 'SC_PA0_SC_NULL_DEALLOC_WE', + 351: 'SC_PA0_SC_DATA_FIFO_EOPG_RD', + 352: 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 353: 'SC_PA0_SC_DEALLOC_0_RD', + 354: 'SC_PA0_SC_DEALLOC_1_RD', + 355: 'SC_PA1_SC_DATA_FIFO_EOPG_RD', + 356: 'SC_PA1_SC_DATA_FIFO_EOP_RD', + 357: 'SC_PA1_SC_DEALLOC_0_RD', + 358: 'SC_PA1_SC_DEALLOC_1_RD', + 359: 'SC_PA1_SC_NULL_WE', + 360: 'SC_PA1_SC_NULL_DEALLOC_WE', + 361: 'SC_PA2_SC_DATA_FIFO_EOPG_RD', + 362: 'SC_PA2_SC_DATA_FIFO_EOP_RD', + 363: 'SC_PA2_SC_DEALLOC_0_RD', + 364: 'SC_PA2_SC_DEALLOC_1_RD', + 365: 'SC_PA2_SC_NULL_WE', + 366: 'SC_PA2_SC_NULL_DEALLOC_WE', + 367: 'SC_PA3_SC_DATA_FIFO_EOPG_RD', + 368: 'SC_PA3_SC_DATA_FIFO_EOP_RD', + 369: 'SC_PA3_SC_DEALLOC_0_RD', + 370: 'SC_PA3_SC_DEALLOC_1_RD', + 371: 'SC_PA3_SC_NULL_WE', + 372: 'SC_PA3_SC_NULL_DEALLOC_WE', + 373: 'SC_PS_PA0_SC_FIFO_EMPTY', + 374: 'SC_PS_PA0_SC_FIFO_FULL', + 375: 'SC_RESERVED_0', + 376: 'SC_PS_PA1_SC_FIFO_EMPTY', + 377: 'SC_PS_PA1_SC_FIFO_FULL', + 378: 'SC_RESERVED_1', + 379: 'SC_PS_PA2_SC_FIFO_EMPTY', + 380: 'SC_PS_PA2_SC_FIFO_FULL', + 381: 'SC_RESERVED_2', + 382: 'SC_PS_PA3_SC_FIFO_EMPTY', + 383: 'SC_PS_PA3_SC_FIFO_FULL', + 384: 'SC_RESERVED_3', + 385: 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', + 386: 'SC_BUSY_CNT_NOT_ZERO', + 387: 'SC_BM_BUSY', + 388: 'SC_BACKEND_BUSY', + 389: 'SC_SCF_SCB_INTERFACE_BUSY', + 390: 'SC_SCB_BUSY', + 391: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 392: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 393: 'SC_PBB_BIN_HIST_NUM_PRIMS', + 394: 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 395: 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 396: 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 397: 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 398: 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 399: 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 400: 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 401: 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 402: 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 403: 'SC_PBB_BUSY', + 404: 'SC_PBB_BUSY_AND_NO_SENDS', + 405: 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 406: 'SC_PBB_NUM_BINS', + 407: 'SC_PBB_END_OF_BIN', + 408: 'SC_PBB_END_OF_BATCH', + 409: 'SC_PBB_PRIMBIN_PROCESSED', + 410: 'SC_PBB_PRIM_ADDED_TO_BATCH', + 411: 'SC_PBB_NONBINNED_PRIM', + 412: 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', + 413: 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 414: 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 415: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 416: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 417: 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 418: 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 419: 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 420: 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 421: 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 422: 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 423: 'SC_POPS_INTRA_WAVE_OVERLAPS', + 424: 'SC_POPS_FORCE_EOV', + 425: 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX', + 426: 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP', + 427: 'SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE', + 428: 'SC_FULL_FULL_QUAD', + 429: 'SC_FULL_HALF_QUAD', + 430: 'SC_FULL_QTR_QUAD', + 431: 'SC_HALF_FULL_QUAD', + 432: 'SC_HALF_HALF_QUAD', + 433: 'SC_HALF_QTR_QUAD', + 434: 'SC_QTR_FULL_QUAD', + 435: 'SC_QTR_HALF_QUAD', + 436: 'SC_QTR_QTR_QUAD', + 437: 'SC_GRP5_DYN_SCLK_BUSY', + 438: 'SC_GRP6_DYN_SCLK_BUSY', + 439: 'SC_GRP7_DYN_SCLK_BUSY', + 440: 'SC_GRP8_DYN_SCLK_BUSY', + 441: 'SC_GRP9_DYN_SCLK_BUSY', + 442: 'SC_PS_TO_BE_SCLK_GATE_STALL', + 443: 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 444: 'SC_PK_BUSY', + 445: 'SC_PK_MAX_DEALLOC_FORCE_EOV', + 446: 'SC_PK_DEALLOC_WAVE_BREAK', + 447: 'SC_SPI_SEND', + 448: 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 449: 'SC_SPI_CREDIT_AT_MAX', + 450: 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 451: 'SC_BCI_SEND', + 452: 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 453: 'SC_BCI_CREDIT_AT_MAX', + 454: 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 455: 'SC_SPIBC_FULL_FREEZE', + 456: 'SC_PW_BM_PASS_EMPTY_PRIM', + 457: 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 458: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 459: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 460: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 461: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 462: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 463: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 464: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 465: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 466: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 467: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 468: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 469: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 470: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 471: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 472: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 473: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 474: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 475: 'SC_DB0_TILE_INTERFACE_BUSY', + 476: 'SC_DB0_TILE_INTERFACE_SEND', + 477: 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 478: 'SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 479: 'SC_DB0_TILE_INTERFACE_SEND_SOP', + 480: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 481: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 482: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 483: 'SC_DB1_TILE_INTERFACE_BUSY', + 484: 'SC_DB1_TILE_INTERFACE_SEND', + 485: 'SC_DB1_TILE_INTERFACE_SEND_EVENT', + 486: 'SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 487: 'SC_DB1_TILE_INTERFACE_SEND_SOP', + 488: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 489: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX', + 490: 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 491: 'SC_BACKEND_PRIM_FIFO_FULL', + 492: 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 493: 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 494: 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 495: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 496: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 497: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 498: 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 499: 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 500: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', + 501: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET', + 502: 'SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE', + 503: 'SC_STALLED_BY_DB0_TILEFIFO', + 504: 'SC_DB0_QUAD_INTF_SEND', + 505: 'SC_DB0_QUAD_INTF_BUSY', + 506: 'SC_DB0_QUAD_INTF_STALLED_BY_DB', + 507: 'SC_DB0_QUAD_INTF_CREDIT_AT_MAX', + 508: 'SC_DB0_QUAD_INTF_IDLE', + 509: 'SC_DB1_QUAD_INTF_SEND', + 510: 'SC_STALLED_BY_DB1_TILEFIFO', + 511: 'SC_DB1_QUAD_INTF_BUSY', + 512: 'SC_DB1_QUAD_INTF_STALLED_BY_DB', + 513: 'SC_DB1_QUAD_INTF_CREDIT_AT_MAX', + 514: 'SC_DB1_QUAD_INTF_IDLE', + 515: 'SC_PKR_WAVE_BREAK_OUTSIDE_REGION', + 516: 'SC_PKR_WAVE_BREAK_FULL_TILE', + 517: 'SC_FSR_WALKED', + 518: 'SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN', + 519: 'SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT', + 520: 'SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL', + 521: 'SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 522: 'SC_DB0_TILE_MASK_FIFO_FULL', + 523: 'SC_DB1_WE_STALLED_BY_RSLT_FIFO_FULL', + 524: 'SC_DB1_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 525: 'SC_DB1_TILE_MASK_FIFO_FULL', + 526: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL', + 527: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL', + 528: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL', + 529: 'SC_PS_PM_PFF_PW_FULL', + 530: 'SC_PS_PM_ZFF_PW_FULL', + 531: 'SC_PS_PM_PBB_TO_PSE_FIFO_FULL', + 532: 'SC_PK_PM_QD1_FD_CONFLICT_WAVE_BRK_1H', + 533: 'SC_PK_PM_QD1_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 534: 'SC_PK_PM_QD1_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 535: 'SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H', + 536: 'SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H', + 537: 'SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H', + 538: 'SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H', + 539: 'SC_PK_PM_LAST_AND_DEALLOC_WAVE_BRK_1H', + 540: 'SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H', + 541: 'SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 542: 'SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H', + 543: 'SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 544: 'SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H', + 545: 'SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H', + 546: 'SC_PK_PM_FULL_TILE_WAVE_BRK_1H', + 547: 'SC_PK_PM_POPS_FORCE_EOV_WAVE_BRK_1H', + 548: 'SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H', + 549: 'SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H', + 550: 'SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H', + 551: 'SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H', + 552: 'SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD', + 553: 'SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD', + 554: 'SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD', + 555: 'SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD', + 556: 'SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD', + 557: 'SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD', + 558: 'SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD', + 559: 'SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD', + 560: 'SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD', + 561: 'SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD', + 562: 'SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD', + 563: 'SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD', + 564: 'SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD', + 565: 'SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD', + 566: 'SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD', + 567: 'SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD', + 568: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_MODE_CHANGE', + 569: 'SC_PBB_RESERVED', + 570: 'SC_BM_BE0_STALLED', + 571: 'SC_BM_BE1_STALLED', + 572: 'SC_BM_BE2_STALLED', + 573: 'SC_BM_BE3_STALLED', + 574: 'SC_BM_MULTI_ACCUM_1_BE_STALLED', + 575: 'SC_BM_MULTI_ACCUM_2_BE_STALLED', + 576: 'SC_BM_MULTI_ACCUM_3_BE_STALLED', + 577: 'SC_BM_MULTI_ACCUM_4_BE_STALLED', +} +SC_SRPS_WINDOW_VALID = 0 +SC_PSSW_WINDOW_VALID = 1 +SC_TPQZ_WINDOW_VALID = 2 +SC_QZQP_WINDOW_VALID = 3 +SC_TRPK_WINDOW_VALID = 4 +SC_SRPS_WINDOW_VALID_BUSY = 5 +SC_PSSW_WINDOW_VALID_BUSY = 6 +SC_TPQZ_WINDOW_VALID_BUSY = 7 +SC_QZQP_WINDOW_VALID_BUSY = 8 +SC_TRPK_WINDOW_VALID_BUSY = 9 +SC_STARVED_BY_PA = 10 +SC_STALLED_BY_PRIMFIFO = 11 +SC_STALLED_BY_DB_TILE = 12 +SC_STARVED_BY_DB_TILE = 13 +SC_STALLED_BY_TILEORDERFIFO = 14 +SC_STALLED_BY_TILEFIFO = 15 +SC_STALLED_BY_DB_QUAD = 16 +SC_STARVED_BY_DB_QUAD = 17 +SC_STALLED_BY_QUADFIFO = 18 +SC_STALLED_BY_BCI = 19 +SC_STALLED_BY_SPI = 20 +SC_SCISSOR_DISCARD = 21 +SC_BB_DISCARD = 22 +SC_SUPERTILE_COUNT = 23 +SC_SUPERTILE_PER_PRIM_H0 = 24 +SC_SUPERTILE_PER_PRIM_H1 = 25 +SC_SUPERTILE_PER_PRIM_H2 = 26 +SC_SUPERTILE_PER_PRIM_H3 = 27 +SC_SUPERTILE_PER_PRIM_H4 = 28 +SC_SUPERTILE_PER_PRIM_H5 = 29 +SC_SUPERTILE_PER_PRIM_H6 = 30 +SC_SUPERTILE_PER_PRIM_H7 = 31 +SC_SUPERTILE_PER_PRIM_H8 = 32 +SC_SUPERTILE_PER_PRIM_H9 = 33 +SC_SUPERTILE_PER_PRIM_H10 = 34 +SC_SUPERTILE_PER_PRIM_H11 = 35 +SC_SUPERTILE_PER_PRIM_H12 = 36 +SC_SUPERTILE_PER_PRIM_H13 = 37 +SC_SUPERTILE_PER_PRIM_H14 = 38 +SC_SUPERTILE_PER_PRIM_H15 = 39 +SC_SUPERTILE_PER_PRIM_H16 = 40 +SC_TILE_PER_PRIM_H0 = 41 +SC_TILE_PER_PRIM_H1 = 42 +SC_TILE_PER_PRIM_H2 = 43 +SC_TILE_PER_PRIM_H3 = 44 +SC_TILE_PER_PRIM_H4 = 45 +SC_TILE_PER_PRIM_H5 = 46 +SC_TILE_PER_PRIM_H6 = 47 +SC_TILE_PER_PRIM_H7 = 48 +SC_TILE_PER_PRIM_H8 = 49 +SC_TILE_PER_PRIM_H9 = 50 +SC_TILE_PER_PRIM_H10 = 51 +SC_TILE_PER_PRIM_H11 = 52 +SC_TILE_PER_PRIM_H12 = 53 +SC_TILE_PER_PRIM_H13 = 54 +SC_TILE_PER_PRIM_H14 = 55 +SC_TILE_PER_PRIM_H15 = 56 +SC_TILE_PER_PRIM_H16 = 57 +SC_TILE_PER_SUPERTILE_H0 = 58 +SC_TILE_PER_SUPERTILE_H1 = 59 +SC_TILE_PER_SUPERTILE_H2 = 60 +SC_TILE_PER_SUPERTILE_H3 = 61 +SC_TILE_PER_SUPERTILE_H4 = 62 +SC_TILE_PER_SUPERTILE_H5 = 63 +SC_TILE_PER_SUPERTILE_H6 = 64 +SC_TILE_PER_SUPERTILE_H7 = 65 +SC_TILE_PER_SUPERTILE_H8 = 66 +SC_TILE_PER_SUPERTILE_H9 = 67 +SC_TILE_PER_SUPERTILE_H10 = 68 +SC_TILE_PER_SUPERTILE_H11 = 69 +SC_TILE_PER_SUPERTILE_H12 = 70 +SC_TILE_PER_SUPERTILE_H13 = 71 +SC_TILE_PER_SUPERTILE_H14 = 72 +SC_TILE_PER_SUPERTILE_H15 = 73 +SC_TILE_PER_SUPERTILE_H16 = 74 +SC_TILE_PICKED_H1 = 75 +SC_TILE_PICKED_H2 = 76 +SC_TILE_PICKED_H3 = 77 +SC_TILE_PICKED_H4 = 78 +SC_QZ0_TILE_COUNT = 79 +SC_QZ1_TILE_COUNT = 80 +SC_QZ2_TILE_COUNT = 81 +SC_QZ3_TILE_COUNT = 82 +SC_QZ0_TILE_COVERED_COUNT = 83 +SC_QZ1_TILE_COVERED_COUNT = 84 +SC_QZ2_TILE_COVERED_COUNT = 85 +SC_QZ3_TILE_COVERED_COUNT = 86 +SC_QZ0_TILE_NOT_COVERED_COUNT = 87 +SC_QZ1_TILE_NOT_COVERED_COUNT = 88 +SC_QZ2_TILE_NOT_COVERED_COUNT = 89 +SC_QZ3_TILE_NOT_COVERED_COUNT = 90 +SC_QZ0_QUAD_PER_TILE_H0 = 91 +SC_QZ0_QUAD_PER_TILE_H1 = 92 +SC_QZ0_QUAD_PER_TILE_H2 = 93 +SC_QZ0_QUAD_PER_TILE_H3 = 94 +SC_QZ0_QUAD_PER_TILE_H4 = 95 +SC_QZ0_QUAD_PER_TILE_H5 = 96 +SC_QZ0_QUAD_PER_TILE_H6 = 97 +SC_QZ0_QUAD_PER_TILE_H7 = 98 +SC_QZ0_QUAD_PER_TILE_H8 = 99 +SC_QZ0_QUAD_PER_TILE_H9 = 100 +SC_QZ0_QUAD_PER_TILE_H10 = 101 +SC_QZ0_QUAD_PER_TILE_H11 = 102 +SC_QZ0_QUAD_PER_TILE_H12 = 103 +SC_QZ0_QUAD_PER_TILE_H13 = 104 +SC_QZ0_QUAD_PER_TILE_H14 = 105 +SC_QZ0_QUAD_PER_TILE_H15 = 106 +SC_QZ0_QUAD_PER_TILE_H16 = 107 +SC_QZ1_QUAD_PER_TILE_H0 = 108 +SC_QZ1_QUAD_PER_TILE_H1 = 109 +SC_QZ1_QUAD_PER_TILE_H2 = 110 +SC_QZ1_QUAD_PER_TILE_H3 = 111 +SC_QZ1_QUAD_PER_TILE_H4 = 112 +SC_QZ1_QUAD_PER_TILE_H5 = 113 +SC_QZ1_QUAD_PER_TILE_H6 = 114 +SC_QZ1_QUAD_PER_TILE_H7 = 115 +SC_QZ1_QUAD_PER_TILE_H8 = 116 +SC_QZ1_QUAD_PER_TILE_H9 = 117 +SC_QZ1_QUAD_PER_TILE_H10 = 118 +SC_QZ1_QUAD_PER_TILE_H11 = 119 +SC_QZ1_QUAD_PER_TILE_H12 = 120 +SC_QZ1_QUAD_PER_TILE_H13 = 121 +SC_QZ1_QUAD_PER_TILE_H14 = 122 +SC_QZ1_QUAD_PER_TILE_H15 = 123 +SC_QZ1_QUAD_PER_TILE_H16 = 124 +SC_QZ2_QUAD_PER_TILE_H0 = 125 +SC_QZ2_QUAD_PER_TILE_H1 = 126 +SC_QZ2_QUAD_PER_TILE_H2 = 127 +SC_QZ2_QUAD_PER_TILE_H3 = 128 +SC_QZ2_QUAD_PER_TILE_H4 = 129 +SC_QZ2_QUAD_PER_TILE_H5 = 130 +SC_QZ2_QUAD_PER_TILE_H6 = 131 +SC_QZ2_QUAD_PER_TILE_H7 = 132 +SC_QZ2_QUAD_PER_TILE_H8 = 133 +SC_QZ2_QUAD_PER_TILE_H9 = 134 +SC_QZ2_QUAD_PER_TILE_H10 = 135 +SC_QZ2_QUAD_PER_TILE_H11 = 136 +SC_QZ2_QUAD_PER_TILE_H12 = 137 +SC_QZ2_QUAD_PER_TILE_H13 = 138 +SC_QZ2_QUAD_PER_TILE_H14 = 139 +SC_QZ2_QUAD_PER_TILE_H15 = 140 +SC_QZ2_QUAD_PER_TILE_H16 = 141 +SC_QZ3_QUAD_PER_TILE_H0 = 142 +SC_QZ3_QUAD_PER_TILE_H1 = 143 +SC_QZ3_QUAD_PER_TILE_H2 = 144 +SC_QZ3_QUAD_PER_TILE_H3 = 145 +SC_QZ3_QUAD_PER_TILE_H4 = 146 +SC_QZ3_QUAD_PER_TILE_H5 = 147 +SC_QZ3_QUAD_PER_TILE_H6 = 148 +SC_QZ3_QUAD_PER_TILE_H7 = 149 +SC_QZ3_QUAD_PER_TILE_H8 = 150 +SC_QZ3_QUAD_PER_TILE_H9 = 151 +SC_QZ3_QUAD_PER_TILE_H10 = 152 +SC_QZ3_QUAD_PER_TILE_H11 = 153 +SC_QZ3_QUAD_PER_TILE_H12 = 154 +SC_QZ3_QUAD_PER_TILE_H13 = 155 +SC_QZ3_QUAD_PER_TILE_H14 = 156 +SC_QZ3_QUAD_PER_TILE_H15 = 157 +SC_QZ3_QUAD_PER_TILE_H16 = 158 +SC_QZ0_QUAD_COUNT = 159 +SC_QZ1_QUAD_COUNT = 160 +SC_QZ2_QUAD_COUNT = 161 +SC_QZ3_QUAD_COUNT = 162 +SC_P0_HIZ_TILE_COUNT = 163 +SC_P1_HIZ_TILE_COUNT = 164 +SC_P2_HIZ_TILE_COUNT = 165 +SC_P3_HIZ_TILE_COUNT = 166 +SC_P0_HIZ_QUAD_PER_TILE_H0 = 167 +SC_P0_HIZ_QUAD_PER_TILE_H1 = 168 +SC_P0_HIZ_QUAD_PER_TILE_H2 = 169 +SC_P0_HIZ_QUAD_PER_TILE_H3 = 170 +SC_P0_HIZ_QUAD_PER_TILE_H4 = 171 +SC_P0_HIZ_QUAD_PER_TILE_H5 = 172 +SC_P0_HIZ_QUAD_PER_TILE_H6 = 173 +SC_P0_HIZ_QUAD_PER_TILE_H7 = 174 +SC_P0_HIZ_QUAD_PER_TILE_H8 = 175 +SC_P0_HIZ_QUAD_PER_TILE_H9 = 176 +SC_P0_HIZ_QUAD_PER_TILE_H10 = 177 +SC_P0_HIZ_QUAD_PER_TILE_H11 = 178 +SC_P0_HIZ_QUAD_PER_TILE_H12 = 179 +SC_P0_HIZ_QUAD_PER_TILE_H13 = 180 +SC_P0_HIZ_QUAD_PER_TILE_H14 = 181 +SC_P0_HIZ_QUAD_PER_TILE_H15 = 182 +SC_P0_HIZ_QUAD_PER_TILE_H16 = 183 +SC_P1_HIZ_QUAD_PER_TILE_H0 = 184 +SC_P1_HIZ_QUAD_PER_TILE_H1 = 185 +SC_P1_HIZ_QUAD_PER_TILE_H2 = 186 +SC_P1_HIZ_QUAD_PER_TILE_H3 = 187 +SC_P1_HIZ_QUAD_PER_TILE_H4 = 188 +SC_P1_HIZ_QUAD_PER_TILE_H5 = 189 +SC_P1_HIZ_QUAD_PER_TILE_H6 = 190 +SC_P1_HIZ_QUAD_PER_TILE_H7 = 191 +SC_P1_HIZ_QUAD_PER_TILE_H8 = 192 +SC_P1_HIZ_QUAD_PER_TILE_H9 = 193 +SC_P1_HIZ_QUAD_PER_TILE_H10 = 194 +SC_P1_HIZ_QUAD_PER_TILE_H11 = 195 +SC_P1_HIZ_QUAD_PER_TILE_H12 = 196 +SC_P1_HIZ_QUAD_PER_TILE_H13 = 197 +SC_P1_HIZ_QUAD_PER_TILE_H14 = 198 +SC_P1_HIZ_QUAD_PER_TILE_H15 = 199 +SC_P1_HIZ_QUAD_PER_TILE_H16 = 200 +SC_P2_HIZ_QUAD_PER_TILE_H0 = 201 +SC_P2_HIZ_QUAD_PER_TILE_H1 = 202 +SC_P2_HIZ_QUAD_PER_TILE_H2 = 203 +SC_P2_HIZ_QUAD_PER_TILE_H3 = 204 +SC_P2_HIZ_QUAD_PER_TILE_H4 = 205 +SC_P2_HIZ_QUAD_PER_TILE_H5 = 206 +SC_P2_HIZ_QUAD_PER_TILE_H6 = 207 +SC_P2_HIZ_QUAD_PER_TILE_H7 = 208 +SC_P2_HIZ_QUAD_PER_TILE_H8 = 209 +SC_P2_HIZ_QUAD_PER_TILE_H9 = 210 +SC_P2_HIZ_QUAD_PER_TILE_H10 = 211 +SC_P2_HIZ_QUAD_PER_TILE_H11 = 212 +SC_P2_HIZ_QUAD_PER_TILE_H12 = 213 +SC_P2_HIZ_QUAD_PER_TILE_H13 = 214 +SC_P2_HIZ_QUAD_PER_TILE_H14 = 215 +SC_P2_HIZ_QUAD_PER_TILE_H15 = 216 +SC_P2_HIZ_QUAD_PER_TILE_H16 = 217 +SC_P3_HIZ_QUAD_PER_TILE_H0 = 218 +SC_P3_HIZ_QUAD_PER_TILE_H1 = 219 +SC_P3_HIZ_QUAD_PER_TILE_H2 = 220 +SC_P3_HIZ_QUAD_PER_TILE_H3 = 221 +SC_P3_HIZ_QUAD_PER_TILE_H4 = 222 +SC_P3_HIZ_QUAD_PER_TILE_H5 = 223 +SC_P3_HIZ_QUAD_PER_TILE_H6 = 224 +SC_P3_HIZ_QUAD_PER_TILE_H7 = 225 +SC_P3_HIZ_QUAD_PER_TILE_H8 = 226 +SC_P3_HIZ_QUAD_PER_TILE_H9 = 227 +SC_P3_HIZ_QUAD_PER_TILE_H10 = 228 +SC_P3_HIZ_QUAD_PER_TILE_H11 = 229 +SC_P3_HIZ_QUAD_PER_TILE_H12 = 230 +SC_P3_HIZ_QUAD_PER_TILE_H13 = 231 +SC_P3_HIZ_QUAD_PER_TILE_H14 = 232 +SC_P3_HIZ_QUAD_PER_TILE_H15 = 233 +SC_P3_HIZ_QUAD_PER_TILE_H16 = 234 +SC_P0_HIZ_QUAD_COUNT = 235 +SC_P1_HIZ_QUAD_COUNT = 236 +SC_P2_HIZ_QUAD_COUNT = 237 +SC_P3_HIZ_QUAD_COUNT = 238 +SC_P0_DETAIL_QUAD_COUNT = 239 +SC_P1_DETAIL_QUAD_COUNT = 240 +SC_P2_DETAIL_QUAD_COUNT = 241 +SC_P3_DETAIL_QUAD_COUNT = 242 +SC_P0_DETAIL_QUAD_WITH_1_PIX = 243 +SC_P0_DETAIL_QUAD_WITH_2_PIX = 244 +SC_P0_DETAIL_QUAD_WITH_3_PIX = 245 +SC_P0_DETAIL_QUAD_WITH_4_PIX = 246 +SC_P1_DETAIL_QUAD_WITH_1_PIX = 247 +SC_P1_DETAIL_QUAD_WITH_2_PIX = 248 +SC_P1_DETAIL_QUAD_WITH_3_PIX = 249 +SC_P1_DETAIL_QUAD_WITH_4_PIX = 250 +SC_P2_DETAIL_QUAD_WITH_1_PIX = 251 +SC_P2_DETAIL_QUAD_WITH_2_PIX = 252 +SC_P2_DETAIL_QUAD_WITH_3_PIX = 253 +SC_P2_DETAIL_QUAD_WITH_4_PIX = 254 +SC_P3_DETAIL_QUAD_WITH_1_PIX = 255 +SC_P3_DETAIL_QUAD_WITH_2_PIX = 256 +SC_P3_DETAIL_QUAD_WITH_3_PIX = 257 +SC_P3_DETAIL_QUAD_WITH_4_PIX = 258 +SC_EARLYZ_QUAD_COUNT = 259 +SC_EARLYZ_QUAD_WITH_1_PIX = 260 +SC_EARLYZ_QUAD_WITH_2_PIX = 261 +SC_EARLYZ_QUAD_WITH_3_PIX = 262 +SC_EARLYZ_QUAD_WITH_4_PIX = 263 +SC_PKR_QUAD_PER_ROW_H1 = 264 +SC_PKR_QUAD_PER_ROW_H2 = 265 +SC_PKR_4X2_QUAD_SPLIT = 266 +SC_PKR_4X2_FILL_QUAD = 267 +SC_PKR_END_OF_VECTOR = 268 +SC_PKR_CONTROL_XFER = 269 +SC_PKR_DBHANG_FORCE_EOV = 270 +SC_REG_SCLK_BUSY = 271 +SC_GRP0_DYN_SCLK_BUSY = 272 +SC_GRP1_DYN_SCLK_BUSY = 273 +SC_GRP2_DYN_SCLK_BUSY = 274 +SC_GRP3_DYN_SCLK_BUSY = 275 +SC_GRP4_DYN_SCLK_BUSY = 276 +SC_PA0_SC_DATA_FIFO_RD = 277 +SC_PA0_SC_DATA_FIFO_WE = 278 +SC_PA1_SC_DATA_FIFO_RD = 279 +SC_PA1_SC_DATA_FIFO_WE = 280 +SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 281 +SC_PS_ARB_XFC_ONLY_PRIM_CYCLES = 282 +SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 283 +SC_PS_ARB_STALLED_FROM_BELOW = 284 +SC_PS_ARB_STARVED_FROM_ABOVE = 285 +SC_PS_ARB_SC_BUSY = 286 +SC_PS_ARB_PA_SC_BUSY = 287 +SC_PA2_SC_DATA_FIFO_RD = 288 +SC_PA2_SC_DATA_FIFO_WE = 289 +SC_PA3_SC_DATA_FIFO_RD = 290 +SC_PA3_SC_DATA_FIFO_WE = 291 +SC_PA_SC_DEALLOC_0_0_WE = 292 +SC_PA_SC_DEALLOC_0_1_WE = 293 +SC_PA_SC_DEALLOC_1_0_WE = 294 +SC_PA_SC_DEALLOC_1_1_WE = 295 +SC_PA_SC_DEALLOC_2_0_WE = 296 +SC_PA_SC_DEALLOC_2_1_WE = 297 +SC_PA_SC_DEALLOC_3_0_WE = 298 +SC_PA_SC_DEALLOC_3_1_WE = 299 +SC_PA0_SC_EOP_WE = 300 +SC_PA0_SC_EOPG_WE = 301 +SC_PA0_SC_EVENT_WE = 302 +SC_PA1_SC_EOP_WE = 303 +SC_PA1_SC_EOPG_WE = 304 +SC_PA1_SC_EVENT_WE = 305 +SC_PA2_SC_EOP_WE = 306 +SC_PA2_SC_EOPG_WE = 307 +SC_PA2_SC_EVENT_WE = 308 +SC_PA3_SC_EOP_WE = 309 +SC_PA3_SC_EOPG_WE = 310 +SC_PA3_SC_EVENT_WE = 311 +SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO = 312 +SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH = 313 +SC_PS_ARB_NULL_PRIM_BUBBLE_POP = 314 +SC_PS_ARB_EOP_POP_SYNC_POP = 315 +SC_PS_ARB_EVENT_SYNC_POP = 316 +SC_PS_ENG_MULTICYCLE_BUBBLE = 317 +SC_PA0_SC_FPOV_WE = 318 +SC_PA1_SC_FPOV_WE = 319 +SC_PA2_SC_FPOV_WE = 320 +SC_PA3_SC_FPOV_WE = 321 +SC_PA0_SC_LPOV_WE = 322 +SC_PA1_SC_LPOV_WE = 323 +SC_PA2_SC_LPOV_WE = 324 +SC_PA3_SC_LPOV_WE = 325 +SC_SPI_DEALLOC_0_0 = 326 +SC_SPI_DEALLOC_0_1 = 327 +SC_SPI_DEALLOC_0_2 = 328 +SC_SPI_DEALLOC_1_0 = 329 +SC_SPI_DEALLOC_1_1 = 330 +SC_SPI_DEALLOC_1_2 = 331 +SC_SPI_DEALLOC_2_0 = 332 +SC_SPI_DEALLOC_2_1 = 333 +SC_SPI_DEALLOC_2_2 = 334 +SC_SPI_DEALLOC_3_0 = 335 +SC_SPI_DEALLOC_3_1 = 336 +SC_SPI_DEALLOC_3_2 = 337 +SC_SPI_FPOV_0 = 338 +SC_SPI_FPOV_1 = 339 +SC_SPI_FPOV_2 = 340 +SC_SPI_FPOV_3 = 341 +SC_SPI_EVENT = 342 +SC_PS_TS_EVENT_FIFO_PUSH = 343 +SC_PS_TS_EVENT_FIFO_POP = 344 +SC_PS_CTX_DONE_FIFO_PUSH = 345 +SC_PS_CTX_DONE_FIFO_POP = 346 +SC_MULTICYCLE_BUBBLE_FREEZE = 347 +SC_EOP_SYNC_WINDOW = 348 +SC_PA0_SC_NULL_WE = 349 +SC_PA0_SC_NULL_DEALLOC_WE = 350 +SC_PA0_SC_DATA_FIFO_EOPG_RD = 351 +SC_PA0_SC_DATA_FIFO_EOP_RD = 352 +SC_PA0_SC_DEALLOC_0_RD = 353 +SC_PA0_SC_DEALLOC_1_RD = 354 +SC_PA1_SC_DATA_FIFO_EOPG_RD = 355 +SC_PA1_SC_DATA_FIFO_EOP_RD = 356 +SC_PA1_SC_DEALLOC_0_RD = 357 +SC_PA1_SC_DEALLOC_1_RD = 358 +SC_PA1_SC_NULL_WE = 359 +SC_PA1_SC_NULL_DEALLOC_WE = 360 +SC_PA2_SC_DATA_FIFO_EOPG_RD = 361 +SC_PA2_SC_DATA_FIFO_EOP_RD = 362 +SC_PA2_SC_DEALLOC_0_RD = 363 +SC_PA2_SC_DEALLOC_1_RD = 364 +SC_PA2_SC_NULL_WE = 365 +SC_PA2_SC_NULL_DEALLOC_WE = 366 +SC_PA3_SC_DATA_FIFO_EOPG_RD = 367 +SC_PA3_SC_DATA_FIFO_EOP_RD = 368 +SC_PA3_SC_DEALLOC_0_RD = 369 +SC_PA3_SC_DEALLOC_1_RD = 370 +SC_PA3_SC_NULL_WE = 371 +SC_PA3_SC_NULL_DEALLOC_WE = 372 +SC_PS_PA0_SC_FIFO_EMPTY = 373 +SC_PS_PA0_SC_FIFO_FULL = 374 +SC_RESERVED_0 = 375 +SC_PS_PA1_SC_FIFO_EMPTY = 376 +SC_PS_PA1_SC_FIFO_FULL = 377 +SC_RESERVED_1 = 378 +SC_PS_PA2_SC_FIFO_EMPTY = 379 +SC_PS_PA2_SC_FIFO_FULL = 380 +SC_RESERVED_2 = 381 +SC_PS_PA3_SC_FIFO_EMPTY = 382 +SC_PS_PA3_SC_FIFO_FULL = 383 +SC_RESERVED_3 = 384 +SC_BUSY_PROCESSING_MULTICYCLE_PRIM = 385 +SC_BUSY_CNT_NOT_ZERO = 386 +SC_BM_BUSY = 387 +SC_BACKEND_BUSY = 388 +SC_SCF_SCB_INTERFACE_BUSY = 389 +SC_SCB_BUSY = 390 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY = 391 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL = 392 +SC_PBB_BIN_HIST_NUM_PRIMS = 393 +SC_PBB_BATCH_HIST_NUM_PRIMS = 394 +SC_PBB_BIN_HIST_NUM_CONTEXTS = 395 +SC_PBB_BATCH_HIST_NUM_CONTEXTS = 396 +SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES = 397 +SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES = 398 +SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS = 399 +SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS = 400 +SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM = 401 +SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW = 402 +SC_PBB_BUSY = 403 +SC_PBB_BUSY_AND_NO_SENDS = 404 +SC_PBB_STALLS_PA_DUE_TO_NO_TILES = 405 +SC_PBB_NUM_BINS = 406 +SC_PBB_END_OF_BIN = 407 +SC_PBB_END_OF_BATCH = 408 +SC_PBB_PRIMBIN_PROCESSED = 409 +SC_PBB_PRIM_ADDED_TO_BATCH = 410 +SC_PBB_NONBINNED_PRIM = 411 +SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB = 412 +SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB = 413 +SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION = 414 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW = 415 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN = 416 +SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE = 417 +SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE = 418 +SC_PBB_BATCH_BREAK_DUE_TO_PRIM = 419 +SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE = 420 +SC_PBB_BATCH_BREAK_DUE_TO_EVENT = 421 +SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT = 422 +SC_POPS_INTRA_WAVE_OVERLAPS = 423 +SC_POPS_FORCE_EOV = 424 +SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX = 425 +SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP = 426 +SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE = 427 +SC_FULL_FULL_QUAD = 428 +SC_FULL_HALF_QUAD = 429 +SC_FULL_QTR_QUAD = 430 +SC_HALF_FULL_QUAD = 431 +SC_HALF_HALF_QUAD = 432 +SC_HALF_QTR_QUAD = 433 +SC_QTR_FULL_QUAD = 434 +SC_QTR_HALF_QUAD = 435 +SC_QTR_QTR_QUAD = 436 +SC_GRP5_DYN_SCLK_BUSY = 437 +SC_GRP6_DYN_SCLK_BUSY = 438 +SC_GRP7_DYN_SCLK_BUSY = 439 +SC_GRP8_DYN_SCLK_BUSY = 440 +SC_GRP9_DYN_SCLK_BUSY = 441 +SC_PS_TO_BE_SCLK_GATE_STALL = 442 +SC_PA_TO_PBB_SCLK_GATE_STALL_STALL = 443 +SC_PK_BUSY = 444 +SC_PK_MAX_DEALLOC_FORCE_EOV = 445 +SC_PK_DEALLOC_WAVE_BREAK = 446 +SC_SPI_SEND = 447 +SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 448 +SC_SPI_CREDIT_AT_MAX = 449 +SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND = 450 +SC_BCI_SEND = 451 +SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 452 +SC_BCI_CREDIT_AT_MAX = 453 +SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND = 454 +SC_SPIBC_FULL_FREEZE = 455 +SC_PW_BM_PASS_EMPTY_PRIM = 456 +SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM = 457 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0 = 458 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1 = 459 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2 = 460 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3 = 461 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4 = 462 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5 = 463 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6 = 464 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7 = 465 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8 = 466 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9 = 467 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10 = 468 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11 = 469 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12 = 470 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13 = 471 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14 = 472 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15 = 473 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16 = 474 +SC_DB0_TILE_INTERFACE_BUSY = 475 +SC_DB0_TILE_INTERFACE_SEND = 476 +SC_DB0_TILE_INTERFACE_SEND_EVENT = 477 +SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT = 478 +SC_DB0_TILE_INTERFACE_SEND_SOP = 479 +SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND = 480 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX = 481 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND = 482 +SC_DB1_TILE_INTERFACE_BUSY = 483 +SC_DB1_TILE_INTERFACE_SEND = 484 +SC_DB1_TILE_INTERFACE_SEND_EVENT = 485 +SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT = 486 +SC_DB1_TILE_INTERFACE_SEND_SOP = 487 +SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND = 488 +SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX = 489 +SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND = 490 +SC_BACKEND_PRIM_FIFO_FULL = 491 +SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER = 492 +SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH = 493 +SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH = 494 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT = 495 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT = 496 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV = 497 +SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE = 498 +SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE = 499 +SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT = 500 +SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET = 501 +SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE = 502 +SC_STALLED_BY_DB0_TILEFIFO = 503 +SC_DB0_QUAD_INTF_SEND = 504 +SC_DB0_QUAD_INTF_BUSY = 505 +SC_DB0_QUAD_INTF_STALLED_BY_DB = 506 +SC_DB0_QUAD_INTF_CREDIT_AT_MAX = 507 +SC_DB0_QUAD_INTF_IDLE = 508 +SC_DB1_QUAD_INTF_SEND = 509 +SC_STALLED_BY_DB1_TILEFIFO = 510 +SC_DB1_QUAD_INTF_BUSY = 511 +SC_DB1_QUAD_INTF_STALLED_BY_DB = 512 +SC_DB1_QUAD_INTF_CREDIT_AT_MAX = 513 +SC_DB1_QUAD_INTF_IDLE = 514 +SC_PKR_WAVE_BREAK_OUTSIDE_REGION = 515 +SC_PKR_WAVE_BREAK_FULL_TILE = 516 +SC_FSR_WALKED = 517 +SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN = 518 +SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT = 519 +SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL = 520 +SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL = 521 +SC_DB0_TILE_MASK_FIFO_FULL = 522 +SC_DB1_WE_STALLED_BY_RSLT_FIFO_FULL = 523 +SC_DB1_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL = 524 +SC_DB1_TILE_MASK_FIFO_FULL = 525 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL = 526 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL = 527 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL = 528 +SC_PS_PM_PFF_PW_FULL = 529 +SC_PS_PM_ZFF_PW_FULL = 530 +SC_PS_PM_PBB_TO_PSE_FIFO_FULL = 531 +SC_PK_PM_QD1_FD_CONFLICT_WAVE_BRK_1H = 532 +SC_PK_PM_QD1_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H = 533 +SC_PK_PM_QD1_AVOID_DEALLOC_ADD_WAVE_BRK_1H = 534 +SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H = 535 +SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H = 536 +SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H = 537 +SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H = 538 +SC_PK_PM_LAST_AND_DEALLOC_WAVE_BRK_1H = 539 +SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H = 540 +SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H = 541 +SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H = 542 +SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H = 543 +SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H = 544 +SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H = 545 +SC_PK_PM_FULL_TILE_WAVE_BRK_1H = 546 +SC_PK_PM_POPS_FORCE_EOV_WAVE_BRK_1H = 547 +SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H = 548 +SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H = 549 +SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H = 550 +SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H = 551 +SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD = 552 +SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD = 553 +SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD = 554 +SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD = 555 +SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD = 556 +SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD = 557 +SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD = 558 +SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD = 559 +SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD = 560 +SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD = 561 +SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD = 562 +SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD = 563 +SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD = 564 +SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD = 565 +SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD = 566 +SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD = 567 +SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_MODE_CHANGE = 568 +SC_PBB_RESERVED = 569 +SC_BM_BE0_STALLED = 570 +SC_BM_BE1_STALLED = 571 +SC_BM_BE2_STALLED = 572 +SC_BM_BE3_STALLED = 573 +SC_BM_MULTI_ACCUM_1_BE_STALLED = 574 +SC_BM_MULTI_ACCUM_2_BE_STALLED = 575 +SC_BM_MULTI_ACCUM_3_BE_STALLED = 576 +SC_BM_MULTI_ACCUM_4_BE_STALLED = 577 +SC_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ScMap' +ScMap__enumvalues = { + 0: 'RASTER_CONFIG_SC_MAP_0', + 1: 'RASTER_CONFIG_SC_MAP_1', + 2: 'RASTER_CONFIG_SC_MAP_2', + 3: 'RASTER_CONFIG_SC_MAP_3', +} +RASTER_CONFIG_SC_MAP_0 = 0 +RASTER_CONFIG_SC_MAP_1 = 1 +RASTER_CONFIG_SC_MAP_2 = 2 +RASTER_CONFIG_SC_MAP_3 = 3 +ScMap = ctypes.c_uint32 # enum + +# values for enumeration 'ScUncertaintyRegionMode' +ScUncertaintyRegionMode__enumvalues = { + 0: 'SC_HALF_LSB', + 1: 'SC_LSB_ONE_SIDED', + 2: 'SC_LSB_TWO_SIDED', +} +SC_HALF_LSB = 0 +SC_LSB_ONE_SIDED = 1 +SC_LSB_TWO_SIDED = 2 +ScUncertaintyRegionMode = ctypes.c_uint32 # enum + +# values for enumeration 'ScUncertaintyRegionMult' +ScUncertaintyRegionMult__enumvalues = { + 0: 'SC_UR_1X', + 1: 'SC_UR_2X', + 2: 'SC_UR_4X', + 3: 'SC_UR_8X', +} +SC_UR_1X = 0 +SC_UR_2X = 1 +SC_UR_4X = 2 +SC_UR_8X = 3 +ScUncertaintyRegionMult = ctypes.c_uint32 # enum + +# values for enumeration 'ScXsel' +ScXsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_XSEL_64_WIDE_TILE = 3 +ScXsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScYsel' +ScYsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_YSEL_64_WIDE_TILE = 3 +ScYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeMap' +SeMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_MAP_0', + 1: 'RASTER_CONFIG_SE_MAP_1', + 2: 'RASTER_CONFIG_SE_MAP_2', + 3: 'RASTER_CONFIG_SE_MAP_3', +} +RASTER_CONFIG_SE_MAP_0 = 0 +RASTER_CONFIG_SE_MAP_1 = 1 +RASTER_CONFIG_SE_MAP_2 = 2 +RASTER_CONFIG_SE_MAP_3 = 3 +SeMap = ctypes.c_uint32 # enum + +# values for enumeration 'SePairMap' +SePairMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_MAP_0', + 1: 'RASTER_CONFIG_SE_PAIR_MAP_1', + 2: 'RASTER_CONFIG_SE_PAIR_MAP_2', + 3: 'RASTER_CONFIG_SE_PAIR_MAP_3', +} +RASTER_CONFIG_SE_PAIR_MAP_0 = 0 +RASTER_CONFIG_SE_PAIR_MAP_1 = 1 +RASTER_CONFIG_SE_PAIR_MAP_2 = 2 +RASTER_CONFIG_SE_PAIR_MAP_3 = 3 +SePairMap = ctypes.c_uint32 # enum + +# values for enumeration 'SePairXsel' +SePairXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE = 3 +SePairXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairYsel' +SePairYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE = 3 +SePairYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeXsel' +SeXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_XSEL_64_WIDE_TILE = 3 +SeXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeYsel' +SeYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_YSEL_64_WIDE_TILE = 3 +SeYsel = ctypes.c_uint32 # enum + +# values for enumeration 'VRSCombinerModeSC' +VRSCombinerModeSC__enumvalues = { + 0: 'SC_VRS_COMB_MODE_PASSTHRU', + 1: 'SC_VRS_COMB_MODE_OVERRIDE', + 2: 'SC_VRS_COMB_MODE_MIN', + 3: 'SC_VRS_COMB_MODE_MAX', + 4: 'SC_VRS_COMB_MODE_SATURATE', +} +SC_VRS_COMB_MODE_PASSTHRU = 0 +SC_VRS_COMB_MODE_OVERRIDE = 1 +SC_VRS_COMB_MODE_MIN = 2 +SC_VRS_COMB_MODE_MAX = 3 +SC_VRS_COMB_MODE_SATURATE = 4 +VRSCombinerModeSC = ctypes.c_uint32 # enum + +# values for enumeration 'VRSrate' +VRSrate__enumvalues = { + 0: 'VRS_SHADING_RATE_1X1', + 1: 'VRS_SHADING_RATE_1X2', + 2: 'VRS_SHADING_RATE_UNDEFINED0', + 3: 'VRS_SHADING_RATE_UNDEFINED1', + 4: 'VRS_SHADING_RATE_2X1', + 5: 'VRS_SHADING_RATE_2X2', + 6: 'VRS_SHADING_RATE_2X4', + 7: 'VRS_SHADING_RATE_UNDEFINED2', + 8: 'VRS_SHADING_RATE_UNDEFINED3', + 9: 'VRS_SHADING_RATE_4X2', + 10: 'VRS_SHADING_RATE_4X4', + 11: 'VRS_SHADING_RATE_UNDEFINED4', + 12: 'VRS_SHADING_RATE_16X_SSAA', + 13: 'VRS_SHADING_RATE_8X_SSAA', + 14: 'VRS_SHADING_RATE_4X_SSAA', + 15: 'VRS_SHADING_RATE_2X_SSAA', +} +VRS_SHADING_RATE_1X1 = 0 +VRS_SHADING_RATE_1X2 = 1 +VRS_SHADING_RATE_UNDEFINED0 = 2 +VRS_SHADING_RATE_UNDEFINED1 = 3 +VRS_SHADING_RATE_2X1 = 4 +VRS_SHADING_RATE_2X2 = 5 +VRS_SHADING_RATE_2X4 = 6 +VRS_SHADING_RATE_UNDEFINED2 = 7 +VRS_SHADING_RATE_UNDEFINED3 = 8 +VRS_SHADING_RATE_4X2 = 9 +VRS_SHADING_RATE_4X4 = 10 +VRS_SHADING_RATE_UNDEFINED4 = 11 +VRS_SHADING_RATE_16X_SSAA = 12 +VRS_SHADING_RATE_8X_SSAA = 13 +VRS_SHADING_RATE_4X_SSAA = 14 +VRS_SHADING_RATE_2X_SSAA = 15 +VRSrate = ctypes.c_uint32 # enum + +# values for enumeration 'TC_EA_CID' +TC_EA_CID__enumvalues = { + 0: 'TC_EA_CID_RT', + 1: 'TC_EA_CID_FMASK', + 2: 'TC_EA_CID_DCC', + 3: 'TC_EA_CID_TCPMETA', + 4: 'TC_EA_CID_Z', + 5: 'TC_EA_CID_STENCIL', + 6: 'TC_EA_CID_HTILE', + 7: 'TC_EA_CID_MISC', + 8: 'TC_EA_CID_TCP', + 9: 'TC_EA_CID_SQC', + 10: 'TC_EA_CID_CPF', + 11: 'TC_EA_CID_CPG', + 12: 'TC_EA_CID_IA', + 13: 'TC_EA_CID_WD', + 14: 'TC_EA_CID_PA', + 15: 'TC_EA_CID_UTCL2_TPI', +} +TC_EA_CID_RT = 0 +TC_EA_CID_FMASK = 1 +TC_EA_CID_DCC = 2 +TC_EA_CID_TCPMETA = 3 +TC_EA_CID_Z = 4 +TC_EA_CID_STENCIL = 5 +TC_EA_CID_HTILE = 6 +TC_EA_CID_MISC = 7 +TC_EA_CID_TCP = 8 +TC_EA_CID_SQC = 9 +TC_EA_CID_CPF = 10 +TC_EA_CID_CPG = 11 +TC_EA_CID_IA = 12 +TC_EA_CID_WD = 13 +TC_EA_CID_PA = 14 +TC_EA_CID_UTCL2_TPI = 15 +TC_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'TC_NACKS' +TC_NACKS__enumvalues = { + 0: 'TC_NACK_NO_FAULT', + 1: 'TC_NACK_PAGE_FAULT', + 2: 'TC_NACK_PROTECTION_FAULT', + 3: 'TC_NACK_DATA_ERROR', +} +TC_NACK_NO_FAULT = 0 +TC_NACK_PAGE_FAULT = 1 +TC_NACK_PROTECTION_FAULT = 2 +TC_NACK_DATA_ERROR = 3 +TC_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP' +TC_OP__enumvalues = { + 0: 'TC_OP_READ', + 1: 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'TC_OP_ATOMIC_FMIN_RTN_32', + 3: 'TC_OP_ATOMIC_FMAX_RTN_32', + 4: 'TC_OP_RESERVED_FOP_RTN_32_0', + 5: 'TC_OP_RESERVED_FADD_RTN_32', + 6: 'TC_OP_RESERVED_FOP_RTN_32_2', + 7: 'TC_OP_ATOMIC_SWAP_RTN_32', + 8: 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'TC_OP_PROBE_FILTER', + 13: 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 14: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'TC_OP_ATOMIC_ADD_RTN_32', + 16: 'TC_OP_ATOMIC_SUB_RTN_32', + 17: 'TC_OP_ATOMIC_SMIN_RTN_32', + 18: 'TC_OP_ATOMIC_UMIN_RTN_32', + 19: 'TC_OP_ATOMIC_SMAX_RTN_32', + 20: 'TC_OP_ATOMIC_UMAX_RTN_32', + 21: 'TC_OP_ATOMIC_AND_RTN_32', + 22: 'TC_OP_ATOMIC_OR_RTN_32', + 23: 'TC_OP_ATOMIC_XOR_RTN_32', + 24: 'TC_OP_ATOMIC_INC_RTN_32', + 25: 'TC_OP_ATOMIC_DEC_RTN_32', + 26: 'TC_OP_WBINVL1_VOL', + 27: 'TC_OP_WBINVL1_SD', + 28: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 29: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 30: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 31: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 32: 'TC_OP_WRITE', + 33: 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'TC_OP_ATOMIC_FMIN_RTN_64', + 35: 'TC_OP_ATOMIC_FMAX_RTN_64', + 36: 'TC_OP_RESERVED_FOP_RTN_64_0', + 37: 'TC_OP_RESERVED_FOP_RTN_64_1', + 38: 'TC_OP_RESERVED_FOP_RTN_64_2', + 39: 'TC_OP_ATOMIC_SWAP_RTN_64', + 40: 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 44: 'TC_OP_WBINVL2_SD', + 45: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 46: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 47: 'TC_OP_ATOMIC_ADD_RTN_64', + 48: 'TC_OP_ATOMIC_SUB_RTN_64', + 49: 'TC_OP_ATOMIC_SMIN_RTN_64', + 50: 'TC_OP_ATOMIC_UMIN_RTN_64', + 51: 'TC_OP_ATOMIC_SMAX_RTN_64', + 52: 'TC_OP_ATOMIC_UMAX_RTN_64', + 53: 'TC_OP_ATOMIC_AND_RTN_64', + 54: 'TC_OP_ATOMIC_OR_RTN_64', + 55: 'TC_OP_ATOMIC_XOR_RTN_64', + 56: 'TC_OP_ATOMIC_INC_RTN_64', + 57: 'TC_OP_ATOMIC_DEC_RTN_64', + 58: 'TC_OP_WBL2_NC', + 59: 'TC_OP_WBL2_WC', + 60: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 61: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 62: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 63: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', + 64: 'TC_OP_WBINVL1', + 65: 'TC_OP_ATOMIC_FCMPSWAP_32', + 66: 'TC_OP_ATOMIC_FMIN_32', + 67: 'TC_OP_ATOMIC_FMAX_32', + 68: 'TC_OP_RESERVED_FOP_32_0', + 69: 'TC_OP_RESERVED_FADD_32', + 70: 'TC_OP_RESERVED_FOP_32_2', + 71: 'TC_OP_ATOMIC_SWAP_32', + 72: 'TC_OP_ATOMIC_CMPSWAP_32', + 73: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'TC_OP_INV_METADATA', + 77: 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 78: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 79: 'TC_OP_ATOMIC_ADD_32', + 80: 'TC_OP_ATOMIC_SUB_32', + 81: 'TC_OP_ATOMIC_SMIN_32', + 82: 'TC_OP_ATOMIC_UMIN_32', + 83: 'TC_OP_ATOMIC_SMAX_32', + 84: 'TC_OP_ATOMIC_UMAX_32', + 85: 'TC_OP_ATOMIC_AND_32', + 86: 'TC_OP_ATOMIC_OR_32', + 87: 'TC_OP_ATOMIC_XOR_32', + 88: 'TC_OP_ATOMIC_INC_32', + 89: 'TC_OP_ATOMIC_DEC_32', + 90: 'TC_OP_INVL2_NC', + 91: 'TC_OP_NOP_RTN0', + 92: 'TC_OP_RESERVED_NON_FLOAT_32_1', + 93: 'TC_OP_RESERVED_NON_FLOAT_32_2', + 94: 'TC_OP_RESERVED_NON_FLOAT_32_3', + 95: 'TC_OP_RESERVED_NON_FLOAT_32_4', + 96: 'TC_OP_WBINVL2', + 97: 'TC_OP_ATOMIC_FCMPSWAP_64', + 98: 'TC_OP_ATOMIC_FMIN_64', + 99: 'TC_OP_ATOMIC_FMAX_64', + 100: 'TC_OP_RESERVED_FOP_64_0', + 101: 'TC_OP_RESERVED_FOP_64_1', + 102: 'TC_OP_RESERVED_FOP_64_2', + 103: 'TC_OP_ATOMIC_SWAP_64', + 104: 'TC_OP_ATOMIC_CMPSWAP_64', + 105: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 108: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 109: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 110: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 111: 'TC_OP_ATOMIC_ADD_64', + 112: 'TC_OP_ATOMIC_SUB_64', + 113: 'TC_OP_ATOMIC_SMIN_64', + 114: 'TC_OP_ATOMIC_UMIN_64', + 115: 'TC_OP_ATOMIC_SMAX_64', + 116: 'TC_OP_ATOMIC_UMAX_64', + 117: 'TC_OP_ATOMIC_AND_64', + 118: 'TC_OP_ATOMIC_OR_64', + 119: 'TC_OP_ATOMIC_XOR_64', + 120: 'TC_OP_ATOMIC_INC_64', + 121: 'TC_OP_ATOMIC_DEC_64', + 122: 'TC_OP_WBINVL2_NC', + 123: 'TC_OP_NOP_ACK', + 124: 'TC_OP_RESERVED_NON_FLOAT_64_1', + 125: 'TC_OP_RESERVED_NON_FLOAT_64_2', + 126: 'TC_OP_RESERVED_NON_FLOAT_64_3', + 127: 'TC_OP_RESERVED_NON_FLOAT_64_4', +} +TC_OP_READ = 0 +TC_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +TC_OP_ATOMIC_FMIN_RTN_32 = 2 +TC_OP_ATOMIC_FMAX_RTN_32 = 3 +TC_OP_RESERVED_FOP_RTN_32_0 = 4 +TC_OP_RESERVED_FADD_RTN_32 = 5 +TC_OP_RESERVED_FOP_RTN_32_2 = 6 +TC_OP_ATOMIC_SWAP_RTN_32 = 7 +TC_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +TC_OP_PROBE_FILTER = 12 +TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32 = 13 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +TC_OP_ATOMIC_ADD_RTN_32 = 15 +TC_OP_ATOMIC_SUB_RTN_32 = 16 +TC_OP_ATOMIC_SMIN_RTN_32 = 17 +TC_OP_ATOMIC_UMIN_RTN_32 = 18 +TC_OP_ATOMIC_SMAX_RTN_32 = 19 +TC_OP_ATOMIC_UMAX_RTN_32 = 20 +TC_OP_ATOMIC_AND_RTN_32 = 21 +TC_OP_ATOMIC_OR_RTN_32 = 22 +TC_OP_ATOMIC_XOR_RTN_32 = 23 +TC_OP_ATOMIC_INC_RTN_32 = 24 +TC_OP_ATOMIC_DEC_RTN_32 = 25 +TC_OP_WBINVL1_VOL = 26 +TC_OP_WBINVL1_SD = 27 +TC_OP_RESERVED_NON_FLOAT_RTN_32_0 = 28 +TC_OP_RESERVED_NON_FLOAT_RTN_32_1 = 29 +TC_OP_RESERVED_NON_FLOAT_RTN_32_2 = 30 +TC_OP_RESERVED_NON_FLOAT_RTN_32_3 = 31 +TC_OP_WRITE = 32 +TC_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +TC_OP_ATOMIC_FMIN_RTN_64 = 34 +TC_OP_ATOMIC_FMAX_RTN_64 = 35 +TC_OP_RESERVED_FOP_RTN_64_0 = 36 +TC_OP_RESERVED_FOP_RTN_64_1 = 37 +TC_OP_RESERVED_FOP_RTN_64_2 = 38 +TC_OP_ATOMIC_SWAP_RTN_64 = 39 +TC_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +TC_OP_WBINVL2_SD = 44 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0 = 45 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1 = 46 +TC_OP_ATOMIC_ADD_RTN_64 = 47 +TC_OP_ATOMIC_SUB_RTN_64 = 48 +TC_OP_ATOMIC_SMIN_RTN_64 = 49 +TC_OP_ATOMIC_UMIN_RTN_64 = 50 +TC_OP_ATOMIC_SMAX_RTN_64 = 51 +TC_OP_ATOMIC_UMAX_RTN_64 = 52 +TC_OP_ATOMIC_AND_RTN_64 = 53 +TC_OP_ATOMIC_OR_RTN_64 = 54 +TC_OP_ATOMIC_XOR_RTN_64 = 55 +TC_OP_ATOMIC_INC_RTN_64 = 56 +TC_OP_ATOMIC_DEC_RTN_64 = 57 +TC_OP_WBL2_NC = 58 +TC_OP_WBL2_WC = 59 +TC_OP_RESERVED_NON_FLOAT_RTN_64_1 = 60 +TC_OP_RESERVED_NON_FLOAT_RTN_64_2 = 61 +TC_OP_RESERVED_NON_FLOAT_RTN_64_3 = 62 +TC_OP_RESERVED_NON_FLOAT_RTN_64_4 = 63 +TC_OP_WBINVL1 = 64 +TC_OP_ATOMIC_FCMPSWAP_32 = 65 +TC_OP_ATOMIC_FMIN_32 = 66 +TC_OP_ATOMIC_FMAX_32 = 67 +TC_OP_RESERVED_FOP_32_0 = 68 +TC_OP_RESERVED_FADD_32 = 69 +TC_OP_RESERVED_FOP_32_2 = 70 +TC_OP_ATOMIC_SWAP_32 = 71 +TC_OP_ATOMIC_CMPSWAP_32 = 72 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +TC_OP_INV_METADATA = 76 +TC_OP_ATOMIC_FADD_FLUSH_DENORM_32 = 77 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2 = 78 +TC_OP_ATOMIC_ADD_32 = 79 +TC_OP_ATOMIC_SUB_32 = 80 +TC_OP_ATOMIC_SMIN_32 = 81 +TC_OP_ATOMIC_UMIN_32 = 82 +TC_OP_ATOMIC_SMAX_32 = 83 +TC_OP_ATOMIC_UMAX_32 = 84 +TC_OP_ATOMIC_AND_32 = 85 +TC_OP_ATOMIC_OR_32 = 86 +TC_OP_ATOMIC_XOR_32 = 87 +TC_OP_ATOMIC_INC_32 = 88 +TC_OP_ATOMIC_DEC_32 = 89 +TC_OP_INVL2_NC = 90 +TC_OP_NOP_RTN0 = 91 +TC_OP_RESERVED_NON_FLOAT_32_1 = 92 +TC_OP_RESERVED_NON_FLOAT_32_2 = 93 +TC_OP_RESERVED_NON_FLOAT_32_3 = 94 +TC_OP_RESERVED_NON_FLOAT_32_4 = 95 +TC_OP_WBINVL2 = 96 +TC_OP_ATOMIC_FCMPSWAP_64 = 97 +TC_OP_ATOMIC_FMIN_64 = 98 +TC_OP_ATOMIC_FMAX_64 = 99 +TC_OP_RESERVED_FOP_64_0 = 100 +TC_OP_RESERVED_FOP_64_1 = 101 +TC_OP_RESERVED_FOP_64_2 = 102 +TC_OP_ATOMIC_SWAP_64 = 103 +TC_OP_ATOMIC_CMPSWAP_64 = 104 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0 = 108 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1 = 109 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2 = 110 +TC_OP_ATOMIC_ADD_64 = 111 +TC_OP_ATOMIC_SUB_64 = 112 +TC_OP_ATOMIC_SMIN_64 = 113 +TC_OP_ATOMIC_UMIN_64 = 114 +TC_OP_ATOMIC_SMAX_64 = 115 +TC_OP_ATOMIC_UMAX_64 = 116 +TC_OP_ATOMIC_AND_64 = 117 +TC_OP_ATOMIC_OR_64 = 118 +TC_OP_ATOMIC_XOR_64 = 119 +TC_OP_ATOMIC_INC_64 = 120 +TC_OP_ATOMIC_DEC_64 = 121 +TC_OP_WBINVL2_NC = 122 +TC_OP_NOP_ACK = 123 +TC_OP_RESERVED_NON_FLOAT_64_1 = 124 +TC_OP_RESERVED_NON_FLOAT_64_2 = 125 +TC_OP_RESERVED_NON_FLOAT_64_3 = 126 +TC_OP_RESERVED_NON_FLOAT_64_4 = 127 +TC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP_MASKS' +TC_OP_MASKS__enumvalues = { + 8: 'TC_OP_MASK_FLUSH_DENROM', + 32: 'TC_OP_MASK_64', + 64: 'TC_OP_MASK_NO_RTN', +} +TC_OP_MASK_FLUSH_DENROM = 8 +TC_OP_MASK_64 = 32 +TC_OP_MASK_NO_RTN = 64 +TC_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_EA_CID' +GL2_EA_CID__enumvalues = { + 0: 'GL2_EA_CID_CLIENT', + 1: 'GL2_EA_CID_SDMA', + 2: 'GL2_EA_CID_RLC', + 3: 'GL2_EA_CID_SQC', + 4: 'GL2_EA_CID_CP', + 5: 'GL2_EA_CID_CPDMA', + 6: 'GL2_EA_CID_UTCL2', + 7: 'GL2_EA_CID_RT', + 8: 'GL2_EA_CID_FMASK', + 9: 'GL2_EA_CID_DCC', + 10: 'GL2_EA_CID_Z_STENCIL', + 11: 'GL2_EA_CID_ZPCPSD', + 12: 'GL2_EA_CID_HTILE', + 13: 'GL2_EA_CID_MES', + 15: 'GL2_EA_CID_TCPMETA', +} +GL2_EA_CID_CLIENT = 0 +GL2_EA_CID_SDMA = 1 +GL2_EA_CID_RLC = 2 +GL2_EA_CID_SQC = 3 +GL2_EA_CID_CP = 4 +GL2_EA_CID_CPDMA = 5 +GL2_EA_CID_UTCL2 = 6 +GL2_EA_CID_RT = 7 +GL2_EA_CID_FMASK = 8 +GL2_EA_CID_DCC = 9 +GL2_EA_CID_Z_STENCIL = 10 +GL2_EA_CID_ZPCPSD = 11 +GL2_EA_CID_HTILE = 12 +GL2_EA_CID_MES = 13 +GL2_EA_CID_TCPMETA = 15 +GL2_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_NACKS' +GL2_NACKS__enumvalues = { + 0: 'GL2_NACK_NO_FAULT', + 1: 'GL2_NACK_PAGE_FAULT', + 2: 'GL2_NACK_PROTECTION_FAULT', + 3: 'GL2_NACK_DATA_ERROR', +} +GL2_NACK_NO_FAULT = 0 +GL2_NACK_PAGE_FAULT = 1 +GL2_NACK_PROTECTION_FAULT = 2 +GL2_NACK_DATA_ERROR = 3 +GL2_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP' +GL2_OP__enumvalues = { + 0: 'GL2_OP_READ', + 1: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'GL2_OP_ATOMIC_FMIN_RTN_32', + 3: 'GL2_OP_ATOMIC_FMAX_RTN_32', + 7: 'GL2_OP_ATOMIC_SWAP_RTN_32', + 8: 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'GL2_OP_PROBE_FILTER', + 13: 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 14: 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'GL2_OP_ATOMIC_ADD_RTN_32', + 16: 'GL2_OP_ATOMIC_SUB_RTN_32', + 17: 'GL2_OP_ATOMIC_SMIN_RTN_32', + 18: 'GL2_OP_ATOMIC_UMIN_RTN_32', + 19: 'GL2_OP_ATOMIC_SMAX_RTN_32', + 20: 'GL2_OP_ATOMIC_UMAX_RTN_32', + 21: 'GL2_OP_ATOMIC_AND_RTN_32', + 22: 'GL2_OP_ATOMIC_OR_RTN_32', + 23: 'GL2_OP_ATOMIC_XOR_RTN_32', + 24: 'GL2_OP_ATOMIC_INC_RTN_32', + 25: 'GL2_OP_ATOMIC_DEC_RTN_32', + 26: 'GL2_OP_ATOMIC_CLAMP_SUB_RTN_32', + 32: 'GL2_OP_WRITE', + 33: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'GL2_OP_ATOMIC_FMIN_RTN_64', + 35: 'GL2_OP_ATOMIC_FMAX_RTN_64', + 39: 'GL2_OP_ATOMIC_SWAP_RTN_64', + 40: 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 47: 'GL2_OP_ATOMIC_ADD_RTN_64', + 48: 'GL2_OP_ATOMIC_SUB_RTN_64', + 49: 'GL2_OP_ATOMIC_SMIN_RTN_64', + 50: 'GL2_OP_ATOMIC_UMIN_RTN_64', + 51: 'GL2_OP_ATOMIC_SMAX_RTN_64', + 52: 'GL2_OP_ATOMIC_UMAX_RTN_64', + 53: 'GL2_OP_ATOMIC_AND_RTN_64', + 54: 'GL2_OP_ATOMIC_OR_RTN_64', + 55: 'GL2_OP_ATOMIC_XOR_RTN_64', + 56: 'GL2_OP_ATOMIC_INC_RTN_64', + 57: 'GL2_OP_ATOMIC_DEC_RTN_64', + 64: 'GL2_OP_GL1_INV', + 65: 'GL2_OP_ATOMIC_FCMPSWAP_32', + 66: 'GL2_OP_ATOMIC_FMIN_32', + 67: 'GL2_OP_ATOMIC_FMAX_32', + 71: 'GL2_OP_ATOMIC_SWAP_32', + 72: 'GL2_OP_ATOMIC_CMPSWAP_32', + 73: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'GL2_OP_ATOMIC_UMIN_8', + 77: 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 79: 'GL2_OP_ATOMIC_ADD_32', + 80: 'GL2_OP_ATOMIC_SUB_32', + 81: 'GL2_OP_ATOMIC_SMIN_32', + 82: 'GL2_OP_ATOMIC_UMIN_32', + 83: 'GL2_OP_ATOMIC_SMAX_32', + 84: 'GL2_OP_ATOMIC_UMAX_32', + 85: 'GL2_OP_ATOMIC_AND_32', + 86: 'GL2_OP_ATOMIC_OR_32', + 87: 'GL2_OP_ATOMIC_XOR_32', + 88: 'GL2_OP_ATOMIC_INC_32', + 89: 'GL2_OP_ATOMIC_DEC_32', + 91: 'GL2_OP_NOP_RTN0', + 97: 'GL2_OP_ATOMIC_FCMPSWAP_64', + 98: 'GL2_OP_ATOMIC_FMIN_64', + 99: 'GL2_OP_ATOMIC_FMAX_64', + 103: 'GL2_OP_ATOMIC_SWAP_64', + 104: 'GL2_OP_ATOMIC_CMPSWAP_64', + 105: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 111: 'GL2_OP_ATOMIC_ADD_64', + 112: 'GL2_OP_ATOMIC_SUB_64', + 113: 'GL2_OP_ATOMIC_SMIN_64', + 114: 'GL2_OP_ATOMIC_UMIN_64', + 115: 'GL2_OP_ATOMIC_SMAX_64', + 116: 'GL2_OP_ATOMIC_UMAX_64', + 117: 'GL2_OP_ATOMIC_AND_64', + 118: 'GL2_OP_ATOMIC_OR_64', + 119: 'GL2_OP_ATOMIC_XOR_64', + 120: 'GL2_OP_ATOMIC_INC_64', + 121: 'GL2_OP_ATOMIC_DEC_64', + 122: 'GL2_OP_ATOMIC_UMAX_8', + 123: 'GL2_OP_NOP_ACK', +} +GL2_OP_READ = 0 +GL2_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +GL2_OP_ATOMIC_FMIN_RTN_32 = 2 +GL2_OP_ATOMIC_FMAX_RTN_32 = 3 +GL2_OP_ATOMIC_SWAP_RTN_32 = 7 +GL2_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +GL2_OP_PROBE_FILTER = 12 +GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32 = 13 +GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +GL2_OP_ATOMIC_ADD_RTN_32 = 15 +GL2_OP_ATOMIC_SUB_RTN_32 = 16 +GL2_OP_ATOMIC_SMIN_RTN_32 = 17 +GL2_OP_ATOMIC_UMIN_RTN_32 = 18 +GL2_OP_ATOMIC_SMAX_RTN_32 = 19 +GL2_OP_ATOMIC_UMAX_RTN_32 = 20 +GL2_OP_ATOMIC_AND_RTN_32 = 21 +GL2_OP_ATOMIC_OR_RTN_32 = 22 +GL2_OP_ATOMIC_XOR_RTN_32 = 23 +GL2_OP_ATOMIC_INC_RTN_32 = 24 +GL2_OP_ATOMIC_DEC_RTN_32 = 25 +GL2_OP_ATOMIC_CLAMP_SUB_RTN_32 = 26 +GL2_OP_WRITE = 32 +GL2_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +GL2_OP_ATOMIC_FMIN_RTN_64 = 34 +GL2_OP_ATOMIC_FMAX_RTN_64 = 35 +GL2_OP_ATOMIC_SWAP_RTN_64 = 39 +GL2_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +GL2_OP_ATOMIC_ADD_RTN_64 = 47 +GL2_OP_ATOMIC_SUB_RTN_64 = 48 +GL2_OP_ATOMIC_SMIN_RTN_64 = 49 +GL2_OP_ATOMIC_UMIN_RTN_64 = 50 +GL2_OP_ATOMIC_SMAX_RTN_64 = 51 +GL2_OP_ATOMIC_UMAX_RTN_64 = 52 +GL2_OP_ATOMIC_AND_RTN_64 = 53 +GL2_OP_ATOMIC_OR_RTN_64 = 54 +GL2_OP_ATOMIC_XOR_RTN_64 = 55 +GL2_OP_ATOMIC_INC_RTN_64 = 56 +GL2_OP_ATOMIC_DEC_RTN_64 = 57 +GL2_OP_GL1_INV = 64 +GL2_OP_ATOMIC_FCMPSWAP_32 = 65 +GL2_OP_ATOMIC_FMIN_32 = 66 +GL2_OP_ATOMIC_FMAX_32 = 67 +GL2_OP_ATOMIC_SWAP_32 = 71 +GL2_OP_ATOMIC_CMPSWAP_32 = 72 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +GL2_OP_ATOMIC_UMIN_8 = 76 +GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32 = 77 +GL2_OP_ATOMIC_ADD_32 = 79 +GL2_OP_ATOMIC_SUB_32 = 80 +GL2_OP_ATOMIC_SMIN_32 = 81 +GL2_OP_ATOMIC_UMIN_32 = 82 +GL2_OP_ATOMIC_SMAX_32 = 83 +GL2_OP_ATOMIC_UMAX_32 = 84 +GL2_OP_ATOMIC_AND_32 = 85 +GL2_OP_ATOMIC_OR_32 = 86 +GL2_OP_ATOMIC_XOR_32 = 87 +GL2_OP_ATOMIC_INC_32 = 88 +GL2_OP_ATOMIC_DEC_32 = 89 +GL2_OP_NOP_RTN0 = 91 +GL2_OP_ATOMIC_FCMPSWAP_64 = 97 +GL2_OP_ATOMIC_FMIN_64 = 98 +GL2_OP_ATOMIC_FMAX_64 = 99 +GL2_OP_ATOMIC_SWAP_64 = 103 +GL2_OP_ATOMIC_CMPSWAP_64 = 104 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +GL2_OP_ATOMIC_ADD_64 = 111 +GL2_OP_ATOMIC_SUB_64 = 112 +GL2_OP_ATOMIC_SMIN_64 = 113 +GL2_OP_ATOMIC_UMIN_64 = 114 +GL2_OP_ATOMIC_SMAX_64 = 115 +GL2_OP_ATOMIC_UMAX_64 = 116 +GL2_OP_ATOMIC_AND_64 = 117 +GL2_OP_ATOMIC_OR_64 = 118 +GL2_OP_ATOMIC_XOR_64 = 119 +GL2_OP_ATOMIC_INC_64 = 120 +GL2_OP_ATOMIC_DEC_64 = 121 +GL2_OP_ATOMIC_UMAX_8 = 122 +GL2_OP_NOP_ACK = 123 +GL2_OP = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP_MASKS' +GL2_OP_MASKS__enumvalues = { + 8: 'GL2_OP_MASK_FLUSH_DENROM', + 32: 'GL2_OP_MASK_64', + 64: 'GL2_OP_MASK_NO_RTN', +} +GL2_OP_MASK_FLUSH_DENROM = 8 +GL2_OP_MASK_64 = 32 +GL2_OP_MASK_NO_RTN = 64 +GL2_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_DOORBELL_MODE' +RLC_DOORBELL_MODE__enumvalues = { + 0: 'RLC_DOORBELL_MODE_DISABLE', + 1: 'RLC_DOORBELL_MODE_ENABLE', + 2: 'RLC_DOORBELL_MODE_ENABLE_PF', + 3: 'RLC_DOORBELL_MODE_ENABLE_PF_VF', +} +RLC_DOORBELL_MODE_DISABLE = 0 +RLC_DOORBELL_MODE_ENABLE = 1 +RLC_DOORBELL_MODE_ENABLE_PF = 2 +RLC_DOORBELL_MODE_ENABLE_PF_VF = 3 +RLC_DOORBELL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_PERFCOUNTER_SEL' +RLC_PERFCOUNTER_SEL__enumvalues = { + 0: 'RLC_PERF_SEL_POWER_FEATURE_0', + 1: 'RLC_PERF_SEL_POWER_FEATURE_1', + 2: 'RLC_PERF_SEL_CP_INTERRUPT', + 3: 'RLC_PERF_SEL_GRBM_INTERRUPT', + 4: 'RLC_PERF_SEL_SPM_INTERRUPT', + 5: 'RLC_PERF_SEL_IH_INTERRUPT', + 6: 'RLC_PERF_SEL_SERDES_COMMAND_WRITE', +} +RLC_PERF_SEL_POWER_FEATURE_0 = 0 +RLC_PERF_SEL_POWER_FEATURE_1 = 1 +RLC_PERF_SEL_CP_INTERRUPT = 2 +RLC_PERF_SEL_GRBM_INTERRUPT = 3 +RLC_PERF_SEL_SPM_INTERRUPT = 4 +RLC_PERF_SEL_IH_INTERRUPT = 5 +RLC_PERF_SEL_SERDES_COMMAND_WRITE = 6 +RLC_PERFCOUNTER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_PERFMON_STATE' +RLC_PERFMON_STATE__enumvalues = { + 0: 'RLC_PERFMON_STATE_RESET', + 1: 'RLC_PERFMON_STATE_ENABLE', + 2: 'RLC_PERFMON_STATE_DISABLE', + 3: 'RLC_PERFMON_STATE_RESERVED_3', + 4: 'RLC_PERFMON_STATE_RESERVED_4', + 5: 'RLC_PERFMON_STATE_RESERVED_5', + 6: 'RLC_PERFMON_STATE_RESERVED_6', + 7: 'RLC_PERFMON_STATE_ROLLOVER', +} +RLC_PERFMON_STATE_RESET = 0 +RLC_PERFMON_STATE_ENABLE = 1 +RLC_PERFMON_STATE_DISABLE = 2 +RLC_PERFMON_STATE_RESERVED_3 = 3 +RLC_PERFMON_STATE_RESERVED_4 = 4 +RLC_PERFMON_STATE_RESERVED_5 = 5 +RLC_PERFMON_STATE_RESERVED_6 = 6 +RLC_PERFMON_STATE_ROLLOVER = 7 +RLC_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'RSPM_CMD' +RSPM_CMD__enumvalues = { + 0: 'RSPM_CMD_INVALID', + 1: 'RSPM_CMD_IDLE', + 2: 'RSPM_CMD_CALIBRATE', + 3: 'RSPM_CMD_SPM_RESET', + 4: 'RSPM_CMD_SPM_START', + 5: 'RSPM_CMD_SPM_STOP', + 6: 'RSPM_CMD_PERF_RESET', + 7: 'RSPM_CMD_PERF_SAMPLE', + 8: 'RSPM_CMD_PROF_START', + 9: 'RSPM_CMD_PROF_STOP', + 10: 'RSPM_CMD_FORCE_SAMPLE', +} +RSPM_CMD_INVALID = 0 +RSPM_CMD_IDLE = 1 +RSPM_CMD_CALIBRATE = 2 +RSPM_CMD_SPM_RESET = 3 +RSPM_CMD_SPM_START = 4 +RSPM_CMD_SPM_STOP = 5 +RSPM_CMD_PERF_RESET = 6 +RSPM_CMD_PERF_SAMPLE = 7 +RSPM_CMD_PROF_START = 8 +RSPM_CMD_PROF_STOP = 9 +RSPM_CMD_FORCE_SAMPLE = 10 +RSPM_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_BASE_MODE' +CLKGATE_BASE_MODE__enumvalues = { + 0: 'MULT_8', + 1: 'MULT_16', +} +MULT_8 = 0 +MULT_16 = 1 +CLKGATE_BASE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_SM_MODE' +CLKGATE_SM_MODE__enumvalues = { + 0: 'ON_SEQ', + 1: 'OFF_SEQ', + 2: 'PROG_SEQ', + 3: 'READ_SEQ', + 4: 'SM_MODE_RESERVED', +} +ON_SEQ = 0 +OFF_SEQ = 1 +PROG_SEQ = 2 +READ_SEQ = 3 +SM_MODE_RESERVED = 4 +CLKGATE_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_FOG_MODE' +SPI_FOG_MODE__enumvalues = { + 0: 'SPI_FOG_NONE', + 1: 'SPI_FOG_EXP', + 2: 'SPI_FOG_EXP2', + 3: 'SPI_FOG_LINEAR', +} +SPI_FOG_NONE = 0 +SPI_FOG_EXP = 1 +SPI_FOG_EXP2 = 2 +SPI_FOG_LINEAR = 3 +SPI_FOG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_LB_WAVES_SELECT' +SPI_LB_WAVES_SELECT__enumvalues = { + 0: 'HS_GS', + 1: 'PS', + 2: 'CS_NA', + 3: 'SPI_LB_WAVES_RSVD', +} +HS_GS = 0 +PS = 1 +CS_NA = 2 +SPI_LB_WAVES_RSVD = 3 +SPI_LB_WAVES_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PERFCNT_SEL' +SPI_PERFCNT_SEL__enumvalues = { + 1: 'SPI_PERF_GS_WINDOW_VALID', + 2: 'SPI_PERF_GS_BUSY', + 3: 'SPI_PERF_GS_CRAWLER_STALL', + 4: 'SPI_PERF_GS_EVENT_WAVE', + 5: 'SPI_PERF_GS_WAVE', + 6: 'SPI_PERF_GS_PERS_UPD_FULL0', + 7: 'SPI_PERF_GS_PERS_UPD_FULL1', + 8: 'SPI_PERF_GS_FIRST_SUBGRP', + 9: 'SPI_PERF_GS_HS_DEALLOC', + 10: 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 11: 'SPI_PERF_GS_POS0_STALL', + 12: 'SPI_PERF_GS_POS1_STALL', + 13: 'SPI_PERF_GS_INDX0_STALL', + 14: 'SPI_PERF_GS_INDX1_STALL', + 15: 'SPI_PERF_GS_PWS_STALL', + 21: 'SPI_PERF_HS_WINDOW_VALID', + 22: 'SPI_PERF_HS_BUSY', + 23: 'SPI_PERF_HS_CRAWLER_STALL', + 24: 'SPI_PERF_HS_FIRST_WAVE', + 25: 'SPI_PERF_HS_OFFCHIP_LDS_STALL', + 26: 'SPI_PERF_HS_EVENT_WAVE', + 27: 'SPI_PERF_HS_WAVE', + 28: 'SPI_PERF_HS_PERS_UPD_FULL0', + 29: 'SPI_PERF_HS_PERS_UPD_FULL1', + 30: 'SPI_PERF_HS_PWS_STALL', + 37: 'SPI_PERF_CSGN_WINDOW_VALID', + 38: 'SPI_PERF_CSGN_BUSY', + 39: 'SPI_PERF_CSGN_NUM_THREADGROUPS', + 40: 'SPI_PERF_CSGN_CRAWLER_STALL', + 41: 'SPI_PERF_CSGN_EVENT_WAVE', + 42: 'SPI_PERF_CSGN_WAVE', + 43: 'SPI_PERF_CSGN_PWS_STALL', + 44: 'SPI_PERF_CSN_WINDOW_VALID', + 45: 'SPI_PERF_CSN_BUSY', + 46: 'SPI_PERF_CSN_NUM_THREADGROUPS', + 47: 'SPI_PERF_CSN_CRAWLER_STALL', + 48: 'SPI_PERF_CSN_EVENT_WAVE', + 49: 'SPI_PERF_CSN_WAVE', + 53: 'SPI_PERF_PS0_WINDOW_VALID', + 54: 'SPI_PERF_PS1_WINDOW_VALID', + 55: 'SPI_PERF_PS2_WINDOW_VALID', + 56: 'SPI_PERF_PS3_WINDOW_VALID', + 57: 'SPI_PERF_PS0_BUSY', + 58: 'SPI_PERF_PS1_BUSY', + 59: 'SPI_PERF_PS2_BUSY', + 60: 'SPI_PERF_PS3_BUSY', + 61: 'SPI_PERF_PS0_ACTIVE', + 62: 'SPI_PERF_PS1_ACTIVE', + 63: 'SPI_PERF_PS2_ACTIVE', + 64: 'SPI_PERF_PS3_ACTIVE', + 65: 'SPI_PERF_PS0_DEALLOC', + 66: 'SPI_PERF_PS1_DEALLOC', + 67: 'SPI_PERF_PS2_DEALLOC', + 68: 'SPI_PERF_PS3_DEALLOC', + 69: 'SPI_PERF_PS0_EVENT_WAVE', + 70: 'SPI_PERF_PS1_EVENT_WAVE', + 71: 'SPI_PERF_PS2_EVENT_WAVE', + 72: 'SPI_PERF_PS3_EVENT_WAVE', + 73: 'SPI_PERF_PS0_WAVE', + 74: 'SPI_PERF_PS1_WAVE', + 75: 'SPI_PERF_PS2_WAVE', + 76: 'SPI_PERF_PS3_WAVE', + 77: 'SPI_PERF_PS0_OPT_WAVE', + 78: 'SPI_PERF_PS1_OPT_WAVE', + 79: 'SPI_PERF_PS2_OPT_WAVE', + 80: 'SPI_PERF_PS3_OPT_WAVE', + 81: 'SPI_PERF_PS0_PRIM_BIN0', + 82: 'SPI_PERF_PS1_PRIM_BIN0', + 83: 'SPI_PERF_PS2_PRIM_BIN0', + 84: 'SPI_PERF_PS3_PRIM_BIN0', + 85: 'SPI_PERF_PS0_PRIM_BIN1', + 86: 'SPI_PERF_PS1_PRIM_BIN1', + 87: 'SPI_PERF_PS2_PRIM_BIN1', + 88: 'SPI_PERF_PS3_PRIM_BIN1', + 89: 'SPI_PERF_PS0_CRAWLER_STALL', + 90: 'SPI_PERF_PS1_CRAWLER_STALL', + 91: 'SPI_PERF_PS2_CRAWLER_STALL', + 92: 'SPI_PERF_PS3_CRAWLER_STALL', + 93: 'SPI_PERF_PS_PERS_UPD_FULL0', + 94: 'SPI_PERF_PS_PERS_UPD_FULL1', + 95: 'SPI_PERF_PS0_2_WAVE_GROUPS', + 96: 'SPI_PERF_PS1_2_WAVE_GROUPS', + 97: 'SPI_PERF_PS2_2_WAVE_GROUPS', + 98: 'SPI_PERF_PS3_2_WAVE_GROUPS', + 99: 'SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY', + 100: 'SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY', + 101: 'SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY', + 102: 'SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY', + 103: 'SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS', + 104: 'SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS', + 105: 'SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS', + 106: 'SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS', + 107: 'SPI_PERF_PS_PWS_STALL', + 141: 'SPI_PERF_RA_PIPE_REQ_BIN2', + 142: 'SPI_PERF_RA_TASK_REQ_BIN3', + 143: 'SPI_PERF_RA_WR_CTL_FULL', + 144: 'SPI_PERF_RA_REQ_NO_ALLOC', + 145: 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 146: 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 147: 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 148: 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 149: 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', + 150: 'SPI_PERF_RA_RES_STALL_PS', + 151: 'SPI_PERF_RA_RES_STALL_GS', + 152: 'SPI_PERF_RA_RES_STALL_HS', + 153: 'SPI_PERF_RA_RES_STALL_CSG', + 154: 'SPI_PERF_RA_RES_STALL_CSN', + 155: 'SPI_PERF_RA_TMP_STALL_PS', + 156: 'SPI_PERF_RA_TMP_STALL_GS', + 157: 'SPI_PERF_RA_TMP_STALL_HS', + 158: 'SPI_PERF_RA_TMP_STALL_CSG', + 159: 'SPI_PERF_RA_TMP_STALL_CSN', + 160: 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 161: 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 162: 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', + 163: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 164: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', + 165: 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 166: 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 167: 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', + 168: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 169: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', + 170: 'SPI_PERF_RA_LDS_CU_FULL_PS', + 171: 'SPI_PERF_RA_LDS_CU_FULL_HS', + 172: 'SPI_PERF_RA_LDS_CU_FULL_GS', + 173: 'SPI_PERF_RA_LDS_CU_FULL_CSG', + 174: 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 175: 'SPI_PERF_RA_BAR_CU_FULL_HS', + 176: 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 177: 'SPI_PERF_RA_BAR_CU_FULL_CSN', + 178: 'SPI_PERF_RA_BULKY_CU_FULL_CSG', + 179: 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 180: 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', + 181: 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 182: 'SPI_PERF_RA_WVLIM_STALL_PS', + 183: 'SPI_PERF_RA_WVLIM_STALL_GS', + 184: 'SPI_PERF_RA_WVLIM_STALL_HS', + 185: 'SPI_PERF_RA_WVLIM_STALL_CSG', + 186: 'SPI_PERF_RA_WVLIM_STALL_CSN', + 187: 'SPI_PERF_RA_GS_LOCK', + 188: 'SPI_PERF_RA_HS_LOCK', + 189: 'SPI_PERF_RA_CSG_LOCK', + 190: 'SPI_PERF_RA_CSN_LOCK', + 191: 'SPI_PERF_RA_RSV_UPD', + 192: 'SPI_PERF_RA_PRE_ALLOC_STALL', + 193: 'SPI_PERF_RA_GFX_UNDER_TUNNEL', + 194: 'SPI_PERF_RA_CSC_UNDER_TUNNEL', + 195: 'SPI_PERF_RA_WVALLOC_STALL', + 196: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_PS', + 197: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_PS', + 198: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_PS', + 199: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_PS', + 200: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_GS', + 201: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_GS', + 202: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_GS', + 203: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_GS', + 204: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_HS', + 205: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_HS', + 206: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_HS', + 207: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_HS', + 208: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG', + 209: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG', + 210: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG', + 211: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG', + 212: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN', + 213: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN', + 214: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN', + 215: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN', + 216: 'SPI_PERF_EXP_ARB_COL_CNT', + 217: 'SPI_PERF_EXP_ARB_POS_CNT', + 218: 'SPI_PERF_EXP_ARB_GDS_CNT', + 219: 'SPI_PERF_EXP_ARB_IDX_CNT', + 220: 'SPI_PERF_EXP_WITH_CONFLICT', + 221: 'SPI_PERF_EXP_WITH_CONFLICT_CLEAR', + 222: 'SPI_PERF_GS_EXP_DONE', + 223: 'SPI_PERF_PS_EXP_DONE', + 224: 'SPI_PERF_PS_EXP_ARB_CONFLICT', + 225: 'SPI_PERF_PS_EXP_ALLOC', + 226: 'SPI_PERF_PS0_WAVEID_STARVED', + 227: 'SPI_PERF_PS1_WAVEID_STARVED', + 228: 'SPI_PERF_PS2_WAVEID_STARVED', + 229: 'SPI_PERF_PS3_WAVEID_STARVED', + 230: 'SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT', + 231: 'SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT', + 232: 'SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT', + 233: 'SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT', + 234: 'SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS', + 235: 'SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS', + 236: 'SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS', + 237: 'SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS', + 238: 'SPI_PERF_NUM_POS_SA0SQ0_EXPORTS', + 239: 'SPI_PERF_NUM_POS_SA0SQ1_EXPORTS', + 240: 'SPI_PERF_NUM_POS_SA1SQ0_EXPORTS', + 241: 'SPI_PERF_NUM_POS_SA1SQ1_EXPORTS', + 242: 'SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS', + 243: 'SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS', + 244: 'SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS', + 245: 'SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS', + 246: 'SPI_PERF_NUM_EXPGRANT_EXPORTS', + 253: 'SPI_PERF_PIX_ALLOC_PEND_CNT', + 254: 'SPI_PERF_EXPORT_SCB0_STALL', + 255: 'SPI_PERF_EXPORT_SCB1_STALL', + 256: 'SPI_PERF_EXPORT_SCB2_STALL', + 257: 'SPI_PERF_EXPORT_SCB3_STALL', + 258: 'SPI_PERF_EXPORT_DB0_STALL', + 259: 'SPI_PERF_EXPORT_DB1_STALL', + 260: 'SPI_PERF_EXPORT_DB2_STALL', + 261: 'SPI_PERF_EXPORT_DB3_STALL', + 262: 'SPI_PERF_EXPORT_DB4_STALL', + 263: 'SPI_PERF_EXPORT_DB5_STALL', + 264: 'SPI_PERF_EXPORT_DB6_STALL', + 265: 'SPI_PERF_EXPORT_DB7_STALL', + 266: 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 267: 'SPI_PERF_GS_NGG_STALL_MSG_VAL', + 268: 'SPI_PERF_SWC_PS_WR', + 269: 'SPI_PERF_SWC_GS_WR', + 270: 'SPI_PERF_SWC_HS_WR', + 271: 'SPI_PERF_SWC_CSGN_WR', + 272: 'SPI_PERF_SWC_CSN_WR', + 273: 'SPI_PERF_VWC_PS_WR', + 274: 'SPI_PERF_VWC_ES_WR', + 275: 'SPI_PERF_VWC_GS_WR', + 276: 'SPI_PERF_VWC_LS_WR', + 277: 'SPI_PERF_VWC_HS_WR', + 278: 'SPI_PERF_VWC_CSGN_WR', + 279: 'SPI_PERF_VWC_CSN_WR', + 280: 'SPI_PERF_EXP_THROT_UPSTEP', + 281: 'SPI_PERF_EXP_THROT_DOWNSTEP', + 282: 'SPI_PERF_EXP_THROT_CAUSALITY_DETECTED', + 283: 'SPI_PERF_BUSY', +} +SPI_PERF_GS_WINDOW_VALID = 1 +SPI_PERF_GS_BUSY = 2 +SPI_PERF_GS_CRAWLER_STALL = 3 +SPI_PERF_GS_EVENT_WAVE = 4 +SPI_PERF_GS_WAVE = 5 +SPI_PERF_GS_PERS_UPD_FULL0 = 6 +SPI_PERF_GS_PERS_UPD_FULL1 = 7 +SPI_PERF_GS_FIRST_SUBGRP = 8 +SPI_PERF_GS_HS_DEALLOC = 9 +SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT = 10 +SPI_PERF_GS_POS0_STALL = 11 +SPI_PERF_GS_POS1_STALL = 12 +SPI_PERF_GS_INDX0_STALL = 13 +SPI_PERF_GS_INDX1_STALL = 14 +SPI_PERF_GS_PWS_STALL = 15 +SPI_PERF_HS_WINDOW_VALID = 21 +SPI_PERF_HS_BUSY = 22 +SPI_PERF_HS_CRAWLER_STALL = 23 +SPI_PERF_HS_FIRST_WAVE = 24 +SPI_PERF_HS_OFFCHIP_LDS_STALL = 25 +SPI_PERF_HS_EVENT_WAVE = 26 +SPI_PERF_HS_WAVE = 27 +SPI_PERF_HS_PERS_UPD_FULL0 = 28 +SPI_PERF_HS_PERS_UPD_FULL1 = 29 +SPI_PERF_HS_PWS_STALL = 30 +SPI_PERF_CSGN_WINDOW_VALID = 37 +SPI_PERF_CSGN_BUSY = 38 +SPI_PERF_CSGN_NUM_THREADGROUPS = 39 +SPI_PERF_CSGN_CRAWLER_STALL = 40 +SPI_PERF_CSGN_EVENT_WAVE = 41 +SPI_PERF_CSGN_WAVE = 42 +SPI_PERF_CSGN_PWS_STALL = 43 +SPI_PERF_CSN_WINDOW_VALID = 44 +SPI_PERF_CSN_BUSY = 45 +SPI_PERF_CSN_NUM_THREADGROUPS = 46 +SPI_PERF_CSN_CRAWLER_STALL = 47 +SPI_PERF_CSN_EVENT_WAVE = 48 +SPI_PERF_CSN_WAVE = 49 +SPI_PERF_PS0_WINDOW_VALID = 53 +SPI_PERF_PS1_WINDOW_VALID = 54 +SPI_PERF_PS2_WINDOW_VALID = 55 +SPI_PERF_PS3_WINDOW_VALID = 56 +SPI_PERF_PS0_BUSY = 57 +SPI_PERF_PS1_BUSY = 58 +SPI_PERF_PS2_BUSY = 59 +SPI_PERF_PS3_BUSY = 60 +SPI_PERF_PS0_ACTIVE = 61 +SPI_PERF_PS1_ACTIVE = 62 +SPI_PERF_PS2_ACTIVE = 63 +SPI_PERF_PS3_ACTIVE = 64 +SPI_PERF_PS0_DEALLOC = 65 +SPI_PERF_PS1_DEALLOC = 66 +SPI_PERF_PS2_DEALLOC = 67 +SPI_PERF_PS3_DEALLOC = 68 +SPI_PERF_PS0_EVENT_WAVE = 69 +SPI_PERF_PS1_EVENT_WAVE = 70 +SPI_PERF_PS2_EVENT_WAVE = 71 +SPI_PERF_PS3_EVENT_WAVE = 72 +SPI_PERF_PS0_WAVE = 73 +SPI_PERF_PS1_WAVE = 74 +SPI_PERF_PS2_WAVE = 75 +SPI_PERF_PS3_WAVE = 76 +SPI_PERF_PS0_OPT_WAVE = 77 +SPI_PERF_PS1_OPT_WAVE = 78 +SPI_PERF_PS2_OPT_WAVE = 79 +SPI_PERF_PS3_OPT_WAVE = 80 +SPI_PERF_PS0_PRIM_BIN0 = 81 +SPI_PERF_PS1_PRIM_BIN0 = 82 +SPI_PERF_PS2_PRIM_BIN0 = 83 +SPI_PERF_PS3_PRIM_BIN0 = 84 +SPI_PERF_PS0_PRIM_BIN1 = 85 +SPI_PERF_PS1_PRIM_BIN1 = 86 +SPI_PERF_PS2_PRIM_BIN1 = 87 +SPI_PERF_PS3_PRIM_BIN1 = 88 +SPI_PERF_PS0_CRAWLER_STALL = 89 +SPI_PERF_PS1_CRAWLER_STALL = 90 +SPI_PERF_PS2_CRAWLER_STALL = 91 +SPI_PERF_PS3_CRAWLER_STALL = 92 +SPI_PERF_PS_PERS_UPD_FULL0 = 93 +SPI_PERF_PS_PERS_UPD_FULL1 = 94 +SPI_PERF_PS0_2_WAVE_GROUPS = 95 +SPI_PERF_PS1_2_WAVE_GROUPS = 96 +SPI_PERF_PS2_2_WAVE_GROUPS = 97 +SPI_PERF_PS3_2_WAVE_GROUPS = 98 +SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY = 99 +SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY = 100 +SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY = 101 +SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY = 102 +SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS = 103 +SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS = 104 +SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS = 105 +SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS = 106 +SPI_PERF_PS_PWS_STALL = 107 +SPI_PERF_RA_PIPE_REQ_BIN2 = 141 +SPI_PERF_RA_TASK_REQ_BIN3 = 142 +SPI_PERF_RA_WR_CTL_FULL = 143 +SPI_PERF_RA_REQ_NO_ALLOC = 144 +SPI_PERF_RA_REQ_NO_ALLOC_PS = 145 +SPI_PERF_RA_REQ_NO_ALLOC_GS = 146 +SPI_PERF_RA_REQ_NO_ALLOC_HS = 147 +SPI_PERF_RA_REQ_NO_ALLOC_CSG = 148 +SPI_PERF_RA_REQ_NO_ALLOC_CSN = 149 +SPI_PERF_RA_RES_STALL_PS = 150 +SPI_PERF_RA_RES_STALL_GS = 151 +SPI_PERF_RA_RES_STALL_HS = 152 +SPI_PERF_RA_RES_STALL_CSG = 153 +SPI_PERF_RA_RES_STALL_CSN = 154 +SPI_PERF_RA_TMP_STALL_PS = 155 +SPI_PERF_RA_TMP_STALL_GS = 156 +SPI_PERF_RA_TMP_STALL_HS = 157 +SPI_PERF_RA_TMP_STALL_CSG = 158 +SPI_PERF_RA_TMP_STALL_CSN = 159 +SPI_PERF_RA_WAVE_SIMD_FULL_PS = 160 +SPI_PERF_RA_WAVE_SIMD_FULL_GS = 161 +SPI_PERF_RA_WAVE_SIMD_FULL_HS = 162 +SPI_PERF_RA_WAVE_SIMD_FULL_CSG = 163 +SPI_PERF_RA_WAVE_SIMD_FULL_CSN = 164 +SPI_PERF_RA_VGPR_SIMD_FULL_PS = 165 +SPI_PERF_RA_VGPR_SIMD_FULL_GS = 166 +SPI_PERF_RA_VGPR_SIMD_FULL_HS = 167 +SPI_PERF_RA_VGPR_SIMD_FULL_CSG = 168 +SPI_PERF_RA_VGPR_SIMD_FULL_CSN = 169 +SPI_PERF_RA_LDS_CU_FULL_PS = 170 +SPI_PERF_RA_LDS_CU_FULL_HS = 171 +SPI_PERF_RA_LDS_CU_FULL_GS = 172 +SPI_PERF_RA_LDS_CU_FULL_CSG = 173 +SPI_PERF_RA_LDS_CU_FULL_CSN = 174 +SPI_PERF_RA_BAR_CU_FULL_HS = 175 +SPI_PERF_RA_BAR_CU_FULL_CSG = 176 +SPI_PERF_RA_BAR_CU_FULL_CSN = 177 +SPI_PERF_RA_BULKY_CU_FULL_CSG = 178 +SPI_PERF_RA_BULKY_CU_FULL_CSN = 179 +SPI_PERF_RA_TGLIM_CU_FULL_CSG = 180 +SPI_PERF_RA_TGLIM_CU_FULL_CSN = 181 +SPI_PERF_RA_WVLIM_STALL_PS = 182 +SPI_PERF_RA_WVLIM_STALL_GS = 183 +SPI_PERF_RA_WVLIM_STALL_HS = 184 +SPI_PERF_RA_WVLIM_STALL_CSG = 185 +SPI_PERF_RA_WVLIM_STALL_CSN = 186 +SPI_PERF_RA_GS_LOCK = 187 +SPI_PERF_RA_HS_LOCK = 188 +SPI_PERF_RA_CSG_LOCK = 189 +SPI_PERF_RA_CSN_LOCK = 190 +SPI_PERF_RA_RSV_UPD = 191 +SPI_PERF_RA_PRE_ALLOC_STALL = 192 +SPI_PERF_RA_GFX_UNDER_TUNNEL = 193 +SPI_PERF_RA_CSC_UNDER_TUNNEL = 194 +SPI_PERF_RA_WVALLOC_STALL = 195 +SPI_PERF_RA_ACCUM0_SIMD_FULL_PS = 196 +SPI_PERF_RA_ACCUM1_SIMD_FULL_PS = 197 +SPI_PERF_RA_ACCUM2_SIMD_FULL_PS = 198 +SPI_PERF_RA_ACCUM3_SIMD_FULL_PS = 199 +SPI_PERF_RA_ACCUM0_SIMD_FULL_GS = 200 +SPI_PERF_RA_ACCUM1_SIMD_FULL_GS = 201 +SPI_PERF_RA_ACCUM2_SIMD_FULL_GS = 202 +SPI_PERF_RA_ACCUM3_SIMD_FULL_GS = 203 +SPI_PERF_RA_ACCUM0_SIMD_FULL_HS = 204 +SPI_PERF_RA_ACCUM1_SIMD_FULL_HS = 205 +SPI_PERF_RA_ACCUM2_SIMD_FULL_HS = 206 +SPI_PERF_RA_ACCUM3_SIMD_FULL_HS = 207 +SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG = 208 +SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG = 209 +SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG = 210 +SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG = 211 +SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN = 212 +SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN = 213 +SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN = 214 +SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN = 215 +SPI_PERF_EXP_ARB_COL_CNT = 216 +SPI_PERF_EXP_ARB_POS_CNT = 217 +SPI_PERF_EXP_ARB_GDS_CNT = 218 +SPI_PERF_EXP_ARB_IDX_CNT = 219 +SPI_PERF_EXP_WITH_CONFLICT = 220 +SPI_PERF_EXP_WITH_CONFLICT_CLEAR = 221 +SPI_PERF_GS_EXP_DONE = 222 +SPI_PERF_PS_EXP_DONE = 223 +SPI_PERF_PS_EXP_ARB_CONFLICT = 224 +SPI_PERF_PS_EXP_ALLOC = 225 +SPI_PERF_PS0_WAVEID_STARVED = 226 +SPI_PERF_PS1_WAVEID_STARVED = 227 +SPI_PERF_PS2_WAVEID_STARVED = 228 +SPI_PERF_PS3_WAVEID_STARVED = 229 +SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT = 230 +SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT = 231 +SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT = 232 +SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT = 233 +SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS = 234 +SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS = 235 +SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS = 236 +SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS = 237 +SPI_PERF_NUM_POS_SA0SQ0_EXPORTS = 238 +SPI_PERF_NUM_POS_SA0SQ1_EXPORTS = 239 +SPI_PERF_NUM_POS_SA1SQ0_EXPORTS = 240 +SPI_PERF_NUM_POS_SA1SQ1_EXPORTS = 241 +SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS = 242 +SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS = 243 +SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS = 244 +SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS = 245 +SPI_PERF_NUM_EXPGRANT_EXPORTS = 246 +SPI_PERF_PIX_ALLOC_PEND_CNT = 253 +SPI_PERF_EXPORT_SCB0_STALL = 254 +SPI_PERF_EXPORT_SCB1_STALL = 255 +SPI_PERF_EXPORT_SCB2_STALL = 256 +SPI_PERF_EXPORT_SCB3_STALL = 257 +SPI_PERF_EXPORT_DB0_STALL = 258 +SPI_PERF_EXPORT_DB1_STALL = 259 +SPI_PERF_EXPORT_DB2_STALL = 260 +SPI_PERF_EXPORT_DB3_STALL = 261 +SPI_PERF_EXPORT_DB4_STALL = 262 +SPI_PERF_EXPORT_DB5_STALL = 263 +SPI_PERF_EXPORT_DB6_STALL = 264 +SPI_PERF_EXPORT_DB7_STALL = 265 +SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC = 266 +SPI_PERF_GS_NGG_STALL_MSG_VAL = 267 +SPI_PERF_SWC_PS_WR = 268 +SPI_PERF_SWC_GS_WR = 269 +SPI_PERF_SWC_HS_WR = 270 +SPI_PERF_SWC_CSGN_WR = 271 +SPI_PERF_SWC_CSN_WR = 272 +SPI_PERF_VWC_PS_WR = 273 +SPI_PERF_VWC_ES_WR = 274 +SPI_PERF_VWC_GS_WR = 275 +SPI_PERF_VWC_LS_WR = 276 +SPI_PERF_VWC_HS_WR = 277 +SPI_PERF_VWC_CSGN_WR = 278 +SPI_PERF_VWC_CSN_WR = 279 +SPI_PERF_EXP_THROT_UPSTEP = 280 +SPI_PERF_EXP_THROT_DOWNSTEP = 281 +SPI_PERF_EXP_THROT_CAUSALITY_DETECTED = 282 +SPI_PERF_BUSY = 283 +SPI_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PNT_SPRITE_OVERRIDE' +SPI_PNT_SPRITE_OVERRIDE__enumvalues = { + 0: 'SPI_PNT_SPRITE_SEL_0', + 1: 'SPI_PNT_SPRITE_SEL_1', + 2: 'SPI_PNT_SPRITE_SEL_S', + 3: 'SPI_PNT_SPRITE_SEL_T', + 4: 'SPI_PNT_SPRITE_SEL_NONE', +} +SPI_PNT_SPRITE_SEL_0 = 0 +SPI_PNT_SPRITE_SEL_1 = 1 +SPI_PNT_SPRITE_SEL_S = 2 +SPI_PNT_SPRITE_SEL_T = 3 +SPI_PNT_SPRITE_SEL_NONE = 4 +SPI_PNT_SPRITE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PS_LDS_GROUP_SIZE' +SPI_PS_LDS_GROUP_SIZE__enumvalues = { + 0: 'SPI_PS_LDS_GROUP_1', + 1: 'SPI_PS_LDS_GROUP_2', + 2: 'SPI_PS_LDS_GROUP_4', +} +SPI_PS_LDS_GROUP_1 = 0 +SPI_PS_LDS_GROUP_2 = 1 +SPI_PS_LDS_GROUP_4 = 2 +SPI_PS_LDS_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SAMPLE_CNTL' +SPI_SAMPLE_CNTL__enumvalues = { + 0: 'CENTROIDS_ONLY', + 1: 'CENTERS_ONLY', + 2: 'CENTROIDS_AND_CENTERS', + 3: 'UNDEF', +} +CENTROIDS_ONLY = 0 +CENTERS_ONLY = 1 +CENTROIDS_AND_CENTERS = 2 +UNDEF = 3 +SPI_SAMPLE_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_EX_FORMAT' +SPI_SHADER_EX_FORMAT__enumvalues = { + 0: 'SPI_SHADER_ZERO', + 1: 'SPI_SHADER_32_R', + 2: 'SPI_SHADER_32_GR', + 3: 'SPI_SHADER_32_AR', + 4: 'SPI_SHADER_FP16_ABGR', + 5: 'SPI_SHADER_UNORM16_ABGR', + 6: 'SPI_SHADER_SNORM16_ABGR', + 7: 'SPI_SHADER_UINT16_ABGR', + 8: 'SPI_SHADER_SINT16_ABGR', + 9: 'SPI_SHADER_32_ABGR', +} +SPI_SHADER_ZERO = 0 +SPI_SHADER_32_R = 1 +SPI_SHADER_32_GR = 2 +SPI_SHADER_32_AR = 3 +SPI_SHADER_FP16_ABGR = 4 +SPI_SHADER_UNORM16_ABGR = 5 +SPI_SHADER_SNORM16_ABGR = 6 +SPI_SHADER_UINT16_ABGR = 7 +SPI_SHADER_SINT16_ABGR = 8 +SPI_SHADER_32_ABGR = 9 +SPI_SHADER_EX_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_FORMAT' +SPI_SHADER_FORMAT__enumvalues = { + 0: 'SPI_SHADER_NONE', + 1: 'SPI_SHADER_1COMP', + 2: 'SPI_SHADER_2COMP', + 3: 'SPI_SHADER_4COMPRESS', + 4: 'SPI_SHADER_4COMP', +} +SPI_SHADER_NONE = 0 +SPI_SHADER_1COMP = 1 +SPI_SHADER_2COMP = 2 +SPI_SHADER_4COMPRESS = 3 +SPI_SHADER_4COMP = 4 +SPI_SHADER_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ADDRESS_MODE' +SH_MEM_ADDRESS_MODE__enumvalues = { + 0: 'SH_MEM_ADDRESS_MODE_64', + 1: 'SH_MEM_ADDRESS_MODE_32', +} +SH_MEM_ADDRESS_MODE_64 = 0 +SH_MEM_ADDRESS_MODE_32 = 1 +SH_MEM_ADDRESS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ALIGNMENT_MODE' +SH_MEM_ALIGNMENT_MODE__enumvalues = { + 0: 'SH_MEM_ALIGNMENT_MODE_DWORD', + 1: 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 2: 'SH_MEM_ALIGNMENT_MODE_STRICT', + 3: 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', +} +SH_MEM_ALIGNMENT_MODE_DWORD = 0 +SH_MEM_ALIGNMENT_MODE_DWORD_STRICT = 1 +SH_MEM_ALIGNMENT_MODE_STRICT = 2 +SH_MEM_ALIGNMENT_MODE_UNALIGNED = 3 +SH_MEM_ALIGNMENT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQG_PERF_SEL' +SQG_PERF_SEL__enumvalues = { + 0: 'SQG_PERF_SEL_NONE', + 1: 'SQG_PERF_SEL_MSG_BUS_BUSY', + 2: 'SQG_PERF_SEL_EXP_REQ0_BUS_BUSY', + 3: 'SQG_PERF_SEL_EXP_REQ1_BUS_BUSY', + 4: 'SQG_PERF_SEL_EXP_BUS0_BUSY', + 5: 'SQG_PERF_SEL_EXP_BUS1_BUSY', + 6: 'SQG_PERF_SEL_TTRACE_REQS', + 7: 'SQG_PERF_SEL_TTRACE_INFLIGHT_REQS', + 8: 'SQG_PERF_SEL_TTRACE_STALL', + 9: 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', + 10: 'SQG_PERF_SEL_WAVES_INITIAL_PREFETCH', + 11: 'SQG_PERF_SEL_EVENTS', + 12: 'SQG_PERF_SEL_WAVES_RESTORED', + 13: 'SQG_PERF_SEL_WAVES_SAVED', + 14: 'SQG_PERF_SEL_ACCUM_PREV', + 15: 'SQG_PERF_SEL_CYCLES', + 16: 'SQG_PERF_SEL_BUSY_CYCLES', + 17: 'SQG_PERF_SEL_WAVE_CYCLES', + 18: 'SQG_PERF_SEL_MSG', + 19: 'SQG_PERF_SEL_MSG_INTERRUPT', + 20: 'SQG_PERF_SEL_WAVES', + 21: 'SQG_PERF_SEL_WAVES_32', + 22: 'SQG_PERF_SEL_WAVES_64', + 23: 'SQG_PERF_SEL_LEVEL_WAVES', + 24: 'SQG_PERF_SEL_ITEMS', + 25: 'SQG_PERF_SEL_WAVE32_ITEMS', + 26: 'SQG_PERF_SEL_WAVE64_ITEMS', + 27: 'SQG_PERF_SEL_PS_QUADS', + 28: 'SQG_PERF_SEL_WAVES_EQ_64', + 29: 'SQG_PERF_SEL_WAVES_EQ_32', + 30: 'SQG_PERF_SEL_WAVES_LT_64', + 31: 'SQG_PERF_SEL_WAVES_LT_48', + 32: 'SQG_PERF_SEL_WAVES_LT_32', + 33: 'SQG_PERF_SEL_WAVES_LT_16', + 34: 'SQG_PERF_SEL_DUMMY_LAST', +} +SQG_PERF_SEL_NONE = 0 +SQG_PERF_SEL_MSG_BUS_BUSY = 1 +SQG_PERF_SEL_EXP_REQ0_BUS_BUSY = 2 +SQG_PERF_SEL_EXP_REQ1_BUS_BUSY = 3 +SQG_PERF_SEL_EXP_BUS0_BUSY = 4 +SQG_PERF_SEL_EXP_BUS1_BUSY = 5 +SQG_PERF_SEL_TTRACE_REQS = 6 +SQG_PERF_SEL_TTRACE_INFLIGHT_REQS = 7 +SQG_PERF_SEL_TTRACE_STALL = 8 +SQG_PERF_SEL_TTRACE_LOST_PACKETS = 9 +SQG_PERF_SEL_WAVES_INITIAL_PREFETCH = 10 +SQG_PERF_SEL_EVENTS = 11 +SQG_PERF_SEL_WAVES_RESTORED = 12 +SQG_PERF_SEL_WAVES_SAVED = 13 +SQG_PERF_SEL_ACCUM_PREV = 14 +SQG_PERF_SEL_CYCLES = 15 +SQG_PERF_SEL_BUSY_CYCLES = 16 +SQG_PERF_SEL_WAVE_CYCLES = 17 +SQG_PERF_SEL_MSG = 18 +SQG_PERF_SEL_MSG_INTERRUPT = 19 +SQG_PERF_SEL_WAVES = 20 +SQG_PERF_SEL_WAVES_32 = 21 +SQG_PERF_SEL_WAVES_64 = 22 +SQG_PERF_SEL_LEVEL_WAVES = 23 +SQG_PERF_SEL_ITEMS = 24 +SQG_PERF_SEL_WAVE32_ITEMS = 25 +SQG_PERF_SEL_WAVE64_ITEMS = 26 +SQG_PERF_SEL_PS_QUADS = 27 +SQG_PERF_SEL_WAVES_EQ_64 = 28 +SQG_PERF_SEL_WAVES_EQ_32 = 29 +SQG_PERF_SEL_WAVES_LT_64 = 30 +SQG_PERF_SEL_WAVES_LT_48 = 31 +SQG_PERF_SEL_WAVES_LT_32 = 32 +SQG_PERF_SEL_WAVES_LT_16 = 33 +SQG_PERF_SEL_DUMMY_LAST = 34 +SQG_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_CAC_POWER_SEL' +SQ_CAC_POWER_SEL__enumvalues = { + 0: 'SQ_CAC_POWER_VALU', + 1: 'SQ_CAC_POWER_VALU0', + 2: 'SQ_CAC_POWER_VALU1', + 3: 'SQ_CAC_POWER_VALU2', + 4: 'SQ_CAC_POWER_GPR_RD', + 5: 'SQ_CAC_POWER_GPR_WR', + 6: 'SQ_CAC_POWER_LDS_BUSY', + 7: 'SQ_CAC_POWER_ALU_BUSY', + 8: 'SQ_CAC_POWER_TEX_BUSY', +} +SQ_CAC_POWER_VALU = 0 +SQ_CAC_POWER_VALU0 = 1 +SQ_CAC_POWER_VALU1 = 2 +SQ_CAC_POWER_VALU2 = 3 +SQ_CAC_POWER_GPR_RD = 4 +SQ_CAC_POWER_GPR_WR = 5 +SQ_CAC_POWER_LDS_BUSY = 6 +SQ_CAC_POWER_ALU_BUSY = 7 +SQ_CAC_POWER_TEX_BUSY = 8 +SQ_CAC_POWER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_EDC_INFO_SOURCE' +SQ_EDC_INFO_SOURCE__enumvalues = { + 0: 'SQ_EDC_INFO_SOURCE_INVALID', + 1: 'SQ_EDC_INFO_SOURCE_INST', + 2: 'SQ_EDC_INFO_SOURCE_SGPR', + 3: 'SQ_EDC_INFO_SOURCE_VGPR', + 4: 'SQ_EDC_INFO_SOURCE_LDS', + 5: 'SQ_EDC_INFO_SOURCE_GDS', + 6: 'SQ_EDC_INFO_SOURCE_TA', +} +SQ_EDC_INFO_SOURCE_INVALID = 0 +SQ_EDC_INFO_SOURCE_INST = 1 +SQ_EDC_INFO_SOURCE_SGPR = 2 +SQ_EDC_INFO_SOURCE_VGPR = 3 +SQ_EDC_INFO_SOURCE_LDS = 4 +SQ_EDC_INFO_SOURCE_GDS = 5 +SQ_EDC_INFO_SOURCE_TA = 6 +SQ_EDC_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IBUF_ST' +SQ_IBUF_ST__enumvalues = { + 0: 'SQ_IBUF_IB_IDLE', + 1: 'SQ_IBUF_IB_INI_WAIT_GNT', + 2: 'SQ_IBUF_IB_INI_WAIT_DRET', + 3: 'SQ_IBUF_IB_LE_4DW', + 4: 'SQ_IBUF_IB_WAIT_DRET', + 5: 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 6: 'SQ_IBUF_IB_DRET', + 7: 'SQ_IBUF_IB_EMPTY_WAIT_GNT', +} +SQ_IBUF_IB_IDLE = 0 +SQ_IBUF_IB_INI_WAIT_GNT = 1 +SQ_IBUF_IB_INI_WAIT_DRET = 2 +SQ_IBUF_IB_LE_4DW = 3 +SQ_IBUF_IB_WAIT_DRET = 4 +SQ_IBUF_IB_EMPTY_WAIT_DRET = 5 +SQ_IBUF_IB_DRET = 6 +SQ_IBUF_IB_EMPTY_WAIT_GNT = 7 +SQ_IBUF_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IMG_FILTER_TYPE' +SQ_IMG_FILTER_TYPE__enumvalues = { + 0: 'SQ_IMG_FILTER_MODE_BLEND', + 1: 'SQ_IMG_FILTER_MODE_MIN', + 2: 'SQ_IMG_FILTER_MODE_MAX', +} +SQ_IMG_FILTER_MODE_BLEND = 0 +SQ_IMG_FILTER_MODE_MIN = 1 +SQ_IMG_FILTER_MODE_MAX = 2 +SQ_IMG_FILTER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_CMD' +SQ_IND_CMD_CMD__enumvalues = { + 0: 'SQ_IND_CMD_CMD_NULL', + 1: 'SQ_IND_CMD_CMD_SETHALT', + 2: 'SQ_IND_CMD_CMD_SAVECTX', + 3: 'SQ_IND_CMD_CMD_KILL', + 4: 'SQ_IND_CMD_CMD_TRAP_AFTER_INST', + 5: 'SQ_IND_CMD_CMD_TRAP', + 6: 'SQ_IND_CMD_CMD_SET_SPI_PRIO', + 7: 'SQ_IND_CMD_CMD_SETFATALHALT', + 8: 'SQ_IND_CMD_CMD_SINGLE_STEP', +} +SQ_IND_CMD_CMD_NULL = 0 +SQ_IND_CMD_CMD_SETHALT = 1 +SQ_IND_CMD_CMD_SAVECTX = 2 +SQ_IND_CMD_CMD_KILL = 3 +SQ_IND_CMD_CMD_TRAP_AFTER_INST = 4 +SQ_IND_CMD_CMD_TRAP = 5 +SQ_IND_CMD_CMD_SET_SPI_PRIO = 6 +SQ_IND_CMD_CMD_SETFATALHALT = 7 +SQ_IND_CMD_CMD_SINGLE_STEP = 8 +SQ_IND_CMD_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_MODE' +SQ_IND_CMD_MODE__enumvalues = { + 0: 'SQ_IND_CMD_MODE_SINGLE', + 1: 'SQ_IND_CMD_MODE_BROADCAST', + 2: 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', + 3: 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 4: 'SQ_IND_CMD_MODE_BROADCAST_ME', +} +SQ_IND_CMD_MODE_SINGLE = 0 +SQ_IND_CMD_MODE_BROADCAST = 1 +SQ_IND_CMD_MODE_BROADCAST_QUEUE = 2 +SQ_IND_CMD_MODE_BROADCAST_PIPE = 3 +SQ_IND_CMD_MODE_BROADCAST_ME = 4 +SQ_IND_CMD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_STR_ST' +SQ_INST_STR_ST__enumvalues = { + 0: 'SQ_INST_STR_IB_WAVE_NORML', + 1: 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 2: 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 3: 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 4: 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', + 5: 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', +} +SQ_INST_STR_IB_WAVE_NORML = 0 +SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV = 1 +SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV = 2 +SQ_INST_STR_IB_WAVE_INST_SKIP_AV = 3 +SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT = 4 +SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT = 5 +SQ_INST_STR_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_TYPE' +SQ_INST_TYPE__enumvalues = { + 0: 'SQ_INST_TYPE_VALU', + 1: 'SQ_INST_TYPE_SCALAR', + 2: 'SQ_INST_TYPE_TEX', + 3: 'SQ_INST_TYPE_LDS', + 4: 'SQ_INST_TYPE_LDS_DIRECT', + 5: 'SQ_INST_TYPE_EXP', + 6: 'SQ_INST_TYPE_MSG', + 7: 'SQ_INST_TYPE_BARRIER', + 8: 'SQ_INST_TYPE_BRANCH_NOT_TAKEN', + 9: 'SQ_INST_TYPE_BRANCH_TAKEN', + 10: 'SQ_INST_TYPE_JUMP', + 11: 'SQ_INST_TYPE_OTHER', + 12: 'SQ_INST_TYPE_NONE', +} +SQ_INST_TYPE_VALU = 0 +SQ_INST_TYPE_SCALAR = 1 +SQ_INST_TYPE_TEX = 2 +SQ_INST_TYPE_LDS = 3 +SQ_INST_TYPE_LDS_DIRECT = 4 +SQ_INST_TYPE_EXP = 5 +SQ_INST_TYPE_MSG = 6 +SQ_INST_TYPE_BARRIER = 7 +SQ_INST_TYPE_BRANCH_NOT_TAKEN = 8 +SQ_INST_TYPE_BRANCH_TAKEN = 9 +SQ_INST_TYPE_JUMP = 10 +SQ_INST_TYPE_OTHER = 11 +SQ_INST_TYPE_NONE = 12 +SQ_INST_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_LLC_CTL' +SQ_LLC_CTL__enumvalues = { + 0: 'SQ_LLC_0', + 1: 'SQ_LLC_1', + 2: 'SQ_LLC_RSVD_2', + 3: 'SQ_LLC_BYPASS', +} +SQ_LLC_0 = 0 +SQ_LLC_1 = 1 +SQ_LLC_RSVD_2 = 2 +SQ_LLC_BYPASS = 3 +SQ_LLC_CTL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_NO_INST_ISSUE' +SQ_NO_INST_ISSUE__enumvalues = { + 0: 'SQ_NO_INST_ISSUE_NO_INSTS', + 1: 'SQ_NO_INST_ISSUE_ALU_DEP', + 2: 'SQ_NO_INST_ISSUE_S_WAITCNT', + 3: 'SQ_NO_INST_ISSUE_NO_ARB_WIN', + 4: 'SQ_NO_INST_ISSUE_SLEEP_WAIT', + 5: 'SQ_NO_INST_ISSUE_BARRIER_WAIT', + 6: 'SQ_NO_INST_ISSUE_OTHER', +} +SQ_NO_INST_ISSUE_NO_INSTS = 0 +SQ_NO_INST_ISSUE_ALU_DEP = 1 +SQ_NO_INST_ISSUE_S_WAITCNT = 2 +SQ_NO_INST_ISSUE_NO_ARB_WIN = 3 +SQ_NO_INST_ISSUE_SLEEP_WAIT = 4 +SQ_NO_INST_ISSUE_BARRIER_WAIT = 5 +SQ_NO_INST_ISSUE_OTHER = 6 +SQ_NO_INST_ISSUE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_OOB_SELECT' +SQ_OOB_SELECT__enumvalues = { + 0: 'SQ_OOB_INDEX_AND_OFFSET', + 1: 'SQ_OOB_INDEX_ONLY', + 2: 'SQ_OOB_NUM_RECORDS_0', + 3: 'SQ_OOB_COMPLETE', +} +SQ_OOB_INDEX_AND_OFFSET = 0 +SQ_OOB_INDEX_ONLY = 1 +SQ_OOB_NUM_RECORDS_0 = 2 +SQ_OOB_COMPLETE = 3 +SQ_OOB_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_PERF_SEL' +SQ_PERF_SEL__enumvalues = { + 0: 'SQ_PERF_SEL_NONE', + 1: 'SQ_PERF_SEL_ACCUM_PREV', + 2: 'SQ_PERF_SEL_CYCLES', + 3: 'SQ_PERF_SEL_BUSY_CYCLES', + 4: 'SQ_PERF_SEL_WAVES', + 5: 'SQ_PERF_SEL_WAVES_32', + 6: 'SQ_PERF_SEL_WAVES_64', + 7: 'SQ_PERF_SEL_LEVEL_WAVES', + 8: 'SQ_PERF_SEL_ITEMS', + 9: 'SQ_PERF_SEL_WAVE32_ITEMS', + 10: 'SQ_PERF_SEL_WAVE64_ITEMS', + 11: 'SQ_PERF_SEL_PS_QUADS', + 12: 'SQ_PERF_SEL_EVENTS', + 13: 'SQ_PERF_SEL_WAVES_EQ_32', + 14: 'SQ_PERF_SEL_WAVES_EQ_64', + 15: 'SQ_PERF_SEL_WAVES_LT_64', + 16: 'SQ_PERF_SEL_WAVES_LT_48', + 17: 'SQ_PERF_SEL_WAVES_LT_32', + 18: 'SQ_PERF_SEL_WAVES_LT_16', + 19: 'SQ_PERF_SEL_WAVES_RESTORED', + 20: 'SQ_PERF_SEL_WAVES_SAVED', + 21: 'SQ_PERF_SEL_MSG', + 22: 'SQ_PERF_SEL_MSG_INTERRUPT', + 23: 'SQ_PERF_SEL_WAVES_INITIAL_PREFETCH', + 24: 'SQ_PERF_SEL_WAVE_CYCLES', + 25: 'SQ_PERF_SEL_WAVE_READY', + 26: 'SQ_PERF_SEL_WAIT_INST_ANY', + 27: 'SQ_PERF_SEL_WAIT_INST_VALU', + 28: 'SQ_PERF_SEL_WAIT_INST_SCA', + 29: 'SQ_PERF_SEL_WAIT_INST_LDS', + 30: 'SQ_PERF_SEL_WAIT_INST_TEX', + 31: 'SQ_PERF_SEL_WAIT_INST_FLAT', + 32: 'SQ_PERF_SEL_WAIT_INST_VMEM', + 33: 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', + 34: 'SQ_PERF_SEL_WAIT_INST_BR_MSG', + 35: 'SQ_PERF_SEL_WAIT_ANY', + 36: 'SQ_PERF_SEL_WAIT_CNT_ANY', + 37: 'SQ_PERF_SEL_WAIT_CNT_VMVS', + 38: 'SQ_PERF_SEL_WAIT_CNT_LGKM', + 39: 'SQ_PERF_SEL_WAIT_CNT_EXP', + 40: 'SQ_PERF_SEL_WAIT_TTRACE', + 41: 'SQ_PERF_SEL_WAIT_IFETCH', + 42: 'SQ_PERF_SEL_WAIT_BARRIER', + 43: 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 44: 'SQ_PERF_SEL_WAIT_SLEEP', + 45: 'SQ_PERF_SEL_WAIT_DELAY_ALU', + 46: 'SQ_PERF_SEL_WAIT_DEPCTR', + 47: 'SQ_PERF_SEL_WAIT_OTHER', + 48: 'SQ_PERF_SEL_INSTS_ALL', + 49: 'SQ_PERF_SEL_INSTS_BRANCH', + 50: 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 51: 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', + 52: 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS', + 53: 'SQ_PERF_SEL_INSTS_EXP_GDS', + 54: 'SQ_PERF_SEL_INSTS_GDS', + 55: 'SQ_PERF_SEL_INSTS_EXP', + 56: 'SQ_PERF_SEL_INSTS_FLAT', + 57: 'SQ_PERF_SEL_INSTS_LDS', + 58: 'SQ_PERF_SEL_INSTS_SALU', + 59: 'SQ_PERF_SEL_INSTS_SMEM', + 60: 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 61: 'SQ_PERF_SEL_INSTS_SENDMSG', + 62: 'SQ_PERF_SEL_INSTS_VALU', + 63: 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 64: 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 65: 'SQ_PERF_SEL_INSTS_TEX', + 66: 'SQ_PERF_SEL_INSTS_TEX_LOAD', + 67: 'SQ_PERF_SEL_INSTS_TEX_STORE', + 68: 'SQ_PERF_SEL_INSTS_DELAY_ALU', + 69: 'SQ_PERF_SEL_INSTS_INTERNAL', + 70: 'SQ_PERF_SEL_INSTS_WAVE32', + 71: 'SQ_PERF_SEL_INSTS_WAVE32_FLAT', + 72: 'SQ_PERF_SEL_INSTS_WAVE32_LDS', + 73: 'SQ_PERF_SEL_INSTS_WAVE32_VALU', + 74: 'SQ_PERF_SEL_WAVE32_INSTS_EXP_GDS', + 75: 'SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32', + 76: 'SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC', + 77: 'SQ_PERF_SEL_INSTS_WAVE32_TEX', + 78: 'SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD', + 79: 'SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE', + 80: 'SQ_PERF_SEL_ITEM_CYCLES_VALU', + 81: 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 82: 'SQ_PERF_SEL_WAVE32_INSTS', + 83: 'SQ_PERF_SEL_WAVE64_INSTS', + 84: 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 85: 'SQ_PERF_SEL_WAVE64_HALF_SKIP', + 86: 'SQ_PERF_SEL_INST_LEVEL_EXP', + 87: 'SQ_PERF_SEL_INST_LEVEL_GDS', + 88: 'SQ_PERF_SEL_INST_LEVEL_LDS', + 89: 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 90: 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 91: 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', + 92: 'SQ_PERF_SEL_IFETCH_REQS', + 93: 'SQ_PERF_SEL_IFETCH_LEVEL', + 94: 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 95: 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 96: 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 97: 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 98: 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 99: 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 100: 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 101: 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 102: 'SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL', + 103: 'SQ_PERF_SEL_INST_CYCLES_VALU', + 104: 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 105: 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 106: 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 107: 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 108: 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 109: 'SQ_PERF_SEL_INST_CYCLES_LDS', + 110: 'SQ_PERF_SEL_INST_CYCLES_TEX', + 111: 'SQ_PERF_SEL_INST_CYCLES_FLAT', + 112: 'SQ_PERF_SEL_INST_CYCLES_EXP_GDS', + 113: 'SQ_PERF_SEL_INST_CYCLES_EXP', + 114: 'SQ_PERF_SEL_INST_CYCLES_GDS', + 115: 'SQ_PERF_SEL_VALU_STARVE', + 116: 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', + 117: 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 118: 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 119: 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', + 120: 'SQ_PERF_SEL_VMEM_BUS_STALL', + 121: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 122: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 123: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 124: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 125: 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', + 126: 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 127: 'SQ_PERF_SEL_SALU_PIPE_STALL', + 128: 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 129: 'SQ_PERF_SEL_MSG_BUS_BUSY', + 130: 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', + 131: 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', + 132: 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 133: 'SQ_PERF_SEL_EXP_BUS0_BUSY', + 134: 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 135: 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', + 136: 'SQ_PERF_SEL_USER0', + 137: 'SQ_PERF_SEL_USER1', + 138: 'SQ_PERF_SEL_USER2', + 139: 'SQ_PERF_SEL_USER3', + 140: 'SQ_PERF_SEL_USER4', + 141: 'SQ_PERF_SEL_USER5', + 142: 'SQ_PERF_SEL_USER6', + 143: 'SQ_PERF_SEL_USER7', + 144: 'SQ_PERF_SEL_USER8', + 145: 'SQ_PERF_SEL_USER9', + 146: 'SQ_PERF_SEL_USER10', + 147: 'SQ_PERF_SEL_USER11', + 148: 'SQ_PERF_SEL_USER12', + 149: 'SQ_PERF_SEL_USER13', + 150: 'SQ_PERF_SEL_USER14', + 151: 'SQ_PERF_SEL_USER15', + 152: 'SQ_PERF_SEL_USER_LEVEL0', + 153: 'SQ_PERF_SEL_USER_LEVEL1', + 154: 'SQ_PERF_SEL_USER_LEVEL2', + 155: 'SQ_PERF_SEL_USER_LEVEL3', + 156: 'SQ_PERF_SEL_USER_LEVEL4', + 157: 'SQ_PERF_SEL_USER_LEVEL5', + 158: 'SQ_PERF_SEL_USER_LEVEL6', + 159: 'SQ_PERF_SEL_USER_LEVEL7', + 160: 'SQ_PERF_SEL_USER_LEVEL8', + 161: 'SQ_PERF_SEL_USER_LEVEL9', + 162: 'SQ_PERF_SEL_USER_LEVEL10', + 163: 'SQ_PERF_SEL_USER_LEVEL11', + 164: 'SQ_PERF_SEL_USER_LEVEL12', + 165: 'SQ_PERF_SEL_USER_LEVEL13', + 166: 'SQ_PERF_SEL_USER_LEVEL14', + 167: 'SQ_PERF_SEL_USER_LEVEL15', + 168: 'SQ_PERF_SEL_VALU_RETURN_SDST', + 169: 'SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT', + 170: 'SQ_PERF_SEL_INSTS_VALU_TRANS', + 171: 'SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD', + 172: 'SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD', + 173: 'SQ_PERF_SEL_INSTS_WAVE32_LDS_PARAM_LOAD', + 174: 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64', + 175: 'SQ_PERF_SEL_INSTS_VALU_VINTERP', + 176: 'SQ_PERF_SEL_INSTS_VALU_WAVE32_VINTERP', + 177: 'SQ_PERF_SEL_OVERFLOW_PREV', + 178: 'SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32', + 179: 'SQ_PERF_SEL_INSTS_VALU_1_PASS', + 180: 'SQ_PERF_SEL_INSTS_VALU_2_PASS', + 181: 'SQ_PERF_SEL_INSTS_VALU_4_PASS', + 182: 'SQ_PERF_SEL_INSTS_VALU_DP', + 183: 'SQ_PERF_SEL_SP_CONST_CYCLES', + 184: 'SQ_PERF_SEL_SP_CONST_STALL_CYCLES', + 185: 'SQ_PERF_SEL_ITEMS_VALU', + 186: 'SQ_PERF_SEL_ITEMS_MAX_VALU', + 187: 'SQ_PERF_SEL_ITEM_CYCLES_VMEM', + 188: 'SQ_PERF_SEL_DUMMY_END', + 255: 'SQ_PERF_SEL_DUMMY_LAST', + 256: 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 257: 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 258: 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', + 259: 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 260: 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 261: 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 262: 'SQC_PERF_SEL_LDS_ADDR_STALL', + 263: 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', + 264: 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 265: 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 266: 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 267: 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', + 268: 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 269: 'SQC_PERF_SEL_ICACHE_REQ', + 270: 'SQC_PERF_SEL_ICACHE_HITS', + 271: 'SQC_PERF_SEL_ICACHE_MISSES', + 272: 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 273: 'SQC_PERF_SEL_ICACHE_INVAL_INST', + 274: 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 275: 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 276: 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 277: 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', + 278: 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 279: 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 280: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 281: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 282: 'SQC_PERF_SEL_TC_REQ', + 283: 'SQC_PERF_SEL_TC_INST_REQ', + 284: 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 285: 'SQC_PERF_SEL_TC_STALL', + 286: 'SQC_PERF_SEL_TC_STARVE', + 287: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 288: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 289: 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 290: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 291: 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 292: 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 293: 'SQC_PERF_SEL_DCACHE_REQ', + 294: 'SQC_PERF_SEL_DCACHE_HITS', + 295: 'SQC_PERF_SEL_DCACHE_MISSES', + 296: 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 297: 'SQC_PERF_SEL_DCACHE_INVAL_INST', + 298: 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 299: 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 300: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 301: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 302: 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 303: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 304: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 305: 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 306: 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 307: 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 308: 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 309: 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 310: 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 311: 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 312: 'SQC_PERF_SEL_SQ_DCACHE_REQS', + 313: 'SQC_PERF_SEL_DCACHE_FLAT_REQ', + 314: 'SQC_PERF_SEL_TD_VGPR_BUSY', + 315: 'SQC_PERF_SEL_LDS_VGPR_BUSY', + 316: 'SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL', + 317: 'SQC_PERF_SEL_ICACHE_GCR', + 318: 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 319: 'SQC_PERF_SEL_DCACHE_GCR', + 320: 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 321: 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', + 322: 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', + 323: 'SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL', + 324: 'SQC_PERF_SEL_DUMMY_LAST', + 448: 'SP_PERF_SEL_DST_BUF_ALLOC_STALL', + 449: 'SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS', + 450: 'SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI', + 451: 'SP_PERF_SEL_DST_BUF_EVEN_DIRTY', + 452: 'SP_PERF_SEL_DST_BUF_ODD_DIRTY', + 453: 'SP_PERF_SEL_SRC_CACHE_HIT_B0', + 454: 'SP_PERF_SEL_SRC_CACHE_HIT_B1', + 455: 'SP_PERF_SEL_SRC_CACHE_HIT_B2', + 456: 'SP_PERF_SEL_SRC_CACHE_HIT_B3', + 457: 'SP_PERF_SEL_SRC_CACHE_PROBE_B0', + 458: 'SP_PERF_SEL_SRC_CACHE_PROBE_B1', + 459: 'SP_PERF_SEL_SRC_CACHE_PROBE_B2', + 460: 'SP_PERF_SEL_SRC_CACHE_PROBE_B3', + 461: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0', + 462: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1', + 463: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2', + 464: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3', + 465: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0', + 466: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1', + 467: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2', + 468: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3', + 469: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0', + 470: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1', + 471: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2', + 472: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3', + 473: 'SP_PERF_SEL_VALU_PENDING_QUEUE_STALL', + 474: 'SP_PERF_SEL_VALU_OPERAND', + 475: 'SP_PERF_SEL_VALU_VGPR_OPERAND', + 476: 'SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF', + 477: 'SP_PERF_SEL_VALU_EXEC_MASK_CHANGE', + 478: 'SP_PERF_SEL_VALU_COEXEC_WITH_TRANS', + 479: 'SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL', + 480: 'SP_PERF_SEL_VALU_STALL', + 481: 'SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY', + 482: 'SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY', + 483: 'SP_PERF_SEL_VALU_STALL_VDST_FWD', + 484: 'SP_PERF_SEL_VALU_STALL_SDST_FWD', + 485: 'SP_PERF_SEL_VALU_STALL_DST_STALL', + 486: 'SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY', + 487: 'SP_PERF_SEL_VGPR_VMEM_RD', + 488: 'SP_PERF_SEL_VGPR_EXP_RD', + 489: 'SP_PERF_SEL_VGPR_SPI_WR', + 490: 'SP_PERF_SEL_VGPR_TDLDS_DATA_WR', + 491: 'SP_PERF_SEL_VGPR_WR', + 492: 'SP_PERF_SEL_VGPR_RD', + 493: 'SP_PERF_SEL_DUMMY_LAST', + 511: 'SQ_PERF_SEL_NONE2', +} +SQ_PERF_SEL_NONE = 0 +SQ_PERF_SEL_ACCUM_PREV = 1 +SQ_PERF_SEL_CYCLES = 2 +SQ_PERF_SEL_BUSY_CYCLES = 3 +SQ_PERF_SEL_WAVES = 4 +SQ_PERF_SEL_WAVES_32 = 5 +SQ_PERF_SEL_WAVES_64 = 6 +SQ_PERF_SEL_LEVEL_WAVES = 7 +SQ_PERF_SEL_ITEMS = 8 +SQ_PERF_SEL_WAVE32_ITEMS = 9 +SQ_PERF_SEL_WAVE64_ITEMS = 10 +SQ_PERF_SEL_PS_QUADS = 11 +SQ_PERF_SEL_EVENTS = 12 +SQ_PERF_SEL_WAVES_EQ_32 = 13 +SQ_PERF_SEL_WAVES_EQ_64 = 14 +SQ_PERF_SEL_WAVES_LT_64 = 15 +SQ_PERF_SEL_WAVES_LT_48 = 16 +SQ_PERF_SEL_WAVES_LT_32 = 17 +SQ_PERF_SEL_WAVES_LT_16 = 18 +SQ_PERF_SEL_WAVES_RESTORED = 19 +SQ_PERF_SEL_WAVES_SAVED = 20 +SQ_PERF_SEL_MSG = 21 +SQ_PERF_SEL_MSG_INTERRUPT = 22 +SQ_PERF_SEL_WAVES_INITIAL_PREFETCH = 23 +SQ_PERF_SEL_WAVE_CYCLES = 24 +SQ_PERF_SEL_WAVE_READY = 25 +SQ_PERF_SEL_WAIT_INST_ANY = 26 +SQ_PERF_SEL_WAIT_INST_VALU = 27 +SQ_PERF_SEL_WAIT_INST_SCA = 28 +SQ_PERF_SEL_WAIT_INST_LDS = 29 +SQ_PERF_SEL_WAIT_INST_TEX = 30 +SQ_PERF_SEL_WAIT_INST_FLAT = 31 +SQ_PERF_SEL_WAIT_INST_VMEM = 32 +SQ_PERF_SEL_WAIT_INST_EXP_GDS = 33 +SQ_PERF_SEL_WAIT_INST_BR_MSG = 34 +SQ_PERF_SEL_WAIT_ANY = 35 +SQ_PERF_SEL_WAIT_CNT_ANY = 36 +SQ_PERF_SEL_WAIT_CNT_VMVS = 37 +SQ_PERF_SEL_WAIT_CNT_LGKM = 38 +SQ_PERF_SEL_WAIT_CNT_EXP = 39 +SQ_PERF_SEL_WAIT_TTRACE = 40 +SQ_PERF_SEL_WAIT_IFETCH = 41 +SQ_PERF_SEL_WAIT_BARRIER = 42 +SQ_PERF_SEL_WAIT_EXP_ALLOC = 43 +SQ_PERF_SEL_WAIT_SLEEP = 44 +SQ_PERF_SEL_WAIT_DELAY_ALU = 45 +SQ_PERF_SEL_WAIT_DEPCTR = 46 +SQ_PERF_SEL_WAIT_OTHER = 47 +SQ_PERF_SEL_INSTS_ALL = 48 +SQ_PERF_SEL_INSTS_BRANCH = 49 +SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN = 50 +SQ_PERF_SEL_INSTS_CBRANCH_TAKEN = 51 +SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS = 52 +SQ_PERF_SEL_INSTS_EXP_GDS = 53 +SQ_PERF_SEL_INSTS_GDS = 54 +SQ_PERF_SEL_INSTS_EXP = 55 +SQ_PERF_SEL_INSTS_FLAT = 56 +SQ_PERF_SEL_INSTS_LDS = 57 +SQ_PERF_SEL_INSTS_SALU = 58 +SQ_PERF_SEL_INSTS_SMEM = 59 +SQ_PERF_SEL_INSTS_SMEM_NORM = 60 +SQ_PERF_SEL_INSTS_SENDMSG = 61 +SQ_PERF_SEL_INSTS_VALU = 62 +SQ_PERF_SEL_INSTS_VALU_TRANS32 = 63 +SQ_PERF_SEL_INSTS_VALU_NO_COEXEC = 64 +SQ_PERF_SEL_INSTS_TEX = 65 +SQ_PERF_SEL_INSTS_TEX_LOAD = 66 +SQ_PERF_SEL_INSTS_TEX_STORE = 67 +SQ_PERF_SEL_INSTS_DELAY_ALU = 68 +SQ_PERF_SEL_INSTS_INTERNAL = 69 +SQ_PERF_SEL_INSTS_WAVE32 = 70 +SQ_PERF_SEL_INSTS_WAVE32_FLAT = 71 +SQ_PERF_SEL_INSTS_WAVE32_LDS = 72 +SQ_PERF_SEL_INSTS_WAVE32_VALU = 73 +SQ_PERF_SEL_WAVE32_INSTS_EXP_GDS = 74 +SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32 = 75 +SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC = 76 +SQ_PERF_SEL_INSTS_WAVE32_TEX = 77 +SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD = 78 +SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE = 79 +SQ_PERF_SEL_ITEM_CYCLES_VALU = 80 +SQ_PERF_SEL_VALU_READWRITELANE_CYCLES = 81 +SQ_PERF_SEL_WAVE32_INSTS = 82 +SQ_PERF_SEL_WAVE64_INSTS = 83 +SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED = 84 +SQ_PERF_SEL_WAVE64_HALF_SKIP = 85 +SQ_PERF_SEL_INST_LEVEL_EXP = 86 +SQ_PERF_SEL_INST_LEVEL_GDS = 87 +SQ_PERF_SEL_INST_LEVEL_LDS = 88 +SQ_PERF_SEL_INST_LEVEL_SMEM = 89 +SQ_PERF_SEL_INST_LEVEL_TEX_LOAD = 90 +SQ_PERF_SEL_INST_LEVEL_TEX_STORE = 91 +SQ_PERF_SEL_IFETCH_REQS = 92 +SQ_PERF_SEL_IFETCH_LEVEL = 93 +SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL = 94 +SQ_PERF_SEL_VALU_SGATHER_STALL = 95 +SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL = 96 +SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL = 97 +SQ_PERF_SEL_VALU_SGATHER_FULL_STALL = 98 +SQ_PERF_SEL_SALU_SGATHER_STALL = 99 +SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL = 100 +SQ_PERF_SEL_SALU_GATHER_FULL_STALL = 101 +SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL = 102 +SQ_PERF_SEL_INST_CYCLES_VALU = 103 +SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32 = 104 +SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC = 105 +SQ_PERF_SEL_INST_CYCLES_VMEM = 106 +SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD = 107 +SQ_PERF_SEL_INST_CYCLES_VMEM_STORE = 108 +SQ_PERF_SEL_INST_CYCLES_LDS = 109 +SQ_PERF_SEL_INST_CYCLES_TEX = 110 +SQ_PERF_SEL_INST_CYCLES_FLAT = 111 +SQ_PERF_SEL_INST_CYCLES_EXP_GDS = 112 +SQ_PERF_SEL_INST_CYCLES_EXP = 113 +SQ_PERF_SEL_INST_CYCLES_GDS = 114 +SQ_PERF_SEL_VALU_STARVE = 115 +SQ_PERF_SEL_VMEM_ARB_FIFO_FULL = 116 +SQ_PERF_SEL_MSG_FIFO_FULL_STALL = 117 +SQ_PERF_SEL_EXP_REQ_FIFO_FULL = 118 +SQ_PERF_SEL_VMEM_BUS_ACTIVE = 119 +SQ_PERF_SEL_VMEM_BUS_STALL = 120 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL = 121 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL = 122 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL = 123 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL = 124 +SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY = 125 +SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY = 126 +SQ_PERF_SEL_SALU_PIPE_STALL = 127 +SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES = 128 +SQ_PERF_SEL_MSG_BUS_BUSY = 129 +SQ_PERF_SEL_EXP_REQ_BUS_STALL = 130 +SQ_PERF_SEL_EXP_REQ0_BUS_BUSY = 131 +SQ_PERF_SEL_EXP_REQ1_BUS_BUSY = 132 +SQ_PERF_SEL_EXP_BUS0_BUSY = 133 +SQ_PERF_SEL_EXP_BUS1_BUSY = 134 +SQ_PERF_SEL_INST_CACHE_REQ_STALL = 135 +SQ_PERF_SEL_USER0 = 136 +SQ_PERF_SEL_USER1 = 137 +SQ_PERF_SEL_USER2 = 138 +SQ_PERF_SEL_USER3 = 139 +SQ_PERF_SEL_USER4 = 140 +SQ_PERF_SEL_USER5 = 141 +SQ_PERF_SEL_USER6 = 142 +SQ_PERF_SEL_USER7 = 143 +SQ_PERF_SEL_USER8 = 144 +SQ_PERF_SEL_USER9 = 145 +SQ_PERF_SEL_USER10 = 146 +SQ_PERF_SEL_USER11 = 147 +SQ_PERF_SEL_USER12 = 148 +SQ_PERF_SEL_USER13 = 149 +SQ_PERF_SEL_USER14 = 150 +SQ_PERF_SEL_USER15 = 151 +SQ_PERF_SEL_USER_LEVEL0 = 152 +SQ_PERF_SEL_USER_LEVEL1 = 153 +SQ_PERF_SEL_USER_LEVEL2 = 154 +SQ_PERF_SEL_USER_LEVEL3 = 155 +SQ_PERF_SEL_USER_LEVEL4 = 156 +SQ_PERF_SEL_USER_LEVEL5 = 157 +SQ_PERF_SEL_USER_LEVEL6 = 158 +SQ_PERF_SEL_USER_LEVEL7 = 159 +SQ_PERF_SEL_USER_LEVEL8 = 160 +SQ_PERF_SEL_USER_LEVEL9 = 161 +SQ_PERF_SEL_USER_LEVEL10 = 162 +SQ_PERF_SEL_USER_LEVEL11 = 163 +SQ_PERF_SEL_USER_LEVEL12 = 164 +SQ_PERF_SEL_USER_LEVEL13 = 165 +SQ_PERF_SEL_USER_LEVEL14 = 166 +SQ_PERF_SEL_USER_LEVEL15 = 167 +SQ_PERF_SEL_VALU_RETURN_SDST = 168 +SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT = 169 +SQ_PERF_SEL_INSTS_VALU_TRANS = 170 +SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD = 171 +SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD = 172 +SQ_PERF_SEL_INSTS_WAVE32_LDS_PARAM_LOAD = 173 +SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64 = 174 +SQ_PERF_SEL_INSTS_VALU_VINTERP = 175 +SQ_PERF_SEL_INSTS_VALU_WAVE32_VINTERP = 176 +SQ_PERF_SEL_OVERFLOW_PREV = 177 +SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32 = 178 +SQ_PERF_SEL_INSTS_VALU_1_PASS = 179 +SQ_PERF_SEL_INSTS_VALU_2_PASS = 180 +SQ_PERF_SEL_INSTS_VALU_4_PASS = 181 +SQ_PERF_SEL_INSTS_VALU_DP = 182 +SQ_PERF_SEL_SP_CONST_CYCLES = 183 +SQ_PERF_SEL_SP_CONST_STALL_CYCLES = 184 +SQ_PERF_SEL_ITEMS_VALU = 185 +SQ_PERF_SEL_ITEMS_MAX_VALU = 186 +SQ_PERF_SEL_ITEM_CYCLES_VMEM = 187 +SQ_PERF_SEL_DUMMY_END = 188 +SQ_PERF_SEL_DUMMY_LAST = 255 +SQC_PERF_SEL_LDS_BANK_CONFLICT = 256 +SQC_PERF_SEL_LDS_ADDR_CONFLICT = 257 +SQC_PERF_SEL_LDS_UNALIGNED_STALL = 258 +SQC_PERF_SEL_LDS_MEM_VIOLATIONS = 259 +SQC_PERF_SEL_LDS_ATOMIC_RETURN = 260 +SQC_PERF_SEL_LDS_IDX_ACTIVE = 261 +SQC_PERF_SEL_LDS_ADDR_STALL = 262 +SQC_PERF_SEL_LDS_ADDR_ACTIVE = 263 +SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD = 264 +SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD = 265 +SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL = 266 +SQC_PERF_SEL_LDS_FP_ADD_CYCLES = 267 +SQC_PERF_SEL_ICACHE_BUSY_CYCLES = 268 +SQC_PERF_SEL_ICACHE_REQ = 269 +SQC_PERF_SEL_ICACHE_HITS = 270 +SQC_PERF_SEL_ICACHE_MISSES = 271 +SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE = 272 +SQC_PERF_SEL_ICACHE_INVAL_INST = 273 +SQC_PERF_SEL_ICACHE_INVAL_ASYNC = 274 +SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL = 275 +SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL = 276 +SQC_PERF_SEL_TC_INFLIGHT_LEVEL = 277 +SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL = 278 +SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL = 279 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB = 280 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB = 281 +SQC_PERF_SEL_TC_REQ = 282 +SQC_PERF_SEL_TC_INST_REQ = 283 +SQC_PERF_SEL_TC_DATA_READ_REQ = 284 +SQC_PERF_SEL_TC_STALL = 285 +SQC_PERF_SEL_TC_STARVE = 286 +SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT = 287 +SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB = 288 +SQC_PERF_SEL_ICACHE_CACHE_STALLED = 289 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX = 290 +SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT = 291 +SQC_PERF_SEL_DCACHE_BUSY_CYCLES = 292 +SQC_PERF_SEL_DCACHE_REQ = 293 +SQC_PERF_SEL_DCACHE_HITS = 294 +SQC_PERF_SEL_DCACHE_MISSES = 295 +SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE = 296 +SQC_PERF_SEL_DCACHE_INVAL_INST = 297 +SQC_PERF_SEL_DCACHE_INVAL_ASYNC = 298 +SQC_PERF_SEL_DCACHE_HIT_LRU_READ = 299 +SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT = 300 +SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB = 301 +SQC_PERF_SEL_DCACHE_CACHE_STALLED = 302 +SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX = 303 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT = 304 +SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT = 305 +SQC_PERF_SEL_DCACHE_REQ_READ_1 = 306 +SQC_PERF_SEL_DCACHE_REQ_READ_2 = 307 +SQC_PERF_SEL_DCACHE_REQ_READ_4 = 308 +SQC_PERF_SEL_DCACHE_REQ_READ_8 = 309 +SQC_PERF_SEL_DCACHE_REQ_READ_16 = 310 +SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE = 311 +SQC_PERF_SEL_SQ_DCACHE_REQS = 312 +SQC_PERF_SEL_DCACHE_FLAT_REQ = 313 +SQC_PERF_SEL_TD_VGPR_BUSY = 314 +SQC_PERF_SEL_LDS_VGPR_BUSY = 315 +SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL = 316 +SQC_PERF_SEL_ICACHE_GCR = 317 +SQC_PERF_SEL_ICACHE_GCR_HITS = 318 +SQC_PERF_SEL_DCACHE_GCR = 319 +SQC_PERF_SEL_DCACHE_GCR_HITS = 320 +SQC_PERF_SEL_ICACHE_GCR_INVALIDATE = 321 +SQC_PERF_SEL_DCACHE_GCR_INVALIDATE = 322 +SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL = 323 +SQC_PERF_SEL_DUMMY_LAST = 324 +SP_PERF_SEL_DST_BUF_ALLOC_STALL = 448 +SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS = 449 +SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI = 450 +SP_PERF_SEL_DST_BUF_EVEN_DIRTY = 451 +SP_PERF_SEL_DST_BUF_ODD_DIRTY = 452 +SP_PERF_SEL_SRC_CACHE_HIT_B0 = 453 +SP_PERF_SEL_SRC_CACHE_HIT_B1 = 454 +SP_PERF_SEL_SRC_CACHE_HIT_B2 = 455 +SP_PERF_SEL_SRC_CACHE_HIT_B3 = 456 +SP_PERF_SEL_SRC_CACHE_PROBE_B0 = 457 +SP_PERF_SEL_SRC_CACHE_PROBE_B1 = 458 +SP_PERF_SEL_SRC_CACHE_PROBE_B2 = 459 +SP_PERF_SEL_SRC_CACHE_PROBE_B3 = 460 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0 = 461 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1 = 462 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2 = 463 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3 = 464 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0 = 465 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1 = 466 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2 = 467 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3 = 468 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0 = 469 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1 = 470 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2 = 471 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3 = 472 +SP_PERF_SEL_VALU_PENDING_QUEUE_STALL = 473 +SP_PERF_SEL_VALU_OPERAND = 474 +SP_PERF_SEL_VALU_VGPR_OPERAND = 475 +SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF = 476 +SP_PERF_SEL_VALU_EXEC_MASK_CHANGE = 477 +SP_PERF_SEL_VALU_COEXEC_WITH_TRANS = 478 +SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL = 479 +SP_PERF_SEL_VALU_STALL = 480 +SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY = 481 +SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY = 482 +SP_PERF_SEL_VALU_STALL_VDST_FWD = 483 +SP_PERF_SEL_VALU_STALL_SDST_FWD = 484 +SP_PERF_SEL_VALU_STALL_DST_STALL = 485 +SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY = 486 +SP_PERF_SEL_VGPR_VMEM_RD = 487 +SP_PERF_SEL_VGPR_EXP_RD = 488 +SP_PERF_SEL_VGPR_SPI_WR = 489 +SP_PERF_SEL_VGPR_TDLDS_DATA_WR = 490 +SP_PERF_SEL_VGPR_WR = 491 +SP_PERF_SEL_VGPR_RD = 492 +SP_PERF_SEL_DUMMY_LAST = 493 +SQ_PERF_SEL_NONE2 = 511 +SQ_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_ROUND_MODE' +SQ_ROUND_MODE__enumvalues = { + 0: 'SQ_ROUND_NEAREST_EVEN', + 1: 'SQ_ROUND_PLUS_INFINITY', + 2: 'SQ_ROUND_MINUS_INFINITY', + 3: 'SQ_ROUND_TO_ZERO', +} +SQ_ROUND_NEAREST_EVEN = 0 +SQ_ROUND_PLUS_INFINITY = 1 +SQ_ROUND_MINUS_INFINITY = 2 +SQ_ROUND_TO_ZERO = 3 +SQ_ROUND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_BUF_TYPE' +SQ_RSRC_BUF_TYPE__enumvalues = { + 0: 'SQ_RSRC_BUF', + 1: 'SQ_RSRC_BUF_RSVD_1', + 2: 'SQ_RSRC_BUF_RSVD_2', + 3: 'SQ_RSRC_BUF_RSVD_3', +} +SQ_RSRC_BUF = 0 +SQ_RSRC_BUF_RSVD_1 = 1 +SQ_RSRC_BUF_RSVD_2 = 2 +SQ_RSRC_BUF_RSVD_3 = 3 +SQ_RSRC_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_FLAT_TYPE' +SQ_RSRC_FLAT_TYPE__enumvalues = { + 0: 'SQ_RSRC_FLAT_RSVD_0', + 1: 'SQ_RSRC_FLAT', + 2: 'SQ_RSRC_FLAT_RSVD_2', + 3: 'SQ_RSRC_FLAT_RSVD_3', +} +SQ_RSRC_FLAT_RSVD_0 = 0 +SQ_RSRC_FLAT = 1 +SQ_RSRC_FLAT_RSVD_2 = 2 +SQ_RSRC_FLAT_RSVD_3 = 3 +SQ_RSRC_FLAT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_IMG_TYPE' +SQ_RSRC_IMG_TYPE__enumvalues = { + 0: 'SQ_RSRC_IMG_RSVD_0', + 1: 'SQ_RSRC_IMG_RSVD_1', + 2: 'SQ_RSRC_IMG_RSVD_2', + 3: 'SQ_RSRC_IMG_RSVD_3', + 4: 'SQ_RSRC_IMG_RSVD_4', + 5: 'SQ_RSRC_IMG_RSVD_5', + 6: 'SQ_RSRC_IMG_RSVD_6', + 7: 'SQ_RSRC_IMG_RSVD_7', + 8: 'SQ_RSRC_IMG_1D', + 9: 'SQ_RSRC_IMG_2D', + 10: 'SQ_RSRC_IMG_3D', + 11: 'SQ_RSRC_IMG_CUBE', + 12: 'SQ_RSRC_IMG_1D_ARRAY', + 13: 'SQ_RSRC_IMG_2D_ARRAY', + 14: 'SQ_RSRC_IMG_2D_MSAA', + 15: 'SQ_RSRC_IMG_2D_MSAA_ARRAY', +} +SQ_RSRC_IMG_RSVD_0 = 0 +SQ_RSRC_IMG_RSVD_1 = 1 +SQ_RSRC_IMG_RSVD_2 = 2 +SQ_RSRC_IMG_RSVD_3 = 3 +SQ_RSRC_IMG_RSVD_4 = 4 +SQ_RSRC_IMG_RSVD_5 = 5 +SQ_RSRC_IMG_RSVD_6 = 6 +SQ_RSRC_IMG_RSVD_7 = 7 +SQ_RSRC_IMG_1D = 8 +SQ_RSRC_IMG_2D = 9 +SQ_RSRC_IMG_3D = 10 +SQ_RSRC_IMG_CUBE = 11 +SQ_RSRC_IMG_1D_ARRAY = 12 +SQ_RSRC_IMG_2D_ARRAY = 13 +SQ_RSRC_IMG_2D_MSAA = 14 +SQ_RSRC_IMG_2D_MSAA_ARRAY = 15 +SQ_RSRC_IMG_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_SEL_XYZW01' +SQ_SEL_XYZW01__enumvalues = { + 0: 'SQ_SEL_0', + 1: 'SQ_SEL_1', + 2: 'SQ_SEL_N_BC_1', + 3: 'SQ_SEL_RESERVED_1', + 4: 'SQ_SEL_X', + 5: 'SQ_SEL_Y', + 6: 'SQ_SEL_Z', + 7: 'SQ_SEL_W', +} +SQ_SEL_0 = 0 +SQ_SEL_1 = 1 +SQ_SEL_N_BC_1 = 2 +SQ_SEL_RESERVED_1 = 3 +SQ_SEL_X = 4 +SQ_SEL_Y = 5 +SQ_SEL_Z = 6 +SQ_SEL_W = 7 +SQ_SEL_XYZW01 = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_ANISO_RATIO' +SQ_TEX_ANISO_RATIO__enumvalues = { + 0: 'SQ_TEX_ANISO_RATIO_1', + 1: 'SQ_TEX_ANISO_RATIO_2', + 2: 'SQ_TEX_ANISO_RATIO_4', + 3: 'SQ_TEX_ANISO_RATIO_8', + 4: 'SQ_TEX_ANISO_RATIO_16', +} +SQ_TEX_ANISO_RATIO_1 = 0 +SQ_TEX_ANISO_RATIO_2 = 1 +SQ_TEX_ANISO_RATIO_4 = 2 +SQ_TEX_ANISO_RATIO_8 = 3 +SQ_TEX_ANISO_RATIO_16 = 4 +SQ_TEX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_BORDER_COLOR' +SQ_TEX_BORDER_COLOR__enumvalues = { + 0: 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 1: 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 2: 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 3: 'SQ_TEX_BORDER_COLOR_REGISTER', +} +SQ_TEX_BORDER_COLOR_TRANS_BLACK = 0 +SQ_TEX_BORDER_COLOR_OPAQUE_BLACK = 1 +SQ_TEX_BORDER_COLOR_OPAQUE_WHITE = 2 +SQ_TEX_BORDER_COLOR_REGISTER = 3 +SQ_TEX_BORDER_COLOR = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_CLAMP' +SQ_TEX_CLAMP__enumvalues = { + 0: 'SQ_TEX_WRAP', + 1: 'SQ_TEX_MIRROR', + 2: 'SQ_TEX_CLAMP_LAST_TEXEL', + 3: 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 4: 'SQ_TEX_CLAMP_HALF_BORDER', + 5: 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', + 6: 'SQ_TEX_CLAMP_BORDER', + 7: 'SQ_TEX_MIRROR_ONCE_BORDER', +} +SQ_TEX_WRAP = 0 +SQ_TEX_MIRROR = 1 +SQ_TEX_CLAMP_LAST_TEXEL = 2 +SQ_TEX_MIRROR_ONCE_LAST_TEXEL = 3 +SQ_TEX_CLAMP_HALF_BORDER = 4 +SQ_TEX_MIRROR_ONCE_HALF_BORDER = 5 +SQ_TEX_CLAMP_BORDER = 6 +SQ_TEX_MIRROR_ONCE_BORDER = 7 +SQ_TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_DEPTH_COMPARE' +SQ_TEX_DEPTH_COMPARE__enumvalues = { + 0: 'SQ_TEX_DEPTH_COMPARE_NEVER', + 1: 'SQ_TEX_DEPTH_COMPARE_LESS', + 2: 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 3: 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', + 4: 'SQ_TEX_DEPTH_COMPARE_GREATER', + 5: 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', + 6: 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', + 7: 'SQ_TEX_DEPTH_COMPARE_ALWAYS', +} +SQ_TEX_DEPTH_COMPARE_NEVER = 0 +SQ_TEX_DEPTH_COMPARE_LESS = 1 +SQ_TEX_DEPTH_COMPARE_EQUAL = 2 +SQ_TEX_DEPTH_COMPARE_LESSEQUAL = 3 +SQ_TEX_DEPTH_COMPARE_GREATER = 4 +SQ_TEX_DEPTH_COMPARE_NOTEQUAL = 5 +SQ_TEX_DEPTH_COMPARE_GREATEREQUAL = 6 +SQ_TEX_DEPTH_COMPARE_ALWAYS = 7 +SQ_TEX_DEPTH_COMPARE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_MIP_FILTER' +SQ_TEX_MIP_FILTER__enumvalues = { + 0: 'SQ_TEX_MIP_FILTER_NONE', + 1: 'SQ_TEX_MIP_FILTER_POINT', + 2: 'SQ_TEX_MIP_FILTER_LINEAR', + 3: 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', +} +SQ_TEX_MIP_FILTER_NONE = 0 +SQ_TEX_MIP_FILTER_POINT = 1 +SQ_TEX_MIP_FILTER_LINEAR = 2 +SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ = 3 +SQ_TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_XY_FILTER' +SQ_TEX_XY_FILTER__enumvalues = { + 0: 'SQ_TEX_XY_FILTER_POINT', + 1: 'SQ_TEX_XY_FILTER_BILINEAR', + 2: 'SQ_TEX_XY_FILTER_ANISO_POINT', + 3: 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', +} +SQ_TEX_XY_FILTER_POINT = 0 +SQ_TEX_XY_FILTER_BILINEAR = 1 +SQ_TEX_XY_FILTER_ANISO_POINT = 2 +SQ_TEX_XY_FILTER_ANISO_BILINEAR = 3 +SQ_TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_Z_FILTER' +SQ_TEX_Z_FILTER__enumvalues = { + 0: 'SQ_TEX_Z_FILTER_NONE', + 1: 'SQ_TEX_Z_FILTER_POINT', + 2: 'SQ_TEX_Z_FILTER_LINEAR', +} +SQ_TEX_Z_FILTER_NONE = 0 +SQ_TEX_Z_FILTER_POINT = 1 +SQ_TEX_Z_FILTER_LINEAR = 2 +SQ_TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_MODE' +SQ_TT_MODE__enumvalues = { + 0: 'SQ_TT_MODE_OFF', + 1: 'SQ_TT_MODE_ON', + 2: 'SQ_TT_MODE_GLOBAL', + 3: 'SQ_TT_MODE_DETAIL', +} +SQ_TT_MODE_OFF = 0 +SQ_TT_MODE_ON = 1 +SQ_TT_MODE_GLOBAL = 2 +SQ_TT_MODE_DETAIL = 3 +SQ_TT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_RT_FREQ' +SQ_TT_RT_FREQ__enumvalues = { + 0: 'SQ_TT_RT_FREQ_NEVER', + 1: 'SQ_TT_RT_FREQ_1024_CLK', + 2: 'SQ_TT_RT_FREQ_4096_CLK', +} +SQ_TT_RT_FREQ_NEVER = 0 +SQ_TT_RT_FREQ_1024_CLK = 1 +SQ_TT_RT_FREQ_4096_CLK = 2 +SQ_TT_RT_FREQ = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_INST_EXCLUDE' +SQ_TT_TOKEN_MASK_INST_EXCLUDE__enumvalues = { + 1: 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_BIT', + 2: 'SQ_TT_INST_EXCLUDE_EXPGNT234_BIT', +} +SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_BIT = 1 +SQ_TT_INST_EXCLUDE_EXPGNT234_BIT = 2 +SQ_TT_TOKEN_MASK_INST_EXCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_INST_EXCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_INST_EXCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_SHIFT', + 1: 'SQ_TT_INST_EXCLUDE_EXPGNT234_SHIFT', +} +SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_SHIFT = 0 +SQ_TT_INST_EXCLUDE_EXPGNT234_SHIFT = 1 +SQ_TT_TOKEN_MASK_INST_EXCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_EXCLUDE' +SQ_TT_TOKEN_MASK_REG_EXCLUDE__enumvalues = { + 1: 'SQ_TT_REG_EXCLUDE_USER_DATA_BIT', + 2: 'SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_BIT', + 4: 'SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_BIT', +} +SQ_TT_REG_EXCLUDE_USER_DATA_BIT = 1 +SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_BIT = 2 +SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_BIT = 4 +SQ_TT_TOKEN_MASK_REG_EXCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_EXCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_REG_EXCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_REG_EXCLUDE_USER_DATA_SHIFT', + 1: 'SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_SHIFT', + 2: 'SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_SHIFT', +} +SQ_TT_REG_EXCLUDE_USER_DATA_SHIFT = 0 +SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_SHIFT = 1 +SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_SHIFT = 2 +SQ_TT_TOKEN_MASK_REG_EXCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_INCLUDE' +SQ_TT_TOKEN_MASK_REG_INCLUDE__enumvalues = { + 1: 'SQ_TT_TOKEN_MASK_SQDEC_BIT', + 2: 'SQ_TT_TOKEN_MASK_SHDEC_BIT', + 4: 'SQ_TT_TOKEN_MASK_GFXUDEC_BIT', + 8: 'SQ_TT_TOKEN_MASK_COMP_BIT', + 16: 'SQ_TT_TOKEN_MASK_CONTEXT_BIT', + 32: 'SQ_TT_TOKEN_MASK_CONFIG_BIT', + 64: 'SQ_TT_TOKEN_MASK_ALL_BIT', + 128: 'SQ_TT_TOKEN_MASK_RSVD_BIT', +} +SQ_TT_TOKEN_MASK_SQDEC_BIT = 1 +SQ_TT_TOKEN_MASK_SHDEC_BIT = 2 +SQ_TT_TOKEN_MASK_GFXUDEC_BIT = 4 +SQ_TT_TOKEN_MASK_COMP_BIT = 8 +SQ_TT_TOKEN_MASK_CONTEXT_BIT = 16 +SQ_TT_TOKEN_MASK_CONFIG_BIT = 32 +SQ_TT_TOKEN_MASK_ALL_BIT = 64 +SQ_TT_TOKEN_MASK_RSVD_BIT = 128 +SQ_TT_TOKEN_MASK_REG_INCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_TOKEN_MASK_SQDEC_SHIFT', + 1: 'SQ_TT_TOKEN_MASK_SHDEC_SHIFT', + 2: 'SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT', + 3: 'SQ_TT_TOKEN_MASK_COMP_SHIFT', + 4: 'SQ_TT_TOKEN_MASK_CONTEXT_SHIFT', + 5: 'SQ_TT_TOKEN_MASK_CONFIG_SHIFT', + 6: 'SQ_TT_TOKEN_MASK_ALL_SHIFT', + 7: 'SQ_TT_TOKEN_MASK_RSVD_SHIFT', +} +SQ_TT_TOKEN_MASK_SQDEC_SHIFT = 0 +SQ_TT_TOKEN_MASK_SHDEC_SHIFT = 1 +SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT = 2 +SQ_TT_TOKEN_MASK_COMP_SHIFT = 3 +SQ_TT_TOKEN_MASK_CONTEXT_SHIFT = 4 +SQ_TT_TOKEN_MASK_CONFIG_SHIFT = 5 +SQ_TT_TOKEN_MASK_ALL_SHIFT = 6 +SQ_TT_TOKEN_MASK_RSVD_SHIFT = 7 +SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT' +SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT', + 1: 'SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT', + 2: 'SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT', + 3: 'SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT', + 4: 'SQ_TT_TOKEN_EXCLUDE_WAVESTARTEND_SHIFT', + 5: 'SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT', + 6: 'SQ_TT_TOKEN_EXCLUDE_REG_SHIFT', + 7: 'SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT', + 8: 'SQ_TT_TOKEN_EXCLUDE_INST_SHIFT', + 9: 'SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT', + 10: 'SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT', + 11: 'SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT', +} +SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT = 0 +SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT = 1 +SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT = 2 +SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT = 3 +SQ_TT_TOKEN_EXCLUDE_WAVESTARTEND_SHIFT = 4 +SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT = 5 +SQ_TT_TOKEN_EXCLUDE_REG_SHIFT = 6 +SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT = 7 +SQ_TT_TOKEN_EXCLUDE_INST_SHIFT = 8 +SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT = 9 +SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT = 10 +SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT = 11 +SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_UTIL_TIMER' +SQ_TT_UTIL_TIMER__enumvalues = { + 0: 'SQ_TT_UTIL_TIMER_100_CLK', + 1: 'SQ_TT_UTIL_TIMER_250_CLK', +} +SQ_TT_UTIL_TIMER_100_CLK = 0 +SQ_TT_UTIL_TIMER_250_CLK = 1 +SQ_TT_UTIL_TIMER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WAVESTART_MODE' +SQ_TT_WAVESTART_MODE__enumvalues = { + 0: 'SQ_TT_WAVESTART_MODE_SHORT', + 1: 'SQ_TT_WAVESTART_MODE_ALLOC', + 2: 'SQ_TT_WAVESTART_MODE_PBB_ID', +} +SQ_TT_WAVESTART_MODE_SHORT = 0 +SQ_TT_WAVESTART_MODE_ALLOC = 1 +SQ_TT_WAVESTART_MODE_PBB_ID = 2 +SQ_TT_WAVESTART_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WTYPE_INCLUDE' +SQ_TT_WTYPE_INCLUDE__enumvalues = { + 1: 'SQ_TT_WTYPE_INCLUDE_PS_BIT', + 2: 'SQ_TT_WTYPE_INCLUDE_RSVD0_BIT', + 4: 'SQ_TT_WTYPE_INCLUDE_GS_BIT', + 8: 'SQ_TT_WTYPE_INCLUDE_RSVD1_BIT', + 16: 'SQ_TT_WTYPE_INCLUDE_HS_BIT', + 32: 'SQ_TT_WTYPE_INCLUDE_RSVD2_BIT', + 64: 'SQ_TT_WTYPE_INCLUDE_CS_BIT', +} +SQ_TT_WTYPE_INCLUDE_PS_BIT = 1 +SQ_TT_WTYPE_INCLUDE_RSVD0_BIT = 2 +SQ_TT_WTYPE_INCLUDE_GS_BIT = 4 +SQ_TT_WTYPE_INCLUDE_RSVD1_BIT = 8 +SQ_TT_WTYPE_INCLUDE_HS_BIT = 16 +SQ_TT_WTYPE_INCLUDE_RSVD2_BIT = 32 +SQ_TT_WTYPE_INCLUDE_CS_BIT = 64 +SQ_TT_WTYPE_INCLUDE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TT_WTYPE_INCLUDE_SHIFT' +SQ_TT_WTYPE_INCLUDE_SHIFT__enumvalues = { + 0: 'SQ_TT_WTYPE_INCLUDE_PS_SHIFT', + 1: 'SQ_TT_WTYPE_INCLUDE_RSVD0_SHIFT', + 2: 'SQ_TT_WTYPE_INCLUDE_GS_SHIFT', + 3: 'SQ_TT_WTYPE_INCLUDE_RSVD1_SHIFT', + 4: 'SQ_TT_WTYPE_INCLUDE_HS_SHIFT', + 5: 'SQ_TT_WTYPE_INCLUDE_RSVD2_SHIFT', + 6: 'SQ_TT_WTYPE_INCLUDE_CS_SHIFT', +} +SQ_TT_WTYPE_INCLUDE_PS_SHIFT = 0 +SQ_TT_WTYPE_INCLUDE_RSVD0_SHIFT = 1 +SQ_TT_WTYPE_INCLUDE_GS_SHIFT = 2 +SQ_TT_WTYPE_INCLUDE_RSVD1_SHIFT = 3 +SQ_TT_WTYPE_INCLUDE_HS_SHIFT = 4 +SQ_TT_WTYPE_INCLUDE_RSVD2_SHIFT = 5 +SQ_TT_WTYPE_INCLUDE_CS_SHIFT = 6 +SQ_TT_WTYPE_INCLUDE_SHIFT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WATCH_MODES' +SQ_WATCH_MODES__enumvalues = { + 0: 'SQ_WATCH_MODE_READ', + 1: 'SQ_WATCH_MODE_NONREAD', + 2: 'SQ_WATCH_MODE_ATOMIC', + 3: 'SQ_WATCH_MODE_ALL', +} +SQ_WATCH_MODE_READ = 0 +SQ_WATCH_MODE_NONREAD = 1 +SQ_WATCH_MODE_ATOMIC = 2 +SQ_WATCH_MODE_ALL = 3 +SQ_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_FWD_PROG_INTERVAL' +SQ_WAVE_FWD_PROG_INTERVAL__enumvalues = { + 0: 'SQ_WAVE_FWD_PROG_INTERVAL_NEVER', + 1: 'SQ_WAVE_FWD_PROG_INTERVAL_256', + 2: 'SQ_WAVE_FWD_PROG_INTERVAL_1024', + 3: 'SQ_WAVE_FWD_PROG_INTERVAL_4096', +} +SQ_WAVE_FWD_PROG_INTERVAL_NEVER = 0 +SQ_WAVE_FWD_PROG_INTERVAL_256 = 1 +SQ_WAVE_FWD_PROG_INTERVAL_1024 = 2 +SQ_WAVE_FWD_PROG_INTERVAL_4096 = 3 +SQ_WAVE_FWD_PROG_INTERVAL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_IB_ECC_ST' +SQ_WAVE_IB_ECC_ST__enumvalues = { + 0: 'SQ_WAVE_IB_ECC_CLEAN', + 1: 'SQ_WAVE_IB_ECC_ERR_CONTINUE', + 2: 'SQ_WAVE_IB_ECC_ERR_HALT', + 3: 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', +} +SQ_WAVE_IB_ECC_CLEAN = 0 +SQ_WAVE_IB_ECC_ERR_CONTINUE = 1 +SQ_WAVE_IB_ECC_ERR_HALT = 2 +SQ_WAVE_IB_ECC_WITH_ERR_MSG = 3 +SQ_WAVE_IB_ECC_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_SCHED_MODES' +SQ_WAVE_SCHED_MODES__enumvalues = { + 0: 'SQ_WAVE_SCHED_MODE_NORMAL', + 1: 'SQ_WAVE_SCHED_MODE_EXPERT', + 2: 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST', +} +SQ_WAVE_SCHED_MODE_NORMAL = 0 +SQ_WAVE_SCHED_MODE_EXPERT = 1 +SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST = 2 +SQ_WAVE_SCHED_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_TYPE' +SQ_WAVE_TYPE__enumvalues = { + 0: 'SQ_WAVE_TYPE_PS', + 1: 'SQ_WAVE_TYPE_RSVD0', + 2: 'SQ_WAVE_TYPE_GS', + 3: 'SQ_WAVE_TYPE_RSVD1', + 4: 'SQ_WAVE_TYPE_HS', + 5: 'SQ_WAVE_TYPE_RSVD2', + 6: 'SQ_WAVE_TYPE_CS', + 7: 'SQ_WAVE_TYPE_PS1', + 8: 'SQ_WAVE_TYPE_PS2', + 9: 'SQ_WAVE_TYPE_PS3', +} +SQ_WAVE_TYPE_PS = 0 +SQ_WAVE_TYPE_RSVD0 = 1 +SQ_WAVE_TYPE_GS = 2 +SQ_WAVE_TYPE_RSVD1 = 3 +SQ_WAVE_TYPE_HS = 4 +SQ_WAVE_TYPE_RSVD2 = 5 +SQ_WAVE_TYPE_CS = 6 +SQ_WAVE_TYPE_PS1 = 7 +SQ_WAVE_TYPE_PS2 = 8 +SQ_WAVE_TYPE_PS3 = 9 +SQ_WAVE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CSCNTL_TYPE' +CSCNTL_TYPE__enumvalues = { + 0: 'CSCNTL_TYPE_TG', + 1: 'CSCNTL_TYPE_STATE', + 2: 'CSCNTL_TYPE_EVENT', + 3: 'CSCNTL_TYPE_PRIVATE', +} +CSCNTL_TYPE_TG = 0 +CSCNTL_TYPE_STATE = 1 +CSCNTL_TYPE_EVENT = 2 +CSCNTL_TYPE_PRIVATE = 3 +CSCNTL_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CSDATA_TYPE' +CSDATA_TYPE__enumvalues = { + 0: 'CSDATA_TYPE_TG', + 1: 'CSDATA_TYPE_STATE', + 2: 'CSDATA_TYPE_EVENT', + 3: 'CSDATA_TYPE_PRIVATE', +} +CSDATA_TYPE_TG = 0 +CSDATA_TYPE_STATE = 1 +CSDATA_TYPE_EVENT = 2 +CSDATA_TYPE_PRIVATE = 3 +CSDATA_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GE1_PERFCOUNT_SELECT' +GE1_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge1_assembler_busy', + 1: 'ge1_assembler_stalled', + 2: 'ge1_dma_busy', + 3: 'ge1_dma_lat_bin_0', + 4: 'ge1_dma_lat_bin_1', + 5: 'ge1_dma_lat_bin_2', + 6: 'ge1_dma_lat_bin_3', + 7: 'ge1_dma_lat_bin_4', + 8: 'ge1_dma_lat_bin_5', + 9: 'ge1_dma_lat_bin_6', + 10: 'ge1_dma_lat_bin_7', + 11: 'ge1_dma_return_cl0', + 12: 'ge1_dma_return_cl1', + 13: 'ge1_dma_utcl1_consecutive_retry_event', + 14: 'ge1_dma_utcl1_request_event', + 15: 'ge1_dma_utcl1_retry_event', + 16: 'ge1_dma_utcl1_stall_event', + 17: 'ge1_dma_utcl1_stall_utcl2_event', + 18: 'ge1_dma_utcl1_translation_hit_event', + 19: 'ge1_dma_utcl1_translation_miss_event', + 20: 'ge1_assembler_dma_starved', + 21: 'ge1_rbiu_di_fifo_stalled_p0', + 22: 'ge1_rbiu_di_fifo_starved_p0', + 23: 'ge1_rbiu_dr_fifo_stalled_p0', + 24: 'ge1_rbiu_dr_fifo_starved_p0', + 25: 'ge1_sclk_reg_vld', + 26: 'ge1_stat_busy', + 27: 'ge1_stat_no_dma_busy', + 28: 'ge1_pipe0_to_pipe1', + 29: 'ge1_pipe1_to_pipe0', + 30: 'ge1_dma_return_size_cl0', + 31: 'ge1_dma_return_size_cl1', + 32: 'ge1_small_draws_one_instance', + 33: 'ge1_sclk_input_vld', + 34: 'ge1_prim_group_limit_hit', + 35: 'ge1_unopt_multi_instance_draws', + 36: 'ge1_rbiu_di_fifo_stalled_p1', + 37: 'ge1_rbiu_di_fifo_starved_p1', + 38: 'ge1_rbiu_dr_fifo_stalled_p1', + 39: 'ge1_rbiu_dr_fifo_starved_p1', +} +ge1_assembler_busy = 0 +ge1_assembler_stalled = 1 +ge1_dma_busy = 2 +ge1_dma_lat_bin_0 = 3 +ge1_dma_lat_bin_1 = 4 +ge1_dma_lat_bin_2 = 5 +ge1_dma_lat_bin_3 = 6 +ge1_dma_lat_bin_4 = 7 +ge1_dma_lat_bin_5 = 8 +ge1_dma_lat_bin_6 = 9 +ge1_dma_lat_bin_7 = 10 +ge1_dma_return_cl0 = 11 +ge1_dma_return_cl1 = 12 +ge1_dma_utcl1_consecutive_retry_event = 13 +ge1_dma_utcl1_request_event = 14 +ge1_dma_utcl1_retry_event = 15 +ge1_dma_utcl1_stall_event = 16 +ge1_dma_utcl1_stall_utcl2_event = 17 +ge1_dma_utcl1_translation_hit_event = 18 +ge1_dma_utcl1_translation_miss_event = 19 +ge1_assembler_dma_starved = 20 +ge1_rbiu_di_fifo_stalled_p0 = 21 +ge1_rbiu_di_fifo_starved_p0 = 22 +ge1_rbiu_dr_fifo_stalled_p0 = 23 +ge1_rbiu_dr_fifo_starved_p0 = 24 +ge1_sclk_reg_vld = 25 +ge1_stat_busy = 26 +ge1_stat_no_dma_busy = 27 +ge1_pipe0_to_pipe1 = 28 +ge1_pipe1_to_pipe0 = 29 +ge1_dma_return_size_cl0 = 30 +ge1_dma_return_size_cl1 = 31 +ge1_small_draws_one_instance = 32 +ge1_sclk_input_vld = 33 +ge1_prim_group_limit_hit = 34 +ge1_unopt_multi_instance_draws = 35 +ge1_rbiu_di_fifo_stalled_p1 = 36 +ge1_rbiu_di_fifo_starved_p1 = 37 +ge1_rbiu_dr_fifo_stalled_p1 = 38 +ge1_rbiu_dr_fifo_starved_p1 = 39 +GE1_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'GE2_DIST_PERFCOUNT_SELECT' +GE2_DIST_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge_dist_hs_done', + 1: 'ge_dist_hs_done_latency_se0', + 2: 'ge_dist_hs_done_latency_se1', + 3: 'ge_dist_hs_done_latency_se2', + 4: 'ge_dist_hs_done_latency_se3', + 5: 'ge_dist_hs_done_latency_se4', + 6: 'ge_dist_hs_done_latency_se5', + 7: 'ge_dist_hs_done_latency_se6', + 8: 'ge_dist_hs_done_latency_se7', + 9: 'ge_dist_inside_tf_bin_0', + 10: 'ge_dist_inside_tf_bin_1', + 11: 'ge_dist_inside_tf_bin_2', + 12: 'ge_dist_inside_tf_bin_3', + 13: 'ge_dist_inside_tf_bin_4', + 14: 'ge_dist_inside_tf_bin_5', + 15: 'ge_dist_inside_tf_bin_6', + 16: 'ge_dist_inside_tf_bin_7', + 17: 'ge_dist_inside_tf_bin_8', + 18: 'ge_dist_null_patch', + 19: 'ge_dist_sclk_core_vld', + 20: 'ge_dist_sclk_wd_te11_vld', + 21: 'ge_dist_tfreq_lat_bin_0', + 22: 'ge_dist_tfreq_lat_bin_1', + 23: 'ge_dist_tfreq_lat_bin_2', + 24: 'ge_dist_tfreq_lat_bin_3', + 25: 'ge_dist_tfreq_lat_bin_4', + 26: 'ge_dist_tfreq_lat_bin_5', + 27: 'ge_dist_tfreq_lat_bin_6', + 28: 'ge_dist_tfreq_lat_bin_7', + 29: 'ge_dist_tfreq_utcl1_consecutive_retry_event', + 30: 'ge_dist_tfreq_utcl1_request_event', + 31: 'ge_dist_tfreq_utcl1_retry_event', + 32: 'ge_dist_tfreq_utcl1_stall_event', + 33: 'ge_dist_tfreq_utcl1_stall_utcl2_event', + 34: 'ge_dist_tfreq_utcl1_translation_hit_event', + 35: 'ge_dist_tfreq_utcl1_translation_miss_event', + 36: 'ge_dist_vs_pc_stall', + 37: 'ge_dist_pc_feorder_fifo_full', + 38: 'ge_dist_pc_ge_manager_busy', + 39: 'ge_dist_pc_req_stall_se0', + 40: 'ge_dist_pc_req_stall_se1', + 41: 'ge_dist_pc_req_stall_se2', + 42: 'ge_dist_pc_req_stall_se3', + 43: 'ge_dist_pc_req_stall_se4', + 44: 'ge_dist_pc_req_stall_se5', + 45: 'ge_dist_pc_req_stall_se6', + 46: 'ge_dist_pc_req_stall_se7', + 47: 'ge_dist_pc_space_zero', + 48: 'ge_dist_sclk_input_vld', + 49: 'ge_dist_reserved', + 50: 'ge_dist_wd_te11_busy', + 51: 'ge_dist_te11_starved', + 52: 'ge_dist_switch_mode_stall', + 53: 'ge_all_tf_eq', + 54: 'ge_all_tf2', + 55: 'ge_all_tf3', + 56: 'ge_all_tf4', + 57: 'ge_all_tf5', + 58: 'ge_all_tf6', + 59: 'ge_se0_te11_starved_on_hs_done', + 60: 'ge_se1_te11_starved_on_hs_done', + 61: 'ge_se2_te11_starved_on_hs_done', + 62: 'ge_se3_te11_starved_on_hs_done', + 63: 'ge_se4_te11_starved_on_hs_done', + 64: 'ge_se5_te11_starved_on_hs_done', + 65: 'ge_se6_te11_starved_on_hs_done', + 66: 'ge_se7_te11_starved_on_hs_done', + 67: 'ge_dist_op_fifo_full_starve', + 68: 'ge_dist_hs_done_se0', + 69: 'ge_dist_hs_done_se1', + 70: 'ge_dist_hs_done_se2', + 71: 'ge_dist_hs_done_se3', + 72: 'ge_dist_hs_done_se4', + 73: 'ge_dist_hs_done_se5', + 74: 'ge_dist_hs_done_se6', + 75: 'ge_dist_hs_done_se7', + 76: 'ge_dist_hs_done_latency', + 77: 'ge_dist_distributer_busy', + 78: 'ge_tf_ret_data_stalling_hs_done', + 79: 'ge_num_of_no_dist_patches', + 80: 'ge_num_of_donut_dist_patches', + 81: 'ge_num_of_patch_dist_patches', + 82: 'ge_num_of_se_switches_due_to_patch_accum', + 83: 'ge_num_of_se_switches_due_to_donut', + 84: 'ge_num_of_se_switches_due_to_trap', + 85: 'ge_num_of_hs_alloc_events', + 86: 'ge_agm_gcr_req', + 87: 'ge_agm_gcr_tag_stall', + 88: 'ge_agm_gcr_crd_stall', + 89: 'ge_agm_gcr_stall', + 90: 'ge_agm_gcr_latency', + 91: 'ge_distclk_vld', +} +ge_dist_hs_done = 0 +ge_dist_hs_done_latency_se0 = 1 +ge_dist_hs_done_latency_se1 = 2 +ge_dist_hs_done_latency_se2 = 3 +ge_dist_hs_done_latency_se3 = 4 +ge_dist_hs_done_latency_se4 = 5 +ge_dist_hs_done_latency_se5 = 6 +ge_dist_hs_done_latency_se6 = 7 +ge_dist_hs_done_latency_se7 = 8 +ge_dist_inside_tf_bin_0 = 9 +ge_dist_inside_tf_bin_1 = 10 +ge_dist_inside_tf_bin_2 = 11 +ge_dist_inside_tf_bin_3 = 12 +ge_dist_inside_tf_bin_4 = 13 +ge_dist_inside_tf_bin_5 = 14 +ge_dist_inside_tf_bin_6 = 15 +ge_dist_inside_tf_bin_7 = 16 +ge_dist_inside_tf_bin_8 = 17 +ge_dist_null_patch = 18 +ge_dist_sclk_core_vld = 19 +ge_dist_sclk_wd_te11_vld = 20 +ge_dist_tfreq_lat_bin_0 = 21 +ge_dist_tfreq_lat_bin_1 = 22 +ge_dist_tfreq_lat_bin_2 = 23 +ge_dist_tfreq_lat_bin_3 = 24 +ge_dist_tfreq_lat_bin_4 = 25 +ge_dist_tfreq_lat_bin_5 = 26 +ge_dist_tfreq_lat_bin_6 = 27 +ge_dist_tfreq_lat_bin_7 = 28 +ge_dist_tfreq_utcl1_consecutive_retry_event = 29 +ge_dist_tfreq_utcl1_request_event = 30 +ge_dist_tfreq_utcl1_retry_event = 31 +ge_dist_tfreq_utcl1_stall_event = 32 +ge_dist_tfreq_utcl1_stall_utcl2_event = 33 +ge_dist_tfreq_utcl1_translation_hit_event = 34 +ge_dist_tfreq_utcl1_translation_miss_event = 35 +ge_dist_vs_pc_stall = 36 +ge_dist_pc_feorder_fifo_full = 37 +ge_dist_pc_ge_manager_busy = 38 +ge_dist_pc_req_stall_se0 = 39 +ge_dist_pc_req_stall_se1 = 40 +ge_dist_pc_req_stall_se2 = 41 +ge_dist_pc_req_stall_se3 = 42 +ge_dist_pc_req_stall_se4 = 43 +ge_dist_pc_req_stall_se5 = 44 +ge_dist_pc_req_stall_se6 = 45 +ge_dist_pc_req_stall_se7 = 46 +ge_dist_pc_space_zero = 47 +ge_dist_sclk_input_vld = 48 +ge_dist_reserved = 49 +ge_dist_wd_te11_busy = 50 +ge_dist_te11_starved = 51 +ge_dist_switch_mode_stall = 52 +ge_all_tf_eq = 53 +ge_all_tf2 = 54 +ge_all_tf3 = 55 +ge_all_tf4 = 56 +ge_all_tf5 = 57 +ge_all_tf6 = 58 +ge_se0_te11_starved_on_hs_done = 59 +ge_se1_te11_starved_on_hs_done = 60 +ge_se2_te11_starved_on_hs_done = 61 +ge_se3_te11_starved_on_hs_done = 62 +ge_se4_te11_starved_on_hs_done = 63 +ge_se5_te11_starved_on_hs_done = 64 +ge_se6_te11_starved_on_hs_done = 65 +ge_se7_te11_starved_on_hs_done = 66 +ge_dist_op_fifo_full_starve = 67 +ge_dist_hs_done_se0 = 68 +ge_dist_hs_done_se1 = 69 +ge_dist_hs_done_se2 = 70 +ge_dist_hs_done_se3 = 71 +ge_dist_hs_done_se4 = 72 +ge_dist_hs_done_se5 = 73 +ge_dist_hs_done_se6 = 74 +ge_dist_hs_done_se7 = 75 +ge_dist_hs_done_latency = 76 +ge_dist_distributer_busy = 77 +ge_tf_ret_data_stalling_hs_done = 78 +ge_num_of_no_dist_patches = 79 +ge_num_of_donut_dist_patches = 80 +ge_num_of_patch_dist_patches = 81 +ge_num_of_se_switches_due_to_patch_accum = 82 +ge_num_of_se_switches_due_to_donut = 83 +ge_num_of_se_switches_due_to_trap = 84 +ge_num_of_hs_alloc_events = 85 +ge_agm_gcr_req = 86 +ge_agm_gcr_tag_stall = 87 +ge_agm_gcr_crd_stall = 88 +ge_agm_gcr_stall = 89 +ge_agm_gcr_latency = 90 +ge_distclk_vld = 91 +GE2_DIST_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'GE2_SE_PERFCOUNT_SELECT' +GE2_SE_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge_se_ds_prims', + 1: 'ge_se_es_thread_groups', + 2: 'ge_se_esvert_stalled_gsprim', + 3: 'ge_se_hs_tfm_stall', + 4: 'ge_se_hs_tgs_active_high_water_mark', + 5: 'ge_se_hs_thread_groups', + 6: 'ge_se_reused_es_indices', + 7: 'ge_se_sclk_ngg_vld', + 8: 'ge_se_sclk_te11_vld', + 9: 'ge_se_spi_esvert_eov', + 10: 'ge_se_spi_esvert_stalled', + 11: 'ge_se_spi_esvert_starved_busy', + 12: 'ge_se_spi_esvert_valid', + 13: 'ge_se_spi_gsprim_cont', + 14: 'ge_se_spi_gsprim_eov', + 15: 'ge_se_spi_gsprim_stalled', + 16: 'ge_se_spi_gsprim_starved_busy', + 17: 'ge_se_spi_gsprim_valid', + 18: 'ge_se_spi_gssubgrp_is_event', + 19: 'ge_se_spi_gssubgrp_send', + 20: 'ge_se_spi_hsvert_eov', + 21: 'ge_se_spi_hsvert_stalled', + 22: 'ge_se_spi_hsvert_starved_busy', + 23: 'ge_se_spi_hsvert_valid', + 24: 'ge_se_spi_hswave_is_event', + 25: 'ge_se_spi_hswave_send', + 26: 'ge_se_spi_lsvert_eov', + 27: 'ge_se_spi_lsvert_stalled', + 28: 'ge_se_spi_lsvert_starved_busy', + 29: 'ge_se_spi_lsvert_valid', + 30: 'ge_se_spi_hsvert_fifo_full_stall', + 31: 'ge_se_spi_tgrp_fifo_stall', + 32: 'ge_spi_hsgrp_spi_stall', + 33: 'ge_se_spi_gssubgrp_event_window_active', + 34: 'ge_se_hs_input_stall', + 35: 'ge_se_sending_vert_or_prim', + 36: 'ge_se_sclk_input_vld', + 37: 'ge_spi_lswave_fifo_full_stall', + 38: 'ge_spi_hswave_fifo_full_stall', + 39: 'ge_hs_tif_stall', + 40: 'ge_csb_spi_bp', + 41: 'ge_ngg_starving_for_pc_grant', + 42: 'ge_pa0_csb_eop', + 43: 'ge_pa1_csb_eop', + 44: 'ge_ngg_starved_idle', + 45: 'ge_gsprim_send', + 46: 'ge_esvert_send', + 47: 'ge_ngg_starved_after_work', + 48: 'ge_ngg_subgrp_fifo_stall', + 49: 'ge_ngg_ord_id_req_stall', + 50: 'ge_ngg_indx_bus_stall', + 51: 'ge_hs_stall_tfmm_fifo_full', + 52: 'ge_gs_issue_rtr_stalled', + 53: 'ge_gsprim_stalled_esvert', + 54: 'ge_gsthread_stalled', + 55: 'ge_te11_stall_prim_funnel', + 56: 'ge_te11_stall_vert_funnel', + 57: 'ge_ngg_attr_grp_alloc', + 58: 'ge_ngg_attr_discard_alloc', + 59: 'ge_ngg_pc_space_not_avail', + 60: 'ge_ngg_agm_req_stall', + 61: 'ge_ngg_spi_esvert_partial_eov', + 62: 'ge_ngg_spi_gsprim_partial_eov', + 63: 'ge_spi_gsgrp_valid', + 64: 'ge_ngg_attr_grp_latency', + 65: 'ge_ngg_reuse_prim_limit_hit', + 66: 'ge_ngg_reuse_vert_limit_hit', + 67: 'ge_te11_con_stall', + 68: 'ge_te11_compactor_starved', + 69: 'ge_ngg_stall_tess_off_tess_on', + 70: 'ge_ngg_stall_tess_on_tess_off', +} +ge_se_ds_prims = 0 +ge_se_es_thread_groups = 1 +ge_se_esvert_stalled_gsprim = 2 +ge_se_hs_tfm_stall = 3 +ge_se_hs_tgs_active_high_water_mark = 4 +ge_se_hs_thread_groups = 5 +ge_se_reused_es_indices = 6 +ge_se_sclk_ngg_vld = 7 +ge_se_sclk_te11_vld = 8 +ge_se_spi_esvert_eov = 9 +ge_se_spi_esvert_stalled = 10 +ge_se_spi_esvert_starved_busy = 11 +ge_se_spi_esvert_valid = 12 +ge_se_spi_gsprim_cont = 13 +ge_se_spi_gsprim_eov = 14 +ge_se_spi_gsprim_stalled = 15 +ge_se_spi_gsprim_starved_busy = 16 +ge_se_spi_gsprim_valid = 17 +ge_se_spi_gssubgrp_is_event = 18 +ge_se_spi_gssubgrp_send = 19 +ge_se_spi_hsvert_eov = 20 +ge_se_spi_hsvert_stalled = 21 +ge_se_spi_hsvert_starved_busy = 22 +ge_se_spi_hsvert_valid = 23 +ge_se_spi_hswave_is_event = 24 +ge_se_spi_hswave_send = 25 +ge_se_spi_lsvert_eov = 26 +ge_se_spi_lsvert_stalled = 27 +ge_se_spi_lsvert_starved_busy = 28 +ge_se_spi_lsvert_valid = 29 +ge_se_spi_hsvert_fifo_full_stall = 30 +ge_se_spi_tgrp_fifo_stall = 31 +ge_spi_hsgrp_spi_stall = 32 +ge_se_spi_gssubgrp_event_window_active = 33 +ge_se_hs_input_stall = 34 +ge_se_sending_vert_or_prim = 35 +ge_se_sclk_input_vld = 36 +ge_spi_lswave_fifo_full_stall = 37 +ge_spi_hswave_fifo_full_stall = 38 +ge_hs_tif_stall = 39 +ge_csb_spi_bp = 40 +ge_ngg_starving_for_pc_grant = 41 +ge_pa0_csb_eop = 42 +ge_pa1_csb_eop = 43 +ge_ngg_starved_idle = 44 +ge_gsprim_send = 45 +ge_esvert_send = 46 +ge_ngg_starved_after_work = 47 +ge_ngg_subgrp_fifo_stall = 48 +ge_ngg_ord_id_req_stall = 49 +ge_ngg_indx_bus_stall = 50 +ge_hs_stall_tfmm_fifo_full = 51 +ge_gs_issue_rtr_stalled = 52 +ge_gsprim_stalled_esvert = 53 +ge_gsthread_stalled = 54 +ge_te11_stall_prim_funnel = 55 +ge_te11_stall_vert_funnel = 56 +ge_ngg_attr_grp_alloc = 57 +ge_ngg_attr_discard_alloc = 58 +ge_ngg_pc_space_not_avail = 59 +ge_ngg_agm_req_stall = 60 +ge_ngg_spi_esvert_partial_eov = 61 +ge_ngg_spi_gsprim_partial_eov = 62 +ge_spi_gsgrp_valid = 63 +ge_ngg_attr_grp_latency = 64 +ge_ngg_reuse_prim_limit_hit = 65 +ge_ngg_reuse_vert_limit_hit = 66 +ge_te11_con_stall = 67 +ge_te11_compactor_starved = 68 +ge_ngg_stall_tess_off_tess_on = 69 +ge_ngg_stall_tess_on_tess_off = 70 +GE2_SE_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ONE' +VGT_DETECT_ONE__enumvalues = { + 0: 'ENABLE_TF1_OPT', + 1: 'DISABLE_TF1_OPT', +} +ENABLE_TF1_OPT = 0 +DISABLE_TF1_OPT = 1 +VGT_DETECT_ONE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ZERO' +VGT_DETECT_ZERO__enumvalues = { + 0: 'ENABLE_TF0_OPT', + 1: 'DISABLE_TF0_OPT', +} +ENABLE_TF0_OPT = 0 +DISABLE_TF0_OPT = 1 +VGT_DETECT_ZERO = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DIST_MODE' +VGT_DIST_MODE__enumvalues = { + 0: 'NO_DIST', + 1: 'PATCHES', + 2: 'DONUTS', + 3: 'TRAPEZOIDS', +} +NO_DIST = 0 +PATCHES = 1 +DONUTS = 2 +TRAPEZOIDS = 3 +VGT_DIST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_INDEX_SIZE' +VGT_DI_INDEX_SIZE__enumvalues = { + 0: 'DI_INDEX_SIZE_16_BIT', + 1: 'DI_INDEX_SIZE_32_BIT', + 2: 'DI_INDEX_SIZE_8_BIT', +} +DI_INDEX_SIZE_16_BIT = 0 +DI_INDEX_SIZE_32_BIT = 1 +DI_INDEX_SIZE_8_BIT = 2 +VGT_DI_INDEX_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_MAJOR_MODE_SELECT' +VGT_DI_MAJOR_MODE_SELECT__enumvalues = { + 0: 'DI_MAJOR_MODE_0', + 1: 'DI_MAJOR_MODE_1', +} +DI_MAJOR_MODE_0 = 0 +DI_MAJOR_MODE_1 = 1 +VGT_DI_MAJOR_MODE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_PRIM_TYPE' +VGT_DI_PRIM_TYPE__enumvalues = { + 0: 'DI_PT_NONE', + 1: 'DI_PT_POINTLIST', + 2: 'DI_PT_LINELIST', + 3: 'DI_PT_LINESTRIP', + 4: 'DI_PT_TRILIST', + 5: 'DI_PT_TRIFAN', + 6: 'DI_PT_TRISTRIP', + 7: 'DI_PT_2D_RECTANGLE', + 8: 'DI_PT_UNUSED_1', + 9: 'DI_PT_PATCH', + 10: 'DI_PT_LINELIST_ADJ', + 11: 'DI_PT_LINESTRIP_ADJ', + 12: 'DI_PT_TRILIST_ADJ', + 13: 'DI_PT_TRISTRIP_ADJ', + 14: 'DI_PT_UNUSED_3', + 15: 'DI_PT_UNUSED_4', + 16: 'DI_PT_UNUSED_5', + 17: 'DI_PT_RECTLIST', + 18: 'DI_PT_LINELOOP', + 19: 'DI_PT_QUADLIST', + 20: 'DI_PT_QUADSTRIP', + 21: 'DI_PT_POLYGON', +} +DI_PT_NONE = 0 +DI_PT_POINTLIST = 1 +DI_PT_LINELIST = 2 +DI_PT_LINESTRIP = 3 +DI_PT_TRILIST = 4 +DI_PT_TRIFAN = 5 +DI_PT_TRISTRIP = 6 +DI_PT_2D_RECTANGLE = 7 +DI_PT_UNUSED_1 = 8 +DI_PT_PATCH = 9 +DI_PT_LINELIST_ADJ = 10 +DI_PT_LINESTRIP_ADJ = 11 +DI_PT_TRILIST_ADJ = 12 +DI_PT_TRISTRIP_ADJ = 13 +DI_PT_UNUSED_3 = 14 +DI_PT_UNUSED_4 = 15 +DI_PT_UNUSED_5 = 16 +DI_PT_RECTLIST = 17 +DI_PT_LINELOOP = 18 +DI_PT_QUADLIST = 19 +DI_PT_QUADSTRIP = 20 +DI_PT_POLYGON = 21 +VGT_DI_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_SOURCE_SELECT' +VGT_DI_SOURCE_SELECT__enumvalues = { + 0: 'DI_SRC_SEL_DMA', + 1: 'DI_SRC_SEL_IMMEDIATE', + 2: 'DI_SRC_SEL_AUTO_INDEX', + 3: 'DI_SRC_SEL_RESERVED', +} +DI_SRC_SEL_DMA = 0 +DI_SRC_SEL_IMMEDIATE = 1 +DI_SRC_SEL_AUTO_INDEX = 2 +DI_SRC_SEL_RESERVED = 3 +VGT_DI_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_BUF_TYPE' +VGT_DMA_BUF_TYPE__enumvalues = { + 0: 'VGT_DMA_BUF_MEM', + 1: 'VGT_DMA_BUF_RING', + 2: 'VGT_DMA_BUF_SETUP', + 3: 'VGT_DMA_PTR_UPDATE', +} +VGT_DMA_BUF_MEM = 0 +VGT_DMA_BUF_RING = 1 +VGT_DMA_BUF_SETUP = 2 +VGT_DMA_PTR_UPDATE = 3 +VGT_DMA_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_SWAP_MODE' +VGT_DMA_SWAP_MODE__enumvalues = { + 0: 'VGT_DMA_SWAP_NONE', + 1: 'VGT_DMA_SWAP_16_BIT', + 2: 'VGT_DMA_SWAP_32_BIT', + 3: 'VGT_DMA_SWAP_WORD', +} +VGT_DMA_SWAP_NONE = 0 +VGT_DMA_SWAP_16_BIT = 1 +VGT_DMA_SWAP_32_BIT = 2 +VGT_DMA_SWAP_WORD = 3 +VGT_DMA_SWAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_EVENT_TYPE' +VGT_EVENT_TYPE__enumvalues = { + 0: 'Reserved_0x00', + 1: 'SAMPLE_STREAMOUTSTATS1', + 2: 'SAMPLE_STREAMOUTSTATS2', + 3: 'SAMPLE_STREAMOUTSTATS3', + 4: 'CACHE_FLUSH_TS', + 5: 'CONTEXT_DONE', + 6: 'CACHE_FLUSH', + 7: 'CS_PARTIAL_FLUSH', + 8: 'VGT_STREAMOUT_SYNC', + 9: 'Reserved_0x09', + 10: 'VGT_STREAMOUT_RESET', + 11: 'END_OF_PIPE_INCR_DE', + 12: 'END_OF_PIPE_IB_END', + 13: 'RST_PIX_CNT', + 14: 'BREAK_BATCH', + 15: 'VS_PARTIAL_FLUSH', + 16: 'PS_PARTIAL_FLUSH', + 17: 'FLUSH_HS_OUTPUT', + 18: 'FLUSH_DFSM', + 19: 'RESET_TO_LOWEST_VGT', + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', + 21: 'WAIT_SYNC', + 22: 'CACHE_FLUSH_AND_INV_EVENT', + 23: 'PERFCOUNTER_START', + 24: 'PERFCOUNTER_STOP', + 25: 'PIPELINESTAT_START', + 26: 'PIPELINESTAT_STOP', + 27: 'PERFCOUNTER_SAMPLE', + 28: 'FLUSH_ES_OUTPUT', + 29: 'BIN_CONF_OVERRIDE_CHECK', + 30: 'SAMPLE_PIPELINESTAT', + 31: 'SO_VGTSTREAMOUT_FLUSH', + 32: 'SAMPLE_STREAMOUTSTATS', + 33: 'RESET_VTX_CNT', + 34: 'BLOCK_CONTEXT_DONE', + 35: 'CS_CONTEXT_DONE', + 36: 'VGT_FLUSH', + 37: 'TGID_ROLLOVER', + 38: 'SQ_NON_EVENT', + 39: 'SC_SEND_DB_VPZ', + 40: 'BOTTOM_OF_PIPE_TS', + 41: 'FLUSH_SX_TS', + 42: 'DB_CACHE_FLUSH_AND_INV', + 43: 'FLUSH_AND_INV_DB_DATA_TS', + 44: 'FLUSH_AND_INV_DB_META', + 45: 'FLUSH_AND_INV_CB_DATA_TS', + 46: 'FLUSH_AND_INV_CB_META', + 47: 'CS_DONE', + 48: 'PS_DONE', + 49: 'FLUSH_AND_INV_CB_PIXEL_DATA', + 50: 'SX_CB_RAT_ACK_REQUEST', + 51: 'THREAD_TRACE_START', + 52: 'THREAD_TRACE_STOP', + 53: 'THREAD_TRACE_MARKER', + 54: 'THREAD_TRACE_DRAW', + 55: 'THREAD_TRACE_FINISH', + 56: 'PIXEL_PIPE_STAT_CONTROL', + 57: 'PIXEL_PIPE_STAT_DUMP', + 58: 'PIXEL_PIPE_STAT_RESET', + 59: 'CONTEXT_SUSPEND', + 60: 'OFFCHIP_HS_DEALLOC', + 61: 'ENABLE_NGG_PIPELINE', + 62: 'ENABLE_LEGACY_PIPELINE', + 63: 'DRAW_DONE', +} +Reserved_0x00 = 0 +SAMPLE_STREAMOUTSTATS1 = 1 +SAMPLE_STREAMOUTSTATS2 = 2 +SAMPLE_STREAMOUTSTATS3 = 3 +CACHE_FLUSH_TS = 4 +CONTEXT_DONE = 5 +CACHE_FLUSH = 6 +CS_PARTIAL_FLUSH = 7 +VGT_STREAMOUT_SYNC = 8 +Reserved_0x09 = 9 +VGT_STREAMOUT_RESET = 10 +END_OF_PIPE_INCR_DE = 11 +END_OF_PIPE_IB_END = 12 +RST_PIX_CNT = 13 +BREAK_BATCH = 14 +VS_PARTIAL_FLUSH = 15 +PS_PARTIAL_FLUSH = 16 +FLUSH_HS_OUTPUT = 17 +FLUSH_DFSM = 18 +RESET_TO_LOWEST_VGT = 19 +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +WAIT_SYNC = 21 +CACHE_FLUSH_AND_INV_EVENT = 22 +PERFCOUNTER_START = 23 +PERFCOUNTER_STOP = 24 +PIPELINESTAT_START = 25 +PIPELINESTAT_STOP = 26 +PERFCOUNTER_SAMPLE = 27 +FLUSH_ES_OUTPUT = 28 +BIN_CONF_OVERRIDE_CHECK = 29 +SAMPLE_PIPELINESTAT = 30 +SO_VGTSTREAMOUT_FLUSH = 31 +SAMPLE_STREAMOUTSTATS = 32 +RESET_VTX_CNT = 33 +BLOCK_CONTEXT_DONE = 34 +CS_CONTEXT_DONE = 35 +VGT_FLUSH = 36 +TGID_ROLLOVER = 37 +SQ_NON_EVENT = 38 +SC_SEND_DB_VPZ = 39 +BOTTOM_OF_PIPE_TS = 40 +FLUSH_SX_TS = 41 +DB_CACHE_FLUSH_AND_INV = 42 +FLUSH_AND_INV_DB_DATA_TS = 43 +FLUSH_AND_INV_DB_META = 44 +FLUSH_AND_INV_CB_DATA_TS = 45 +FLUSH_AND_INV_CB_META = 46 +CS_DONE = 47 +PS_DONE = 48 +FLUSH_AND_INV_CB_PIXEL_DATA = 49 +SX_CB_RAT_ACK_REQUEST = 50 +THREAD_TRACE_START = 51 +THREAD_TRACE_STOP = 52 +THREAD_TRACE_MARKER = 53 +THREAD_TRACE_DRAW = 54 +THREAD_TRACE_FINISH = 55 +PIXEL_PIPE_STAT_CONTROL = 56 +PIXEL_PIPE_STAT_DUMP = 57 +PIXEL_PIPE_STAT_RESET = 58 +CONTEXT_SUSPEND = 59 +OFFCHIP_HS_DEALLOC = 60 +ENABLE_NGG_PIPELINE = 61 +ENABLE_LEGACY_PIPELINE = 62 +DRAW_DONE = 63 +VGT_EVENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GROUP_CONV_SEL' +VGT_GROUP_CONV_SEL__enumvalues = { + 0: 'VGT_GRP_INDEX_16', + 1: 'VGT_GRP_INDEX_32', + 2: 'VGT_GRP_UINT_16', + 3: 'VGT_GRP_UINT_32', + 4: 'VGT_GRP_SINT_16', + 5: 'VGT_GRP_SINT_32', + 6: 'VGT_GRP_FLOAT_32', + 7: 'VGT_GRP_AUTO_PRIM', + 8: 'VGT_GRP_FIX_1_23_TO_FLOAT', +} +VGT_GRP_INDEX_16 = 0 +VGT_GRP_INDEX_32 = 1 +VGT_GRP_UINT_16 = 2 +VGT_GRP_UINT_32 = 3 +VGT_GRP_SINT_16 = 4 +VGT_GRP_SINT_32 = 5 +VGT_GRP_FLOAT_32 = 6 +VGT_GRP_AUTO_PRIM = 7 +VGT_GRP_FIX_1_23_TO_FLOAT = 8 +VGT_GROUP_CONV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_MODE_TYPE' +VGT_GS_MODE_TYPE__enumvalues = { + 0: 'GS_OFF', + 1: 'GS_SCENARIO_A', + 2: 'GS_SCENARIO_B', + 3: 'GS_SCENARIO_G', + 4: 'GS_SCENARIO_C', + 5: 'SPRITE_EN', +} +GS_OFF = 0 +GS_SCENARIO_A = 1 +GS_SCENARIO_B = 2 +GS_SCENARIO_G = 3 +GS_SCENARIO_C = 4 +SPRITE_EN = 5 +VGT_GS_MODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_OUTPRIM_TYPE' +VGT_GS_OUTPRIM_TYPE__enumvalues = { + 0: 'POINTLIST', + 1: 'LINESTRIP', + 2: 'TRISTRIP', + 3: 'RECT_2D', + 4: 'RECTLIST', +} +POINTLIST = 0 +LINESTRIP = 1 +TRISTRIP = 2 +RECT_2D = 3 +RECTLIST = 4 +VGT_GS_OUTPRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_INDEX_TYPE_MODE' +VGT_INDEX_TYPE_MODE__enumvalues = { + 0: 'VGT_INDEX_16', + 1: 'VGT_INDEX_32', + 2: 'VGT_INDEX_8', +} +VGT_INDEX_16 = 0 +VGT_INDEX_32 = 1 +VGT_INDEX_8 = 2 +VGT_INDEX_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUTPATH_SELECT' +VGT_OUTPATH_SELECT__enumvalues = { + 0: 'VGT_OUTPATH_VTX_REUSE', + 1: 'VGT_OUTPATH_GS_BLOCK', + 2: 'VGT_OUTPATH_HS_BLOCK', + 3: 'VGT_OUTPATH_PRIM_GEN', + 4: 'VGT_OUTPATH_TE_PRIM_GEN', + 5: 'VGT_OUTPATH_TE_GS_BLOCK', + 6: 'VGT_OUTPATH_TE_OUTPUT', +} +VGT_OUTPATH_VTX_REUSE = 0 +VGT_OUTPATH_GS_BLOCK = 1 +VGT_OUTPATH_HS_BLOCK = 2 +VGT_OUTPATH_PRIM_GEN = 3 +VGT_OUTPATH_TE_PRIM_GEN = 4 +VGT_OUTPATH_TE_GS_BLOCK = 5 +VGT_OUTPATH_TE_OUTPUT = 6 +VGT_OUTPATH_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUT_PRIM_TYPE' +VGT_OUT_PRIM_TYPE__enumvalues = { + 0: 'VGT_OUT_POINT', + 1: 'VGT_OUT_LINE', + 2: 'VGT_OUT_TRI', + 3: 'VGT_OUT_RECT_V0', + 4: 'VGT_OUT_RECT_V1', + 5: 'VGT_OUT_RECT_V2', + 6: 'VGT_OUT_RECT_V3', + 7: 'VGT_OUT_2D_RECT', + 8: 'VGT_TE_QUAD', + 9: 'VGT_TE_PRIM_INDEX_LINE', + 10: 'VGT_TE_PRIM_INDEX_TRI', + 11: 'VGT_TE_PRIM_INDEX_QUAD', + 12: 'VGT_OUT_LINE_ADJ', + 13: 'VGT_OUT_TRI_ADJ', + 14: 'VGT_OUT_PATCH', +} +VGT_OUT_POINT = 0 +VGT_OUT_LINE = 1 +VGT_OUT_TRI = 2 +VGT_OUT_RECT_V0 = 3 +VGT_OUT_RECT_V1 = 4 +VGT_OUT_RECT_V2 = 5 +VGT_OUT_RECT_V3 = 6 +VGT_OUT_2D_RECT = 7 +VGT_TE_QUAD = 8 +VGT_TE_PRIM_INDEX_LINE = 9 +VGT_TE_PRIM_INDEX_TRI = 10 +VGT_TE_PRIM_INDEX_QUAD = 11 +VGT_OUT_LINE_ADJ = 12 +VGT_OUT_TRI_ADJ = 13 +VGT_OUT_PATCH = 14 +VGT_OUT_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_RDREQ_POLICY' +VGT_RDREQ_POLICY__enumvalues = { + 0: 'VGT_POLICY_LRU', + 1: 'VGT_POLICY_STREAM', + 2: 'VGT_POLICY_BYPASS', +} +VGT_POLICY_LRU = 0 +VGT_POLICY_STREAM = 1 +VGT_POLICY_BYPASS = 2 +VGT_RDREQ_POLICY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_ES_EN' +VGT_STAGES_ES_EN__enumvalues = { + 0: 'ES_STAGE_OFF', + 1: 'ES_STAGE_DS', + 2: 'ES_STAGE_REAL', + 3: 'RESERVED_ES', +} +ES_STAGE_OFF = 0 +ES_STAGE_DS = 1 +ES_STAGE_REAL = 2 +RESERVED_ES = 3 +VGT_STAGES_ES_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_GS_EN' +VGT_STAGES_GS_EN__enumvalues = { + 0: 'GS_STAGE_OFF', + 1: 'GS_STAGE_ON', +} +GS_STAGE_OFF = 0 +GS_STAGE_ON = 1 +VGT_STAGES_GS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_HS_EN' +VGT_STAGES_HS_EN__enumvalues = { + 0: 'HS_STAGE_OFF', + 1: 'HS_STAGE_ON', +} +HS_STAGE_OFF = 0 +HS_STAGE_ON = 1 +VGT_STAGES_HS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_LS_EN' +VGT_STAGES_LS_EN__enumvalues = { + 0: 'LS_STAGE_OFF', + 1: 'LS_STAGE_ON', + 2: 'CS_STAGE_ON', + 3: 'RESERVED_LS', +} +LS_STAGE_OFF = 0 +LS_STAGE_ON = 1 +CS_STAGE_ON = 2 +RESERVED_LS = 3 +VGT_STAGES_LS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_VS_EN' +VGT_STAGES_VS_EN__enumvalues = { + 0: 'VS_STAGE_REAL', + 1: 'VS_STAGE_DS', + 2: 'VS_STAGE_COPY_SHADER', + 3: 'RESERVED_VS', +} +VS_STAGE_REAL = 0 +VS_STAGE_DS = 1 +VS_STAGE_COPY_SHADER = 2 +RESERVED_VS = 3 +VGT_STAGES_VS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_PARTITION' +VGT_TESS_PARTITION__enumvalues = { + 0: 'PART_INTEGER', + 1: 'PART_POW2', + 2: 'PART_FRAC_ODD', + 3: 'PART_FRAC_EVEN', +} +PART_INTEGER = 0 +PART_POW2 = 1 +PART_FRAC_ODD = 2 +PART_FRAC_EVEN = 3 +VGT_TESS_PARTITION = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TOPOLOGY' +VGT_TESS_TOPOLOGY__enumvalues = { + 0: 'OUTPUT_POINT', + 1: 'OUTPUT_LINE', + 2: 'OUTPUT_TRIANGLE_CW', + 3: 'OUTPUT_TRIANGLE_CCW', +} +OUTPUT_POINT = 0 +OUTPUT_LINE = 1 +OUTPUT_TRIANGLE_CW = 2 +OUTPUT_TRIANGLE_CCW = 3 +VGT_TESS_TOPOLOGY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TYPE' +VGT_TESS_TYPE__enumvalues = { + 0: 'TESS_ISOLINE', + 1: 'TESS_TRIANGLE', + 2: 'TESS_QUAD', +} +TESS_ISOLINE = 0 +TESS_TRIANGLE = 1 +TESS_QUAD = 2 +VGT_TESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_REG_XFER' +WD_IA_DRAW_REG_XFER__enumvalues = { + 0: 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 1: 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 2: 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 3: 'WD_IA_DRAW_REG_XFER_GE_CNTL', + 4: 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN', + 5: 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM', + 6: 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1', + 7: 'WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE', + 8: 'WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC', +} +WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM = 0 +WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN = 1 +WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID = 2 +WD_IA_DRAW_REG_XFER_GE_CNTL = 3 +WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN = 4 +WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM = 5 +WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1 = 6 +WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE = 7 +WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC = 8 +WD_IA_DRAW_REG_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_SOURCE' +WD_IA_DRAW_SOURCE__enumvalues = { + 0: 'WD_IA_DRAW_SOURCE_DMA', + 1: 'WD_IA_DRAW_SOURCE_IMMD', + 2: 'WD_IA_DRAW_SOURCE_AUTO', + 3: 'WD_IA_DRAW_SOURCE_OPAQ', +} +WD_IA_DRAW_SOURCE_DMA = 0 +WD_IA_DRAW_SOURCE_IMMD = 1 +WD_IA_DRAW_SOURCE_AUTO = 2 +WD_IA_DRAW_SOURCE_OPAQ = 3 +WD_IA_DRAW_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_TYPE' +WD_IA_DRAW_TYPE__enumvalues = { + 0: 'WD_IA_DRAW_TYPE_DI_MM0', + 1: 'WD_IA_DRAW_TYPE_REG_XFER', + 2: 'WD_IA_DRAW_TYPE_EVENT_INIT', + 3: 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 4: 'WD_IA_DRAW_TYPE_MIN_INDX', + 5: 'WD_IA_DRAW_TYPE_MAX_INDX', + 6: 'WD_IA_DRAW_TYPE_INDX_OFF', + 7: 'WD_IA_DRAW_TYPE_IMM_DATA', +} +WD_IA_DRAW_TYPE_DI_MM0 = 0 +WD_IA_DRAW_TYPE_REG_XFER = 1 +WD_IA_DRAW_TYPE_EVENT_INIT = 2 +WD_IA_DRAW_TYPE_EVENT_ADDR = 3 +WD_IA_DRAW_TYPE_MIN_INDX = 4 +WD_IA_DRAW_TYPE_MAX_INDX = 5 +WD_IA_DRAW_TYPE_INDX_OFF = 6 +WD_IA_DRAW_TYPE_IMM_DATA = 7 +WD_IA_DRAW_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GB_EDC_DED_MODE' +GB_EDC_DED_MODE__enumvalues = { + 0: 'GB_EDC_DED_MODE_LOG', + 1: 'GB_EDC_DED_MODE_HALT', + 2: 'GB_EDC_DED_MODE_INT_HALT', +} +GB_EDC_DED_MODE_LOG = 0 +GB_EDC_DED_MODE_HALT = 1 +GB_EDC_DED_MODE_INT_HALT = 2 +GB_EDC_DED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CHA_PERF_SEL' +CHA_PERF_SEL__enumvalues = { + 0: 'CHA_PERF_SEL_BUSY', + 1: 'CHA_PERF_SEL_STALL_CHC0', + 2: 'CHA_PERF_SEL_STALL_CHC1', + 3: 'CHA_PERF_SEL_STALL_CHC2', + 4: 'CHA_PERF_SEL_STALL_CHC3', + 5: 'CHA_PERF_SEL_STALL_CHC4', + 6: 'CHA_PERF_SEL_STALL_CHC5', + 7: 'CHA_PERF_SEL_REQUEST_CHC0', + 8: 'CHA_PERF_SEL_REQUEST_CHC1', + 9: 'CHA_PERF_SEL_REQUEST_CHC2', + 10: 'CHA_PERF_SEL_REQUEST_CHC3', + 11: 'CHA_PERF_SEL_REQUEST_CHC4', + 12: 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', + 13: 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 14: 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', + 15: 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 16: 'CHA_PERF_SEL_MEM_32B_WDS_CHC4', + 17: 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 18: 'CHA_PERF_SEL_IO_32B_WDS_CHC1', + 19: 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 20: 'CHA_PERF_SEL_IO_32B_WDS_CHC3', + 21: 'CHA_PERF_SEL_IO_32B_WDS_CHC4', + 22: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 23: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 24: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 25: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', + 26: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC4', + 27: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 28: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 29: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 30: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 31: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC4', + 32: 'CHA_PERF_SEL_ARB_REQUESTS', + 33: 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 34: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 35: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 36: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 37: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', + 38: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4', + 39: 'CHA_PERF_SEL_CYCLE', +} +CHA_PERF_SEL_BUSY = 0 +CHA_PERF_SEL_STALL_CHC0 = 1 +CHA_PERF_SEL_STALL_CHC1 = 2 +CHA_PERF_SEL_STALL_CHC2 = 3 +CHA_PERF_SEL_STALL_CHC3 = 4 +CHA_PERF_SEL_STALL_CHC4 = 5 +CHA_PERF_SEL_STALL_CHC5 = 6 +CHA_PERF_SEL_REQUEST_CHC0 = 7 +CHA_PERF_SEL_REQUEST_CHC1 = 8 +CHA_PERF_SEL_REQUEST_CHC2 = 9 +CHA_PERF_SEL_REQUEST_CHC3 = 10 +CHA_PERF_SEL_REQUEST_CHC4 = 11 +CHA_PERF_SEL_MEM_32B_WDS_CHC0 = 12 +CHA_PERF_SEL_MEM_32B_WDS_CHC1 = 13 +CHA_PERF_SEL_MEM_32B_WDS_CHC2 = 14 +CHA_PERF_SEL_MEM_32B_WDS_CHC3 = 15 +CHA_PERF_SEL_MEM_32B_WDS_CHC4 = 16 +CHA_PERF_SEL_IO_32B_WDS_CHC0 = 17 +CHA_PERF_SEL_IO_32B_WDS_CHC1 = 18 +CHA_PERF_SEL_IO_32B_WDS_CHC2 = 19 +CHA_PERF_SEL_IO_32B_WDS_CHC3 = 20 +CHA_PERF_SEL_IO_32B_WDS_CHC4 = 21 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC0 = 22 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC1 = 23 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC2 = 24 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC3 = 25 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC4 = 26 +CHA_PERF_SEL_IO_BURST_COUNT_CHC0 = 27 +CHA_PERF_SEL_IO_BURST_COUNT_CHC1 = 28 +CHA_PERF_SEL_IO_BURST_COUNT_CHC2 = 29 +CHA_PERF_SEL_IO_BURST_COUNT_CHC3 = 30 +CHA_PERF_SEL_IO_BURST_COUNT_CHC4 = 31 +CHA_PERF_SEL_ARB_REQUESTS = 32 +CHA_PERF_SEL_REQ_INFLIGHT_LEVEL = 33 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0 = 34 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1 = 35 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2 = 36 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3 = 37 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4 = 38 +CHA_PERF_SEL_CYCLE = 39 +CHA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CHCG_PERF_SEL' +CHCG_PERF_SEL__enumvalues = { + 0: 'CHCG_PERF_SEL_CYCLE', + 1: 'CHCG_PERF_SEL_BUSY', + 2: 'CHCG_PERF_SEL_STARVE', + 3: 'CHCG_PERF_SEL_ARB_RET_LEVEL', + 4: 'CHCG_PERF_SEL_GL2_REQ_READ_LATENCY', + 5: 'CHCG_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 6: 'CHCG_PERF_SEL_REQ', + 7: 'CHCG_PERF_SEL_REQ_ATOMIC_WITH_RET', + 8: 'CHCG_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 9: 'CHCG_PERF_SEL_REQ_NOP_ACK', + 10: 'CHCG_PERF_SEL_REQ_NOP_RTN0', + 11: 'CHCG_PERF_SEL_REQ_READ', + 12: 'CHCG_PERF_SEL_REQ_READ_128B', + 13: 'CHCG_PERF_SEL_REQ_READ_32B', + 14: 'CHCG_PERF_SEL_REQ_READ_64B', + 15: 'CHCG_PERF_SEL_REQ_WRITE', + 16: 'CHCG_PERF_SEL_REQ_WRITE_32B', + 17: 'CHCG_PERF_SEL_REQ_WRITE_64B', + 18: 'CHCG_PERF_SEL_STALL_GUS_GL1', + 19: 'CHCG_PERF_SEL_STALL_BUFFER_FULL', + 20: 'CHCG_PERF_SEL_REQ_CLIENT0', + 21: 'CHCG_PERF_SEL_REQ_CLIENT1', + 22: 'CHCG_PERF_SEL_REQ_CLIENT2', + 23: 'CHCG_PERF_SEL_REQ_CLIENT3', + 24: 'CHCG_PERF_SEL_REQ_CLIENT4', + 25: 'CHCG_PERF_SEL_REQ_CLIENT5', + 26: 'CHCG_PERF_SEL_REQ_CLIENT6', + 27: 'CHCG_PERF_SEL_REQ_CLIENT7', + 28: 'CHCG_PERF_SEL_REQ_CLIENT8', + 29: 'CHCG_PERF_SEL_REQ_CLIENT9', + 30: 'CHCG_PERF_SEL_REQ_CLIENT10', + 31: 'CHCG_PERF_SEL_REQ_CLIENT11', + 32: 'CHCG_PERF_SEL_REQ_CLIENT12', + 33: 'CHCG_PERF_SEL_REQ_CLIENT13', + 34: 'CHCG_PERF_SEL_REQ_CLIENT14', + 35: 'CHCG_PERF_SEL_REQ_CLIENT15', + 36: 'CHCG_PERF_SEL_REQ_CLIENT16', + 37: 'CHCG_PERF_SEL_REQ_CLIENT17', + 38: 'CHCG_PERF_SEL_REQ_CLIENT18', + 39: 'CHCG_PERF_SEL_REQ_CLIENT19', + 40: 'CHCG_PERF_SEL_REQ_CLIENT20', + 41: 'CHCG_PERF_SEL_REQ_CLIENT21', + 42: 'CHCG_PERF_SEL_REQ_CLIENT22', + 43: 'CHCG_PERF_SEL_REQ_CLIENT23', +} +CHCG_PERF_SEL_CYCLE = 0 +CHCG_PERF_SEL_BUSY = 1 +CHCG_PERF_SEL_STARVE = 2 +CHCG_PERF_SEL_ARB_RET_LEVEL = 3 +CHCG_PERF_SEL_GL2_REQ_READ_LATENCY = 4 +CHCG_PERF_SEL_GL2_REQ_WRITE_LATENCY = 5 +CHCG_PERF_SEL_REQ = 6 +CHCG_PERF_SEL_REQ_ATOMIC_WITH_RET = 7 +CHCG_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 8 +CHCG_PERF_SEL_REQ_NOP_ACK = 9 +CHCG_PERF_SEL_REQ_NOP_RTN0 = 10 +CHCG_PERF_SEL_REQ_READ = 11 +CHCG_PERF_SEL_REQ_READ_128B = 12 +CHCG_PERF_SEL_REQ_READ_32B = 13 +CHCG_PERF_SEL_REQ_READ_64B = 14 +CHCG_PERF_SEL_REQ_WRITE = 15 +CHCG_PERF_SEL_REQ_WRITE_32B = 16 +CHCG_PERF_SEL_REQ_WRITE_64B = 17 +CHCG_PERF_SEL_STALL_GUS_GL1 = 18 +CHCG_PERF_SEL_STALL_BUFFER_FULL = 19 +CHCG_PERF_SEL_REQ_CLIENT0 = 20 +CHCG_PERF_SEL_REQ_CLIENT1 = 21 +CHCG_PERF_SEL_REQ_CLIENT2 = 22 +CHCG_PERF_SEL_REQ_CLIENT3 = 23 +CHCG_PERF_SEL_REQ_CLIENT4 = 24 +CHCG_PERF_SEL_REQ_CLIENT5 = 25 +CHCG_PERF_SEL_REQ_CLIENT6 = 26 +CHCG_PERF_SEL_REQ_CLIENT7 = 27 +CHCG_PERF_SEL_REQ_CLIENT8 = 28 +CHCG_PERF_SEL_REQ_CLIENT9 = 29 +CHCG_PERF_SEL_REQ_CLIENT10 = 30 +CHCG_PERF_SEL_REQ_CLIENT11 = 31 +CHCG_PERF_SEL_REQ_CLIENT12 = 32 +CHCG_PERF_SEL_REQ_CLIENT13 = 33 +CHCG_PERF_SEL_REQ_CLIENT14 = 34 +CHCG_PERF_SEL_REQ_CLIENT15 = 35 +CHCG_PERF_SEL_REQ_CLIENT16 = 36 +CHCG_PERF_SEL_REQ_CLIENT17 = 37 +CHCG_PERF_SEL_REQ_CLIENT18 = 38 +CHCG_PERF_SEL_REQ_CLIENT19 = 39 +CHCG_PERF_SEL_REQ_CLIENT20 = 40 +CHCG_PERF_SEL_REQ_CLIENT21 = 41 +CHCG_PERF_SEL_REQ_CLIENT22 = 42 +CHCG_PERF_SEL_REQ_CLIENT23 = 43 +CHCG_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CHC_PERF_SEL' +CHC_PERF_SEL__enumvalues = { + 0: 'CHC_PERF_SEL_CYCLE', + 1: 'CHC_PERF_SEL_BUSY', + 2: 'CHC_PERF_SEL_STARVE', + 3: 'CHC_PERF_SEL_ARB_RET_LEVEL', + 4: 'CHC_PERF_SEL_GL2_REQ_READ_LATENCY', + 5: 'CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 6: 'CHC_PERF_SEL_REQ', + 7: 'CHC_PERF_SEL_REQ_ATOMIC_WITH_RET', + 8: 'CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 9: 'CHC_PERF_SEL_REQ_NOP_ACK', + 10: 'CHC_PERF_SEL_REQ_NOP_RTN0', + 11: 'CHC_PERF_SEL_REQ_READ', + 12: 'CHC_PERF_SEL_REQ_READ_128B', + 13: 'CHC_PERF_SEL_REQ_READ_32B', + 14: 'CHC_PERF_SEL_REQ_READ_64B', + 15: 'CHC_PERF_SEL_REQ_WRITE', + 16: 'CHC_PERF_SEL_REQ_WRITE_32B', + 17: 'CHC_PERF_SEL_REQ_WRITE_64B', + 18: 'CHC_PERF_SEL_STALL_GL2_GL1', + 19: 'CHC_PERF_SEL_STALL_BUFFER_FULL', + 20: 'CHC_PERF_SEL_REQ_CLIENT0', + 21: 'CHC_PERF_SEL_REQ_CLIENT1', + 22: 'CHC_PERF_SEL_REQ_CLIENT2', + 23: 'CHC_PERF_SEL_REQ_CLIENT3', + 24: 'CHC_PERF_SEL_REQ_CLIENT4', + 25: 'CHC_PERF_SEL_REQ_CLIENT5', + 26: 'CHC_PERF_SEL_REQ_CLIENT6', + 27: 'CHC_PERF_SEL_REQ_CLIENT7', + 28: 'CHC_PERF_SEL_REQ_CLIENT8', + 29: 'CHC_PERF_SEL_REQ_CLIENT9', + 30: 'CHC_PERF_SEL_REQ_CLIENT10', + 31: 'CHC_PERF_SEL_REQ_CLIENT11', + 32: 'CHC_PERF_SEL_REQ_CLIENT12', + 33: 'CHC_PERF_SEL_REQ_CLIENT13', + 34: 'CHC_PERF_SEL_REQ_CLIENT14', + 35: 'CHC_PERF_SEL_REQ_CLIENT15', + 36: 'CHC_PERF_SEL_REQ_CLIENT16', + 37: 'CHC_PERF_SEL_REQ_CLIENT17', + 38: 'CHC_PERF_SEL_REQ_CLIENT18', + 39: 'CHC_PERF_SEL_REQ_CLIENT19', + 40: 'CHC_PERF_SEL_REQ_CLIENT20', + 41: 'CHC_PERF_SEL_REQ_CLIENT21', + 42: 'CHC_PERF_SEL_REQ_CLIENT22', + 43: 'CHC_PERF_SEL_REQ_CLIENT23', +} +CHC_PERF_SEL_CYCLE = 0 +CHC_PERF_SEL_BUSY = 1 +CHC_PERF_SEL_STARVE = 2 +CHC_PERF_SEL_ARB_RET_LEVEL = 3 +CHC_PERF_SEL_GL2_REQ_READ_LATENCY = 4 +CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY = 5 +CHC_PERF_SEL_REQ = 6 +CHC_PERF_SEL_REQ_ATOMIC_WITH_RET = 7 +CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 8 +CHC_PERF_SEL_REQ_NOP_ACK = 9 +CHC_PERF_SEL_REQ_NOP_RTN0 = 10 +CHC_PERF_SEL_REQ_READ = 11 +CHC_PERF_SEL_REQ_READ_128B = 12 +CHC_PERF_SEL_REQ_READ_32B = 13 +CHC_PERF_SEL_REQ_READ_64B = 14 +CHC_PERF_SEL_REQ_WRITE = 15 +CHC_PERF_SEL_REQ_WRITE_32B = 16 +CHC_PERF_SEL_REQ_WRITE_64B = 17 +CHC_PERF_SEL_STALL_GL2_GL1 = 18 +CHC_PERF_SEL_STALL_BUFFER_FULL = 19 +CHC_PERF_SEL_REQ_CLIENT0 = 20 +CHC_PERF_SEL_REQ_CLIENT1 = 21 +CHC_PERF_SEL_REQ_CLIENT2 = 22 +CHC_PERF_SEL_REQ_CLIENT3 = 23 +CHC_PERF_SEL_REQ_CLIENT4 = 24 +CHC_PERF_SEL_REQ_CLIENT5 = 25 +CHC_PERF_SEL_REQ_CLIENT6 = 26 +CHC_PERF_SEL_REQ_CLIENT7 = 27 +CHC_PERF_SEL_REQ_CLIENT8 = 28 +CHC_PERF_SEL_REQ_CLIENT9 = 29 +CHC_PERF_SEL_REQ_CLIENT10 = 30 +CHC_PERF_SEL_REQ_CLIENT11 = 31 +CHC_PERF_SEL_REQ_CLIENT12 = 32 +CHC_PERF_SEL_REQ_CLIENT13 = 33 +CHC_PERF_SEL_REQ_CLIENT14 = 34 +CHC_PERF_SEL_REQ_CLIENT15 = 35 +CHC_PERF_SEL_REQ_CLIENT16 = 36 +CHC_PERF_SEL_REQ_CLIENT17 = 37 +CHC_PERF_SEL_REQ_CLIENT18 = 38 +CHC_PERF_SEL_REQ_CLIENT19 = 39 +CHC_PERF_SEL_REQ_CLIENT20 = 40 +CHC_PERF_SEL_REQ_CLIENT21 = 41 +CHC_PERF_SEL_REQ_CLIENT22 = 42 +CHC_PERF_SEL_REQ_CLIENT23 = 43 +CHC_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1A_PERF_SEL' +GL1A_PERF_SEL__enumvalues = { + 0: 'GL1A_PERF_SEL_BUSY', + 1: 'GL1A_PERF_SEL_STALL_GL1C0', + 2: 'GL1A_PERF_SEL_STALL_GL1C1', + 3: 'GL1A_PERF_SEL_STALL_GL1C2', + 4: 'GL1A_PERF_SEL_STALL_GL1C3', + 5: 'GL1A_PERF_SEL_REQUEST_GL1C0', + 6: 'GL1A_PERF_SEL_REQUEST_GL1C1', + 7: 'GL1A_PERF_SEL_REQUEST_GL1C2', + 8: 'GL1A_PERF_SEL_REQUEST_GL1C3', + 9: 'GL1A_PERF_SEL_WDS_32B_GL1C0', + 10: 'GL1A_PERF_SEL_WDS_32B_GL1C1', + 11: 'GL1A_PERF_SEL_WDS_32B_GL1C2', + 12: 'GL1A_PERF_SEL_WDS_32B_GL1C3', + 13: 'GL1A_PERF_SEL_BURST_COUNT_GL1C0', + 14: 'GL1A_PERF_SEL_BURST_COUNT_GL1C1', + 15: 'GL1A_PERF_SEL_BURST_COUNT_GL1C2', + 16: 'GL1A_PERF_SEL_BURST_COUNT_GL1C3', + 17: 'GL1A_PERF_SEL_ARB_REQUESTS', + 18: 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 19: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 20: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 21: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 22: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 23: 'GL1A_PERF_SEL_CYCLE', +} +GL1A_PERF_SEL_BUSY = 0 +GL1A_PERF_SEL_STALL_GL1C0 = 1 +GL1A_PERF_SEL_STALL_GL1C1 = 2 +GL1A_PERF_SEL_STALL_GL1C2 = 3 +GL1A_PERF_SEL_STALL_GL1C3 = 4 +GL1A_PERF_SEL_REQUEST_GL1C0 = 5 +GL1A_PERF_SEL_REQUEST_GL1C1 = 6 +GL1A_PERF_SEL_REQUEST_GL1C2 = 7 +GL1A_PERF_SEL_REQUEST_GL1C3 = 8 +GL1A_PERF_SEL_WDS_32B_GL1C0 = 9 +GL1A_PERF_SEL_WDS_32B_GL1C1 = 10 +GL1A_PERF_SEL_WDS_32B_GL1C2 = 11 +GL1A_PERF_SEL_WDS_32B_GL1C3 = 12 +GL1A_PERF_SEL_BURST_COUNT_GL1C0 = 13 +GL1A_PERF_SEL_BURST_COUNT_GL1C1 = 14 +GL1A_PERF_SEL_BURST_COUNT_GL1C2 = 15 +GL1A_PERF_SEL_BURST_COUNT_GL1C3 = 16 +GL1A_PERF_SEL_ARB_REQUESTS = 17 +GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL = 18 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0 = 19 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1 = 20 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2 = 21 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3 = 22 +GL1A_PERF_SEL_CYCLE = 23 +GL1A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1C_PERF_SEL' +GL1C_PERF_SEL__enumvalues = { + 0: 'GL1C_PERF_SEL_CYCLE', + 1: 'GL1C_PERF_SEL_BUSY', + 2: 'GL1C_PERF_SEL_STARVE', + 3: 'GL1C_PERF_SEL_ARB_RET_LEVEL', + 4: 'GL1C_PERF_SEL_GL2_REQ_READ', + 5: 'GL1C_PERF_SEL_GL2_REQ_READ_128B', + 6: 'GL1C_PERF_SEL_GL2_REQ_READ_32B', + 7: 'GL1C_PERF_SEL_GL2_REQ_READ_64B', + 8: 'GL1C_PERF_SEL_GL2_REQ_READ_LATENCY', + 9: 'GL1C_PERF_SEL_GL2_REQ_WRITE', + 10: 'GL1C_PERF_SEL_GL2_REQ_WRITE_32B', + 11: 'GL1C_PERF_SEL_GL2_REQ_WRITE_64B', + 12: 'GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 13: 'GL1C_PERF_SEL_GL2_REQ_PREFETCH', + 14: 'GL1C_PERF_SEL_REQ', + 15: 'GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET', + 16: 'GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 17: 'GL1C_PERF_SEL_REQ_SHADER_INV', + 18: 'GL1C_PERF_SEL_REQ_MISS', + 19: 'GL1C_PERF_SEL_REQ_NOP_ACK', + 20: 'GL1C_PERF_SEL_REQ_NOP_RTN0', + 21: 'GL1C_PERF_SEL_REQ_READ', + 22: 'GL1C_PERF_SEL_REQ_READ_128B', + 23: 'GL1C_PERF_SEL_REQ_READ_32B', + 24: 'GL1C_PERF_SEL_REQ_READ_64B', + 25: 'GL1C_PERF_SEL_REQ_READ_POLICY_HIT_EVICT', + 26: 'GL1C_PERF_SEL_REQ_READ_POLICY_HIT_LRU', + 27: 'GL1C_PERF_SEL_REQ_READ_POLICY_MISS_EVICT', + 28: 'GL1C_PERF_SEL_REQ_WRITE', + 29: 'GL1C_PERF_SEL_REQ_WRITE_32B', + 30: 'GL1C_PERF_SEL_REQ_WRITE_64B', + 31: 'GL1C_PERF_SEL_STALL_GL2_GL1', + 32: 'GL1C_PERF_SEL_STALL_LFIFO_FULL', + 33: 'GL1C_PERF_SEL_STALL_NO_AVAILABLE_ACK_ALLOC', + 34: 'GL1C_PERF_SEL_STALL_NOTHING_REPLACEABLE', + 35: 'GL1C_PERF_SEL_STALL_GCR_INV', + 36: 'GL1C_PERF_SEL_STALL_VM', + 37: 'GL1C_PERF_SEL_REQ_CLIENT0', + 38: 'GL1C_PERF_SEL_REQ_CLIENT1', + 39: 'GL1C_PERF_SEL_REQ_CLIENT2', + 40: 'GL1C_PERF_SEL_REQ_CLIENT3', + 41: 'GL1C_PERF_SEL_REQ_CLIENT4', + 42: 'GL1C_PERF_SEL_REQ_CLIENT5', + 43: 'GL1C_PERF_SEL_REQ_CLIENT6', + 44: 'GL1C_PERF_SEL_REQ_CLIENT7', + 45: 'GL1C_PERF_SEL_REQ_CLIENT8', + 46: 'GL1C_PERF_SEL_REQ_CLIENT9', + 47: 'GL1C_PERF_SEL_REQ_CLIENT10', + 48: 'GL1C_PERF_SEL_REQ_CLIENT11', + 49: 'GL1C_PERF_SEL_REQ_CLIENT12', + 50: 'GL1C_PERF_SEL_REQ_CLIENT13', + 51: 'GL1C_PERF_SEL_REQ_CLIENT14', + 52: 'GL1C_PERF_SEL_REQ_CLIENT15', + 53: 'GL1C_PERF_SEL_REQ_CLIENT16', + 54: 'GL1C_PERF_SEL_REQ_CLIENT17', + 55: 'GL1C_PERF_SEL_REQ_CLIENT18', + 56: 'GL1C_PERF_SEL_REQ_CLIENT19', + 57: 'GL1C_PERF_SEL_REQ_CLIENT20', + 58: 'GL1C_PERF_SEL_REQ_CLIENT21', + 59: 'GL1C_PERF_SEL_REQ_CLIENT22', + 60: 'GL1C_PERF_SEL_REQ_CLIENT23', + 61: 'GL1C_PERF_SEL_REQ_CLIENT24', + 62: 'GL1C_PERF_SEL_REQ_CLIENT25', + 63: 'GL1C_PERF_SEL_REQ_CLIENT26', + 64: 'GL1C_PERF_SEL_REQ_CLIENT27', + 65: 'GL1C_PERF_SEL_UTCL0_REQUEST', + 66: 'GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT', + 67: 'GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS', + 68: 'GL1C_PERF_SEL_UTCL0_PERMISSION_MISS', + 69: 'GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 70: 'GL1C_PERF_SEL_UTCL0_LFIFO_FULL', + 71: 'GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 72: 'GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 73: 'GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 74: 'GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 75: 'GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 76: 'GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 77: 'GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 78: 'GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 79: 'GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 80: 'GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 81: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', + 82: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 83: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', +} +GL1C_PERF_SEL_CYCLE = 0 +GL1C_PERF_SEL_BUSY = 1 +GL1C_PERF_SEL_STARVE = 2 +GL1C_PERF_SEL_ARB_RET_LEVEL = 3 +GL1C_PERF_SEL_GL2_REQ_READ = 4 +GL1C_PERF_SEL_GL2_REQ_READ_128B = 5 +GL1C_PERF_SEL_GL2_REQ_READ_32B = 6 +GL1C_PERF_SEL_GL2_REQ_READ_64B = 7 +GL1C_PERF_SEL_GL2_REQ_READ_LATENCY = 8 +GL1C_PERF_SEL_GL2_REQ_WRITE = 9 +GL1C_PERF_SEL_GL2_REQ_WRITE_32B = 10 +GL1C_PERF_SEL_GL2_REQ_WRITE_64B = 11 +GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY = 12 +GL1C_PERF_SEL_GL2_REQ_PREFETCH = 13 +GL1C_PERF_SEL_REQ = 14 +GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET = 15 +GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 16 +GL1C_PERF_SEL_REQ_SHADER_INV = 17 +GL1C_PERF_SEL_REQ_MISS = 18 +GL1C_PERF_SEL_REQ_NOP_ACK = 19 +GL1C_PERF_SEL_REQ_NOP_RTN0 = 20 +GL1C_PERF_SEL_REQ_READ = 21 +GL1C_PERF_SEL_REQ_READ_128B = 22 +GL1C_PERF_SEL_REQ_READ_32B = 23 +GL1C_PERF_SEL_REQ_READ_64B = 24 +GL1C_PERF_SEL_REQ_READ_POLICY_HIT_EVICT = 25 +GL1C_PERF_SEL_REQ_READ_POLICY_HIT_LRU = 26 +GL1C_PERF_SEL_REQ_READ_POLICY_MISS_EVICT = 27 +GL1C_PERF_SEL_REQ_WRITE = 28 +GL1C_PERF_SEL_REQ_WRITE_32B = 29 +GL1C_PERF_SEL_REQ_WRITE_64B = 30 +GL1C_PERF_SEL_STALL_GL2_GL1 = 31 +GL1C_PERF_SEL_STALL_LFIFO_FULL = 32 +GL1C_PERF_SEL_STALL_NO_AVAILABLE_ACK_ALLOC = 33 +GL1C_PERF_SEL_STALL_NOTHING_REPLACEABLE = 34 +GL1C_PERF_SEL_STALL_GCR_INV = 35 +GL1C_PERF_SEL_STALL_VM = 36 +GL1C_PERF_SEL_REQ_CLIENT0 = 37 +GL1C_PERF_SEL_REQ_CLIENT1 = 38 +GL1C_PERF_SEL_REQ_CLIENT2 = 39 +GL1C_PERF_SEL_REQ_CLIENT3 = 40 +GL1C_PERF_SEL_REQ_CLIENT4 = 41 +GL1C_PERF_SEL_REQ_CLIENT5 = 42 +GL1C_PERF_SEL_REQ_CLIENT6 = 43 +GL1C_PERF_SEL_REQ_CLIENT7 = 44 +GL1C_PERF_SEL_REQ_CLIENT8 = 45 +GL1C_PERF_SEL_REQ_CLIENT9 = 46 +GL1C_PERF_SEL_REQ_CLIENT10 = 47 +GL1C_PERF_SEL_REQ_CLIENT11 = 48 +GL1C_PERF_SEL_REQ_CLIENT12 = 49 +GL1C_PERF_SEL_REQ_CLIENT13 = 50 +GL1C_PERF_SEL_REQ_CLIENT14 = 51 +GL1C_PERF_SEL_REQ_CLIENT15 = 52 +GL1C_PERF_SEL_REQ_CLIENT16 = 53 +GL1C_PERF_SEL_REQ_CLIENT17 = 54 +GL1C_PERF_SEL_REQ_CLIENT18 = 55 +GL1C_PERF_SEL_REQ_CLIENT19 = 56 +GL1C_PERF_SEL_REQ_CLIENT20 = 57 +GL1C_PERF_SEL_REQ_CLIENT21 = 58 +GL1C_PERF_SEL_REQ_CLIENT22 = 59 +GL1C_PERF_SEL_REQ_CLIENT23 = 60 +GL1C_PERF_SEL_REQ_CLIENT24 = 61 +GL1C_PERF_SEL_REQ_CLIENT25 = 62 +GL1C_PERF_SEL_REQ_CLIENT26 = 63 +GL1C_PERF_SEL_REQ_CLIENT27 = 64 +GL1C_PERF_SEL_UTCL0_REQUEST = 65 +GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT = 66 +GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS = 67 +GL1C_PERF_SEL_UTCL0_PERMISSION_MISS = 68 +GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS = 69 +GL1C_PERF_SEL_UTCL0_LFIFO_FULL = 70 +GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX = 71 +GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES = 72 +GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT = 73 +GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL = 74 +GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS = 75 +GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 76 +GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT = 77 +GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT = 78 +GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT = 79 +GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ = 80 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT = 81 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT = 82 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT = 83 +GL1C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1H_REQ_PERF_SEL' +GL1H_REQ_PERF_SEL__enumvalues = { + 0: 'GL1H_REQ_PERF_SEL_BUSY', + 1: 'GL1H_REQ_PERF_SEL_STALL_GL1_0', + 2: 'GL1H_REQ_PERF_SEL_STALL_GL1_1', + 3: 'GL1H_REQ_PERF_SEL_REQUEST_GL1_0', + 4: 'GL1H_REQ_PERF_SEL_REQUEST_GL1_1', + 5: 'GL1H_REQ_PERF_SEL_WDS_32B_GL1_0', + 6: 'GL1H_REQ_PERF_SEL_WDS_32B_GL1_1', + 7: 'GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_0', + 8: 'GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_1', + 9: 'GL1H_REQ_PERF_SEL_ARB_REQUESTS', + 10: 'GL1H_REQ_PERF_SEL_REQ_INFLIGHT_LEVEL', + 11: 'GL1H_REQ_PERF_SEL_CYCLE', +} +GL1H_REQ_PERF_SEL_BUSY = 0 +GL1H_REQ_PERF_SEL_STALL_GL1_0 = 1 +GL1H_REQ_PERF_SEL_STALL_GL1_1 = 2 +GL1H_REQ_PERF_SEL_REQUEST_GL1_0 = 3 +GL1H_REQ_PERF_SEL_REQUEST_GL1_1 = 4 +GL1H_REQ_PERF_SEL_WDS_32B_GL1_0 = 5 +GL1H_REQ_PERF_SEL_WDS_32B_GL1_1 = 6 +GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_0 = 7 +GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_1 = 8 +GL1H_REQ_PERF_SEL_ARB_REQUESTS = 9 +GL1H_REQ_PERF_SEL_REQ_INFLIGHT_LEVEL = 10 +GL1H_REQ_PERF_SEL_CYCLE = 11 +GL1H_REQ_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TA_PERFCOUNT_SEL' +TA_PERFCOUNT_SEL__enumvalues = { + 0: 'TA_PERF_SEL_NULL', + 1: 'TA_PERF_SEL_image_sampler_has_offset_instructions', + 2: 'TA_PERF_SEL_image_sampler_has_bias_instructions', + 3: 'TA_PERF_SEL_image_sampler_has_reference_instructions', + 4: 'TA_PERF_SEL_image_sampler_has_ds_instructions', + 5: 'TA_PERF_SEL_image_sampler_has_dt_instructions', + 6: 'TA_PERF_SEL_image_sampler_has_dr_instructions', + 7: 'TA_PERF_SEL_gradient_busy', + 8: 'TA_PERF_SEL_gradient_fifo_busy', + 9: 'TA_PERF_SEL_lod_busy', + 10: 'TA_PERF_SEL_lod_fifo_busy', + 11: 'TA_PERF_SEL_addresser_busy', + 12: 'TA_PERF_SEL_addresser_fifo_busy', + 13: 'TA_PERF_SEL_aligner_busy', + 14: 'TA_PERF_SEL_write_path_busy', + 15: 'TA_PERF_SEL_ta_busy', + 16: 'TA_PERF_SEL_image_sampler_1_input_vgpr_instructions', + 17: 'TA_PERF_SEL_image_sampler_2_input_vgpr_instructions', + 18: 'TA_PERF_SEL_image_sampler_3_input_vgpr_instructions', + 19: 'TA_PERF_SEL_image_sampler_4_input_vgpr_instructions', + 20: 'TA_PERF_SEL_image_sampler_5_input_vgpr_instructions', + 21: 'TA_PERF_SEL_image_sampler_6_input_vgpr_instructions', + 22: 'TA_PERF_SEL_image_sampler_7_input_vgpr_instructions', + 23: 'TA_PERF_SEL_image_sampler_8_input_vgpr_instructions', + 24: 'TA_PERF_SEL_image_sampler_9_input_vgpr_instructions', + 25: 'TA_PERF_SEL_image_sampler_10_input_vgpr_instructions', + 26: 'TA_PERF_SEL_image_sampler_11_input_vgpr_instructions', + 27: 'TA_PERF_SEL_image_sampler_12_input_vgpr_instructions', + 28: 'TA_PERF_SEL_image_sampler_has_t_instructions', + 29: 'TA_PERF_SEL_image_sampler_has_r_instructions', + 30: 'TA_PERF_SEL_image_sampler_has_q_instructions', + 32: 'TA_PERF_SEL_total_wavefronts', + 33: 'TA_PERF_SEL_gradient_cycles', + 34: 'TA_PERF_SEL_walker_cycles', + 35: 'TA_PERF_SEL_aligner_cycles', + 36: 'TA_PERF_SEL_image_wavefronts', + 37: 'TA_PERF_SEL_image_read_wavefronts', + 38: 'TA_PERF_SEL_image_store_wavefronts', + 39: 'TA_PERF_SEL_image_atomic_wavefronts', + 40: 'TA_PERF_SEL_image_sampler_total_cycles', + 41: 'TA_PERF_SEL_image_nosampler_total_cycles', + 42: 'TA_PERF_SEL_flat_total_cycles', + 43: 'TA_PERF_SEL_bvh_total_cycles', + 44: 'TA_PERF_SEL_buffer_wavefronts', + 45: 'TA_PERF_SEL_buffer_load_wavefronts', + 46: 'TA_PERF_SEL_buffer_store_wavefronts', + 47: 'TA_PERF_SEL_buffer_atomic_wavefronts', + 49: 'TA_PERF_SEL_buffer_total_cycles', + 50: 'TA_PERF_SEL_buffer_1_address_input_vgpr_instructions', + 51: 'TA_PERF_SEL_buffer_2_address_input_vgpr_instructions', + 52: 'TA_PERF_SEL_buffer_has_index_instructions', + 53: 'TA_PERF_SEL_buffer_has_offset_instructions', + 54: 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 55: 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 56: 'TA_PERF_SEL_image_sampler_wavefronts', + 57: 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 58: 'TA_PERF_SEL_addresser_stalled_cycles', + 59: 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 60: 'TA_PERF_SEL_aniso_stalled_cycles', + 61: 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 62: 'TA_PERF_SEL_deriv_stalled_cycles', + 63: 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 64: 'TA_PERF_SEL_color_1_cycle_quads', + 65: 'TA_PERF_SEL_color_2_cycle_quads', + 66: 'TA_PERF_SEL_color_3_cycle_quads', + 68: 'TA_PERF_SEL_mip_1_cycle_quads', + 69: 'TA_PERF_SEL_mip_2_cycle_quads', + 70: 'TA_PERF_SEL_vol_1_cycle_quads', + 71: 'TA_PERF_SEL_vol_2_cycle_quads', + 72: 'TA_PERF_SEL_sampler_op_quads', + 73: 'TA_PERF_SEL_mipmap_lod_0_samples', + 74: 'TA_PERF_SEL_mipmap_lod_1_samples', + 75: 'TA_PERF_SEL_mipmap_lod_2_samples', + 76: 'TA_PERF_SEL_mipmap_lod_3_samples', + 77: 'TA_PERF_SEL_mipmap_lod_4_samples', + 78: 'TA_PERF_SEL_mipmap_lod_5_samples', + 79: 'TA_PERF_SEL_mipmap_lod_6_samples', + 80: 'TA_PERF_SEL_mipmap_lod_7_samples', + 81: 'TA_PERF_SEL_mipmap_lod_8_samples', + 82: 'TA_PERF_SEL_mipmap_lod_9_samples', + 83: 'TA_PERF_SEL_mipmap_lod_10_samples', + 84: 'TA_PERF_SEL_mipmap_lod_11_samples', + 85: 'TA_PERF_SEL_mipmap_lod_12_samples', + 86: 'TA_PERF_SEL_mipmap_lod_13_samples', + 87: 'TA_PERF_SEL_mipmap_lod_14_samples', + 88: 'TA_PERF_SEL_mipmap_invalid_samples', + 89: 'TA_PERF_SEL_aniso_1_cycle_quads', + 90: 'TA_PERF_SEL_aniso_2_cycle_quads', + 91: 'TA_PERF_SEL_aniso_4_cycle_quads', + 92: 'TA_PERF_SEL_aniso_6_cycle_quads', + 93: 'TA_PERF_SEL_aniso_8_cycle_quads', + 94: 'TA_PERF_SEL_aniso_10_cycle_quads', + 95: 'TA_PERF_SEL_aniso_12_cycle_quads', + 96: 'TA_PERF_SEL_aniso_14_cycle_quads', + 97: 'TA_PERF_SEL_aniso_16_cycle_quads', + 98: 'TA_PERF_SEL_store_write_data_input_cycles', + 99: 'TA_PERF_SEL_store_write_data_output_cycles', + 100: 'TA_PERF_SEL_flat_wavefronts', + 101: 'TA_PERF_SEL_flat_load_wavefronts', + 102: 'TA_PERF_SEL_flat_store_wavefronts', + 103: 'TA_PERF_SEL_flat_atomic_wavefronts', + 104: 'TA_PERF_SEL_flat_1_address_input_vgpr_instructions', + 105: 'TA_PERF_SEL_register_clk_valid_cycles', + 106: 'TA_PERF_SEL_non_harvestable_clk_enabled_cycles', + 107: 'TA_PERF_SEL_harvestable_clk_enabled_cycles', + 108: 'TA_PERF_SEL_harvestable_register_clk_enabled_cycles', + 109: 'TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles', + 110: 'TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles', + 114: 'TA_PERF_SEL_store_2_write_data_vgpr_instructions', + 115: 'TA_PERF_SEL_store_3_write_data_vgpr_instructions', + 116: 'TA_PERF_SEL_store_4_write_data_vgpr_instructions', + 117: 'TA_PERF_SEL_store_has_x_instructions', + 118: 'TA_PERF_SEL_store_has_y_instructions', + 119: 'TA_PERF_SEL_store_has_z_instructions', + 120: 'TA_PERF_SEL_store_has_w_instructions', + 121: 'TA_PERF_SEL_image_nosampler_has_t_instructions', + 122: 'TA_PERF_SEL_image_nosampler_has_r_instructions', + 123: 'TA_PERF_SEL_image_nosampler_has_q_instructions', + 124: 'TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions', + 125: 'TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions', + 126: 'TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions', + 127: 'TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions', + 128: 'TA_PERF_SEL_in_busy', + 129: 'TA_PERF_SEL_in_fifos_busy', + 130: 'TA_PERF_SEL_in_cfifo_busy', + 131: 'TA_PERF_SEL_in_qfifo_busy', + 132: 'TA_PERF_SEL_in_wfifo_busy', + 133: 'TA_PERF_SEL_in_rfifo_busy', + 134: 'TA_PERF_SEL_bf_busy', + 135: 'TA_PERF_SEL_ns_busy', + 136: 'TA_PERF_SEL_smp_busy_ns_idle', + 137: 'TA_PERF_SEL_smp_idle_ns_busy', + 144: 'TA_PERF_SEL_vmemcmd_cycles', + 145: 'TA_PERF_SEL_vmemreq_cycles', + 146: 'TA_PERF_SEL_in_waiting_on_req_cycles', + 150: 'TA_PERF_SEL_in_addr_cycles', + 151: 'TA_PERF_SEL_in_data_cycles', + 154: 'TA_PERF_SEL_latency_ram_weights_written_cycles', + 155: 'TA_PERF_SEL_latency_ram_ws_required_quads', + 156: 'TA_PERF_SEL_latency_ram_whv_required_quads', + 157: 'TA_PERF_SEL_latency_ram_ws_required_instructions', + 158: 'TA_PERF_SEL_latency_ram_whv_required_instructions', + 159: 'TA_PERF_SEL_latency_ram_ref_required_instructions', + 160: 'TA_PERF_SEL_point_sampled_quads', + 162: 'TA_PERF_SEL_atomic_2_write_data_vgpr_instructions', + 163: 'TA_PERF_SEL_atomic_4_write_data_vgpr_instructions', + 164: 'TA_PERF_SEL_atomic_write_data_input_cycles', + 165: 'TA_PERF_SEL_atomic_write_data_output_cycles', + 173: 'TA_PERF_SEL_num_unlit_nodes_ta_opt', + 174: 'TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input', + 175: 'TA_PERF_SEL_num_nodes_invalidated_due_to_oob', + 176: 'TA_PERF_SEL_num_of_bvh_valid_first_tri', + 177: 'TA_PERF_SEL_num_of_bvh_valid_second_tri', + 178: 'TA_PERF_SEL_num_of_bvh_valid_third_tri', + 179: 'TA_PERF_SEL_num_of_bvh_valid_fourth_tri', + 180: 'TA_PERF_SEL_num_of_bvh_valid_fp16_box', + 181: 'TA_PERF_SEL_num_of_bvh_valid_fp32_box', + 182: 'TA_PERF_SEL_num_of_bvh_invalidated_first_tri', + 183: 'TA_PERF_SEL_num_of_bvh_invalidated_second_tri', + 184: 'TA_PERF_SEL_num_of_bvh_invalidated_third_tri', + 185: 'TA_PERF_SEL_num_of_bvh_invalidated_fourth_tri', + 186: 'TA_PERF_SEL_num_of_bvh_invalidated_fp16_box', + 187: 'TA_PERF_SEL_num_of_bvh_invalidated_fp32_box', + 188: 'TA_PERF_SEL_image_bvh_8_input_vgpr_instructions', + 189: 'TA_PERF_SEL_image_bvh_9_input_vgpr_instructions', + 190: 'TA_PERF_SEL_image_bvh_11_input_vgpr_instructions', + 191: 'TA_PERF_SEL_image_bvh_12_input_vgpr_instructions', + 192: 'TA_PERF_SEL_image_sampler_1_op_burst', + 193: 'TA_PERF_SEL_image_sampler_2to3_op_burst', + 194: 'TA_PERF_SEL_image_sampler_4to7_op_burst', + 195: 'TA_PERF_SEL_image_sampler_ge8_op_burst', + 196: 'TA_PERF_SEL_image_linked_1_op_burst', + 197: 'TA_PERF_SEL_image_linked_2to3_op_burst', + 198: 'TA_PERF_SEL_image_linked_4to7_op_burst', + 199: 'TA_PERF_SEL_image_linked_ge8_op_burst', + 200: 'TA_PERF_SEL_image_bvh_1_op_burst', + 201: 'TA_PERF_SEL_image_bvh_2to3_op_burst', + 202: 'TA_PERF_SEL_image_bvh_4to7_op_burst', + 203: 'TA_PERF_SEL_image_bvh_ge8_op_burst', + 204: 'TA_PERF_SEL_image_nosampler_1_op_burst', + 205: 'TA_PERF_SEL_image_nosampler_2to3_op_burst', + 206: 'TA_PERF_SEL_image_nosampler_4to31_op_burst', + 207: 'TA_PERF_SEL_image_nosampler_ge32_op_burst', + 208: 'TA_PERF_SEL_buffer_flat_1_op_burst', + 209: 'TA_PERF_SEL_buffer_flat_2to3_op_burst', + 210: 'TA_PERF_SEL_buffer_flat_4to31_op_burst', + 211: 'TA_PERF_SEL_buffer_flat_ge32_op_burst', + 212: 'TA_PERF_SEL_write_1_op_burst', + 213: 'TA_PERF_SEL_write_2to3_op_burst', + 214: 'TA_PERF_SEL_write_4to31_op_burst', + 215: 'TA_PERF_SEL_write_ge32_op_burst', + 216: 'TA_PERF_SEL_ibubble_1_cycle_burst', + 217: 'TA_PERF_SEL_ibubble_2to3_cycle_burst', + 218: 'TA_PERF_SEL_ibubble_4to15_cycle_burst', + 219: 'TA_PERF_SEL_ibubble_16to31_cycle_burst', + 220: 'TA_PERF_SEL_ibubble_32to63_cycle_burst', + 221: 'TA_PERF_SEL_ibubble_ge64_cycle_burst', + 224: 'TA_PERF_SEL_sampler_clk_valid_cycles', + 225: 'TA_PERF_SEL_nonsampler_clk_valid_cycles', + 226: 'TA_PERF_SEL_buffer_flat_clk_valid_cycles', + 227: 'TA_PERF_SEL_write_data_clk_valid_cycles', + 228: 'TA_PERF_SEL_gradient_clk_valid_cycles', + 229: 'TA_PERF_SEL_lod_aniso_clk_valid_cycles', + 230: 'TA_PERF_SEL_sampler_addressing_clk_valid_cycles', + 231: 'TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles', + 232: 'TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles', + 233: 'TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles', + 234: 'TA_PERF_SEL_aligner_clk_valid_cycles', + 235: 'TA_PERF_SEL_tcreq_clk_valid_cycles', +} +TA_PERF_SEL_NULL = 0 +TA_PERF_SEL_image_sampler_has_offset_instructions = 1 +TA_PERF_SEL_image_sampler_has_bias_instructions = 2 +TA_PERF_SEL_image_sampler_has_reference_instructions = 3 +TA_PERF_SEL_image_sampler_has_ds_instructions = 4 +TA_PERF_SEL_image_sampler_has_dt_instructions = 5 +TA_PERF_SEL_image_sampler_has_dr_instructions = 6 +TA_PERF_SEL_gradient_busy = 7 +TA_PERF_SEL_gradient_fifo_busy = 8 +TA_PERF_SEL_lod_busy = 9 +TA_PERF_SEL_lod_fifo_busy = 10 +TA_PERF_SEL_addresser_busy = 11 +TA_PERF_SEL_addresser_fifo_busy = 12 +TA_PERF_SEL_aligner_busy = 13 +TA_PERF_SEL_write_path_busy = 14 +TA_PERF_SEL_ta_busy = 15 +TA_PERF_SEL_image_sampler_1_input_vgpr_instructions = 16 +TA_PERF_SEL_image_sampler_2_input_vgpr_instructions = 17 +TA_PERF_SEL_image_sampler_3_input_vgpr_instructions = 18 +TA_PERF_SEL_image_sampler_4_input_vgpr_instructions = 19 +TA_PERF_SEL_image_sampler_5_input_vgpr_instructions = 20 +TA_PERF_SEL_image_sampler_6_input_vgpr_instructions = 21 +TA_PERF_SEL_image_sampler_7_input_vgpr_instructions = 22 +TA_PERF_SEL_image_sampler_8_input_vgpr_instructions = 23 +TA_PERF_SEL_image_sampler_9_input_vgpr_instructions = 24 +TA_PERF_SEL_image_sampler_10_input_vgpr_instructions = 25 +TA_PERF_SEL_image_sampler_11_input_vgpr_instructions = 26 +TA_PERF_SEL_image_sampler_12_input_vgpr_instructions = 27 +TA_PERF_SEL_image_sampler_has_t_instructions = 28 +TA_PERF_SEL_image_sampler_has_r_instructions = 29 +TA_PERF_SEL_image_sampler_has_q_instructions = 30 +TA_PERF_SEL_total_wavefronts = 32 +TA_PERF_SEL_gradient_cycles = 33 +TA_PERF_SEL_walker_cycles = 34 +TA_PERF_SEL_aligner_cycles = 35 +TA_PERF_SEL_image_wavefronts = 36 +TA_PERF_SEL_image_read_wavefronts = 37 +TA_PERF_SEL_image_store_wavefronts = 38 +TA_PERF_SEL_image_atomic_wavefronts = 39 +TA_PERF_SEL_image_sampler_total_cycles = 40 +TA_PERF_SEL_image_nosampler_total_cycles = 41 +TA_PERF_SEL_flat_total_cycles = 42 +TA_PERF_SEL_bvh_total_cycles = 43 +TA_PERF_SEL_buffer_wavefronts = 44 +TA_PERF_SEL_buffer_load_wavefronts = 45 +TA_PERF_SEL_buffer_store_wavefronts = 46 +TA_PERF_SEL_buffer_atomic_wavefronts = 47 +TA_PERF_SEL_buffer_total_cycles = 49 +TA_PERF_SEL_buffer_1_address_input_vgpr_instructions = 50 +TA_PERF_SEL_buffer_2_address_input_vgpr_instructions = 51 +TA_PERF_SEL_buffer_has_index_instructions = 52 +TA_PERF_SEL_buffer_has_offset_instructions = 53 +TA_PERF_SEL_addr_stalled_by_tc_cycles = 54 +TA_PERF_SEL_addr_stalled_by_td_cycles = 55 +TA_PERF_SEL_image_sampler_wavefronts = 56 +TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles = 57 +TA_PERF_SEL_addresser_stalled_cycles = 58 +TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles = 59 +TA_PERF_SEL_aniso_stalled_cycles = 60 +TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles = 61 +TA_PERF_SEL_deriv_stalled_cycles = 62 +TA_PERF_SEL_aniso_gt1_cycle_quads = 63 +TA_PERF_SEL_color_1_cycle_quads = 64 +TA_PERF_SEL_color_2_cycle_quads = 65 +TA_PERF_SEL_color_3_cycle_quads = 66 +TA_PERF_SEL_mip_1_cycle_quads = 68 +TA_PERF_SEL_mip_2_cycle_quads = 69 +TA_PERF_SEL_vol_1_cycle_quads = 70 +TA_PERF_SEL_vol_2_cycle_quads = 71 +TA_PERF_SEL_sampler_op_quads = 72 +TA_PERF_SEL_mipmap_lod_0_samples = 73 +TA_PERF_SEL_mipmap_lod_1_samples = 74 +TA_PERF_SEL_mipmap_lod_2_samples = 75 +TA_PERF_SEL_mipmap_lod_3_samples = 76 +TA_PERF_SEL_mipmap_lod_4_samples = 77 +TA_PERF_SEL_mipmap_lod_5_samples = 78 +TA_PERF_SEL_mipmap_lod_6_samples = 79 +TA_PERF_SEL_mipmap_lod_7_samples = 80 +TA_PERF_SEL_mipmap_lod_8_samples = 81 +TA_PERF_SEL_mipmap_lod_9_samples = 82 +TA_PERF_SEL_mipmap_lod_10_samples = 83 +TA_PERF_SEL_mipmap_lod_11_samples = 84 +TA_PERF_SEL_mipmap_lod_12_samples = 85 +TA_PERF_SEL_mipmap_lod_13_samples = 86 +TA_PERF_SEL_mipmap_lod_14_samples = 87 +TA_PERF_SEL_mipmap_invalid_samples = 88 +TA_PERF_SEL_aniso_1_cycle_quads = 89 +TA_PERF_SEL_aniso_2_cycle_quads = 90 +TA_PERF_SEL_aniso_4_cycle_quads = 91 +TA_PERF_SEL_aniso_6_cycle_quads = 92 +TA_PERF_SEL_aniso_8_cycle_quads = 93 +TA_PERF_SEL_aniso_10_cycle_quads = 94 +TA_PERF_SEL_aniso_12_cycle_quads = 95 +TA_PERF_SEL_aniso_14_cycle_quads = 96 +TA_PERF_SEL_aniso_16_cycle_quads = 97 +TA_PERF_SEL_store_write_data_input_cycles = 98 +TA_PERF_SEL_store_write_data_output_cycles = 99 +TA_PERF_SEL_flat_wavefronts = 100 +TA_PERF_SEL_flat_load_wavefronts = 101 +TA_PERF_SEL_flat_store_wavefronts = 102 +TA_PERF_SEL_flat_atomic_wavefronts = 103 +TA_PERF_SEL_flat_1_address_input_vgpr_instructions = 104 +TA_PERF_SEL_register_clk_valid_cycles = 105 +TA_PERF_SEL_non_harvestable_clk_enabled_cycles = 106 +TA_PERF_SEL_harvestable_clk_enabled_cycles = 107 +TA_PERF_SEL_harvestable_register_clk_enabled_cycles = 108 +TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles = 109 +TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles = 110 +TA_PERF_SEL_store_2_write_data_vgpr_instructions = 114 +TA_PERF_SEL_store_3_write_data_vgpr_instructions = 115 +TA_PERF_SEL_store_4_write_data_vgpr_instructions = 116 +TA_PERF_SEL_store_has_x_instructions = 117 +TA_PERF_SEL_store_has_y_instructions = 118 +TA_PERF_SEL_store_has_z_instructions = 119 +TA_PERF_SEL_store_has_w_instructions = 120 +TA_PERF_SEL_image_nosampler_has_t_instructions = 121 +TA_PERF_SEL_image_nosampler_has_r_instructions = 122 +TA_PERF_SEL_image_nosampler_has_q_instructions = 123 +TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions = 124 +TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions = 125 +TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions = 126 +TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions = 127 +TA_PERF_SEL_in_busy = 128 +TA_PERF_SEL_in_fifos_busy = 129 +TA_PERF_SEL_in_cfifo_busy = 130 +TA_PERF_SEL_in_qfifo_busy = 131 +TA_PERF_SEL_in_wfifo_busy = 132 +TA_PERF_SEL_in_rfifo_busy = 133 +TA_PERF_SEL_bf_busy = 134 +TA_PERF_SEL_ns_busy = 135 +TA_PERF_SEL_smp_busy_ns_idle = 136 +TA_PERF_SEL_smp_idle_ns_busy = 137 +TA_PERF_SEL_vmemcmd_cycles = 144 +TA_PERF_SEL_vmemreq_cycles = 145 +TA_PERF_SEL_in_waiting_on_req_cycles = 146 +TA_PERF_SEL_in_addr_cycles = 150 +TA_PERF_SEL_in_data_cycles = 151 +TA_PERF_SEL_latency_ram_weights_written_cycles = 154 +TA_PERF_SEL_latency_ram_ws_required_quads = 155 +TA_PERF_SEL_latency_ram_whv_required_quads = 156 +TA_PERF_SEL_latency_ram_ws_required_instructions = 157 +TA_PERF_SEL_latency_ram_whv_required_instructions = 158 +TA_PERF_SEL_latency_ram_ref_required_instructions = 159 +TA_PERF_SEL_point_sampled_quads = 160 +TA_PERF_SEL_atomic_2_write_data_vgpr_instructions = 162 +TA_PERF_SEL_atomic_4_write_data_vgpr_instructions = 163 +TA_PERF_SEL_atomic_write_data_input_cycles = 164 +TA_PERF_SEL_atomic_write_data_output_cycles = 165 +TA_PERF_SEL_num_unlit_nodes_ta_opt = 173 +TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input = 174 +TA_PERF_SEL_num_nodes_invalidated_due_to_oob = 175 +TA_PERF_SEL_num_of_bvh_valid_first_tri = 176 +TA_PERF_SEL_num_of_bvh_valid_second_tri = 177 +TA_PERF_SEL_num_of_bvh_valid_third_tri = 178 +TA_PERF_SEL_num_of_bvh_valid_fourth_tri = 179 +TA_PERF_SEL_num_of_bvh_valid_fp16_box = 180 +TA_PERF_SEL_num_of_bvh_valid_fp32_box = 181 +TA_PERF_SEL_num_of_bvh_invalidated_first_tri = 182 +TA_PERF_SEL_num_of_bvh_invalidated_second_tri = 183 +TA_PERF_SEL_num_of_bvh_invalidated_third_tri = 184 +TA_PERF_SEL_num_of_bvh_invalidated_fourth_tri = 185 +TA_PERF_SEL_num_of_bvh_invalidated_fp16_box = 186 +TA_PERF_SEL_num_of_bvh_invalidated_fp32_box = 187 +TA_PERF_SEL_image_bvh_8_input_vgpr_instructions = 188 +TA_PERF_SEL_image_bvh_9_input_vgpr_instructions = 189 +TA_PERF_SEL_image_bvh_11_input_vgpr_instructions = 190 +TA_PERF_SEL_image_bvh_12_input_vgpr_instructions = 191 +TA_PERF_SEL_image_sampler_1_op_burst = 192 +TA_PERF_SEL_image_sampler_2to3_op_burst = 193 +TA_PERF_SEL_image_sampler_4to7_op_burst = 194 +TA_PERF_SEL_image_sampler_ge8_op_burst = 195 +TA_PERF_SEL_image_linked_1_op_burst = 196 +TA_PERF_SEL_image_linked_2to3_op_burst = 197 +TA_PERF_SEL_image_linked_4to7_op_burst = 198 +TA_PERF_SEL_image_linked_ge8_op_burst = 199 +TA_PERF_SEL_image_bvh_1_op_burst = 200 +TA_PERF_SEL_image_bvh_2to3_op_burst = 201 +TA_PERF_SEL_image_bvh_4to7_op_burst = 202 +TA_PERF_SEL_image_bvh_ge8_op_burst = 203 +TA_PERF_SEL_image_nosampler_1_op_burst = 204 +TA_PERF_SEL_image_nosampler_2to3_op_burst = 205 +TA_PERF_SEL_image_nosampler_4to31_op_burst = 206 +TA_PERF_SEL_image_nosampler_ge32_op_burst = 207 +TA_PERF_SEL_buffer_flat_1_op_burst = 208 +TA_PERF_SEL_buffer_flat_2to3_op_burst = 209 +TA_PERF_SEL_buffer_flat_4to31_op_burst = 210 +TA_PERF_SEL_buffer_flat_ge32_op_burst = 211 +TA_PERF_SEL_write_1_op_burst = 212 +TA_PERF_SEL_write_2to3_op_burst = 213 +TA_PERF_SEL_write_4to31_op_burst = 214 +TA_PERF_SEL_write_ge32_op_burst = 215 +TA_PERF_SEL_ibubble_1_cycle_burst = 216 +TA_PERF_SEL_ibubble_2to3_cycle_burst = 217 +TA_PERF_SEL_ibubble_4to15_cycle_burst = 218 +TA_PERF_SEL_ibubble_16to31_cycle_burst = 219 +TA_PERF_SEL_ibubble_32to63_cycle_burst = 220 +TA_PERF_SEL_ibubble_ge64_cycle_burst = 221 +TA_PERF_SEL_sampler_clk_valid_cycles = 224 +TA_PERF_SEL_nonsampler_clk_valid_cycles = 225 +TA_PERF_SEL_buffer_flat_clk_valid_cycles = 226 +TA_PERF_SEL_write_data_clk_valid_cycles = 227 +TA_PERF_SEL_gradient_clk_valid_cycles = 228 +TA_PERF_SEL_lod_aniso_clk_valid_cycles = 229 +TA_PERF_SEL_sampler_addressing_clk_valid_cycles = 230 +TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles = 231 +TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles = 232 +TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles = 233 +TA_PERF_SEL_aligner_clk_valid_cycles = 234 +TA_PERF_SEL_tcreq_clk_valid_cycles = 235 +TA_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BC_SWIZZLE' +TEX_BC_SWIZZLE__enumvalues = { + 0: 'TEX_BC_Swizzle_XYZW', + 1: 'TEX_BC_Swizzle_XWYZ', + 2: 'TEX_BC_Swizzle_WZYX', + 3: 'TEX_BC_Swizzle_WXYZ', + 4: 'TEX_BC_Swizzle_ZYXW', + 5: 'TEX_BC_Swizzle_YXWZ', +} +TEX_BC_Swizzle_XYZW = 0 +TEX_BC_Swizzle_XWYZ = 1 +TEX_BC_Swizzle_WZYX = 2 +TEX_BC_Swizzle_WXYZ = 3 +TEX_BC_Swizzle_ZYXW = 4 +TEX_BC_Swizzle_YXWZ = 5 +TEX_BC_SWIZZLE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BORDER_COLOR_TYPE' +TEX_BORDER_COLOR_TYPE__enumvalues = { + 0: 'TEX_BorderColor_TransparentBlack', + 1: 'TEX_BorderColor_OpaqueBlack', + 2: 'TEX_BorderColor_OpaqueWhite', + 3: 'TEX_BorderColor_Register', +} +TEX_BorderColor_TransparentBlack = 0 +TEX_BorderColor_OpaqueBlack = 1 +TEX_BorderColor_OpaqueWhite = 2 +TEX_BorderColor_Register = 3 +TEX_BORDER_COLOR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CHROMA_KEY' +TEX_CHROMA_KEY__enumvalues = { + 0: 'TEX_ChromaKey_Disabled', + 1: 'TEX_ChromaKey_Kill', + 2: 'TEX_ChromaKey_Blend', + 3: 'TEX_ChromaKey_RESERVED_3', +} +TEX_ChromaKey_Disabled = 0 +TEX_ChromaKey_Kill = 1 +TEX_ChromaKey_Blend = 2 +TEX_ChromaKey_RESERVED_3 = 3 +TEX_CHROMA_KEY = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CLAMP' +TEX_CLAMP__enumvalues = { + 0: 'TEX_Clamp_Repeat', + 1: 'TEX_Clamp_Mirror', + 2: 'TEX_Clamp_ClampToLast', + 3: 'TEX_Clamp_MirrorOnceToLast', + 4: 'TEX_Clamp_ClampHalfToBorder', + 5: 'TEX_Clamp_MirrorOnceHalfToBorder', + 6: 'TEX_Clamp_ClampToBorder', + 7: 'TEX_Clamp_MirrorOnceToBorder', +} +TEX_Clamp_Repeat = 0 +TEX_Clamp_Mirror = 1 +TEX_Clamp_ClampToLast = 2 +TEX_Clamp_MirrorOnceToLast = 3 +TEX_Clamp_ClampHalfToBorder = 4 +TEX_Clamp_MirrorOnceHalfToBorder = 5 +TEX_Clamp_ClampToBorder = 6 +TEX_Clamp_MirrorOnceToBorder = 7 +TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_COORD_TYPE' +TEX_COORD_TYPE__enumvalues = { + 0: 'TEX_CoordType_Unnormalized', + 1: 'TEX_CoordType_Normalized', +} +TEX_CoordType_Unnormalized = 0 +TEX_CoordType_Normalized = 1 +TEX_COORD_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DEPTH_COMPARE_FUNCTION' +TEX_DEPTH_COMPARE_FUNCTION__enumvalues = { + 0: 'TEX_DepthCompareFunction_Never', + 1: 'TEX_DepthCompareFunction_Less', + 2: 'TEX_DepthCompareFunction_Equal', + 3: 'TEX_DepthCompareFunction_LessEqual', + 4: 'TEX_DepthCompareFunction_Greater', + 5: 'TEX_DepthCompareFunction_NotEqual', + 6: 'TEX_DepthCompareFunction_GreaterEqual', + 7: 'TEX_DepthCompareFunction_Always', +} +TEX_DepthCompareFunction_Never = 0 +TEX_DepthCompareFunction_Less = 1 +TEX_DepthCompareFunction_Equal = 2 +TEX_DepthCompareFunction_LessEqual = 3 +TEX_DepthCompareFunction_Greater = 4 +TEX_DepthCompareFunction_NotEqual = 5 +TEX_DepthCompareFunction_GreaterEqual = 6 +TEX_DepthCompareFunction_Always = 7 +TEX_DEPTH_COMPARE_FUNCTION = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_FORMAT_COMP' +TEX_FORMAT_COMP__enumvalues = { + 0: 'TEX_FormatComp_Unsigned', + 1: 'TEX_FormatComp_Signed', + 2: 'TEX_FormatComp_UnsignedBiased', + 3: 'TEX_FormatComp_RESERVED_3', +} +TEX_FormatComp_Unsigned = 0 +TEX_FormatComp_Signed = 1 +TEX_FormatComp_UnsignedBiased = 2 +TEX_FormatComp_RESERVED_3 = 3 +TEX_FORMAT_COMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MAX_ANISO_RATIO' +TEX_MAX_ANISO_RATIO__enumvalues = { + 0: 'TEX_MaxAnisoRatio_1to1', + 1: 'TEX_MaxAnisoRatio_2to1', + 2: 'TEX_MaxAnisoRatio_4to1', + 3: 'TEX_MaxAnisoRatio_8to1', + 4: 'TEX_MaxAnisoRatio_16to1', + 5: 'TEX_MaxAnisoRatio_RESERVED_5', + 6: 'TEX_MaxAnisoRatio_RESERVED_6', + 7: 'TEX_MaxAnisoRatio_RESERVED_7', +} +TEX_MaxAnisoRatio_1to1 = 0 +TEX_MaxAnisoRatio_2to1 = 1 +TEX_MaxAnisoRatio_4to1 = 2 +TEX_MaxAnisoRatio_8to1 = 3 +TEX_MaxAnisoRatio_16to1 = 4 +TEX_MaxAnisoRatio_RESERVED_5 = 5 +TEX_MaxAnisoRatio_RESERVED_6 = 6 +TEX_MaxAnisoRatio_RESERVED_7 = 7 +TEX_MAX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MIP_FILTER' +TEX_MIP_FILTER__enumvalues = { + 0: 'TEX_MipFilter_None', + 1: 'TEX_MipFilter_Point', + 2: 'TEX_MipFilter_Linear', + 3: 'TEX_MipFilter_Point_Aniso_Adj', +} +TEX_MipFilter_None = 0 +TEX_MipFilter_Point = 1 +TEX_MipFilter_Linear = 2 +TEX_MipFilter_Point_Aniso_Adj = 3 +TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_REQUEST_SIZE' +TEX_REQUEST_SIZE__enumvalues = { + 0: 'TEX_RequestSize_32B', + 1: 'TEX_RequestSize_64B', + 2: 'TEX_RequestSize_128B', + 3: 'TEX_RequestSize_2X64B', +} +TEX_RequestSize_32B = 0 +TEX_RequestSize_64B = 1 +TEX_RequestSize_128B = 2 +TEX_RequestSize_2X64B = 3 +TEX_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_SAMPLER_TYPE' +TEX_SAMPLER_TYPE__enumvalues = { + 0: 'TEX_SamplerType_Invalid', + 1: 'TEX_SamplerType_Valid', +} +TEX_SamplerType_Invalid = 0 +TEX_SamplerType_Valid = 1 +TEX_SAMPLER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_XY_FILTER' +TEX_XY_FILTER__enumvalues = { + 0: 'TEX_XYFilter_Point', + 1: 'TEX_XYFilter_Linear', + 2: 'TEX_XYFilter_AnisoPoint', + 3: 'TEX_XYFilter_AnisoLinear', +} +TEX_XYFilter_Point = 0 +TEX_XYFilter_Linear = 1 +TEX_XYFilter_AnisoPoint = 2 +TEX_XYFilter_AnisoLinear = 3 +TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_Z_FILTER' +TEX_Z_FILTER__enumvalues = { + 0: 'TEX_ZFilter_None', + 1: 'TEX_ZFilter_Point', + 2: 'TEX_ZFilter_Linear', + 3: 'TEX_ZFilter_RESERVED_3', +} +TEX_ZFilter_None = 0 +TEX_ZFilter_Point = 1 +TEX_ZFilter_Linear = 2 +TEX_ZFilter_RESERVED_3 = 3 +TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_TYPE' +TVX_TYPE__enumvalues = { + 0: 'TVX_Type_InvalidTextureResource', + 1: 'TVX_Type_InvalidVertexBuffer', + 2: 'TVX_Type_ValidTextureResource', + 3: 'TVX_Type_ValidVertexBuffer', +} +TVX_Type_InvalidTextureResource = 0 +TVX_Type_InvalidVertexBuffer = 1 +TVX_Type_ValidTextureResource = 2 +TVX_Type_ValidVertexBuffer = 3 +TVX_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_ADDR_MODES' +TA_TC_ADDR_MODES__enumvalues = { + 0: 'TA_TC_ADDR_MODE_DEFAULT', + 1: 'TA_TC_ADDR_MODE_COMP0', + 2: 'TA_TC_ADDR_MODE_COMP1', + 3: 'TA_TC_ADDR_MODE_COMP2', + 4: 'TA_TC_ADDR_MODE_COMP3', + 5: 'TA_TC_ADDR_MODE_UNALIGNED', + 6: 'TA_TC_ADDR_MODE_BORDER_COLOR', +} +TA_TC_ADDR_MODE_DEFAULT = 0 +TA_TC_ADDR_MODE_COMP0 = 1 +TA_TC_ADDR_MODE_COMP1 = 2 +TA_TC_ADDR_MODE_COMP2 = 3 +TA_TC_ADDR_MODE_COMP3 = 4 +TA_TC_ADDR_MODE_UNALIGNED = 5 +TA_TC_ADDR_MODE_BORDER_COLOR = 6 +TA_TC_ADDR_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_REQ_MODES' +TA_TC_REQ_MODES__enumvalues = { + 0: 'TA_TC_REQ_MODE_BORDER', + 1: 'TA_TC_REQ_MODE_TEX2', + 2: 'TA_TC_REQ_MODE_TEX1', + 3: 'TA_TC_REQ_MODE_TEX0', + 4: 'TA_TC_REQ_MODE_NORMAL', + 5: 'TA_TC_REQ_MODE_DWORD', + 6: 'TA_TC_REQ_MODE_BYTE', + 7: 'TA_TC_REQ_MODE_BYTE_NV', +} +TA_TC_REQ_MODE_BORDER = 0 +TA_TC_REQ_MODE_TEX2 = 1 +TA_TC_REQ_MODE_TEX1 = 2 +TA_TC_REQ_MODE_TEX0 = 3 +TA_TC_REQ_MODE_NORMAL = 4 +TA_TC_REQ_MODE_DWORD = 5 +TA_TC_REQ_MODE_BYTE = 6 +TA_TC_REQ_MODE_BYTE_NV = 7 +TA_TC_REQ_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_POLICIES' +TCP_CACHE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_POLICY_MISS_LRU', + 1: 'TCP_CACHE_POLICY_MISS_EVICT', + 2: 'TCP_CACHE_POLICY_HIT_LRU', + 3: 'TCP_CACHE_POLICY_HIT_EVICT', +} +TCP_CACHE_POLICY_MISS_LRU = 0 +TCP_CACHE_POLICY_MISS_EVICT = 1 +TCP_CACHE_POLICY_HIT_LRU = 2 +TCP_CACHE_POLICY_HIT_EVICT = 3 +TCP_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_STORE_POLICIES' +TCP_CACHE_STORE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_STORE_POLICY_WT_LRU', + 1: 'TCP_CACHE_STORE_POLICY_WT_EVICT', +} +TCP_CACHE_STORE_POLICY_WT_LRU = 0 +TCP_CACHE_STORE_POLICY_WT_EVICT = 1 +TCP_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_DATA_SEL' +TCP_DSM_DATA_SEL__enumvalues = { + 0: 'TCP_DSM_DISABLE', + 1: 'TCP_DSM_SEL0', + 2: 'TCP_DSM_SEL1', + 3: 'TCP_DSM_SEL_BOTH', +} +TCP_DSM_DISABLE = 0 +TCP_DSM_SEL0 = 1 +TCP_DSM_SEL1 = 2 +TCP_DSM_SEL_BOTH = 3 +TCP_DSM_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_INJECT_SEL' +TCP_DSM_INJECT_SEL__enumvalues = { + 0: 'TCP_DSM_INJECT_SEL0', + 1: 'TCP_DSM_INJECT_SEL1', + 2: 'TCP_DSM_INJECT_SEL2', + 3: 'TCP_DSM_INJECT_SEL3', +} +TCP_DSM_INJECT_SEL0 = 0 +TCP_DSM_INJECT_SEL1 = 1 +TCP_DSM_INJECT_SEL2 = 2 +TCP_DSM_INJECT_SEL3 = 3 +TCP_DSM_INJECT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_SINGLE_WRITE' +TCP_DSM_SINGLE_WRITE__enumvalues = { + 0: 'TCP_DSM_SINGLE_WRITE_DIS', + 1: 'TCP_DSM_SINGLE_WRITE_EN', +} +TCP_DSM_SINGLE_WRITE_DIS = 0 +TCP_DSM_SINGLE_WRITE_EN = 1 +TCP_DSM_SINGLE_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_OPCODE_TYPE' +TCP_OPCODE_TYPE__enumvalues = { + 0: 'TCP_OPCODE_READ', + 1: 'TCP_OPCODE_WRITE', + 2: 'TCP_OPCODE_ATOMIC', + 3: 'TCP_OPCODE_INV', + 4: 'TCP_OPCODE_ATOMIC_CMPSWAP', + 5: 'TCP_OPCODE_SAMPLER', + 6: 'TCP_OPCODE_LOAD', + 7: 'TCP_OPCODE_GATHERH', +} +TCP_OPCODE_READ = 0 +TCP_OPCODE_WRITE = 1 +TCP_OPCODE_ATOMIC = 2 +TCP_OPCODE_INV = 3 +TCP_OPCODE_ATOMIC_CMPSWAP = 4 +TCP_OPCODE_SAMPLER = 5 +TCP_OPCODE_LOAD = 6 +TCP_OPCODE_GATHERH = 7 +TCP_OPCODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_PERFCOUNT_SELECT' +TCP_PERFCOUNT_SELECT__enumvalues = { + 0: 'TCP_PERF_SEL_GATE_EN1', + 1: 'TCP_PERF_SEL_GATE_EN2', + 2: 'TCP_PERF_SEL_TA_REQ', + 3: 'TCP_PERF_SEL_TA_REQ_STATE_READ', + 4: 'TCP_PERF_SEL_TA_REQ_READ', + 5: 'TCP_PERF_SEL_TA_REQ_WRITE', + 6: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', + 7: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 8: 'TCP_PERF_SEL_TA_REQ_GL0_INV', + 9: 'TCP_PERF_SEL_REQ', + 10: 'TCP_PERF_SEL_REQ_READ', + 11: 'TCP_PERF_SEL_REQ_READ_HIT_EVICT', + 12: 'TCP_PERF_SEL_REQ_READ_HIT_LRU', + 13: 'TCP_PERF_SEL_REQ_READ_MISS_EVICT', + 14: 'TCP_PERF_SEL_REQ_WRITE', + 15: 'TCP_PERF_SEL_REQ_WRITE_MISS_EVICT', + 16: 'TCP_PERF_SEL_REQ_WRITE_MISS_LRU', + 17: 'TCP_PERF_SEL_REQ_NON_READ', + 18: 'TCP_PERF_SEL_REQ_MISS', + 19: 'TCP_PERF_SEL_REQ_TAGBANK0_SET0', + 20: 'TCP_PERF_SEL_REQ_TAGBANK0_SET1', + 21: 'TCP_PERF_SEL_REQ_TAGBANK1_SET0', + 22: 'TCP_PERF_SEL_REQ_TAGBANK1_SET1', + 23: 'TCP_PERF_SEL_REQ_TAGBANK2_SET0', + 24: 'TCP_PERF_SEL_REQ_TAGBANK2_SET1', + 25: 'TCP_PERF_SEL_REQ_TAGBANK3_SET0', + 26: 'TCP_PERF_SEL_REQ_TAGBANK3_SET1', + 27: 'TCP_PERF_SEL_REQ_MISS_TAGBANK0', + 28: 'TCP_PERF_SEL_REQ_MISS_TAGBANK1', + 29: 'TCP_PERF_SEL_REQ_MISS_TAGBANK2', + 30: 'TCP_PERF_SEL_REQ_MISS_TAGBANK3', + 31: 'TCP_PERF_SEL_GL1_REQ_READ', + 32: 'TCP_PERF_SEL_GL1_REQ_READ_128B', + 33: 'TCP_PERF_SEL_GL1_REQ_READ_64B', + 34: 'TCP_PERF_SEL_GL1_REQ_WRITE', + 35: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', + 36: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 37: 'TCP_PERF_SEL_GL1_READ_LATENCY', + 38: 'TCP_PERF_SEL_GL1_WRITE_LATENCY', + 39: 'TCP_PERF_SEL_TCP_LATENCY', + 40: 'TCP_PERF_SEL_TCP_TA_REQ_STALL', + 41: 'TCP_PERF_SEL_TA_TCP_REQ_STARVE', + 42: 'TCP_PERF_SEL_DATA_FIFO_STALL', + 43: 'TCP_PERF_SEL_LOD_STALL', + 44: 'TCP_PERF_SEL_POWER_STALL', + 45: 'TCP_PERF_SEL_ALLOC_STALL', + 46: 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 47: 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL', + 48: 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL', + 49: 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL', + 50: 'TCP_PERF_SEL_LFIFO_STALL', + 51: 'TCP_PERF_SEL_MEM_REQ_FIFO_STALL', + 52: 'TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE', + 53: 'TCP_PERF_SEL_GL1_TCP_RDRET_STALL', + 54: 'TCP_PERF_SEL_GL1_GRANT_READ_STALL', + 55: 'TCP_PERF_SEL_GL1_PENDING_STALL', + 56: 'TCP_PERF_SEL_OFIFO_INCOMPLETE_STALL', + 57: 'TCP_PERF_SEL_OFIFO_AGE_ORDER_STALL', + 58: 'TCP_PERF_SEL_TD_DATA_CYCLE_STALL', + 59: 'TCP_PERF_SEL_COMP_TEX_LOAD_STALL', + 60: 'TCP_PERF_SEL_READ_DATACONFLICT_STALL', + 61: 'TCP_PERF_SEL_WRITE_DATACONFLICT_STALL', + 62: 'TCP_PERF_SEL_TD_TCP_STALL', +} +TCP_PERF_SEL_GATE_EN1 = 0 +TCP_PERF_SEL_GATE_EN2 = 1 +TCP_PERF_SEL_TA_REQ = 2 +TCP_PERF_SEL_TA_REQ_STATE_READ = 3 +TCP_PERF_SEL_TA_REQ_READ = 4 +TCP_PERF_SEL_TA_REQ_WRITE = 5 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET = 6 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET = 7 +TCP_PERF_SEL_TA_REQ_GL0_INV = 8 +TCP_PERF_SEL_REQ = 9 +TCP_PERF_SEL_REQ_READ = 10 +TCP_PERF_SEL_REQ_READ_HIT_EVICT = 11 +TCP_PERF_SEL_REQ_READ_HIT_LRU = 12 +TCP_PERF_SEL_REQ_READ_MISS_EVICT = 13 +TCP_PERF_SEL_REQ_WRITE = 14 +TCP_PERF_SEL_REQ_WRITE_MISS_EVICT = 15 +TCP_PERF_SEL_REQ_WRITE_MISS_LRU = 16 +TCP_PERF_SEL_REQ_NON_READ = 17 +TCP_PERF_SEL_REQ_MISS = 18 +TCP_PERF_SEL_REQ_TAGBANK0_SET0 = 19 +TCP_PERF_SEL_REQ_TAGBANK0_SET1 = 20 +TCP_PERF_SEL_REQ_TAGBANK1_SET0 = 21 +TCP_PERF_SEL_REQ_TAGBANK1_SET1 = 22 +TCP_PERF_SEL_REQ_TAGBANK2_SET0 = 23 +TCP_PERF_SEL_REQ_TAGBANK2_SET1 = 24 +TCP_PERF_SEL_REQ_TAGBANK3_SET0 = 25 +TCP_PERF_SEL_REQ_TAGBANK3_SET1 = 26 +TCP_PERF_SEL_REQ_MISS_TAGBANK0 = 27 +TCP_PERF_SEL_REQ_MISS_TAGBANK1 = 28 +TCP_PERF_SEL_REQ_MISS_TAGBANK2 = 29 +TCP_PERF_SEL_REQ_MISS_TAGBANK3 = 30 +TCP_PERF_SEL_GL1_REQ_READ = 31 +TCP_PERF_SEL_GL1_REQ_READ_128B = 32 +TCP_PERF_SEL_GL1_REQ_READ_64B = 33 +TCP_PERF_SEL_GL1_REQ_WRITE = 34 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET = 35 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET = 36 +TCP_PERF_SEL_GL1_READ_LATENCY = 37 +TCP_PERF_SEL_GL1_WRITE_LATENCY = 38 +TCP_PERF_SEL_TCP_LATENCY = 39 +TCP_PERF_SEL_TCP_TA_REQ_STALL = 40 +TCP_PERF_SEL_TA_TCP_REQ_STARVE = 41 +TCP_PERF_SEL_DATA_FIFO_STALL = 42 +TCP_PERF_SEL_LOD_STALL = 43 +TCP_PERF_SEL_POWER_STALL = 44 +TCP_PERF_SEL_ALLOC_STALL = 45 +TCP_PERF_SEL_UNORDERED_MTYPE_STALL = 46 +TCP_PERF_SEL_READ_TAGCONFLICT_STALL = 47 +TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL = 48 +TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL = 49 +TCP_PERF_SEL_LFIFO_STALL = 50 +TCP_PERF_SEL_MEM_REQ_FIFO_STALL = 51 +TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE = 52 +TCP_PERF_SEL_GL1_TCP_RDRET_STALL = 53 +TCP_PERF_SEL_GL1_GRANT_READ_STALL = 54 +TCP_PERF_SEL_GL1_PENDING_STALL = 55 +TCP_PERF_SEL_OFIFO_INCOMPLETE_STALL = 56 +TCP_PERF_SEL_OFIFO_AGE_ORDER_STALL = 57 +TCP_PERF_SEL_TD_DATA_CYCLE_STALL = 58 +TCP_PERF_SEL_COMP_TEX_LOAD_STALL = 59 +TCP_PERF_SEL_READ_DATACONFLICT_STALL = 60 +TCP_PERF_SEL_WRITE_DATACONFLICT_STALL = 61 +TCP_PERF_SEL_TD_TCP_STALL = 62 +TCP_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_WATCH_MODES' +TCP_WATCH_MODES__enumvalues = { + 0: 'TCP_WATCH_MODE_READ', + 1: 'TCP_WATCH_MODE_NONREAD', + 2: 'TCP_WATCH_MODE_ATOMIC', + 3: 'TCP_WATCH_MODE_ALL', +} +TCP_WATCH_MODE_READ = 0 +TCP_WATCH_MODE_NONREAD = 1 +TCP_WATCH_MODE_ATOMIC = 2 +TCP_WATCH_MODE_ALL = 3 +TCP_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TD_PERFCOUNT_SEL' +TD_PERFCOUNT_SEL__enumvalues = { + 0: 'TD_PERF_SEL_none', + 1: 'TD_PERF_SEL_td_busy', + 2: 'TD_PERF_SEL_input_busy', + 3: 'TD_PERF_SEL_sampler_lerp_busy', + 4: 'TD_PERF_SEL_sampler_out_busy', + 5: 'TD_PERF_SEL_nofilter_busy', + 6: 'TD_PERF_SEL_ray_tracing_bvh4_busy', + 7: 'TD_PERF_SEL_sampler_core_sclk_en', + 8: 'TD_PERF_SEL_sampler_preformatter_sclk_en', + 9: 'TD_PERF_SEL_sampler_bilerp_sclk_en', + 10: 'TD_PERF_SEL_sampler_bypass_sclk_en', + 11: 'TD_PERF_SEL_sampler_minmax_sclk_en', + 12: 'TD_PERF_SEL_sampler_accum_sclk_en', + 13: 'TD_PERF_SEL_sampler_format_flt_sclk_en', + 14: 'TD_PERF_SEL_sampler_format_fxdpt_sclk_en', + 15: 'TD_PERF_SEL_sampler_out_sclk_en', + 16: 'TD_PERF_SEL_nofilter_sclk_en', + 17: 'TD_PERF_SEL_nofilter_d32_sclk_en', + 18: 'TD_PERF_SEL_nofilter_d16_sclk_en', + 22: 'TD_PERF_SEL_ray_tracing_bvh4_sclk_en', + 23: 'TD_PERF_SEL_ray_tracing_bvh4_ip_sclk_en', + 24: 'TD_PERF_SEL_ray_tracing_bvh4_box_sclk_en', + 25: 'TD_PERF_SEL_ray_tracing_bvh4_tri_sclk_en', + 26: 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 27: 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 28: 'TD_PERF_SEL_all_pipes_sclk_on_at_same_time', + 29: 'TD_PERF_SEL_sampler_and_nofilter_sclk_on_bvh4_sclk_off', + 30: 'TD_PERF_SEL_sampler_and_bvh4_sclk_on_nofilter_sclk_off', + 31: 'TD_PERF_SEL_nofilter_and_bvh4_sclk_on_sampler_sclk_off', + 32: 'TD_PERF_SEL_core_state_ram_max_cnt', + 33: 'TD_PERF_SEL_core_state_rams_read', + 34: 'TD_PERF_SEL_weight_data_rams_read', + 35: 'TD_PERF_SEL_reference_data_rams_read', + 36: 'TD_PERF_SEL_tc_td_ram_fifo_full', + 37: 'TD_PERF_SEL_tc_td_ram_fifo_max_cnt', + 38: 'TD_PERF_SEL_tc_td_data_fifo_full', + 39: 'TD_PERF_SEL_input_state_fifo_full', + 40: 'TD_PERF_SEL_ta_data_stall', + 41: 'TD_PERF_SEL_tc_data_stall', + 42: 'TD_PERF_SEL_tc_ram_stall', + 43: 'TD_PERF_SEL_lds_stall', + 44: 'TD_PERF_SEL_sampler_pkr_full', + 45: 'TD_PERF_SEL_sampler_pkr_full_due_to_arb', + 46: 'TD_PERF_SEL_nofilter_pkr_full', + 47: 'TD_PERF_SEL_nofilter_pkr_full_due_to_arb', + 48: 'TD_PERF_SEL_ray_tracing_bvh4_pkr_full', + 49: 'TD_PERF_SEL_ray_tracing_bvh4_pkr_full_due_to_arb', + 50: 'TD_PERF_SEL_gather4_instr', + 51: 'TD_PERF_SEL_gather4h_instr', + 54: 'TD_PERF_SEL_sample_instr', + 55: 'TD_PERF_SEL_sample_c_instr', + 56: 'TD_PERF_SEL_load_instr', + 57: 'TD_PERF_SEL_ldfptr_instr', + 58: 'TD_PERF_SEL_write_ack_instr', + 59: 'TD_PERF_SEL_d16_en_instr', + 60: 'TD_PERF_SEL_bypassLerp_instr', + 61: 'TD_PERF_SEL_min_max_filter_instr', + 62: 'TD_PERF_SEL_one_comp_return_instr', + 63: 'TD_PERF_SEL_two_comp_return_instr', + 64: 'TD_PERF_SEL_three_comp_return_instr', + 65: 'TD_PERF_SEL_four_comp_return_instr', + 66: 'TD_PERF_SEL_user_defined_border', + 67: 'TD_PERF_SEL_white_border', + 68: 'TD_PERF_SEL_opaque_black_border', + 69: 'TD_PERF_SEL_lod_warn_from_ta', + 70: 'TD_PERF_SEL_instruction_dest_is_lds', + 71: 'TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles', + 72: 'TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles', + 73: 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles', + 74: 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles', + 75: 'TD_PERF_SEL_out_of_order_instr', + 76: 'TD_PERF_SEL_total_num_instr', + 77: 'TD_PERF_SEL_total_num_instr_with_perf_wdw', + 78: 'TD_PERF_SEL_total_num_sampler_instr', + 79: 'TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw', + 80: 'TD_PERF_SEL_total_num_nofilter_instr', + 81: 'TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw', + 82: 'TD_PERF_SEL_total_num_ray_tracing_bvh4_instr', + 83: 'TD_PERF_SEL_total_num_ray_tracing_bvh4_instr_with_perf_wdw', + 84: 'TD_PERF_SEL_mixmode_instr', + 85: 'TD_PERF_SEL_mixmode_resource', + 86: 'TD_PERF_SEL_status_packet', + 87: 'TD_PERF_SEL_address_cmd_poison', + 88: 'TD_PERF_SEL_data_poison', + 89: 'TD_PERF_SEL_done_scoreboard_max_stored_cnt', + 90: 'TD_PERF_SEL_done_scoreboard_max_waiting_cnt', + 91: 'TD_PERF_SEL_done_scoreboard_not_empty', + 92: 'TD_PERF_SEL_done_scoreboard_is_full', + 93: 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 94: 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 95: 'TD_PERF_SEL_nofilter_formatters_turned_on', + 96: 'TD_PERF_SEL_nofilter_insert_extra_comps', + 97: 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 98: 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', + 99: 'TD_PERF_SEL_msaa_load_instr', + 100: 'TD_PERF_SEL_blend_prt_with_prt_default_0', + 101: 'TD_PERF_SEL_blend_prt_with_prt_default_1', + 102: 'TD_PERF_SEL_resmap_instr', + 103: 'TD_PERF_SEL_prt_ack_instr', + 104: 'TD_PERF_SEL_resmap_with_volume_filtering', + 105: 'TD_PERF_SEL_resmap_with_aniso_filtering', + 106: 'TD_PERF_SEL_resmap_with_no_more_filtering', + 107: 'TD_PERF_SEL_resmap_with_cubemap_corner', + 108: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_0', + 109: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_1', + 110: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_2', + 111: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_3to4', + 112: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_5to8', + 113: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_9to16', + 114: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_17to31', + 115: 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_32', + 116: 'TD_PERF_SEL_ray_tracing_bvh4_fp16_box_node', + 117: 'TD_PERF_SEL_ray_tracing_bvh4_fp32_box_node', + 118: 'TD_PERF_SEL_ray_tracing_bvh4_tri_node', + 119: 'TD_PERF_SEL_ray_tracing_bvh4_dropped_box_node', + 120: 'TD_PERF_SEL_ray_tracing_bvh4_dropped_tri_node', + 121: 'TD_PERF_SEL_ray_tracing_bvh4_invalid_box_node', + 122: 'TD_PERF_SEL_ray_tracing_bvh4_invalid_tri_node', + 123: 'TD_PERF_SEL_ray_tracing_bvh4_box_sort_en', + 124: 'TD_PERF_SEL_ray_tracing_bvh4_box_grow_val_nonzero', + 125: 'TD_PERF_SEL_ray_tracing_bvh4_num_box_with_inf_or_nan_vtx', + 126: 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_with_inf_or_nan_vtx', + 127: 'TD_PERF_SEL_ray_tracing_bvh4_num_box_that_squashed_a_nan', + 128: 'TD_PERF_SEL_ray_tracing_bvh4_num_box_misses', + 129: 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_misses', + 130: 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_tie_breakers', + 131: 'TD_PERF_SEL_burst_bin_preempting_nofilter_1', + 132: 'TD_PERF_SEL_burst_bin_preempting_nofilter_2to4', + 133: 'TD_PERF_SEL_burst_bin_preempting_nofilter_5to7', + 134: 'TD_PERF_SEL_burst_bin_preempting_nofilter_8to16', + 135: 'TD_PERF_SEL_burst_bin_preempting_nofilter_gt16', + 136: 'TD_PERF_SEL_burst_bin_sampler_1', + 137: 'TD_PERF_SEL_burst_bin_sampler_2to8', + 138: 'TD_PERF_SEL_burst_bin_sampler_9to16', + 139: 'TD_PERF_SEL_burst_bin_sampler_gt16', + 140: 'TD_PERF_SEL_burst_bin_gather_1', + 141: 'TD_PERF_SEL_burst_bin_gather_2to8', + 142: 'TD_PERF_SEL_burst_bin_gather_9to16', + 143: 'TD_PERF_SEL_burst_bin_gather_gt16', + 144: 'TD_PERF_SEL_burst_bin_nofilter_1', + 145: 'TD_PERF_SEL_burst_bin_nofilter_2to4', + 146: 'TD_PERF_SEL_burst_bin_nofilter_5to7', + 147: 'TD_PERF_SEL_burst_bin_nofilter_8to16', + 148: 'TD_PERF_SEL_burst_bin_nofilter_gt16', + 149: 'TD_PERF_SEL_burst_bin_bvh4_1', + 150: 'TD_PERF_SEL_burst_bin_bvh4_2to8', + 151: 'TD_PERF_SEL_burst_bin_bvh4_9to16', + 152: 'TD_PERF_SEL_burst_bin_bvh4_gt16', + 153: 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_1', + 154: 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_2to4', + 155: 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_5to7', + 156: 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_8to16', + 157: 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_gt16', + 158: 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_1', + 159: 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_2to8', + 160: 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_9to16', + 161: 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_gt16', + 162: 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_1', + 163: 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_2to8', + 164: 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_9to16', + 165: 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_gt16', + 166: 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_1', + 167: 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_2to8', + 168: 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_9to16', + 169: 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_gt16', + 170: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0', + 171: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1', + 172: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31', + 173: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127', + 174: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511', + 175: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511', + 176: 'TD_PERF_SEL_bubble_bin_lds_stall_1to3', + 177: 'TD_PERF_SEL_bubble_bin_lds_stall_4to7', + 178: 'TD_PERF_SEL_bubble_bin_lds_stall_8to15', + 179: 'TD_PERF_SEL_bubble_bin_lds_stall_gt15', + 180: 'TD_PERF_SEL_preempting_nofilter_max_cnt', + 181: 'TD_PERF_SEL_sampler_lerp0_active', + 182: 'TD_PERF_SEL_sampler_lerp1_active', + 183: 'TD_PERF_SEL_sampler_lerp2_active', + 184: 'TD_PERF_SEL_sampler_lerp3_active', + 185: 'TD_PERF_SEL_nofilter_total_num_comps_to_lds', + 186: 'TD_PERF_SEL_nofilter_byte_cycling_4cycles', + 187: 'TD_PERF_SEL_nofilter_byte_cycling_8cycles', + 188: 'TD_PERF_SEL_nofilter_byte_cycling_16cycles', + 189: 'TD_PERF_SEL_nofilter_dword_cycling_2cycles', + 190: 'TD_PERF_SEL_nofilter_dword_cycling_4cycles', + 191: 'TD_PERF_SEL_input_bp_due_to_done_scoreboard_full', + 192: 'TD_PERF_SEL_ray_tracing_bvh4_instr_invld_thread_cnt', +} +TD_PERF_SEL_none = 0 +TD_PERF_SEL_td_busy = 1 +TD_PERF_SEL_input_busy = 2 +TD_PERF_SEL_sampler_lerp_busy = 3 +TD_PERF_SEL_sampler_out_busy = 4 +TD_PERF_SEL_nofilter_busy = 5 +TD_PERF_SEL_ray_tracing_bvh4_busy = 6 +TD_PERF_SEL_sampler_core_sclk_en = 7 +TD_PERF_SEL_sampler_preformatter_sclk_en = 8 +TD_PERF_SEL_sampler_bilerp_sclk_en = 9 +TD_PERF_SEL_sampler_bypass_sclk_en = 10 +TD_PERF_SEL_sampler_minmax_sclk_en = 11 +TD_PERF_SEL_sampler_accum_sclk_en = 12 +TD_PERF_SEL_sampler_format_flt_sclk_en = 13 +TD_PERF_SEL_sampler_format_fxdpt_sclk_en = 14 +TD_PERF_SEL_sampler_out_sclk_en = 15 +TD_PERF_SEL_nofilter_sclk_en = 16 +TD_PERF_SEL_nofilter_d32_sclk_en = 17 +TD_PERF_SEL_nofilter_d16_sclk_en = 18 +TD_PERF_SEL_ray_tracing_bvh4_sclk_en = 22 +TD_PERF_SEL_ray_tracing_bvh4_ip_sclk_en = 23 +TD_PERF_SEL_ray_tracing_bvh4_box_sclk_en = 24 +TD_PERF_SEL_ray_tracing_bvh4_tri_sclk_en = 25 +TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off = 26 +TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off = 27 +TD_PERF_SEL_all_pipes_sclk_on_at_same_time = 28 +TD_PERF_SEL_sampler_and_nofilter_sclk_on_bvh4_sclk_off = 29 +TD_PERF_SEL_sampler_and_bvh4_sclk_on_nofilter_sclk_off = 30 +TD_PERF_SEL_nofilter_and_bvh4_sclk_on_sampler_sclk_off = 31 +TD_PERF_SEL_core_state_ram_max_cnt = 32 +TD_PERF_SEL_core_state_rams_read = 33 +TD_PERF_SEL_weight_data_rams_read = 34 +TD_PERF_SEL_reference_data_rams_read = 35 +TD_PERF_SEL_tc_td_ram_fifo_full = 36 +TD_PERF_SEL_tc_td_ram_fifo_max_cnt = 37 +TD_PERF_SEL_tc_td_data_fifo_full = 38 +TD_PERF_SEL_input_state_fifo_full = 39 +TD_PERF_SEL_ta_data_stall = 40 +TD_PERF_SEL_tc_data_stall = 41 +TD_PERF_SEL_tc_ram_stall = 42 +TD_PERF_SEL_lds_stall = 43 +TD_PERF_SEL_sampler_pkr_full = 44 +TD_PERF_SEL_sampler_pkr_full_due_to_arb = 45 +TD_PERF_SEL_nofilter_pkr_full = 46 +TD_PERF_SEL_nofilter_pkr_full_due_to_arb = 47 +TD_PERF_SEL_ray_tracing_bvh4_pkr_full = 48 +TD_PERF_SEL_ray_tracing_bvh4_pkr_full_due_to_arb = 49 +TD_PERF_SEL_gather4_instr = 50 +TD_PERF_SEL_gather4h_instr = 51 +TD_PERF_SEL_sample_instr = 54 +TD_PERF_SEL_sample_c_instr = 55 +TD_PERF_SEL_load_instr = 56 +TD_PERF_SEL_ldfptr_instr = 57 +TD_PERF_SEL_write_ack_instr = 58 +TD_PERF_SEL_d16_en_instr = 59 +TD_PERF_SEL_bypassLerp_instr = 60 +TD_PERF_SEL_min_max_filter_instr = 61 +TD_PERF_SEL_one_comp_return_instr = 62 +TD_PERF_SEL_two_comp_return_instr = 63 +TD_PERF_SEL_three_comp_return_instr = 64 +TD_PERF_SEL_four_comp_return_instr = 65 +TD_PERF_SEL_user_defined_border = 66 +TD_PERF_SEL_white_border = 67 +TD_PERF_SEL_opaque_black_border = 68 +TD_PERF_SEL_lod_warn_from_ta = 69 +TD_PERF_SEL_instruction_dest_is_lds = 70 +TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles = 71 +TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles = 72 +TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles = 73 +TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles = 74 +TD_PERF_SEL_out_of_order_instr = 75 +TD_PERF_SEL_total_num_instr = 76 +TD_PERF_SEL_total_num_instr_with_perf_wdw = 77 +TD_PERF_SEL_total_num_sampler_instr = 78 +TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw = 79 +TD_PERF_SEL_total_num_nofilter_instr = 80 +TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw = 81 +TD_PERF_SEL_total_num_ray_tracing_bvh4_instr = 82 +TD_PERF_SEL_total_num_ray_tracing_bvh4_instr_with_perf_wdw = 83 +TD_PERF_SEL_mixmode_instr = 84 +TD_PERF_SEL_mixmode_resource = 85 +TD_PERF_SEL_status_packet = 86 +TD_PERF_SEL_address_cmd_poison = 87 +TD_PERF_SEL_data_poison = 88 +TD_PERF_SEL_done_scoreboard_max_stored_cnt = 89 +TD_PERF_SEL_done_scoreboard_max_waiting_cnt = 90 +TD_PERF_SEL_done_scoreboard_not_empty = 91 +TD_PERF_SEL_done_scoreboard_is_full = 92 +TD_PERF_SEL_done_scoreboard_bp_due_to_ooo = 93 +TD_PERF_SEL_done_scoreboard_bp_due_to_lds = 94 +TD_PERF_SEL_nofilter_formatters_turned_on = 95 +TD_PERF_SEL_nofilter_insert_extra_comps = 96 +TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt = 97 +TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt = 98 +TD_PERF_SEL_msaa_load_instr = 99 +TD_PERF_SEL_blend_prt_with_prt_default_0 = 100 +TD_PERF_SEL_blend_prt_with_prt_default_1 = 101 +TD_PERF_SEL_resmap_instr = 102 +TD_PERF_SEL_prt_ack_instr = 103 +TD_PERF_SEL_resmap_with_volume_filtering = 104 +TD_PERF_SEL_resmap_with_aniso_filtering = 105 +TD_PERF_SEL_resmap_with_no_more_filtering = 106 +TD_PERF_SEL_resmap_with_cubemap_corner = 107 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_0 = 108 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_1 = 109 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_2 = 110 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_3to4 = 111 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_5to8 = 112 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_9to16 = 113 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_17to31 = 114 +TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_32 = 115 +TD_PERF_SEL_ray_tracing_bvh4_fp16_box_node = 116 +TD_PERF_SEL_ray_tracing_bvh4_fp32_box_node = 117 +TD_PERF_SEL_ray_tracing_bvh4_tri_node = 118 +TD_PERF_SEL_ray_tracing_bvh4_dropped_box_node = 119 +TD_PERF_SEL_ray_tracing_bvh4_dropped_tri_node = 120 +TD_PERF_SEL_ray_tracing_bvh4_invalid_box_node = 121 +TD_PERF_SEL_ray_tracing_bvh4_invalid_tri_node = 122 +TD_PERF_SEL_ray_tracing_bvh4_box_sort_en = 123 +TD_PERF_SEL_ray_tracing_bvh4_box_grow_val_nonzero = 124 +TD_PERF_SEL_ray_tracing_bvh4_num_box_with_inf_or_nan_vtx = 125 +TD_PERF_SEL_ray_tracing_bvh4_num_tri_with_inf_or_nan_vtx = 126 +TD_PERF_SEL_ray_tracing_bvh4_num_box_that_squashed_a_nan = 127 +TD_PERF_SEL_ray_tracing_bvh4_num_box_misses = 128 +TD_PERF_SEL_ray_tracing_bvh4_num_tri_misses = 129 +TD_PERF_SEL_ray_tracing_bvh4_num_tri_tie_breakers = 130 +TD_PERF_SEL_burst_bin_preempting_nofilter_1 = 131 +TD_PERF_SEL_burst_bin_preempting_nofilter_2to4 = 132 +TD_PERF_SEL_burst_bin_preempting_nofilter_5to7 = 133 +TD_PERF_SEL_burst_bin_preempting_nofilter_8to16 = 134 +TD_PERF_SEL_burst_bin_preempting_nofilter_gt16 = 135 +TD_PERF_SEL_burst_bin_sampler_1 = 136 +TD_PERF_SEL_burst_bin_sampler_2to8 = 137 +TD_PERF_SEL_burst_bin_sampler_9to16 = 138 +TD_PERF_SEL_burst_bin_sampler_gt16 = 139 +TD_PERF_SEL_burst_bin_gather_1 = 140 +TD_PERF_SEL_burst_bin_gather_2to8 = 141 +TD_PERF_SEL_burst_bin_gather_9to16 = 142 +TD_PERF_SEL_burst_bin_gather_gt16 = 143 +TD_PERF_SEL_burst_bin_nofilter_1 = 144 +TD_PERF_SEL_burst_bin_nofilter_2to4 = 145 +TD_PERF_SEL_burst_bin_nofilter_5to7 = 146 +TD_PERF_SEL_burst_bin_nofilter_8to16 = 147 +TD_PERF_SEL_burst_bin_nofilter_gt16 = 148 +TD_PERF_SEL_burst_bin_bvh4_1 = 149 +TD_PERF_SEL_burst_bin_bvh4_2to8 = 150 +TD_PERF_SEL_burst_bin_bvh4_9to16 = 151 +TD_PERF_SEL_burst_bin_bvh4_gt16 = 152 +TD_PERF_SEL_burst_bin_bvh4_box_nodes_1 = 153 +TD_PERF_SEL_burst_bin_bvh4_box_nodes_2to4 = 154 +TD_PERF_SEL_burst_bin_bvh4_box_nodes_5to7 = 155 +TD_PERF_SEL_burst_bin_bvh4_box_nodes_8to16 = 156 +TD_PERF_SEL_burst_bin_bvh4_box_nodes_gt16 = 157 +TD_PERF_SEL_burst_bin_bvh4_tri_nodes_1 = 158 +TD_PERF_SEL_burst_bin_bvh4_tri_nodes_2to8 = 159 +TD_PERF_SEL_burst_bin_bvh4_tri_nodes_9to16 = 160 +TD_PERF_SEL_burst_bin_bvh4_tri_nodes_gt16 = 161 +TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_1 = 162 +TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_2to8 = 163 +TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_9to16 = 164 +TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_gt16 = 165 +TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_1 = 166 +TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_2to8 = 167 +TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_9to16 = 168 +TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_gt16 = 169 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0 = 170 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1 = 171 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31 = 172 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127 = 173 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511 = 174 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511 = 175 +TD_PERF_SEL_bubble_bin_lds_stall_1to3 = 176 +TD_PERF_SEL_bubble_bin_lds_stall_4to7 = 177 +TD_PERF_SEL_bubble_bin_lds_stall_8to15 = 178 +TD_PERF_SEL_bubble_bin_lds_stall_gt15 = 179 +TD_PERF_SEL_preempting_nofilter_max_cnt = 180 +TD_PERF_SEL_sampler_lerp0_active = 181 +TD_PERF_SEL_sampler_lerp1_active = 182 +TD_PERF_SEL_sampler_lerp2_active = 183 +TD_PERF_SEL_sampler_lerp3_active = 184 +TD_PERF_SEL_nofilter_total_num_comps_to_lds = 185 +TD_PERF_SEL_nofilter_byte_cycling_4cycles = 186 +TD_PERF_SEL_nofilter_byte_cycling_8cycles = 187 +TD_PERF_SEL_nofilter_byte_cycling_16cycles = 188 +TD_PERF_SEL_nofilter_dword_cycling_2cycles = 189 +TD_PERF_SEL_nofilter_dword_cycling_4cycles = 190 +TD_PERF_SEL_input_bp_due_to_done_scoreboard_full = 191 +TD_PERF_SEL_ray_tracing_bvh4_instr_invld_thread_cnt = 192 +TD_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL2A_PERF_SEL' +GL2A_PERF_SEL__enumvalues = { + 0: 'GL2A_PERF_SEL_NONE', + 1: 'GL2A_PERF_SEL_CYCLE', + 2: 'GL2A_PERF_SEL_BUSY', + 3: 'GL2A_PERF_SEL_REQ_GL2C0', + 4: 'GL2A_PERF_SEL_REQ_GL2C1', + 5: 'GL2A_PERF_SEL_REQ_GL2C2', + 6: 'GL2A_PERF_SEL_REQ_GL2C3', + 7: 'GL2A_PERF_SEL_REQ_GL2C4', + 8: 'GL2A_PERF_SEL_REQ_GL2C5', + 9: 'GL2A_PERF_SEL_REQ_GL2C6', + 10: 'GL2A_PERF_SEL_REQ_GL2C7', + 11: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0', + 12: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1', + 13: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2', + 14: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3', + 15: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4', + 16: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5', + 17: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6', + 18: 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7', + 19: 'GL2A_PERF_SEL_REQ_BURST_GL2C0', + 20: 'GL2A_PERF_SEL_REQ_BURST_GL2C1', + 21: 'GL2A_PERF_SEL_REQ_BURST_GL2C2', + 22: 'GL2A_PERF_SEL_REQ_BURST_GL2C3', + 23: 'GL2A_PERF_SEL_REQ_BURST_GL2C4', + 24: 'GL2A_PERF_SEL_REQ_BURST_GL2C5', + 25: 'GL2A_PERF_SEL_REQ_BURST_GL2C6', + 26: 'GL2A_PERF_SEL_REQ_BURST_GL2C7', + 27: 'GL2A_PERF_SEL_REQ_STALL_GL2C0', + 28: 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 29: 'GL2A_PERF_SEL_REQ_STALL_GL2C2', + 30: 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 31: 'GL2A_PERF_SEL_REQ_STALL_GL2C4', + 32: 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 33: 'GL2A_PERF_SEL_REQ_STALL_GL2C6', + 34: 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 35: 'GL2A_PERF_SEL_RTN_STALL_GL2C0', + 36: 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 37: 'GL2A_PERF_SEL_RTN_STALL_GL2C2', + 38: 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 39: 'GL2A_PERF_SEL_RTN_STALL_GL2C4', + 40: 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 41: 'GL2A_PERF_SEL_RTN_STALL_GL2C6', + 42: 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 43: 'GL2A_PERF_SEL_RTN_CLIENT0', + 44: 'GL2A_PERF_SEL_RTN_CLIENT1', + 45: 'GL2A_PERF_SEL_RTN_CLIENT2', + 46: 'GL2A_PERF_SEL_RTN_CLIENT3', + 47: 'GL2A_PERF_SEL_RTN_CLIENT4', + 48: 'GL2A_PERF_SEL_RTN_CLIENT5', + 49: 'GL2A_PERF_SEL_RTN_CLIENT6', + 50: 'GL2A_PERF_SEL_RTN_CLIENT7', + 51: 'GL2A_PERF_SEL_RTN_CLIENT8', + 52: 'GL2A_PERF_SEL_RTN_CLIENT9', + 53: 'GL2A_PERF_SEL_RTN_CLIENT10', + 54: 'GL2A_PERF_SEL_RTN_CLIENT11', + 55: 'GL2A_PERF_SEL_RTN_CLIENT12', + 56: 'GL2A_PERF_SEL_RTN_CLIENT13', + 57: 'GL2A_PERF_SEL_RTN_CLIENT14', + 58: 'GL2A_PERF_SEL_RTN_CLIENT15', + 59: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 60: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 61: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 62: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 63: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 64: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 65: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 66: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', + 67: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8', + 68: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9', + 69: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10', + 70: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11', + 71: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12', + 72: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13', + 73: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14', + 74: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15', + 75: 'GL2A_PERF_SEL_REQ_BURST_CLIENT0', + 76: 'GL2A_PERF_SEL_REQ_BURST_CLIENT1', + 77: 'GL2A_PERF_SEL_REQ_BURST_CLIENT2', + 78: 'GL2A_PERF_SEL_REQ_BURST_CLIENT3', + 79: 'GL2A_PERF_SEL_REQ_BURST_CLIENT4', + 80: 'GL2A_PERF_SEL_REQ_BURST_CLIENT5', + 81: 'GL2A_PERF_SEL_REQ_BURST_CLIENT6', + 82: 'GL2A_PERF_SEL_REQ_BURST_CLIENT7', + 83: 'GL2A_PERF_SEL_REQ_BURST_CLIENT8', + 84: 'GL2A_PERF_SEL_REQ_BURST_CLIENT9', + 85: 'GL2A_PERF_SEL_REQ_BURST_CLIENT10', + 86: 'GL2A_PERF_SEL_REQ_BURST_CLIENT11', + 87: 'GL2A_PERF_SEL_REQ_BURST_CLIENT12', + 88: 'GL2A_PERF_SEL_REQ_BURST_CLIENT13', + 89: 'GL2A_PERF_SEL_REQ_BURST_CLIENT14', + 90: 'GL2A_PERF_SEL_REQ_BURST_CLIENT15', + 91: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0', + 92: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1', + 93: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2', + 94: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3', + 95: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4', + 96: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5', + 97: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6', + 98: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7', + 99: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8', + 100: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9', + 101: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10', + 103: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11', + 104: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12', + 105: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13', + 106: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14', + 107: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15', +} +GL2A_PERF_SEL_NONE = 0 +GL2A_PERF_SEL_CYCLE = 1 +GL2A_PERF_SEL_BUSY = 2 +GL2A_PERF_SEL_REQ_GL2C0 = 3 +GL2A_PERF_SEL_REQ_GL2C1 = 4 +GL2A_PERF_SEL_REQ_GL2C2 = 5 +GL2A_PERF_SEL_REQ_GL2C3 = 6 +GL2A_PERF_SEL_REQ_GL2C4 = 7 +GL2A_PERF_SEL_REQ_GL2C5 = 8 +GL2A_PERF_SEL_REQ_GL2C6 = 9 +GL2A_PERF_SEL_REQ_GL2C7 = 10 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0 = 11 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1 = 12 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2 = 13 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3 = 14 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4 = 15 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5 = 16 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6 = 17 +GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7 = 18 +GL2A_PERF_SEL_REQ_BURST_GL2C0 = 19 +GL2A_PERF_SEL_REQ_BURST_GL2C1 = 20 +GL2A_PERF_SEL_REQ_BURST_GL2C2 = 21 +GL2A_PERF_SEL_REQ_BURST_GL2C3 = 22 +GL2A_PERF_SEL_REQ_BURST_GL2C4 = 23 +GL2A_PERF_SEL_REQ_BURST_GL2C5 = 24 +GL2A_PERF_SEL_REQ_BURST_GL2C6 = 25 +GL2A_PERF_SEL_REQ_BURST_GL2C7 = 26 +GL2A_PERF_SEL_REQ_STALL_GL2C0 = 27 +GL2A_PERF_SEL_REQ_STALL_GL2C1 = 28 +GL2A_PERF_SEL_REQ_STALL_GL2C2 = 29 +GL2A_PERF_SEL_REQ_STALL_GL2C3 = 30 +GL2A_PERF_SEL_REQ_STALL_GL2C4 = 31 +GL2A_PERF_SEL_REQ_STALL_GL2C5 = 32 +GL2A_PERF_SEL_REQ_STALL_GL2C6 = 33 +GL2A_PERF_SEL_REQ_STALL_GL2C7 = 34 +GL2A_PERF_SEL_RTN_STALL_GL2C0 = 35 +GL2A_PERF_SEL_RTN_STALL_GL2C1 = 36 +GL2A_PERF_SEL_RTN_STALL_GL2C2 = 37 +GL2A_PERF_SEL_RTN_STALL_GL2C3 = 38 +GL2A_PERF_SEL_RTN_STALL_GL2C4 = 39 +GL2A_PERF_SEL_RTN_STALL_GL2C5 = 40 +GL2A_PERF_SEL_RTN_STALL_GL2C6 = 41 +GL2A_PERF_SEL_RTN_STALL_GL2C7 = 42 +GL2A_PERF_SEL_RTN_CLIENT0 = 43 +GL2A_PERF_SEL_RTN_CLIENT1 = 44 +GL2A_PERF_SEL_RTN_CLIENT2 = 45 +GL2A_PERF_SEL_RTN_CLIENT3 = 46 +GL2A_PERF_SEL_RTN_CLIENT4 = 47 +GL2A_PERF_SEL_RTN_CLIENT5 = 48 +GL2A_PERF_SEL_RTN_CLIENT6 = 49 +GL2A_PERF_SEL_RTN_CLIENT7 = 50 +GL2A_PERF_SEL_RTN_CLIENT8 = 51 +GL2A_PERF_SEL_RTN_CLIENT9 = 52 +GL2A_PERF_SEL_RTN_CLIENT10 = 53 +GL2A_PERF_SEL_RTN_CLIENT11 = 54 +GL2A_PERF_SEL_RTN_CLIENT12 = 55 +GL2A_PERF_SEL_RTN_CLIENT13 = 56 +GL2A_PERF_SEL_RTN_CLIENT14 = 57 +GL2A_PERF_SEL_RTN_CLIENT15 = 58 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0 = 59 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1 = 60 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2 = 61 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3 = 62 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4 = 63 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5 = 64 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6 = 65 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7 = 66 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8 = 67 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9 = 68 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10 = 69 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11 = 70 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12 = 71 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13 = 72 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14 = 73 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15 = 74 +GL2A_PERF_SEL_REQ_BURST_CLIENT0 = 75 +GL2A_PERF_SEL_REQ_BURST_CLIENT1 = 76 +GL2A_PERF_SEL_REQ_BURST_CLIENT2 = 77 +GL2A_PERF_SEL_REQ_BURST_CLIENT3 = 78 +GL2A_PERF_SEL_REQ_BURST_CLIENT4 = 79 +GL2A_PERF_SEL_REQ_BURST_CLIENT5 = 80 +GL2A_PERF_SEL_REQ_BURST_CLIENT6 = 81 +GL2A_PERF_SEL_REQ_BURST_CLIENT7 = 82 +GL2A_PERF_SEL_REQ_BURST_CLIENT8 = 83 +GL2A_PERF_SEL_REQ_BURST_CLIENT9 = 84 +GL2A_PERF_SEL_REQ_BURST_CLIENT10 = 85 +GL2A_PERF_SEL_REQ_BURST_CLIENT11 = 86 +GL2A_PERF_SEL_REQ_BURST_CLIENT12 = 87 +GL2A_PERF_SEL_REQ_BURST_CLIENT13 = 88 +GL2A_PERF_SEL_REQ_BURST_CLIENT14 = 89 +GL2A_PERF_SEL_REQ_BURST_CLIENT15 = 90 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0 = 91 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1 = 92 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2 = 93 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3 = 94 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4 = 95 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5 = 96 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6 = 97 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7 = 98 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8 = 99 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9 = 100 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10 = 101 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11 = 103 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12 = 104 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13 = 105 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14 = 106 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15 = 107 +GL2A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL2C_PERF_SEL' +GL2C_PERF_SEL__enumvalues = { + 0: 'GL2C_PERF_SEL_NONE', + 1: 'GL2C_PERF_SEL_CYCLE', + 2: 'GL2C_PERF_SEL_BUSY', + 3: 'GL2C_PERF_SEL_REQ', + 4: 'GL2C_PERF_SEL_VOL_REQ', + 5: 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', + 6: 'GL2C_PERF_SEL_READ', + 7: 'GL2C_PERF_SEL_WRITE', + 8: 'GL2C_PERF_SEL_ATOMIC', + 9: 'GL2C_PERF_SEL_NOP_ACK', + 10: 'GL2C_PERF_SEL_NOP_RTN0', + 11: 'GL2C_PERF_SEL_PROBE', + 12: 'GL2C_PERF_SEL_PROBE_ALL', + 13: 'GL2C_PERF_SEL_INTERNAL_PROBE', + 14: 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', + 15: 'GL2C_PERF_SEL_METADATA_READ_REQ', + 16: 'GL2C_PERF_SEL_CLIENT0_REQ', + 17: 'GL2C_PERF_SEL_CLIENT1_REQ', + 18: 'GL2C_PERF_SEL_CLIENT2_REQ', + 19: 'GL2C_PERF_SEL_CLIENT3_REQ', + 20: 'GL2C_PERF_SEL_CLIENT4_REQ', + 21: 'GL2C_PERF_SEL_CLIENT5_REQ', + 22: 'GL2C_PERF_SEL_CLIENT6_REQ', + 23: 'GL2C_PERF_SEL_CLIENT7_REQ', + 24: 'GL2C_PERF_SEL_CLIENT8_REQ', + 25: 'GL2C_PERF_SEL_CLIENT9_REQ', + 26: 'GL2C_PERF_SEL_CLIENT10_REQ', + 27: 'GL2C_PERF_SEL_CLIENT11_REQ', + 28: 'GL2C_PERF_SEL_CLIENT12_REQ', + 29: 'GL2C_PERF_SEL_CLIENT13_REQ', + 30: 'GL2C_PERF_SEL_CLIENT14_REQ', + 31: 'GL2C_PERF_SEL_CLIENT15_REQ', + 32: 'GL2C_PERF_SEL_C_RW_S_REQ', + 33: 'GL2C_PERF_SEL_C_RW_US_REQ', + 34: 'GL2C_PERF_SEL_C_RO_S_REQ', + 35: 'GL2C_PERF_SEL_C_RO_US_REQ', + 36: 'GL2C_PERF_SEL_UC_REQ', + 37: 'GL2C_PERF_SEL_LRU_REQ', + 38: 'GL2C_PERF_SEL_STREAM_REQ', + 39: 'GL2C_PERF_SEL_BYPASS_REQ', + 40: 'GL2C_PERF_SEL_NOA_REQ', + 41: 'GL2C_PERF_SEL_SHARED_REQ', + 42: 'GL2C_PERF_SEL_HIT', + 43: 'GL2C_PERF_SEL_MISS', + 44: 'GL2C_PERF_SEL_FULL_HIT', + 45: 'GL2C_PERF_SEL_PARTIAL_32B_HIT', + 46: 'GL2C_PERF_SEL_PARTIAL_64B_HIT', + 47: 'GL2C_PERF_SEL_PARTIAL_96B_HIT', + 48: 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', + 49: 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', + 50: 'GL2C_PERF_SEL_UNCACHED_WRITE', + 51: 'GL2C_PERF_SEL_WRITEBACK', + 52: 'GL2C_PERF_SEL_NORMAL_WRITEBACK', + 53: 'GL2C_PERF_SEL_EVICT', + 54: 'GL2C_PERF_SEL_NORMAL_EVICT', + 55: 'GL2C_PERF_SEL_PROBE_EVICT', + 56: 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', + 57: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 58: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 59: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 60: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 61: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 62: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 63: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 64: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 65: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8', + 66: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9', + 67: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10', + 68: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11', + 69: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12', + 70: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13', + 71: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14', + 72: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15', + 73: 'GL2C_PERF_SEL_READ_32_REQ', + 74: 'GL2C_PERF_SEL_READ_64_REQ', + 75: 'GL2C_PERF_SEL_READ_128_REQ', + 76: 'GL2C_PERF_SEL_WRITE_32_REQ', + 77: 'GL2C_PERF_SEL_WRITE_64_REQ', + 78: 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 79: 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 80: 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 81: 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 82: 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 83: 'GL2C_PERF_SEL_MC_WRREQ', + 84: 'GL2C_PERF_SEL_EA_WRREQ_SNOOP', + 85: 'GL2C_PERF_SEL_EA_WRREQ_64B', + 86: 'GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 87: 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', + 88: 'GL2C_PERF_SEL_MC_WRREQ_STALL', + 89: 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 90: 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 91: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 92: 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', + 93: 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', + 94: 'GL2C_PERF_SEL_EA_ATOMIC', + 95: 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', + 96: 'GL2C_PERF_SEL_MC_RDREQ', + 97: 'GL2C_PERF_SEL_EA_RDREQ_SNOOP', + 98: 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', + 99: 'GL2C_PERF_SEL_EA_RDREQ_32B', + 100: 'GL2C_PERF_SEL_EA_RDREQ_64B', + 101: 'GL2C_PERF_SEL_EA_RDREQ_96B', + 102: 'GL2C_PERF_SEL_EA_RDREQ_128B', + 103: 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', + 104: 'GL2C_PERF_SEL_EA_RD_MDC_32B', + 105: 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 106: 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 107: 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 108: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 109: 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', + 110: 'GL2C_PERF_SEL_EA_RDREQ_DRAM', + 111: 'GL2C_PERF_SEL_EA_WRREQ_DRAM', + 112: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 113: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 114: 'GL2C_PERF_SEL_ONION_READ', + 115: 'GL2C_PERF_SEL_ONION_WRITE', + 116: 'GL2C_PERF_SEL_IO_READ', + 117: 'GL2C_PERF_SEL_IO_WRITE', + 118: 'GL2C_PERF_SEL_GARLIC_READ', + 119: 'GL2C_PERF_SEL_GARLIC_WRITE', + 120: 'GL2C_PERF_SEL_EA_OUTSTANDING', + 121: 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', + 122: 'GL2C_PERF_SEL_SRC_FIFO_FULL', + 123: 'GL2C_PERF_SEL_TAG_STALL', + 124: 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 125: 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 126: 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 127: 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 128: 'GL2C_PERF_SEL_TAG_PROBE_STALL', + 129: 'GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL', + 130: 'GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL', + 131: 'GL2C_PERF_SEL_TAG_READ_DST_STALL', + 132: 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', + 133: 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 134: 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 135: 'GL2C_PERF_SEL_BUBBLE', + 136: 'GL2C_PERF_SEL_IB_REQ', + 137: 'GL2C_PERF_SEL_IB_STALL', + 138: 'GL2C_PERF_SEL_IB_TAG_STALL', + 139: 'GL2C_PERF_SEL_IB_CM_STALL', + 140: 'GL2C_PERF_SEL_RETURN_ACK', + 141: 'GL2C_PERF_SEL_RETURN_DATA', + 142: 'GL2C_PERF_SEL_EA_RDRET_NACK', + 143: 'GL2C_PERF_SEL_EA_WRRET_NACK', + 144: 'GL2C_PERF_SEL_GL2A_LEVEL', + 145: 'GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 146: 'GL2C_PERF_SEL_PROBE_FILTER_DISABLED', + 147: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 148: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 149: 'GL2C_PERF_SEL_GCR_INV', + 150: 'GL2C_PERF_SEL_GCR_WB', + 151: 'GL2C_PERF_SEL_GCR_DISCARD', + 152: 'GL2C_PERF_SEL_GCR_RANGE', + 153: 'GL2C_PERF_SEL_GCR_ALL', + 154: 'GL2C_PERF_SEL_GCR_VOL', + 155: 'GL2C_PERF_SEL_GCR_UNSHARED', + 156: 'GL2C_PERF_SEL_GCR_MDC_INV', + 157: 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 158: 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 159: 'GL2C_PERF_SEL_GCR_MDC_INV_ALL', + 160: 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', + 161: 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', + 162: 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 163: 'GL2C_PERF_SEL_GCR_MDC_INV_RANGE', + 164: 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 165: 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 166: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 167: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 168: 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 169: 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 170: 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 171: 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', + 172: 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 173: 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', + 174: 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 175: 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 176: 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 177: 'GL2C_PERF_SEL_MDC_INV_METADATA', + 178: 'GL2C_PERF_SEL_MDC_REQ', + 179: 'GL2C_PERF_SEL_MDC_LEVEL', + 180: 'GL2C_PERF_SEL_MDC_TAG_HIT', + 181: 'GL2C_PERF_SEL_MDC_SECTOR_HIT', + 182: 'GL2C_PERF_SEL_MDC_SECTOR_MISS', + 183: 'GL2C_PERF_SEL_MDC_TAG_STALL', + 184: 'GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 185: 'GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 186: 'GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 187: 'GL2C_PERF_SEL_CM_CHANNEL0_REQ', + 188: 'GL2C_PERF_SEL_CM_CHANNEL1_REQ', + 189: 'GL2C_PERF_SEL_CM_CHANNEL2_REQ', + 190: 'GL2C_PERF_SEL_CM_CHANNEL3_REQ', + 191: 'GL2C_PERF_SEL_CM_CHANNEL4_REQ', + 192: 'GL2C_PERF_SEL_CM_CHANNEL5_REQ', + 193: 'GL2C_PERF_SEL_CM_CHANNEL6_REQ', + 194: 'GL2C_PERF_SEL_CM_CHANNEL7_REQ', + 195: 'GL2C_PERF_SEL_CM_CHANNEL8_REQ', + 196: 'GL2C_PERF_SEL_CM_CHANNEL9_REQ', + 197: 'GL2C_PERF_SEL_CM_CHANNEL10_REQ', + 198: 'GL2C_PERF_SEL_CM_CHANNEL11_REQ', + 199: 'GL2C_PERF_SEL_CM_CHANNEL12_REQ', + 200: 'GL2C_PERF_SEL_CM_CHANNEL13_REQ', + 201: 'GL2C_PERF_SEL_CM_CHANNEL14_REQ', + 202: 'GL2C_PERF_SEL_CM_CHANNEL15_REQ', + 203: 'GL2C_PERF_SEL_CM_CHANNEL16_REQ', + 204: 'GL2C_PERF_SEL_CM_CHANNEL17_REQ', + 205: 'GL2C_PERF_SEL_CM_CHANNEL18_REQ', + 206: 'GL2C_PERF_SEL_CM_CHANNEL19_REQ', + 207: 'GL2C_PERF_SEL_CM_CHANNEL20_REQ', + 208: 'GL2C_PERF_SEL_CM_CHANNEL21_REQ', + 209: 'GL2C_PERF_SEL_CM_CHANNEL22_REQ', + 210: 'GL2C_PERF_SEL_CM_CHANNEL23_REQ', + 211: 'GL2C_PERF_SEL_CM_CHANNEL24_REQ', + 212: 'GL2C_PERF_SEL_CM_CHANNEL25_REQ', + 213: 'GL2C_PERF_SEL_CM_CHANNEL26_REQ', + 214: 'GL2C_PERF_SEL_CM_CHANNEL27_REQ', + 215: 'GL2C_PERF_SEL_CM_CHANNEL28_REQ', + 216: 'GL2C_PERF_SEL_CM_CHANNEL29_REQ', + 217: 'GL2C_PERF_SEL_CM_CHANNEL30_REQ', + 218: 'GL2C_PERF_SEL_CM_CHANNEL31_REQ', + 219: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ', + 220: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ', + 221: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ', + 222: 'GL2C_PERF_SEL_CM_COMP_ATOMIC_STENCIL_REQ', + 223: 'GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ', + 224: 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ', + 225: 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ', + 226: 'GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ', + 227: 'GL2C_PERF_SEL_CM_COMP_READ_REQ', + 228: 'GL2C_PERF_SEL_CM_READ_BACK_REQ', + 229: 'GL2C_PERF_SEL_CM_METADATA_WR_REQ', + 230: 'GL2C_PERF_SEL_CM_WR_ACK_REQ', + 231: 'GL2C_PERF_SEL_CM_NO_ACK_REQ', + 232: 'GL2C_PERF_SEL_CM_NOOP_REQ', + 233: 'GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ', + 234: 'GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ', + 235: 'GL2C_PERF_SEL_CM_COMP_STENCIL_REQ', + 236: 'GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ', + 237: 'GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ', + 238: 'GL2C_PERF_SEL_CM_COMP_RB_SKIP_REQ', + 239: 'GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ', + 240: 'GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ', + 241: 'GL2C_PERF_SEL_CM_FULL_WRITE_REQ', + 242: 'GL2C_PERF_SEL_CM_RVF_FULL', + 243: 'GL2C_PERF_SEL_CM_SDR_FULL', + 244: 'GL2C_PERF_SEL_CM_MERGE_BUF_FULL', + 245: 'GL2C_PERF_SEL_CM_DCC_STALL', + 246: 'GL2C_PERF_SEL_CM_DCC_IN_XFC', + 247: 'GL2C_PERF_SEL_CM_DCC_OUT_XFC', + 248: 'GL2C_PERF_SEL_CM_DCC_OUT_1x1', + 249: 'GL2C_PERF_SEL_CM_DCC_OUT_1x2', + 250: 'GL2C_PERF_SEL_CM_DCC_OUT_2x1', + 251: 'GL2C_PERF_SEL_CM_DCC_OUT_2x2', + 252: 'GL2C_PERF_SEL_CM_DCC_OUT_UNCOMP', + 253: 'GL2C_PERF_SEL_CM_DCC_OUT_CONST', + 254: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16', + 255: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17', + 256: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18', + 257: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19', +} +GL2C_PERF_SEL_NONE = 0 +GL2C_PERF_SEL_CYCLE = 1 +GL2C_PERF_SEL_BUSY = 2 +GL2C_PERF_SEL_REQ = 3 +GL2C_PERF_SEL_VOL_REQ = 4 +GL2C_PERF_SEL_HIGH_PRIORITY_REQ = 5 +GL2C_PERF_SEL_READ = 6 +GL2C_PERF_SEL_WRITE = 7 +GL2C_PERF_SEL_ATOMIC = 8 +GL2C_PERF_SEL_NOP_ACK = 9 +GL2C_PERF_SEL_NOP_RTN0 = 10 +GL2C_PERF_SEL_PROBE = 11 +GL2C_PERF_SEL_PROBE_ALL = 12 +GL2C_PERF_SEL_INTERNAL_PROBE = 13 +GL2C_PERF_SEL_COMPRESSED_READ_REQ = 14 +GL2C_PERF_SEL_METADATA_READ_REQ = 15 +GL2C_PERF_SEL_CLIENT0_REQ = 16 +GL2C_PERF_SEL_CLIENT1_REQ = 17 +GL2C_PERF_SEL_CLIENT2_REQ = 18 +GL2C_PERF_SEL_CLIENT3_REQ = 19 +GL2C_PERF_SEL_CLIENT4_REQ = 20 +GL2C_PERF_SEL_CLIENT5_REQ = 21 +GL2C_PERF_SEL_CLIENT6_REQ = 22 +GL2C_PERF_SEL_CLIENT7_REQ = 23 +GL2C_PERF_SEL_CLIENT8_REQ = 24 +GL2C_PERF_SEL_CLIENT9_REQ = 25 +GL2C_PERF_SEL_CLIENT10_REQ = 26 +GL2C_PERF_SEL_CLIENT11_REQ = 27 +GL2C_PERF_SEL_CLIENT12_REQ = 28 +GL2C_PERF_SEL_CLIENT13_REQ = 29 +GL2C_PERF_SEL_CLIENT14_REQ = 30 +GL2C_PERF_SEL_CLIENT15_REQ = 31 +GL2C_PERF_SEL_C_RW_S_REQ = 32 +GL2C_PERF_SEL_C_RW_US_REQ = 33 +GL2C_PERF_SEL_C_RO_S_REQ = 34 +GL2C_PERF_SEL_C_RO_US_REQ = 35 +GL2C_PERF_SEL_UC_REQ = 36 +GL2C_PERF_SEL_LRU_REQ = 37 +GL2C_PERF_SEL_STREAM_REQ = 38 +GL2C_PERF_SEL_BYPASS_REQ = 39 +GL2C_PERF_SEL_NOA_REQ = 40 +GL2C_PERF_SEL_SHARED_REQ = 41 +GL2C_PERF_SEL_HIT = 42 +GL2C_PERF_SEL_MISS = 43 +GL2C_PERF_SEL_FULL_HIT = 44 +GL2C_PERF_SEL_PARTIAL_32B_HIT = 45 +GL2C_PERF_SEL_PARTIAL_64B_HIT = 46 +GL2C_PERF_SEL_PARTIAL_96B_HIT = 47 +GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT = 48 +GL2C_PERF_SEL_FULLY_WRITTEN_HIT = 49 +GL2C_PERF_SEL_UNCACHED_WRITE = 50 +GL2C_PERF_SEL_WRITEBACK = 51 +GL2C_PERF_SEL_NORMAL_WRITEBACK = 52 +GL2C_PERF_SEL_EVICT = 53 +GL2C_PERF_SEL_NORMAL_EVICT = 54 +GL2C_PERF_SEL_PROBE_EVICT = 55 +GL2C_PERF_SEL_REQ_TO_MISS_QUEUE = 56 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0 = 57 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1 = 58 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2 = 59 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3 = 60 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4 = 61 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5 = 62 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6 = 63 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7 = 64 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8 = 65 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9 = 66 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10 = 67 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11 = 68 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12 = 69 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13 = 70 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14 = 71 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15 = 72 +GL2C_PERF_SEL_READ_32_REQ = 73 +GL2C_PERF_SEL_READ_64_REQ = 74 +GL2C_PERF_SEL_READ_128_REQ = 75 +GL2C_PERF_SEL_WRITE_32_REQ = 76 +GL2C_PERF_SEL_WRITE_64_REQ = 77 +GL2C_PERF_SEL_COMPRESSED_READ_0_REQ = 78 +GL2C_PERF_SEL_COMPRESSED_READ_32_REQ = 79 +GL2C_PERF_SEL_COMPRESSED_READ_64_REQ = 80 +GL2C_PERF_SEL_COMPRESSED_READ_96_REQ = 81 +GL2C_PERF_SEL_COMPRESSED_READ_128_REQ = 82 +GL2C_PERF_SEL_MC_WRREQ = 83 +GL2C_PERF_SEL_EA_WRREQ_SNOOP = 84 +GL2C_PERF_SEL_EA_WRREQ_64B = 85 +GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND = 86 +GL2C_PERF_SEL_EA_WR_UNCACHED_32B = 87 +GL2C_PERF_SEL_MC_WRREQ_STALL = 88 +GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL = 89 +GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL = 90 +GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL = 91 +GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL = 92 +GL2C_PERF_SEL_MC_WRREQ_LEVEL = 93 +GL2C_PERF_SEL_EA_ATOMIC = 94 +GL2C_PERF_SEL_EA_ATOMIC_LEVEL = 95 +GL2C_PERF_SEL_MC_RDREQ = 96 +GL2C_PERF_SEL_EA_RDREQ_SNOOP = 97 +GL2C_PERF_SEL_EA_RDREQ_SPLIT = 98 +GL2C_PERF_SEL_EA_RDREQ_32B = 99 +GL2C_PERF_SEL_EA_RDREQ_64B = 100 +GL2C_PERF_SEL_EA_RDREQ_96B = 101 +GL2C_PERF_SEL_EA_RDREQ_128B = 102 +GL2C_PERF_SEL_EA_RD_UNCACHED_32B = 103 +GL2C_PERF_SEL_EA_RD_MDC_32B = 104 +GL2C_PERF_SEL_EA_RD_COMPRESSED_32B = 105 +GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL = 106 +GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL = 107 +GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL = 108 +GL2C_PERF_SEL_MC_RDREQ_LEVEL = 109 +GL2C_PERF_SEL_EA_RDREQ_DRAM = 110 +GL2C_PERF_SEL_EA_WRREQ_DRAM = 111 +GL2C_PERF_SEL_EA_RDREQ_DRAM_32B = 112 +GL2C_PERF_SEL_EA_WRREQ_DRAM_32B = 113 +GL2C_PERF_SEL_ONION_READ = 114 +GL2C_PERF_SEL_ONION_WRITE = 115 +GL2C_PERF_SEL_IO_READ = 116 +GL2C_PERF_SEL_IO_WRITE = 117 +GL2C_PERF_SEL_GARLIC_READ = 118 +GL2C_PERF_SEL_GARLIC_WRITE = 119 +GL2C_PERF_SEL_EA_OUTSTANDING = 120 +GL2C_PERF_SEL_LATENCY_FIFO_FULL = 121 +GL2C_PERF_SEL_SRC_FIFO_FULL = 122 +GL2C_PERF_SEL_TAG_STALL = 123 +GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL = 124 +GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL = 125 +GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL = 126 +GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL = 127 +GL2C_PERF_SEL_TAG_PROBE_STALL = 128 +GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL = 129 +GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL = 130 +GL2C_PERF_SEL_TAG_READ_DST_STALL = 131 +GL2C_PERF_SEL_READ_RETURN_TIMEOUT = 132 +GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT = 133 +GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE = 134 +GL2C_PERF_SEL_BUBBLE = 135 +GL2C_PERF_SEL_IB_REQ = 136 +GL2C_PERF_SEL_IB_STALL = 137 +GL2C_PERF_SEL_IB_TAG_STALL = 138 +GL2C_PERF_SEL_IB_CM_STALL = 139 +GL2C_PERF_SEL_RETURN_ACK = 140 +GL2C_PERF_SEL_RETURN_DATA = 141 +GL2C_PERF_SEL_EA_RDRET_NACK = 142 +GL2C_PERF_SEL_EA_WRRET_NACK = 143 +GL2C_PERF_SEL_GL2A_LEVEL = 144 +GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION = 145 +GL2C_PERF_SEL_PROBE_FILTER_DISABLED = 146 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START = 147 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START = 148 +GL2C_PERF_SEL_GCR_INV = 149 +GL2C_PERF_SEL_GCR_WB = 150 +GL2C_PERF_SEL_GCR_DISCARD = 151 +GL2C_PERF_SEL_GCR_RANGE = 152 +GL2C_PERF_SEL_GCR_ALL = 153 +GL2C_PERF_SEL_GCR_VOL = 154 +GL2C_PERF_SEL_GCR_UNSHARED = 155 +GL2C_PERF_SEL_GCR_MDC_INV = 156 +GL2C_PERF_SEL_GCR_GL2_INV_ALL = 157 +GL2C_PERF_SEL_GCR_GL2_WB_ALL = 158 +GL2C_PERF_SEL_GCR_MDC_INV_ALL = 159 +GL2C_PERF_SEL_GCR_GL2_INV_RANGE = 160 +GL2C_PERF_SEL_GCR_GL2_WB_RANGE = 161 +GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE = 162 +GL2C_PERF_SEL_GCR_MDC_INV_RANGE = 163 +GL2C_PERF_SEL_ALL_GCR_INV_EVICT = 164 +GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT = 165 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE = 166 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE = 167 +GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK = 168 +GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE = 169 +GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT = 170 +GL2C_PERF_SEL_GCR_INVL2_VOL_START = 171 +GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE = 172 +GL2C_PERF_SEL_GCR_WBL2_VOL_START = 173 +GL2C_PERF_SEL_GCR_WBINVL2_CYCLE = 174 +GL2C_PERF_SEL_GCR_WBINVL2_EVICT = 175 +GL2C_PERF_SEL_GCR_WBINVL2_START = 176 +GL2C_PERF_SEL_MDC_INV_METADATA = 177 +GL2C_PERF_SEL_MDC_REQ = 178 +GL2C_PERF_SEL_MDC_LEVEL = 179 +GL2C_PERF_SEL_MDC_TAG_HIT = 180 +GL2C_PERF_SEL_MDC_SECTOR_HIT = 181 +GL2C_PERF_SEL_MDC_SECTOR_MISS = 182 +GL2C_PERF_SEL_MDC_TAG_STALL = 183 +GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL = 184 +GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL = 185 +GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL = 186 +GL2C_PERF_SEL_CM_CHANNEL0_REQ = 187 +GL2C_PERF_SEL_CM_CHANNEL1_REQ = 188 +GL2C_PERF_SEL_CM_CHANNEL2_REQ = 189 +GL2C_PERF_SEL_CM_CHANNEL3_REQ = 190 +GL2C_PERF_SEL_CM_CHANNEL4_REQ = 191 +GL2C_PERF_SEL_CM_CHANNEL5_REQ = 192 +GL2C_PERF_SEL_CM_CHANNEL6_REQ = 193 +GL2C_PERF_SEL_CM_CHANNEL7_REQ = 194 +GL2C_PERF_SEL_CM_CHANNEL8_REQ = 195 +GL2C_PERF_SEL_CM_CHANNEL9_REQ = 196 +GL2C_PERF_SEL_CM_CHANNEL10_REQ = 197 +GL2C_PERF_SEL_CM_CHANNEL11_REQ = 198 +GL2C_PERF_SEL_CM_CHANNEL12_REQ = 199 +GL2C_PERF_SEL_CM_CHANNEL13_REQ = 200 +GL2C_PERF_SEL_CM_CHANNEL14_REQ = 201 +GL2C_PERF_SEL_CM_CHANNEL15_REQ = 202 +GL2C_PERF_SEL_CM_CHANNEL16_REQ = 203 +GL2C_PERF_SEL_CM_CHANNEL17_REQ = 204 +GL2C_PERF_SEL_CM_CHANNEL18_REQ = 205 +GL2C_PERF_SEL_CM_CHANNEL19_REQ = 206 +GL2C_PERF_SEL_CM_CHANNEL20_REQ = 207 +GL2C_PERF_SEL_CM_CHANNEL21_REQ = 208 +GL2C_PERF_SEL_CM_CHANNEL22_REQ = 209 +GL2C_PERF_SEL_CM_CHANNEL23_REQ = 210 +GL2C_PERF_SEL_CM_CHANNEL24_REQ = 211 +GL2C_PERF_SEL_CM_CHANNEL25_REQ = 212 +GL2C_PERF_SEL_CM_CHANNEL26_REQ = 213 +GL2C_PERF_SEL_CM_CHANNEL27_REQ = 214 +GL2C_PERF_SEL_CM_CHANNEL28_REQ = 215 +GL2C_PERF_SEL_CM_CHANNEL29_REQ = 216 +GL2C_PERF_SEL_CM_CHANNEL30_REQ = 217 +GL2C_PERF_SEL_CM_CHANNEL31_REQ = 218 +GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ = 219 +GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ = 220 +GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ = 221 +GL2C_PERF_SEL_CM_COMP_ATOMIC_STENCIL_REQ = 222 +GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ = 223 +GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ = 224 +GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ = 225 +GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ = 226 +GL2C_PERF_SEL_CM_COMP_READ_REQ = 227 +GL2C_PERF_SEL_CM_READ_BACK_REQ = 228 +GL2C_PERF_SEL_CM_METADATA_WR_REQ = 229 +GL2C_PERF_SEL_CM_WR_ACK_REQ = 230 +GL2C_PERF_SEL_CM_NO_ACK_REQ = 231 +GL2C_PERF_SEL_CM_NOOP_REQ = 232 +GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ = 233 +GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ = 234 +GL2C_PERF_SEL_CM_COMP_STENCIL_REQ = 235 +GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ = 236 +GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ = 237 +GL2C_PERF_SEL_CM_COMP_RB_SKIP_REQ = 238 +GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ = 239 +GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ = 240 +GL2C_PERF_SEL_CM_FULL_WRITE_REQ = 241 +GL2C_PERF_SEL_CM_RVF_FULL = 242 +GL2C_PERF_SEL_CM_SDR_FULL = 243 +GL2C_PERF_SEL_CM_MERGE_BUF_FULL = 244 +GL2C_PERF_SEL_CM_DCC_STALL = 245 +GL2C_PERF_SEL_CM_DCC_IN_XFC = 246 +GL2C_PERF_SEL_CM_DCC_OUT_XFC = 247 +GL2C_PERF_SEL_CM_DCC_OUT_1x1 = 248 +GL2C_PERF_SEL_CM_DCC_OUT_1x2 = 249 +GL2C_PERF_SEL_CM_DCC_OUT_2x1 = 250 +GL2C_PERF_SEL_CM_DCC_OUT_2x2 = 251 +GL2C_PERF_SEL_CM_DCC_OUT_UNCOMP = 252 +GL2C_PERF_SEL_CM_DCC_OUT_CONST = 253 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16 = 254 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17 = 255 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18 = 256 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19 = 257 +GL2C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_PERF_SEL' +GRBM_PERF_SEL__enumvalues = { + 0: 'GRBM_PERF_SEL_COUNT', + 1: 'GRBM_PERF_SEL_USER_DEFINED', + 2: 'GRBM_PERF_SEL_GUI_ACTIVE', + 3: 'GRBM_PERF_SEL_CP_BUSY', + 4: 'GRBM_PERF_SEL_CP_COHER_BUSY', + 5: 'GRBM_PERF_SEL_CP_DMA_BUSY', + 6: 'GRBM_PERF_SEL_CB_BUSY', + 7: 'GRBM_PERF_SEL_DB_BUSY', + 8: 'GRBM_PERF_SEL_PA_BUSY', + 9: 'GRBM_PERF_SEL_SC_BUSY', + 11: 'GRBM_PERF_SEL_SPI_BUSY', + 12: 'GRBM_PERF_SEL_SX_BUSY', + 13: 'GRBM_PERF_SEL_TA_BUSY', + 14: 'GRBM_PERF_SEL_CB_CLEAN', + 15: 'GRBM_PERF_SEL_DB_CLEAN', + 25: 'GRBM_PERF_SEL_GDS_BUSY', + 26: 'GRBM_PERF_SEL_BCI_BUSY', + 27: 'GRBM_PERF_SEL_RLC_BUSY', + 28: 'GRBM_PERF_SEL_TCP_BUSY', + 29: 'GRBM_PERF_SEL_CPG_BUSY', + 30: 'GRBM_PERF_SEL_CPC_BUSY', + 31: 'GRBM_PERF_SEL_CPF_BUSY', + 32: 'GRBM_PERF_SEL_GE_BUSY', + 33: 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', + 34: 'GRBM_PERF_SEL_UTCL2_BUSY', + 35: 'GRBM_PERF_SEL_EA_BUSY', + 36: 'GRBM_PERF_SEL_RMI_BUSY', + 37: 'GRBM_PERF_SEL_CPAXI_BUSY', + 39: 'GRBM_PERF_SEL_UTCL1_BUSY', + 40: 'GRBM_PERF_SEL_GL2CC_BUSY', + 41: 'GRBM_PERF_SEL_SDMA_BUSY', + 42: 'GRBM_PERF_SEL_CH_BUSY', + 43: 'GRBM_PERF_SEL_PH_BUSY', + 44: 'GRBM_PERF_SEL_PMM_BUSY', + 45: 'GRBM_PERF_SEL_GUS_BUSY', + 46: 'GRBM_PERF_SEL_GL1CC_BUSY', + 47: 'GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY', + 48: 'GRBM_PERF_SEL_GL1H_BUSY', + 49: 'GRBM_PERF_SEL_PC_BUSY', +} +GRBM_PERF_SEL_COUNT = 0 +GRBM_PERF_SEL_USER_DEFINED = 1 +GRBM_PERF_SEL_GUI_ACTIVE = 2 +GRBM_PERF_SEL_CP_BUSY = 3 +GRBM_PERF_SEL_CP_COHER_BUSY = 4 +GRBM_PERF_SEL_CP_DMA_BUSY = 5 +GRBM_PERF_SEL_CB_BUSY = 6 +GRBM_PERF_SEL_DB_BUSY = 7 +GRBM_PERF_SEL_PA_BUSY = 8 +GRBM_PERF_SEL_SC_BUSY = 9 +GRBM_PERF_SEL_SPI_BUSY = 11 +GRBM_PERF_SEL_SX_BUSY = 12 +GRBM_PERF_SEL_TA_BUSY = 13 +GRBM_PERF_SEL_CB_CLEAN = 14 +GRBM_PERF_SEL_DB_CLEAN = 15 +GRBM_PERF_SEL_GDS_BUSY = 25 +GRBM_PERF_SEL_BCI_BUSY = 26 +GRBM_PERF_SEL_RLC_BUSY = 27 +GRBM_PERF_SEL_TCP_BUSY = 28 +GRBM_PERF_SEL_CPG_BUSY = 29 +GRBM_PERF_SEL_CPC_BUSY = 30 +GRBM_PERF_SEL_CPF_BUSY = 31 +GRBM_PERF_SEL_GE_BUSY = 32 +GRBM_PERF_SEL_GE_NO_DMA_BUSY = 33 +GRBM_PERF_SEL_UTCL2_BUSY = 34 +GRBM_PERF_SEL_EA_BUSY = 35 +GRBM_PERF_SEL_RMI_BUSY = 36 +GRBM_PERF_SEL_CPAXI_BUSY = 37 +GRBM_PERF_SEL_UTCL1_BUSY = 39 +GRBM_PERF_SEL_GL2CC_BUSY = 40 +GRBM_PERF_SEL_SDMA_BUSY = 41 +GRBM_PERF_SEL_CH_BUSY = 42 +GRBM_PERF_SEL_PH_BUSY = 43 +GRBM_PERF_SEL_PMM_BUSY = 44 +GRBM_PERF_SEL_GUS_BUSY = 45 +GRBM_PERF_SEL_GL1CC_BUSY = 46 +GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY = 47 +GRBM_PERF_SEL_GL1H_BUSY = 48 +GRBM_PERF_SEL_PC_BUSY = 49 +GRBM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE0_PERF_SEL' +GRBM_SE0_PERF_SEL__enumvalues = { + 0: 'GRBM_SE0_PERF_SEL_COUNT', + 1: 'GRBM_SE0_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE0_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE0_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE0_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE0_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE0_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE0_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE0_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE0_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE0_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE0_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE0_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE0_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE0_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE0_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE0_PERF_SEL_PC_BUSY', +} +GRBM_SE0_PERF_SEL_COUNT = 0 +GRBM_SE0_PERF_SEL_USER_DEFINED = 1 +GRBM_SE0_PERF_SEL_CB_BUSY = 2 +GRBM_SE0_PERF_SEL_DB_BUSY = 3 +GRBM_SE0_PERF_SEL_SC_BUSY = 4 +GRBM_SE0_PERF_SEL_SPI_BUSY = 6 +GRBM_SE0_PERF_SEL_SX_BUSY = 7 +GRBM_SE0_PERF_SEL_TA_BUSY = 8 +GRBM_SE0_PERF_SEL_CB_CLEAN = 9 +GRBM_SE0_PERF_SEL_DB_CLEAN = 10 +GRBM_SE0_PERF_SEL_PA_BUSY = 12 +GRBM_SE0_PERF_SEL_BCI_BUSY = 14 +GRBM_SE0_PERF_SEL_RMI_BUSY = 15 +GRBM_SE0_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE0_PERF_SEL_TCP_BUSY = 17 +GRBM_SE0_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE0_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE0_PERF_SEL_PC_BUSY = 20 +GRBM_SE0_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE1_PERF_SEL' +GRBM_SE1_PERF_SEL__enumvalues = { + 0: 'GRBM_SE1_PERF_SEL_COUNT', + 1: 'GRBM_SE1_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE1_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE1_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE1_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE1_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE1_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE1_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE1_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE1_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE1_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE1_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE1_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE1_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE1_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE1_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE1_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE1_PERF_SEL_PC_BUSY', +} +GRBM_SE1_PERF_SEL_COUNT = 0 +GRBM_SE1_PERF_SEL_USER_DEFINED = 1 +GRBM_SE1_PERF_SEL_CB_BUSY = 2 +GRBM_SE1_PERF_SEL_DB_BUSY = 3 +GRBM_SE1_PERF_SEL_SC_BUSY = 4 +GRBM_SE1_PERF_SEL_SPI_BUSY = 6 +GRBM_SE1_PERF_SEL_SX_BUSY = 7 +GRBM_SE1_PERF_SEL_TA_BUSY = 8 +GRBM_SE1_PERF_SEL_CB_CLEAN = 9 +GRBM_SE1_PERF_SEL_DB_CLEAN = 10 +GRBM_SE1_PERF_SEL_PA_BUSY = 12 +GRBM_SE1_PERF_SEL_BCI_BUSY = 14 +GRBM_SE1_PERF_SEL_RMI_BUSY = 15 +GRBM_SE1_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE1_PERF_SEL_TCP_BUSY = 17 +GRBM_SE1_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE1_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE1_PERF_SEL_PC_BUSY = 20 +GRBM_SE1_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE2_PERF_SEL' +GRBM_SE2_PERF_SEL__enumvalues = { + 0: 'GRBM_SE2_PERF_SEL_COUNT', + 1: 'GRBM_SE2_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE2_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE2_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE2_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE2_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE2_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE2_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE2_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE2_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE2_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE2_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE2_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE2_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE2_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE2_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE2_PERF_SEL_PC_BUSY', +} +GRBM_SE2_PERF_SEL_COUNT = 0 +GRBM_SE2_PERF_SEL_USER_DEFINED = 1 +GRBM_SE2_PERF_SEL_CB_BUSY = 2 +GRBM_SE2_PERF_SEL_DB_BUSY = 3 +GRBM_SE2_PERF_SEL_SC_BUSY = 4 +GRBM_SE2_PERF_SEL_SPI_BUSY = 6 +GRBM_SE2_PERF_SEL_SX_BUSY = 7 +GRBM_SE2_PERF_SEL_TA_BUSY = 8 +GRBM_SE2_PERF_SEL_CB_CLEAN = 9 +GRBM_SE2_PERF_SEL_DB_CLEAN = 10 +GRBM_SE2_PERF_SEL_PA_BUSY = 12 +GRBM_SE2_PERF_SEL_BCI_BUSY = 14 +GRBM_SE2_PERF_SEL_RMI_BUSY = 15 +GRBM_SE2_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE2_PERF_SEL_TCP_BUSY = 17 +GRBM_SE2_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE2_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE2_PERF_SEL_PC_BUSY = 20 +GRBM_SE2_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE3_PERF_SEL' +GRBM_SE3_PERF_SEL__enumvalues = { + 0: 'GRBM_SE3_PERF_SEL_COUNT', + 1: 'GRBM_SE3_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE3_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE3_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE3_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE3_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE3_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE3_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE3_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE3_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE3_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE3_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE3_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE3_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE3_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE3_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE3_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE3_PERF_SEL_PC_BUSY', +} +GRBM_SE3_PERF_SEL_COUNT = 0 +GRBM_SE3_PERF_SEL_USER_DEFINED = 1 +GRBM_SE3_PERF_SEL_CB_BUSY = 2 +GRBM_SE3_PERF_SEL_DB_BUSY = 3 +GRBM_SE3_PERF_SEL_SC_BUSY = 4 +GRBM_SE3_PERF_SEL_SPI_BUSY = 6 +GRBM_SE3_PERF_SEL_SX_BUSY = 7 +GRBM_SE3_PERF_SEL_TA_BUSY = 8 +GRBM_SE3_PERF_SEL_CB_CLEAN = 9 +GRBM_SE3_PERF_SEL_DB_CLEAN = 10 +GRBM_SE3_PERF_SEL_PA_BUSY = 12 +GRBM_SE3_PERF_SEL_BCI_BUSY = 14 +GRBM_SE3_PERF_SEL_RMI_BUSY = 15 +GRBM_SE3_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE3_PERF_SEL_TCP_BUSY = 17 +GRBM_SE3_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE3_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE3_PERF_SEL_PC_BUSY = 20 +GRBM_SE3_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE4_PERF_SEL' +GRBM_SE4_PERF_SEL__enumvalues = { + 0: 'GRBM_SE4_PERF_SEL_COUNT', + 1: 'GRBM_SE4_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE4_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE4_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE4_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE4_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE4_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE4_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE4_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE4_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE4_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE4_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE4_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE4_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE4_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE4_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE4_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE4_PERF_SEL_PC_BUSY', +} +GRBM_SE4_PERF_SEL_COUNT = 0 +GRBM_SE4_PERF_SEL_USER_DEFINED = 1 +GRBM_SE4_PERF_SEL_CB_BUSY = 2 +GRBM_SE4_PERF_SEL_DB_BUSY = 3 +GRBM_SE4_PERF_SEL_SC_BUSY = 4 +GRBM_SE4_PERF_SEL_SPI_BUSY = 6 +GRBM_SE4_PERF_SEL_SX_BUSY = 7 +GRBM_SE4_PERF_SEL_TA_BUSY = 8 +GRBM_SE4_PERF_SEL_CB_CLEAN = 9 +GRBM_SE4_PERF_SEL_DB_CLEAN = 10 +GRBM_SE4_PERF_SEL_PA_BUSY = 12 +GRBM_SE4_PERF_SEL_BCI_BUSY = 14 +GRBM_SE4_PERF_SEL_RMI_BUSY = 15 +GRBM_SE4_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE4_PERF_SEL_TCP_BUSY = 17 +GRBM_SE4_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE4_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE4_PERF_SEL_PC_BUSY = 20 +GRBM_SE4_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE5_PERF_SEL' +GRBM_SE5_PERF_SEL__enumvalues = { + 0: 'GRBM_SE5_PERF_SEL_COUNT', + 1: 'GRBM_SE5_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE5_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE5_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE5_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE5_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE5_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE5_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE5_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE5_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE5_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE5_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE5_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE5_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE5_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE5_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE5_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE5_PERF_SEL_PC_BUSY', +} +GRBM_SE5_PERF_SEL_COUNT = 0 +GRBM_SE5_PERF_SEL_USER_DEFINED = 1 +GRBM_SE5_PERF_SEL_CB_BUSY = 2 +GRBM_SE5_PERF_SEL_DB_BUSY = 3 +GRBM_SE5_PERF_SEL_SC_BUSY = 4 +GRBM_SE5_PERF_SEL_SPI_BUSY = 6 +GRBM_SE5_PERF_SEL_SX_BUSY = 7 +GRBM_SE5_PERF_SEL_TA_BUSY = 8 +GRBM_SE5_PERF_SEL_CB_CLEAN = 9 +GRBM_SE5_PERF_SEL_DB_CLEAN = 10 +GRBM_SE5_PERF_SEL_PA_BUSY = 12 +GRBM_SE5_PERF_SEL_BCI_BUSY = 14 +GRBM_SE5_PERF_SEL_RMI_BUSY = 15 +GRBM_SE5_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE5_PERF_SEL_TCP_BUSY = 17 +GRBM_SE5_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE5_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE5_PERF_SEL_PC_BUSY = 20 +GRBM_SE5_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE6_PERF_SEL' +GRBM_SE6_PERF_SEL__enumvalues = { + 0: 'GRBM_SE6_PERF_SEL_COUNT', + 1: 'GRBM_SE6_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE6_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE6_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE6_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE6_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE6_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE6_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE6_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE6_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE6_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE6_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE6_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE6_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE6_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE6_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE6_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE6_PERF_SEL_PC_BUSY', +} +GRBM_SE6_PERF_SEL_COUNT = 0 +GRBM_SE6_PERF_SEL_USER_DEFINED = 1 +GRBM_SE6_PERF_SEL_CB_BUSY = 2 +GRBM_SE6_PERF_SEL_DB_BUSY = 3 +GRBM_SE6_PERF_SEL_SC_BUSY = 4 +GRBM_SE6_PERF_SEL_SPI_BUSY = 6 +GRBM_SE6_PERF_SEL_SX_BUSY = 7 +GRBM_SE6_PERF_SEL_TA_BUSY = 8 +GRBM_SE6_PERF_SEL_CB_CLEAN = 9 +GRBM_SE6_PERF_SEL_DB_CLEAN = 10 +GRBM_SE6_PERF_SEL_PA_BUSY = 12 +GRBM_SE6_PERF_SEL_BCI_BUSY = 14 +GRBM_SE6_PERF_SEL_RMI_BUSY = 15 +GRBM_SE6_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE6_PERF_SEL_TCP_BUSY = 17 +GRBM_SE6_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE6_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE6_PERF_SEL_PC_BUSY = 20 +GRBM_SE6_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE7_PERF_SEL' +GRBM_SE7_PERF_SEL__enumvalues = { + 0: 'GRBM_SE7_PERF_SEL_COUNT', + 1: 'GRBM_SE7_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE7_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE7_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE7_PERF_SEL_SC_BUSY', + 6: 'GRBM_SE7_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE7_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE7_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE7_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE7_PERF_SEL_DB_CLEAN', + 12: 'GRBM_SE7_PERF_SEL_PA_BUSY', + 14: 'GRBM_SE7_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE7_PERF_SEL_RMI_BUSY', + 16: 'GRBM_SE7_PERF_SEL_UTCL1_BUSY', + 17: 'GRBM_SE7_PERF_SEL_TCP_BUSY', + 18: 'GRBM_SE7_PERF_SEL_GL1CC_BUSY', + 19: 'GRBM_SE7_PERF_SEL_GL1H_BUSY', + 20: 'GRBM_SE7_PERF_SEL_PC_BUSY', +} +GRBM_SE7_PERF_SEL_COUNT = 0 +GRBM_SE7_PERF_SEL_USER_DEFINED = 1 +GRBM_SE7_PERF_SEL_CB_BUSY = 2 +GRBM_SE7_PERF_SEL_DB_BUSY = 3 +GRBM_SE7_PERF_SEL_SC_BUSY = 4 +GRBM_SE7_PERF_SEL_SPI_BUSY = 6 +GRBM_SE7_PERF_SEL_SX_BUSY = 7 +GRBM_SE7_PERF_SEL_TA_BUSY = 8 +GRBM_SE7_PERF_SEL_CB_CLEAN = 9 +GRBM_SE7_PERF_SEL_DB_CLEAN = 10 +GRBM_SE7_PERF_SEL_PA_BUSY = 12 +GRBM_SE7_PERF_SEL_BCI_BUSY = 14 +GRBM_SE7_PERF_SEL_RMI_BUSY = 15 +GRBM_SE7_PERF_SEL_UTCL1_BUSY = 16 +GRBM_SE7_PERF_SEL_TCP_BUSY = 17 +GRBM_SE7_PERF_SEL_GL1CC_BUSY = 18 +GRBM_SE7_PERF_SEL_GL1H_BUSY = 19 +GRBM_SE7_PERF_SEL_PC_BUSY = 20 +GRBM_SE7_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_COMPAT_LEVEL' +PIPE_COMPAT_LEVEL__enumvalues = { + 0: 'GEN_ZERO', + 1: 'GEN_ONE', + 2: 'GEN_TWO', + 3: 'GEN_RESERVED', +} +GEN_ZERO = 0 +GEN_ONE = 1 +GEN_TWO = 2 +GEN_RESERVED = 3 +PIPE_COMPAT_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_LATENCY_STATS_SEL' +CPC_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPC_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 7: 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 8: 'CPC_LATENCY_STATS_SEL_INVAL_LAST', +} +CPC_LATENCY_STATS_SEL_XACK_MAX = 0 +CPC_LATENCY_STATS_SEL_XACK_MIN = 1 +CPC_LATENCY_STATS_SEL_XACK_LAST = 2 +CPC_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPC_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPC_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPC_LATENCY_STATS_SEL_INVAL_MAX = 6 +CPC_LATENCY_STATS_SEL_INVAL_MIN = 7 +CPC_LATENCY_STATS_SEL_INVAL_LAST = 8 +CPC_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_PERFCOUNT_SEL' +CPC_PERFCOUNT_SEL__enumvalues = { + 0: 'CPC_PERF_SEL_ALWAYS_COUNT', + 1: 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 2: 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 5: 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 6: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 7: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 8: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 9: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ', + 10: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE', + 11: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 12: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 13: 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 14: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 15: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 16: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 17: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ', + 18: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE', + 19: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 20: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 21: 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 22: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 23: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 24: 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 25: 'CPC_PERF_SEL_CPC_STAT_BUSY', + 26: 'CPC_PERF_SEL_CPC_STAT_IDLE', + 27: 'CPC_PERF_SEL_CPC_STAT_STALL', + 28: 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 29: 'CPC_PERF_SEL_CPC_TCIU_IDLE', + 30: 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 31: 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', + 32: 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 33: 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 34: 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 35: 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 36: 'CPC_PERF_SEL_CPC_GCRIU_IDLE', + 37: 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 38: 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 39: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 40: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 41: 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', + 42: 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 43: 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 44: 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', + 45: 'CPC_PERF_SEL_MES_THREAD0', + 46: 'CPC_PERF_SEL_MES_THREAD1', +} +CPC_PERF_SEL_ALWAYS_COUNT = 0 +CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 1 +CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION = 2 +CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 5 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY = 6 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF = 7 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ = 8 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ = 9 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE = 10 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ = 11 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF = 12 +CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE = 13 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY = 14 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF = 15 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ = 16 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ = 17 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE = 18 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ = 19 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF = 20 +CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE = 21 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 22 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 23 +CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 24 +CPC_PERF_SEL_CPC_STAT_BUSY = 25 +CPC_PERF_SEL_CPC_STAT_IDLE = 26 +CPC_PERF_SEL_CPC_STAT_STALL = 27 +CPC_PERF_SEL_CPC_TCIU_BUSY = 28 +CPC_PERF_SEL_CPC_TCIU_IDLE = 29 +CPC_PERF_SEL_CPC_UTCL2IU_BUSY = 30 +CPC_PERF_SEL_CPC_UTCL2IU_IDLE = 31 +CPC_PERF_SEL_CPC_UTCL2IU_STALL = 32 +CPC_PERF_SEL_ME1_DC0_SPI_BUSY = 33 +CPC_PERF_SEL_ME2_DC1_SPI_BUSY = 34 +CPC_PERF_SEL_CPC_GCRIU_BUSY = 35 +CPC_PERF_SEL_CPC_GCRIU_IDLE = 36 +CPC_PERF_SEL_CPC_GCRIU_STALL = 37 +CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 38 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ = 39 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ = 40 +CPC_PERF_SEL_CPC_UTCL2IU_XACK = 41 +CPC_PERF_SEL_CPC_UTCL2IU_XNACK = 42 +CPC_PERF_SEL_MEC_INSTR_CACHE_HIT = 43 +CPC_PERF_SEL_MEC_INSTR_CACHE_MISS = 44 +CPC_PERF_SEL_MES_THREAD0 = 45 +CPC_PERF_SEL_MES_THREAD1 = 46 +CPC_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_LATENCY_STATS_SEL' +CPF_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPF_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPF_LATENCY_STATS_SEL_READ_MAX', + 7: 'CPF_LATENCY_STATS_SEL_READ_MIN', + 8: 'CPF_LATENCY_STATS_SEL_READ_LAST', + 9: 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 10: 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 11: 'CPF_LATENCY_STATS_SEL_INVAL_LAST', +} +CPF_LATENCY_STATS_SEL_XACK_MAX = 0 +CPF_LATENCY_STATS_SEL_XACK_MIN = 1 +CPF_LATENCY_STATS_SEL_XACK_LAST = 2 +CPF_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPF_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPF_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPF_LATENCY_STATS_SEL_READ_MAX = 6 +CPF_LATENCY_STATS_SEL_READ_MIN = 7 +CPF_LATENCY_STATS_SEL_READ_LAST = 8 +CPF_LATENCY_STATS_SEL_INVAL_MAX = 9 +CPF_LATENCY_STATS_SEL_INVAL_MIN = 10 +CPF_LATENCY_STATS_SEL_INVAL_LAST = 11 +CPF_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNTWINDOW_SEL' +CPF_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPF_PERFWINDOW_SEL_CSF', + 1: 'CPF_PERFWINDOW_SEL_HQD1', + 2: 'CPF_PERFWINDOW_SEL_HQD2', + 3: 'CPF_PERFWINDOW_SEL_RDMA', + 4: 'CPF_PERFWINDOW_SEL_RWPP', +} +CPF_PERFWINDOW_SEL_CSF = 0 +CPF_PERFWINDOW_SEL_HQD1 = 1 +CPF_PERFWINDOW_SEL_HQD2 = 2 +CPF_PERFWINDOW_SEL_RDMA = 3 +CPF_PERFWINDOW_SEL_RWPP = 4 +CPF_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNT_SEL' +CPF_PERFCOUNT_SEL__enumvalues = { + 0: 'CPF_PERF_SEL_ALWAYS_COUNT', + 2: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 3: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 4: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 5: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 6: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 7: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE', + 10: 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 11: 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 12: 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 13: 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 14: 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 15: 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 16: 'CPF_PERF_SEL_GUS_READ_REQUEST_SENT', + 17: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 18: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 19: 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 20: 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 21: 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 22: 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 23: 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 24: 'CPF_PERF_SEL_CPF_STAT_BUSY', + 25: 'CPF_PERF_SEL_CPF_STAT_IDLE', + 26: 'CPF_PERF_SEL_CPF_STAT_STALL', + 27: 'CPF_PERF_SEL_CPF_TCIU_BUSY', + 28: 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 29: 'CPF_PERF_SEL_CPF_TCIU_STALL', + 30: 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 31: 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', + 32: 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 33: 'CPF_PERF_SEL_CPF_GCRIU_BUSY', + 34: 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 35: 'CPF_PERF_SEL_CPF_GCRIU_STALL', + 36: 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 37: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 38: 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', + 39: 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', + 40: 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ', + 41: 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE', + 42: 'CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY', + 43: 'CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY', +} +CPF_PERF_SEL_ALWAYS_COUNT = 0 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE = 2 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS = 3 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING = 4 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1 = 5 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2 = 6 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE = 7 +CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR = 10 +CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 11 +CPF_PERF_SEL_GRBM_DWORDS_SENT = 12 +CPF_PERF_SEL_DYNAMIC_CLOCK_VALID = 13 +CPF_PERF_SEL_REGISTER_CLOCK_VALID = 14 +CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT = 15 +CPF_PERF_SEL_GUS_READ_REQUEST_SENT = 16 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 17 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 18 +CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION = 19 +CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION = 20 +CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 21 +CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 22 +CPF_PERF_SEL_TCIU_READ_REQUEST_SENT = 23 +CPF_PERF_SEL_CPF_STAT_BUSY = 24 +CPF_PERF_SEL_CPF_STAT_IDLE = 25 +CPF_PERF_SEL_CPF_STAT_STALL = 26 +CPF_PERF_SEL_CPF_TCIU_BUSY = 27 +CPF_PERF_SEL_CPF_TCIU_IDLE = 28 +CPF_PERF_SEL_CPF_TCIU_STALL = 29 +CPF_PERF_SEL_CPF_UTCL2IU_BUSY = 30 +CPF_PERF_SEL_CPF_UTCL2IU_IDLE = 31 +CPF_PERF_SEL_CPF_UTCL2IU_STALL = 32 +CPF_PERF_SEL_CPF_GCRIU_BUSY = 33 +CPF_PERF_SEL_CPF_GCRIU_IDLE = 34 +CPF_PERF_SEL_CPF_GCRIU_STALL = 35 +CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 36 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB = 37 +CPF_PERF_SEL_CPF_UTCL2IU_XACK = 38 +CPF_PERF_SEL_CPF_UTCL2IU_XNACK = 39 +CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ = 40 +CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE = 41 +CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY = 42 +CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY = 43 +CPF_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_SCRATCH_REG_ATOMIC_OP' +CPF_SCRATCH_REG_ATOMIC_OP__enumvalues = { + 0: 'CPF_SCRATCH_REG_ATOMIC_ADD', + 1: 'CPF_SCRATCH_REG_ATOMIC_SUB', + 2: 'CPF_SCRATCH_REG_ATOMIC_OR', + 3: 'CPF_SCRATCH_REG_ATOMIC_AND', + 4: 'CPF_SCRATCH_REG_ATOMIC_NOT', + 5: 'CPF_SCRATCH_REG_ATOMIC_MIN', + 6: 'CPF_SCRATCH_REG_ATOMIC_MAX', + 7: 'CPF_SCRATCH_REG_ATOMIC_CMPSWAP', +} +CPF_SCRATCH_REG_ATOMIC_ADD = 0 +CPF_SCRATCH_REG_ATOMIC_SUB = 1 +CPF_SCRATCH_REG_ATOMIC_OR = 2 +CPF_SCRATCH_REG_ATOMIC_AND = 3 +CPF_SCRATCH_REG_ATOMIC_NOT = 4 +CPF_SCRATCH_REG_ATOMIC_MIN = 5 +CPF_SCRATCH_REG_ATOMIC_MAX = 6 +CPF_SCRATCH_REG_ATOMIC_CMPSWAP = 7 +CPF_SCRATCH_REG_ATOMIC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_LATENCY_STATS_SEL' +CPG_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPG_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 7: 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 8: 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 9: 'CPG_LATENCY_STATS_SEL_READ_MAX', + 10: 'CPG_LATENCY_STATS_SEL_READ_MIN', + 11: 'CPG_LATENCY_STATS_SEL_READ_LAST', + 12: 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 13: 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 14: 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 15: 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 16: 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 17: 'CPG_LATENCY_STATS_SEL_INVAL_LAST', +} +CPG_LATENCY_STATS_SEL_XACK_MAX = 0 +CPG_LATENCY_STATS_SEL_XACK_MIN = 1 +CPG_LATENCY_STATS_SEL_XACK_LAST = 2 +CPG_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPG_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPG_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPG_LATENCY_STATS_SEL_WRITE_MAX = 6 +CPG_LATENCY_STATS_SEL_WRITE_MIN = 7 +CPG_LATENCY_STATS_SEL_WRITE_LAST = 8 +CPG_LATENCY_STATS_SEL_READ_MAX = 9 +CPG_LATENCY_STATS_SEL_READ_MIN = 10 +CPG_LATENCY_STATS_SEL_READ_LAST = 11 +CPG_LATENCY_STATS_SEL_ATOMIC_MAX = 12 +CPG_LATENCY_STATS_SEL_ATOMIC_MIN = 13 +CPG_LATENCY_STATS_SEL_ATOMIC_LAST = 14 +CPG_LATENCY_STATS_SEL_INVAL_MAX = 15 +CPG_LATENCY_STATS_SEL_INVAL_MIN = 16 +CPG_LATENCY_STATS_SEL_INVAL_LAST = 17 +CPG_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNTWINDOW_SEL' +CPG_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPG_PERFWINDOW_SEL_PFP', + 1: 'CPG_PERFWINDOW_SEL_ME', + 2: 'CPG_PERFWINDOW_SEL_CE', + 3: 'CPG_PERFWINDOW_SEL_MES', + 4: 'CPG_PERFWINDOW_SEL_MEC1', + 5: 'CPG_PERFWINDOW_SEL_MEC2', + 6: 'CPG_PERFWINDOW_SEL_DFY', + 7: 'CPG_PERFWINDOW_SEL_DMA', + 8: 'CPG_PERFWINDOW_SEL_SHADOW', + 9: 'CPG_PERFWINDOW_SEL_RB', + 10: 'CPG_PERFWINDOW_SEL_CEDMA', + 11: 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 12: 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', + 13: 'CPG_PERFWINDOW_SEL_PQ1', + 14: 'CPG_PERFWINDOW_SEL_PQ2', + 15: 'CPG_PERFWINDOW_SEL_PQ3', + 16: 'CPG_PERFWINDOW_SEL_MEMWR', + 17: 'CPG_PERFWINDOW_SEL_MEMRD', + 18: 'CPG_PERFWINDOW_SEL_VGT0', + 19: 'CPG_PERFWINDOW_SEL_VGT1', + 20: 'CPG_PERFWINDOW_SEL_APPEND', + 21: 'CPG_PERFWINDOW_SEL_QURD', + 22: 'CPG_PERFWINDOW_SEL_DDID', + 23: 'CPG_PERFWINDOW_SEL_SR', + 24: 'CPG_PERFWINDOW_SEL_QU_EOP', + 25: 'CPG_PERFWINDOW_SEL_QU_STRM', + 26: 'CPG_PERFWINDOW_SEL_QU_PIPE', + 27: 'CPG_PERFWINDOW_SEL_RESERVED1', + 28: 'CPG_PERFWINDOW_SEL_CPC_IC', + 29: 'CPG_PERFWINDOW_SEL_RESERVED2', + 30: 'CPG_PERFWINDOW_SEL_CPG_IC', +} +CPG_PERFWINDOW_SEL_PFP = 0 +CPG_PERFWINDOW_SEL_ME = 1 +CPG_PERFWINDOW_SEL_CE = 2 +CPG_PERFWINDOW_SEL_MES = 3 +CPG_PERFWINDOW_SEL_MEC1 = 4 +CPG_PERFWINDOW_SEL_MEC2 = 5 +CPG_PERFWINDOW_SEL_DFY = 6 +CPG_PERFWINDOW_SEL_DMA = 7 +CPG_PERFWINDOW_SEL_SHADOW = 8 +CPG_PERFWINDOW_SEL_RB = 9 +CPG_PERFWINDOW_SEL_CEDMA = 10 +CPG_PERFWINDOW_SEL_PRT_HDR_RPTR = 11 +CPG_PERFWINDOW_SEL_PRT_SMP_RPTR = 12 +CPG_PERFWINDOW_SEL_PQ1 = 13 +CPG_PERFWINDOW_SEL_PQ2 = 14 +CPG_PERFWINDOW_SEL_PQ3 = 15 +CPG_PERFWINDOW_SEL_MEMWR = 16 +CPG_PERFWINDOW_SEL_MEMRD = 17 +CPG_PERFWINDOW_SEL_VGT0 = 18 +CPG_PERFWINDOW_SEL_VGT1 = 19 +CPG_PERFWINDOW_SEL_APPEND = 20 +CPG_PERFWINDOW_SEL_QURD = 21 +CPG_PERFWINDOW_SEL_DDID = 22 +CPG_PERFWINDOW_SEL_SR = 23 +CPG_PERFWINDOW_SEL_QU_EOP = 24 +CPG_PERFWINDOW_SEL_QU_STRM = 25 +CPG_PERFWINDOW_SEL_QU_PIPE = 26 +CPG_PERFWINDOW_SEL_RESERVED1 = 27 +CPG_PERFWINDOW_SEL_CPC_IC = 28 +CPG_PERFWINDOW_SEL_RESERVED2 = 29 +CPG_PERFWINDOW_SEL_CPG_IC = 30 +CPG_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNT_SEL' +CPG_PERFCOUNT_SEL__enumvalues = { + 0: 'CPG_PERF_SEL_ALWAYS_COUNT', + 1: 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 4: 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 5: 'CPG_PERF_SEL_ME_PARSER_BUSY', + 6: 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 7: 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', + 9: 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 10: 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 11: 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 12: 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 13: 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 14: 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 15: 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 16: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 17: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 18: 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 19: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 20: 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 21: 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 22: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 23: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 24: 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 25: 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 26: 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 27: 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 28: 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 29: 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 31: 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 32: 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 33: 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 34: 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 35: 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 36: 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 37: 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 38: 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 39: 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 41: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 42: 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 43: 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 44: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 45: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 46: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 47: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 48: 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 49: 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 50: 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 51: 'CPG_PERF_SEL_CPG_STAT_BUSY', + 52: 'CPG_PERF_SEL_CPG_STAT_IDLE', + 53: 'CPG_PERF_SEL_CPG_STAT_STALL', + 54: 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 55: 'CPG_PERF_SEL_CPG_TCIU_IDLE', + 56: 'CPG_PERF_SEL_CPG_TCIU_STALL', + 57: 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', + 58: 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', + 59: 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', + 60: 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 61: 'CPG_PERF_SEL_CPG_GCRIU_IDLE', + 62: 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 63: 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 64: 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', + 65: 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', + 66: 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 67: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 68: 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 69: 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 70: 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 71: 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 72: 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 73: 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', + 74: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 75: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 76: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 77: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', + 78: 'CPG_PERF_SEL_DMA_BUSY', + 79: 'CPG_PERF_SEL_DMA_STARVED', + 80: 'CPG_PERF_SEL_DMA_STALLED', + 81: 'CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL', + 82: 'CPG_PERF_SEL_PFP_PWS_STALLED0', + 83: 'CPG_PERF_SEL_ME_PWS_STALLED0', + 84: 'CPG_PERF_SEL_PFP_PWS_STALLED1', + 85: 'CPG_PERF_SEL_ME_PWS_STALLED1', +} +CPG_PERF_SEL_ALWAYS_COUNT = 0 +CPG_PERF_SEL_RBIU_FIFO_FULL = 1 +CPG_PERF_SEL_CP_GRBM_DWORDS_SENT = 4 +CPG_PERF_SEL_ME_PARSER_BUSY = 5 +CPG_PERF_SEL_COUNT_TYPE0_PACKETS = 6 +CPG_PERF_SEL_COUNT_TYPE3_PACKETS = 7 +CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS = 9 +CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS = 10 +CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS = 11 +CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ = 12 +CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ = 13 +CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX = 14 +CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS = 15 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE = 16 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM = 17 +CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY = 18 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY = 19 +CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY = 20 +CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ = 21 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP = 22 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ = 23 +CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX = 24 +CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU = 25 +CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS = 26 +CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH = 27 +CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER = 28 +CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER = 29 +CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY = 31 +CPG_PERF_SEL_DYNAMIC_CLK_VALID = 32 +CPG_PERF_SEL_REGISTER_CLK_VALID = 33 +CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT = 34 +CPG_PERF_SEL_GUS_READ_REQUEST_SENT = 35 +CPG_PERF_SEL_CE_STALL_RAM_DUMP = 36 +CPG_PERF_SEL_CE_STALL_RAM_WRITE = 37 +CPG_PERF_SEL_CE_STALL_ON_INC_FIFO = 38 +CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO = 39 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ = 41 +CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG = 42 +CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER = 43 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 44 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS = 45 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 46 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 47 +CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 48 +CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 49 +CPG_PERF_SEL_TCIU_READ_REQUEST_SENT = 50 +CPG_PERF_SEL_CPG_STAT_BUSY = 51 +CPG_PERF_SEL_CPG_STAT_IDLE = 52 +CPG_PERF_SEL_CPG_STAT_STALL = 53 +CPG_PERF_SEL_CPG_TCIU_BUSY = 54 +CPG_PERF_SEL_CPG_TCIU_IDLE = 55 +CPG_PERF_SEL_CPG_TCIU_STALL = 56 +CPG_PERF_SEL_CPG_UTCL2IU_BUSY = 57 +CPG_PERF_SEL_CPG_UTCL2IU_IDLE = 58 +CPG_PERF_SEL_CPG_UTCL2IU_STALL = 59 +CPG_PERF_SEL_CPG_GCRIU_BUSY = 60 +CPG_PERF_SEL_CPG_GCRIU_IDLE = 61 +CPG_PERF_SEL_CPG_GCRIU_STALL = 62 +CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 63 +CPG_PERF_SEL_ALL_GFX_PIPES_BUSY = 64 +CPG_PERF_SEL_CPG_UTCL2IU_XACK = 65 +CPG_PERF_SEL_CPG_UTCL2IU_XNACK = 66 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY = 67 +CPG_PERF_SEL_PFP_INSTR_CACHE_HIT = 68 +CPG_PERF_SEL_PFP_INSTR_CACHE_MISS = 69 +CPG_PERF_SEL_CE_INSTR_CACHE_HIT = 70 +CPG_PERF_SEL_CE_INSTR_CACHE_MISS = 71 +CPG_PERF_SEL_ME_INSTR_CACHE_HIT = 72 +CPG_PERF_SEL_ME_INSTR_CACHE_MISS = 73 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1 = 74 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1 = 75 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2 = 76 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2 = 77 +CPG_PERF_SEL_DMA_BUSY = 78 +CPG_PERF_SEL_DMA_STARVED = 79 +CPG_PERF_SEL_DMA_STALLED = 80 +CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL = 81 +CPG_PERF_SEL_PFP_PWS_STALLED0 = 82 +CPG_PERF_SEL_ME_PWS_STALLED0 = 83 +CPG_PERF_SEL_PFP_PWS_STALLED1 = 84 +CPG_PERF_SEL_ME_PWS_STALLED1 = 85 +CPG_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ALPHA_TAG_RAM_SEL' +CP_ALPHA_TAG_RAM_SEL__enumvalues = { + 0: 'CPG_TAG_RAM', + 1: 'CPC_TAG_RAM', + 2: 'CPF_TAG_RAM', + 3: 'RSV_TAG_RAM', +} +CPG_TAG_RAM = 0 +CPC_TAG_RAM = 1 +CPF_TAG_RAM = 2 +RSV_TAG_RAM = 3 +CP_ALPHA_TAG_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_MODE' +CP_DDID_CNTL_MODE__enumvalues = { + 0: 'STALL', + 1: 'OVERRUN', +} +STALL = 0 +OVERRUN = 1 +CP_DDID_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_SIZE' +CP_DDID_CNTL_SIZE__enumvalues = { + 0: 'SIZE_8K', + 1: 'SIZE_16K', +} +SIZE_8K = 0 +SIZE_16K = 1 +CP_DDID_CNTL_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_VMID_SEL' +CP_DDID_CNTL_VMID_SEL__enumvalues = { + 0: 'DDID_VMID_PIPE', + 1: 'DDID_VMID_CNTL', +} +DDID_VMID_PIPE = 0 +DDID_VMID_CNTL = 1 +CP_DDID_CNTL_VMID_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ME_ID' +CP_ME_ID__enumvalues = { + 0: 'ME_ID0', + 1: 'ME_ID1', + 2: 'ME_ID2', + 3: 'ME_ID3', +} +ME_ID0 = 0 +ME_ID1 = 1 +ME_ID2 = 2 +ME_ID3 = 3 +CP_ME_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_ENABLE_MODE' +CP_PERFMON_ENABLE_MODE__enumvalues = { + 0: 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 1: 'CP_PERFMON_ENABLE_MODE_RESERVED_1', + 2: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 3: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', +} +CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT = 0 +CP_PERFMON_ENABLE_MODE_RESERVED_1 = 1 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE = 2 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE = 3 +CP_PERFMON_ENABLE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_STATE' +CP_PERFMON_STATE__enumvalues = { + 0: 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'CP_PERFMON_STATE_START_COUNTING', + 2: 'CP_PERFMON_STATE_STOP_COUNTING', + 3: 'CP_PERFMON_STATE_RESERVED_3', + 4: 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +CP_PERFMON_STATE_DISABLE_AND_RESET = 0 +CP_PERFMON_STATE_START_COUNTING = 1 +CP_PERFMON_STATE_STOP_COUNTING = 2 +CP_PERFMON_STATE_RESERVED_3 = 3 +CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +CP_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PIPE_ID' +CP_PIPE_ID__enumvalues = { + 0: 'PIPE_ID0', + 1: 'PIPE_ID1', + 2: 'PIPE_ID2', + 3: 'PIPE_ID3', +} +PIPE_ID0 = 0 +PIPE_ID1 = 1 +PIPE_ID2 = 2 +PIPE_ID3 = 3 +CP_PIPE_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_RING_ID' +CP_RING_ID__enumvalues = { + 0: 'RINGID0', + 1: 'RINGID1', + 2: 'RINGID2', + 3: 'RINGID3', +} +RINGID0 = 0 +RINGID1 = 1 +RINGID2 = 2 +RINGID3 = 3 +CP_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'SPM_PERFMON_STATE' +SPM_PERFMON_STATE__enumvalues = { + 0: 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'STRM_PERFMON_STATE_START_COUNTING', + 2: 'STRM_PERFMON_STATE_STOP_COUNTING', + 3: 'STRM_PERFMON_STATE_RESERVED_3', + 4: 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +STRM_PERFMON_STATE_DISABLE_AND_RESET = 0 +STRM_PERFMON_STATE_START_COUNTING = 1 +STRM_PERFMON_STATE_STOP_COUNTING = 2 +STRM_PERFMON_STATE_RESERVED_3 = 3 +STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +SPM_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'SX_BLEND_OPT' +SX_BLEND_OPT__enumvalues = { + 0: 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 1: 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 2: 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 3: 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 4: 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 5: 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 6: 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 7: 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', +} +BLEND_OPT_PRESERVE_NONE_IGNORE_ALL = 0 +BLEND_OPT_PRESERVE_ALL_IGNORE_NONE = 1 +BLEND_OPT_PRESERVE_C1_IGNORE_C0 = 2 +BLEND_OPT_PRESERVE_C0_IGNORE_C1 = 3 +BLEND_OPT_PRESERVE_A1_IGNORE_A0 = 4 +BLEND_OPT_PRESERVE_A0_IGNORE_A1 = 5 +BLEND_OPT_PRESERVE_NONE_IGNORE_A0 = 6 +BLEND_OPT_PRESERVE_NONE_IGNORE_NONE = 7 +SX_BLEND_OPT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_DOWNCONVERT_FORMAT' +SX_DOWNCONVERT_FORMAT__enumvalues = { + 0: 'SX_RT_EXPORT_NO_CONVERSION', + 1: 'SX_RT_EXPORT_32_R', + 2: 'SX_RT_EXPORT_32_A', + 3: 'SX_RT_EXPORT_10_11_11', + 4: 'SX_RT_EXPORT_2_10_10_10', + 5: 'SX_RT_EXPORT_8_8_8_8', + 6: 'SX_RT_EXPORT_5_6_5', + 7: 'SX_RT_EXPORT_1_5_5_5', + 8: 'SX_RT_EXPORT_4_4_4_4', + 9: 'SX_RT_EXPORT_16_16_GR', + 10: 'SX_RT_EXPORT_16_16_AR', + 11: 'SX_RT_EXPORT_9_9_9_E5', + 12: 'SX_RT_EXPORT_2_10_10_10_7E3', + 13: 'SX_RT_EXPORT_2_10_10_10_6E4', +} +SX_RT_EXPORT_NO_CONVERSION = 0 +SX_RT_EXPORT_32_R = 1 +SX_RT_EXPORT_32_A = 2 +SX_RT_EXPORT_10_11_11 = 3 +SX_RT_EXPORT_2_10_10_10 = 4 +SX_RT_EXPORT_8_8_8_8 = 5 +SX_RT_EXPORT_5_6_5 = 6 +SX_RT_EXPORT_1_5_5_5 = 7 +SX_RT_EXPORT_4_4_4_4 = 8 +SX_RT_EXPORT_16_16_GR = 9 +SX_RT_EXPORT_16_16_AR = 10 +SX_RT_EXPORT_9_9_9_E5 = 11 +SX_RT_EXPORT_2_10_10_10_7E3 = 12 +SX_RT_EXPORT_2_10_10_10_6E4 = 13 +SX_DOWNCONVERT_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_OPT_COMB_FCN' +SX_OPT_COMB_FCN__enumvalues = { + 0: 'OPT_COMB_NONE', + 1: 'OPT_COMB_ADD', + 2: 'OPT_COMB_SUBTRACT', + 3: 'OPT_COMB_MIN', + 4: 'OPT_COMB_MAX', + 5: 'OPT_COMB_REVSUBTRACT', + 6: 'OPT_COMB_BLEND_DISABLED', + 7: 'OPT_COMB_SAFE_ADD', +} +OPT_COMB_NONE = 0 +OPT_COMB_ADD = 1 +OPT_COMB_SUBTRACT = 2 +OPT_COMB_MIN = 3 +OPT_COMB_MAX = 4 +OPT_COMB_REVSUBTRACT = 5 +OPT_COMB_BLEND_DISABLED = 6 +OPT_COMB_SAFE_ADD = 7 +SX_OPT_COMB_FCN = ctypes.c_uint32 # enum + +# values for enumeration 'SX_PERFCOUNTER_VALS' +SX_PERFCOUNTER_VALS__enumvalues = { + 0: 'SX_PERF_SEL_PA_IDLE_CYCLES', + 1: 'SX_PERF_SEL_PA_REQ', + 2: 'SX_PERF_SEL_PA_POS', + 3: 'SX_PERF_SEL_CLOCK', + 4: 'SX_PERF_SEL_GATE_EN1', + 5: 'SX_PERF_SEL_GATE_EN2', + 6: 'SX_PERF_SEL_GATE_EN3', + 7: 'SX_PERF_SEL_GATE_EN4', + 8: 'SX_PERF_SEL_SH_POS_STARVE', + 9: 'SX_PERF_SEL_SH_COLOR_STARVE', + 10: 'SX_PERF_SEL_SH_POS_STALL', + 11: 'SX_PERF_SEL_SH_COLOR_STALL', + 12: 'SX_PERF_SEL_DB0_PIXELS', + 13: 'SX_PERF_SEL_DB0_HALF_QUADS', + 14: 'SX_PERF_SEL_DB0_PIXEL_STALL', + 15: 'SX_PERF_SEL_DB0_PIXEL_IDLE', + 16: 'SX_PERF_SEL_DB0_PRED_PIXELS', + 17: 'SX_PERF_SEL_DB1_PIXELS', + 18: 'SX_PERF_SEL_DB1_HALF_QUADS', + 19: 'SX_PERF_SEL_DB1_PIXEL_STALL', + 20: 'SX_PERF_SEL_DB1_PIXEL_IDLE', + 21: 'SX_PERF_SEL_DB1_PRED_PIXELS', + 22: 'SX_PERF_SEL_DB2_PIXELS', + 23: 'SX_PERF_SEL_DB2_HALF_QUADS', + 24: 'SX_PERF_SEL_DB2_PIXEL_STALL', + 25: 'SX_PERF_SEL_DB2_PIXEL_IDLE', + 26: 'SX_PERF_SEL_DB2_PRED_PIXELS', + 27: 'SX_PERF_SEL_DB3_PIXELS', + 28: 'SX_PERF_SEL_DB3_HALF_QUADS', + 29: 'SX_PERF_SEL_DB3_PIXEL_STALL', + 30: 'SX_PERF_SEL_DB3_PIXEL_IDLE', + 31: 'SX_PERF_SEL_DB3_PRED_PIXELS', + 32: 'SX_PERF_SEL_COL_BUSY', + 33: 'SX_PERF_SEL_POS_BUSY', + 34: 'SX_PERF_SEL_DB0_MRT_BLEND_BYPASS', + 35: 'SX_PERF_SEL_DB0_MRT_DONT_RD_DEST', + 36: 'SX_PERF_SEL_DB0_MRT_DISCARD_SRC', + 37: 'SX_PERF_SEL_DB0_MRT_SINGLE_QUADS', + 38: 'SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS', + 39: 'SX_PERF_SEL_DB1_MRT_BLEND_BYPASS', + 40: 'SX_PERF_SEL_DB1_MRT_DONT_RD_DEST', + 41: 'SX_PERF_SEL_DB1_MRT_DISCARD_SRC', + 42: 'SX_PERF_SEL_DB1_MRT_SINGLE_QUADS', + 43: 'SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS', + 44: 'SX_PERF_SEL_DB2_MRT_BLEND_BYPASS', + 45: 'SX_PERF_SEL_DB2_MRT_DONT_RD_DEST', + 46: 'SX_PERF_SEL_DB2_MRT_DISCARD_SRC', + 47: 'SX_PERF_SEL_DB2_MRT_SINGLE_QUADS', + 48: 'SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS', + 49: 'SX_PERF_SEL_DB3_MRT_BLEND_BYPASS', + 50: 'SX_PERF_SEL_DB3_MRT_DONT_RD_DEST', + 51: 'SX_PERF_SEL_DB3_MRT_DISCARD_SRC', + 52: 'SX_PERF_SEL_DB3_MRT_SINGLE_QUADS', + 53: 'SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS', + 54: 'SX_PERF_SEL_PA_REQ_LATENCY', + 55: 'SX_PERF_SEL_POS_SCBD_STALL', + 56: 'SX_PERF_SEL_CLOCK_DROP_STALL', + 57: 'SX_PERF_SEL_GATE_EN5', + 58: 'SX_PERF_SEL_GATE_EN6', + 59: 'SX_PERF_SEL_DB0_SIZE', + 60: 'SX_PERF_SEL_DB1_SIZE', + 61: 'SX_PERF_SEL_DB2_SIZE', + 62: 'SX_PERF_SEL_DB3_SIZE', + 63: 'SX_PERF_SEL_IDX_STALL_CYCLES', + 64: 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 65: 'SX_PERF_SEL_IDX_REQ', + 66: 'SX_PERF_SEL_IDX_RET', + 67: 'SX_PERF_SEL_IDX_REQ_LATENCY', + 68: 'SX_PERF_SEL_IDX_SCBD_STALL', + 69: 'SX_PERF_SEL_GATE_EN7', + 70: 'SX_PERF_SEL_GATE_EN8', + 71: 'SX_PERF_SEL_SH_IDX_STARVE', + 72: 'SX_PERF_SEL_IDX_BUSY', + 73: 'SX_PERF_SEL_PA_POS_BANK_CONF', + 74: 'SX_PERF_SEL_DB0_END_OF_WAVE', + 75: 'SX_PERF_SEL_DB0_4X2_DISCARD', + 76: 'SX_PERF_SEL_DB1_END_OF_WAVE', + 77: 'SX_PERF_SEL_DB1_4X2_DISCARD', + 78: 'SX_PERF_SEL_DB2_END_OF_WAVE', + 79: 'SX_PERF_SEL_DB2_4X2_DISCARD', + 80: 'SX_PERF_SEL_DB3_END_OF_WAVE', + 81: 'SX_PERF_SEL_DB3_4X2_DISCARD', +} +SX_PERF_SEL_PA_IDLE_CYCLES = 0 +SX_PERF_SEL_PA_REQ = 1 +SX_PERF_SEL_PA_POS = 2 +SX_PERF_SEL_CLOCK = 3 +SX_PERF_SEL_GATE_EN1 = 4 +SX_PERF_SEL_GATE_EN2 = 5 +SX_PERF_SEL_GATE_EN3 = 6 +SX_PERF_SEL_GATE_EN4 = 7 +SX_PERF_SEL_SH_POS_STARVE = 8 +SX_PERF_SEL_SH_COLOR_STARVE = 9 +SX_PERF_SEL_SH_POS_STALL = 10 +SX_PERF_SEL_SH_COLOR_STALL = 11 +SX_PERF_SEL_DB0_PIXELS = 12 +SX_PERF_SEL_DB0_HALF_QUADS = 13 +SX_PERF_SEL_DB0_PIXEL_STALL = 14 +SX_PERF_SEL_DB0_PIXEL_IDLE = 15 +SX_PERF_SEL_DB0_PRED_PIXELS = 16 +SX_PERF_SEL_DB1_PIXELS = 17 +SX_PERF_SEL_DB1_HALF_QUADS = 18 +SX_PERF_SEL_DB1_PIXEL_STALL = 19 +SX_PERF_SEL_DB1_PIXEL_IDLE = 20 +SX_PERF_SEL_DB1_PRED_PIXELS = 21 +SX_PERF_SEL_DB2_PIXELS = 22 +SX_PERF_SEL_DB2_HALF_QUADS = 23 +SX_PERF_SEL_DB2_PIXEL_STALL = 24 +SX_PERF_SEL_DB2_PIXEL_IDLE = 25 +SX_PERF_SEL_DB2_PRED_PIXELS = 26 +SX_PERF_SEL_DB3_PIXELS = 27 +SX_PERF_SEL_DB3_HALF_QUADS = 28 +SX_PERF_SEL_DB3_PIXEL_STALL = 29 +SX_PERF_SEL_DB3_PIXEL_IDLE = 30 +SX_PERF_SEL_DB3_PRED_PIXELS = 31 +SX_PERF_SEL_COL_BUSY = 32 +SX_PERF_SEL_POS_BUSY = 33 +SX_PERF_SEL_DB0_MRT_BLEND_BYPASS = 34 +SX_PERF_SEL_DB0_MRT_DONT_RD_DEST = 35 +SX_PERF_SEL_DB0_MRT_DISCARD_SRC = 36 +SX_PERF_SEL_DB0_MRT_SINGLE_QUADS = 37 +SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS = 38 +SX_PERF_SEL_DB1_MRT_BLEND_BYPASS = 39 +SX_PERF_SEL_DB1_MRT_DONT_RD_DEST = 40 +SX_PERF_SEL_DB1_MRT_DISCARD_SRC = 41 +SX_PERF_SEL_DB1_MRT_SINGLE_QUADS = 42 +SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS = 43 +SX_PERF_SEL_DB2_MRT_BLEND_BYPASS = 44 +SX_PERF_SEL_DB2_MRT_DONT_RD_DEST = 45 +SX_PERF_SEL_DB2_MRT_DISCARD_SRC = 46 +SX_PERF_SEL_DB2_MRT_SINGLE_QUADS = 47 +SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS = 48 +SX_PERF_SEL_DB3_MRT_BLEND_BYPASS = 49 +SX_PERF_SEL_DB3_MRT_DONT_RD_DEST = 50 +SX_PERF_SEL_DB3_MRT_DISCARD_SRC = 51 +SX_PERF_SEL_DB3_MRT_SINGLE_QUADS = 52 +SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS = 53 +SX_PERF_SEL_PA_REQ_LATENCY = 54 +SX_PERF_SEL_POS_SCBD_STALL = 55 +SX_PERF_SEL_CLOCK_DROP_STALL = 56 +SX_PERF_SEL_GATE_EN5 = 57 +SX_PERF_SEL_GATE_EN6 = 58 +SX_PERF_SEL_DB0_SIZE = 59 +SX_PERF_SEL_DB1_SIZE = 60 +SX_PERF_SEL_DB2_SIZE = 61 +SX_PERF_SEL_DB3_SIZE = 62 +SX_PERF_SEL_IDX_STALL_CYCLES = 63 +SX_PERF_SEL_IDX_IDLE_CYCLES = 64 +SX_PERF_SEL_IDX_REQ = 65 +SX_PERF_SEL_IDX_RET = 66 +SX_PERF_SEL_IDX_REQ_LATENCY = 67 +SX_PERF_SEL_IDX_SCBD_STALL = 68 +SX_PERF_SEL_GATE_EN7 = 69 +SX_PERF_SEL_GATE_EN8 = 70 +SX_PERF_SEL_SH_IDX_STARVE = 71 +SX_PERF_SEL_IDX_BUSY = 72 +SX_PERF_SEL_PA_POS_BANK_CONF = 73 +SX_PERF_SEL_DB0_END_OF_WAVE = 74 +SX_PERF_SEL_DB0_4X2_DISCARD = 75 +SX_PERF_SEL_DB1_END_OF_WAVE = 76 +SX_PERF_SEL_DB1_4X2_DISCARD = 77 +SX_PERF_SEL_DB2_END_OF_WAVE = 78 +SX_PERF_SEL_DB2_4X2_DISCARD = 79 +SX_PERF_SEL_DB3_END_OF_WAVE = 80 +SX_PERF_SEL_DB3_4X2_DISCARD = 81 +SX_PERFCOUNTER_VALS = ctypes.c_uint32 # enum + +# values for enumeration 'CompareFrag' +CompareFrag__enumvalues = { + 0: 'FRAG_NEVER', + 1: 'FRAG_LESS', + 2: 'FRAG_EQUAL', + 3: 'FRAG_LEQUAL', + 4: 'FRAG_GREATER', + 5: 'FRAG_NOTEQUAL', + 6: 'FRAG_GEQUAL', + 7: 'FRAG_ALWAYS', +} +FRAG_NEVER = 0 +FRAG_LESS = 1 +FRAG_EQUAL = 2 +FRAG_LEQUAL = 3 +FRAG_GREATER = 4 +FRAG_NOTEQUAL = 5 +FRAG_GEQUAL = 6 +FRAG_ALWAYS = 7 +CompareFrag = ctypes.c_uint32 # enum + +# values for enumeration 'ConservativeZExport' +ConservativeZExport__enumvalues = { + 0: 'EXPORT_ANY_Z', + 1: 'EXPORT_LESS_THAN_Z', + 2: 'EXPORT_GREATER_THAN_Z', + 3: 'EXPORT_RESERVED', +} +EXPORT_ANY_Z = 0 +EXPORT_LESS_THAN_Z = 1 +EXPORT_GREATER_THAN_Z = 2 +EXPORT_RESERVED = 3 +ConservativeZExport = ctypes.c_uint32 # enum + +# values for enumeration 'DFSMFlushEvents' +DFSMFlushEvents__enumvalues = { + 0: 'DB_FLUSH_AND_INV_DB_DATA_TS', + 1: 'DB_FLUSH_AND_INV_DB_META', + 2: 'DB_CACHE_FLUSH', + 3: 'DB_CACHE_FLUSH_TS', + 4: 'DB_CACHE_FLUSH_AND_INV_EVENT', + 5: 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', + 6: 'DB_VPORT_CHANGED_EVENT', + 7: 'DB_CONTEXT_DONE_EVENT', + 8: 'DB_BREAK_BATCH_EVENT', + 9: 'DB_INVOKE_CHANGE_EVENT', + 10: 'DB_CONTEXT_SUSPEND_EVENT', +} +DB_FLUSH_AND_INV_DB_DATA_TS = 0 +DB_FLUSH_AND_INV_DB_META = 1 +DB_CACHE_FLUSH = 2 +DB_CACHE_FLUSH_TS = 3 +DB_CACHE_FLUSH_AND_INV_EVENT = 4 +DB_CACHE_FLUSH_AND_INV_TS_EVENT = 5 +DB_VPORT_CHANGED_EVENT = 6 +DB_CONTEXT_DONE_EVENT = 7 +DB_BREAK_BATCH_EVENT = 8 +DB_INVOKE_CHANGE_EVENT = 9 +DB_CONTEXT_SUSPEND_EVENT = 10 +DFSMFlushEvents = ctypes.c_uint32 # enum + +# values for enumeration 'DbMemArbWatermarks' +DbMemArbWatermarks__enumvalues = { + 0: 'TRANSFERRED_64_BYTES', + 1: 'TRANSFERRED_128_BYTES', + 2: 'TRANSFERRED_256_BYTES', + 3: 'TRANSFERRED_512_BYTES', + 4: 'TRANSFERRED_1024_BYTES', + 5: 'TRANSFERRED_2048_BYTES', + 6: 'TRANSFERRED_4096_BYTES', + 7: 'TRANSFERRED_8192_BYTES', +} +TRANSFERRED_64_BYTES = 0 +TRANSFERRED_128_BYTES = 1 +TRANSFERRED_256_BYTES = 2 +TRANSFERRED_512_BYTES = 3 +TRANSFERRED_1024_BYTES = 4 +TRANSFERRED_2048_BYTES = 5 +TRANSFERRED_4096_BYTES = 6 +TRANSFERRED_8192_BYTES = 7 +DbMemArbWatermarks = ctypes.c_uint32 # enum + +# values for enumeration 'DbPRTFaultBehavior' +DbPRTFaultBehavior__enumvalues = { + 0: 'FAULT_ZERO', + 1: 'FAULT_ONE', + 2: 'FAULT_FAIL', + 3: 'FAULT_PASS', +} +FAULT_ZERO = 0 +FAULT_ONE = 1 +FAULT_FAIL = 2 +FAULT_PASS = 3 +DbPRTFaultBehavior = ctypes.c_uint32 # enum + +# values for enumeration 'DbPSLControl' +DbPSLControl__enumvalues = { + 0: 'PSLC_AUTO', + 1: 'PSLC_ON_HANG_ONLY', + 2: 'PSLC_ASAP', + 3: 'PSLC_COUNTDOWN', +} +PSLC_AUTO = 0 +PSLC_ON_HANG_ONLY = 1 +PSLC_ASAP = 2 +PSLC_COUNTDOWN = 3 +DbPSLControl = ctypes.c_uint32 # enum + +# values for enumeration 'ForceControl' +ForceControl__enumvalues = { + 0: 'FORCE_OFF', + 1: 'FORCE_ENABLE', + 2: 'FORCE_DISABLE', + 3: 'FORCE_RESERVED', +} +FORCE_OFF = 0 +FORCE_ENABLE = 1 +FORCE_DISABLE = 2 +FORCE_RESERVED = 3 +ForceControl = ctypes.c_uint32 # enum + +# values for enumeration 'OreoMode' +OreoMode__enumvalues = { + 0: 'OMODE_BLEND', + 1: 'OMODE_O_THEN_B', + 2: 'OMODE_P_THEN_O_THEN_B', + 3: 'OMODE_RESERVED_3', +} +OMODE_BLEND = 0 +OMODE_O_THEN_B = 1 +OMODE_P_THEN_O_THEN_B = 2 +OMODE_RESERVED_3 = 3 +OreoMode = ctypes.c_uint32 # enum + +# values for enumeration 'PerfCounter_Vals' +PerfCounter_Vals__enumvalues = { + 0: 'DB_PERF_SEL_SC_DB_tile_sends', + 1: 'DB_PERF_SEL_SC_DB_tile_busy', + 2: 'DB_PERF_SEL_SC_DB_tile_stalls', + 3: 'DB_PERF_SEL_SC_DB_tile_events', + 4: 'DB_PERF_SEL_SC_DB_tile_tiles', + 5: 'DB_PERF_SEL_SC_DB_tile_covered', + 6: 'DB_PERF_SEL_hiz_tc_read_starved', + 7: 'DB_PERF_SEL_hiz_tc_write_stall', + 8: 'DB_PERF_SEL_hiz_tile_culled', + 9: 'DB_PERF_SEL_his_tile_culled', + 10: 'DB_PERF_SEL_DB_SC_tile_sends', + 11: 'DB_PERF_SEL_DB_SC_tile_busy', + 12: 'DB_PERF_SEL_DB_SC_tile_stalls', + 13: 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 14: 'DB_PERF_SEL_DB_SC_tile_tiles', + 15: 'DB_PERF_SEL_DB_SC_tile_culled', + 16: 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 17: 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 18: 'DB_PERF_SEL_DB_SC_tile_no_ops', + 19: 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 20: 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 21: 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 22: 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 23: 'DB_PERF_SEL_SC_DB_quad_sends', + 24: 'DB_PERF_SEL_SC_DB_quad_busy', + 25: 'DB_PERF_SEL_SC_DB_quad_squads', + 26: 'DB_PERF_SEL_SC_DB_quad_tiles', + 27: 'DB_PERF_SEL_SC_DB_quad_pixels', + 28: 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 29: 'DB_PERF_SEL_DB_SC_quad_sends', + 30: 'DB_PERF_SEL_DB_SC_quad_busy', + 31: 'DB_PERF_SEL_DB_SC_quad_stalls', + 32: 'DB_PERF_SEL_DB_SC_quad_tiles', + 33: 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 34: 'DB_PERF_SEL_DB_CB_tile_sends', + 35: 'DB_PERF_SEL_DB_CB_tile_busy', + 36: 'DB_PERF_SEL_DB_CB_tile_stalls', + 37: 'DB_PERF_SEL_SX_DB_quad_sends', + 38: 'DB_PERF_SEL_SX_DB_quad_busy', + 39: 'DB_PERF_SEL_SX_DB_quad_stalls', + 40: 'DB_PERF_SEL_SX_DB_quad_quads', + 41: 'DB_PERF_SEL_SX_DB_quad_pixels', + 42: 'DB_PERF_SEL_SX_DB_quad_exports', + 43: 'DB_PERF_SEL_SH_quads_outstanding_sum', + 44: 'DB_PERF_SEL_DB_CB_lquad_sends', + 45: 'DB_PERF_SEL_DB_CB_lquad_busy', + 46: 'DB_PERF_SEL_DB_CB_lquad_stalls', + 47: 'DB_PERF_SEL_DB_CB_lquad_quads', + 48: 'DB_PERF_SEL_tile_rd_sends', + 49: 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 50: 'DB_PERF_SEL_quad_rd_sends', + 51: 'DB_PERF_SEL_quad_rd_busy', + 52: 'DB_PERF_SEL_quad_rd_mi_stall', + 53: 'DB_PERF_SEL_quad_rd_rw_collision', + 54: 'DB_PERF_SEL_quad_rd_tag_stall', + 55: 'DB_PERF_SEL_quad_rd_32byte_reqs', + 56: 'DB_PERF_SEL_quad_rd_panic', + 57: 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 58: 'DB_PERF_SEL_quad_rdret_sends', + 59: 'DB_PERF_SEL_quad_rdret_busy', + 60: 'DB_PERF_SEL_tile_wr_sends', + 61: 'DB_PERF_SEL_tile_wr_acks', + 62: 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 63: 'DB_PERF_SEL_quad_wr_sends', + 64: 'DB_PERF_SEL_quad_wr_busy', + 65: 'DB_PERF_SEL_quad_wr_mi_stall', + 66: 'DB_PERF_SEL_quad_wr_coherency_stall', + 67: 'DB_PERF_SEL_quad_wr_acks', + 68: 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 69: 'DB_PERF_SEL_Tile_Cache_misses', + 70: 'DB_PERF_SEL_Tile_Cache_hits', + 71: 'DB_PERF_SEL_Tile_Cache_flushes', + 72: 'DB_PERF_SEL_Tile_Cache_surface_stall', + 73: 'DB_PERF_SEL_Tile_Cache_starves', + 74: 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 75: 'DB_PERF_SEL_tcp_dispatcher_reads', + 76: 'DB_PERF_SEL_tcp_prefetcher_reads', + 77: 'DB_PERF_SEL_tcp_preloader_reads', + 78: 'DB_PERF_SEL_tcp_dispatcher_flushes', + 79: 'DB_PERF_SEL_tcp_prefetcher_flushes', + 80: 'DB_PERF_SEL_tcp_preloader_flushes', + 81: 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 82: 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 83: 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 84: 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 85: 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 86: 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 87: 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 88: 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 89: 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 90: 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 91: 'DB_PERF_SEL_Depth_Tile_Cache_event', + 92: 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 93: 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 94: 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 95: 'DB_PERF_SEL_Stencil_Cache_misses', + 96: 'DB_PERF_SEL_Stencil_Cache_hits', + 97: 'DB_PERF_SEL_Stencil_Cache_flushes', + 98: 'DB_PERF_SEL_Stencil_Cache_starves', + 99: 'DB_PERF_SEL_Stencil_Cache_frees', + 100: 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 101: 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 102: 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 103: 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 104: 'DB_PERF_SEL_Z_Cache_pmask_misses', + 105: 'DB_PERF_SEL_Z_Cache_pmask_hits', + 106: 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 107: 'DB_PERF_SEL_Z_Cache_pmask_starves', + 108: 'DB_PERF_SEL_Z_Cache_frees', + 109: 'DB_PERF_SEL_Plane_Cache_misses', + 110: 'DB_PERF_SEL_Plane_Cache_hits', + 111: 'DB_PERF_SEL_Plane_Cache_flushes', + 112: 'DB_PERF_SEL_Plane_Cache_starves', + 113: 'DB_PERF_SEL_Plane_Cache_frees', + 114: 'DB_PERF_SEL_flush_expanded_stencil', + 115: 'DB_PERF_SEL_flush_compressed_stencil', + 116: 'DB_PERF_SEL_flush_single_stencil', + 117: 'DB_PERF_SEL_planes_flushed', + 118: 'DB_PERF_SEL_flush_1plane', + 119: 'DB_PERF_SEL_flush_2plane', + 120: 'DB_PERF_SEL_flush_3plane', + 121: 'DB_PERF_SEL_flush_4plane', + 122: 'DB_PERF_SEL_flush_5plane', + 123: 'DB_PERF_SEL_flush_6plane', + 124: 'DB_PERF_SEL_flush_7plane', + 125: 'DB_PERF_SEL_flush_8plane', + 126: 'DB_PERF_SEL_flush_9plane', + 127: 'DB_PERF_SEL_flush_10plane', + 128: 'DB_PERF_SEL_flush_11plane', + 129: 'DB_PERF_SEL_flush_12plane', + 130: 'DB_PERF_SEL_flush_13plane', + 131: 'DB_PERF_SEL_flush_14plane', + 132: 'DB_PERF_SEL_flush_15plane', + 133: 'DB_PERF_SEL_flush_16plane', + 134: 'DB_PERF_SEL_flush_expanded_z', + 135: 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 136: 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 137: 'DB_PERF_SEL_dk_tile_sends', + 138: 'DB_PERF_SEL_dk_tile_busy', + 139: 'DB_PERF_SEL_dk_tile_quad_starves', + 140: 'DB_PERF_SEL_dk_tile_stalls', + 141: 'DB_PERF_SEL_dk_squad_sends', + 142: 'DB_PERF_SEL_dk_squad_busy', + 143: 'DB_PERF_SEL_dk_squad_stalls', + 144: 'DB_PERF_SEL_Op_Pipe_Busy', + 145: 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 146: 'DB_PERF_SEL_qc_busy', + 147: 'DB_PERF_SEL_qc_xfc', + 148: 'DB_PERF_SEL_qc_conflicts', + 149: 'DB_PERF_SEL_qc_full_stall', + 150: 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', + 151: 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 152: 'DB_PERF_SEL_tsc_insert_summarize_stall', + 153: 'DB_PERF_SEL_tl_busy', + 154: 'DB_PERF_SEL_tl_dtc_read_starved', + 155: 'DB_PERF_SEL_tl_z_fetch_stall', + 156: 'DB_PERF_SEL_tl_stencil_stall', + 157: 'DB_PERF_SEL_tl_z_decompress_stall', + 158: 'DB_PERF_SEL_tl_stencil_locked_stall', + 159: 'DB_PERF_SEL_tl_events', + 160: 'DB_PERF_SEL_tl_summarize_squads', + 161: 'DB_PERF_SEL_tl_flush_expand_squads', + 162: 'DB_PERF_SEL_tl_expand_squads', + 163: 'DB_PERF_SEL_tl_preZ_squads', + 164: 'DB_PERF_SEL_tl_postZ_squads', + 165: 'DB_PERF_SEL_tl_preZ_noop_squads', + 166: 'DB_PERF_SEL_tl_postZ_noop_squads', + 167: 'DB_PERF_SEL_tl_tile_ops', + 168: 'DB_PERF_SEL_tl_in_xfc', + 169: 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 170: 'DB_PERF_SEL_tl_in_fast_z_stall', + 171: 'DB_PERF_SEL_tl_out_xfc', + 172: 'DB_PERF_SEL_tl_out_squads', + 173: 'DB_PERF_SEL_zf_plane_multicycle', + 174: 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 175: 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 176: 'DB_PERF_SEL_PostZ_Samples_failing_S', + 177: 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 178: 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 179: 'DB_PERF_SEL_PreZ_Samples_failing_S', + 180: 'DB_PERF_SEL_ts_tc_update_stall', + 181: 'DB_PERF_SEL_sc_kick_start', + 182: 'DB_PERF_SEL_sc_kick_end', + 183: 'DB_PERF_SEL_clock_reg_active', + 184: 'DB_PERF_SEL_clock_main_active', + 185: 'DB_PERF_SEL_clock_mem_export_active', + 186: 'DB_PERF_SEL_esr_ps_out_busy', + 187: 'DB_PERF_SEL_esr_ps_lqf_busy', + 188: 'DB_PERF_SEL_esr_ps_lqf_stall', + 189: 'DB_PERF_SEL_etr_out_send', + 190: 'DB_PERF_SEL_etr_out_busy', + 191: 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 192: 'DB_PERF_SEL_etr_out_cb_tile_stall', + 193: 'DB_PERF_SEL_etr_out_esr_stall', + 194: 'DB_PERF_SEL_esr_ps_vic_busy', + 195: 'DB_PERF_SEL_esr_ps_vic_stall', + 196: 'DB_PERF_SEL_esr_eot_fwd_busy', + 197: 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 198: 'DB_PERF_SEL_esr_eot_fwd_forward', + 199: 'DB_PERF_SEL_esr_sqq_zi_busy', + 200: 'DB_PERF_SEL_esr_sqq_zi_stall', + 201: 'DB_PERF_SEL_postzl_sq_pt_busy', + 202: 'DB_PERF_SEL_postzl_sq_pt_stall', + 203: 'DB_PERF_SEL_postzl_se_busy', + 204: 'DB_PERF_SEL_postzl_se_stall', + 205: 'DB_PERF_SEL_postzl_partial_launch', + 206: 'DB_PERF_SEL_postzl_full_launch', + 207: 'DB_PERF_SEL_postzl_partial_waiting', + 208: 'DB_PERF_SEL_postzl_tile_mem_stall', + 209: 'DB_PERF_SEL_postzl_tile_init_stall', + 210: 'DB_PERF_SEL_prezl_tile_mem_stall', + 211: 'DB_PERF_SEL_prezl_tile_init_stall', + 212: 'DB_PERF_SEL_dtt_sm_clash_stall', + 213: 'DB_PERF_SEL_dtt_sm_slot_stall', + 214: 'DB_PERF_SEL_dtt_sm_miss_stall', + 215: 'DB_PERF_SEL_mi_rdreq_busy', + 216: 'DB_PERF_SEL_mi_rdreq_stall', + 217: 'DB_PERF_SEL_mi_wrreq_busy', + 218: 'DB_PERF_SEL_mi_wrreq_stall', + 219: 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 220: 'DB_PERF_SEL_dkg_tile_rate_tile', + 221: 'DB_PERF_SEL_prezl_src_in_sends', + 222: 'DB_PERF_SEL_prezl_src_in_stall', + 223: 'DB_PERF_SEL_prezl_src_in_squads', + 224: 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 225: 'DB_PERF_SEL_prezl_src_in_tile_rate', + 226: 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 227: 'DB_PERF_SEL_prezl_src_out_stall', + 228: 'DB_PERF_SEL_postzl_src_in_sends', + 229: 'DB_PERF_SEL_postzl_src_in_stall', + 230: 'DB_PERF_SEL_postzl_src_in_squads', + 231: 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 232: 'DB_PERF_SEL_postzl_src_in_tile_rate', + 233: 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 234: 'DB_PERF_SEL_postzl_src_out_stall', + 235: 'DB_PERF_SEL_esr_ps_src_in_sends', + 236: 'DB_PERF_SEL_esr_ps_src_in_stall', + 237: 'DB_PERF_SEL_esr_ps_src_in_squads', + 238: 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 239: 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 240: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 241: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 242: 'DB_PERF_SEL_esr_ps_src_out_stall', + 243: 'DB_PERF_SEL_depth_bounds_tile_culled', + 244: 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 245: 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 246: 'DB_PERF_SEL_flush_compressed', + 247: 'DB_PERF_SEL_flush_plane_le4', + 248: 'DB_PERF_SEL_tiles_z_fully_summarized', + 249: 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 250: 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 251: 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 252: 'DB_PERF_SEL_tiles_decomp_on_expclear', + 253: 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 254: 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 255: 'DB_PERF_SEL_Op_Pipe_Postz_Busy', + 256: 'DB_PERF_SEL_di_dt_stall', + 257: 'Spare_257', + 258: 'DB_PERF_SEL_DB_SC_s_tile_rate', + 259: 'DB_PERF_SEL_DB_SC_c_tile_rate', + 260: 'DB_PERF_SEL_DB_SC_z_tile_rate', + 261: 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 262: 'DB_PERF_SEL_DB_CB_lquad_double_format', + 263: 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 264: 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 265: 'DB_PERF_SEL_CB_DB_rdreq_sends', + 266: 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 267: 'DB_PERF_SEL_CB_DB_wrreq_sends', + 268: 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 269: 'DB_PERF_SEL_DB_CB_rdret_ack', + 270: 'DB_PERF_SEL_DB_CB_rdret_nack', + 271: 'DB_PERF_SEL_DB_CB_wrret_ack', + 272: 'DB_PERF_SEL_DB_CB_wrret_nack', + 273: 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 274: 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 275: 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 276: 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 277: 'DB_PERF_SEL_unmapped_z_tile_culled', + 278: 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS', + 279: 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 280: 'DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS', + 281: 'DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event', + 282: 'DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix', + 283: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix', + 284: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix', + 285: 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix', + 286: 'DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending', + 287: 'DB_PERF_SEL_DB_CB_context_dones', + 288: 'DB_PERF_SEL_DB_CB_eop_dones', + 289: 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 290: 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 291: 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 292: 'DB_PERF_SEL_SC_DB_tile_backface', + 293: 'DB_PERF_SEL_SC_DB_quad_quads', + 294: 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 295: 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 296: 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 297: 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 298: 'DB_PERF_SEL_DB_SC_quad_double_quad', + 299: 'DB_PERF_SEL_SX_DB_quad_export_quads', + 300: 'DB_PERF_SEL_SX_DB_quad_double_format', + 301: 'DB_PERF_SEL_SX_DB_quad_fast_format', + 302: 'DB_PERF_SEL_SX_DB_quad_slow_format', + 303: 'DB_PERF_SEL_quad_rd_sends_unc', + 304: 'DB_PERF_SEL_quad_rd_mi_stall_unc', + 305: 'DB_PERF_SEL_SC_DB_tile_tiles_pipe0', + 306: 'DB_PERF_SEL_SC_DB_tile_tiles_pipe1', + 307: 'DB_PERF_SEL_SC_DB_quad_quads_pipe0', + 308: 'DB_PERF_SEL_SC_DB_quad_quads_pipe1', + 309: 'DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits', + 310: 'DB_PERF_SEL_noz_waiting_for_postz_done', + 311: 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x1', + 312: 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x1', + 313: 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x2', + 314: 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x2', + 315: 'DB_PERF_SEL_RMI_rd_tile_32byte_req', + 316: 'DB_PERF_SEL_RMI_rd_z_32byte_req', + 317: 'DB_PERF_SEL_RMI_rd_s_32byte_req', + 318: 'DB_PERF_SEL_RMI_wr_tile_32byte_req', + 319: 'DB_PERF_SEL_RMI_wr_z_32byte_req', + 320: 'DB_PERF_SEL_RMI_wr_s_32byte_req', + 321: 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_req', + 322: 'DB_PERF_SEL_RMI_rd_tile_32byte_ret', + 323: 'DB_PERF_SEL_RMI_rd_z_32byte_ret', + 324: 'DB_PERF_SEL_RMI_rd_s_32byte_ret', + 325: 'DB_PERF_SEL_RMI_wr_tile_32byte_ack', + 326: 'DB_PERF_SEL_RMI_wr_z_32byte_ack', + 327: 'DB_PERF_SEL_RMI_wr_s_32byte_ack', + 328: 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack', + 329: 'DB_PERF_SEL_esr_vic_sqq_busy', + 330: 'DB_PERF_SEL_esr_vic_sqq_stall', + 331: 'DB_PERF_SEL_esr_psi_vic_tile_rate', + 332: 'DB_PERF_SEL_esr_vic_footprint_match_2x2', + 333: 'DB_PERF_SEL_esr_vic_footprint_match_2x1', + 334: 'DB_PERF_SEL_esr_vic_footprint_match_1x2', + 335: 'DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels', + 336: 'DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels', + 337: 'DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels', + 338: 'DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1', + 339: 'DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1', + 340: 'DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut', + 341: 'DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut', + 342: 'DB_PERF_SEL_prez_ps_invoked_pixel_cnt', + 343: 'DB_PERF_SEL_postz_ps_invoked_pixel_cnt', + 344: 'DB_PERF_SEL_ts_events_pws_enable', + 345: 'DB_PERF_SEL_ps_events_pws_enable', + 346: 'DB_PERF_SEL_cs_events_pws_enable', + 347: 'DB_PERF_SEL_DB_SC_quad_noz_tiles', + 348: 'DB_PERF_SEL_DB_SC_quad_lit_noz_quad', +} +DB_PERF_SEL_SC_DB_tile_sends = 0 +DB_PERF_SEL_SC_DB_tile_busy = 1 +DB_PERF_SEL_SC_DB_tile_stalls = 2 +DB_PERF_SEL_SC_DB_tile_events = 3 +DB_PERF_SEL_SC_DB_tile_tiles = 4 +DB_PERF_SEL_SC_DB_tile_covered = 5 +DB_PERF_SEL_hiz_tc_read_starved = 6 +DB_PERF_SEL_hiz_tc_write_stall = 7 +DB_PERF_SEL_hiz_tile_culled = 8 +DB_PERF_SEL_his_tile_culled = 9 +DB_PERF_SEL_DB_SC_tile_sends = 10 +DB_PERF_SEL_DB_SC_tile_busy = 11 +DB_PERF_SEL_DB_SC_tile_stalls = 12 +DB_PERF_SEL_DB_SC_tile_df_stalls = 13 +DB_PERF_SEL_DB_SC_tile_tiles = 14 +DB_PERF_SEL_DB_SC_tile_culled = 15 +DB_PERF_SEL_DB_SC_tile_hier_kill = 16 +DB_PERF_SEL_DB_SC_tile_fast_ops = 17 +DB_PERF_SEL_DB_SC_tile_no_ops = 18 +DB_PERF_SEL_DB_SC_tile_tile_rate = 19 +DB_PERF_SEL_DB_SC_tile_ssaa_kill = 20 +DB_PERF_SEL_DB_SC_tile_fast_z_ops = 21 +DB_PERF_SEL_DB_SC_tile_fast_stencil_ops = 22 +DB_PERF_SEL_SC_DB_quad_sends = 23 +DB_PERF_SEL_SC_DB_quad_busy = 24 +DB_PERF_SEL_SC_DB_quad_squads = 25 +DB_PERF_SEL_SC_DB_quad_tiles = 26 +DB_PERF_SEL_SC_DB_quad_pixels = 27 +DB_PERF_SEL_SC_DB_quad_killed_tiles = 28 +DB_PERF_SEL_DB_SC_quad_sends = 29 +DB_PERF_SEL_DB_SC_quad_busy = 30 +DB_PERF_SEL_DB_SC_quad_stalls = 31 +DB_PERF_SEL_DB_SC_quad_tiles = 32 +DB_PERF_SEL_DB_SC_quad_lit_quad = 33 +DB_PERF_SEL_DB_CB_tile_sends = 34 +DB_PERF_SEL_DB_CB_tile_busy = 35 +DB_PERF_SEL_DB_CB_tile_stalls = 36 +DB_PERF_SEL_SX_DB_quad_sends = 37 +DB_PERF_SEL_SX_DB_quad_busy = 38 +DB_PERF_SEL_SX_DB_quad_stalls = 39 +DB_PERF_SEL_SX_DB_quad_quads = 40 +DB_PERF_SEL_SX_DB_quad_pixels = 41 +DB_PERF_SEL_SX_DB_quad_exports = 42 +DB_PERF_SEL_SH_quads_outstanding_sum = 43 +DB_PERF_SEL_DB_CB_lquad_sends = 44 +DB_PERF_SEL_DB_CB_lquad_busy = 45 +DB_PERF_SEL_DB_CB_lquad_stalls = 46 +DB_PERF_SEL_DB_CB_lquad_quads = 47 +DB_PERF_SEL_tile_rd_sends = 48 +DB_PERF_SEL_mi_tile_rd_outstanding_sum = 49 +DB_PERF_SEL_quad_rd_sends = 50 +DB_PERF_SEL_quad_rd_busy = 51 +DB_PERF_SEL_quad_rd_mi_stall = 52 +DB_PERF_SEL_quad_rd_rw_collision = 53 +DB_PERF_SEL_quad_rd_tag_stall = 54 +DB_PERF_SEL_quad_rd_32byte_reqs = 55 +DB_PERF_SEL_quad_rd_panic = 56 +DB_PERF_SEL_mi_quad_rd_outstanding_sum = 57 +DB_PERF_SEL_quad_rdret_sends = 58 +DB_PERF_SEL_quad_rdret_busy = 59 +DB_PERF_SEL_tile_wr_sends = 60 +DB_PERF_SEL_tile_wr_acks = 61 +DB_PERF_SEL_mi_tile_wr_outstanding_sum = 62 +DB_PERF_SEL_quad_wr_sends = 63 +DB_PERF_SEL_quad_wr_busy = 64 +DB_PERF_SEL_quad_wr_mi_stall = 65 +DB_PERF_SEL_quad_wr_coherency_stall = 66 +DB_PERF_SEL_quad_wr_acks = 67 +DB_PERF_SEL_mi_quad_wr_outstanding_sum = 68 +DB_PERF_SEL_Tile_Cache_misses = 69 +DB_PERF_SEL_Tile_Cache_hits = 70 +DB_PERF_SEL_Tile_Cache_flushes = 71 +DB_PERF_SEL_Tile_Cache_surface_stall = 72 +DB_PERF_SEL_Tile_Cache_starves = 73 +DB_PERF_SEL_Tile_Cache_mem_return_starve = 74 +DB_PERF_SEL_tcp_dispatcher_reads = 75 +DB_PERF_SEL_tcp_prefetcher_reads = 76 +DB_PERF_SEL_tcp_preloader_reads = 77 +DB_PERF_SEL_tcp_dispatcher_flushes = 78 +DB_PERF_SEL_tcp_prefetcher_flushes = 79 +DB_PERF_SEL_tcp_preloader_flushes = 80 +DB_PERF_SEL_Depth_Tile_Cache_sends = 81 +DB_PERF_SEL_Depth_Tile_Cache_busy = 82 +DB_PERF_SEL_Depth_Tile_Cache_starves = 83 +DB_PERF_SEL_Depth_Tile_Cache_dtile_locked = 84 +DB_PERF_SEL_Depth_Tile_Cache_alloc_stall = 85 +DB_PERF_SEL_Depth_Tile_Cache_misses = 86 +DB_PERF_SEL_Depth_Tile_Cache_hits = 87 +DB_PERF_SEL_Depth_Tile_Cache_flushes = 88 +DB_PERF_SEL_Depth_Tile_Cache_noop_tile = 89 +DB_PERF_SEL_Depth_Tile_Cache_detailed_noop = 90 +DB_PERF_SEL_Depth_Tile_Cache_event = 91 +DB_PERF_SEL_Depth_Tile_Cache_tile_frees = 92 +DB_PERF_SEL_Depth_Tile_Cache_data_frees = 93 +DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve = 94 +DB_PERF_SEL_Stencil_Cache_misses = 95 +DB_PERF_SEL_Stencil_Cache_hits = 96 +DB_PERF_SEL_Stencil_Cache_flushes = 97 +DB_PERF_SEL_Stencil_Cache_starves = 98 +DB_PERF_SEL_Stencil_Cache_frees = 99 +DB_PERF_SEL_Z_Cache_separate_Z_misses = 100 +DB_PERF_SEL_Z_Cache_separate_Z_hits = 101 +DB_PERF_SEL_Z_Cache_separate_Z_flushes = 102 +DB_PERF_SEL_Z_Cache_separate_Z_starves = 103 +DB_PERF_SEL_Z_Cache_pmask_misses = 104 +DB_PERF_SEL_Z_Cache_pmask_hits = 105 +DB_PERF_SEL_Z_Cache_pmask_flushes = 106 +DB_PERF_SEL_Z_Cache_pmask_starves = 107 +DB_PERF_SEL_Z_Cache_frees = 108 +DB_PERF_SEL_Plane_Cache_misses = 109 +DB_PERF_SEL_Plane_Cache_hits = 110 +DB_PERF_SEL_Plane_Cache_flushes = 111 +DB_PERF_SEL_Plane_Cache_starves = 112 +DB_PERF_SEL_Plane_Cache_frees = 113 +DB_PERF_SEL_flush_expanded_stencil = 114 +DB_PERF_SEL_flush_compressed_stencil = 115 +DB_PERF_SEL_flush_single_stencil = 116 +DB_PERF_SEL_planes_flushed = 117 +DB_PERF_SEL_flush_1plane = 118 +DB_PERF_SEL_flush_2plane = 119 +DB_PERF_SEL_flush_3plane = 120 +DB_PERF_SEL_flush_4plane = 121 +DB_PERF_SEL_flush_5plane = 122 +DB_PERF_SEL_flush_6plane = 123 +DB_PERF_SEL_flush_7plane = 124 +DB_PERF_SEL_flush_8plane = 125 +DB_PERF_SEL_flush_9plane = 126 +DB_PERF_SEL_flush_10plane = 127 +DB_PERF_SEL_flush_11plane = 128 +DB_PERF_SEL_flush_12plane = 129 +DB_PERF_SEL_flush_13plane = 130 +DB_PERF_SEL_flush_14plane = 131 +DB_PERF_SEL_flush_15plane = 132 +DB_PERF_SEL_flush_16plane = 133 +DB_PERF_SEL_flush_expanded_z = 134 +DB_PERF_SEL_earlyZ_waiting_for_postZ_done = 135 +DB_PERF_SEL_reZ_waiting_for_postZ_done = 136 +DB_PERF_SEL_dk_tile_sends = 137 +DB_PERF_SEL_dk_tile_busy = 138 +DB_PERF_SEL_dk_tile_quad_starves = 139 +DB_PERF_SEL_dk_tile_stalls = 140 +DB_PERF_SEL_dk_squad_sends = 141 +DB_PERF_SEL_dk_squad_busy = 142 +DB_PERF_SEL_dk_squad_stalls = 143 +DB_PERF_SEL_Op_Pipe_Busy = 144 +DB_PERF_SEL_Op_Pipe_MC_Read_stall = 145 +DB_PERF_SEL_qc_busy = 146 +DB_PERF_SEL_qc_xfc = 147 +DB_PERF_SEL_qc_conflicts = 148 +DB_PERF_SEL_qc_full_stall = 149 +DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ = 150 +DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ = 151 +DB_PERF_SEL_tsc_insert_summarize_stall = 152 +DB_PERF_SEL_tl_busy = 153 +DB_PERF_SEL_tl_dtc_read_starved = 154 +DB_PERF_SEL_tl_z_fetch_stall = 155 +DB_PERF_SEL_tl_stencil_stall = 156 +DB_PERF_SEL_tl_z_decompress_stall = 157 +DB_PERF_SEL_tl_stencil_locked_stall = 158 +DB_PERF_SEL_tl_events = 159 +DB_PERF_SEL_tl_summarize_squads = 160 +DB_PERF_SEL_tl_flush_expand_squads = 161 +DB_PERF_SEL_tl_expand_squads = 162 +DB_PERF_SEL_tl_preZ_squads = 163 +DB_PERF_SEL_tl_postZ_squads = 164 +DB_PERF_SEL_tl_preZ_noop_squads = 165 +DB_PERF_SEL_tl_postZ_noop_squads = 166 +DB_PERF_SEL_tl_tile_ops = 167 +DB_PERF_SEL_tl_in_xfc = 168 +DB_PERF_SEL_tl_in_single_stencil_expand_stall = 169 +DB_PERF_SEL_tl_in_fast_z_stall = 170 +DB_PERF_SEL_tl_out_xfc = 171 +DB_PERF_SEL_tl_out_squads = 172 +DB_PERF_SEL_zf_plane_multicycle = 173 +DB_PERF_SEL_PostZ_Samples_passing_Z = 174 +DB_PERF_SEL_PostZ_Samples_failing_Z = 175 +DB_PERF_SEL_PostZ_Samples_failing_S = 176 +DB_PERF_SEL_PreZ_Samples_passing_Z = 177 +DB_PERF_SEL_PreZ_Samples_failing_Z = 178 +DB_PERF_SEL_PreZ_Samples_failing_S = 179 +DB_PERF_SEL_ts_tc_update_stall = 180 +DB_PERF_SEL_sc_kick_start = 181 +DB_PERF_SEL_sc_kick_end = 182 +DB_PERF_SEL_clock_reg_active = 183 +DB_PERF_SEL_clock_main_active = 184 +DB_PERF_SEL_clock_mem_export_active = 185 +DB_PERF_SEL_esr_ps_out_busy = 186 +DB_PERF_SEL_esr_ps_lqf_busy = 187 +DB_PERF_SEL_esr_ps_lqf_stall = 188 +DB_PERF_SEL_etr_out_send = 189 +DB_PERF_SEL_etr_out_busy = 190 +DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall = 191 +DB_PERF_SEL_etr_out_cb_tile_stall = 192 +DB_PERF_SEL_etr_out_esr_stall = 193 +DB_PERF_SEL_esr_ps_vic_busy = 194 +DB_PERF_SEL_esr_ps_vic_stall = 195 +DB_PERF_SEL_esr_eot_fwd_busy = 196 +DB_PERF_SEL_esr_eot_fwd_holding_squad = 197 +DB_PERF_SEL_esr_eot_fwd_forward = 198 +DB_PERF_SEL_esr_sqq_zi_busy = 199 +DB_PERF_SEL_esr_sqq_zi_stall = 200 +DB_PERF_SEL_postzl_sq_pt_busy = 201 +DB_PERF_SEL_postzl_sq_pt_stall = 202 +DB_PERF_SEL_postzl_se_busy = 203 +DB_PERF_SEL_postzl_se_stall = 204 +DB_PERF_SEL_postzl_partial_launch = 205 +DB_PERF_SEL_postzl_full_launch = 206 +DB_PERF_SEL_postzl_partial_waiting = 207 +DB_PERF_SEL_postzl_tile_mem_stall = 208 +DB_PERF_SEL_postzl_tile_init_stall = 209 +DB_PERF_SEL_prezl_tile_mem_stall = 210 +DB_PERF_SEL_prezl_tile_init_stall = 211 +DB_PERF_SEL_dtt_sm_clash_stall = 212 +DB_PERF_SEL_dtt_sm_slot_stall = 213 +DB_PERF_SEL_dtt_sm_miss_stall = 214 +DB_PERF_SEL_mi_rdreq_busy = 215 +DB_PERF_SEL_mi_rdreq_stall = 216 +DB_PERF_SEL_mi_wrreq_busy = 217 +DB_PERF_SEL_mi_wrreq_stall = 218 +DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop = 219 +DB_PERF_SEL_dkg_tile_rate_tile = 220 +DB_PERF_SEL_prezl_src_in_sends = 221 +DB_PERF_SEL_prezl_src_in_stall = 222 +DB_PERF_SEL_prezl_src_in_squads = 223 +DB_PERF_SEL_prezl_src_in_squads_unrolled = 224 +DB_PERF_SEL_prezl_src_in_tile_rate = 225 +DB_PERF_SEL_prezl_src_in_tile_rate_unrolled = 226 +DB_PERF_SEL_prezl_src_out_stall = 227 +DB_PERF_SEL_postzl_src_in_sends = 228 +DB_PERF_SEL_postzl_src_in_stall = 229 +DB_PERF_SEL_postzl_src_in_squads = 230 +DB_PERF_SEL_postzl_src_in_squads_unrolled = 231 +DB_PERF_SEL_postzl_src_in_tile_rate = 232 +DB_PERF_SEL_postzl_src_in_tile_rate_unrolled = 233 +DB_PERF_SEL_postzl_src_out_stall = 234 +DB_PERF_SEL_esr_ps_src_in_sends = 235 +DB_PERF_SEL_esr_ps_src_in_stall = 236 +DB_PERF_SEL_esr_ps_src_in_squads = 237 +DB_PERF_SEL_esr_ps_src_in_squads_unrolled = 238 +DB_PERF_SEL_esr_ps_src_in_tile_rate = 239 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled = 240 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate = 241 +DB_PERF_SEL_esr_ps_src_out_stall = 242 +DB_PERF_SEL_depth_bounds_tile_culled = 243 +DB_PERF_SEL_PreZ_Samples_failing_DB = 244 +DB_PERF_SEL_PostZ_Samples_failing_DB = 245 +DB_PERF_SEL_flush_compressed = 246 +DB_PERF_SEL_flush_plane_le4 = 247 +DB_PERF_SEL_tiles_z_fully_summarized = 248 +DB_PERF_SEL_tiles_stencil_fully_summarized = 249 +DB_PERF_SEL_tiles_z_clear_on_expclear = 250 +DB_PERF_SEL_tiles_s_clear_on_expclear = 251 +DB_PERF_SEL_tiles_decomp_on_expclear = 252 +DB_PERF_SEL_tiles_compressed_to_decompressed = 253 +DB_PERF_SEL_Op_Pipe_Prez_Busy = 254 +DB_PERF_SEL_Op_Pipe_Postz_Busy = 255 +DB_PERF_SEL_di_dt_stall = 256 +Spare_257 = 257 +DB_PERF_SEL_DB_SC_s_tile_rate = 258 +DB_PERF_SEL_DB_SC_c_tile_rate = 259 +DB_PERF_SEL_DB_SC_z_tile_rate = 260 +DB_PERF_SEL_DB_CB_lquad_export_quads = 261 +DB_PERF_SEL_DB_CB_lquad_double_format = 262 +DB_PERF_SEL_DB_CB_lquad_fast_format = 263 +DB_PERF_SEL_DB_CB_lquad_slow_format = 264 +DB_PERF_SEL_CB_DB_rdreq_sends = 265 +DB_PERF_SEL_CB_DB_rdreq_prt_sends = 266 +DB_PERF_SEL_CB_DB_wrreq_sends = 267 +DB_PERF_SEL_CB_DB_wrreq_prt_sends = 268 +DB_PERF_SEL_DB_CB_rdret_ack = 269 +DB_PERF_SEL_DB_CB_rdret_nack = 270 +DB_PERF_SEL_DB_CB_wrret_ack = 271 +DB_PERF_SEL_DB_CB_wrret_nack = 272 +DB_PERF_SEL_MI_tile_req_wrack_counter_stall = 273 +DB_PERF_SEL_MI_quad_req_wrack_counter_stall = 274 +DB_PERF_SEL_MI_zpc_req_wrack_counter_stall = 275 +DB_PERF_SEL_MI_psd_req_wrack_counter_stall = 276 +DB_PERF_SEL_unmapped_z_tile_culled = 277 +DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS = 278 +DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA = 279 +DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS = 280 +DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event = 281 +DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix = 282 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix = 283 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix = 284 +DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix = 285 +DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending = 286 +DB_PERF_SEL_DB_CB_context_dones = 287 +DB_PERF_SEL_DB_CB_eop_dones = 288 +DB_PERF_SEL_SX_DB_quad_all_pixels_killed = 289 +DB_PERF_SEL_SX_DB_quad_all_pixels_enabled = 290 +DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read = 291 +DB_PERF_SEL_SC_DB_tile_backface = 292 +DB_PERF_SEL_SC_DB_quad_quads = 293 +DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel = 294 +DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels = 295 +DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels = 296 +DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels = 297 +DB_PERF_SEL_DB_SC_quad_double_quad = 298 +DB_PERF_SEL_SX_DB_quad_export_quads = 299 +DB_PERF_SEL_SX_DB_quad_double_format = 300 +DB_PERF_SEL_SX_DB_quad_fast_format = 301 +DB_PERF_SEL_SX_DB_quad_slow_format = 302 +DB_PERF_SEL_quad_rd_sends_unc = 303 +DB_PERF_SEL_quad_rd_mi_stall_unc = 304 +DB_PERF_SEL_SC_DB_tile_tiles_pipe0 = 305 +DB_PERF_SEL_SC_DB_tile_tiles_pipe1 = 306 +DB_PERF_SEL_SC_DB_quad_quads_pipe0 = 307 +DB_PERF_SEL_SC_DB_quad_quads_pipe1 = 308 +DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits = 309 +DB_PERF_SEL_noz_waiting_for_postz_done = 310 +DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x1 = 311 +DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x1 = 312 +DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x2 = 313 +DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x2 = 314 +DB_PERF_SEL_RMI_rd_tile_32byte_req = 315 +DB_PERF_SEL_RMI_rd_z_32byte_req = 316 +DB_PERF_SEL_RMI_rd_s_32byte_req = 317 +DB_PERF_SEL_RMI_wr_tile_32byte_req = 318 +DB_PERF_SEL_RMI_wr_z_32byte_req = 319 +DB_PERF_SEL_RMI_wr_s_32byte_req = 320 +DB_PERF_SEL_RMI_wr_psdzpc_32byte_req = 321 +DB_PERF_SEL_RMI_rd_tile_32byte_ret = 322 +DB_PERF_SEL_RMI_rd_z_32byte_ret = 323 +DB_PERF_SEL_RMI_rd_s_32byte_ret = 324 +DB_PERF_SEL_RMI_wr_tile_32byte_ack = 325 +DB_PERF_SEL_RMI_wr_z_32byte_ack = 326 +DB_PERF_SEL_RMI_wr_s_32byte_ack = 327 +DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack = 328 +DB_PERF_SEL_esr_vic_sqq_busy = 329 +DB_PERF_SEL_esr_vic_sqq_stall = 330 +DB_PERF_SEL_esr_psi_vic_tile_rate = 331 +DB_PERF_SEL_esr_vic_footprint_match_2x2 = 332 +DB_PERF_SEL_esr_vic_footprint_match_2x1 = 333 +DB_PERF_SEL_esr_vic_footprint_match_1x2 = 334 +DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels = 335 +DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels = 336 +DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels = 337 +DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1 = 338 +DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1 = 339 +DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut = 340 +DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut = 341 +DB_PERF_SEL_prez_ps_invoked_pixel_cnt = 342 +DB_PERF_SEL_postz_ps_invoked_pixel_cnt = 343 +DB_PERF_SEL_ts_events_pws_enable = 344 +DB_PERF_SEL_ps_events_pws_enable = 345 +DB_PERF_SEL_cs_events_pws_enable = 346 +DB_PERF_SEL_DB_SC_quad_noz_tiles = 347 +DB_PERF_SEL_DB_SC_quad_lit_noz_quad = 348 +PerfCounter_Vals = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeCounterId' +PixelPipeCounterId__enumvalues = { + 0: 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 1: 'PIXEL_PIPE_OCCLUSION_COUNT_1', + 2: 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 3: 'PIXEL_PIPE_OCCLUSION_COUNT_3', + 4: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 5: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 6: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', + 7: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', +} +PIXEL_PIPE_OCCLUSION_COUNT_0 = 0 +PIXEL_PIPE_OCCLUSION_COUNT_1 = 1 +PIXEL_PIPE_OCCLUSION_COUNT_2 = 2 +PIXEL_PIPE_OCCLUSION_COUNT_3 = 3 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_0 = 4 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_0 = 5 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_1 = 6 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_1 = 7 +PixelPipeCounterId = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeStride' +PixelPipeStride__enumvalues = { + 0: 'PIXEL_PIPE_STRIDE_32_BITS', + 1: 'PIXEL_PIPE_STRIDE_64_BITS', + 2: 'PIXEL_PIPE_STRIDE_128_BITS', + 3: 'PIXEL_PIPE_STRIDE_256_BITS', +} +PIXEL_PIPE_STRIDE_32_BITS = 0 +PIXEL_PIPE_STRIDE_64_BITS = 1 +PIXEL_PIPE_STRIDE_128_BITS = 2 +PIXEL_PIPE_STRIDE_256_BITS = 3 +PixelPipeStride = ctypes.c_uint32 # enum + +# values for enumeration 'RingCounterControl' +RingCounterControl__enumvalues = { + 0: 'COUNTER_RING_SPLIT', + 1: 'COUNTER_RING_0', + 2: 'COUNTER_RING_1', +} +COUNTER_RING_SPLIT = 0 +COUNTER_RING_0 = 1 +COUNTER_RING_1 = 2 +RingCounterControl = ctypes.c_uint32 # enum + +# values for enumeration 'StencilOp' +StencilOp__enumvalues = { + 0: 'STENCIL_KEEP', + 1: 'STENCIL_ZERO', + 2: 'STENCIL_ONES', + 3: 'STENCIL_REPLACE_TEST', + 4: 'STENCIL_REPLACE_OP', + 5: 'STENCIL_ADD_CLAMP', + 6: 'STENCIL_SUB_CLAMP', + 7: 'STENCIL_INVERT', + 8: 'STENCIL_ADD_WRAP', + 9: 'STENCIL_SUB_WRAP', + 10: 'STENCIL_AND', + 11: 'STENCIL_OR', + 12: 'STENCIL_XOR', + 13: 'STENCIL_NAND', + 14: 'STENCIL_NOR', + 15: 'STENCIL_XNOR', +} +STENCIL_KEEP = 0 +STENCIL_ZERO = 1 +STENCIL_ONES = 2 +STENCIL_REPLACE_TEST = 3 +STENCIL_REPLACE_OP = 4 +STENCIL_ADD_CLAMP = 5 +STENCIL_SUB_CLAMP = 6 +STENCIL_INVERT = 7 +STENCIL_ADD_WRAP = 8 +STENCIL_SUB_WRAP = 9 +STENCIL_AND = 10 +STENCIL_OR = 11 +STENCIL_XOR = 12 +STENCIL_NAND = 13 +STENCIL_NOR = 14 +STENCIL_XNOR = 15 +StencilOp = ctypes.c_uint32 # enum + +# values for enumeration 'ZLimitSumm' +ZLimitSumm__enumvalues = { + 0: 'FORCE_SUMM_OFF', + 1: 'FORCE_SUMM_MINZ', + 2: 'FORCE_SUMM_MAXZ', + 3: 'FORCE_SUMM_BOTH', +} +FORCE_SUMM_OFF = 0 +FORCE_SUMM_MINZ = 1 +FORCE_SUMM_MAXZ = 2 +FORCE_SUMM_BOTH = 3 +ZLimitSumm = ctypes.c_uint32 # enum + +# values for enumeration 'ZModeForce' +ZModeForce__enumvalues = { + 0: 'NO_FORCE', + 1: 'FORCE_EARLY_Z', + 2: 'FORCE_LATE_Z', + 3: 'FORCE_RE_Z', +} +NO_FORCE = 0 +FORCE_EARLY_Z = 1 +FORCE_LATE_Z = 2 +FORCE_RE_Z = 3 +ZModeForce = ctypes.c_uint32 # enum + +# values for enumeration 'ZOrder' +ZOrder__enumvalues = { + 0: 'LATE_Z', + 1: 'EARLY_Z_THEN_LATE_Z', + 2: 'RE_Z', + 3: 'EARLY_Z_THEN_RE_Z', +} +LATE_Z = 0 +EARLY_Z_THEN_LATE_Z = 1 +RE_Z = 2 +EARLY_Z_THEN_RE_Z = 3 +ZOrder = ctypes.c_uint32 # enum + +# values for enumeration 'ZSamplePosition' +ZSamplePosition__enumvalues = { + 0: 'Z_SAMPLE_CENTER', + 1: 'Z_SAMPLE_CENTROID', +} +Z_SAMPLE_CENTER = 0 +Z_SAMPLE_CENTROID = 1 +ZSamplePosition = ctypes.c_uint32 # enum + +# values for enumeration 'ZpassControl' +ZpassControl__enumvalues = { + 0: 'ZPASS_DISABLE', + 1: 'ZPASS_SAMPLES', + 2: 'ZPASS_PIXELS', +} +ZPASS_DISABLE = 0 +ZPASS_SAMPLES = 1 +ZPASS_PIXELS = 2 +ZpassControl = ctypes.c_uint32 # enum + +# values for enumeration 'SU_PERFCNT_SEL' +SU_PERFCNT_SEL__enumvalues = { + 0: 'PERF_PAPC_PASX_REQ', + 1: 'PERF_PAPC_PASX_DISABLE_PIPE', + 2: 'PERF_PAPC_PASX_FIRST_VECTOR', + 3: 'PERF_PAPC_PASX_SECOND_VECTOR', + 4: 'PERF_PAPC_PASX_FIRST_DEAD', + 5: 'PERF_PAPC_PASX_SECOND_DEAD', + 6: 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 7: 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 8: 'PERF_PAPC_PA_INPUT_PRIM', + 9: 'PERF_PAPC_PA_INPUT_NULL_PRIM', + 10: 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 11: 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 12: 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 13: 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 14: 'PERF_PAPC_CLPR_CULL_PRIM', + 15: 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', + 16: 'PERF_PAPC_CLPR_VV_CULL_PRIM', + 17: 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 18: 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 19: 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 20: 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 21: 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 22: 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 23: 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', + 24: 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 25: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 26: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 27: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 28: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 29: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 30: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 31: 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 32: 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', + 33: 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 34: 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 35: 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', + 36: 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 37: 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 38: 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 39: 'PERF_PAPC_CLSM_NULL_PRIM', + 40: 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 41: 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', + 42: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', + 43: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 44: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', + 45: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 46: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 47: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 48: 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', + 49: 'PERF_PAPC_SU_INPUT_PRIM', + 50: 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 51: 'PERF_PAPC_SU_INPUT_NULL_PRIM', + 52: 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 53: 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 54: 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 55: 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 56: 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 57: 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 58: 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 59: 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 60: 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 61: 'PERF_PAPC_SU_OUTPUT_PRIM', + 62: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 63: 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 64: 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 65: 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 66: 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', + 67: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 68: 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 69: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', + 70: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 71: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 72: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 73: 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 74: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 75: 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 76: 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 77: 'PERF_PAPC_PASX_REQ_IDLE', + 78: 'PERF_PAPC_PASX_REQ_BUSY', + 79: 'PERF_PAPC_PASX_REQ_STALLED', + 80: 'PERF_PAPC_PASX_REC_IDLE', + 81: 'PERF_PAPC_PASX_REC_BUSY', + 82: 'PERF_PAPC_PASX_REC_STARVED_SX', + 83: 'PERF_PAPC_PASX_REC_STALLED', + 84: 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 85: 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 86: 'PERF_PAPC_CCGSM_IDLE', + 87: 'PERF_PAPC_CCGSM_BUSY', + 88: 'PERF_PAPC_CCGSM_STALLED', + 89: 'PERF_PAPC_CLPRIM_IDLE', + 90: 'PERF_PAPC_CLPRIM_BUSY', + 91: 'PERF_PAPC_CLPRIM_STALLED', + 92: 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 93: 'PERF_PAPC_CLIPSM_IDLE', + 94: 'PERF_PAPC_CLIPSM_BUSY', + 95: 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 96: 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', + 97: 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 98: 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 99: 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 100: 'PERF_PAPC_CLIPGA_IDLE', + 101: 'PERF_PAPC_CLIPGA_BUSY', + 102: 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 103: 'PERF_PAPC_CLIPGA_STALLED', + 104: 'PERF_PAPC_CLIP_IDLE', + 105: 'PERF_PAPC_CLIP_BUSY', + 106: 'PERF_PAPC_SU_IDLE', + 107: 'PERF_PAPC_SU_BUSY', + 108: 'PERF_PAPC_SU_STARVED_CLIP', + 109: 'PERF_PAPC_SU_STALLED_SC', + 110: 'PERF_PAPC_CL_DYN_SCLK_VLD', + 111: 'PERF_PAPC_SU_DYN_SCLK_VLD', + 112: 'PERF_PAPC_PA_REG_SCLK_VLD', + 113: 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 114: 'PERF_PAPC_PASX_SE0_REQ', + 115: 'PERF_PAPC_PASX_SE1_REQ', + 116: 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 117: 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 118: 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', + 119: 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', + 120: 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 121: 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 122: 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 123: 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 124: 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 125: 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 126: 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 127: 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 128: 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 129: 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 130: 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 131: 'PERF_PAPC_SU_SE0_STALLED_SC', + 132: 'PERF_PAPC_SU_SE1_STALLED_SC', + 133: 'PERF_PAPC_SU_SE01_STALLED_SC', + 134: 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 135: 'PERF_PAPC_SU_CULLED_PRIM', + 136: 'PERF_PAPC_SU_OUTPUT_EOPG', + 137: 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 138: 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 139: 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 140: 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 141: 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 142: 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 143: 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 144: 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 145: 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 146: 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 147: 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 148: 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 149: 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 150: 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 151: 'PERF_PAPC_SU_SE2_STALLED_SC', + 152: 'PERF_PAPC_SU_SE3_STALLED_SC', + 153: 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', + 154: 'PERF_SMALL_PRIM_CULL_PRIM_1X1', + 155: 'PERF_SMALL_PRIM_CULL_PRIM_2X1', + 156: 'PERF_SMALL_PRIM_CULL_PRIM_1X2', + 157: 'PERF_SMALL_PRIM_CULL_PRIM_2X2', + 158: 'PERF_SMALL_PRIM_CULL_PRIM_3X1', + 159: 'PERF_SMALL_PRIM_CULL_PRIM_1X3', + 160: 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 161: 'PERF_SMALL_PRIM_CULL_PRIM_2X3', + 162: 'PERF_SMALL_PRIM_CULL_PRIM_NX1', + 163: 'PERF_SMALL_PRIM_CULL_PRIM_1XN', + 164: 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 165: 'PERF_SMALL_PRIM_CULL_PRIM_2XN', + 166: 'PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT', + 167: 'PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT', + 168: 'PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT', + 170: 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 171: 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 172: 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 173: 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 174: 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 175: 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 176: 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 177: 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 179: 'PERF_PA_VERTEX_FIFO_FULL', + 180: 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', + 182: 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 183: 'PERF_PA_FETCH_TO_SXIF_FIFO_FULL', + 185: 'PERF_PA_PIPE0_SWITCHED_GEN', + 186: 'PERF_PA_PIPE1_SWITCHED_GEN', + 188: 'PERF_ENGG_CSB_MACHINE_IS_STARVED', + 189: 'PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 190: 'PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI', + 191: 'PERF_ENGG_CSB_GE_INPUT_FIFO_FULL', + 192: 'PERF_ENGG_CSB_SPI_INPUT_FIFO_FULL', + 193: 'PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL', + 194: 'PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT', + 195: 'PERF_ENGG_CSB_PRIM_COUNT_EQ0', + 196: 'PERF_ENGG_CSB_NULL_SUBGROUP', + 197: 'PERF_ENGG_CSB_GE_SENDING_SUBGROUP', + 198: 'PERF_ENGG_CSB_GE_MEMORY_FULL', + 199: 'PERF_ENGG_CSB_GE_MEMORY_EMPTY', + 200: 'PERF_ENGG_CSB_SPI_MEMORY_FULL', + 201: 'PERF_ENGG_CSB_SPI_MEMORY_EMPTY', + 202: 'PERF_ENGG_CSB_DELAY_BIN00', + 203: 'PERF_ENGG_CSB_DELAY_BIN01', + 204: 'PERF_ENGG_CSB_DELAY_BIN02', + 205: 'PERF_ENGG_CSB_DELAY_BIN03', + 206: 'PERF_ENGG_CSB_DELAY_BIN04', + 207: 'PERF_ENGG_CSB_DELAY_BIN05', + 208: 'PERF_ENGG_CSB_DELAY_BIN06', + 209: 'PERF_ENGG_CSB_DELAY_BIN07', + 210: 'PERF_ENGG_CSB_DELAY_BIN08', + 211: 'PERF_ENGG_CSB_DELAY_BIN09', + 212: 'PERF_ENGG_CSB_DELAY_BIN10', + 213: 'PERF_ENGG_CSB_DELAY_BIN11', + 214: 'PERF_ENGG_CSB_DELAY_BIN12', + 215: 'PERF_ENGG_CSB_DELAY_BIN13', + 216: 'PERF_ENGG_CSB_DELAY_BIN14', + 217: 'PERF_ENGG_CSB_DELAY_BIN15', + 218: 'PERF_ENGG_CSB_SPI_DELAY_BIN00', + 219: 'PERF_ENGG_CSB_SPI_DELAY_BIN01', + 220: 'PERF_ENGG_CSB_SPI_DELAY_BIN02', + 221: 'PERF_ENGG_CSB_SPI_DELAY_BIN03', + 222: 'PERF_ENGG_CSB_SPI_DELAY_BIN04', + 223: 'PERF_ENGG_CSB_SPI_DELAY_BIN05', + 224: 'PERF_ENGG_CSB_SPI_DELAY_BIN06', + 225: 'PERF_ENGG_CSB_SPI_DELAY_BIN07', + 226: 'PERF_ENGG_CSB_SPI_DELAY_BIN08', + 227: 'PERF_ENGG_CSB_SPI_DELAY_BIN09', + 228: 'PERF_ENGG_CSB_SPI_DELAY_BIN10', + 229: 'PERF_ENGG_INDEX_REQ_NULL_REQUEST', + 230: 'PERF_ENGG_INDEX_REQ_0_NEW_VERTS_THIS_PRIM', + 231: 'PERF_ENGG_INDEX_REQ_1_NEW_VERTS_THIS_PRIM', + 232: 'PERF_ENGG_INDEX_REQ_2_NEW_VERTS_THIS_PRIM', + 233: 'PERF_ENGG_INDEX_REQ_3_NEW_VERTS_THIS_PRIM', + 234: 'PERF_ENGG_INDEX_REQ_STARVED', + 235: 'PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 236: 'PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 237: 'PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', + 238: 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 239: 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 240: 'PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 241: 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 242: 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 243: 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 244: 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 245: 'PERF_ENGG_INDEX_RET_SXRX_READING_EVENT', + 246: 'PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 247: 'PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 248: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 249: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 250: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL', + 251: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL', + 252: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL', + 253: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 254: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 255: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL', + 256: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL', + 257: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL', + 258: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_NULL_PRIMS', + 259: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_NULL_PRIMS', + 260: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_NULL_PRIMS', + 261: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_NULL_PRIMS', + 262: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_NULL_PRIMS', + 263: 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 264: 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 265: 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB', + 266: 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 267: 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 268: 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 269: 'PERF_ENGG_POS_REQ_STARVED', + 270: 'PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO', + 271: 'PERF_ENGG_BUSY', + 272: 'PERF_CLIPSM_CULL_PRIMS_CNT', + 273: 'PERF_PH_SEND_1_SC', + 274: 'PERF_PH_SEND_2_SC', + 275: 'PERF_PH_SEND_3_SC', + 276: 'PERF_PH_SEND_4_SC', + 277: 'PERF_OUTPUT_PRIM_1_SC', + 278: 'PERF_OUTPUT_PRIM_2_SC', + 279: 'PERF_OUTPUT_PRIM_3_SC', + 280: 'PERF_OUTPUT_PRIM_4_SC', +} +PERF_PAPC_PASX_REQ = 0 +PERF_PAPC_PASX_DISABLE_PIPE = 1 +PERF_PAPC_PASX_FIRST_VECTOR = 2 +PERF_PAPC_PASX_SECOND_VECTOR = 3 +PERF_PAPC_PASX_FIRST_DEAD = 4 +PERF_PAPC_PASX_SECOND_DEAD = 5 +PERF_PAPC_PASX_VTX_KILL_DISCARD = 6 +PERF_PAPC_PASX_VTX_NAN_DISCARD = 7 +PERF_PAPC_PA_INPUT_PRIM = 8 +PERF_PAPC_PA_INPUT_NULL_PRIM = 9 +PERF_PAPC_PA_INPUT_EVENT_FLAG = 10 +PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT = 11 +PERF_PAPC_PA_INPUT_END_OF_PACKET = 12 +PERF_PAPC_PA_INPUT_EXTENDED_EVENT = 13 +PERF_PAPC_CLPR_CULL_PRIM = 14 +PERF_PAPC_CLPR_VVUCP_CULL_PRIM = 15 +PERF_PAPC_CLPR_VV_CULL_PRIM = 16 +PERF_PAPC_CLPR_UCP_CULL_PRIM = 17 +PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM = 18 +PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM = 19 +PERF_PAPC_CLPR_CULL_TO_NULL_PRIM = 20 +PERF_PAPC_CLPR_VVUCP_CLIP_PRIM = 21 +PERF_PAPC_CLPR_VV_CLIP_PRIM = 22 +PERF_PAPC_CLPR_UCP_CLIP_PRIM = 23 +PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE = 24 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_1 = 25 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_2 = 26 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_3 = 27 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_4 = 28 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8 = 29 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12 = 30 +PERF_PAPC_CLPR_CLIP_PLANE_NEAR = 31 +PERF_PAPC_CLPR_CLIP_PLANE_FAR = 32 +PERF_PAPC_CLPR_CLIP_PLANE_LEFT = 33 +PERF_PAPC_CLPR_CLIP_PLANE_RIGHT = 34 +PERF_PAPC_CLPR_CLIP_PLANE_TOP = 35 +PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM = 36 +PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM = 37 +PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM = 38 +PERF_PAPC_CLSM_NULL_PRIM = 39 +PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM = 40 +PERF_PAPC_CLSM_CULL_TO_NULL_PRIM = 41 +PERF_PAPC_CLSM_OUT_PRIM_CNT_1 = 42 +PERF_PAPC_CLSM_OUT_PRIM_CNT_2 = 43 +PERF_PAPC_CLSM_OUT_PRIM_CNT_3 = 44 +PERF_PAPC_CLSM_OUT_PRIM_CNT_4 = 45 +PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8 = 46 +PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13 = 47 +PERF_PAPC_CLIPGA_VTE_KILL_PRIM = 48 +PERF_PAPC_SU_INPUT_PRIM = 49 +PERF_PAPC_SU_INPUT_CLIP_PRIM = 50 +PERF_PAPC_SU_INPUT_NULL_PRIM = 51 +PERF_PAPC_SU_INPUT_PRIM_DUAL = 52 +PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL = 53 +PERF_PAPC_SU_ZERO_AREA_CULL_PRIM = 54 +PERF_PAPC_SU_BACK_FACE_CULL_PRIM = 55 +PERF_PAPC_SU_FRONT_FACE_CULL_PRIM = 56 +PERF_PAPC_SU_POLYMODE_FACE_CULL = 57 +PERF_PAPC_SU_POLYMODE_BACK_CULL = 58 +PERF_PAPC_SU_POLYMODE_FRONT_CULL = 59 +PERF_PAPC_SU_POLYMODE_INVALID_FILL = 60 +PERF_PAPC_SU_OUTPUT_PRIM = 61 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM = 62 +PERF_PAPC_SU_OUTPUT_NULL_PRIM = 63 +PERF_PAPC_SU_OUTPUT_EVENT_FLAG = 64 +PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT = 65 +PERF_PAPC_SU_OUTPUT_END_OF_PACKET = 66 +PERF_PAPC_SU_OUTPUT_POLYMODE_FACE = 67 +PERF_PAPC_SU_OUTPUT_POLYMODE_BACK = 68 +PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT = 69 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE = 70 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK = 71 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT = 72 +PERF_PAPC_SU_OUTPUT_PRIM_DUAL = 73 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL = 74 +PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL = 75 +PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL = 76 +PERF_PAPC_PASX_REQ_IDLE = 77 +PERF_PAPC_PASX_REQ_BUSY = 78 +PERF_PAPC_PASX_REQ_STALLED = 79 +PERF_PAPC_PASX_REC_IDLE = 80 +PERF_PAPC_PASX_REC_BUSY = 81 +PERF_PAPC_PASX_REC_STARVED_SX = 82 +PERF_PAPC_PASX_REC_STALLED = 83 +PERF_PAPC_PASX_REC_STALLED_POS_MEM = 84 +PERF_PAPC_PASX_REC_STALLED_CCGSM_IN = 85 +PERF_PAPC_CCGSM_IDLE = 86 +PERF_PAPC_CCGSM_BUSY = 87 +PERF_PAPC_CCGSM_STALLED = 88 +PERF_PAPC_CLPRIM_IDLE = 89 +PERF_PAPC_CLPRIM_BUSY = 90 +PERF_PAPC_CLPRIM_STALLED = 91 +PERF_PAPC_CLPRIM_STARVED_CCGSM = 92 +PERF_PAPC_CLIPSM_IDLE = 93 +PERF_PAPC_CLIPSM_BUSY = 94 +PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH = 95 +PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ = 96 +PERF_PAPC_CLIPSM_WAIT_CLIPGA = 97 +PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP = 98 +PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM = 99 +PERF_PAPC_CLIPGA_IDLE = 100 +PERF_PAPC_CLIPGA_BUSY = 101 +PERF_PAPC_CLIPGA_STARVED_VTE_CLIP = 102 +PERF_PAPC_CLIPGA_STALLED = 103 +PERF_PAPC_CLIP_IDLE = 104 +PERF_PAPC_CLIP_BUSY = 105 +PERF_PAPC_SU_IDLE = 106 +PERF_PAPC_SU_BUSY = 107 +PERF_PAPC_SU_STARVED_CLIP = 108 +PERF_PAPC_SU_STALLED_SC = 109 +PERF_PAPC_CL_DYN_SCLK_VLD = 110 +PERF_PAPC_SU_DYN_SCLK_VLD = 111 +PERF_PAPC_PA_REG_SCLK_VLD = 112 +PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL = 113 +PERF_PAPC_PASX_SE0_REQ = 114 +PERF_PAPC_PASX_SE1_REQ = 115 +PERF_PAPC_PASX_SE0_FIRST_VECTOR = 116 +PERF_PAPC_PASX_SE0_SECOND_VECTOR = 117 +PERF_PAPC_PASX_SE1_FIRST_VECTOR = 118 +PERF_PAPC_PASX_SE1_SECOND_VECTOR = 119 +PERF_PAPC_SU_SE0_PRIM_FILTER_CULL = 120 +PERF_PAPC_SU_SE1_PRIM_FILTER_CULL = 121 +PERF_PAPC_SU_SE01_PRIM_FILTER_CULL = 122 +PERF_PAPC_SU_SE0_OUTPUT_PRIM = 123 +PERF_PAPC_SU_SE1_OUTPUT_PRIM = 124 +PERF_PAPC_SU_SE01_OUTPUT_PRIM = 125 +PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM = 126 +PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM = 127 +PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM = 128 +PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT = 129 +PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT = 130 +PERF_PAPC_SU_SE0_STALLED_SC = 131 +PERF_PAPC_SU_SE1_STALLED_SC = 132 +PERF_PAPC_SU_SE01_STALLED_SC = 133 +PERF_PAPC_CLSM_CLIPPING_PRIM = 134 +PERF_PAPC_SU_CULLED_PRIM = 135 +PERF_PAPC_SU_OUTPUT_EOPG = 136 +PERF_PAPC_SU_SE2_PRIM_FILTER_CULL = 137 +PERF_PAPC_SU_SE3_PRIM_FILTER_CULL = 138 +PERF_PAPC_SU_SE2_OUTPUT_PRIM = 139 +PERF_PAPC_SU_SE3_OUTPUT_PRIM = 140 +PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM = 141 +PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM = 142 +PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET = 143 +PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET = 144 +PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET = 145 +PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET = 146 +PERF_PAPC_SU_SE0_OUTPUT_EOPG = 147 +PERF_PAPC_SU_SE1_OUTPUT_EOPG = 148 +PERF_PAPC_SU_SE2_OUTPUT_EOPG = 149 +PERF_PAPC_SU_SE3_OUTPUT_EOPG = 150 +PERF_PAPC_SU_SE2_STALLED_SC = 151 +PERF_PAPC_SU_SE3_STALLED_SC = 152 +PERF_SU_SMALL_PRIM_FILTER_CULL_CNT = 153 +PERF_SMALL_PRIM_CULL_PRIM_1X1 = 154 +PERF_SMALL_PRIM_CULL_PRIM_2X1 = 155 +PERF_SMALL_PRIM_CULL_PRIM_1X2 = 156 +PERF_SMALL_PRIM_CULL_PRIM_2X2 = 157 +PERF_SMALL_PRIM_CULL_PRIM_3X1 = 158 +PERF_SMALL_PRIM_CULL_PRIM_1X3 = 159 +PERF_SMALL_PRIM_CULL_PRIM_3X2 = 160 +PERF_SMALL_PRIM_CULL_PRIM_2X3 = 161 +PERF_SMALL_PRIM_CULL_PRIM_NX1 = 162 +PERF_SMALL_PRIM_CULL_PRIM_1XN = 163 +PERF_SMALL_PRIM_CULL_PRIM_NX2 = 164 +PERF_SMALL_PRIM_CULL_PRIM_2XN = 165 +PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT = 166 +PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT = 167 +PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT = 168 +PERF_SC0_QUALIFIED_SEND_BUSY_EVENT = 170 +PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT = 171 +PERF_SC1_QUALIFIED_SEND_BUSY_EVENT = 172 +PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT = 173 +PERF_SC2_QUALIFIED_SEND_BUSY_EVENT = 174 +PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT = 175 +PERF_SC3_QUALIFIED_SEND_BUSY_EVENT = 176 +PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT = 177 +PERF_PA_VERTEX_FIFO_FULL = 179 +PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL = 180 +PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL = 182 +PERF_PA_FETCH_TO_SXIF_FIFO_FULL = 183 +PERF_PA_PIPE0_SWITCHED_GEN = 185 +PERF_PA_PIPE1_SWITCHED_GEN = 186 +PERF_ENGG_CSB_MACHINE_IS_STARVED = 188 +PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY = 189 +PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI = 190 +PERF_ENGG_CSB_GE_INPUT_FIFO_FULL = 191 +PERF_ENGG_CSB_SPI_INPUT_FIFO_FULL = 192 +PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL = 193 +PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT = 194 +PERF_ENGG_CSB_PRIM_COUNT_EQ0 = 195 +PERF_ENGG_CSB_NULL_SUBGROUP = 196 +PERF_ENGG_CSB_GE_SENDING_SUBGROUP = 197 +PERF_ENGG_CSB_GE_MEMORY_FULL = 198 +PERF_ENGG_CSB_GE_MEMORY_EMPTY = 199 +PERF_ENGG_CSB_SPI_MEMORY_FULL = 200 +PERF_ENGG_CSB_SPI_MEMORY_EMPTY = 201 +PERF_ENGG_CSB_DELAY_BIN00 = 202 +PERF_ENGG_CSB_DELAY_BIN01 = 203 +PERF_ENGG_CSB_DELAY_BIN02 = 204 +PERF_ENGG_CSB_DELAY_BIN03 = 205 +PERF_ENGG_CSB_DELAY_BIN04 = 206 +PERF_ENGG_CSB_DELAY_BIN05 = 207 +PERF_ENGG_CSB_DELAY_BIN06 = 208 +PERF_ENGG_CSB_DELAY_BIN07 = 209 +PERF_ENGG_CSB_DELAY_BIN08 = 210 +PERF_ENGG_CSB_DELAY_BIN09 = 211 +PERF_ENGG_CSB_DELAY_BIN10 = 212 +PERF_ENGG_CSB_DELAY_BIN11 = 213 +PERF_ENGG_CSB_DELAY_BIN12 = 214 +PERF_ENGG_CSB_DELAY_BIN13 = 215 +PERF_ENGG_CSB_DELAY_BIN14 = 216 +PERF_ENGG_CSB_DELAY_BIN15 = 217 +PERF_ENGG_CSB_SPI_DELAY_BIN00 = 218 +PERF_ENGG_CSB_SPI_DELAY_BIN01 = 219 +PERF_ENGG_CSB_SPI_DELAY_BIN02 = 220 +PERF_ENGG_CSB_SPI_DELAY_BIN03 = 221 +PERF_ENGG_CSB_SPI_DELAY_BIN04 = 222 +PERF_ENGG_CSB_SPI_DELAY_BIN05 = 223 +PERF_ENGG_CSB_SPI_DELAY_BIN06 = 224 +PERF_ENGG_CSB_SPI_DELAY_BIN07 = 225 +PERF_ENGG_CSB_SPI_DELAY_BIN08 = 226 +PERF_ENGG_CSB_SPI_DELAY_BIN09 = 227 +PERF_ENGG_CSB_SPI_DELAY_BIN10 = 228 +PERF_ENGG_INDEX_REQ_NULL_REQUEST = 229 +PERF_ENGG_INDEX_REQ_0_NEW_VERTS_THIS_PRIM = 230 +PERF_ENGG_INDEX_REQ_1_NEW_VERTS_THIS_PRIM = 231 +PERF_ENGG_INDEX_REQ_2_NEW_VERTS_THIS_PRIM = 232 +PERF_ENGG_INDEX_REQ_3_NEW_VERTS_THIS_PRIM = 233 +PERF_ENGG_INDEX_REQ_STARVED = 234 +PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 235 +PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 236 +PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS = 237 +PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL = 238 +PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY = 239 +PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL = 240 +PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB = 241 +PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS = 242 +PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO = 243 +PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO = 244 +PERF_ENGG_INDEX_RET_SXRX_READING_EVENT = 245 +PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP = 246 +PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0 = 247 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL = 248 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL = 249 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL = 250 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL = 251 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL = 252 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL = 253 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL = 254 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL = 255 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL = 256 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL = 257 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_NULL_PRIMS = 258 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_NULL_PRIMS = 259 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_NULL_PRIMS = 260 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_NULL_PRIMS = 261 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_NULL_PRIMS = 262 +PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO = 263 +PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO = 264 +PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB = 265 +PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM = 266 +PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE = 267 +PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE = 268 +PERF_ENGG_POS_REQ_STARVED = 269 +PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO = 270 +PERF_ENGG_BUSY = 271 +PERF_CLIPSM_CULL_PRIMS_CNT = 272 +PERF_PH_SEND_1_SC = 273 +PERF_PH_SEND_2_SC = 274 +PERF_PH_SEND_3_SC = 275 +PERF_PH_SEND_4_SC = 276 +PERF_OUTPUT_PRIM_1_SC = 277 +PERF_OUTPUT_PRIM_2_SC = 278 +PERF_OUTPUT_PRIM_3_SC = 279 +PERF_OUTPUT_PRIM_4_SC = 280 +SU_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PH_PERFCNT_SEL' +PH_PERFCNT_SEL__enumvalues = { + 0: 'PH_PERF_SEL_SC0_SRPS_WINDOW_VALID', + 1: 'PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 2: 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES', + 3: 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 4: 'PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW', + 5: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE', + 6: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 7: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 8: 'PH_PERF_SEL_SC0_ARB_BUSY', + 9: 'PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP', + 10: 'PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP', + 11: 'PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP', + 12: 'PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE', + 13: 'PH_PERF_SEL_SC0_EOP_SYNC_WINDOW', + 14: 'PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', + 15: 'PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO', + 16: 'PH_PERF_SEL_SC0_SEND', + 17: 'PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 18: 'PH_PERF_SEL_SC0_CREDIT_AT_MAX', + 19: 'PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 20: 'PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION', + 21: 'PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION', + 22: 'PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 23: 'PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 24: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD', + 25: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE', + 26: 'PH_PERF_SEL_SC0_PA0_FIFO_EMPTY', + 27: 'PH_PERF_SEL_SC0_PA0_FIFO_FULL', + 28: 'PH_PERF_SEL_SC0_PA0_NULL_WE', + 29: 'PH_PERF_SEL_SC0_PA0_EVENT_WE', + 30: 'PH_PERF_SEL_SC0_PA0_FPOV_WE', + 31: 'PH_PERF_SEL_SC0_PA0_LPOV_WE', + 32: 'PH_PERF_SEL_SC0_PA0_EOP_WE', + 33: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD', + 34: 'PH_PERF_SEL_SC0_PA0_EOPG_WE', + 35: 'PH_PERF_SEL_SC0_PA0_DEALLOC_4_0_RD', + 36: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD', + 37: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE', + 38: 'PH_PERF_SEL_SC0_PA1_FIFO_EMPTY', + 39: 'PH_PERF_SEL_SC0_PA1_FIFO_FULL', + 40: 'PH_PERF_SEL_SC0_PA1_NULL_WE', + 41: 'PH_PERF_SEL_SC0_PA1_EVENT_WE', + 42: 'PH_PERF_SEL_SC0_PA1_FPOV_WE', + 43: 'PH_PERF_SEL_SC0_PA1_LPOV_WE', + 44: 'PH_PERF_SEL_SC0_PA1_EOP_WE', + 45: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD', + 46: 'PH_PERF_SEL_SC0_PA1_EOPG_WE', + 47: 'PH_PERF_SEL_SC0_PA1_DEALLOC_4_0_RD', + 48: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD', + 49: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE', + 50: 'PH_PERF_SEL_SC0_PA2_FIFO_EMPTY', + 51: 'PH_PERF_SEL_SC0_PA2_FIFO_FULL', + 52: 'PH_PERF_SEL_SC0_PA2_NULL_WE', + 53: 'PH_PERF_SEL_SC0_PA2_EVENT_WE', + 54: 'PH_PERF_SEL_SC0_PA2_FPOV_WE', + 55: 'PH_PERF_SEL_SC0_PA2_LPOV_WE', + 56: 'PH_PERF_SEL_SC0_PA2_EOP_WE', + 57: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD', + 58: 'PH_PERF_SEL_SC0_PA2_EOPG_WE', + 59: 'PH_PERF_SEL_SC0_PA2_DEALLOC_4_0_RD', + 60: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD', + 61: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE', + 62: 'PH_PERF_SEL_SC0_PA3_FIFO_EMPTY', + 63: 'PH_PERF_SEL_SC0_PA3_FIFO_FULL', + 64: 'PH_PERF_SEL_SC0_PA3_NULL_WE', + 65: 'PH_PERF_SEL_SC0_PA3_EVENT_WE', + 66: 'PH_PERF_SEL_SC0_PA3_FPOV_WE', + 67: 'PH_PERF_SEL_SC0_PA3_LPOV_WE', + 68: 'PH_PERF_SEL_SC0_PA3_EOP_WE', + 69: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD', + 70: 'PH_PERF_SEL_SC0_PA3_EOPG_WE', + 71: 'PH_PERF_SEL_SC0_PA3_DEALLOC_4_0_RD', + 72: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD', + 73: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE', + 74: 'PH_PERF_SEL_SC0_PA4_FIFO_EMPTY', + 75: 'PH_PERF_SEL_SC0_PA4_FIFO_FULL', + 76: 'PH_PERF_SEL_SC0_PA4_NULL_WE', + 77: 'PH_PERF_SEL_SC0_PA4_EVENT_WE', + 78: 'PH_PERF_SEL_SC0_PA4_FPOV_WE', + 79: 'PH_PERF_SEL_SC0_PA4_LPOV_WE', + 80: 'PH_PERF_SEL_SC0_PA4_EOP_WE', + 81: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD', + 82: 'PH_PERF_SEL_SC0_PA4_EOPG_WE', + 83: 'PH_PERF_SEL_SC0_PA4_DEALLOC_4_0_RD', + 84: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD', + 85: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE', + 86: 'PH_PERF_SEL_SC0_PA5_FIFO_EMPTY', + 87: 'PH_PERF_SEL_SC0_PA5_FIFO_FULL', + 88: 'PH_PERF_SEL_SC0_PA5_NULL_WE', + 89: 'PH_PERF_SEL_SC0_PA5_EVENT_WE', + 90: 'PH_PERF_SEL_SC0_PA5_FPOV_WE', + 91: 'PH_PERF_SEL_SC0_PA5_LPOV_WE', + 92: 'PH_PERF_SEL_SC0_PA5_EOP_WE', + 93: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD', + 94: 'PH_PERF_SEL_SC0_PA5_EOPG_WE', + 95: 'PH_PERF_SEL_SC0_PA5_DEALLOC_4_0_RD', + 96: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD', + 97: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE', + 98: 'PH_PERF_SEL_SC0_PA6_FIFO_EMPTY', + 99: 'PH_PERF_SEL_SC0_PA6_FIFO_FULL', + 100: 'PH_PERF_SEL_SC0_PA6_NULL_WE', + 101: 'PH_PERF_SEL_SC0_PA6_EVENT_WE', + 102: 'PH_PERF_SEL_SC0_PA6_FPOV_WE', + 103: 'PH_PERF_SEL_SC0_PA6_LPOV_WE', + 104: 'PH_PERF_SEL_SC0_PA6_EOP_WE', + 105: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD', + 106: 'PH_PERF_SEL_SC0_PA6_EOPG_WE', + 107: 'PH_PERF_SEL_SC0_PA6_DEALLOC_4_0_RD', + 108: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD', + 109: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE', + 110: 'PH_PERF_SEL_SC0_PA7_FIFO_EMPTY', + 111: 'PH_PERF_SEL_SC0_PA7_FIFO_FULL', + 112: 'PH_PERF_SEL_SC0_PA7_NULL_WE', + 113: 'PH_PERF_SEL_SC0_PA7_EVENT_WE', + 114: 'PH_PERF_SEL_SC0_PA7_FPOV_WE', + 115: 'PH_PERF_SEL_SC0_PA7_LPOV_WE', + 116: 'PH_PERF_SEL_SC0_PA7_EOP_WE', + 117: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD', + 118: 'PH_PERF_SEL_SC0_PA7_EOPG_WE', + 119: 'PH_PERF_SEL_SC0_PA7_DEALLOC_4_0_RD', + 120: 'PH_PERF_SEL_SC1_SRPS_WINDOW_VALID', + 121: 'PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 122: 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES', + 123: 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 124: 'PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW', + 125: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE', + 126: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 127: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 128: 'PH_PERF_SEL_SC1_ARB_BUSY', + 129: 'PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP', + 130: 'PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP', + 131: 'PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP', + 132: 'PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE', + 133: 'PH_PERF_SEL_SC1_EOP_SYNC_WINDOW', + 134: 'PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', + 135: 'PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO', + 136: 'PH_PERF_SEL_SC1_SEND', + 137: 'PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 138: 'PH_PERF_SEL_SC1_CREDIT_AT_MAX', + 139: 'PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 140: 'PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION', + 141: 'PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION', + 142: 'PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 143: 'PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 144: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD', + 145: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE', + 146: 'PH_PERF_SEL_SC1_PA0_FIFO_EMPTY', + 147: 'PH_PERF_SEL_SC1_PA0_FIFO_FULL', + 148: 'PH_PERF_SEL_SC1_PA0_NULL_WE', + 149: 'PH_PERF_SEL_SC1_PA0_EVENT_WE', + 150: 'PH_PERF_SEL_SC1_PA0_FPOV_WE', + 151: 'PH_PERF_SEL_SC1_PA0_LPOV_WE', + 152: 'PH_PERF_SEL_SC1_PA0_EOP_WE', + 153: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD', + 154: 'PH_PERF_SEL_SC1_PA0_EOPG_WE', + 155: 'PH_PERF_SEL_SC1_PA0_DEALLOC_4_0_RD', + 156: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD', + 157: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE', + 158: 'PH_PERF_SEL_SC1_PA1_FIFO_EMPTY', + 159: 'PH_PERF_SEL_SC1_PA1_FIFO_FULL', + 160: 'PH_PERF_SEL_SC1_PA1_NULL_WE', + 161: 'PH_PERF_SEL_SC1_PA1_EVENT_WE', + 162: 'PH_PERF_SEL_SC1_PA1_FPOV_WE', + 163: 'PH_PERF_SEL_SC1_PA1_LPOV_WE', + 164: 'PH_PERF_SEL_SC1_PA1_EOP_WE', + 165: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD', + 166: 'PH_PERF_SEL_SC1_PA1_EOPG_WE', + 167: 'PH_PERF_SEL_SC1_PA1_DEALLOC_4_0_RD', + 168: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD', + 169: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE', + 170: 'PH_PERF_SEL_SC1_PA2_FIFO_EMPTY', + 171: 'PH_PERF_SEL_SC1_PA2_FIFO_FULL', + 172: 'PH_PERF_SEL_SC1_PA2_NULL_WE', + 173: 'PH_PERF_SEL_SC1_PA2_EVENT_WE', + 174: 'PH_PERF_SEL_SC1_PA2_FPOV_WE', + 175: 'PH_PERF_SEL_SC1_PA2_LPOV_WE', + 176: 'PH_PERF_SEL_SC1_PA2_EOP_WE', + 177: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD', + 178: 'PH_PERF_SEL_SC1_PA2_EOPG_WE', + 179: 'PH_PERF_SEL_SC1_PA2_DEALLOC_4_0_RD', + 180: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD', + 181: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE', + 182: 'PH_PERF_SEL_SC1_PA3_FIFO_EMPTY', + 183: 'PH_PERF_SEL_SC1_PA3_FIFO_FULL', + 184: 'PH_PERF_SEL_SC1_PA3_NULL_WE', + 185: 'PH_PERF_SEL_SC1_PA3_EVENT_WE', + 186: 'PH_PERF_SEL_SC1_PA3_FPOV_WE', + 187: 'PH_PERF_SEL_SC1_PA3_LPOV_WE', + 188: 'PH_PERF_SEL_SC1_PA3_EOP_WE', + 189: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD', + 190: 'PH_PERF_SEL_SC1_PA3_EOPG_WE', + 191: 'PH_PERF_SEL_SC1_PA3_DEALLOC_4_0_RD', + 192: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD', + 193: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE', + 194: 'PH_PERF_SEL_SC1_PA4_FIFO_EMPTY', + 195: 'PH_PERF_SEL_SC1_PA4_FIFO_FULL', + 196: 'PH_PERF_SEL_SC1_PA4_NULL_WE', + 197: 'PH_PERF_SEL_SC1_PA4_EVENT_WE', + 198: 'PH_PERF_SEL_SC1_PA4_FPOV_WE', + 199: 'PH_PERF_SEL_SC1_PA4_LPOV_WE', + 200: 'PH_PERF_SEL_SC1_PA4_EOP_WE', + 201: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD', + 202: 'PH_PERF_SEL_SC1_PA4_EOPG_WE', + 203: 'PH_PERF_SEL_SC1_PA4_DEALLOC_4_0_RD', + 204: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD', + 205: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE', + 206: 'PH_PERF_SEL_SC1_PA5_FIFO_EMPTY', + 207: 'PH_PERF_SEL_SC1_PA5_FIFO_FULL', + 208: 'PH_PERF_SEL_SC1_PA5_NULL_WE', + 209: 'PH_PERF_SEL_SC1_PA5_EVENT_WE', + 210: 'PH_PERF_SEL_SC1_PA5_FPOV_WE', + 211: 'PH_PERF_SEL_SC1_PA5_LPOV_WE', + 212: 'PH_PERF_SEL_SC1_PA5_EOP_WE', + 213: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD', + 214: 'PH_PERF_SEL_SC1_PA5_EOPG_WE', + 215: 'PH_PERF_SEL_SC1_PA5_DEALLOC_4_0_RD', + 216: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD', + 217: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE', + 218: 'PH_PERF_SEL_SC1_PA6_FIFO_EMPTY', + 219: 'PH_PERF_SEL_SC1_PA6_FIFO_FULL', + 220: 'PH_PERF_SEL_SC1_PA6_NULL_WE', + 221: 'PH_PERF_SEL_SC1_PA6_EVENT_WE', + 222: 'PH_PERF_SEL_SC1_PA6_FPOV_WE', + 223: 'PH_PERF_SEL_SC1_PA6_LPOV_WE', + 224: 'PH_PERF_SEL_SC1_PA6_EOP_WE', + 225: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD', + 226: 'PH_PERF_SEL_SC1_PA6_EOPG_WE', + 227: 'PH_PERF_SEL_SC1_PA6_DEALLOC_4_0_RD', + 228: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD', + 229: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE', + 230: 'PH_PERF_SEL_SC1_PA7_FIFO_EMPTY', + 231: 'PH_PERF_SEL_SC1_PA7_FIFO_FULL', + 232: 'PH_PERF_SEL_SC1_PA7_NULL_WE', + 233: 'PH_PERF_SEL_SC1_PA7_EVENT_WE', + 234: 'PH_PERF_SEL_SC1_PA7_FPOV_WE', + 235: 'PH_PERF_SEL_SC1_PA7_LPOV_WE', + 236: 'PH_PERF_SEL_SC1_PA7_EOP_WE', + 237: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD', + 238: 'PH_PERF_SEL_SC1_PA7_EOPG_WE', + 239: 'PH_PERF_SEL_SC1_PA7_DEALLOC_4_0_RD', + 240: 'PH_PERF_SEL_SC2_SRPS_WINDOW_VALID', + 241: 'PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 242: 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES', + 243: 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 244: 'PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW', + 245: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE', + 246: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 247: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 248: 'PH_PERF_SEL_SC2_ARB_BUSY', + 249: 'PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP', + 250: 'PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP', + 251: 'PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP', + 252: 'PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE', + 253: 'PH_PERF_SEL_SC2_EOP_SYNC_WINDOW', + 254: 'PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', + 255: 'PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO', + 256: 'PH_PERF_SEL_SC2_SEND', + 257: 'PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 258: 'PH_PERF_SEL_SC2_CREDIT_AT_MAX', + 259: 'PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 260: 'PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION', + 261: 'PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION', + 262: 'PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 263: 'PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 264: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD', + 265: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE', + 266: 'PH_PERF_SEL_SC2_PA0_FIFO_EMPTY', + 267: 'PH_PERF_SEL_SC2_PA0_FIFO_FULL', + 268: 'PH_PERF_SEL_SC2_PA0_NULL_WE', + 269: 'PH_PERF_SEL_SC2_PA0_EVENT_WE', + 270: 'PH_PERF_SEL_SC2_PA0_FPOV_WE', + 271: 'PH_PERF_SEL_SC2_PA0_LPOV_WE', + 272: 'PH_PERF_SEL_SC2_PA0_EOP_WE', + 273: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD', + 274: 'PH_PERF_SEL_SC2_PA0_EOPG_WE', + 275: 'PH_PERF_SEL_SC2_PA0_DEALLOC_4_0_RD', + 276: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD', + 277: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE', + 278: 'PH_PERF_SEL_SC2_PA1_FIFO_EMPTY', + 279: 'PH_PERF_SEL_SC2_PA1_FIFO_FULL', + 280: 'PH_PERF_SEL_SC2_PA1_NULL_WE', + 281: 'PH_PERF_SEL_SC2_PA1_EVENT_WE', + 282: 'PH_PERF_SEL_SC2_PA1_FPOV_WE', + 283: 'PH_PERF_SEL_SC2_PA1_LPOV_WE', + 284: 'PH_PERF_SEL_SC2_PA1_EOP_WE', + 285: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD', + 286: 'PH_PERF_SEL_SC2_PA1_EOPG_WE', + 287: 'PH_PERF_SEL_SC2_PA1_DEALLOC_4_0_RD', + 288: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD', + 289: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE', + 290: 'PH_PERF_SEL_SC2_PA2_FIFO_EMPTY', + 291: 'PH_PERF_SEL_SC2_PA2_FIFO_FULL', + 292: 'PH_PERF_SEL_SC2_PA2_NULL_WE', + 293: 'PH_PERF_SEL_SC2_PA2_EVENT_WE', + 294: 'PH_PERF_SEL_SC2_PA2_FPOV_WE', + 295: 'PH_PERF_SEL_SC2_PA2_LPOV_WE', + 296: 'PH_PERF_SEL_SC2_PA2_EOP_WE', + 297: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD', + 298: 'PH_PERF_SEL_SC2_PA2_EOPG_WE', + 299: 'PH_PERF_SEL_SC2_PA2_DEALLOC_4_0_RD', + 300: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD', + 301: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE', + 302: 'PH_PERF_SEL_SC2_PA3_FIFO_EMPTY', + 303: 'PH_PERF_SEL_SC2_PA3_FIFO_FULL', + 304: 'PH_PERF_SEL_SC2_PA3_NULL_WE', + 305: 'PH_PERF_SEL_SC2_PA3_EVENT_WE', + 306: 'PH_PERF_SEL_SC2_PA3_FPOV_WE', + 307: 'PH_PERF_SEL_SC2_PA3_LPOV_WE', + 308: 'PH_PERF_SEL_SC2_PA3_EOP_WE', + 309: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD', + 310: 'PH_PERF_SEL_SC2_PA3_EOPG_WE', + 311: 'PH_PERF_SEL_SC2_PA3_DEALLOC_4_0_RD', + 312: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD', + 313: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE', + 314: 'PH_PERF_SEL_SC2_PA4_FIFO_EMPTY', + 315: 'PH_PERF_SEL_SC2_PA4_FIFO_FULL', + 316: 'PH_PERF_SEL_SC2_PA4_NULL_WE', + 317: 'PH_PERF_SEL_SC2_PA4_EVENT_WE', + 318: 'PH_PERF_SEL_SC2_PA4_FPOV_WE', + 319: 'PH_PERF_SEL_SC2_PA4_LPOV_WE', + 320: 'PH_PERF_SEL_SC2_PA4_EOP_WE', + 321: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD', + 322: 'PH_PERF_SEL_SC2_PA4_EOPG_WE', + 323: 'PH_PERF_SEL_SC2_PA4_DEALLOC_4_0_RD', + 324: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD', + 325: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE', + 326: 'PH_PERF_SEL_SC2_PA5_FIFO_EMPTY', + 327: 'PH_PERF_SEL_SC2_PA5_FIFO_FULL', + 328: 'PH_PERF_SEL_SC2_PA5_NULL_WE', + 329: 'PH_PERF_SEL_SC2_PA5_EVENT_WE', + 330: 'PH_PERF_SEL_SC2_PA5_FPOV_WE', + 331: 'PH_PERF_SEL_SC2_PA5_LPOV_WE', + 332: 'PH_PERF_SEL_SC2_PA5_EOP_WE', + 333: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD', + 334: 'PH_PERF_SEL_SC2_PA5_EOPG_WE', + 335: 'PH_PERF_SEL_SC2_PA5_DEALLOC_4_0_RD', + 336: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD', + 337: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE', + 338: 'PH_PERF_SEL_SC2_PA6_FIFO_EMPTY', + 339: 'PH_PERF_SEL_SC2_PA6_FIFO_FULL', + 340: 'PH_PERF_SEL_SC2_PA6_NULL_WE', + 341: 'PH_PERF_SEL_SC2_PA6_EVENT_WE', + 342: 'PH_PERF_SEL_SC2_PA6_FPOV_WE', + 343: 'PH_PERF_SEL_SC2_PA6_LPOV_WE', + 344: 'PH_PERF_SEL_SC2_PA6_EOP_WE', + 345: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD', + 346: 'PH_PERF_SEL_SC2_PA6_EOPG_WE', + 347: 'PH_PERF_SEL_SC2_PA6_DEALLOC_4_0_RD', + 348: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD', + 349: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE', + 350: 'PH_PERF_SEL_SC2_PA7_FIFO_EMPTY', + 351: 'PH_PERF_SEL_SC2_PA7_FIFO_FULL', + 352: 'PH_PERF_SEL_SC2_PA7_NULL_WE', + 353: 'PH_PERF_SEL_SC2_PA7_EVENT_WE', + 354: 'PH_PERF_SEL_SC2_PA7_FPOV_WE', + 355: 'PH_PERF_SEL_SC2_PA7_LPOV_WE', + 356: 'PH_PERF_SEL_SC2_PA7_EOP_WE', + 357: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD', + 358: 'PH_PERF_SEL_SC2_PA7_EOPG_WE', + 359: 'PH_PERF_SEL_SC2_PA7_DEALLOC_4_0_RD', + 360: 'PH_PERF_SEL_SC3_SRPS_WINDOW_VALID', + 361: 'PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 362: 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES', + 363: 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 364: 'PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW', + 365: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE', + 366: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 367: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 368: 'PH_PERF_SEL_SC3_ARB_BUSY', + 369: 'PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP', + 370: 'PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP', + 371: 'PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP', + 372: 'PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE', + 373: 'PH_PERF_SEL_SC3_EOP_SYNC_WINDOW', + 374: 'PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', + 375: 'PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO', + 376: 'PH_PERF_SEL_SC3_SEND', + 377: 'PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 378: 'PH_PERF_SEL_SC3_CREDIT_AT_MAX', + 379: 'PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 380: 'PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION', + 381: 'PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION', + 382: 'PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 383: 'PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 384: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD', + 385: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE', + 386: 'PH_PERF_SEL_SC3_PA0_FIFO_EMPTY', + 387: 'PH_PERF_SEL_SC3_PA0_FIFO_FULL', + 388: 'PH_PERF_SEL_SC3_PA0_NULL_WE', + 389: 'PH_PERF_SEL_SC3_PA0_EVENT_WE', + 390: 'PH_PERF_SEL_SC3_PA0_FPOV_WE', + 391: 'PH_PERF_SEL_SC3_PA0_LPOV_WE', + 392: 'PH_PERF_SEL_SC3_PA0_EOP_WE', + 393: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD', + 394: 'PH_PERF_SEL_SC3_PA0_EOPG_WE', + 395: 'PH_PERF_SEL_SC3_PA0_DEALLOC_4_0_RD', + 396: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD', + 397: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE', + 398: 'PH_PERF_SEL_SC3_PA1_FIFO_EMPTY', + 399: 'PH_PERF_SEL_SC3_PA1_FIFO_FULL', + 400: 'PH_PERF_SEL_SC3_PA1_NULL_WE', + 401: 'PH_PERF_SEL_SC3_PA1_EVENT_WE', + 402: 'PH_PERF_SEL_SC3_PA1_FPOV_WE', + 403: 'PH_PERF_SEL_SC3_PA1_LPOV_WE', + 404: 'PH_PERF_SEL_SC3_PA1_EOP_WE', + 405: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD', + 406: 'PH_PERF_SEL_SC3_PA1_EOPG_WE', + 407: 'PH_PERF_SEL_SC3_PA1_DEALLOC_4_0_RD', + 408: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD', + 409: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE', + 410: 'PH_PERF_SEL_SC3_PA2_FIFO_EMPTY', + 411: 'PH_PERF_SEL_SC3_PA2_FIFO_FULL', + 412: 'PH_PERF_SEL_SC3_PA2_NULL_WE', + 413: 'PH_PERF_SEL_SC3_PA2_EVENT_WE', + 414: 'PH_PERF_SEL_SC3_PA2_FPOV_WE', + 415: 'PH_PERF_SEL_SC3_PA2_LPOV_WE', + 416: 'PH_PERF_SEL_SC3_PA2_EOP_WE', + 417: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD', + 418: 'PH_PERF_SEL_SC3_PA2_EOPG_WE', + 419: 'PH_PERF_SEL_SC3_PA2_DEALLOC_4_0_RD', + 420: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD', + 421: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE', + 422: 'PH_PERF_SEL_SC3_PA3_FIFO_EMPTY', + 423: 'PH_PERF_SEL_SC3_PA3_FIFO_FULL', + 424: 'PH_PERF_SEL_SC3_PA3_NULL_WE', + 425: 'PH_PERF_SEL_SC3_PA3_EVENT_WE', + 426: 'PH_PERF_SEL_SC3_PA3_FPOV_WE', + 427: 'PH_PERF_SEL_SC3_PA3_LPOV_WE', + 428: 'PH_PERF_SEL_SC3_PA3_EOP_WE', + 429: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD', + 430: 'PH_PERF_SEL_SC3_PA3_EOPG_WE', + 431: 'PH_PERF_SEL_SC3_PA3_DEALLOC_4_0_RD', + 432: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD', + 433: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE', + 434: 'PH_PERF_SEL_SC3_PA4_FIFO_EMPTY', + 435: 'PH_PERF_SEL_SC3_PA4_FIFO_FULL', + 436: 'PH_PERF_SEL_SC3_PA4_NULL_WE', + 437: 'PH_PERF_SEL_SC3_PA4_EVENT_WE', + 438: 'PH_PERF_SEL_SC3_PA4_FPOV_WE', + 439: 'PH_PERF_SEL_SC3_PA4_LPOV_WE', + 440: 'PH_PERF_SEL_SC3_PA4_EOP_WE', + 441: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD', + 442: 'PH_PERF_SEL_SC3_PA4_EOPG_WE', + 443: 'PH_PERF_SEL_SC3_PA4_DEALLOC_4_0_RD', + 444: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD', + 445: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE', + 446: 'PH_PERF_SEL_SC3_PA5_FIFO_EMPTY', + 447: 'PH_PERF_SEL_SC3_PA5_FIFO_FULL', + 448: 'PH_PERF_SEL_SC3_PA5_NULL_WE', + 449: 'PH_PERF_SEL_SC3_PA5_EVENT_WE', + 450: 'PH_PERF_SEL_SC3_PA5_FPOV_WE', + 451: 'PH_PERF_SEL_SC3_PA5_LPOV_WE', + 452: 'PH_PERF_SEL_SC3_PA5_EOP_WE', + 453: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD', + 454: 'PH_PERF_SEL_SC3_PA5_EOPG_WE', + 455: 'PH_PERF_SEL_SC3_PA5_DEALLOC_4_0_RD', + 456: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD', + 457: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE', + 458: 'PH_PERF_SEL_SC3_PA6_FIFO_EMPTY', + 459: 'PH_PERF_SEL_SC3_PA6_FIFO_FULL', + 460: 'PH_PERF_SEL_SC3_PA6_NULL_WE', + 461: 'PH_PERF_SEL_SC3_PA6_EVENT_WE', + 462: 'PH_PERF_SEL_SC3_PA6_FPOV_WE', + 463: 'PH_PERF_SEL_SC3_PA6_LPOV_WE', + 464: 'PH_PERF_SEL_SC3_PA6_EOP_WE', + 465: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD', + 466: 'PH_PERF_SEL_SC3_PA6_EOPG_WE', + 467: 'PH_PERF_SEL_SC3_PA6_DEALLOC_4_0_RD', + 468: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD', + 469: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE', + 470: 'PH_PERF_SEL_SC3_PA7_FIFO_EMPTY', + 471: 'PH_PERF_SEL_SC3_PA7_FIFO_FULL', + 472: 'PH_PERF_SEL_SC3_PA7_NULL_WE', + 473: 'PH_PERF_SEL_SC3_PA7_EVENT_WE', + 474: 'PH_PERF_SEL_SC3_PA7_FPOV_WE', + 475: 'PH_PERF_SEL_SC3_PA7_LPOV_WE', + 476: 'PH_PERF_SEL_SC3_PA7_EOP_WE', + 477: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD', + 478: 'PH_PERF_SEL_SC3_PA7_EOPG_WE', + 479: 'PH_PERF_SEL_SC3_PA7_DEALLOC_4_0_RD', + 480: 'PH_PERF_SEL_SC4_SRPS_WINDOW_VALID', + 481: 'PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 482: 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES', + 483: 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 484: 'PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW', + 485: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE', + 486: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 487: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 488: 'PH_PERF_SEL_SC4_ARB_BUSY', + 489: 'PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP', + 490: 'PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP', + 491: 'PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP', + 492: 'PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE', + 493: 'PH_PERF_SEL_SC4_EOP_SYNC_WINDOW', + 494: 'PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', + 495: 'PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO', + 496: 'PH_PERF_SEL_SC4_SEND', + 497: 'PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 498: 'PH_PERF_SEL_SC4_CREDIT_AT_MAX', + 499: 'PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 500: 'PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION', + 501: 'PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION', + 502: 'PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 503: 'PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 504: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD', + 505: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE', + 506: 'PH_PERF_SEL_SC4_PA0_FIFO_EMPTY', + 507: 'PH_PERF_SEL_SC4_PA0_FIFO_FULL', + 508: 'PH_PERF_SEL_SC4_PA0_NULL_WE', + 509: 'PH_PERF_SEL_SC4_PA0_EVENT_WE', + 510: 'PH_PERF_SEL_SC4_PA0_FPOV_WE', + 511: 'PH_PERF_SEL_SC4_PA0_LPOV_WE', + 512: 'PH_PERF_SEL_SC4_PA0_EOP_WE', + 513: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD', + 514: 'PH_PERF_SEL_SC4_PA0_EOPG_WE', + 515: 'PH_PERF_SEL_SC4_PA0_DEALLOC_4_0_RD', + 516: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD', + 517: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE', + 518: 'PH_PERF_SEL_SC4_PA1_FIFO_EMPTY', + 519: 'PH_PERF_SEL_SC4_PA1_FIFO_FULL', + 520: 'PH_PERF_SEL_SC4_PA1_NULL_WE', + 521: 'PH_PERF_SEL_SC4_PA1_EVENT_WE', + 522: 'PH_PERF_SEL_SC4_PA1_FPOV_WE', + 523: 'PH_PERF_SEL_SC4_PA1_LPOV_WE', + 524: 'PH_PERF_SEL_SC4_PA1_EOP_WE', + 525: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD', + 526: 'PH_PERF_SEL_SC4_PA1_EOPG_WE', + 527: 'PH_PERF_SEL_SC4_PA1_DEALLOC_4_0_RD', + 528: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD', + 529: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE', + 530: 'PH_PERF_SEL_SC4_PA2_FIFO_EMPTY', + 531: 'PH_PERF_SEL_SC4_PA2_FIFO_FULL', + 532: 'PH_PERF_SEL_SC4_PA2_NULL_WE', + 533: 'PH_PERF_SEL_SC4_PA2_EVENT_WE', + 534: 'PH_PERF_SEL_SC4_PA2_FPOV_WE', + 535: 'PH_PERF_SEL_SC4_PA2_LPOV_WE', + 536: 'PH_PERF_SEL_SC4_PA2_EOP_WE', + 537: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD', + 538: 'PH_PERF_SEL_SC4_PA2_EOPG_WE', + 539: 'PH_PERF_SEL_SC4_PA2_DEALLOC_4_0_RD', + 540: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD', + 541: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE', + 542: 'PH_PERF_SEL_SC4_PA3_FIFO_EMPTY', + 543: 'PH_PERF_SEL_SC4_PA3_FIFO_FULL', + 544: 'PH_PERF_SEL_SC4_PA3_NULL_WE', + 545: 'PH_PERF_SEL_SC4_PA3_EVENT_WE', + 546: 'PH_PERF_SEL_SC4_PA3_FPOV_WE', + 547: 'PH_PERF_SEL_SC4_PA3_LPOV_WE', + 548: 'PH_PERF_SEL_SC4_PA3_EOP_WE', + 549: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD', + 550: 'PH_PERF_SEL_SC4_PA3_EOPG_WE', + 551: 'PH_PERF_SEL_SC4_PA3_DEALLOC_4_0_RD', + 552: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD', + 553: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE', + 554: 'PH_PERF_SEL_SC4_PA4_FIFO_EMPTY', + 555: 'PH_PERF_SEL_SC4_PA4_FIFO_FULL', + 556: 'PH_PERF_SEL_SC4_PA4_NULL_WE', + 557: 'PH_PERF_SEL_SC4_PA4_EVENT_WE', + 558: 'PH_PERF_SEL_SC4_PA4_FPOV_WE', + 559: 'PH_PERF_SEL_SC4_PA4_LPOV_WE', + 560: 'PH_PERF_SEL_SC4_PA4_EOP_WE', + 561: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD', + 562: 'PH_PERF_SEL_SC4_PA4_EOPG_WE', + 563: 'PH_PERF_SEL_SC4_PA4_DEALLOC_4_0_RD', + 564: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD', + 565: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE', + 566: 'PH_PERF_SEL_SC4_PA5_FIFO_EMPTY', + 567: 'PH_PERF_SEL_SC4_PA5_FIFO_FULL', + 568: 'PH_PERF_SEL_SC4_PA5_NULL_WE', + 569: 'PH_PERF_SEL_SC4_PA5_EVENT_WE', + 570: 'PH_PERF_SEL_SC4_PA5_FPOV_WE', + 571: 'PH_PERF_SEL_SC4_PA5_LPOV_WE', + 572: 'PH_PERF_SEL_SC4_PA5_EOP_WE', + 573: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD', + 574: 'PH_PERF_SEL_SC4_PA5_EOPG_WE', + 575: 'PH_PERF_SEL_SC4_PA5_DEALLOC_4_0_RD', + 576: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD', + 577: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE', + 578: 'PH_PERF_SEL_SC4_PA6_FIFO_EMPTY', + 579: 'PH_PERF_SEL_SC4_PA6_FIFO_FULL', + 580: 'PH_PERF_SEL_SC4_PA6_NULL_WE', + 581: 'PH_PERF_SEL_SC4_PA6_EVENT_WE', + 582: 'PH_PERF_SEL_SC4_PA6_FPOV_WE', + 583: 'PH_PERF_SEL_SC4_PA6_LPOV_WE', + 584: 'PH_PERF_SEL_SC4_PA6_EOP_WE', + 585: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD', + 586: 'PH_PERF_SEL_SC4_PA6_EOPG_WE', + 587: 'PH_PERF_SEL_SC4_PA6_DEALLOC_4_0_RD', + 588: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD', + 589: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE', + 590: 'PH_PERF_SEL_SC4_PA7_FIFO_EMPTY', + 591: 'PH_PERF_SEL_SC4_PA7_FIFO_FULL', + 592: 'PH_PERF_SEL_SC4_PA7_NULL_WE', + 593: 'PH_PERF_SEL_SC4_PA7_EVENT_WE', + 594: 'PH_PERF_SEL_SC4_PA7_FPOV_WE', + 595: 'PH_PERF_SEL_SC4_PA7_LPOV_WE', + 596: 'PH_PERF_SEL_SC4_PA7_EOP_WE', + 597: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD', + 598: 'PH_PERF_SEL_SC4_PA7_EOPG_WE', + 599: 'PH_PERF_SEL_SC4_PA7_DEALLOC_4_0_RD', + 600: 'PH_PERF_SEL_SC5_SRPS_WINDOW_VALID', + 601: 'PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 602: 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES', + 603: 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 604: 'PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW', + 605: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE', + 606: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 607: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 608: 'PH_PERF_SEL_SC5_ARB_BUSY', + 609: 'PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP', + 610: 'PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP', + 611: 'PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP', + 612: 'PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE', + 613: 'PH_PERF_SEL_SC5_EOP_SYNC_WINDOW', + 614: 'PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', + 615: 'PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO', + 616: 'PH_PERF_SEL_SC5_SEND', + 617: 'PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 618: 'PH_PERF_SEL_SC5_CREDIT_AT_MAX', + 619: 'PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 620: 'PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION', + 621: 'PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION', + 622: 'PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 623: 'PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 624: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD', + 625: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE', + 626: 'PH_PERF_SEL_SC5_PA0_FIFO_EMPTY', + 627: 'PH_PERF_SEL_SC5_PA0_FIFO_FULL', + 628: 'PH_PERF_SEL_SC5_PA0_NULL_WE', + 629: 'PH_PERF_SEL_SC5_PA0_EVENT_WE', + 630: 'PH_PERF_SEL_SC5_PA0_FPOV_WE', + 631: 'PH_PERF_SEL_SC5_PA0_LPOV_WE', + 632: 'PH_PERF_SEL_SC5_PA0_EOP_WE', + 633: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD', + 634: 'PH_PERF_SEL_SC5_PA0_EOPG_WE', + 635: 'PH_PERF_SEL_SC5_PA0_DEALLOC_4_0_RD', + 636: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD', + 637: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE', + 638: 'PH_PERF_SEL_SC5_PA1_FIFO_EMPTY', + 639: 'PH_PERF_SEL_SC5_PA1_FIFO_FULL', + 640: 'PH_PERF_SEL_SC5_PA1_NULL_WE', + 641: 'PH_PERF_SEL_SC5_PA1_EVENT_WE', + 642: 'PH_PERF_SEL_SC5_PA1_FPOV_WE', + 643: 'PH_PERF_SEL_SC5_PA1_LPOV_WE', + 644: 'PH_PERF_SEL_SC5_PA1_EOP_WE', + 645: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD', + 646: 'PH_PERF_SEL_SC5_PA1_EOPG_WE', + 647: 'PH_PERF_SEL_SC5_PA1_DEALLOC_4_0_RD', + 648: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD', + 649: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE', + 650: 'PH_PERF_SEL_SC5_PA2_FIFO_EMPTY', + 651: 'PH_PERF_SEL_SC5_PA2_FIFO_FULL', + 652: 'PH_PERF_SEL_SC5_PA2_NULL_WE', + 653: 'PH_PERF_SEL_SC5_PA2_EVENT_WE', + 654: 'PH_PERF_SEL_SC5_PA2_FPOV_WE', + 655: 'PH_PERF_SEL_SC5_PA2_LPOV_WE', + 656: 'PH_PERF_SEL_SC5_PA2_EOP_WE', + 657: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD', + 658: 'PH_PERF_SEL_SC5_PA2_EOPG_WE', + 659: 'PH_PERF_SEL_SC5_PA2_DEALLOC_4_0_RD', + 660: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD', + 661: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE', + 662: 'PH_PERF_SEL_SC5_PA3_FIFO_EMPTY', + 663: 'PH_PERF_SEL_SC5_PA3_FIFO_FULL', + 664: 'PH_PERF_SEL_SC5_PA3_NULL_WE', + 665: 'PH_PERF_SEL_SC5_PA3_EVENT_WE', + 666: 'PH_PERF_SEL_SC5_PA3_FPOV_WE', + 667: 'PH_PERF_SEL_SC5_PA3_LPOV_WE', + 668: 'PH_PERF_SEL_SC5_PA3_EOP_WE', + 669: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD', + 670: 'PH_PERF_SEL_SC5_PA3_EOPG_WE', + 671: 'PH_PERF_SEL_SC5_PA3_DEALLOC_4_0_RD', + 672: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD', + 673: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE', + 674: 'PH_PERF_SEL_SC5_PA4_FIFO_EMPTY', + 675: 'PH_PERF_SEL_SC5_PA4_FIFO_FULL', + 676: 'PH_PERF_SEL_SC5_PA4_NULL_WE', + 677: 'PH_PERF_SEL_SC5_PA4_EVENT_WE', + 678: 'PH_PERF_SEL_SC5_PA4_FPOV_WE', + 679: 'PH_PERF_SEL_SC5_PA4_LPOV_WE', + 680: 'PH_PERF_SEL_SC5_PA4_EOP_WE', + 681: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD', + 682: 'PH_PERF_SEL_SC5_PA4_EOPG_WE', + 683: 'PH_PERF_SEL_SC5_PA4_DEALLOC_4_0_RD', + 684: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD', + 685: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE', + 686: 'PH_PERF_SEL_SC5_PA5_FIFO_EMPTY', + 687: 'PH_PERF_SEL_SC5_PA5_FIFO_FULL', + 688: 'PH_PERF_SEL_SC5_PA5_NULL_WE', + 689: 'PH_PERF_SEL_SC5_PA5_EVENT_WE', + 690: 'PH_PERF_SEL_SC5_PA5_FPOV_WE', + 691: 'PH_PERF_SEL_SC5_PA5_LPOV_WE', + 692: 'PH_PERF_SEL_SC5_PA5_EOP_WE', + 693: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD', + 694: 'PH_PERF_SEL_SC5_PA5_EOPG_WE', + 695: 'PH_PERF_SEL_SC5_PA5_DEALLOC_4_0_RD', + 696: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD', + 697: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE', + 698: 'PH_PERF_SEL_SC5_PA6_FIFO_EMPTY', + 699: 'PH_PERF_SEL_SC5_PA6_FIFO_FULL', + 700: 'PH_PERF_SEL_SC5_PA6_NULL_WE', + 701: 'PH_PERF_SEL_SC5_PA6_EVENT_WE', + 702: 'PH_PERF_SEL_SC5_PA6_FPOV_WE', + 703: 'PH_PERF_SEL_SC5_PA6_LPOV_WE', + 704: 'PH_PERF_SEL_SC5_PA6_EOP_WE', + 705: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD', + 706: 'PH_PERF_SEL_SC5_PA6_EOPG_WE', + 707: 'PH_PERF_SEL_SC5_PA6_DEALLOC_4_0_RD', + 708: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD', + 709: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE', + 710: 'PH_PERF_SEL_SC5_PA7_FIFO_EMPTY', + 711: 'PH_PERF_SEL_SC5_PA7_FIFO_FULL', + 712: 'PH_PERF_SEL_SC5_PA7_NULL_WE', + 713: 'PH_PERF_SEL_SC5_PA7_EVENT_WE', + 714: 'PH_PERF_SEL_SC5_PA7_FPOV_WE', + 715: 'PH_PERF_SEL_SC5_PA7_LPOV_WE', + 716: 'PH_PERF_SEL_SC5_PA7_EOP_WE', + 717: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD', + 718: 'PH_PERF_SEL_SC5_PA7_EOPG_WE', + 719: 'PH_PERF_SEL_SC5_PA7_DEALLOC_4_0_RD', + 720: 'PH_PERF_SEL_SC6_SRPS_WINDOW_VALID', + 721: 'PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 722: 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES', + 723: 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 724: 'PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW', + 725: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE', + 726: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 727: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 728: 'PH_PERF_SEL_SC6_ARB_BUSY', + 729: 'PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP', + 730: 'PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP', + 731: 'PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP', + 732: 'PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE', + 733: 'PH_PERF_SEL_SC6_EOP_SYNC_WINDOW', + 734: 'PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', + 735: 'PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO', + 736: 'PH_PERF_SEL_SC6_SEND', + 737: 'PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 738: 'PH_PERF_SEL_SC6_CREDIT_AT_MAX', + 739: 'PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 740: 'PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION', + 741: 'PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION', + 742: 'PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 743: 'PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 744: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD', + 745: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE', + 746: 'PH_PERF_SEL_SC6_PA0_FIFO_EMPTY', + 747: 'PH_PERF_SEL_SC6_PA0_FIFO_FULL', + 748: 'PH_PERF_SEL_SC6_PA0_NULL_WE', + 749: 'PH_PERF_SEL_SC6_PA0_EVENT_WE', + 750: 'PH_PERF_SEL_SC6_PA0_FPOV_WE', + 751: 'PH_PERF_SEL_SC6_PA0_LPOV_WE', + 752: 'PH_PERF_SEL_SC6_PA0_EOP_WE', + 753: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD', + 754: 'PH_PERF_SEL_SC6_PA0_EOPG_WE', + 755: 'PH_PERF_SEL_SC6_PA0_DEALLOC_4_0_RD', + 756: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD', + 757: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE', + 758: 'PH_PERF_SEL_SC6_PA1_FIFO_EMPTY', + 759: 'PH_PERF_SEL_SC6_PA1_FIFO_FULL', + 760: 'PH_PERF_SEL_SC6_PA1_NULL_WE', + 761: 'PH_PERF_SEL_SC6_PA1_EVENT_WE', + 762: 'PH_PERF_SEL_SC6_PA1_FPOV_WE', + 763: 'PH_PERF_SEL_SC6_PA1_LPOV_WE', + 764: 'PH_PERF_SEL_SC6_PA1_EOP_WE', + 765: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD', + 766: 'PH_PERF_SEL_SC6_PA1_EOPG_WE', + 767: 'PH_PERF_SEL_SC6_PA1_DEALLOC_4_0_RD', + 768: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD', + 769: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE', + 770: 'PH_PERF_SEL_SC6_PA2_FIFO_EMPTY', + 771: 'PH_PERF_SEL_SC6_PA2_FIFO_FULL', + 772: 'PH_PERF_SEL_SC6_PA2_NULL_WE', + 773: 'PH_PERF_SEL_SC6_PA2_EVENT_WE', + 774: 'PH_PERF_SEL_SC6_PA2_FPOV_WE', + 775: 'PH_PERF_SEL_SC6_PA2_LPOV_WE', + 776: 'PH_PERF_SEL_SC6_PA2_EOP_WE', + 777: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD', + 778: 'PH_PERF_SEL_SC6_PA2_EOPG_WE', + 779: 'PH_PERF_SEL_SC6_PA2_DEALLOC_4_0_RD', + 780: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD', + 781: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE', + 782: 'PH_PERF_SEL_SC6_PA3_FIFO_EMPTY', + 783: 'PH_PERF_SEL_SC6_PA3_FIFO_FULL', + 784: 'PH_PERF_SEL_SC6_PA3_NULL_WE', + 785: 'PH_PERF_SEL_SC6_PA3_EVENT_WE', + 786: 'PH_PERF_SEL_SC6_PA3_FPOV_WE', + 787: 'PH_PERF_SEL_SC6_PA3_LPOV_WE', + 788: 'PH_PERF_SEL_SC6_PA3_EOP_WE', + 789: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD', + 790: 'PH_PERF_SEL_SC6_PA3_EOPG_WE', + 791: 'PH_PERF_SEL_SC6_PA3_DEALLOC_4_0_RD', + 792: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD', + 793: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE', + 794: 'PH_PERF_SEL_SC6_PA4_FIFO_EMPTY', + 795: 'PH_PERF_SEL_SC6_PA4_FIFO_FULL', + 796: 'PH_PERF_SEL_SC6_PA4_NULL_WE', + 797: 'PH_PERF_SEL_SC6_PA4_EVENT_WE', + 798: 'PH_PERF_SEL_SC6_PA4_FPOV_WE', + 799: 'PH_PERF_SEL_SC6_PA4_LPOV_WE', + 800: 'PH_PERF_SEL_SC6_PA4_EOP_WE', + 801: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD', + 802: 'PH_PERF_SEL_SC6_PA4_EOPG_WE', + 803: 'PH_PERF_SEL_SC6_PA4_DEALLOC_4_0_RD', + 804: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD', + 805: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE', + 806: 'PH_PERF_SEL_SC6_PA5_FIFO_EMPTY', + 807: 'PH_PERF_SEL_SC6_PA5_FIFO_FULL', + 808: 'PH_PERF_SEL_SC6_PA5_NULL_WE', + 809: 'PH_PERF_SEL_SC6_PA5_EVENT_WE', + 810: 'PH_PERF_SEL_SC6_PA5_FPOV_WE', + 811: 'PH_PERF_SEL_SC6_PA5_LPOV_WE', + 812: 'PH_PERF_SEL_SC6_PA5_EOP_WE', + 813: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD', + 814: 'PH_PERF_SEL_SC6_PA5_EOPG_WE', + 815: 'PH_PERF_SEL_SC6_PA5_DEALLOC_4_0_RD', + 816: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD', + 817: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE', + 818: 'PH_PERF_SEL_SC6_PA6_FIFO_EMPTY', + 819: 'PH_PERF_SEL_SC6_PA6_FIFO_FULL', + 820: 'PH_PERF_SEL_SC6_PA6_NULL_WE', + 821: 'PH_PERF_SEL_SC6_PA6_EVENT_WE', + 822: 'PH_PERF_SEL_SC6_PA6_FPOV_WE', + 823: 'PH_PERF_SEL_SC6_PA6_LPOV_WE', + 824: 'PH_PERF_SEL_SC6_PA6_EOP_WE', + 825: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD', + 826: 'PH_PERF_SEL_SC6_PA6_EOPG_WE', + 827: 'PH_PERF_SEL_SC6_PA6_DEALLOC_4_0_RD', + 828: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD', + 829: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE', + 830: 'PH_PERF_SEL_SC6_PA7_FIFO_EMPTY', + 831: 'PH_PERF_SEL_SC6_PA7_FIFO_FULL', + 832: 'PH_PERF_SEL_SC6_PA7_NULL_WE', + 833: 'PH_PERF_SEL_SC6_PA7_EVENT_WE', + 834: 'PH_PERF_SEL_SC6_PA7_FPOV_WE', + 835: 'PH_PERF_SEL_SC6_PA7_LPOV_WE', + 836: 'PH_PERF_SEL_SC6_PA7_EOP_WE', + 837: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD', + 838: 'PH_PERF_SEL_SC6_PA7_EOPG_WE', + 839: 'PH_PERF_SEL_SC6_PA7_DEALLOC_4_0_RD', + 840: 'PH_PERF_SEL_SC7_SRPS_WINDOW_VALID', + 841: 'PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 842: 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES', + 843: 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 844: 'PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW', + 845: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE', + 846: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 847: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 848: 'PH_PERF_SEL_SC7_ARB_BUSY', + 849: 'PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP', + 850: 'PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP', + 851: 'PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP', + 852: 'PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE', + 853: 'PH_PERF_SEL_SC7_EOP_SYNC_WINDOW', + 854: 'PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', + 855: 'PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO', + 856: 'PH_PERF_SEL_SC7_SEND', + 857: 'PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 858: 'PH_PERF_SEL_SC7_CREDIT_AT_MAX', + 859: 'PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 860: 'PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION', + 861: 'PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION', + 862: 'PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 863: 'PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 864: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD', + 865: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE', + 866: 'PH_PERF_SEL_SC7_PA0_FIFO_EMPTY', + 867: 'PH_PERF_SEL_SC7_PA0_FIFO_FULL', + 868: 'PH_PERF_SEL_SC7_PA0_NULL_WE', + 869: 'PH_PERF_SEL_SC7_PA0_EVENT_WE', + 870: 'PH_PERF_SEL_SC7_PA0_FPOV_WE', + 871: 'PH_PERF_SEL_SC7_PA0_LPOV_WE', + 872: 'PH_PERF_SEL_SC7_PA0_EOP_WE', + 873: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD', + 874: 'PH_PERF_SEL_SC7_PA0_EOPG_WE', + 875: 'PH_PERF_SEL_SC7_PA0_DEALLOC_4_0_RD', + 876: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD', + 877: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE', + 878: 'PH_PERF_SEL_SC7_PA1_FIFO_EMPTY', + 879: 'PH_PERF_SEL_SC7_PA1_FIFO_FULL', + 880: 'PH_PERF_SEL_SC7_PA1_NULL_WE', + 881: 'PH_PERF_SEL_SC7_PA1_EVENT_WE', + 882: 'PH_PERF_SEL_SC7_PA1_FPOV_WE', + 883: 'PH_PERF_SEL_SC7_PA1_LPOV_WE', + 884: 'PH_PERF_SEL_SC7_PA1_EOP_WE', + 885: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD', + 886: 'PH_PERF_SEL_SC7_PA1_EOPG_WE', + 887: 'PH_PERF_SEL_SC7_PA1_DEALLOC_4_0_RD', + 888: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD', + 889: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE', + 890: 'PH_PERF_SEL_SC7_PA2_FIFO_EMPTY', + 891: 'PH_PERF_SEL_SC7_PA2_FIFO_FULL', + 892: 'PH_PERF_SEL_SC7_PA2_NULL_WE', + 893: 'PH_PERF_SEL_SC7_PA2_EVENT_WE', + 894: 'PH_PERF_SEL_SC7_PA2_FPOV_WE', + 895: 'PH_PERF_SEL_SC7_PA2_LPOV_WE', + 896: 'PH_PERF_SEL_SC7_PA2_EOP_WE', + 897: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD', + 898: 'PH_PERF_SEL_SC7_PA2_EOPG_WE', + 899: 'PH_PERF_SEL_SC7_PA2_DEALLOC_4_0_RD', + 900: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD', + 901: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE', + 902: 'PH_PERF_SEL_SC7_PA3_FIFO_EMPTY', + 903: 'PH_PERF_SEL_SC7_PA3_FIFO_FULL', + 904: 'PH_PERF_SEL_SC7_PA3_NULL_WE', + 905: 'PH_PERF_SEL_SC7_PA3_EVENT_WE', + 906: 'PH_PERF_SEL_SC7_PA3_FPOV_WE', + 907: 'PH_PERF_SEL_SC7_PA3_LPOV_WE', + 908: 'PH_PERF_SEL_SC7_PA3_EOP_WE', + 909: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD', + 910: 'PH_PERF_SEL_SC7_PA3_EOPG_WE', + 911: 'PH_PERF_SEL_SC7_PA3_DEALLOC_4_0_RD', + 912: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD', + 913: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE', + 914: 'PH_PERF_SEL_SC7_PA4_FIFO_EMPTY', + 915: 'PH_PERF_SEL_SC7_PA4_FIFO_FULL', + 916: 'PH_PERF_SEL_SC7_PA4_NULL_WE', + 917: 'PH_PERF_SEL_SC7_PA4_EVENT_WE', + 918: 'PH_PERF_SEL_SC7_PA4_FPOV_WE', + 919: 'PH_PERF_SEL_SC7_PA4_LPOV_WE', + 920: 'PH_PERF_SEL_SC7_PA4_EOP_WE', + 921: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD', + 922: 'PH_PERF_SEL_SC7_PA4_EOPG_WE', + 923: 'PH_PERF_SEL_SC7_PA4_DEALLOC_4_0_RD', + 924: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD', + 925: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE', + 926: 'PH_PERF_SEL_SC7_PA5_FIFO_EMPTY', + 927: 'PH_PERF_SEL_SC7_PA5_FIFO_FULL', + 928: 'PH_PERF_SEL_SC7_PA5_NULL_WE', + 929: 'PH_PERF_SEL_SC7_PA5_EVENT_WE', + 930: 'PH_PERF_SEL_SC7_PA5_FPOV_WE', + 931: 'PH_PERF_SEL_SC7_PA5_LPOV_WE', + 932: 'PH_PERF_SEL_SC7_PA5_EOP_WE', + 933: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD', + 934: 'PH_PERF_SEL_SC7_PA5_EOPG_WE', + 935: 'PH_PERF_SEL_SC7_PA5_DEALLOC_4_0_RD', + 936: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD', + 937: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE', + 938: 'PH_PERF_SEL_SC7_PA6_FIFO_EMPTY', + 939: 'PH_PERF_SEL_SC7_PA6_FIFO_FULL', + 940: 'PH_PERF_SEL_SC7_PA6_NULL_WE', + 941: 'PH_PERF_SEL_SC7_PA6_EVENT_WE', + 942: 'PH_PERF_SEL_SC7_PA6_FPOV_WE', + 943: 'PH_PERF_SEL_SC7_PA6_LPOV_WE', + 944: 'PH_PERF_SEL_SC7_PA6_EOP_WE', + 945: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD', + 946: 'PH_PERF_SEL_SC7_PA6_EOPG_WE', + 947: 'PH_PERF_SEL_SC7_PA6_DEALLOC_4_0_RD', + 948: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD', + 949: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE', + 950: 'PH_PERF_SEL_SC7_PA7_FIFO_EMPTY', + 951: 'PH_PERF_SEL_SC7_PA7_FIFO_FULL', + 952: 'PH_PERF_SEL_SC7_PA7_NULL_WE', + 953: 'PH_PERF_SEL_SC7_PA7_EVENT_WE', + 954: 'PH_PERF_SEL_SC7_PA7_FPOV_WE', + 955: 'PH_PERF_SEL_SC7_PA7_LPOV_WE', + 956: 'PH_PERF_SEL_SC7_PA7_EOP_WE', + 957: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD', + 958: 'PH_PERF_SEL_SC7_PA7_EOPG_WE', + 959: 'PH_PERF_SEL_SC7_PA7_DEALLOC_4_0_RD', + 960: 'PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW', + 961: 'PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW', + 962: 'PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW', + 963: 'PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW', + 964: 'PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW', + 965: 'PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW', + 966: 'PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW', + 967: 'PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW', + 968: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE', + 969: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE', + 970: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE', + 971: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE', + 972: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE', + 973: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE', + 974: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE', + 975: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE', + 976: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 977: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 978: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 979: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 980: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 981: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 982: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 983: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 984: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 985: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 986: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 987: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 988: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 989: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 990: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 991: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 992: 'PH_PERF_SC0_FIFO_STATUS_0', + 993: 'PH_PERF_SC0_FIFO_STATUS_1', + 994: 'PH_PERF_SC0_FIFO_STATUS_2', + 995: 'PH_PERF_SC0_FIFO_STATUS_3', + 996: 'PH_PERF_SC1_FIFO_STATUS_0', + 997: 'PH_PERF_SC1_FIFO_STATUS_1', + 998: 'PH_PERF_SC1_FIFO_STATUS_2', + 999: 'PH_PERF_SC1_FIFO_STATUS_3', + 1000: 'PH_PERF_SC2_FIFO_STATUS_0', + 1001: 'PH_PERF_SC2_FIFO_STATUS_1', + 1002: 'PH_PERF_SC2_FIFO_STATUS_2', + 1003: 'PH_PERF_SC2_FIFO_STATUS_3', + 1004: 'PH_PERF_SC3_FIFO_STATUS_0', + 1005: 'PH_PERF_SC3_FIFO_STATUS_1', + 1006: 'PH_PERF_SC3_FIFO_STATUS_2', + 1007: 'PH_PERF_SC3_FIFO_STATUS_3', + 1008: 'PH_PERF_SC4_FIFO_STATUS_0', + 1009: 'PH_PERF_SC4_FIFO_STATUS_1', + 1010: 'PH_PERF_SC4_FIFO_STATUS_2', + 1011: 'PH_PERF_SC4_FIFO_STATUS_3', + 1012: 'PH_PERF_SC5_FIFO_STATUS_0', + 1013: 'PH_PERF_SC5_FIFO_STATUS_1', + 1014: 'PH_PERF_SC5_FIFO_STATUS_2', + 1015: 'PH_PERF_SC5_FIFO_STATUS_3', + 1016: 'PH_PERF_SC6_FIFO_STATUS_0', + 1017: 'PH_PERF_SC6_FIFO_STATUS_1', + 1018: 'PH_PERF_SC6_FIFO_STATUS_2', + 1019: 'PH_PERF_SC6_FIFO_STATUS_3', + 1020: 'PH_PERF_SC7_FIFO_STATUS_0', + 1021: 'PH_PERF_SC7_FIFO_STATUS_1', + 1022: 'PH_PERF_SC7_FIFO_STATUS_2', + 1023: 'PH_PERF_SC7_FIFO_STATUS_3', +} +PH_PERF_SEL_SC0_SRPS_WINDOW_VALID = 0 +PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 1 +PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES = 2 +PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 3 +PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW = 4 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE = 5 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 6 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 7 +PH_PERF_SEL_SC0_ARB_BUSY = 8 +PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP = 9 +PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP = 10 +PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP = 11 +PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE = 12 +PH_PERF_SEL_SC0_EOP_SYNC_WINDOW = 13 +PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM = 14 +PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO = 15 +PH_PERF_SEL_SC0_SEND = 16 +PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND = 17 +PH_PERF_SEL_SC0_CREDIT_AT_MAX = 18 +PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND = 19 +PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION = 20 +PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION = 21 +PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION = 22 +PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 23 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD = 24 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE = 25 +PH_PERF_SEL_SC0_PA0_FIFO_EMPTY = 26 +PH_PERF_SEL_SC0_PA0_FIFO_FULL = 27 +PH_PERF_SEL_SC0_PA0_NULL_WE = 28 +PH_PERF_SEL_SC0_PA0_EVENT_WE = 29 +PH_PERF_SEL_SC0_PA0_FPOV_WE = 30 +PH_PERF_SEL_SC0_PA0_LPOV_WE = 31 +PH_PERF_SEL_SC0_PA0_EOP_WE = 32 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD = 33 +PH_PERF_SEL_SC0_PA0_EOPG_WE = 34 +PH_PERF_SEL_SC0_PA0_DEALLOC_4_0_RD = 35 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD = 36 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE = 37 +PH_PERF_SEL_SC0_PA1_FIFO_EMPTY = 38 +PH_PERF_SEL_SC0_PA1_FIFO_FULL = 39 +PH_PERF_SEL_SC0_PA1_NULL_WE = 40 +PH_PERF_SEL_SC0_PA1_EVENT_WE = 41 +PH_PERF_SEL_SC0_PA1_FPOV_WE = 42 +PH_PERF_SEL_SC0_PA1_LPOV_WE = 43 +PH_PERF_SEL_SC0_PA1_EOP_WE = 44 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD = 45 +PH_PERF_SEL_SC0_PA1_EOPG_WE = 46 +PH_PERF_SEL_SC0_PA1_DEALLOC_4_0_RD = 47 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD = 48 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE = 49 +PH_PERF_SEL_SC0_PA2_FIFO_EMPTY = 50 +PH_PERF_SEL_SC0_PA2_FIFO_FULL = 51 +PH_PERF_SEL_SC0_PA2_NULL_WE = 52 +PH_PERF_SEL_SC0_PA2_EVENT_WE = 53 +PH_PERF_SEL_SC0_PA2_FPOV_WE = 54 +PH_PERF_SEL_SC0_PA2_LPOV_WE = 55 +PH_PERF_SEL_SC0_PA2_EOP_WE = 56 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD = 57 +PH_PERF_SEL_SC0_PA2_EOPG_WE = 58 +PH_PERF_SEL_SC0_PA2_DEALLOC_4_0_RD = 59 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD = 60 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE = 61 +PH_PERF_SEL_SC0_PA3_FIFO_EMPTY = 62 +PH_PERF_SEL_SC0_PA3_FIFO_FULL = 63 +PH_PERF_SEL_SC0_PA3_NULL_WE = 64 +PH_PERF_SEL_SC0_PA3_EVENT_WE = 65 +PH_PERF_SEL_SC0_PA3_FPOV_WE = 66 +PH_PERF_SEL_SC0_PA3_LPOV_WE = 67 +PH_PERF_SEL_SC0_PA3_EOP_WE = 68 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD = 69 +PH_PERF_SEL_SC0_PA3_EOPG_WE = 70 +PH_PERF_SEL_SC0_PA3_DEALLOC_4_0_RD = 71 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD = 72 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE = 73 +PH_PERF_SEL_SC0_PA4_FIFO_EMPTY = 74 +PH_PERF_SEL_SC0_PA4_FIFO_FULL = 75 +PH_PERF_SEL_SC0_PA4_NULL_WE = 76 +PH_PERF_SEL_SC0_PA4_EVENT_WE = 77 +PH_PERF_SEL_SC0_PA4_FPOV_WE = 78 +PH_PERF_SEL_SC0_PA4_LPOV_WE = 79 +PH_PERF_SEL_SC0_PA4_EOP_WE = 80 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD = 81 +PH_PERF_SEL_SC0_PA4_EOPG_WE = 82 +PH_PERF_SEL_SC0_PA4_DEALLOC_4_0_RD = 83 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD = 84 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE = 85 +PH_PERF_SEL_SC0_PA5_FIFO_EMPTY = 86 +PH_PERF_SEL_SC0_PA5_FIFO_FULL = 87 +PH_PERF_SEL_SC0_PA5_NULL_WE = 88 +PH_PERF_SEL_SC0_PA5_EVENT_WE = 89 +PH_PERF_SEL_SC0_PA5_FPOV_WE = 90 +PH_PERF_SEL_SC0_PA5_LPOV_WE = 91 +PH_PERF_SEL_SC0_PA5_EOP_WE = 92 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD = 93 +PH_PERF_SEL_SC0_PA5_EOPG_WE = 94 +PH_PERF_SEL_SC0_PA5_DEALLOC_4_0_RD = 95 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD = 96 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE = 97 +PH_PERF_SEL_SC0_PA6_FIFO_EMPTY = 98 +PH_PERF_SEL_SC0_PA6_FIFO_FULL = 99 +PH_PERF_SEL_SC0_PA6_NULL_WE = 100 +PH_PERF_SEL_SC0_PA6_EVENT_WE = 101 +PH_PERF_SEL_SC0_PA6_FPOV_WE = 102 +PH_PERF_SEL_SC0_PA6_LPOV_WE = 103 +PH_PERF_SEL_SC0_PA6_EOP_WE = 104 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD = 105 +PH_PERF_SEL_SC0_PA6_EOPG_WE = 106 +PH_PERF_SEL_SC0_PA6_DEALLOC_4_0_RD = 107 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD = 108 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE = 109 +PH_PERF_SEL_SC0_PA7_FIFO_EMPTY = 110 +PH_PERF_SEL_SC0_PA7_FIFO_FULL = 111 +PH_PERF_SEL_SC0_PA7_NULL_WE = 112 +PH_PERF_SEL_SC0_PA7_EVENT_WE = 113 +PH_PERF_SEL_SC0_PA7_FPOV_WE = 114 +PH_PERF_SEL_SC0_PA7_LPOV_WE = 115 +PH_PERF_SEL_SC0_PA7_EOP_WE = 116 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD = 117 +PH_PERF_SEL_SC0_PA7_EOPG_WE = 118 +PH_PERF_SEL_SC0_PA7_DEALLOC_4_0_RD = 119 +PH_PERF_SEL_SC1_SRPS_WINDOW_VALID = 120 +PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 121 +PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES = 122 +PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 123 +PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW = 124 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE = 125 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 126 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 127 +PH_PERF_SEL_SC1_ARB_BUSY = 128 +PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP = 129 +PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP = 130 +PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP = 131 +PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE = 132 +PH_PERF_SEL_SC1_EOP_SYNC_WINDOW = 133 +PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM = 134 +PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO = 135 +PH_PERF_SEL_SC1_SEND = 136 +PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND = 137 +PH_PERF_SEL_SC1_CREDIT_AT_MAX = 138 +PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND = 139 +PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION = 140 +PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION = 141 +PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 142 +PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 143 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD = 144 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE = 145 +PH_PERF_SEL_SC1_PA0_FIFO_EMPTY = 146 +PH_PERF_SEL_SC1_PA0_FIFO_FULL = 147 +PH_PERF_SEL_SC1_PA0_NULL_WE = 148 +PH_PERF_SEL_SC1_PA0_EVENT_WE = 149 +PH_PERF_SEL_SC1_PA0_FPOV_WE = 150 +PH_PERF_SEL_SC1_PA0_LPOV_WE = 151 +PH_PERF_SEL_SC1_PA0_EOP_WE = 152 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD = 153 +PH_PERF_SEL_SC1_PA0_EOPG_WE = 154 +PH_PERF_SEL_SC1_PA0_DEALLOC_4_0_RD = 155 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD = 156 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE = 157 +PH_PERF_SEL_SC1_PA1_FIFO_EMPTY = 158 +PH_PERF_SEL_SC1_PA1_FIFO_FULL = 159 +PH_PERF_SEL_SC1_PA1_NULL_WE = 160 +PH_PERF_SEL_SC1_PA1_EVENT_WE = 161 +PH_PERF_SEL_SC1_PA1_FPOV_WE = 162 +PH_PERF_SEL_SC1_PA1_LPOV_WE = 163 +PH_PERF_SEL_SC1_PA1_EOP_WE = 164 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD = 165 +PH_PERF_SEL_SC1_PA1_EOPG_WE = 166 +PH_PERF_SEL_SC1_PA1_DEALLOC_4_0_RD = 167 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD = 168 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE = 169 +PH_PERF_SEL_SC1_PA2_FIFO_EMPTY = 170 +PH_PERF_SEL_SC1_PA2_FIFO_FULL = 171 +PH_PERF_SEL_SC1_PA2_NULL_WE = 172 +PH_PERF_SEL_SC1_PA2_EVENT_WE = 173 +PH_PERF_SEL_SC1_PA2_FPOV_WE = 174 +PH_PERF_SEL_SC1_PA2_LPOV_WE = 175 +PH_PERF_SEL_SC1_PA2_EOP_WE = 176 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD = 177 +PH_PERF_SEL_SC1_PA2_EOPG_WE = 178 +PH_PERF_SEL_SC1_PA2_DEALLOC_4_0_RD = 179 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD = 180 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE = 181 +PH_PERF_SEL_SC1_PA3_FIFO_EMPTY = 182 +PH_PERF_SEL_SC1_PA3_FIFO_FULL = 183 +PH_PERF_SEL_SC1_PA3_NULL_WE = 184 +PH_PERF_SEL_SC1_PA3_EVENT_WE = 185 +PH_PERF_SEL_SC1_PA3_FPOV_WE = 186 +PH_PERF_SEL_SC1_PA3_LPOV_WE = 187 +PH_PERF_SEL_SC1_PA3_EOP_WE = 188 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD = 189 +PH_PERF_SEL_SC1_PA3_EOPG_WE = 190 +PH_PERF_SEL_SC1_PA3_DEALLOC_4_0_RD = 191 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD = 192 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE = 193 +PH_PERF_SEL_SC1_PA4_FIFO_EMPTY = 194 +PH_PERF_SEL_SC1_PA4_FIFO_FULL = 195 +PH_PERF_SEL_SC1_PA4_NULL_WE = 196 +PH_PERF_SEL_SC1_PA4_EVENT_WE = 197 +PH_PERF_SEL_SC1_PA4_FPOV_WE = 198 +PH_PERF_SEL_SC1_PA4_LPOV_WE = 199 +PH_PERF_SEL_SC1_PA4_EOP_WE = 200 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD = 201 +PH_PERF_SEL_SC1_PA4_EOPG_WE = 202 +PH_PERF_SEL_SC1_PA4_DEALLOC_4_0_RD = 203 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD = 204 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE = 205 +PH_PERF_SEL_SC1_PA5_FIFO_EMPTY = 206 +PH_PERF_SEL_SC1_PA5_FIFO_FULL = 207 +PH_PERF_SEL_SC1_PA5_NULL_WE = 208 +PH_PERF_SEL_SC1_PA5_EVENT_WE = 209 +PH_PERF_SEL_SC1_PA5_FPOV_WE = 210 +PH_PERF_SEL_SC1_PA5_LPOV_WE = 211 +PH_PERF_SEL_SC1_PA5_EOP_WE = 212 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD = 213 +PH_PERF_SEL_SC1_PA5_EOPG_WE = 214 +PH_PERF_SEL_SC1_PA5_DEALLOC_4_0_RD = 215 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD = 216 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE = 217 +PH_PERF_SEL_SC1_PA6_FIFO_EMPTY = 218 +PH_PERF_SEL_SC1_PA6_FIFO_FULL = 219 +PH_PERF_SEL_SC1_PA6_NULL_WE = 220 +PH_PERF_SEL_SC1_PA6_EVENT_WE = 221 +PH_PERF_SEL_SC1_PA6_FPOV_WE = 222 +PH_PERF_SEL_SC1_PA6_LPOV_WE = 223 +PH_PERF_SEL_SC1_PA6_EOP_WE = 224 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD = 225 +PH_PERF_SEL_SC1_PA6_EOPG_WE = 226 +PH_PERF_SEL_SC1_PA6_DEALLOC_4_0_RD = 227 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD = 228 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE = 229 +PH_PERF_SEL_SC1_PA7_FIFO_EMPTY = 230 +PH_PERF_SEL_SC1_PA7_FIFO_FULL = 231 +PH_PERF_SEL_SC1_PA7_NULL_WE = 232 +PH_PERF_SEL_SC1_PA7_EVENT_WE = 233 +PH_PERF_SEL_SC1_PA7_FPOV_WE = 234 +PH_PERF_SEL_SC1_PA7_LPOV_WE = 235 +PH_PERF_SEL_SC1_PA7_EOP_WE = 236 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD = 237 +PH_PERF_SEL_SC1_PA7_EOPG_WE = 238 +PH_PERF_SEL_SC1_PA7_DEALLOC_4_0_RD = 239 +PH_PERF_SEL_SC2_SRPS_WINDOW_VALID = 240 +PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 241 +PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES = 242 +PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 243 +PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW = 244 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE = 245 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 246 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 247 +PH_PERF_SEL_SC2_ARB_BUSY = 248 +PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP = 249 +PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP = 250 +PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP = 251 +PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE = 252 +PH_PERF_SEL_SC2_EOP_SYNC_WINDOW = 253 +PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM = 254 +PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO = 255 +PH_PERF_SEL_SC2_SEND = 256 +PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND = 257 +PH_PERF_SEL_SC2_CREDIT_AT_MAX = 258 +PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND = 259 +PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION = 260 +PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION = 261 +PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 262 +PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 263 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD = 264 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE = 265 +PH_PERF_SEL_SC2_PA0_FIFO_EMPTY = 266 +PH_PERF_SEL_SC2_PA0_FIFO_FULL = 267 +PH_PERF_SEL_SC2_PA0_NULL_WE = 268 +PH_PERF_SEL_SC2_PA0_EVENT_WE = 269 +PH_PERF_SEL_SC2_PA0_FPOV_WE = 270 +PH_PERF_SEL_SC2_PA0_LPOV_WE = 271 +PH_PERF_SEL_SC2_PA0_EOP_WE = 272 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD = 273 +PH_PERF_SEL_SC2_PA0_EOPG_WE = 274 +PH_PERF_SEL_SC2_PA0_DEALLOC_4_0_RD = 275 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD = 276 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE = 277 +PH_PERF_SEL_SC2_PA1_FIFO_EMPTY = 278 +PH_PERF_SEL_SC2_PA1_FIFO_FULL = 279 +PH_PERF_SEL_SC2_PA1_NULL_WE = 280 +PH_PERF_SEL_SC2_PA1_EVENT_WE = 281 +PH_PERF_SEL_SC2_PA1_FPOV_WE = 282 +PH_PERF_SEL_SC2_PA1_LPOV_WE = 283 +PH_PERF_SEL_SC2_PA1_EOP_WE = 284 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD = 285 +PH_PERF_SEL_SC2_PA1_EOPG_WE = 286 +PH_PERF_SEL_SC2_PA1_DEALLOC_4_0_RD = 287 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD = 288 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE = 289 +PH_PERF_SEL_SC2_PA2_FIFO_EMPTY = 290 +PH_PERF_SEL_SC2_PA2_FIFO_FULL = 291 +PH_PERF_SEL_SC2_PA2_NULL_WE = 292 +PH_PERF_SEL_SC2_PA2_EVENT_WE = 293 +PH_PERF_SEL_SC2_PA2_FPOV_WE = 294 +PH_PERF_SEL_SC2_PA2_LPOV_WE = 295 +PH_PERF_SEL_SC2_PA2_EOP_WE = 296 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD = 297 +PH_PERF_SEL_SC2_PA2_EOPG_WE = 298 +PH_PERF_SEL_SC2_PA2_DEALLOC_4_0_RD = 299 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD = 300 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE = 301 +PH_PERF_SEL_SC2_PA3_FIFO_EMPTY = 302 +PH_PERF_SEL_SC2_PA3_FIFO_FULL = 303 +PH_PERF_SEL_SC2_PA3_NULL_WE = 304 +PH_PERF_SEL_SC2_PA3_EVENT_WE = 305 +PH_PERF_SEL_SC2_PA3_FPOV_WE = 306 +PH_PERF_SEL_SC2_PA3_LPOV_WE = 307 +PH_PERF_SEL_SC2_PA3_EOP_WE = 308 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD = 309 +PH_PERF_SEL_SC2_PA3_EOPG_WE = 310 +PH_PERF_SEL_SC2_PA3_DEALLOC_4_0_RD = 311 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD = 312 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE = 313 +PH_PERF_SEL_SC2_PA4_FIFO_EMPTY = 314 +PH_PERF_SEL_SC2_PA4_FIFO_FULL = 315 +PH_PERF_SEL_SC2_PA4_NULL_WE = 316 +PH_PERF_SEL_SC2_PA4_EVENT_WE = 317 +PH_PERF_SEL_SC2_PA4_FPOV_WE = 318 +PH_PERF_SEL_SC2_PA4_LPOV_WE = 319 +PH_PERF_SEL_SC2_PA4_EOP_WE = 320 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD = 321 +PH_PERF_SEL_SC2_PA4_EOPG_WE = 322 +PH_PERF_SEL_SC2_PA4_DEALLOC_4_0_RD = 323 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD = 324 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE = 325 +PH_PERF_SEL_SC2_PA5_FIFO_EMPTY = 326 +PH_PERF_SEL_SC2_PA5_FIFO_FULL = 327 +PH_PERF_SEL_SC2_PA5_NULL_WE = 328 +PH_PERF_SEL_SC2_PA5_EVENT_WE = 329 +PH_PERF_SEL_SC2_PA5_FPOV_WE = 330 +PH_PERF_SEL_SC2_PA5_LPOV_WE = 331 +PH_PERF_SEL_SC2_PA5_EOP_WE = 332 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD = 333 +PH_PERF_SEL_SC2_PA5_EOPG_WE = 334 +PH_PERF_SEL_SC2_PA5_DEALLOC_4_0_RD = 335 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD = 336 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE = 337 +PH_PERF_SEL_SC2_PA6_FIFO_EMPTY = 338 +PH_PERF_SEL_SC2_PA6_FIFO_FULL = 339 +PH_PERF_SEL_SC2_PA6_NULL_WE = 340 +PH_PERF_SEL_SC2_PA6_EVENT_WE = 341 +PH_PERF_SEL_SC2_PA6_FPOV_WE = 342 +PH_PERF_SEL_SC2_PA6_LPOV_WE = 343 +PH_PERF_SEL_SC2_PA6_EOP_WE = 344 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD = 345 +PH_PERF_SEL_SC2_PA6_EOPG_WE = 346 +PH_PERF_SEL_SC2_PA6_DEALLOC_4_0_RD = 347 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD = 348 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE = 349 +PH_PERF_SEL_SC2_PA7_FIFO_EMPTY = 350 +PH_PERF_SEL_SC2_PA7_FIFO_FULL = 351 +PH_PERF_SEL_SC2_PA7_NULL_WE = 352 +PH_PERF_SEL_SC2_PA7_EVENT_WE = 353 +PH_PERF_SEL_SC2_PA7_FPOV_WE = 354 +PH_PERF_SEL_SC2_PA7_LPOV_WE = 355 +PH_PERF_SEL_SC2_PA7_EOP_WE = 356 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD = 357 +PH_PERF_SEL_SC2_PA7_EOPG_WE = 358 +PH_PERF_SEL_SC2_PA7_DEALLOC_4_0_RD = 359 +PH_PERF_SEL_SC3_SRPS_WINDOW_VALID = 360 +PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 361 +PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES = 362 +PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 363 +PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW = 364 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE = 365 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 366 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 367 +PH_PERF_SEL_SC3_ARB_BUSY = 368 +PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP = 369 +PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP = 370 +PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP = 371 +PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE = 372 +PH_PERF_SEL_SC3_EOP_SYNC_WINDOW = 373 +PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM = 374 +PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO = 375 +PH_PERF_SEL_SC3_SEND = 376 +PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND = 377 +PH_PERF_SEL_SC3_CREDIT_AT_MAX = 378 +PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND = 379 +PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION = 380 +PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION = 381 +PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 382 +PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 383 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD = 384 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE = 385 +PH_PERF_SEL_SC3_PA0_FIFO_EMPTY = 386 +PH_PERF_SEL_SC3_PA0_FIFO_FULL = 387 +PH_PERF_SEL_SC3_PA0_NULL_WE = 388 +PH_PERF_SEL_SC3_PA0_EVENT_WE = 389 +PH_PERF_SEL_SC3_PA0_FPOV_WE = 390 +PH_PERF_SEL_SC3_PA0_LPOV_WE = 391 +PH_PERF_SEL_SC3_PA0_EOP_WE = 392 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD = 393 +PH_PERF_SEL_SC3_PA0_EOPG_WE = 394 +PH_PERF_SEL_SC3_PA0_DEALLOC_4_0_RD = 395 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD = 396 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE = 397 +PH_PERF_SEL_SC3_PA1_FIFO_EMPTY = 398 +PH_PERF_SEL_SC3_PA1_FIFO_FULL = 399 +PH_PERF_SEL_SC3_PA1_NULL_WE = 400 +PH_PERF_SEL_SC3_PA1_EVENT_WE = 401 +PH_PERF_SEL_SC3_PA1_FPOV_WE = 402 +PH_PERF_SEL_SC3_PA1_LPOV_WE = 403 +PH_PERF_SEL_SC3_PA1_EOP_WE = 404 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD = 405 +PH_PERF_SEL_SC3_PA1_EOPG_WE = 406 +PH_PERF_SEL_SC3_PA1_DEALLOC_4_0_RD = 407 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD = 408 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE = 409 +PH_PERF_SEL_SC3_PA2_FIFO_EMPTY = 410 +PH_PERF_SEL_SC3_PA2_FIFO_FULL = 411 +PH_PERF_SEL_SC3_PA2_NULL_WE = 412 +PH_PERF_SEL_SC3_PA2_EVENT_WE = 413 +PH_PERF_SEL_SC3_PA2_FPOV_WE = 414 +PH_PERF_SEL_SC3_PA2_LPOV_WE = 415 +PH_PERF_SEL_SC3_PA2_EOP_WE = 416 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD = 417 +PH_PERF_SEL_SC3_PA2_EOPG_WE = 418 +PH_PERF_SEL_SC3_PA2_DEALLOC_4_0_RD = 419 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD = 420 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE = 421 +PH_PERF_SEL_SC3_PA3_FIFO_EMPTY = 422 +PH_PERF_SEL_SC3_PA3_FIFO_FULL = 423 +PH_PERF_SEL_SC3_PA3_NULL_WE = 424 +PH_PERF_SEL_SC3_PA3_EVENT_WE = 425 +PH_PERF_SEL_SC3_PA3_FPOV_WE = 426 +PH_PERF_SEL_SC3_PA3_LPOV_WE = 427 +PH_PERF_SEL_SC3_PA3_EOP_WE = 428 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD = 429 +PH_PERF_SEL_SC3_PA3_EOPG_WE = 430 +PH_PERF_SEL_SC3_PA3_DEALLOC_4_0_RD = 431 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD = 432 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE = 433 +PH_PERF_SEL_SC3_PA4_FIFO_EMPTY = 434 +PH_PERF_SEL_SC3_PA4_FIFO_FULL = 435 +PH_PERF_SEL_SC3_PA4_NULL_WE = 436 +PH_PERF_SEL_SC3_PA4_EVENT_WE = 437 +PH_PERF_SEL_SC3_PA4_FPOV_WE = 438 +PH_PERF_SEL_SC3_PA4_LPOV_WE = 439 +PH_PERF_SEL_SC3_PA4_EOP_WE = 440 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD = 441 +PH_PERF_SEL_SC3_PA4_EOPG_WE = 442 +PH_PERF_SEL_SC3_PA4_DEALLOC_4_0_RD = 443 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD = 444 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE = 445 +PH_PERF_SEL_SC3_PA5_FIFO_EMPTY = 446 +PH_PERF_SEL_SC3_PA5_FIFO_FULL = 447 +PH_PERF_SEL_SC3_PA5_NULL_WE = 448 +PH_PERF_SEL_SC3_PA5_EVENT_WE = 449 +PH_PERF_SEL_SC3_PA5_FPOV_WE = 450 +PH_PERF_SEL_SC3_PA5_LPOV_WE = 451 +PH_PERF_SEL_SC3_PA5_EOP_WE = 452 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD = 453 +PH_PERF_SEL_SC3_PA5_EOPG_WE = 454 +PH_PERF_SEL_SC3_PA5_DEALLOC_4_0_RD = 455 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD = 456 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE = 457 +PH_PERF_SEL_SC3_PA6_FIFO_EMPTY = 458 +PH_PERF_SEL_SC3_PA6_FIFO_FULL = 459 +PH_PERF_SEL_SC3_PA6_NULL_WE = 460 +PH_PERF_SEL_SC3_PA6_EVENT_WE = 461 +PH_PERF_SEL_SC3_PA6_FPOV_WE = 462 +PH_PERF_SEL_SC3_PA6_LPOV_WE = 463 +PH_PERF_SEL_SC3_PA6_EOP_WE = 464 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD = 465 +PH_PERF_SEL_SC3_PA6_EOPG_WE = 466 +PH_PERF_SEL_SC3_PA6_DEALLOC_4_0_RD = 467 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD = 468 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE = 469 +PH_PERF_SEL_SC3_PA7_FIFO_EMPTY = 470 +PH_PERF_SEL_SC3_PA7_FIFO_FULL = 471 +PH_PERF_SEL_SC3_PA7_NULL_WE = 472 +PH_PERF_SEL_SC3_PA7_EVENT_WE = 473 +PH_PERF_SEL_SC3_PA7_FPOV_WE = 474 +PH_PERF_SEL_SC3_PA7_LPOV_WE = 475 +PH_PERF_SEL_SC3_PA7_EOP_WE = 476 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD = 477 +PH_PERF_SEL_SC3_PA7_EOPG_WE = 478 +PH_PERF_SEL_SC3_PA7_DEALLOC_4_0_RD = 479 +PH_PERF_SEL_SC4_SRPS_WINDOW_VALID = 480 +PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 481 +PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES = 482 +PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 483 +PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW = 484 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE = 485 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 486 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 487 +PH_PERF_SEL_SC4_ARB_BUSY = 488 +PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP = 489 +PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP = 490 +PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP = 491 +PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE = 492 +PH_PERF_SEL_SC4_EOP_SYNC_WINDOW = 493 +PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM = 494 +PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO = 495 +PH_PERF_SEL_SC4_SEND = 496 +PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND = 497 +PH_PERF_SEL_SC4_CREDIT_AT_MAX = 498 +PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND = 499 +PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION = 500 +PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION = 501 +PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 502 +PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 503 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD = 504 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE = 505 +PH_PERF_SEL_SC4_PA0_FIFO_EMPTY = 506 +PH_PERF_SEL_SC4_PA0_FIFO_FULL = 507 +PH_PERF_SEL_SC4_PA0_NULL_WE = 508 +PH_PERF_SEL_SC4_PA0_EVENT_WE = 509 +PH_PERF_SEL_SC4_PA0_FPOV_WE = 510 +PH_PERF_SEL_SC4_PA0_LPOV_WE = 511 +PH_PERF_SEL_SC4_PA0_EOP_WE = 512 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD = 513 +PH_PERF_SEL_SC4_PA0_EOPG_WE = 514 +PH_PERF_SEL_SC4_PA0_DEALLOC_4_0_RD = 515 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD = 516 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE = 517 +PH_PERF_SEL_SC4_PA1_FIFO_EMPTY = 518 +PH_PERF_SEL_SC4_PA1_FIFO_FULL = 519 +PH_PERF_SEL_SC4_PA1_NULL_WE = 520 +PH_PERF_SEL_SC4_PA1_EVENT_WE = 521 +PH_PERF_SEL_SC4_PA1_FPOV_WE = 522 +PH_PERF_SEL_SC4_PA1_LPOV_WE = 523 +PH_PERF_SEL_SC4_PA1_EOP_WE = 524 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD = 525 +PH_PERF_SEL_SC4_PA1_EOPG_WE = 526 +PH_PERF_SEL_SC4_PA1_DEALLOC_4_0_RD = 527 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD = 528 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE = 529 +PH_PERF_SEL_SC4_PA2_FIFO_EMPTY = 530 +PH_PERF_SEL_SC4_PA2_FIFO_FULL = 531 +PH_PERF_SEL_SC4_PA2_NULL_WE = 532 +PH_PERF_SEL_SC4_PA2_EVENT_WE = 533 +PH_PERF_SEL_SC4_PA2_FPOV_WE = 534 +PH_PERF_SEL_SC4_PA2_LPOV_WE = 535 +PH_PERF_SEL_SC4_PA2_EOP_WE = 536 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD = 537 +PH_PERF_SEL_SC4_PA2_EOPG_WE = 538 +PH_PERF_SEL_SC4_PA2_DEALLOC_4_0_RD = 539 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD = 540 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE = 541 +PH_PERF_SEL_SC4_PA3_FIFO_EMPTY = 542 +PH_PERF_SEL_SC4_PA3_FIFO_FULL = 543 +PH_PERF_SEL_SC4_PA3_NULL_WE = 544 +PH_PERF_SEL_SC4_PA3_EVENT_WE = 545 +PH_PERF_SEL_SC4_PA3_FPOV_WE = 546 +PH_PERF_SEL_SC4_PA3_LPOV_WE = 547 +PH_PERF_SEL_SC4_PA3_EOP_WE = 548 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD = 549 +PH_PERF_SEL_SC4_PA3_EOPG_WE = 550 +PH_PERF_SEL_SC4_PA3_DEALLOC_4_0_RD = 551 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD = 552 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE = 553 +PH_PERF_SEL_SC4_PA4_FIFO_EMPTY = 554 +PH_PERF_SEL_SC4_PA4_FIFO_FULL = 555 +PH_PERF_SEL_SC4_PA4_NULL_WE = 556 +PH_PERF_SEL_SC4_PA4_EVENT_WE = 557 +PH_PERF_SEL_SC4_PA4_FPOV_WE = 558 +PH_PERF_SEL_SC4_PA4_LPOV_WE = 559 +PH_PERF_SEL_SC4_PA4_EOP_WE = 560 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD = 561 +PH_PERF_SEL_SC4_PA4_EOPG_WE = 562 +PH_PERF_SEL_SC4_PA4_DEALLOC_4_0_RD = 563 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD = 564 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE = 565 +PH_PERF_SEL_SC4_PA5_FIFO_EMPTY = 566 +PH_PERF_SEL_SC4_PA5_FIFO_FULL = 567 +PH_PERF_SEL_SC4_PA5_NULL_WE = 568 +PH_PERF_SEL_SC4_PA5_EVENT_WE = 569 +PH_PERF_SEL_SC4_PA5_FPOV_WE = 570 +PH_PERF_SEL_SC4_PA5_LPOV_WE = 571 +PH_PERF_SEL_SC4_PA5_EOP_WE = 572 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD = 573 +PH_PERF_SEL_SC4_PA5_EOPG_WE = 574 +PH_PERF_SEL_SC4_PA5_DEALLOC_4_0_RD = 575 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD = 576 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE = 577 +PH_PERF_SEL_SC4_PA6_FIFO_EMPTY = 578 +PH_PERF_SEL_SC4_PA6_FIFO_FULL = 579 +PH_PERF_SEL_SC4_PA6_NULL_WE = 580 +PH_PERF_SEL_SC4_PA6_EVENT_WE = 581 +PH_PERF_SEL_SC4_PA6_FPOV_WE = 582 +PH_PERF_SEL_SC4_PA6_LPOV_WE = 583 +PH_PERF_SEL_SC4_PA6_EOP_WE = 584 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD = 585 +PH_PERF_SEL_SC4_PA6_EOPG_WE = 586 +PH_PERF_SEL_SC4_PA6_DEALLOC_4_0_RD = 587 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD = 588 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE = 589 +PH_PERF_SEL_SC4_PA7_FIFO_EMPTY = 590 +PH_PERF_SEL_SC4_PA7_FIFO_FULL = 591 +PH_PERF_SEL_SC4_PA7_NULL_WE = 592 +PH_PERF_SEL_SC4_PA7_EVENT_WE = 593 +PH_PERF_SEL_SC4_PA7_FPOV_WE = 594 +PH_PERF_SEL_SC4_PA7_LPOV_WE = 595 +PH_PERF_SEL_SC4_PA7_EOP_WE = 596 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD = 597 +PH_PERF_SEL_SC4_PA7_EOPG_WE = 598 +PH_PERF_SEL_SC4_PA7_DEALLOC_4_0_RD = 599 +PH_PERF_SEL_SC5_SRPS_WINDOW_VALID = 600 +PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 601 +PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES = 602 +PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 603 +PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW = 604 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE = 605 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 606 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 607 +PH_PERF_SEL_SC5_ARB_BUSY = 608 +PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP = 609 +PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP = 610 +PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP = 611 +PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE = 612 +PH_PERF_SEL_SC5_EOP_SYNC_WINDOW = 613 +PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM = 614 +PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO = 615 +PH_PERF_SEL_SC5_SEND = 616 +PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND = 617 +PH_PERF_SEL_SC5_CREDIT_AT_MAX = 618 +PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND = 619 +PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION = 620 +PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION = 621 +PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 622 +PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 623 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD = 624 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE = 625 +PH_PERF_SEL_SC5_PA0_FIFO_EMPTY = 626 +PH_PERF_SEL_SC5_PA0_FIFO_FULL = 627 +PH_PERF_SEL_SC5_PA0_NULL_WE = 628 +PH_PERF_SEL_SC5_PA0_EVENT_WE = 629 +PH_PERF_SEL_SC5_PA0_FPOV_WE = 630 +PH_PERF_SEL_SC5_PA0_LPOV_WE = 631 +PH_PERF_SEL_SC5_PA0_EOP_WE = 632 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD = 633 +PH_PERF_SEL_SC5_PA0_EOPG_WE = 634 +PH_PERF_SEL_SC5_PA0_DEALLOC_4_0_RD = 635 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD = 636 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE = 637 +PH_PERF_SEL_SC5_PA1_FIFO_EMPTY = 638 +PH_PERF_SEL_SC5_PA1_FIFO_FULL = 639 +PH_PERF_SEL_SC5_PA1_NULL_WE = 640 +PH_PERF_SEL_SC5_PA1_EVENT_WE = 641 +PH_PERF_SEL_SC5_PA1_FPOV_WE = 642 +PH_PERF_SEL_SC5_PA1_LPOV_WE = 643 +PH_PERF_SEL_SC5_PA1_EOP_WE = 644 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD = 645 +PH_PERF_SEL_SC5_PA1_EOPG_WE = 646 +PH_PERF_SEL_SC5_PA1_DEALLOC_4_0_RD = 647 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD = 648 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE = 649 +PH_PERF_SEL_SC5_PA2_FIFO_EMPTY = 650 +PH_PERF_SEL_SC5_PA2_FIFO_FULL = 651 +PH_PERF_SEL_SC5_PA2_NULL_WE = 652 +PH_PERF_SEL_SC5_PA2_EVENT_WE = 653 +PH_PERF_SEL_SC5_PA2_FPOV_WE = 654 +PH_PERF_SEL_SC5_PA2_LPOV_WE = 655 +PH_PERF_SEL_SC5_PA2_EOP_WE = 656 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD = 657 +PH_PERF_SEL_SC5_PA2_EOPG_WE = 658 +PH_PERF_SEL_SC5_PA2_DEALLOC_4_0_RD = 659 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD = 660 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE = 661 +PH_PERF_SEL_SC5_PA3_FIFO_EMPTY = 662 +PH_PERF_SEL_SC5_PA3_FIFO_FULL = 663 +PH_PERF_SEL_SC5_PA3_NULL_WE = 664 +PH_PERF_SEL_SC5_PA3_EVENT_WE = 665 +PH_PERF_SEL_SC5_PA3_FPOV_WE = 666 +PH_PERF_SEL_SC5_PA3_LPOV_WE = 667 +PH_PERF_SEL_SC5_PA3_EOP_WE = 668 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD = 669 +PH_PERF_SEL_SC5_PA3_EOPG_WE = 670 +PH_PERF_SEL_SC5_PA3_DEALLOC_4_0_RD = 671 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD = 672 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE = 673 +PH_PERF_SEL_SC5_PA4_FIFO_EMPTY = 674 +PH_PERF_SEL_SC5_PA4_FIFO_FULL = 675 +PH_PERF_SEL_SC5_PA4_NULL_WE = 676 +PH_PERF_SEL_SC5_PA4_EVENT_WE = 677 +PH_PERF_SEL_SC5_PA4_FPOV_WE = 678 +PH_PERF_SEL_SC5_PA4_LPOV_WE = 679 +PH_PERF_SEL_SC5_PA4_EOP_WE = 680 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD = 681 +PH_PERF_SEL_SC5_PA4_EOPG_WE = 682 +PH_PERF_SEL_SC5_PA4_DEALLOC_4_0_RD = 683 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD = 684 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE = 685 +PH_PERF_SEL_SC5_PA5_FIFO_EMPTY = 686 +PH_PERF_SEL_SC5_PA5_FIFO_FULL = 687 +PH_PERF_SEL_SC5_PA5_NULL_WE = 688 +PH_PERF_SEL_SC5_PA5_EVENT_WE = 689 +PH_PERF_SEL_SC5_PA5_FPOV_WE = 690 +PH_PERF_SEL_SC5_PA5_LPOV_WE = 691 +PH_PERF_SEL_SC5_PA5_EOP_WE = 692 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD = 693 +PH_PERF_SEL_SC5_PA5_EOPG_WE = 694 +PH_PERF_SEL_SC5_PA5_DEALLOC_4_0_RD = 695 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD = 696 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE = 697 +PH_PERF_SEL_SC5_PA6_FIFO_EMPTY = 698 +PH_PERF_SEL_SC5_PA6_FIFO_FULL = 699 +PH_PERF_SEL_SC5_PA6_NULL_WE = 700 +PH_PERF_SEL_SC5_PA6_EVENT_WE = 701 +PH_PERF_SEL_SC5_PA6_FPOV_WE = 702 +PH_PERF_SEL_SC5_PA6_LPOV_WE = 703 +PH_PERF_SEL_SC5_PA6_EOP_WE = 704 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD = 705 +PH_PERF_SEL_SC5_PA6_EOPG_WE = 706 +PH_PERF_SEL_SC5_PA6_DEALLOC_4_0_RD = 707 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD = 708 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE = 709 +PH_PERF_SEL_SC5_PA7_FIFO_EMPTY = 710 +PH_PERF_SEL_SC5_PA7_FIFO_FULL = 711 +PH_PERF_SEL_SC5_PA7_NULL_WE = 712 +PH_PERF_SEL_SC5_PA7_EVENT_WE = 713 +PH_PERF_SEL_SC5_PA7_FPOV_WE = 714 +PH_PERF_SEL_SC5_PA7_LPOV_WE = 715 +PH_PERF_SEL_SC5_PA7_EOP_WE = 716 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD = 717 +PH_PERF_SEL_SC5_PA7_EOPG_WE = 718 +PH_PERF_SEL_SC5_PA7_DEALLOC_4_0_RD = 719 +PH_PERF_SEL_SC6_SRPS_WINDOW_VALID = 720 +PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 721 +PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES = 722 +PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 723 +PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW = 724 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE = 725 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 726 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 727 +PH_PERF_SEL_SC6_ARB_BUSY = 728 +PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP = 729 +PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP = 730 +PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP = 731 +PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE = 732 +PH_PERF_SEL_SC6_EOP_SYNC_WINDOW = 733 +PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM = 734 +PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO = 735 +PH_PERF_SEL_SC6_SEND = 736 +PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND = 737 +PH_PERF_SEL_SC6_CREDIT_AT_MAX = 738 +PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND = 739 +PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION = 740 +PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION = 741 +PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 742 +PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 743 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD = 744 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE = 745 +PH_PERF_SEL_SC6_PA0_FIFO_EMPTY = 746 +PH_PERF_SEL_SC6_PA0_FIFO_FULL = 747 +PH_PERF_SEL_SC6_PA0_NULL_WE = 748 +PH_PERF_SEL_SC6_PA0_EVENT_WE = 749 +PH_PERF_SEL_SC6_PA0_FPOV_WE = 750 +PH_PERF_SEL_SC6_PA0_LPOV_WE = 751 +PH_PERF_SEL_SC6_PA0_EOP_WE = 752 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD = 753 +PH_PERF_SEL_SC6_PA0_EOPG_WE = 754 +PH_PERF_SEL_SC6_PA0_DEALLOC_4_0_RD = 755 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD = 756 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE = 757 +PH_PERF_SEL_SC6_PA1_FIFO_EMPTY = 758 +PH_PERF_SEL_SC6_PA1_FIFO_FULL = 759 +PH_PERF_SEL_SC6_PA1_NULL_WE = 760 +PH_PERF_SEL_SC6_PA1_EVENT_WE = 761 +PH_PERF_SEL_SC6_PA1_FPOV_WE = 762 +PH_PERF_SEL_SC6_PA1_LPOV_WE = 763 +PH_PERF_SEL_SC6_PA1_EOP_WE = 764 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD = 765 +PH_PERF_SEL_SC6_PA1_EOPG_WE = 766 +PH_PERF_SEL_SC6_PA1_DEALLOC_4_0_RD = 767 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD = 768 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE = 769 +PH_PERF_SEL_SC6_PA2_FIFO_EMPTY = 770 +PH_PERF_SEL_SC6_PA2_FIFO_FULL = 771 +PH_PERF_SEL_SC6_PA2_NULL_WE = 772 +PH_PERF_SEL_SC6_PA2_EVENT_WE = 773 +PH_PERF_SEL_SC6_PA2_FPOV_WE = 774 +PH_PERF_SEL_SC6_PA2_LPOV_WE = 775 +PH_PERF_SEL_SC6_PA2_EOP_WE = 776 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD = 777 +PH_PERF_SEL_SC6_PA2_EOPG_WE = 778 +PH_PERF_SEL_SC6_PA2_DEALLOC_4_0_RD = 779 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD = 780 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE = 781 +PH_PERF_SEL_SC6_PA3_FIFO_EMPTY = 782 +PH_PERF_SEL_SC6_PA3_FIFO_FULL = 783 +PH_PERF_SEL_SC6_PA3_NULL_WE = 784 +PH_PERF_SEL_SC6_PA3_EVENT_WE = 785 +PH_PERF_SEL_SC6_PA3_FPOV_WE = 786 +PH_PERF_SEL_SC6_PA3_LPOV_WE = 787 +PH_PERF_SEL_SC6_PA3_EOP_WE = 788 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD = 789 +PH_PERF_SEL_SC6_PA3_EOPG_WE = 790 +PH_PERF_SEL_SC6_PA3_DEALLOC_4_0_RD = 791 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD = 792 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE = 793 +PH_PERF_SEL_SC6_PA4_FIFO_EMPTY = 794 +PH_PERF_SEL_SC6_PA4_FIFO_FULL = 795 +PH_PERF_SEL_SC6_PA4_NULL_WE = 796 +PH_PERF_SEL_SC6_PA4_EVENT_WE = 797 +PH_PERF_SEL_SC6_PA4_FPOV_WE = 798 +PH_PERF_SEL_SC6_PA4_LPOV_WE = 799 +PH_PERF_SEL_SC6_PA4_EOP_WE = 800 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD = 801 +PH_PERF_SEL_SC6_PA4_EOPG_WE = 802 +PH_PERF_SEL_SC6_PA4_DEALLOC_4_0_RD = 803 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD = 804 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE = 805 +PH_PERF_SEL_SC6_PA5_FIFO_EMPTY = 806 +PH_PERF_SEL_SC6_PA5_FIFO_FULL = 807 +PH_PERF_SEL_SC6_PA5_NULL_WE = 808 +PH_PERF_SEL_SC6_PA5_EVENT_WE = 809 +PH_PERF_SEL_SC6_PA5_FPOV_WE = 810 +PH_PERF_SEL_SC6_PA5_LPOV_WE = 811 +PH_PERF_SEL_SC6_PA5_EOP_WE = 812 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD = 813 +PH_PERF_SEL_SC6_PA5_EOPG_WE = 814 +PH_PERF_SEL_SC6_PA5_DEALLOC_4_0_RD = 815 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD = 816 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE = 817 +PH_PERF_SEL_SC6_PA6_FIFO_EMPTY = 818 +PH_PERF_SEL_SC6_PA6_FIFO_FULL = 819 +PH_PERF_SEL_SC6_PA6_NULL_WE = 820 +PH_PERF_SEL_SC6_PA6_EVENT_WE = 821 +PH_PERF_SEL_SC6_PA6_FPOV_WE = 822 +PH_PERF_SEL_SC6_PA6_LPOV_WE = 823 +PH_PERF_SEL_SC6_PA6_EOP_WE = 824 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD = 825 +PH_PERF_SEL_SC6_PA6_EOPG_WE = 826 +PH_PERF_SEL_SC6_PA6_DEALLOC_4_0_RD = 827 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD = 828 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE = 829 +PH_PERF_SEL_SC6_PA7_FIFO_EMPTY = 830 +PH_PERF_SEL_SC6_PA7_FIFO_FULL = 831 +PH_PERF_SEL_SC6_PA7_NULL_WE = 832 +PH_PERF_SEL_SC6_PA7_EVENT_WE = 833 +PH_PERF_SEL_SC6_PA7_FPOV_WE = 834 +PH_PERF_SEL_SC6_PA7_LPOV_WE = 835 +PH_PERF_SEL_SC6_PA7_EOP_WE = 836 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD = 837 +PH_PERF_SEL_SC6_PA7_EOPG_WE = 838 +PH_PERF_SEL_SC6_PA7_DEALLOC_4_0_RD = 839 +PH_PERF_SEL_SC7_SRPS_WINDOW_VALID = 840 +PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 841 +PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES = 842 +PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 843 +PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW = 844 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE = 845 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 846 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 847 +PH_PERF_SEL_SC7_ARB_BUSY = 848 +PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP = 849 +PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP = 850 +PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP = 851 +PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE = 852 +PH_PERF_SEL_SC7_EOP_SYNC_WINDOW = 853 +PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM = 854 +PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO = 855 +PH_PERF_SEL_SC7_SEND = 856 +PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND = 857 +PH_PERF_SEL_SC7_CREDIT_AT_MAX = 858 +PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND = 859 +PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION = 860 +PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION = 861 +PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 862 +PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 863 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD = 864 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE = 865 +PH_PERF_SEL_SC7_PA0_FIFO_EMPTY = 866 +PH_PERF_SEL_SC7_PA0_FIFO_FULL = 867 +PH_PERF_SEL_SC7_PA0_NULL_WE = 868 +PH_PERF_SEL_SC7_PA0_EVENT_WE = 869 +PH_PERF_SEL_SC7_PA0_FPOV_WE = 870 +PH_PERF_SEL_SC7_PA0_LPOV_WE = 871 +PH_PERF_SEL_SC7_PA0_EOP_WE = 872 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD = 873 +PH_PERF_SEL_SC7_PA0_EOPG_WE = 874 +PH_PERF_SEL_SC7_PA0_DEALLOC_4_0_RD = 875 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD = 876 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE = 877 +PH_PERF_SEL_SC7_PA1_FIFO_EMPTY = 878 +PH_PERF_SEL_SC7_PA1_FIFO_FULL = 879 +PH_PERF_SEL_SC7_PA1_NULL_WE = 880 +PH_PERF_SEL_SC7_PA1_EVENT_WE = 881 +PH_PERF_SEL_SC7_PA1_FPOV_WE = 882 +PH_PERF_SEL_SC7_PA1_LPOV_WE = 883 +PH_PERF_SEL_SC7_PA1_EOP_WE = 884 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD = 885 +PH_PERF_SEL_SC7_PA1_EOPG_WE = 886 +PH_PERF_SEL_SC7_PA1_DEALLOC_4_0_RD = 887 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD = 888 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE = 889 +PH_PERF_SEL_SC7_PA2_FIFO_EMPTY = 890 +PH_PERF_SEL_SC7_PA2_FIFO_FULL = 891 +PH_PERF_SEL_SC7_PA2_NULL_WE = 892 +PH_PERF_SEL_SC7_PA2_EVENT_WE = 893 +PH_PERF_SEL_SC7_PA2_FPOV_WE = 894 +PH_PERF_SEL_SC7_PA2_LPOV_WE = 895 +PH_PERF_SEL_SC7_PA2_EOP_WE = 896 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD = 897 +PH_PERF_SEL_SC7_PA2_EOPG_WE = 898 +PH_PERF_SEL_SC7_PA2_DEALLOC_4_0_RD = 899 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD = 900 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE = 901 +PH_PERF_SEL_SC7_PA3_FIFO_EMPTY = 902 +PH_PERF_SEL_SC7_PA3_FIFO_FULL = 903 +PH_PERF_SEL_SC7_PA3_NULL_WE = 904 +PH_PERF_SEL_SC7_PA3_EVENT_WE = 905 +PH_PERF_SEL_SC7_PA3_FPOV_WE = 906 +PH_PERF_SEL_SC7_PA3_LPOV_WE = 907 +PH_PERF_SEL_SC7_PA3_EOP_WE = 908 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD = 909 +PH_PERF_SEL_SC7_PA3_EOPG_WE = 910 +PH_PERF_SEL_SC7_PA3_DEALLOC_4_0_RD = 911 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD = 912 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE = 913 +PH_PERF_SEL_SC7_PA4_FIFO_EMPTY = 914 +PH_PERF_SEL_SC7_PA4_FIFO_FULL = 915 +PH_PERF_SEL_SC7_PA4_NULL_WE = 916 +PH_PERF_SEL_SC7_PA4_EVENT_WE = 917 +PH_PERF_SEL_SC7_PA4_FPOV_WE = 918 +PH_PERF_SEL_SC7_PA4_LPOV_WE = 919 +PH_PERF_SEL_SC7_PA4_EOP_WE = 920 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD = 921 +PH_PERF_SEL_SC7_PA4_EOPG_WE = 922 +PH_PERF_SEL_SC7_PA4_DEALLOC_4_0_RD = 923 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD = 924 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE = 925 +PH_PERF_SEL_SC7_PA5_FIFO_EMPTY = 926 +PH_PERF_SEL_SC7_PA5_FIFO_FULL = 927 +PH_PERF_SEL_SC7_PA5_NULL_WE = 928 +PH_PERF_SEL_SC7_PA5_EVENT_WE = 929 +PH_PERF_SEL_SC7_PA5_FPOV_WE = 930 +PH_PERF_SEL_SC7_PA5_LPOV_WE = 931 +PH_PERF_SEL_SC7_PA5_EOP_WE = 932 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD = 933 +PH_PERF_SEL_SC7_PA5_EOPG_WE = 934 +PH_PERF_SEL_SC7_PA5_DEALLOC_4_0_RD = 935 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD = 936 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE = 937 +PH_PERF_SEL_SC7_PA6_FIFO_EMPTY = 938 +PH_PERF_SEL_SC7_PA6_FIFO_FULL = 939 +PH_PERF_SEL_SC7_PA6_NULL_WE = 940 +PH_PERF_SEL_SC7_PA6_EVENT_WE = 941 +PH_PERF_SEL_SC7_PA6_FPOV_WE = 942 +PH_PERF_SEL_SC7_PA6_LPOV_WE = 943 +PH_PERF_SEL_SC7_PA6_EOP_WE = 944 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD = 945 +PH_PERF_SEL_SC7_PA6_EOPG_WE = 946 +PH_PERF_SEL_SC7_PA6_DEALLOC_4_0_RD = 947 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD = 948 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE = 949 +PH_PERF_SEL_SC7_PA7_FIFO_EMPTY = 950 +PH_PERF_SEL_SC7_PA7_FIFO_FULL = 951 +PH_PERF_SEL_SC7_PA7_NULL_WE = 952 +PH_PERF_SEL_SC7_PA7_EVENT_WE = 953 +PH_PERF_SEL_SC7_PA7_FPOV_WE = 954 +PH_PERF_SEL_SC7_PA7_LPOV_WE = 955 +PH_PERF_SEL_SC7_PA7_EOP_WE = 956 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD = 957 +PH_PERF_SEL_SC7_PA7_EOPG_WE = 958 +PH_PERF_SEL_SC7_PA7_DEALLOC_4_0_RD = 959 +PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW = 960 +PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW = 961 +PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW = 962 +PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW = 963 +PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW = 964 +PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW = 965 +PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW = 966 +PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW = 967 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE = 968 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE = 969 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE = 970 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE = 971 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE = 972 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE = 973 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE = 974 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE = 975 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 976 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 977 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 978 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 979 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 980 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 981 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 982 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 983 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 984 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 985 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 986 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 987 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 988 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 989 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 990 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 991 +PH_PERF_SC0_FIFO_STATUS_0 = 992 +PH_PERF_SC0_FIFO_STATUS_1 = 993 +PH_PERF_SC0_FIFO_STATUS_2 = 994 +PH_PERF_SC0_FIFO_STATUS_3 = 995 +PH_PERF_SC1_FIFO_STATUS_0 = 996 +PH_PERF_SC1_FIFO_STATUS_1 = 997 +PH_PERF_SC1_FIFO_STATUS_2 = 998 +PH_PERF_SC1_FIFO_STATUS_3 = 999 +PH_PERF_SC2_FIFO_STATUS_0 = 1000 +PH_PERF_SC2_FIFO_STATUS_1 = 1001 +PH_PERF_SC2_FIFO_STATUS_2 = 1002 +PH_PERF_SC2_FIFO_STATUS_3 = 1003 +PH_PERF_SC3_FIFO_STATUS_0 = 1004 +PH_PERF_SC3_FIFO_STATUS_1 = 1005 +PH_PERF_SC3_FIFO_STATUS_2 = 1006 +PH_PERF_SC3_FIFO_STATUS_3 = 1007 +PH_PERF_SC4_FIFO_STATUS_0 = 1008 +PH_PERF_SC4_FIFO_STATUS_1 = 1009 +PH_PERF_SC4_FIFO_STATUS_2 = 1010 +PH_PERF_SC4_FIFO_STATUS_3 = 1011 +PH_PERF_SC5_FIFO_STATUS_0 = 1012 +PH_PERF_SC5_FIFO_STATUS_1 = 1013 +PH_PERF_SC5_FIFO_STATUS_2 = 1014 +PH_PERF_SC5_FIFO_STATUS_3 = 1015 +PH_PERF_SC6_FIFO_STATUS_0 = 1016 +PH_PERF_SC6_FIFO_STATUS_1 = 1017 +PH_PERF_SC6_FIFO_STATUS_2 = 1018 +PH_PERF_SC6_FIFO_STATUS_3 = 1019 +PH_PERF_SC7_FIFO_STATUS_0 = 1020 +PH_PERF_SC7_FIFO_STATUS_1 = 1021 +PH_PERF_SC7_FIFO_STATUS_2 = 1022 +PH_PERF_SC7_FIFO_STATUS_3 = 1023 +PH_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PhSPIstatusMode' +PhSPIstatusMode__enumvalues = { + 0: 'PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT', + 1: 'PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT', + 2: 'PH_SPI_MODE_DISABLED', +} +PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT = 0 +PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT = 1 +PH_SPI_MODE_DISABLED = 2 +PhSPIstatusMode = ctypes.c_uint32 # enum + +# values for enumeration 'RMIPerfSel' +RMIPerfSel__enumvalues = { + 0: 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 1: 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', +} +RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID = 0 +RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID = 1 +RMIPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'GCRPerfSel' +GCRPerfSel__enumvalues = { + 0: 'GCR_PERF_SEL_NONE', + 1: 'GCR_PERF_SEL_SDMA0_ALL_REQ', + 2: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 3: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 4: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 5: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 6: 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 7: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 8: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 9: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 10: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 11: 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 12: 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 13: 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 14: 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', + 15: 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 16: 'GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ', + 17: 'GCR_PERF_SEL_SDMA1_ALL_REQ', + 18: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 19: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 20: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 21: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 22: 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 23: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 24: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 25: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 26: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 27: 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 28: 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 29: 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 30: 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', + 31: 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 32: 'GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ', + 33: 'GCR_PERF_SEL_CPC_ALL_REQ', + 34: 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', + 35: 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 36: 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 37: 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 38: 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 39: 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', + 40: 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 41: 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 42: 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 43: 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 44: 'GCR_PERF_SEL_CPC_METADATA_REQ', + 45: 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', + 46: 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 47: 'GCR_PERF_SEL_CPC_TCP_REQ', + 48: 'GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ', + 49: 'GCR_PERF_SEL_CPG_ALL_REQ', + 50: 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', + 51: 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 52: 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 53: 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 54: 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 55: 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', + 56: 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 57: 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 58: 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 59: 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 60: 'GCR_PERF_SEL_CPG_METADATA_REQ', + 61: 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', + 62: 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 63: 'GCR_PERF_SEL_CPG_TCP_REQ', + 64: 'GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ', + 65: 'GCR_PERF_SEL_CPF_ALL_REQ', + 66: 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', + 67: 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 68: 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 69: 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 70: 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 71: 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', + 72: 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 73: 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 74: 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 75: 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 76: 'GCR_PERF_SEL_CPF_METADATA_REQ', + 77: 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', + 78: 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 79: 'GCR_PERF_SEL_CPF_TCP_REQ', + 80: 'GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ', + 81: 'GCR_PERF_SEL_VIRT_REQ', + 82: 'GCR_PERF_SEL_PHY_REQ', + 83: 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 84: 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 85: 'GCR_PERF_SEL_ALL_REQ', + 86: 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 87: 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 88: 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 89: 'GCR_PERF_SEL_UTCL2_REQ', + 90: 'GCR_PERF_SEL_UTCL2_RET', + 91: 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 92: 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 93: 'GCR_PERF_SEL_UTCL2_FILTERED_RET', + 94: 'GCR_PERF_SEL_RLC_ALL_REQ', + 95: 'GCR_PERF_SEL_RLC_GL2_RANGE_REQ', + 96: 'GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ', + 97: 'GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ', + 98: 'GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ', + 99: 'GCR_PERF_SEL_RLC_GL2_ALL_REQ', + 100: 'GCR_PERF_SEL_RLC_GL1_RANGE_REQ', + 101: 'GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ', + 102: 'GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ', + 103: 'GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ', + 104: 'GCR_PERF_SEL_RLC_GL1_ALL_REQ', + 105: 'GCR_PERF_SEL_RLC_METADATA_REQ', + 106: 'GCR_PERF_SEL_RLC_SQC_DATA_REQ', + 107: 'GCR_PERF_SEL_RLC_SQC_INST_REQ', + 108: 'GCR_PERF_SEL_RLC_TCP_REQ', + 109: 'GCR_PERF_SEL_RLC_TCP_TLB_SHOOTDOWN_REQ', + 110: 'GCR_PERF_SEL_PM_ALL_REQ', + 111: 'GCR_PERF_SEL_PM_GL2_RANGE_REQ', + 112: 'GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ', + 113: 'GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ', + 114: 'GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ', + 115: 'GCR_PERF_SEL_PM_GL2_ALL_REQ', + 116: 'GCR_PERF_SEL_PM_GL1_RANGE_REQ', + 117: 'GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ', + 118: 'GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ', + 119: 'GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ', + 120: 'GCR_PERF_SEL_PM_GL1_ALL_REQ', + 121: 'GCR_PERF_SEL_PM_METADATA_REQ', + 122: 'GCR_PERF_SEL_PM_SQC_DATA_REQ', + 123: 'GCR_PERF_SEL_PM_SQC_INST_REQ', + 124: 'GCR_PERF_SEL_PM_TCP_REQ', + 125: 'GCR_PERF_SEL_PM_TCP_TLB_SHOOTDOWN_REQ', + 126: 'GCR_PERF_SEL_PIO_ALL_REQ', + 127: 'GCR_PERF_SEL_PIO_GL2_RANGE_REQ', + 128: 'GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ', + 129: 'GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ', + 130: 'GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ', + 131: 'GCR_PERF_SEL_PIO_GL2_ALL_REQ', + 132: 'GCR_PERF_SEL_PIO_GL1_RANGE_REQ', + 133: 'GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ', + 134: 'GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ', + 135: 'GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ', + 136: 'GCR_PERF_SEL_PIO_GL1_ALL_REQ', + 137: 'GCR_PERF_SEL_PIO_METADATA_REQ', + 138: 'GCR_PERF_SEL_PIO_SQC_DATA_REQ', + 139: 'GCR_PERF_SEL_PIO_SQC_INST_REQ', + 140: 'GCR_PERF_SEL_PIO_TCP_REQ', + 141: 'GCR_PERF_SEL_PIO_TCP_TLB_SHOOTDOWN_REQ', +} +GCR_PERF_SEL_NONE = 0 +GCR_PERF_SEL_SDMA0_ALL_REQ = 1 +GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ = 2 +GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ = 3 +GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ = 4 +GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ = 5 +GCR_PERF_SEL_SDMA0_GL2_ALL_REQ = 6 +GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ = 7 +GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ = 8 +GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ = 9 +GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ = 10 +GCR_PERF_SEL_SDMA0_GL1_ALL_REQ = 11 +GCR_PERF_SEL_SDMA0_METADATA_REQ = 12 +GCR_PERF_SEL_SDMA0_SQC_DATA_REQ = 13 +GCR_PERF_SEL_SDMA0_SQC_INST_REQ = 14 +GCR_PERF_SEL_SDMA0_TCP_REQ = 15 +GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ = 16 +GCR_PERF_SEL_SDMA1_ALL_REQ = 17 +GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ = 18 +GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ = 19 +GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ = 20 +GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ = 21 +GCR_PERF_SEL_SDMA1_GL2_ALL_REQ = 22 +GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ = 23 +GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ = 24 +GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ = 25 +GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ = 26 +GCR_PERF_SEL_SDMA1_GL1_ALL_REQ = 27 +GCR_PERF_SEL_SDMA1_METADATA_REQ = 28 +GCR_PERF_SEL_SDMA1_SQC_DATA_REQ = 29 +GCR_PERF_SEL_SDMA1_SQC_INST_REQ = 30 +GCR_PERF_SEL_SDMA1_TCP_REQ = 31 +GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ = 32 +GCR_PERF_SEL_CPC_ALL_REQ = 33 +GCR_PERF_SEL_CPC_GL2_RANGE_REQ = 34 +GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ = 35 +GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ = 36 +GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ = 37 +GCR_PERF_SEL_CPC_GL2_ALL_REQ = 38 +GCR_PERF_SEL_CPC_GL1_RANGE_REQ = 39 +GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ = 40 +GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ = 41 +GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ = 42 +GCR_PERF_SEL_CPC_GL1_ALL_REQ = 43 +GCR_PERF_SEL_CPC_METADATA_REQ = 44 +GCR_PERF_SEL_CPC_SQC_DATA_REQ = 45 +GCR_PERF_SEL_CPC_SQC_INST_REQ = 46 +GCR_PERF_SEL_CPC_TCP_REQ = 47 +GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ = 48 +GCR_PERF_SEL_CPG_ALL_REQ = 49 +GCR_PERF_SEL_CPG_GL2_RANGE_REQ = 50 +GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ = 51 +GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ = 52 +GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ = 53 +GCR_PERF_SEL_CPG_GL2_ALL_REQ = 54 +GCR_PERF_SEL_CPG_GL1_RANGE_REQ = 55 +GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ = 56 +GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ = 57 +GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ = 58 +GCR_PERF_SEL_CPG_GL1_ALL_REQ = 59 +GCR_PERF_SEL_CPG_METADATA_REQ = 60 +GCR_PERF_SEL_CPG_SQC_DATA_REQ = 61 +GCR_PERF_SEL_CPG_SQC_INST_REQ = 62 +GCR_PERF_SEL_CPG_TCP_REQ = 63 +GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ = 64 +GCR_PERF_SEL_CPF_ALL_REQ = 65 +GCR_PERF_SEL_CPF_GL2_RANGE_REQ = 66 +GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ = 67 +GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ = 68 +GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ = 69 +GCR_PERF_SEL_CPF_GL2_ALL_REQ = 70 +GCR_PERF_SEL_CPF_GL1_RANGE_REQ = 71 +GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ = 72 +GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ = 73 +GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ = 74 +GCR_PERF_SEL_CPF_GL1_ALL_REQ = 75 +GCR_PERF_SEL_CPF_METADATA_REQ = 76 +GCR_PERF_SEL_CPF_SQC_DATA_REQ = 77 +GCR_PERF_SEL_CPF_SQC_INST_REQ = 78 +GCR_PERF_SEL_CPF_TCP_REQ = 79 +GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ = 80 +GCR_PERF_SEL_VIRT_REQ = 81 +GCR_PERF_SEL_PHY_REQ = 82 +GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ = 83 +GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ = 84 +GCR_PERF_SEL_ALL_REQ = 85 +GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ = 86 +GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ = 87 +GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ = 88 +GCR_PERF_SEL_UTCL2_REQ = 89 +GCR_PERF_SEL_UTCL2_RET = 90 +GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT = 91 +GCR_PERF_SEL_UTCL2_INFLIGHT_REQ = 92 +GCR_PERF_SEL_UTCL2_FILTERED_RET = 93 +GCR_PERF_SEL_RLC_ALL_REQ = 94 +GCR_PERF_SEL_RLC_GL2_RANGE_REQ = 95 +GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ = 96 +GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ = 97 +GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ = 98 +GCR_PERF_SEL_RLC_GL2_ALL_REQ = 99 +GCR_PERF_SEL_RLC_GL1_RANGE_REQ = 100 +GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ = 101 +GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ = 102 +GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ = 103 +GCR_PERF_SEL_RLC_GL1_ALL_REQ = 104 +GCR_PERF_SEL_RLC_METADATA_REQ = 105 +GCR_PERF_SEL_RLC_SQC_DATA_REQ = 106 +GCR_PERF_SEL_RLC_SQC_INST_REQ = 107 +GCR_PERF_SEL_RLC_TCP_REQ = 108 +GCR_PERF_SEL_RLC_TCP_TLB_SHOOTDOWN_REQ = 109 +GCR_PERF_SEL_PM_ALL_REQ = 110 +GCR_PERF_SEL_PM_GL2_RANGE_REQ = 111 +GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ = 112 +GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ = 113 +GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ = 114 +GCR_PERF_SEL_PM_GL2_ALL_REQ = 115 +GCR_PERF_SEL_PM_GL1_RANGE_REQ = 116 +GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ = 117 +GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ = 118 +GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ = 119 +GCR_PERF_SEL_PM_GL1_ALL_REQ = 120 +GCR_PERF_SEL_PM_METADATA_REQ = 121 +GCR_PERF_SEL_PM_SQC_DATA_REQ = 122 +GCR_PERF_SEL_PM_SQC_INST_REQ = 123 +GCR_PERF_SEL_PM_TCP_REQ = 124 +GCR_PERF_SEL_PM_TCP_TLB_SHOOTDOWN_REQ = 125 +GCR_PERF_SEL_PIO_ALL_REQ = 126 +GCR_PERF_SEL_PIO_GL2_RANGE_REQ = 127 +GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ = 128 +GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ = 129 +GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ = 130 +GCR_PERF_SEL_PIO_GL2_ALL_REQ = 131 +GCR_PERF_SEL_PIO_GL1_RANGE_REQ = 132 +GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ = 133 +GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ = 134 +GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ = 135 +GCR_PERF_SEL_PIO_GL1_ALL_REQ = 136 +GCR_PERF_SEL_PIO_METADATA_REQ = 137 +GCR_PERF_SEL_PIO_SQC_DATA_REQ = 138 +GCR_PERF_SEL_PIO_SQC_INST_REQ = 139 +GCR_PERF_SEL_PIO_TCP_REQ = 140 +GCR_PERF_SEL_PIO_TCP_TLB_SHOOTDOWN_REQ = 141 +GCRPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1PerfSel' +UTCL1PerfSel__enumvalues = { + 0: 'UTCL1_PERF_SEL_NONE', + 1: 'UTCL1_PERF_SEL_REQS', + 2: 'UTCL1_PERF_SEL_HITS', + 3: 'UTCL1_PERF_SEL_MISSES', + 4: 'UTCL1_PERF_SEL_MH_RECENT_BUF_HIT', + 5: 'UTCL1_PERF_SEL_MH_DUPLICATE_DETECT', + 6: 'UTCL1_PERF_SEL_UTCL2_REQS', + 7: 'UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY', + 8: 'UTCL1_PERF_SEL_UTCL2_RET_FAULT', + 9: 'UTCL1_PERF_SEL_STALL_UTCL2_CREDITS', + 10: 'UTCL1_PERF_SEL_STALL_MH_FULL', + 11: 'UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM', + 12: 'UTCL1_PERF_SEL_UTCL2_RET_CNT', + 13: 'UTCL1_PERF_SEL_RTNS', + 14: 'UTCL1_PERF_SEL_XLAT_REQ_BUSY', + 15: 'UTCL1_PERF_SEL_BYPASS_REQS', + 16: 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 17: 'UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT', + 18: 'UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT', + 19: 'UTCL1_PERF_SEL_CP_INVREQS', + 20: 'UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS', + 21: 'UTCL1_PERF_SEL_RANGE_INVREQS', + 22: 'UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS', +} +UTCL1_PERF_SEL_NONE = 0 +UTCL1_PERF_SEL_REQS = 1 +UTCL1_PERF_SEL_HITS = 2 +UTCL1_PERF_SEL_MISSES = 3 +UTCL1_PERF_SEL_MH_RECENT_BUF_HIT = 4 +UTCL1_PERF_SEL_MH_DUPLICATE_DETECT = 5 +UTCL1_PERF_SEL_UTCL2_REQS = 6 +UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY = 7 +UTCL1_PERF_SEL_UTCL2_RET_FAULT = 8 +UTCL1_PERF_SEL_STALL_UTCL2_CREDITS = 9 +UTCL1_PERF_SEL_STALL_MH_FULL = 10 +UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM = 11 +UTCL1_PERF_SEL_UTCL2_RET_CNT = 12 +UTCL1_PERF_SEL_RTNS = 13 +UTCL1_PERF_SEL_XLAT_REQ_BUSY = 14 +UTCL1_PERF_SEL_BYPASS_REQS = 15 +UTCL1_PERF_SEL_HIT_INV_FILTER_REQS = 16 +UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT = 17 +UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT = 18 +UTCL1_PERF_SEL_CP_INVREQS = 19 +UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS = 20 +UTCL1_PERF_SEL_RANGE_INVREQS = 21 +UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS = 22 +UTCL1PerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'IH_CLIENT_TYPE' +IH_CLIENT_TYPE__enumvalues = { + 0: 'IH_GFX_VMID_CLIENT', + 1: 'IH_MM_VMID_CLIENT', + 2: 'IH_MULTI_VMID_CLIENT', + 3: 'IH_CLIENT_TYPE_RESERVED', +} +IH_GFX_VMID_CLIENT = 0 +IH_MM_VMID_CLIENT = 1 +IH_MULTI_VMID_CLIENT = 2 +IH_CLIENT_TYPE_RESERVED = 3 +IH_CLIENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'IH_INTERFACE_TYPE' +IH_INTERFACE_TYPE__enumvalues = { + 0: 'IH_LEGACY_INTERFACE', + 1: 'IH_REGISTER_WRITE_INTERFACE', +} +IH_LEGACY_INTERFACE = 0 +IH_REGISTER_WRITE_INTERFACE = 1 +IH_INTERFACE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'IH_PERF_SEL' +IH_PERF_SEL__enumvalues = { + 0: 'IH_PERF_SEL_CYCLE', + 1: 'IH_PERF_SEL_IDLE', + 2: 'IH_PERF_SEL_INPUT_IDLE', + 3: 'IH_PERF_SEL_BUFFER_IDLE', + 4: 'IH_PERF_SEL_RB0_FULL', + 5: 'IH_PERF_SEL_RB0_OVERFLOW', + 6: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 7: 'IH_PERF_SEL_RB0_WPTR_WRAP', + 8: 'IH_PERF_SEL_RB0_RPTR_WRAP', + 9: 'IH_PERF_SEL_MC_WR_IDLE', + 10: 'IH_PERF_SEL_MC_WR_COUNT', + 11: 'IH_PERF_SEL_MC_WR_STALL', + 12: 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 13: 'IH_PERF_SEL_MC_WR_CLEAN_STALL', + 14: 'IH_PERF_SEL_BIF_LINE0_RISING', + 15: 'IH_PERF_SEL_BIF_LINE0_FALLING', + 16: 'IH_PERF_SEL_RB1_FULL', + 17: 'IH_PERF_SEL_RB1_OVERFLOW', + 18: 'IH_PERF_SEL_COOKIE_REC_ERROR', + 19: 'IH_PERF_SEL_RB1_WPTR_WRAP', + 20: 'IH_PERF_SEL_RB1_RPTR_WRAP', + 21: 'IH_PERF_SEL_RB2_FULL', + 22: 'IH_PERF_SEL_RB2_OVERFLOW', + 23: 'IH_PERF_SEL_CLIENT_CREDIT_ERROR', + 24: 'IH_PERF_SEL_RB2_WPTR_WRAP', + 25: 'IH_PERF_SEL_RB2_RPTR_WRAP', + 26: 'IH_PERF_SEL_STORM_CLIENT_INT_DROP', + 27: 'IH_PERF_SEL_SELF_IV_VALID', + 28: 'IH_PERF_SEL_BUFFER_FIFO_FULL', + 29: 'IH_PERF_SEL_RB0_FULL_VF0', + 30: 'IH_PERF_SEL_RB0_FULL_VF1', + 31: 'IH_PERF_SEL_RB0_FULL_VF2', + 32: 'IH_PERF_SEL_RB0_FULL_VF3', + 33: 'IH_PERF_SEL_RB0_FULL_VF4', + 34: 'IH_PERF_SEL_RB0_FULL_VF5', + 35: 'IH_PERF_SEL_RB0_FULL_VF6', + 36: 'IH_PERF_SEL_RB0_FULL_VF7', + 37: 'IH_PERF_SEL_RB0_FULL_VF8', + 38: 'IH_PERF_SEL_RB0_FULL_VF9', + 39: 'IH_PERF_SEL_RB0_FULL_VF10', + 40: 'IH_PERF_SEL_RB0_FULL_VF11', + 41: 'IH_PERF_SEL_RB0_FULL_VF12', + 42: 'IH_PERF_SEL_RB0_FULL_VF13', + 43: 'IH_PERF_SEL_RB0_FULL_VF14', + 44: 'IH_PERF_SEL_RB0_FULL_VF15', + 45: 'IH_PERF_SEL_RB0_OVERFLOW_VF0', + 46: 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 47: 'IH_PERF_SEL_RB0_OVERFLOW_VF2', + 48: 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 49: 'IH_PERF_SEL_RB0_OVERFLOW_VF4', + 50: 'IH_PERF_SEL_RB0_OVERFLOW_VF5', + 51: 'IH_PERF_SEL_RB0_OVERFLOW_VF6', + 52: 'IH_PERF_SEL_RB0_OVERFLOW_VF7', + 53: 'IH_PERF_SEL_RB0_OVERFLOW_VF8', + 54: 'IH_PERF_SEL_RB0_OVERFLOW_VF9', + 55: 'IH_PERF_SEL_RB0_OVERFLOW_VF10', + 56: 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 57: 'IH_PERF_SEL_RB0_OVERFLOW_VF12', + 58: 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 59: 'IH_PERF_SEL_RB0_OVERFLOW_VF14', + 60: 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 61: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 62: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 63: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 64: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 65: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 66: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 67: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 68: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 69: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 70: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', + 71: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 72: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 73: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 74: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 75: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 76: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 77: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', + 78: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 79: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 80: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', + 81: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 82: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', + 83: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 84: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', + 85: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 86: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', + 87: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 88: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 89: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 90: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 91: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 92: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', + 93: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', + 94: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', + 95: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 96: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', + 97: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 98: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', + 99: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 100: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', + 101: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 102: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', + 103: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 104: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 105: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 106: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 107: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 108: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', + 109: 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 110: 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 111: 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 112: 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 113: 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 114: 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 115: 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 116: 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 117: 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 118: 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', + 119: 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 120: 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 121: 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 122: 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 123: 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 124: 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 125: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 126: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 127: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 128: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 129: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 130: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 131: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 132: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 133: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 134: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 135: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 136: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 137: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 138: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 139: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 140: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 141: 'IH_PERF_SEL_CLIENT0_INT', + 142: 'IH_PERF_SEL_CLIENT1_INT', + 143: 'IH_PERF_SEL_CLIENT2_INT', + 144: 'IH_PERF_SEL_CLIENT3_INT', + 145: 'IH_PERF_SEL_CLIENT4_INT', + 146: 'IH_PERF_SEL_CLIENT5_INT', + 147: 'IH_PERF_SEL_CLIENT6_INT', + 148: 'IH_PERF_SEL_CLIENT7_INT', + 149: 'IH_PERF_SEL_CLIENT8_INT', + 150: 'IH_PERF_SEL_CLIENT9_INT', + 151: 'IH_PERF_SEL_CLIENT10_INT', + 152: 'IH_PERF_SEL_CLIENT11_INT', + 153: 'IH_PERF_SEL_CLIENT12_INT', + 154: 'IH_PERF_SEL_CLIENT13_INT', + 155: 'IH_PERF_SEL_CLIENT14_INT', + 156: 'IH_PERF_SEL_CLIENT15_INT', + 157: 'IH_PERF_SEL_CLIENT16_INT', + 158: 'IH_PERF_SEL_CLIENT17_INT', + 159: 'IH_PERF_SEL_CLIENT18_INT', + 160: 'IH_PERF_SEL_CLIENT19_INT', + 161: 'IH_PERF_SEL_CLIENT20_INT', + 162: 'IH_PERF_SEL_CLIENT21_INT', + 163: 'IH_PERF_SEL_CLIENT22_INT', + 164: 'IH_PERF_SEL_CLIENT23_INT', + 165: 'IH_PERF_SEL_CLIENT24_INT', + 166: 'IH_PERF_SEL_CLIENT25_INT', + 167: 'IH_PERF_SEL_CLIENT26_INT', + 168: 'IH_PERF_SEL_CLIENT27_INT', + 169: 'IH_PERF_SEL_CLIENT28_INT', + 170: 'IH_PERF_SEL_CLIENT29_INT', + 171: 'IH_PERF_SEL_CLIENT30_INT', + 172: 'IH_PERF_SEL_CLIENT31_INT', + 173: 'IH_PERF_SEL_RB1_FULL_VF0', + 174: 'IH_PERF_SEL_RB1_FULL_VF1', + 175: 'IH_PERF_SEL_RB1_FULL_VF2', + 176: 'IH_PERF_SEL_RB1_FULL_VF3', + 177: 'IH_PERF_SEL_RB1_FULL_VF4', + 178: 'IH_PERF_SEL_RB1_FULL_VF5', + 179: 'IH_PERF_SEL_RB1_FULL_VF6', + 180: 'IH_PERF_SEL_RB1_FULL_VF7', + 181: 'IH_PERF_SEL_RB1_FULL_VF8', + 182: 'IH_PERF_SEL_RB1_FULL_VF9', + 183: 'IH_PERF_SEL_RB1_FULL_VF10', + 184: 'IH_PERF_SEL_RB1_FULL_VF11', + 185: 'IH_PERF_SEL_RB1_FULL_VF12', + 186: 'IH_PERF_SEL_RB1_FULL_VF13', + 187: 'IH_PERF_SEL_RB1_FULL_VF14', + 188: 'IH_PERF_SEL_RB1_FULL_VF15', + 189: 'IH_PERF_SEL_RB1_OVERFLOW_VF0', + 190: 'IH_PERF_SEL_RB1_OVERFLOW_VF1', + 191: 'IH_PERF_SEL_RB1_OVERFLOW_VF2', + 192: 'IH_PERF_SEL_RB1_OVERFLOW_VF3', + 193: 'IH_PERF_SEL_RB1_OVERFLOW_VF4', + 194: 'IH_PERF_SEL_RB1_OVERFLOW_VF5', + 195: 'IH_PERF_SEL_RB1_OVERFLOW_VF6', + 196: 'IH_PERF_SEL_RB1_OVERFLOW_VF7', + 197: 'IH_PERF_SEL_RB1_OVERFLOW_VF8', + 198: 'IH_PERF_SEL_RB1_OVERFLOW_VF9', + 199: 'IH_PERF_SEL_RB1_OVERFLOW_VF10', + 200: 'IH_PERF_SEL_RB1_OVERFLOW_VF11', + 201: 'IH_PERF_SEL_RB1_OVERFLOW_VF12', + 202: 'IH_PERF_SEL_RB1_OVERFLOW_VF13', + 203: 'IH_PERF_SEL_RB1_OVERFLOW_VF14', + 204: 'IH_PERF_SEL_RB1_OVERFLOW_VF15', + 205: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', + 206: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 207: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 208: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', + 209: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 210: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', + 211: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 212: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', + 213: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 214: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', + 215: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 216: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 217: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 218: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 219: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 220: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', + 221: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', + 222: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', + 223: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 224: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', + 225: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 226: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', + 227: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 228: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', + 229: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 230: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', + 231: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 232: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 233: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 234: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 235: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 236: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', + 237: 'IH_PERF_SEL_RB2_FULL_VF0', + 238: 'IH_PERF_SEL_RB2_FULL_VF1', + 239: 'IH_PERF_SEL_RB2_FULL_VF2', + 240: 'IH_PERF_SEL_RB2_FULL_VF3', + 241: 'IH_PERF_SEL_RB2_FULL_VF4', + 242: 'IH_PERF_SEL_RB2_FULL_VF5', + 243: 'IH_PERF_SEL_RB2_FULL_VF6', + 244: 'IH_PERF_SEL_RB2_FULL_VF7', + 245: 'IH_PERF_SEL_RB2_FULL_VF8', + 246: 'IH_PERF_SEL_RB2_FULL_VF9', + 247: 'IH_PERF_SEL_RB2_FULL_VF10', + 248: 'IH_PERF_SEL_RB2_FULL_VF11', + 249: 'IH_PERF_SEL_RB2_FULL_VF12', + 250: 'IH_PERF_SEL_RB2_FULL_VF13', + 251: 'IH_PERF_SEL_RB2_FULL_VF14', + 252: 'IH_PERF_SEL_RB2_FULL_VF15', + 253: 'IH_PERF_SEL_RB2_OVERFLOW_VF0', + 254: 'IH_PERF_SEL_RB2_OVERFLOW_VF1', + 255: 'IH_PERF_SEL_RB2_OVERFLOW_VF2', + 256: 'IH_PERF_SEL_RB2_OVERFLOW_VF3', + 257: 'IH_PERF_SEL_RB2_OVERFLOW_VF4', + 258: 'IH_PERF_SEL_RB2_OVERFLOW_VF5', + 259: 'IH_PERF_SEL_RB2_OVERFLOW_VF6', + 260: 'IH_PERF_SEL_RB2_OVERFLOW_VF7', + 261: 'IH_PERF_SEL_RB2_OVERFLOW_VF8', + 262: 'IH_PERF_SEL_RB2_OVERFLOW_VF9', + 263: 'IH_PERF_SEL_RB2_OVERFLOW_VF10', + 264: 'IH_PERF_SEL_RB2_OVERFLOW_VF11', + 265: 'IH_PERF_SEL_RB2_OVERFLOW_VF12', + 266: 'IH_PERF_SEL_RB2_OVERFLOW_VF13', + 267: 'IH_PERF_SEL_RB2_OVERFLOW_VF14', + 268: 'IH_PERF_SEL_RB2_OVERFLOW_VF15', + 269: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', + 270: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 271: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 272: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', + 273: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 274: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', + 275: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 276: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', + 277: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 278: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', + 279: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 280: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 281: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 282: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 283: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 284: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', + 285: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', + 286: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', + 287: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 288: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', + 289: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 290: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', + 291: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 292: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', + 293: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 294: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', + 295: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 296: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 297: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 298: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 299: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 300: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', + 301: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP', + 302: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0', + 303: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1', + 304: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2', + 305: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3', + 306: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4', + 307: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5', + 308: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6', + 309: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7', + 310: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8', + 311: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9', + 312: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10', + 313: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11', + 314: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12', + 315: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13', + 316: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14', + 317: 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15', + 318: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP', + 319: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0', + 320: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1', + 321: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2', + 322: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3', + 323: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4', + 324: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5', + 325: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6', + 326: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7', + 327: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8', + 328: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9', + 329: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10', + 330: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11', + 331: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12', + 332: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13', + 333: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14', + 334: 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15', + 335: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP', + 336: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0', + 337: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1', + 338: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2', + 339: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3', + 340: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4', + 341: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5', + 342: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6', + 343: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7', + 344: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8', + 345: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9', + 346: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10', + 347: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11', + 348: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12', + 349: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13', + 350: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14', + 351: 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15', + 352: 'IH_PERF_SEL_RB0_LOAD_RPTR', + 353: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF0', + 354: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF1', + 355: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF2', + 356: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF3', + 357: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF4', + 358: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF5', + 359: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF6', + 360: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF7', + 361: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF8', + 362: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF9', + 363: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF10', + 364: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF11', + 365: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF12', + 366: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF13', + 367: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF14', + 368: 'IH_PERF_SEL_RB0_LOAD_RPTR_VF15', + 369: 'IH_PERF_SEL_RB1_LOAD_RPTR', + 370: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF0', + 371: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF1', + 372: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF2', + 373: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF3', + 374: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF4', + 375: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF5', + 376: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF6', + 377: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF7', + 378: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF8', + 379: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF9', + 380: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF10', + 381: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF11', + 382: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF12', + 383: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF13', + 384: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF14', + 385: 'IH_PERF_SEL_RB1_LOAD_RPTR_VF15', + 386: 'IH_PERF_SEL_RB2_LOAD_RPTR', + 387: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF0', + 388: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF1', + 389: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF2', + 390: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF3', + 391: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF4', + 392: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF5', + 393: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF6', + 394: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF7', + 395: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF8', + 396: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF9', + 397: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF10', + 398: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF11', + 399: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF12', + 400: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF13', + 401: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF14', + 402: 'IH_PERF_SEL_RB2_LOAD_RPTR_VF15', +} +IH_PERF_SEL_CYCLE = 0 +IH_PERF_SEL_IDLE = 1 +IH_PERF_SEL_INPUT_IDLE = 2 +IH_PERF_SEL_BUFFER_IDLE = 3 +IH_PERF_SEL_RB0_FULL = 4 +IH_PERF_SEL_RB0_OVERFLOW = 5 +IH_PERF_SEL_RB0_WPTR_WRITEBACK = 6 +IH_PERF_SEL_RB0_WPTR_WRAP = 7 +IH_PERF_SEL_RB0_RPTR_WRAP = 8 +IH_PERF_SEL_MC_WR_IDLE = 9 +IH_PERF_SEL_MC_WR_COUNT = 10 +IH_PERF_SEL_MC_WR_STALL = 11 +IH_PERF_SEL_MC_WR_CLEAN_PENDING = 12 +IH_PERF_SEL_MC_WR_CLEAN_STALL = 13 +IH_PERF_SEL_BIF_LINE0_RISING = 14 +IH_PERF_SEL_BIF_LINE0_FALLING = 15 +IH_PERF_SEL_RB1_FULL = 16 +IH_PERF_SEL_RB1_OVERFLOW = 17 +IH_PERF_SEL_COOKIE_REC_ERROR = 18 +IH_PERF_SEL_RB1_WPTR_WRAP = 19 +IH_PERF_SEL_RB1_RPTR_WRAP = 20 +IH_PERF_SEL_RB2_FULL = 21 +IH_PERF_SEL_RB2_OVERFLOW = 22 +IH_PERF_SEL_CLIENT_CREDIT_ERROR = 23 +IH_PERF_SEL_RB2_WPTR_WRAP = 24 +IH_PERF_SEL_RB2_RPTR_WRAP = 25 +IH_PERF_SEL_STORM_CLIENT_INT_DROP = 26 +IH_PERF_SEL_SELF_IV_VALID = 27 +IH_PERF_SEL_BUFFER_FIFO_FULL = 28 +IH_PERF_SEL_RB0_FULL_VF0 = 29 +IH_PERF_SEL_RB0_FULL_VF1 = 30 +IH_PERF_SEL_RB0_FULL_VF2 = 31 +IH_PERF_SEL_RB0_FULL_VF3 = 32 +IH_PERF_SEL_RB0_FULL_VF4 = 33 +IH_PERF_SEL_RB0_FULL_VF5 = 34 +IH_PERF_SEL_RB0_FULL_VF6 = 35 +IH_PERF_SEL_RB0_FULL_VF7 = 36 +IH_PERF_SEL_RB0_FULL_VF8 = 37 +IH_PERF_SEL_RB0_FULL_VF9 = 38 +IH_PERF_SEL_RB0_FULL_VF10 = 39 +IH_PERF_SEL_RB0_FULL_VF11 = 40 +IH_PERF_SEL_RB0_FULL_VF12 = 41 +IH_PERF_SEL_RB0_FULL_VF13 = 42 +IH_PERF_SEL_RB0_FULL_VF14 = 43 +IH_PERF_SEL_RB0_FULL_VF15 = 44 +IH_PERF_SEL_RB0_OVERFLOW_VF0 = 45 +IH_PERF_SEL_RB0_OVERFLOW_VF1 = 46 +IH_PERF_SEL_RB0_OVERFLOW_VF2 = 47 +IH_PERF_SEL_RB0_OVERFLOW_VF3 = 48 +IH_PERF_SEL_RB0_OVERFLOW_VF4 = 49 +IH_PERF_SEL_RB0_OVERFLOW_VF5 = 50 +IH_PERF_SEL_RB0_OVERFLOW_VF6 = 51 +IH_PERF_SEL_RB0_OVERFLOW_VF7 = 52 +IH_PERF_SEL_RB0_OVERFLOW_VF8 = 53 +IH_PERF_SEL_RB0_OVERFLOW_VF9 = 54 +IH_PERF_SEL_RB0_OVERFLOW_VF10 = 55 +IH_PERF_SEL_RB0_OVERFLOW_VF11 = 56 +IH_PERF_SEL_RB0_OVERFLOW_VF12 = 57 +IH_PERF_SEL_RB0_OVERFLOW_VF13 = 58 +IH_PERF_SEL_RB0_OVERFLOW_VF14 = 59 +IH_PERF_SEL_RB0_OVERFLOW_VF15 = 60 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0 = 61 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1 = 62 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2 = 63 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3 = 64 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4 = 65 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5 = 66 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6 = 67 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7 = 68 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8 = 69 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9 = 70 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10 = 71 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11 = 72 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12 = 73 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13 = 74 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14 = 75 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15 = 76 +IH_PERF_SEL_RB0_WPTR_WRAP_VF0 = 77 +IH_PERF_SEL_RB0_WPTR_WRAP_VF1 = 78 +IH_PERF_SEL_RB0_WPTR_WRAP_VF2 = 79 +IH_PERF_SEL_RB0_WPTR_WRAP_VF3 = 80 +IH_PERF_SEL_RB0_WPTR_WRAP_VF4 = 81 +IH_PERF_SEL_RB0_WPTR_WRAP_VF5 = 82 +IH_PERF_SEL_RB0_WPTR_WRAP_VF6 = 83 +IH_PERF_SEL_RB0_WPTR_WRAP_VF7 = 84 +IH_PERF_SEL_RB0_WPTR_WRAP_VF8 = 85 +IH_PERF_SEL_RB0_WPTR_WRAP_VF9 = 86 +IH_PERF_SEL_RB0_WPTR_WRAP_VF10 = 87 +IH_PERF_SEL_RB0_WPTR_WRAP_VF11 = 88 +IH_PERF_SEL_RB0_WPTR_WRAP_VF12 = 89 +IH_PERF_SEL_RB0_WPTR_WRAP_VF13 = 90 +IH_PERF_SEL_RB0_WPTR_WRAP_VF14 = 91 +IH_PERF_SEL_RB0_WPTR_WRAP_VF15 = 92 +IH_PERF_SEL_RB0_RPTR_WRAP_VF0 = 93 +IH_PERF_SEL_RB0_RPTR_WRAP_VF1 = 94 +IH_PERF_SEL_RB0_RPTR_WRAP_VF2 = 95 +IH_PERF_SEL_RB0_RPTR_WRAP_VF3 = 96 +IH_PERF_SEL_RB0_RPTR_WRAP_VF4 = 97 +IH_PERF_SEL_RB0_RPTR_WRAP_VF5 = 98 +IH_PERF_SEL_RB0_RPTR_WRAP_VF6 = 99 +IH_PERF_SEL_RB0_RPTR_WRAP_VF7 = 100 +IH_PERF_SEL_RB0_RPTR_WRAP_VF8 = 101 +IH_PERF_SEL_RB0_RPTR_WRAP_VF9 = 102 +IH_PERF_SEL_RB0_RPTR_WRAP_VF10 = 103 +IH_PERF_SEL_RB0_RPTR_WRAP_VF11 = 104 +IH_PERF_SEL_RB0_RPTR_WRAP_VF12 = 105 +IH_PERF_SEL_RB0_RPTR_WRAP_VF13 = 106 +IH_PERF_SEL_RB0_RPTR_WRAP_VF14 = 107 +IH_PERF_SEL_RB0_RPTR_WRAP_VF15 = 108 +IH_PERF_SEL_BIF_LINE0_RISING_VF0 = 109 +IH_PERF_SEL_BIF_LINE0_RISING_VF1 = 110 +IH_PERF_SEL_BIF_LINE0_RISING_VF2 = 111 +IH_PERF_SEL_BIF_LINE0_RISING_VF3 = 112 +IH_PERF_SEL_BIF_LINE0_RISING_VF4 = 113 +IH_PERF_SEL_BIF_LINE0_RISING_VF5 = 114 +IH_PERF_SEL_BIF_LINE0_RISING_VF6 = 115 +IH_PERF_SEL_BIF_LINE0_RISING_VF7 = 116 +IH_PERF_SEL_BIF_LINE0_RISING_VF8 = 117 +IH_PERF_SEL_BIF_LINE0_RISING_VF9 = 118 +IH_PERF_SEL_BIF_LINE0_RISING_VF10 = 119 +IH_PERF_SEL_BIF_LINE0_RISING_VF11 = 120 +IH_PERF_SEL_BIF_LINE0_RISING_VF12 = 121 +IH_PERF_SEL_BIF_LINE0_RISING_VF13 = 122 +IH_PERF_SEL_BIF_LINE0_RISING_VF14 = 123 +IH_PERF_SEL_BIF_LINE0_RISING_VF15 = 124 +IH_PERF_SEL_BIF_LINE0_FALLING_VF0 = 125 +IH_PERF_SEL_BIF_LINE0_FALLING_VF1 = 126 +IH_PERF_SEL_BIF_LINE0_FALLING_VF2 = 127 +IH_PERF_SEL_BIF_LINE0_FALLING_VF3 = 128 +IH_PERF_SEL_BIF_LINE0_FALLING_VF4 = 129 +IH_PERF_SEL_BIF_LINE0_FALLING_VF5 = 130 +IH_PERF_SEL_BIF_LINE0_FALLING_VF6 = 131 +IH_PERF_SEL_BIF_LINE0_FALLING_VF7 = 132 +IH_PERF_SEL_BIF_LINE0_FALLING_VF8 = 133 +IH_PERF_SEL_BIF_LINE0_FALLING_VF9 = 134 +IH_PERF_SEL_BIF_LINE0_FALLING_VF10 = 135 +IH_PERF_SEL_BIF_LINE0_FALLING_VF11 = 136 +IH_PERF_SEL_BIF_LINE0_FALLING_VF12 = 137 +IH_PERF_SEL_BIF_LINE0_FALLING_VF13 = 138 +IH_PERF_SEL_BIF_LINE0_FALLING_VF14 = 139 +IH_PERF_SEL_BIF_LINE0_FALLING_VF15 = 140 +IH_PERF_SEL_CLIENT0_INT = 141 +IH_PERF_SEL_CLIENT1_INT = 142 +IH_PERF_SEL_CLIENT2_INT = 143 +IH_PERF_SEL_CLIENT3_INT = 144 +IH_PERF_SEL_CLIENT4_INT = 145 +IH_PERF_SEL_CLIENT5_INT = 146 +IH_PERF_SEL_CLIENT6_INT = 147 +IH_PERF_SEL_CLIENT7_INT = 148 +IH_PERF_SEL_CLIENT8_INT = 149 +IH_PERF_SEL_CLIENT9_INT = 150 +IH_PERF_SEL_CLIENT10_INT = 151 +IH_PERF_SEL_CLIENT11_INT = 152 +IH_PERF_SEL_CLIENT12_INT = 153 +IH_PERF_SEL_CLIENT13_INT = 154 +IH_PERF_SEL_CLIENT14_INT = 155 +IH_PERF_SEL_CLIENT15_INT = 156 +IH_PERF_SEL_CLIENT16_INT = 157 +IH_PERF_SEL_CLIENT17_INT = 158 +IH_PERF_SEL_CLIENT18_INT = 159 +IH_PERF_SEL_CLIENT19_INT = 160 +IH_PERF_SEL_CLIENT20_INT = 161 +IH_PERF_SEL_CLIENT21_INT = 162 +IH_PERF_SEL_CLIENT22_INT = 163 +IH_PERF_SEL_CLIENT23_INT = 164 +IH_PERF_SEL_CLIENT24_INT = 165 +IH_PERF_SEL_CLIENT25_INT = 166 +IH_PERF_SEL_CLIENT26_INT = 167 +IH_PERF_SEL_CLIENT27_INT = 168 +IH_PERF_SEL_CLIENT28_INT = 169 +IH_PERF_SEL_CLIENT29_INT = 170 +IH_PERF_SEL_CLIENT30_INT = 171 +IH_PERF_SEL_CLIENT31_INT = 172 +IH_PERF_SEL_RB1_FULL_VF0 = 173 +IH_PERF_SEL_RB1_FULL_VF1 = 174 +IH_PERF_SEL_RB1_FULL_VF2 = 175 +IH_PERF_SEL_RB1_FULL_VF3 = 176 +IH_PERF_SEL_RB1_FULL_VF4 = 177 +IH_PERF_SEL_RB1_FULL_VF5 = 178 +IH_PERF_SEL_RB1_FULL_VF6 = 179 +IH_PERF_SEL_RB1_FULL_VF7 = 180 +IH_PERF_SEL_RB1_FULL_VF8 = 181 +IH_PERF_SEL_RB1_FULL_VF9 = 182 +IH_PERF_SEL_RB1_FULL_VF10 = 183 +IH_PERF_SEL_RB1_FULL_VF11 = 184 +IH_PERF_SEL_RB1_FULL_VF12 = 185 +IH_PERF_SEL_RB1_FULL_VF13 = 186 +IH_PERF_SEL_RB1_FULL_VF14 = 187 +IH_PERF_SEL_RB1_FULL_VF15 = 188 +IH_PERF_SEL_RB1_OVERFLOW_VF0 = 189 +IH_PERF_SEL_RB1_OVERFLOW_VF1 = 190 +IH_PERF_SEL_RB1_OVERFLOW_VF2 = 191 +IH_PERF_SEL_RB1_OVERFLOW_VF3 = 192 +IH_PERF_SEL_RB1_OVERFLOW_VF4 = 193 +IH_PERF_SEL_RB1_OVERFLOW_VF5 = 194 +IH_PERF_SEL_RB1_OVERFLOW_VF6 = 195 +IH_PERF_SEL_RB1_OVERFLOW_VF7 = 196 +IH_PERF_SEL_RB1_OVERFLOW_VF8 = 197 +IH_PERF_SEL_RB1_OVERFLOW_VF9 = 198 +IH_PERF_SEL_RB1_OVERFLOW_VF10 = 199 +IH_PERF_SEL_RB1_OVERFLOW_VF11 = 200 +IH_PERF_SEL_RB1_OVERFLOW_VF12 = 201 +IH_PERF_SEL_RB1_OVERFLOW_VF13 = 202 +IH_PERF_SEL_RB1_OVERFLOW_VF14 = 203 +IH_PERF_SEL_RB1_OVERFLOW_VF15 = 204 +IH_PERF_SEL_RB1_WPTR_WRAP_VF0 = 205 +IH_PERF_SEL_RB1_WPTR_WRAP_VF1 = 206 +IH_PERF_SEL_RB1_WPTR_WRAP_VF2 = 207 +IH_PERF_SEL_RB1_WPTR_WRAP_VF3 = 208 +IH_PERF_SEL_RB1_WPTR_WRAP_VF4 = 209 +IH_PERF_SEL_RB1_WPTR_WRAP_VF5 = 210 +IH_PERF_SEL_RB1_WPTR_WRAP_VF6 = 211 +IH_PERF_SEL_RB1_WPTR_WRAP_VF7 = 212 +IH_PERF_SEL_RB1_WPTR_WRAP_VF8 = 213 +IH_PERF_SEL_RB1_WPTR_WRAP_VF9 = 214 +IH_PERF_SEL_RB1_WPTR_WRAP_VF10 = 215 +IH_PERF_SEL_RB1_WPTR_WRAP_VF11 = 216 +IH_PERF_SEL_RB1_WPTR_WRAP_VF12 = 217 +IH_PERF_SEL_RB1_WPTR_WRAP_VF13 = 218 +IH_PERF_SEL_RB1_WPTR_WRAP_VF14 = 219 +IH_PERF_SEL_RB1_WPTR_WRAP_VF15 = 220 +IH_PERF_SEL_RB1_RPTR_WRAP_VF0 = 221 +IH_PERF_SEL_RB1_RPTR_WRAP_VF1 = 222 +IH_PERF_SEL_RB1_RPTR_WRAP_VF2 = 223 +IH_PERF_SEL_RB1_RPTR_WRAP_VF3 = 224 +IH_PERF_SEL_RB1_RPTR_WRAP_VF4 = 225 +IH_PERF_SEL_RB1_RPTR_WRAP_VF5 = 226 +IH_PERF_SEL_RB1_RPTR_WRAP_VF6 = 227 +IH_PERF_SEL_RB1_RPTR_WRAP_VF7 = 228 +IH_PERF_SEL_RB1_RPTR_WRAP_VF8 = 229 +IH_PERF_SEL_RB1_RPTR_WRAP_VF9 = 230 +IH_PERF_SEL_RB1_RPTR_WRAP_VF10 = 231 +IH_PERF_SEL_RB1_RPTR_WRAP_VF11 = 232 +IH_PERF_SEL_RB1_RPTR_WRAP_VF12 = 233 +IH_PERF_SEL_RB1_RPTR_WRAP_VF13 = 234 +IH_PERF_SEL_RB1_RPTR_WRAP_VF14 = 235 +IH_PERF_SEL_RB1_RPTR_WRAP_VF15 = 236 +IH_PERF_SEL_RB2_FULL_VF0 = 237 +IH_PERF_SEL_RB2_FULL_VF1 = 238 +IH_PERF_SEL_RB2_FULL_VF2 = 239 +IH_PERF_SEL_RB2_FULL_VF3 = 240 +IH_PERF_SEL_RB2_FULL_VF4 = 241 +IH_PERF_SEL_RB2_FULL_VF5 = 242 +IH_PERF_SEL_RB2_FULL_VF6 = 243 +IH_PERF_SEL_RB2_FULL_VF7 = 244 +IH_PERF_SEL_RB2_FULL_VF8 = 245 +IH_PERF_SEL_RB2_FULL_VF9 = 246 +IH_PERF_SEL_RB2_FULL_VF10 = 247 +IH_PERF_SEL_RB2_FULL_VF11 = 248 +IH_PERF_SEL_RB2_FULL_VF12 = 249 +IH_PERF_SEL_RB2_FULL_VF13 = 250 +IH_PERF_SEL_RB2_FULL_VF14 = 251 +IH_PERF_SEL_RB2_FULL_VF15 = 252 +IH_PERF_SEL_RB2_OVERFLOW_VF0 = 253 +IH_PERF_SEL_RB2_OVERFLOW_VF1 = 254 +IH_PERF_SEL_RB2_OVERFLOW_VF2 = 255 +IH_PERF_SEL_RB2_OVERFLOW_VF3 = 256 +IH_PERF_SEL_RB2_OVERFLOW_VF4 = 257 +IH_PERF_SEL_RB2_OVERFLOW_VF5 = 258 +IH_PERF_SEL_RB2_OVERFLOW_VF6 = 259 +IH_PERF_SEL_RB2_OVERFLOW_VF7 = 260 +IH_PERF_SEL_RB2_OVERFLOW_VF8 = 261 +IH_PERF_SEL_RB2_OVERFLOW_VF9 = 262 +IH_PERF_SEL_RB2_OVERFLOW_VF10 = 263 +IH_PERF_SEL_RB2_OVERFLOW_VF11 = 264 +IH_PERF_SEL_RB2_OVERFLOW_VF12 = 265 +IH_PERF_SEL_RB2_OVERFLOW_VF13 = 266 +IH_PERF_SEL_RB2_OVERFLOW_VF14 = 267 +IH_PERF_SEL_RB2_OVERFLOW_VF15 = 268 +IH_PERF_SEL_RB2_WPTR_WRAP_VF0 = 269 +IH_PERF_SEL_RB2_WPTR_WRAP_VF1 = 270 +IH_PERF_SEL_RB2_WPTR_WRAP_VF2 = 271 +IH_PERF_SEL_RB2_WPTR_WRAP_VF3 = 272 +IH_PERF_SEL_RB2_WPTR_WRAP_VF4 = 273 +IH_PERF_SEL_RB2_WPTR_WRAP_VF5 = 274 +IH_PERF_SEL_RB2_WPTR_WRAP_VF6 = 275 +IH_PERF_SEL_RB2_WPTR_WRAP_VF7 = 276 +IH_PERF_SEL_RB2_WPTR_WRAP_VF8 = 277 +IH_PERF_SEL_RB2_WPTR_WRAP_VF9 = 278 +IH_PERF_SEL_RB2_WPTR_WRAP_VF10 = 279 +IH_PERF_SEL_RB2_WPTR_WRAP_VF11 = 280 +IH_PERF_SEL_RB2_WPTR_WRAP_VF12 = 281 +IH_PERF_SEL_RB2_WPTR_WRAP_VF13 = 282 +IH_PERF_SEL_RB2_WPTR_WRAP_VF14 = 283 +IH_PERF_SEL_RB2_WPTR_WRAP_VF15 = 284 +IH_PERF_SEL_RB2_RPTR_WRAP_VF0 = 285 +IH_PERF_SEL_RB2_RPTR_WRAP_VF1 = 286 +IH_PERF_SEL_RB2_RPTR_WRAP_VF2 = 287 +IH_PERF_SEL_RB2_RPTR_WRAP_VF3 = 288 +IH_PERF_SEL_RB2_RPTR_WRAP_VF4 = 289 +IH_PERF_SEL_RB2_RPTR_WRAP_VF5 = 290 +IH_PERF_SEL_RB2_RPTR_WRAP_VF6 = 291 +IH_PERF_SEL_RB2_RPTR_WRAP_VF7 = 292 +IH_PERF_SEL_RB2_RPTR_WRAP_VF8 = 293 +IH_PERF_SEL_RB2_RPTR_WRAP_VF9 = 294 +IH_PERF_SEL_RB2_RPTR_WRAP_VF10 = 295 +IH_PERF_SEL_RB2_RPTR_WRAP_VF11 = 296 +IH_PERF_SEL_RB2_RPTR_WRAP_VF12 = 297 +IH_PERF_SEL_RB2_RPTR_WRAP_VF13 = 298 +IH_PERF_SEL_RB2_RPTR_WRAP_VF14 = 299 +IH_PERF_SEL_RB2_RPTR_WRAP_VF15 = 300 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP = 301 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0 = 302 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1 = 303 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2 = 304 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3 = 305 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4 = 306 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5 = 307 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6 = 308 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7 = 309 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8 = 310 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9 = 311 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10 = 312 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11 = 313 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12 = 314 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13 = 315 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14 = 316 +IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15 = 317 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP = 318 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0 = 319 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1 = 320 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2 = 321 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3 = 322 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4 = 323 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5 = 324 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6 = 325 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7 = 326 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8 = 327 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9 = 328 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10 = 329 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11 = 330 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12 = 331 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13 = 332 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14 = 333 +IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15 = 334 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP = 335 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0 = 336 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1 = 337 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2 = 338 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3 = 339 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4 = 340 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5 = 341 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6 = 342 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7 = 343 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8 = 344 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9 = 345 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10 = 346 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11 = 347 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12 = 348 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13 = 349 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14 = 350 +IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15 = 351 +IH_PERF_SEL_RB0_LOAD_RPTR = 352 +IH_PERF_SEL_RB0_LOAD_RPTR_VF0 = 353 +IH_PERF_SEL_RB0_LOAD_RPTR_VF1 = 354 +IH_PERF_SEL_RB0_LOAD_RPTR_VF2 = 355 +IH_PERF_SEL_RB0_LOAD_RPTR_VF3 = 356 +IH_PERF_SEL_RB0_LOAD_RPTR_VF4 = 357 +IH_PERF_SEL_RB0_LOAD_RPTR_VF5 = 358 +IH_PERF_SEL_RB0_LOAD_RPTR_VF6 = 359 +IH_PERF_SEL_RB0_LOAD_RPTR_VF7 = 360 +IH_PERF_SEL_RB0_LOAD_RPTR_VF8 = 361 +IH_PERF_SEL_RB0_LOAD_RPTR_VF9 = 362 +IH_PERF_SEL_RB0_LOAD_RPTR_VF10 = 363 +IH_PERF_SEL_RB0_LOAD_RPTR_VF11 = 364 +IH_PERF_SEL_RB0_LOAD_RPTR_VF12 = 365 +IH_PERF_SEL_RB0_LOAD_RPTR_VF13 = 366 +IH_PERF_SEL_RB0_LOAD_RPTR_VF14 = 367 +IH_PERF_SEL_RB0_LOAD_RPTR_VF15 = 368 +IH_PERF_SEL_RB1_LOAD_RPTR = 369 +IH_PERF_SEL_RB1_LOAD_RPTR_VF0 = 370 +IH_PERF_SEL_RB1_LOAD_RPTR_VF1 = 371 +IH_PERF_SEL_RB1_LOAD_RPTR_VF2 = 372 +IH_PERF_SEL_RB1_LOAD_RPTR_VF3 = 373 +IH_PERF_SEL_RB1_LOAD_RPTR_VF4 = 374 +IH_PERF_SEL_RB1_LOAD_RPTR_VF5 = 375 +IH_PERF_SEL_RB1_LOAD_RPTR_VF6 = 376 +IH_PERF_SEL_RB1_LOAD_RPTR_VF7 = 377 +IH_PERF_SEL_RB1_LOAD_RPTR_VF8 = 378 +IH_PERF_SEL_RB1_LOAD_RPTR_VF9 = 379 +IH_PERF_SEL_RB1_LOAD_RPTR_VF10 = 380 +IH_PERF_SEL_RB1_LOAD_RPTR_VF11 = 381 +IH_PERF_SEL_RB1_LOAD_RPTR_VF12 = 382 +IH_PERF_SEL_RB1_LOAD_RPTR_VF13 = 383 +IH_PERF_SEL_RB1_LOAD_RPTR_VF14 = 384 +IH_PERF_SEL_RB1_LOAD_RPTR_VF15 = 385 +IH_PERF_SEL_RB2_LOAD_RPTR = 386 +IH_PERF_SEL_RB2_LOAD_RPTR_VF0 = 387 +IH_PERF_SEL_RB2_LOAD_RPTR_VF1 = 388 +IH_PERF_SEL_RB2_LOAD_RPTR_VF2 = 389 +IH_PERF_SEL_RB2_LOAD_RPTR_VF3 = 390 +IH_PERF_SEL_RB2_LOAD_RPTR_VF4 = 391 +IH_PERF_SEL_RB2_LOAD_RPTR_VF5 = 392 +IH_PERF_SEL_RB2_LOAD_RPTR_VF6 = 393 +IH_PERF_SEL_RB2_LOAD_RPTR_VF7 = 394 +IH_PERF_SEL_RB2_LOAD_RPTR_VF8 = 395 +IH_PERF_SEL_RB2_LOAD_RPTR_VF9 = 396 +IH_PERF_SEL_RB2_LOAD_RPTR_VF10 = 397 +IH_PERF_SEL_RB2_LOAD_RPTR_VF11 = 398 +IH_PERF_SEL_RB2_LOAD_RPTR_VF12 = 399 +IH_PERF_SEL_RB2_LOAD_RPTR_VF13 = 400 +IH_PERF_SEL_RB2_LOAD_RPTR_VF14 = 401 +IH_PERF_SEL_RB2_LOAD_RPTR_VF15 = 402 +IH_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'IH_RING_ID' +IH_RING_ID__enumvalues = { + 0: 'IH_RING_ID_INTERRUPT', + 1: 'IH_RING_ID_REQUEST', + 2: 'IH_RING_ID_TRANSLATION', + 3: 'IH_RING_ID_RESERVED', +} +IH_RING_ID_INTERRUPT = 0 +IH_RING_ID_REQUEST = 1 +IH_RING_ID_TRANSLATION = 2 +IH_RING_ID_RESERVED = 3 +IH_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'IH_VF_RB_SELECT' +IH_VF_RB_SELECT__enumvalues = { + 0: 'IH_VF_RB_SELECT_CLIENT_FCN_ID', + 1: 'IH_VF_RB_SELECT_IH_FCN_ID', + 2: 'IH_VF_RB_SELECT_PF', + 3: 'IH_VF_RB_SELECT_RESERVED', +} +IH_VF_RB_SELECT_CLIENT_FCN_ID = 0 +IH_VF_RB_SELECT_IH_FCN_ID = 1 +IH_VF_RB_SELECT_PF = 2 +IH_VF_RB_SELECT_RESERVED = 3 +IH_VF_RB_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SEM_PERF_SEL' +SEM_PERF_SEL__enumvalues = { + 0: 'SEM_PERF_SEL_CYCLE', + 1: 'SEM_PERF_SEL_IDLE', + 2: 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', + 3: 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', + 4: 'SEM_PERF_SEL_SDMA2_REQ_SIGNAL', + 5: 'SEM_PERF_SEL_SDMA3_REQ_SIGNAL', + 6: 'SEM_PERF_SEL_UVD_REQ_SIGNAL', + 7: 'SEM_PERF_SEL_UVD1_REQ_SIGNAL', + 8: 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', + 9: 'SEM_PERF_SEL_ACP_REQ_SIGNAL', + 10: 'SEM_PERF_SEL_ISP_REQ_SIGNAL', + 11: 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', + 12: 'SEM_PERF_SEL_VP8_REQ_SIGNAL', + 13: 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', + 14: 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', + 15: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 16: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 17: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 18: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 19: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 20: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 21: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 22: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 23: 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 24: 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 25: 'SEM_PERF_SEL_SDMA2_REQ_WAIT', + 26: 'SEM_PERF_SEL_SDMA3_REQ_WAIT', + 27: 'SEM_PERF_SEL_UVD_REQ_WAIT', + 28: 'SEM_PERF_SEL_UVD1_REQ_WAIT', + 29: 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 30: 'SEM_PERF_SEL_ACP_REQ_WAIT', + 31: 'SEM_PERF_SEL_ISP_REQ_WAIT', + 32: 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 33: 'SEM_PERF_SEL_VP8_REQ_WAIT', + 34: 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 35: 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 36: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 37: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 38: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 39: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 40: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 41: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 42: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 43: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 44: 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 45: 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 46: 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 47: 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 48: 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 49: 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 50: 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 51: 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 52: 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 53: 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 54: 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 55: 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 56: 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 57: 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 58: 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 59: 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 60: 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 61: 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 62: 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 63: 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 64: 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 65: 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 66: 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 67: 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 68: 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 69: 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 70: 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 71: 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 72: 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 73: 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 74: 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 75: 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 76: 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 77: 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 78: 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 79: 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 80: 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 81: 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 82: 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 83: 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 84: 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 85: 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 86: 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 87: 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 88: 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 89: 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 90: 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 91: 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 92: 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 93: 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 94: 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 95: 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 96: 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 97: 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 98: 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 99: 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 100: 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 101: 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 102: 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 103: 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 104: 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 105: 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 106: 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 107: 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 108: 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 109: 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 110: 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 111: 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 112: 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 113: 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 114: 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 115: 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 116: 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 117: 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 118: 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 119: 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 120: 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 121: 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 122: 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 123: 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 124: 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 125: 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 126: 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 127: 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 128: 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 129: 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 130: 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 131: 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 132: 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 133: 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 134: 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 135: 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 136: 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 137: 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 138: 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 139: 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 140: 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 141: 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 142: 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 143: 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 144: 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 145: 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 146: 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 147: 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 148: 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 149: 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 150: 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 151: 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 152: 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 153: 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 154: 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 155: 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 156: 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 157: 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 158: 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 159: 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 160: 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 161: 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 162: 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 163: 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 164: 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 165: 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 166: 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 167: 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 168: 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 169: 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 170: 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 171: 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 172: 'SEM_PERF_SEL_MC_RD_REQ', + 173: 'SEM_PERF_SEL_MC_RD_RET', + 174: 'SEM_PERF_SEL_MC_WR_REQ', + 175: 'SEM_PERF_SEL_MC_WR_RET', + 176: 'SEM_PERF_SEL_ATC_REQ', + 177: 'SEM_PERF_SEL_ATC_RET', + 178: 'SEM_PERF_SEL_ATC_XNACK', + 179: 'SEM_PERF_SEL_ATC_INVALIDATION', + 180: 'SEM_PERF_SEL_ATC_VM_INVALIDATION', +} +SEM_PERF_SEL_CYCLE = 0 +SEM_PERF_SEL_IDLE = 1 +SEM_PERF_SEL_SDMA0_REQ_SIGNAL = 2 +SEM_PERF_SEL_SDMA1_REQ_SIGNAL = 3 +SEM_PERF_SEL_SDMA2_REQ_SIGNAL = 4 +SEM_PERF_SEL_SDMA3_REQ_SIGNAL = 5 +SEM_PERF_SEL_UVD_REQ_SIGNAL = 6 +SEM_PERF_SEL_UVD1_REQ_SIGNAL = 7 +SEM_PERF_SEL_VCE0_REQ_SIGNAL = 8 +SEM_PERF_SEL_ACP_REQ_SIGNAL = 9 +SEM_PERF_SEL_ISP_REQ_SIGNAL = 10 +SEM_PERF_SEL_VCE1_REQ_SIGNAL = 11 +SEM_PERF_SEL_VP8_REQ_SIGNAL = 12 +SEM_PERF_SEL_CPG_E0_REQ_SIGNAL = 13 +SEM_PERF_SEL_CPG_E1_REQ_SIGNAL = 14 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL = 15 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL = 16 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL = 17 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL = 18 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL = 19 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL = 20 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL = 21 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL = 22 +SEM_PERF_SEL_SDMA0_REQ_WAIT = 23 +SEM_PERF_SEL_SDMA1_REQ_WAIT = 24 +SEM_PERF_SEL_SDMA2_REQ_WAIT = 25 +SEM_PERF_SEL_SDMA3_REQ_WAIT = 26 +SEM_PERF_SEL_UVD_REQ_WAIT = 27 +SEM_PERF_SEL_UVD1_REQ_WAIT = 28 +SEM_PERF_SEL_VCE0_REQ_WAIT = 29 +SEM_PERF_SEL_ACP_REQ_WAIT = 30 +SEM_PERF_SEL_ISP_REQ_WAIT = 31 +SEM_PERF_SEL_VCE1_REQ_WAIT = 32 +SEM_PERF_SEL_VP8_REQ_WAIT = 33 +SEM_PERF_SEL_CPG_E0_REQ_WAIT = 34 +SEM_PERF_SEL_CPG_E1_REQ_WAIT = 35 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT = 36 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT = 37 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT = 38 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT = 39 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT = 40 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT = 41 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT = 42 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT = 43 +SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT = 44 +SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT = 45 +SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT = 46 +SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT = 47 +SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT = 48 +SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT = 49 +SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT = 50 +SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT = 51 +SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT = 52 +SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT = 53 +SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT = 54 +SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT = 55 +SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT = 56 +SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT = 57 +SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT = 58 +SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT = 59 +SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT = 60 +SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT = 61 +SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT = 62 +SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT = 63 +SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT = 64 +SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT = 65 +SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT = 66 +SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT = 67 +SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT = 68 +SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT = 69 +SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT = 70 +SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT = 71 +SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT = 72 +SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT = 73 +SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT = 74 +SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT = 75 +SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT = 76 +SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT = 77 +SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT = 78 +SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT = 79 +SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT = 80 +SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT = 81 +SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT = 82 +SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT = 83 +SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT = 84 +SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT = 85 +SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT = 86 +SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT = 87 +SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT = 88 +SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT = 89 +SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT = 90 +SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT = 91 +SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT = 92 +SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT = 93 +SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT = 94 +SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT = 95 +SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT = 96 +SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT = 97 +SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT = 98 +SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT = 99 +SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT = 100 +SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT = 101 +SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT = 102 +SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT = 103 +SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT = 104 +SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT = 105 +SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT = 106 +SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT = 107 +SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT = 108 +SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT = 109 +SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT = 110 +SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT = 111 +SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT = 112 +SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT = 113 +SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT = 114 +SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT = 115 +SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT = 116 +SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT = 117 +SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT = 118 +SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT = 119 +SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT = 120 +SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT = 121 +SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT = 122 +SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT = 123 +SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT = 124 +SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT = 125 +SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT = 126 +SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT = 127 +SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT = 128 +SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT = 129 +SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT = 130 +SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT = 131 +SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT = 132 +SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT = 133 +SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT = 134 +SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT = 135 +SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT = 136 +SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT = 137 +SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT = 138 +SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT = 139 +SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT = 140 +SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT = 141 +SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT = 142 +SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT = 143 +SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT = 144 +SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT = 145 +SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT = 146 +SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT = 147 +SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT = 148 +SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT = 149 +SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT = 150 +SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT = 151 +SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT = 152 +SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT = 153 +SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT = 154 +SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT = 155 +SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT = 156 +SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT = 157 +SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT = 158 +SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT = 159 +SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT = 160 +SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT = 161 +SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT = 162 +SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT = 163 +SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT = 164 +SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT = 165 +SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT = 166 +SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT = 167 +SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT = 168 +SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT = 169 +SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT = 170 +SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT = 171 +SEM_PERF_SEL_MC_RD_REQ = 172 +SEM_PERF_SEL_MC_RD_RET = 173 +SEM_PERF_SEL_MC_WR_REQ = 174 +SEM_PERF_SEL_MC_WR_RET = 175 +SEM_PERF_SEL_ATC_REQ = 176 +SEM_PERF_SEL_ATC_RET = 177 +SEM_PERF_SEL_ATC_XNACK = 178 +SEM_PERF_SEL_ATC_INVALIDATION = 179 +SEM_PERF_SEL_ATC_VM_INVALIDATION = 180 +SEM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'LSDMA_PERF_SEL' +LSDMA_PERF_SEL__enumvalues = { + 0: 'LSDMA_PERF_SEL_CYCLE', + 1: 'LSDMA_PERF_SEL_IDLE', + 2: 'LSDMA_PERF_SEL_REG_IDLE', + 3: 'LSDMA_PERF_SEL_RB_EMPTY', + 4: 'LSDMA_PERF_SEL_RB_FULL', + 5: 'LSDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'LSDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'LSDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'LSDMA_PERF_SEL_RB_RPTR_WB', + 9: 'LSDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'LSDMA_PERF_SEL_RB_CMD_FULL', + 11: 'LSDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'LSDMA_PERF_SEL_IB_CMD_FULL', + 13: 'LSDMA_PERF_SEL_EX_IDLE', + 14: 'LSDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'LSDMA_PERF_SEL_MC_WR_IDLE', + 17: 'LSDMA_PERF_SEL_MC_WR_COUNT', + 18: 'LSDMA_PERF_SEL_MC_RD_IDLE', + 19: 'LSDMA_PERF_SEL_MC_RD_COUNT', + 20: 'LSDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'LSDMA_PERF_SEL_SEM_IDLE', + 25: 'LSDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'LSDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'LSDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'LSDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'LSDMA_PERF_SEL_INT_IDLE', + 31: 'LSDMA_PERF_SEL_INT_REQ_STALL', + 32: 'LSDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'LSDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'LSDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'LSDMA_PERF_SEL_NUM_PACKET', + 37: 'LSDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'LSDMA_PERF_SEL_CE_WR_IDLE', + 39: 'LSDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'LSDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'LSDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'LSDMA_PERF_SEL_CE_IN_IDLE', + 43: 'LSDMA_PERF_SEL_CE_DST_IDLE', + 46: 'LSDMA_PERF_SEL_CE_AFIFO_FULL', + 49: 'LSDMA_PERF_SEL_CE_INFO_FULL', + 50: 'LSDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'LSDMA_PERF_SEL_CE_RD_STALL', + 52: 'LSDMA_PERF_SEL_CE_WR_STALL', + 53: 'LSDMA_PERF_SEL_GFX_SELECT', + 54: 'LSDMA_PERF_SEL_RLC0_SELECT', + 55: 'LSDMA_PERF_SEL_RLC1_SELECT', + 56: 'LSDMA_PERF_SEL_PAGE_SELECT', + 57: 'LSDMA_PERF_SEL_CTX_CHANGE', + 58: 'LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'LSDMA_PERF_SEL_DOORBELL', + 61: 'LSDMA_PERF_SEL_RD_BA_RTR', + 62: 'LSDMA_PERF_SEL_WR_BA_RTR', + 63: 'LSDMA_PERF_SEL_F32_L1_WR_VLD', + 64: 'LSDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'LSDMA_PERF_SEL_CE_L1_STALL', + 66: 'LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH', + 67: 'LSDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 68: 'LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 69: 'LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 70: 'LSDMA_PERF_SEL_ATCL2_RET_XNACK', + 71: 'LSDMA_PERF_SEL_ATCL2_RET_ACK', + 72: 'LSDMA_PERF_SEL_ATCL2_FREE', + 73: 'LSDMA_PERF_SEL_SDMA_ATCL2_SEND', + 74: 'LSDMA_PERF_SEL_DMA_L1_WR_SEND', + 75: 'LSDMA_PERF_SEL_DMA_L1_RD_SEND', + 76: 'LSDMA_PERF_SEL_DMA_MC_WR_SEND', + 77: 'LSDMA_PERF_SEL_DMA_MC_RD_SEND', + 78: 'LSDMA_PERF_SEL_L1_WR_FIFO_IDLE', + 79: 'LSDMA_PERF_SEL_L1_RD_FIFO_IDLE', + 80: 'LSDMA_PERF_SEL_L1_WRL2_IDLE', + 81: 'LSDMA_PERF_SEL_L1_RDL2_IDLE', + 82: 'LSDMA_PERF_SEL_L1_WRMC_IDLE', + 83: 'LSDMA_PERF_SEL_L1_RDMC_IDLE', + 84: 'LSDMA_PERF_SEL_L1_WR_INV_IDLE', + 85: 'LSDMA_PERF_SEL_L1_RD_INV_IDLE', + 86: 'LSDMA_PERF_SEL_L1_WR_INV_EN', + 87: 'LSDMA_PERF_SEL_L1_RD_INV_EN', + 88: 'LSDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 89: 'LSDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 90: 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR', + 91: 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 92: 'LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', + 93: 'LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', + 94: 'LSDMA_PERF_SEL_L1_INV_MIDDLE', + 95: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ', + 96: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET', + 97: 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ', + 98: 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET', + 99: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ', + 100: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET', + 101: 'LSDMA_PERF_SEL_RB_MMHUB_RD_REQ', + 102: 'LSDMA_PERF_SEL_RB_MMHUB_RD_RET', + 103: 'LSDMA_PERF_SEL_IB_MMHUB_RD_REQ', + 104: 'LSDMA_PERF_SEL_IB_MMHUB_RD_RET', + 105: 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ', + 106: 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET', + 107: 'LSDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 108: 'LSDMA_PERF_SEL_UTCL1_UTCL2_RET', + 109: 'LSDMA_PERF_SEL_CMD_OP_MATCH', + 110: 'LSDMA_PERF_SEL_CMD_OP_START', + 111: 'LSDMA_PERF_SEL_CMD_OP_END', + 112: 'LSDMA_PERF_SEL_CE_BUSY', + 113: 'LSDMA_PERF_SEL_CE_BUSY_START', + 114: 'LSDMA_PERF_SEL_CE_BUSY_END', + 115: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 116: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 117: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 118: 'LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND', + 119: 'LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID', + 120: 'LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND', + 121: 'LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID', + 122: 'LSDMA_PERF_SEL_DRAM_ECC', + 123: 'LSDMA_PERF_SEL_NACK_GEN_ERR', +} +LSDMA_PERF_SEL_CYCLE = 0 +LSDMA_PERF_SEL_IDLE = 1 +LSDMA_PERF_SEL_REG_IDLE = 2 +LSDMA_PERF_SEL_RB_EMPTY = 3 +LSDMA_PERF_SEL_RB_FULL = 4 +LSDMA_PERF_SEL_RB_WPTR_WRAP = 5 +LSDMA_PERF_SEL_RB_RPTR_WRAP = 6 +LSDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +LSDMA_PERF_SEL_RB_RPTR_WB = 8 +LSDMA_PERF_SEL_RB_CMD_IDLE = 9 +LSDMA_PERF_SEL_RB_CMD_FULL = 10 +LSDMA_PERF_SEL_IB_CMD_IDLE = 11 +LSDMA_PERF_SEL_IB_CMD_FULL = 12 +LSDMA_PERF_SEL_EX_IDLE = 13 +LSDMA_PERF_SEL_SRBM_REG_SEND = 14 +LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +LSDMA_PERF_SEL_MC_WR_IDLE = 16 +LSDMA_PERF_SEL_MC_WR_COUNT = 17 +LSDMA_PERF_SEL_MC_RD_IDLE = 18 +LSDMA_PERF_SEL_MC_RD_COUNT = 19 +LSDMA_PERF_SEL_MC_RD_RET_STALL = 20 +LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +LSDMA_PERF_SEL_SEM_IDLE = 24 +LSDMA_PERF_SEL_SEM_REQ_STALL = 25 +LSDMA_PERF_SEL_SEM_REQ_COUNT = 26 +LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +LSDMA_PERF_SEL_SEM_RESP_FAIL = 28 +LSDMA_PERF_SEL_SEM_RESP_PASS = 29 +LSDMA_PERF_SEL_INT_IDLE = 30 +LSDMA_PERF_SEL_INT_REQ_STALL = 31 +LSDMA_PERF_SEL_INT_REQ_COUNT = 32 +LSDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +LSDMA_PERF_SEL_INT_RESP_RETRY = 34 +LSDMA_PERF_SEL_NUM_PACKET = 35 +LSDMA_PERF_SEL_CE_WREQ_IDLE = 37 +LSDMA_PERF_SEL_CE_WR_IDLE = 38 +LSDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +LSDMA_PERF_SEL_CE_RREQ_IDLE = 40 +LSDMA_PERF_SEL_CE_OUT_IDLE = 41 +LSDMA_PERF_SEL_CE_IN_IDLE = 42 +LSDMA_PERF_SEL_CE_DST_IDLE = 43 +LSDMA_PERF_SEL_CE_AFIFO_FULL = 46 +LSDMA_PERF_SEL_CE_INFO_FULL = 49 +LSDMA_PERF_SEL_CE_INFO1_FULL = 50 +LSDMA_PERF_SEL_CE_RD_STALL = 51 +LSDMA_PERF_SEL_CE_WR_STALL = 52 +LSDMA_PERF_SEL_GFX_SELECT = 53 +LSDMA_PERF_SEL_RLC0_SELECT = 54 +LSDMA_PERF_SEL_RLC1_SELECT = 55 +LSDMA_PERF_SEL_PAGE_SELECT = 56 +LSDMA_PERF_SEL_CTX_CHANGE = 57 +LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +LSDMA_PERF_SEL_DOORBELL = 60 +LSDMA_PERF_SEL_RD_BA_RTR = 61 +LSDMA_PERF_SEL_WR_BA_RTR = 62 +LSDMA_PERF_SEL_F32_L1_WR_VLD = 63 +LSDMA_PERF_SEL_CE_L1_WR_VLD = 64 +LSDMA_PERF_SEL_CE_L1_STALL = 65 +LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH = 66 +LSDMA_PERF_SEL_SDMA_INVACK_FLUSH = 67 +LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH = 68 +LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH = 69 +LSDMA_PERF_SEL_ATCL2_RET_XNACK = 70 +LSDMA_PERF_SEL_ATCL2_RET_ACK = 71 +LSDMA_PERF_SEL_ATCL2_FREE = 72 +LSDMA_PERF_SEL_SDMA_ATCL2_SEND = 73 +LSDMA_PERF_SEL_DMA_L1_WR_SEND = 74 +LSDMA_PERF_SEL_DMA_L1_RD_SEND = 75 +LSDMA_PERF_SEL_DMA_MC_WR_SEND = 76 +LSDMA_PERF_SEL_DMA_MC_RD_SEND = 77 +LSDMA_PERF_SEL_L1_WR_FIFO_IDLE = 78 +LSDMA_PERF_SEL_L1_RD_FIFO_IDLE = 79 +LSDMA_PERF_SEL_L1_WRL2_IDLE = 80 +LSDMA_PERF_SEL_L1_RDL2_IDLE = 81 +LSDMA_PERF_SEL_L1_WRMC_IDLE = 82 +LSDMA_PERF_SEL_L1_RDMC_IDLE = 83 +LSDMA_PERF_SEL_L1_WR_INV_IDLE = 84 +LSDMA_PERF_SEL_L1_RD_INV_IDLE = 85 +LSDMA_PERF_SEL_L1_WR_INV_EN = 86 +LSDMA_PERF_SEL_L1_RD_INV_EN = 87 +LSDMA_PERF_SEL_L1_WR_WAIT_INVADR = 88 +LSDMA_PERF_SEL_L1_RD_WAIT_INVADR = 89 +LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR = 90 +LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD = 91 +LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT = 92 +LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT = 93 +LSDMA_PERF_SEL_L1_INV_MIDDLE = 94 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ = 95 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET = 96 +LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ = 97 +LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET = 98 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ = 99 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET = 100 +LSDMA_PERF_SEL_RB_MMHUB_RD_REQ = 101 +LSDMA_PERF_SEL_RB_MMHUB_RD_RET = 102 +LSDMA_PERF_SEL_IB_MMHUB_RD_REQ = 103 +LSDMA_PERF_SEL_IB_MMHUB_RD_RET = 104 +LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ = 105 +LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET = 106 +LSDMA_PERF_SEL_UTCL1_UTCL2_REQ = 107 +LSDMA_PERF_SEL_UTCL1_UTCL2_RET = 108 +LSDMA_PERF_SEL_CMD_OP_MATCH = 109 +LSDMA_PERF_SEL_CMD_OP_START = 110 +LSDMA_PERF_SEL_CMD_OP_END = 111 +LSDMA_PERF_SEL_CE_BUSY = 112 +LSDMA_PERF_SEL_CE_BUSY_START = 113 +LSDMA_PERF_SEL_CE_BUSY_END = 114 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER = 115 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START = 116 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END = 117 +LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND = 118 +LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID = 119 +LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND = 120 +LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID = 121 +LSDMA_PERF_SEL_DRAM_ECC = 122 +LSDMA_PERF_SEL_NACK_GEN_ERR = 123 +LSDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'EFC_SURFACE_PIXEL_FORMAT' +EFC_SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'EFC_ARGB1555', + 2: 'EFC_RGBA5551', + 3: 'EFC_RGB565', + 4: 'EFC_BGR565', + 5: 'EFC_ARGB4444', + 6: 'EFC_RGBA4444', + 8: 'EFC_ARGB8888', + 9: 'EFC_RGBA8888', + 10: 'EFC_ARGB2101010', + 11: 'EFC_RGBA1010102', + 12: 'EFC_AYCrCb8888', + 13: 'EFC_YCrCbA8888', + 14: 'EFC_ACrYCb8888', + 15: 'EFC_CrYCbA8888', + 16: 'EFC_ARGB16161616_10MSB', + 17: 'EFC_RGBA16161616_10MSB', + 18: 'EFC_ARGB16161616_10LSB', + 19: 'EFC_RGBA16161616_10LSB', + 20: 'EFC_ARGB16161616_12MSB', + 21: 'EFC_RGBA16161616_12MSB', + 22: 'EFC_ARGB16161616_12LSB', + 23: 'EFC_RGBA16161616_12LSB', + 24: 'EFC_ARGB16161616_FLOAT', + 25: 'EFC_RGBA16161616_FLOAT', + 26: 'EFC_ARGB16161616_UNORM', + 27: 'EFC_RGBA16161616_UNORM', + 28: 'EFC_ARGB16161616_SNORM', + 29: 'EFC_RGBA16161616_SNORM', + 32: 'EFC_AYCrCb16161616_10MSB', + 33: 'EFC_AYCrCb16161616_10LSB', + 34: 'EFC_YCrCbA16161616_10MSB', + 35: 'EFC_YCrCbA16161616_10LSB', + 36: 'EFC_ACrYCb16161616_10MSB', + 37: 'EFC_ACrYCb16161616_10LSB', + 38: 'EFC_CrYCbA16161616_10MSB', + 39: 'EFC_CrYCbA16161616_10LSB', + 40: 'EFC_AYCrCb16161616_12MSB', + 41: 'EFC_AYCrCb16161616_12LSB', + 42: 'EFC_YCrCbA16161616_12MSB', + 43: 'EFC_YCrCbA16161616_12LSB', + 44: 'EFC_ACrYCb16161616_12MSB', + 45: 'EFC_ACrYCb16161616_12LSB', + 46: 'EFC_CrYCbA16161616_12MSB', + 47: 'EFC_CrYCbA16161616_12LSB', + 64: 'EFC_Y8_CrCb88_420_PLANAR', + 65: 'EFC_Y8_CbCr88_420_PLANAR', + 66: 'EFC_Y10_CrCb1010_420_PLANAR', + 67: 'EFC_Y10_CbCr1010_420_PLANAR', + 68: 'EFC_Y12_CrCb1212_420_PLANAR', + 69: 'EFC_Y12_CbCr1212_420_PLANAR', + 72: 'EFC_YCrYCb8888_422_PACKED', + 73: 'EFC_YCbYCr8888_422_PACKED', + 74: 'EFC_CrYCbY8888_422_PACKED', + 75: 'EFC_CbYCrY8888_422_PACKED', + 76: 'EFC_YCrYCb10101010_422_PACKED', + 77: 'EFC_YCbYCr10101010_422_PACKED', + 78: 'EFC_CrYCbY10101010_422_PACKED', + 79: 'EFC_CbYCrY10101010_422_PACKED', + 80: 'EFC_YCrYCb12121212_422_PACKED', + 81: 'EFC_YCbYCr12121212_422_PACKED', + 82: 'EFC_CrYCbY12121212_422_PACKED', + 83: 'EFC_CbYCrY12121212_422_PACKED', + 112: 'EFC_RGB111110_FIX', + 113: 'EFC_BGR101111_FIX', + 114: 'EFC_ACrYCb2101010', + 115: 'EFC_CrYCbA1010102', + 118: 'EFC_RGB111110_FLOAT', + 119: 'EFC_BGR101111_FLOAT', + 120: 'EFC_MONO_8', + 121: 'EFC_MONO_10MSB', + 122: 'EFC_MONO_10LSB', + 123: 'EFC_MONO_12MSB', + 124: 'EFC_MONO_12LSB', + 125: 'EFC_MONO_16', +} +EFC_ARGB1555 = 1 +EFC_RGBA5551 = 2 +EFC_RGB565 = 3 +EFC_BGR565 = 4 +EFC_ARGB4444 = 5 +EFC_RGBA4444 = 6 +EFC_ARGB8888 = 8 +EFC_RGBA8888 = 9 +EFC_ARGB2101010 = 10 +EFC_RGBA1010102 = 11 +EFC_AYCrCb8888 = 12 +EFC_YCrCbA8888 = 13 +EFC_ACrYCb8888 = 14 +EFC_CrYCbA8888 = 15 +EFC_ARGB16161616_10MSB = 16 +EFC_RGBA16161616_10MSB = 17 +EFC_ARGB16161616_10LSB = 18 +EFC_RGBA16161616_10LSB = 19 +EFC_ARGB16161616_12MSB = 20 +EFC_RGBA16161616_12MSB = 21 +EFC_ARGB16161616_12LSB = 22 +EFC_RGBA16161616_12LSB = 23 +EFC_ARGB16161616_FLOAT = 24 +EFC_RGBA16161616_FLOAT = 25 +EFC_ARGB16161616_UNORM = 26 +EFC_RGBA16161616_UNORM = 27 +EFC_ARGB16161616_SNORM = 28 +EFC_RGBA16161616_SNORM = 29 +EFC_AYCrCb16161616_10MSB = 32 +EFC_AYCrCb16161616_10LSB = 33 +EFC_YCrCbA16161616_10MSB = 34 +EFC_YCrCbA16161616_10LSB = 35 +EFC_ACrYCb16161616_10MSB = 36 +EFC_ACrYCb16161616_10LSB = 37 +EFC_CrYCbA16161616_10MSB = 38 +EFC_CrYCbA16161616_10LSB = 39 +EFC_AYCrCb16161616_12MSB = 40 +EFC_AYCrCb16161616_12LSB = 41 +EFC_YCrCbA16161616_12MSB = 42 +EFC_YCrCbA16161616_12LSB = 43 +EFC_ACrYCb16161616_12MSB = 44 +EFC_ACrYCb16161616_12LSB = 45 +EFC_CrYCbA16161616_12MSB = 46 +EFC_CrYCbA16161616_12LSB = 47 +EFC_Y8_CrCb88_420_PLANAR = 64 +EFC_Y8_CbCr88_420_PLANAR = 65 +EFC_Y10_CrCb1010_420_PLANAR = 66 +EFC_Y10_CbCr1010_420_PLANAR = 67 +EFC_Y12_CrCb1212_420_PLANAR = 68 +EFC_Y12_CbCr1212_420_PLANAR = 69 +EFC_YCrYCb8888_422_PACKED = 72 +EFC_YCbYCr8888_422_PACKED = 73 +EFC_CrYCbY8888_422_PACKED = 74 +EFC_CbYCrY8888_422_PACKED = 75 +EFC_YCrYCb10101010_422_PACKED = 76 +EFC_YCbYCr10101010_422_PACKED = 77 +EFC_CrYCbY10101010_422_PACKED = 78 +EFC_CbYCrY10101010_422_PACKED = 79 +EFC_YCrYCb12121212_422_PACKED = 80 +EFC_YCbYCr12121212_422_PACKED = 81 +EFC_CrYCbY12121212_422_PACKED = 82 +EFC_CbYCrY12121212_422_PACKED = 83 +EFC_RGB111110_FIX = 112 +EFC_BGR101111_FIX = 113 +EFC_ACrYCb2101010 = 114 +EFC_CrYCbA1010102 = 115 +EFC_RGB111110_FLOAT = 118 +EFC_BGR101111_FLOAT = 119 +EFC_MONO_8 = 120 +EFC_MONO_10MSB = 121 +EFC_MONO_10LSB = 122 +EFC_MONO_12MSB = 123 +EFC_MONO_12LSB = 124 +EFC_MONO_16 = 125 +EFC_SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum +__all__ = \ + ['ACCEPT_UNSOLICITED_RESPONSE_ENABLE', + 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', 'ACP_TYPE_DVD_AUDIO', + 'ACP_TYPE_GENERIC_AUDIO', 'ACP_TYPE_ICE60958_AUDIO', + 'ACP_TYPE_SUPER_AUDIO_CD', 'ACrYCb16161616_10LSB', + 'ACrYCb16161616_10MSB', 'ACrYCb16161616_12LSB', + 'ACrYCb16161616_12MSB', 'ACrYCb2101010', 'ACrYCb8888', + 'ADDR_GEN_ONE', 'ADDR_GEN_TWO', 'ADDR_GEN_ZERO', 'ADDR_RESERVED', + 'AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_ACP_SOURCE_FROM_AZALIA', 'AFMT_ACP_TYPE', + 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', + 'AFMT_AUDIO_CRC_AUTO_RESTART', 'AFMT_AUDIO_CRC_CH0_SIG', + 'AFMT_AUDIO_CRC_CH1_SIG', 'AFMT_AUDIO_CRC_CH2_SIG', + 'AFMT_AUDIO_CRC_CH3_SIG', 'AFMT_AUDIO_CRC_CH4_SIG', + 'AFMT_AUDIO_CRC_CH5_SIG', 'AFMT_AUDIO_CRC_CH6_SIG', + 'AFMT_AUDIO_CRC_CH7_SIG', 'AFMT_AUDIO_CRC_CONTROL_CH_SEL', + 'AFMT_AUDIO_CRC_CONTROL_CONT', 'AFMT_AUDIO_CRC_CONTROL_SOURCE', + 'AFMT_AUDIO_CRC_ONESHOT', 'AFMT_AUDIO_CRC_RESERVED_10', + 'AFMT_AUDIO_CRC_RESERVED_11', 'AFMT_AUDIO_CRC_RESERVED_12', + 'AFMT_AUDIO_CRC_RESERVED_13', 'AFMT_AUDIO_CRC_RESERVED_14', + 'AFMT_AUDIO_CRC_RESERVED_8', 'AFMT_AUDIO_CRC_RESERVED_9', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', + 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', + 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD', + 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND', + 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS', + 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 'AFMT_AUDIO_PACKET_SENT_ENABLED', 'AFMT_AUDIO_SRC_CONTROL_SELECT', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', + 'AFMT_HDMI_AUDIO_SEND_MAX_PACKETS', + 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE', + 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 'AFMT_INTERRUPT_DISABLE', 'AFMT_INTERRUPT_ENABLE', + 'AFMT_INTERRUPT_STATUS_CHG_MASK', 'AFMT_MEM_DISABLE_MEM_PWR_CTRL', + 'AFMT_MEM_ENABLE_MEM_PWR_CTRL', + 'AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'AFMT_MEM_FORCE_SHUT_DOWN_REQUEST', 'AFMT_MEM_NO_FORCE_REQUEST', + 'AFMT_MEM_PWR_DIS_CTRL', 'AFMT_MEM_PWR_FORCE_CTRL', + 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 'AFMT_RAMP_CONTROL0_SIGN', 'AFMT_RAMP_SIGNED', + 'AFMT_RAMP_UNSIGNED', 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', + 'AFMT_VBI_PACKET_CONTROL_ACP_SOURCE', 'ALLOW_SR_ON_TRANS_REQ', + 'ALLOW_SR_ON_TRANS_REQ_DISABLE', 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 'ALL_USE_R', 'ALPHA_DATA_ONTO_ALPHA_PORT', + 'ALPHA_DATA_ONTO_CB_B_PORT', 'ALPHA_DATA_ONTO_CR_R_PORT', + 'ALPHA_DATA_ONTO_Y_G_PORT', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', 'AMCLOCK_ENABLE', + 'APG_ACP_OVERRIDE', 'APG_ACP_SOURCE_NO_OVERRIDE', + 'APG_ACP_TYPE_DVD_AUDIO', 'APG_ACP_TYPE_GENERIC_AUDIO', + 'APG_ACP_TYPE_ICE60958_AUDIO', 'APG_ACP_TYPE_SUPER_AUDIO_CD', + 'APG_AUDIO_CRC_CH0_SIG', 'APG_AUDIO_CRC_CH1_SIG', + 'APG_AUDIO_CRC_CH2_SIG', 'APG_AUDIO_CRC_CH3_SIG', + 'APG_AUDIO_CRC_CH4_SIG', 'APG_AUDIO_CRC_CH5_SIG', + 'APG_AUDIO_CRC_CH6_SIG', 'APG_AUDIO_CRC_CH7_SIG', + 'APG_AUDIO_CRC_CONTINUOUS', 'APG_AUDIO_CRC_CONTROL_CH_SEL', + 'APG_AUDIO_CRC_CONTROL_CONT', 'APG_AUDIO_CRC_ONESHOT', + 'APG_AUDIO_CRC_RESERVED_10', 'APG_AUDIO_CRC_RESERVED_11', + 'APG_AUDIO_CRC_RESERVED_12', 'APG_AUDIO_CRC_RESERVED_13', + 'APG_AUDIO_CRC_RESERVED_14', 'APG_AUDIO_CRC_RESERVED_15', + 'APG_AUDIO_CRC_RESERVED_8', 'APG_AUDIO_CRC_RESERVED_9', + 'APG_DBG_ACP_TYPE', 'APG_DBG_AUDIO_DTO_BASE', + 'APG_DBG_AUDIO_DTO_DIV', 'APG_DBG_AUDIO_DTO_MULTI', + 'APG_DBG_MUX_SEL', 'APG_DEBUG_AUDIO_MODE', + 'APG_DP_ASP_CHANNEL_COUNT_FROM_AZ', + 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE', + 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'APG_FUNCTIONAL_MODE', 'APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS', + 'APG_INFOFRAME_SOURCE_NO_OVERRIDE', + 'APG_MEM_DISABLE_MEM_PWR_CTRL', 'APG_MEM_ENABLE_MEM_PWR_CTRL', + 'APG_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'APG_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'APG_MEM_FORCE_SHUT_DOWN_REQUEST', 'APG_MEM_NO_FORCE_REQUEST', + 'APG_MEM_POWER_STATE', 'APG_MEM_POWER_STATE_DS', + 'APG_MEM_POWER_STATE_LS', 'APG_MEM_POWER_STATE_ON', + 'APG_MEM_POWER_STATE_SD', 'APG_MEM_PWR_DIS_CTRL', + 'APG_MEM_PWR_FORCE_CTRL', 'APG_PACKET_CONTROL_ACP_SOURCE', + 'APG_PACKET_CONTROL_AUDIO_INFO_SOURCE', 'APG_RAMP_CONTROL_SIGN', + 'APG_RAMP_SIGNED', 'APG_RAMP_UNSIGNED', 'ARGB1555', + 'ARGB16161616_10LSB', 'ARGB16161616_10MSB', 'ARGB16161616_12LSB', + 'ARGB16161616_12MSB', 'ARGB16161616_FLOAT', 'ARGB16161616_SNORM', + 'ARGB16161616_UNORM', 'ARGB2101010', 'ARGB4444', 'ARGB8888', + 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', 'AUDIO_LAYOUT_SELECT', + 'AUTOCAL_MODE_AUTOCENTER', 'AUTOCAL_MODE_AUTOREPLICATE', + 'AUTOCAL_MODE_AUTOSCALE', 'AUTOCAL_MODE_OFF', + 'AYCrCb16161616_10LSB', 'AYCrCb16161616_10MSB', + 'AYCrCb16161616_12LSB', 'AYCrCb16161616_12MSB', 'AYCrCb8888', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', + 'AZ_CORB_SIZE', 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 'AZ_CORB_SIZE_256ENTRIES', 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 'AZ_CORB_SIZE_RESERVED', 'AZ_GLOBAL_CAPABILITIES', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', + 'AZ_LATENCY_COUNTER_CONTROL', 'AZ_LATENCY_COUNTER_NO_RESET', + 'AZ_LATENCY_COUNTER_RESET_DONE', 'AZ_RIRB_SIZE', + 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', 'AZ_RIRB_SIZE_256ENTRIES', + 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', 'AZ_RIRB_SIZE_UNDEFINED', + 'AZ_RIRB_WRITE_POINTER_DO_RESET', + 'AZ_RIRB_WRITE_POINTER_NOT_RESET', 'AZ_RIRB_WRITE_POINTER_RESET', + 'AZ_STATE_CHANGE_STATUS', + 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', 'BASE_RATE_44P1KHZ', + 'BASE_RATE_48KHZ', 'BGR101111_FIX', 'BGR101111_FLOAT', 'BGR565', + 'BIGK_FRAGMENT_SIZE', 'BINNER_BREAK_BATCH', 'BINNER_DROP', + 'BINNER_PIPELINE', 'BINNER_PIPELINE_BREAK', 'BINNING_ALLOWED', + 'BIN_CONF_OVERRIDE_CHECK', 'BIN_MAP_MODE_NONE', + 'BIN_MAP_MODE_POPS', 'BIN_MAP_MODE_RTA_INDEX', + 'BIN_SIZE_128_PIXELS', 'BIN_SIZE_256_PIXELS', + 'BIN_SIZE_32_PIXELS', 'BIN_SIZE_512_PIXELS', 'BIN_SIZE_64_PIXELS', + 'BITS_31_0', 'BITS_32_1', 'BITS_33_2', 'BITS_34_3', 'BITS_35_4', + 'BITS_36_5', 'BITS_37_6', 'BITS_38_7', 'BLEND_CONSTANT_ALPHA', + 'BLEND_CONSTANT_COLOR', 'BLEND_DST_ALPHA', 'BLEND_DST_COLOR', + 'BLEND_INV_SRC1_ALPHA', 'BLEND_INV_SRC1_COLOR', 'BLEND_ONE', + 'BLEND_ONE_MINUS_CONSTANT_ALPHA', + 'BLEND_ONE_MINUS_CONSTANT_COLOR', 'BLEND_ONE_MINUS_DST_ALPHA', + 'BLEND_ONE_MINUS_DST_COLOR', 'BLEND_ONE_MINUS_SRC_ALPHA', + 'BLEND_ONE_MINUS_SRC_COLOR', 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', 'BLEND_SRC1_ALPHA', + 'BLEND_SRC1_COLOR', 'BLEND_SRC_ALPHA', 'BLEND_SRC_ALPHA_SATURATE', + 'BLEND_SRC_COLOR', 'BLEND_ZERO', 'BLOCK_CONTEXT_DONE', 'BLUE_LUT', + 'BORROWBUFFER_MEM_POWER_STATE_ENUM', + 'BORROWBUFFER_MEM_POWER_STATE_ENUM_DS', + 'BORROWBUFFER_MEM_POWER_STATE_ENUM_LS', + 'BORROWBUFFER_MEM_POWER_STATE_ENUM_ON', + 'BORROWBUFFER_MEM_POWER_STATE_ENUM_SD', 'BOTTOM_OF_PIPE_TS', + 'BREAK_BATCH', 'BYPASS', 'BYPASS_EN', 'BYPASS_GAMUT', + 'BYPASS_POST_CSC', 'BinEventCntl', 'BinMapMode', 'BinSizeExtend', + 'BinningMode', 'BlendOp', 'BlendOpt', 'CACHE_BYPASS', + 'CACHE_FLUSH', 'CACHE_FLUSH_AND_INV_EVENT', + 'CACHE_FLUSH_AND_INV_TS_EVENT', 'CACHE_FLUSH_TS', 'CACHE_LRU_RD', + 'CACHE_LRU_WR', 'CACHE_NOA', 'CACHE_NOA_WR', 'CACHE_STREAM', + 'CACHE_STREAM_RD', 'CBMode', 'CBPerfClearFilterSel', + 'CBPerfOpFilterSel', 'CBPerfSel', 'CBRamList', + 'CB_B_DATA_ONTO_ALPHA_PORT', 'CB_B_DATA_ONTO_CB_B_PORT', + 'CB_B_DATA_ONTO_CR_R_PORT', 'CB_B_DATA_ONTO_Y_G_PORT', + 'CB_DCC_DECOMPRESS', 'CB_DCG_BACKEND_RDLAT_FIFO', + 'CB_DCG_CCC_CAS_COLOR_PTR', 'CB_DCG_CCC_CAS_FRAG_PTR', + 'CB_DCG_CCC_CAS_KEYID', 'CB_DCG_CCC_CAS_SURF_PARAM', + 'CB_DCG_CCC_CAS_TAG_ARRAY', 'CB_DCG_COLOR_STORE', + 'CB_DCG_COLOR_STORE_DIRTY_BYTE', 'CB_DCG_DCC_CACHE', + 'CB_DCG_DCC_DIRTY_BITS', 'CB_DCG_FMASK_CACHE_STORE', + 'CB_DCG_FRONTEND_RDLAT_FIFO', 'CB_DCG_OUTPUT_FIFO', + 'CB_DCG_QBLOCK_ALLOC', 'CB_DCG_QUAD_PTR_FIFO', + 'CB_DCG_READ_SKID_FIFO', 'CB_DCG_SRC_FIFO', 'CB_DISABLE', + 'CB_ELIMINATE_FAST_CLEAR', 'CB_NORMAL', + 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', + 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', + 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 'CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_READ_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN', + 'CB_PERF_SEL_BLEND_CLOCK_EN', + 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 'CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 'CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED', + 'CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 'CB_PERF_SEL_BLEND_STALL_AT_OUTPUT', + 'CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_RMI_RDREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_RMI_RDREQ_VALID_READY', + 'CB_PERF_SEL_CB_RMI_RDREQ_VALID_READYB', + 'CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_RMI_WRREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_RMI_WRREQ_VALID_READY', + 'CB_PERF_SEL_CB_RMI_WRREQ_VALID_READYB', + 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_CC_CACHE_FLUSH', + 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_SECTOR_HIT', + 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CC_CACHE_STALL', + 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TID_IN', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TID_OUT', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_IN', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TID_OUT', + 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_SURFACE_SYNC', 'CB_PERF_SEL_CC_TAG_HIT', + 'CB_PERF_SEL_COLOR_STORE_CLOCK_EN', + 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READY', + 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB', + 'CB_PERF_SEL_DCC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_DCC_CACHE_FLUSH', + 'CB_PERF_SEL_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_DCC_CACHE_PERF_HIT', + 'CB_PERF_SEL_DCC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_DCC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_DCC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_DCC_CACHE_SECTOR_MISS', + 'CB_PERF_SEL_DCC_CACHE_STALL', + 'CB_PERF_SEL_DCC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_DCC_CACHE_TAG_MISS', + 'CB_PERF_SEL_DCC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_DRAWN_PIXEL', 'CB_PERF_SEL_DRAWN_QUAD', + 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', 'CB_PERF_SEL_DRAWN_TILE', + 'CB_PERF_SEL_EVENT', 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 'CB_PERF_SEL_FILTER_DRAWN_PIXEL', 'CB_PERF_SEL_FILTER_DRAWN_QUAD', + 'CB_PERF_SEL_FILTER_DRAWN_QUAD_FRAGMENT', + 'CB_PERF_SEL_FILTER_DRAWN_TILE', + 'CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN', + 'CB_PERF_SEL_GRBM_CLOCK_EN', 'CB_PERF_SEL_MEMARB_CLOCK_EN', + 'CB_PERF_SEL_NACK_CC_READ', 'CB_PERF_SEL_NACK_CC_WRITE', + 'CB_PERF_SEL_NONE', 'CB_PERF_SEL_PERFMON_CLOCK_EN', + 'CB_PERF_SEL_RESERVED_118', 'CB_PERF_SEL_RESERVED_119', + 'CB_PERF_SEL_RESERVED_120', 'CB_PERF_SEL_RESERVED_121', + 'CB_PERF_SEL_RESERVED_122', 'CB_PERF_SEL_RESERVED_123', + 'CB_PERF_SEL_RESERVED_124', 'CB_PERF_SEL_RESERVED_125', + 'CB_PERF_SEL_RESERVED_126', 'CB_PERF_SEL_RESERVED_127', + 'CB_PERF_SEL_RESERVED_128', 'CB_PERF_SEL_RESERVED_129', + 'CB_PERF_SEL_RESERVED_130', 'CB_PERF_SEL_RESERVED_131', + 'CB_PERF_SEL_RESERVED_132', 'CB_PERF_SEL_RESERVED_133', + 'CB_PERF_SEL_RESERVED_134', 'CB_PERF_SEL_RESERVED_135', + 'CB_PERF_SEL_RESERVED_136', 'CB_PERF_SEL_RESERVED_137', + 'CB_PERF_SEL_RESERVED_138', 'CB_PERF_SEL_RESERVED_139', + 'CB_PERF_SEL_RESERVED_140', 'CB_PERF_SEL_RESERVED_141', + 'CB_PERF_SEL_RESERVED_142', 'CB_PERF_SEL_RESERVED_143', + 'CB_PERF_SEL_RESERVED_144', 'CB_PERF_SEL_RESERVED_145', + 'CB_PERF_SEL_RESERVED_146', 'CB_PERF_SEL_RESERVED_147', + 'CB_PERF_SEL_RESERVED_148', 'CB_PERF_SEL_RESERVED_149', + 'CB_PERF_SEL_RESERVED_165', 'CB_PERF_SEL_RESERVED_166', + 'CB_PERF_SEL_RESERVED_167', 'CB_PERF_SEL_RESERVED_168', + 'CB_PERF_SEL_RESERVED_169', 'CB_PERF_SEL_RESERVED_170', + 'CB_PERF_SEL_RESERVED_171', 'CB_PERF_SEL_RESERVED_172', + 'CB_PERF_SEL_RESERVED_173', 'CB_PERF_SEL_RESERVED_174', + 'CB_PERF_SEL_RESERVED_175', 'CB_PERF_SEL_RESERVED_176', + 'CB_PERF_SEL_RESERVED_177', 'CB_PERF_SEL_RESERVED_178', + 'CB_PERF_SEL_RESERVED_179', 'CB_PERF_SEL_RESERVED_180', + 'CB_PERF_SEL_RESERVED_181', 'CB_PERF_SEL_RESERVED_182', + 'CB_PERF_SEL_RESERVED_183', 'CB_PERF_SEL_RESERVED_184', + 'CB_PERF_SEL_RESERVED_185', 'CB_PERF_SEL_RESERVED_186', + 'CB_PERF_SEL_RESERVED_187', 'CB_PERF_SEL_RESERVED_188', + 'CB_PERF_SEL_RESERVED_189', 'CB_PERF_SEL_RESERVED_190', + 'CB_PERF_SEL_RESERVED_191', 'CB_PERF_SEL_RESERVED_192', + 'CB_PERF_SEL_RESERVED_193', 'CB_PERF_SEL_RESERVED_194', + 'CB_PERF_SEL_RESERVED_195', 'CB_PERF_SEL_RESERVED_196', + 'CB_PERF_SEL_RESERVED_197', 'CB_PERF_SEL_RESERVED_198', + 'CB_PERF_SEL_RESERVED_199', 'CB_PERF_SEL_RESERVED_205', + 'CB_PERF_SEL_RESERVED_206', 'CB_PERF_SEL_RESERVED_207', + 'CB_PERF_SEL_RESERVED_208', 'CB_PERF_SEL_RESERVED_209', + 'CB_PERF_SEL_RESERVED_21', 'CB_PERF_SEL_RESERVED_210', + 'CB_PERF_SEL_RESERVED_211', 'CB_PERF_SEL_RESERVED_212', + 'CB_PERF_SEL_RESERVED_213', 'CB_PERF_SEL_RESERVED_214', + 'CB_PERF_SEL_RESERVED_215', 'CB_PERF_SEL_RESERVED_216', + 'CB_PERF_SEL_RESERVED_217', 'CB_PERF_SEL_RESERVED_218', + 'CB_PERF_SEL_RESERVED_219', 'CB_PERF_SEL_RESERVED_22', + 'CB_PERF_SEL_RESERVED_220', 'CB_PERF_SEL_RESERVED_221', + 'CB_PERF_SEL_RESERVED_222', 'CB_PERF_SEL_RESERVED_223', + 'CB_PERF_SEL_RESERVED_224', 'CB_PERF_SEL_RESERVED_225', + 'CB_PERF_SEL_RESERVED_226', 'CB_PERF_SEL_RESERVED_227', + 'CB_PERF_SEL_RESERVED_228', 'CB_PERF_SEL_RESERVED_229', + 'CB_PERF_SEL_RESERVED_23', 'CB_PERF_SEL_RESERVED_230', + 'CB_PERF_SEL_RESERVED_231', 'CB_PERF_SEL_RESERVED_232', + 'CB_PERF_SEL_RESERVED_233', 'CB_PERF_SEL_RESERVED_234', + 'CB_PERF_SEL_RESERVED_235', 'CB_PERF_SEL_RESERVED_236', + 'CB_PERF_SEL_RESERVED_237', 'CB_PERF_SEL_RESERVED_238', + 'CB_PERF_SEL_RESERVED_239', 'CB_PERF_SEL_RESERVED_24', + 'CB_PERF_SEL_RESERVED_240', 'CB_PERF_SEL_RESERVED_241', + 'CB_PERF_SEL_RESERVED_242', 'CB_PERF_SEL_RESERVED_243', + 'CB_PERF_SEL_RESERVED_244', 'CB_PERF_SEL_RESERVED_245', + 'CB_PERF_SEL_RESERVED_246', 'CB_PERF_SEL_RESERVED_247', + 'CB_PERF_SEL_RESERVED_248', 'CB_PERF_SEL_RESERVED_249', + 'CB_PERF_SEL_RESERVED_25', 'CB_PERF_SEL_RESERVED_259', + 'CB_PERF_SEL_RESERVED_26', 'CB_PERF_SEL_RESERVED_260', + 'CB_PERF_SEL_RESERVED_261', 'CB_PERF_SEL_RESERVED_262', + 'CB_PERF_SEL_RESERVED_263', 'CB_PERF_SEL_RESERVED_264', + 'CB_PERF_SEL_RESERVED_265', 'CB_PERF_SEL_RESERVED_266', + 'CB_PERF_SEL_RESERVED_267', 'CB_PERF_SEL_RESERVED_268', + 'CB_PERF_SEL_RESERVED_269', 'CB_PERF_SEL_RESERVED_27', + 'CB_PERF_SEL_RESERVED_270', 'CB_PERF_SEL_RESERVED_271', + 'CB_PERF_SEL_RESERVED_272', 'CB_PERF_SEL_RESERVED_273', + 'CB_PERF_SEL_RESERVED_274', 'CB_PERF_SEL_RESERVED_275', + 'CB_PERF_SEL_RESERVED_276', 'CB_PERF_SEL_RESERVED_277', + 'CB_PERF_SEL_RESERVED_278', 'CB_PERF_SEL_RESERVED_279', + 'CB_PERF_SEL_RESERVED_28', 'CB_PERF_SEL_RESERVED_280', + 'CB_PERF_SEL_RESERVED_281', 'CB_PERF_SEL_RESERVED_282', + 'CB_PERF_SEL_RESERVED_283', 'CB_PERF_SEL_RESERVED_284', + 'CB_PERF_SEL_RESERVED_285', 'CB_PERF_SEL_RESERVED_286', + 'CB_PERF_SEL_RESERVED_287', 'CB_PERF_SEL_RESERVED_288', + 'CB_PERF_SEL_RESERVED_289', 'CB_PERF_SEL_RESERVED_29', + 'CB_PERF_SEL_RESERVED_290', 'CB_PERF_SEL_RESERVED_291', + 'CB_PERF_SEL_RESERVED_292', 'CB_PERF_SEL_RESERVED_293', + 'CB_PERF_SEL_RESERVED_294', 'CB_PERF_SEL_RESERVED_295', + 'CB_PERF_SEL_RESERVED_296', 'CB_PERF_SEL_RESERVED_297', + 'CB_PERF_SEL_RESERVED_298', 'CB_PERF_SEL_RESERVED_299', + 'CB_PERF_SEL_RESERVED_303', 'CB_PERF_SEL_RESERVED_304', + 'CB_PERF_SEL_RESERVED_305', 'CB_PERF_SEL_RESERVED_306', + 'CB_PERF_SEL_RESERVED_307', 'CB_PERF_SEL_RESERVED_308', + 'CB_PERF_SEL_RESERVED_309', 'CB_PERF_SEL_RESERVED_310', + 'CB_PERF_SEL_RESERVED_311', 'CB_PERF_SEL_RESERVED_312', + 'CB_PERF_SEL_RESERVED_313', 'CB_PERF_SEL_RESERVED_314', + 'CB_PERF_SEL_RESERVED_315', 'CB_PERF_SEL_RESERVED_316', + 'CB_PERF_SEL_RESERVED_317', 'CB_PERF_SEL_RESERVED_318', + 'CB_PERF_SEL_RESERVED_319', 'CB_PERF_SEL_RESERVED_320', + 'CB_PERF_SEL_RESERVED_321', 'CB_PERF_SEL_RESERVED_322', + 'CB_PERF_SEL_RESERVED_323', 'CB_PERF_SEL_RESERVED_324', + 'CB_PERF_SEL_RESERVED_325', 'CB_PERF_SEL_RESERVED_326', + 'CB_PERF_SEL_RESERVED_327', 'CB_PERF_SEL_RESERVED_328', + 'CB_PERF_SEL_RESERVED_329', 'CB_PERF_SEL_RESERVED_330', + 'CB_PERF_SEL_RESERVED_331', 'CB_PERF_SEL_RESERVED_332', + 'CB_PERF_SEL_RESERVED_333', 'CB_PERF_SEL_RESERVED_334', + 'CB_PERF_SEL_RESERVED_335', 'CB_PERF_SEL_RESERVED_336', + 'CB_PERF_SEL_RESERVED_337', 'CB_PERF_SEL_RESERVED_338', + 'CB_PERF_SEL_RESERVED_339', 'CB_PERF_SEL_RESERVED_340', + 'CB_PERF_SEL_RESERVED_341', 'CB_PERF_SEL_RESERVED_342', + 'CB_PERF_SEL_RESERVED_343', 'CB_PERF_SEL_RESERVED_344', + 'CB_PERF_SEL_RESERVED_345', 'CB_PERF_SEL_RESERVED_346', + 'CB_PERF_SEL_RESERVED_347', 'CB_PERF_SEL_RESERVED_348', + 'CB_PERF_SEL_RESERVED_349', 'CB_PERF_SEL_RESERVED_350', + 'CB_PERF_SEL_RESERVED_351', 'CB_PERF_SEL_RESERVED_352', + 'CB_PERF_SEL_RESERVED_353', 'CB_PERF_SEL_RESERVED_354', + 'CB_PERF_SEL_RESERVED_355', 'CB_PERF_SEL_RESERVED_356', + 'CB_PERF_SEL_RESERVED_357', 'CB_PERF_SEL_RESERVED_358', + 'CB_PERF_SEL_RESERVED_359', 'CB_PERF_SEL_RESERVED_360', + 'CB_PERF_SEL_RESERVED_361', 'CB_PERF_SEL_RESERVED_362', + 'CB_PERF_SEL_RESERVED_363', 'CB_PERF_SEL_RESERVED_364', + 'CB_PERF_SEL_RESERVED_365', 'CB_PERF_SEL_RESERVED_366', + 'CB_PERF_SEL_RESERVED_367', 'CB_PERF_SEL_RESERVED_368', + 'CB_PERF_SEL_RESERVED_369', 'CB_PERF_SEL_RESERVED_370', + 'CB_PERF_SEL_RESERVED_371', 'CB_PERF_SEL_RESERVED_372', + 'CB_PERF_SEL_RESERVED_373', 'CB_PERF_SEL_RESERVED_374', + 'CB_PERF_SEL_RESERVED_375', 'CB_PERF_SEL_RESERVED_376', + 'CB_PERF_SEL_RESERVED_377', 'CB_PERF_SEL_RESERVED_378', + 'CB_PERF_SEL_RESERVED_379', 'CB_PERF_SEL_RESERVED_38', + 'CB_PERF_SEL_RESERVED_380', 'CB_PERF_SEL_RESERVED_381', + 'CB_PERF_SEL_RESERVED_382', 'CB_PERF_SEL_RESERVED_383', + 'CB_PERF_SEL_RESERVED_384', 'CB_PERF_SEL_RESERVED_385', + 'CB_PERF_SEL_RESERVED_386', 'CB_PERF_SEL_RESERVED_387', + 'CB_PERF_SEL_RESERVED_388', 'CB_PERF_SEL_RESERVED_389', + 'CB_PERF_SEL_RESERVED_39', 'CB_PERF_SEL_RESERVED_390', + 'CB_PERF_SEL_RESERVED_391', 'CB_PERF_SEL_RESERVED_392', + 'CB_PERF_SEL_RESERVED_393', 'CB_PERF_SEL_RESERVED_394', + 'CB_PERF_SEL_RESERVED_395', 'CB_PERF_SEL_RESERVED_396', + 'CB_PERF_SEL_RESERVED_397', 'CB_PERF_SEL_RESERVED_398', + 'CB_PERF_SEL_RESERVED_399', 'CB_PERF_SEL_RESERVED_40', + 'CB_PERF_SEL_RESERVED_400', 'CB_PERF_SEL_RESERVED_401', + 'CB_PERF_SEL_RESERVED_402', 'CB_PERF_SEL_RESERVED_403', + 'CB_PERF_SEL_RESERVED_404', 'CB_PERF_SEL_RESERVED_405', + 'CB_PERF_SEL_RESERVED_406', 'CB_PERF_SEL_RESERVED_407', + 'CB_PERF_SEL_RESERVED_408', 'CB_PERF_SEL_RESERVED_409', + 'CB_PERF_SEL_RESERVED_41', 'CB_PERF_SEL_RESERVED_410', + 'CB_PERF_SEL_RESERVED_411', 'CB_PERF_SEL_RESERVED_412', + 'CB_PERF_SEL_RESERVED_413', 'CB_PERF_SEL_RESERVED_414', + 'CB_PERF_SEL_RESERVED_415', 'CB_PERF_SEL_RESERVED_416', + 'CB_PERF_SEL_RESERVED_417', 'CB_PERF_SEL_RESERVED_418', + 'CB_PERF_SEL_RESERVED_419', 'CB_PERF_SEL_RESERVED_42', + 'CB_PERF_SEL_RESERVED_420', 'CB_PERF_SEL_RESERVED_421', + 'CB_PERF_SEL_RESERVED_422', 'CB_PERF_SEL_RESERVED_423', + 'CB_PERF_SEL_RESERVED_424', 'CB_PERF_SEL_RESERVED_425', + 'CB_PERF_SEL_RESERVED_426', 'CB_PERF_SEL_RESERVED_427', + 'CB_PERF_SEL_RESERVED_428', 'CB_PERF_SEL_RESERVED_429', + 'CB_PERF_SEL_RESERVED_43', 'CB_PERF_SEL_RESERVED_430', + 'CB_PERF_SEL_RESERVED_431', 'CB_PERF_SEL_RESERVED_432', + 'CB_PERF_SEL_RESERVED_433', 'CB_PERF_SEL_RESERVED_434', + 'CB_PERF_SEL_RESERVED_435', 'CB_PERF_SEL_RESERVED_436', + 'CB_PERF_SEL_RESERVED_437', 'CB_PERF_SEL_RESERVED_438', + 'CB_PERF_SEL_RESERVED_439', 'CB_PERF_SEL_RESERVED_44', + 'CB_PERF_SEL_RESERVED_440', 'CB_PERF_SEL_RESERVED_441', + 'CB_PERF_SEL_RESERVED_442', 'CB_PERF_SEL_RESERVED_443', + 'CB_PERF_SEL_RESERVED_444', 'CB_PERF_SEL_RESERVED_445', + 'CB_PERF_SEL_RESERVED_446', 'CB_PERF_SEL_RESERVED_447', + 'CB_PERF_SEL_RESERVED_448', 'CB_PERF_SEL_RESERVED_449', + 'CB_PERF_SEL_RESERVED_45', 'CB_PERF_SEL_RESERVED_450', + 'CB_PERF_SEL_RESERVED_451', 'CB_PERF_SEL_RESERVED_452', + 'CB_PERF_SEL_RESERVED_453', 'CB_PERF_SEL_RESERVED_454', + 'CB_PERF_SEL_RESERVED_455', 'CB_PERF_SEL_RESERVED_456', + 'CB_PERF_SEL_RESERVED_457', 'CB_PERF_SEL_RESERVED_458', + 'CB_PERF_SEL_RESERVED_459', 'CB_PERF_SEL_RESERVED_46', + 'CB_PERF_SEL_RESERVED_460', 'CB_PERF_SEL_RESERVED_461', + 'CB_PERF_SEL_RESERVED_462', 'CB_PERF_SEL_RESERVED_463', + 'CB_PERF_SEL_RESERVED_464', 'CB_PERF_SEL_RESERVED_465', + 'CB_PERF_SEL_RESERVED_47', 'CB_PERF_SEL_RESERVED_48', + 'CB_PERF_SEL_RESERVED_49', 'CB_PERF_SEL_RESERVED_65', + 'CB_PERF_SEL_RESERVED_66', 'CB_PERF_SEL_RESERVED_67', + 'CB_PERF_SEL_RESERVED_68', 'CB_PERF_SEL_RESERVED_69', + 'CB_PERF_SEL_RESERVED_70', 'CB_PERF_SEL_RESERVED_71', + 'CB_PERF_SEL_RESERVED_72', 'CB_PERF_SEL_RESERVED_73', + 'CB_PERF_SEL_RESERVED_74', 'CB_PERF_SEL_RESERVED_75', + 'CB_PERF_SEL_RESERVED_76', 'CB_PERF_SEL_RESERVED_77', + 'CB_PERF_SEL_RESERVED_78', 'CB_PERF_SEL_RESERVED_79', + 'CB_PERF_SEL_RESERVED_80', 'CB_PERF_SEL_RESERVED_81', + 'CB_PERF_SEL_RESERVED_82', 'CB_PERF_SEL_RESERVED_83', + 'CB_PERF_SEL_RESERVED_84', 'CB_PERF_SEL_RESERVED_85', + 'CB_PERF_SEL_RESERVED_86', 'CB_PERF_SEL_RESERVED_87', + 'CB_PERF_SEL_RESERVED_88', 'CB_PERF_SEL_RESERVED_89', + 'CB_PERF_SEL_RESERVED_90', 'CB_PERF_SEL_RESERVED_91', + 'CB_PERF_SEL_RESERVED_92', 'CB_PERF_SEL_RESERVED_93', + 'CB_PERF_SEL_RESERVED_94', 'CB_PERF_SEL_RESERVED_95', + 'CB_PERF_SEL_RESERVED_96', 'CB_PERF_SEL_RESERVED_97', + 'CB_PERF_SEL_RESERVED_98', 'CB_PERF_SEL_RESERVED_99', + 'CB_PERF_SEL_STATIC_CLOCK_EN', 'CB_RESERVED', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 'CENTERS_ONLY', 'CENTROIDS_AND_CENTERS', 'CENTROIDS_ONLY', + 'CHA_PERF_SEL', 'CHA_PERF_SEL_ARB_REQUESTS', 'CHA_PERF_SEL_BUSY', + 'CHA_PERF_SEL_CYCLE', 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 'CHA_PERF_SEL_IO_32B_WDS_CHC1', 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 'CHA_PERF_SEL_IO_32B_WDS_CHC3', 'CHA_PERF_SEL_IO_32B_WDS_CHC4', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC4', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC4', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC4', 'CHA_PERF_SEL_REQUEST_CHC0', + 'CHA_PERF_SEL_REQUEST_CHC1', 'CHA_PERF_SEL_REQUEST_CHC2', + 'CHA_PERF_SEL_REQUEST_CHC3', 'CHA_PERF_SEL_REQUEST_CHC4', + 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', 'CHA_PERF_SEL_STALL_CHC0', + 'CHA_PERF_SEL_STALL_CHC1', 'CHA_PERF_SEL_STALL_CHC2', + 'CHA_PERF_SEL_STALL_CHC3', 'CHA_PERF_SEL_STALL_CHC4', + 'CHA_PERF_SEL_STALL_CHC5', 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC4', 'CHCG_PERF_SEL', + 'CHCG_PERF_SEL_ARB_RET_LEVEL', 'CHCG_PERF_SEL_BUSY', + 'CHCG_PERF_SEL_CYCLE', 'CHCG_PERF_SEL_GL2_REQ_READ_LATENCY', + 'CHCG_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'CHCG_PERF_SEL_REQ', + 'CHCG_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'CHCG_PERF_SEL_REQ_ATOMIC_WITH_RET', 'CHCG_PERF_SEL_REQ_CLIENT0', + 'CHCG_PERF_SEL_REQ_CLIENT1', 'CHCG_PERF_SEL_REQ_CLIENT10', + 'CHCG_PERF_SEL_REQ_CLIENT11', 'CHCG_PERF_SEL_REQ_CLIENT12', + 'CHCG_PERF_SEL_REQ_CLIENT13', 'CHCG_PERF_SEL_REQ_CLIENT14', + 'CHCG_PERF_SEL_REQ_CLIENT15', 'CHCG_PERF_SEL_REQ_CLIENT16', + 'CHCG_PERF_SEL_REQ_CLIENT17', 'CHCG_PERF_SEL_REQ_CLIENT18', + 'CHCG_PERF_SEL_REQ_CLIENT19', 'CHCG_PERF_SEL_REQ_CLIENT2', + 'CHCG_PERF_SEL_REQ_CLIENT20', 'CHCG_PERF_SEL_REQ_CLIENT21', + 'CHCG_PERF_SEL_REQ_CLIENT22', 'CHCG_PERF_SEL_REQ_CLIENT23', + 'CHCG_PERF_SEL_REQ_CLIENT3', 'CHCG_PERF_SEL_REQ_CLIENT4', + 'CHCG_PERF_SEL_REQ_CLIENT5', 'CHCG_PERF_SEL_REQ_CLIENT6', + 'CHCG_PERF_SEL_REQ_CLIENT7', 'CHCG_PERF_SEL_REQ_CLIENT8', + 'CHCG_PERF_SEL_REQ_CLIENT9', 'CHCG_PERF_SEL_REQ_NOP_ACK', + 'CHCG_PERF_SEL_REQ_NOP_RTN0', 'CHCG_PERF_SEL_REQ_READ', + 'CHCG_PERF_SEL_REQ_READ_128B', 'CHCG_PERF_SEL_REQ_READ_32B', + 'CHCG_PERF_SEL_REQ_READ_64B', 'CHCG_PERF_SEL_REQ_WRITE', + 'CHCG_PERF_SEL_REQ_WRITE_32B', 'CHCG_PERF_SEL_REQ_WRITE_64B', + 'CHCG_PERF_SEL_STALL_BUFFER_FULL', 'CHCG_PERF_SEL_STALL_GUS_GL1', + 'CHCG_PERF_SEL_STARVE', 'CHC_PERF_SEL', + 'CHC_PERF_SEL_ARB_RET_LEVEL', 'CHC_PERF_SEL_BUSY', + 'CHC_PERF_SEL_CYCLE', 'CHC_PERF_SEL_GL2_REQ_READ_LATENCY', + 'CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'CHC_PERF_SEL_REQ', + 'CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'CHC_PERF_SEL_REQ_ATOMIC_WITH_RET', 'CHC_PERF_SEL_REQ_CLIENT0', + 'CHC_PERF_SEL_REQ_CLIENT1', 'CHC_PERF_SEL_REQ_CLIENT10', + 'CHC_PERF_SEL_REQ_CLIENT11', 'CHC_PERF_SEL_REQ_CLIENT12', + 'CHC_PERF_SEL_REQ_CLIENT13', 'CHC_PERF_SEL_REQ_CLIENT14', + 'CHC_PERF_SEL_REQ_CLIENT15', 'CHC_PERF_SEL_REQ_CLIENT16', + 'CHC_PERF_SEL_REQ_CLIENT17', 'CHC_PERF_SEL_REQ_CLIENT18', + 'CHC_PERF_SEL_REQ_CLIENT19', 'CHC_PERF_SEL_REQ_CLIENT2', + 'CHC_PERF_SEL_REQ_CLIENT20', 'CHC_PERF_SEL_REQ_CLIENT21', + 'CHC_PERF_SEL_REQ_CLIENT22', 'CHC_PERF_SEL_REQ_CLIENT23', + 'CHC_PERF_SEL_REQ_CLIENT3', 'CHC_PERF_SEL_REQ_CLIENT4', + 'CHC_PERF_SEL_REQ_CLIENT5', 'CHC_PERF_SEL_REQ_CLIENT6', + 'CHC_PERF_SEL_REQ_CLIENT7', 'CHC_PERF_SEL_REQ_CLIENT8', + 'CHC_PERF_SEL_REQ_CLIENT9', 'CHC_PERF_SEL_REQ_NOP_ACK', + 'CHC_PERF_SEL_REQ_NOP_RTN0', 'CHC_PERF_SEL_REQ_READ', + 'CHC_PERF_SEL_REQ_READ_128B', 'CHC_PERF_SEL_REQ_READ_32B', + 'CHC_PERF_SEL_REQ_READ_64B', 'CHC_PERF_SEL_REQ_WRITE', + 'CHC_PERF_SEL_REQ_WRITE_32B', 'CHC_PERF_SEL_REQ_WRITE_64B', + 'CHC_PERF_SEL_STALL_BUFFER_FULL', 'CHC_PERF_SEL_STALL_GL2_GL1', + 'CHC_PERF_SEL_STARVE', 'CHUNK_SIZE', 'CHUNK_SIZE_16KB', + 'CHUNK_SIZE_1KB', 'CHUNK_SIZE_2KB', 'CHUNK_SIZE_32KB', + 'CHUNK_SIZE_4KB', 'CHUNK_SIZE_64KB', 'CHUNK_SIZE_8KB', + 'CLEAR_SMU_INTR', 'CLKGATE_BASE_MODE', 'CLKGATE_SM_MODE', + 'CLOCK_BRANCH_SOFT_RESET', 'CLOCK_BRANCH_SOFT_RESET_FORCE', + 'CLOCK_BRANCH_SOFT_RESET_NOOP', 'CLOCK_GATING_DISABLE', + 'CLOCK_GATING_DISABLED', 'CLOCK_GATING_DISABLED_IN_DCO', + 'CLOCK_GATING_DISABLE_ENUM', 'CLOCK_GATING_DISABLE_ENUM_DISABLED', + 'CLOCK_GATING_DISABLE_ENUM_ENABLED', 'CLOCK_GATING_EN', + 'CLOCK_GATING_ENABLE', 'CLOCK_GATING_ENABLED', + 'CLOCK_GATING_ENABLED_IN_DCO', 'CMASK_CLR00_F0', 'CMASK_CLR00_F1', + 'CMASK_CLR00_F2', 'CMASK_CLR00_FX', 'CMASK_CLR01_F0', + 'CMASK_CLR01_F1', 'CMASK_CLR01_F2', 'CMASK_CLR01_FX', + 'CMASK_CLR10_F0', 'CMASK_CLR10_F1', 'CMASK_CLR10_F2', + 'CMASK_CLR10_FX', 'CMASK_CLR11_F0', 'CMASK_CLR11_F1', + 'CMASK_CLR11_F2', 'CMASK_CLR11_FX', 'CMC_3DLUT_17CUBE', + 'CMC_3DLUT_30BIT', 'CMC_3DLUT_30BIT_ENUM', 'CMC_3DLUT_36BIT', + 'CMC_3DLUT_9CUBE', 'CMC_3DLUT_RAM_SEL', 'CMC_3DLUT_SIZE_ENUM', + 'CMC_LUT_2CFG_MEMORY_A', 'CMC_LUT_2CFG_MEMORY_B', + 'CMC_LUT_2CFG_NO_MEMORY', 'CMC_LUT_2_CONFIG_ENUM', + 'CMC_LUT_2_MODE_BYPASS', 'CMC_LUT_2_MODE_ENUM', + 'CMC_LUT_2_MODE_RAMA_LUT', 'CMC_LUT_2_MODE_RAMB_LUT', + 'CMC_LUT_NUM_SEG', 'CMC_LUT_RAM_SEL', 'CMC_RAM0_ACCESS', + 'CMC_RAM1_ACCESS', 'CMC_RAM2_ACCESS', 'CMC_RAM3_ACCESS', + 'CMC_RAMA_ACCESS', 'CMC_RAMB_ACCESS', 'CMC_SEGMENTS_1', + 'CMC_SEGMENTS_128', 'CMC_SEGMENTS_16', 'CMC_SEGMENTS_2', + 'CMC_SEGMENTS_32', 'CMC_SEGMENTS_4', 'CMC_SEGMENTS_64', + 'CMC_SEGMENTS_8', 'CMPTO', 'CM_BYPASS', 'CM_COEF_FORMAT_ENUM', + 'CM_DATA_SIGNED', 'CM_DISABLE', 'CM_EN', 'CM_ENABLE', + 'CM_GAMMA_LUT_MODE_ENUM', 'CM_GAMMA_LUT_PWL_DISABLE_ENUM', + 'CM_GAMMA_LUT_SEL_ENUM', 'CM_GAMUT_REMAP_MODE_ENUM', + 'CM_LUT_2_CONFIG_ENUM', 'CM_LUT_2_MODE_ENUM', + 'CM_LUT_4_CONFIG_ENUM', 'CM_LUT_4_MODE_ENUM', + 'CM_LUT_CONFIG_MODE', 'CM_LUT_NUM_SEG', 'CM_LUT_RAM_SEL', + 'CM_LUT_READ_COLOR_SEL', 'CM_LUT_READ_DBG', 'CM_NOT_PENDING', + 'CM_PENDING', 'CM_POST_CSC_MODE_ENUM', 'CM_WRITE_BASE_ONLY', + 'CM_YES_PENDING', 'CNVC_BYPASS', 'CNVC_BYPASS_DISABLE', + 'CNVC_BYPASS_EN', 'CNVC_COEF_FORMAT_ENUM', 'CNVC_DIS', 'CNVC_EN', + 'CNVC_ENABLE', 'CNVC_FIX_S2_13', 'CNVC_FIX_S3_12', + 'CNVC_NOT_PENDING', 'CNVC_PENDING', 'CNVC_ROUND', 'CNVC_TRUNCATE', + 'CNVC_YES_PENDING', 'COEF_POST_CSC', 'COEF_POST_CSC_B', + 'COEF_RAM_SELECT_BACK', 'COEF_RAM_SELECT_CURRENT', + 'COEF_RAM_SELECT_RD', 'COLOR_24BIT_1BIT_AND', + 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', 'COLOR_64BIT_FP_PREMULT', + 'COLOR_64BIT_FP_UNPREMULT', 'COLOR_KEYER_MODE', + 'COMB_DST_MINUS_SRC', 'COMB_DST_PLUS_SRC', 'COMB_MAX_DST_SRC', + 'COMB_MIN_DST_SRC', 'COMB_SRC_MINUS_DST', 'COMPAT_LEVEL', + 'CONFIG_SPACE1_END', 'CONFIG_SPACE1_START', 'CONFIG_SPACE2_END', + 'CONFIG_SPACE2_START', 'CONFIG_SPACE_END', 'CONFIG_SPACE_START', + 'CONTEXT_DONE', 'CONTEXT_SPACE_END', 'CONTEXT_SPACE_START', + 'CONTEXT_SUSPEND', 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', + 'CORB_READ_POINTER_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', 'COUNTER_RING_0', + 'COUNTER_RING_1', 'COUNTER_RING_SPLIT', 'CPC_LATENCY_STATS_SEL', + 'CPC_LATENCY_STATS_SEL_INVAL_LAST', + 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 'CPC_LATENCY_STATS_SEL_XNACK_MIN', 'CPC_PERFCOUNT_SEL', + 'CPC_PERF_SEL_ALWAYS_COUNT', 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 'CPC_PERF_SEL_CPC_GCRIU_IDLE', 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 'CPC_PERF_SEL_CPC_STAT_BUSY', 'CPC_PERF_SEL_CPC_STAT_IDLE', + 'CPC_PERF_SEL_CPC_STAT_STALL', 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 'CPC_PERF_SEL_CPC_TCIU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_GUS_WRITE', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_GUS_WRITE', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', 'CPC_PERF_SEL_MES_THREAD0', + 'CPC_PERF_SEL_MES_THREAD1', + 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPC_TAG_RAM', + 'CPF_LATENCY_STATS_SEL', 'CPF_LATENCY_STATS_SEL_INVAL_LAST', + 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 'CPF_LATENCY_STATS_SEL_READ_LAST', + 'CPF_LATENCY_STATS_SEL_READ_MAX', + 'CPF_LATENCY_STATS_SEL_READ_MIN', + 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 'CPF_LATENCY_STATS_SEL_XNACK_MIN', 'CPF_PERFCOUNTWINDOW_SEL', + 'CPF_PERFCOUNT_SEL', 'CPF_PERFWINDOW_SEL_CSF', + 'CPF_PERFWINDOW_SEL_HQD1', 'CPF_PERFWINDOW_SEL_HQD2', + 'CPF_PERFWINDOW_SEL_RDMA', 'CPF_PERFWINDOW_SEL_RWPP', + 'CPF_PERF_SEL_ALWAYS_COUNT', + 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_CPF_GCRIU_BUSY', 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 'CPF_PERF_SEL_CPF_GCRIU_STALL', 'CPF_PERF_SEL_CPF_STAT_BUSY', + 'CPF_PERF_SEL_CPF_STAT_IDLE', 'CPF_PERF_SEL_CPF_STAT_STALL', + 'CPF_PERF_SEL_CPF_TCIU_BUSY', 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 'CPF_PERF_SEL_CPF_TCIU_STALL', 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', + 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE', + 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ', + 'CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY', + 'CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE', + 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 'CPF_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 'CPF_SCRATCH_REG_ATOMIC_ADD', 'CPF_SCRATCH_REG_ATOMIC_AND', + 'CPF_SCRATCH_REG_ATOMIC_CMPSWAP', 'CPF_SCRATCH_REG_ATOMIC_MAX', + 'CPF_SCRATCH_REG_ATOMIC_MIN', 'CPF_SCRATCH_REG_ATOMIC_NOT', + 'CPF_SCRATCH_REG_ATOMIC_OP', 'CPF_SCRATCH_REG_ATOMIC_OR', + 'CPF_SCRATCH_REG_ATOMIC_SUB', 'CPF_TAG_RAM', + 'CPG_LATENCY_STATS_SEL', 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 'CPG_LATENCY_STATS_SEL_INVAL_LAST', + 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 'CPG_LATENCY_STATS_SEL_READ_LAST', + 'CPG_LATENCY_STATS_SEL_READ_MAX', + 'CPG_LATENCY_STATS_SEL_READ_MIN', + 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 'CPG_LATENCY_STATS_SEL_XNACK_MIN', 'CPG_PERFCOUNTWINDOW_SEL', + 'CPG_PERFCOUNT_SEL', 'CPG_PERFWINDOW_SEL_APPEND', + 'CPG_PERFWINDOW_SEL_CE', 'CPG_PERFWINDOW_SEL_CEDMA', + 'CPG_PERFWINDOW_SEL_CPC_IC', 'CPG_PERFWINDOW_SEL_CPG_IC', + 'CPG_PERFWINDOW_SEL_DDID', 'CPG_PERFWINDOW_SEL_DFY', + 'CPG_PERFWINDOW_SEL_DMA', 'CPG_PERFWINDOW_SEL_ME', + 'CPG_PERFWINDOW_SEL_MEC1', 'CPG_PERFWINDOW_SEL_MEC2', + 'CPG_PERFWINDOW_SEL_MEMRD', 'CPG_PERFWINDOW_SEL_MEMWR', + 'CPG_PERFWINDOW_SEL_MES', 'CPG_PERFWINDOW_SEL_PFP', + 'CPG_PERFWINDOW_SEL_PQ1', 'CPG_PERFWINDOW_SEL_PQ2', + 'CPG_PERFWINDOW_SEL_PQ3', 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', 'CPG_PERFWINDOW_SEL_QURD', + 'CPG_PERFWINDOW_SEL_QU_EOP', 'CPG_PERFWINDOW_SEL_QU_PIPE', + 'CPG_PERFWINDOW_SEL_QU_STRM', 'CPG_PERFWINDOW_SEL_RB', + 'CPG_PERFWINDOW_SEL_RESERVED1', 'CPG_PERFWINDOW_SEL_RESERVED2', + 'CPG_PERFWINDOW_SEL_SHADOW', 'CPG_PERFWINDOW_SEL_SR', + 'CPG_PERFWINDOW_SEL_VGT0', 'CPG_PERFWINDOW_SEL_VGT1', + 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', 'CPG_PERF_SEL_ALWAYS_COUNT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 'CPG_PERF_SEL_CPG_GCRIU_IDLE', 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 'CPG_PERF_SEL_CPG_STAT_BUSY', 'CPG_PERF_SEL_CPG_STAT_IDLE', + 'CPG_PERF_SEL_CPG_STAT_STALL', 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 'CPG_PERF_SEL_CPG_TCIU_IDLE', 'CPG_PERF_SEL_CPG_TCIU_STALL', + 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', + 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', + 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_DMA_BUSY', + 'CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL', + 'CPG_PERF_SEL_DMA_STALLED', 'CPG_PERF_SEL_DMA_STARVED', + 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', 'CPG_PERF_SEL_ME_PARSER_BUSY', + 'CPG_PERF_SEL_ME_PWS_STALLED0', 'CPG_PERF_SEL_ME_PWS_STALLED1', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', + 'CPG_PERF_SEL_PFP_PWS_STALLED0', 'CPG_PERF_SEL_PFP_PWS_STALLED1', + 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPG_TAG_RAM', + 'CP_ALPHA_TAG_RAM_SEL', 'CP_DDID_CNTL_MODE', 'CP_DDID_CNTL_SIZE', + 'CP_DDID_CNTL_VMID_SEL', 'CP_ME_ID', 'CP_PERFMON_ENABLE_MODE', + 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 'CP_PERFMON_ENABLE_MODE_RESERVED_1', 'CP_PERFMON_STATE', + 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'CP_PERFMON_STATE_RESERVED_3', 'CP_PERFMON_STATE_START_COUNTING', + 'CP_PERFMON_STATE_STOP_COUNTING', 'CP_PIPE_ID', 'CP_RING_ID', + 'CRC_CUR_0', 'CRC_CUR_1', 'CRC_CUR_SEL', 'CRC_INTERLACE_0', + 'CRC_INTERLACE_1', 'CRC_INTERLACE_2', 'CRC_INTERLACE_3', + 'CRC_INTERLACE_SEL', 'CRC_IN_CUR_0', 'CRC_IN_CUR_1', + 'CRC_IN_CUR_2', 'CRC_IN_CUR_3', 'CRC_IN_CUR_SEL', 'CRC_IN_PIX_0', + 'CRC_IN_PIX_1', 'CRC_IN_PIX_2', 'CRC_IN_PIX_3', 'CRC_IN_PIX_4', + 'CRC_IN_PIX_5', 'CRC_IN_PIX_6', 'CRC_IN_PIX_7', 'CRC_IN_PIX_SEL', + 'CRC_SRC_0', 'CRC_SRC_1', 'CRC_SRC_2', 'CRC_SRC_3', 'CRC_SRC_SEL', + 'CRC_STEREO_0', 'CRC_STEREO_1', 'CRC_STEREO_2', 'CRC_STEREO_3', + 'CRC_STEREO_SEL', 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'CROB_MEM_PWR_LIGHT_SLEEP_MODE', 'CROSSBAR_FOR_ALPHA', + 'CROSSBAR_FOR_CB_B', 'CROSSBAR_FOR_CR_R', 'CROSSBAR_FOR_Y_G', + 'CRS', 'CR_R_DATA_ONTO_ALPHA_PORT', 'CR_R_DATA_ONTO_CB_B_PORT', + 'CR_R_DATA_ONTO_CR_R_PORT', 'CR_R_DATA_ONTO_Y_G_PORT', + 'CSCNTL_ADDR_WIDTH', 'CSCNTL_DATA_WIDTH', 'CSCNTL_TYPE', + 'CSCNTL_TYPE_EVENT', 'CSCNTL_TYPE_PRIVATE', 'CSCNTL_TYPE_STATE', + 'CSCNTL_TYPE_TG', 'CSCNTL_TYPE_WIDTH', 'CSDATA_ADDR_WIDTH', + 'CSDATA_DATA_WIDTH', 'CSDATA_TYPE', 'CSDATA_TYPE_EVENT', + 'CSDATA_TYPE_PRIVATE', 'CSDATA_TYPE_STATE', 'CSDATA_TYPE_TG', + 'CSDATA_TYPE_WIDTH', 'CS_CONTEXT_DONE', 'CS_DONE', 'CS_NA', + 'CS_PARTIAL_FLUSH', 'CS_STAGE_ON', 'CURSOR_2X_MAGNIFY', + 'CURSOR_2X_MAGNIFY_IS_DISABLE', 'CURSOR_2X_MAGNIFY_IS_ENABLE', + 'CURSOR_COLOR_24BIT_1BIT_AND', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 'CURSOR_COLOR_64BIT_FP_PREMULT', + 'CURSOR_COLOR_64BIT_FP_UNPREMULT', 'CURSOR_ENABLE', + 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', + 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', 'CURSOR_IS_DISABLE', + 'CURSOR_IS_ENABLE', 'CURSOR_IS_NOT_SNOOP', 'CURSOR_IS_SNOOP', + 'CURSOR_LINES_PER_CHUNK', 'CURSOR_LINE_PER_CHUNK_1', + 'CURSOR_LINE_PER_CHUNK_16', 'CURSOR_LINE_PER_CHUNK_2', + 'CURSOR_LINE_PER_CHUNK_4', 'CURSOR_LINE_PER_CHUNK_8', + 'CURSOR_MODE', 'CURSOR_MONO_2BIT', + 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_EN', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_SEL', 'CURSOR_PITCH', + 'CURSOR_PITCH_128_PIXELS', 'CURSOR_PITCH_256_PIXELS', + 'CURSOR_PITCH_64_PIXELS', 'CURSOR_REQUEST_EARLY', + 'CURSOR_REQUEST_NORMALLY', 'CURSOR_REQ_MODE', 'CURSOR_SNOOP', + 'CURSOR_STEREO_EN', 'CURSOR_STEREO_IS_DISABLED', + 'CURSOR_STEREO_IS_ENABLED', 'CURSOR_SURFACE_IS_NOT_TMZ', + 'CURSOR_SURFACE_IS_TMZ', 'CURSOR_SURFACE_TMZ', 'CURSOR_SYSTEM', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', + 'CUR_CLAMP_DIS', 'CUR_CLAMP_EN', 'CUR_DIS', + 'CUR_DYNAMIC_EXPANSION', 'CUR_EN', 'CUR_ENABLE', + 'CUR_EXPAND_MODE', 'CUR_FP_NO_ROM', 'CUR_FP_USE_ROM', + 'CUR_INV_CLAMP', 'CUR_MODE', 'CUR_NOT_PENDING', 'CUR_PENDING', + 'CUR_ROM_EN', 'CUR_YES_PENDING', 'CUR_ZERO_EXPANSION', + 'CbYCrY10101010_422_PACKED', 'CbYCrY12121212_422_PACKED', + 'CbYCrY8888_422_PACKED', 'CmaskCode', 'CombFunc', 'CompareFrag', + 'ConservativeZExport', 'CovToShaderSel', 'CrYCbA1010102', + 'CrYCbA16161616_10LSB', 'CrYCbA16161616_10MSB', + 'CrYCbA16161616_12LSB', 'CrYCbA16161616_12MSB', 'CrYCbA8888', + 'CrYCbY10101010_422_PACKED', 'CrYCbY12121212_422_PACKED', + 'CrYCbY8888_422_PACKED', 'DAC_MUX_SELECT', 'DAC_MUX_SELECT_DACA', + 'DAC_MUX_SELECT_DACB', 'DB_BREAK_BATCH_EVENT', 'DB_CACHE_FLUSH', + 'DB_CACHE_FLUSH_AND_INV', 'DB_CACHE_FLUSH_AND_INV_EVENT', + 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', 'DB_CACHE_FLUSH_TS', + 'DB_CONTEXT_DONE_EVENT', 'DB_CONTEXT_SUSPEND_EVENT', + 'DB_FLUSH_AND_INV_DB_DATA_TS', 'DB_FLUSH_AND_INV_DB_META', + 'DB_INVOKE_CHANGE_EVENT', 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 'DB_PERF_SEL_CB_DB_rdreq_sends', + 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 'DB_PERF_SEL_CB_DB_wrreq_sends', + 'DB_PERF_SEL_DB_CB_context_dones', 'DB_PERF_SEL_DB_CB_eop_dones', + 'DB_PERF_SEL_DB_CB_lquad_busy', + 'DB_PERF_SEL_DB_CB_lquad_double_format', + 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_float_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_signed_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_16_16_unsigned_8pix', + 'DB_PERF_SEL_DB_CB_lquad_fmt_32bpp_8pix', + 'DB_PERF_SEL_DB_CB_lquad_num_pixels_need_blending', + 'DB_PERF_SEL_DB_CB_lquad_quads', + 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x1', + 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_1x2', + 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x1', + 'DB_PERF_SEL_DB_CB_lquad_quads_vrs_rate_2x2', + 'DB_PERF_SEL_DB_CB_lquad_sends', + 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 'DB_PERF_SEL_DB_CB_lquad_stalls', 'DB_PERF_SEL_DB_CB_rdret_ack', + 'DB_PERF_SEL_DB_CB_rdret_nack', 'DB_PERF_SEL_DB_CB_tile_busy', + 'DB_PERF_SEL_DB_CB_tile_is_event_BOTTOM_OF_PIPE_TS', + 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 'DB_PERF_SEL_DB_CB_tile_is_event_FLUSH_AND_INV_DB_DATA_TS', + 'DB_PERF_SEL_DB_CB_tile_sends', 'DB_PERF_SEL_DB_CB_tile_stalls', + 'DB_PERF_SEL_DB_CB_tile_waiting_for_perfcounter_stop_event', + 'DB_PERF_SEL_DB_CB_wrret_ack', 'DB_PERF_SEL_DB_CB_wrret_nack', + 'DB_PERF_SEL_DB_SC_c_tile_rate', 'DB_PERF_SEL_DB_SC_quad_busy', + 'DB_PERF_SEL_DB_SC_quad_double_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_noz_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 'DB_PERF_SEL_DB_SC_quad_noz_tiles', + 'DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 'DB_PERF_SEL_DB_SC_quad_sends', 'DB_PERF_SEL_DB_SC_quad_stalls', + 'DB_PERF_SEL_DB_SC_quad_tiles', 'DB_PERF_SEL_DB_SC_s_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_busy', 'DB_PERF_SEL_DB_SC_tile_culled', + 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 'DB_PERF_SEL_DB_SC_tile_no_ops', 'DB_PERF_SEL_DB_SC_tile_sends', + 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 'DB_PERF_SEL_DB_SC_tile_stalls', + 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_tiles', 'DB_PERF_SEL_DB_SC_z_tile_rate', + 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 'DB_PERF_SEL_Depth_Tile_Cache_event', + 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 'DB_PERF_SEL_Op_Pipe_Busy', 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 'DB_PERF_SEL_Op_Pipe_Postz_Busy', 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 'DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits', + 'DB_PERF_SEL_Plane_Cache_flushes', + 'DB_PERF_SEL_Plane_Cache_frees', 'DB_PERF_SEL_Plane_Cache_hits', + 'DB_PERF_SEL_Plane_Cache_misses', + 'DB_PERF_SEL_Plane_Cache_starves', + 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 'DB_PERF_SEL_PostZ_Samples_failing_S', + 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 'DB_PERF_SEL_PreZ_Samples_failing_S', + 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 'DB_PERF_SEL_RMI_rd_s_32byte_req', + 'DB_PERF_SEL_RMI_rd_s_32byte_ret', + 'DB_PERF_SEL_RMI_rd_tile_32byte_req', + 'DB_PERF_SEL_RMI_rd_tile_32byte_ret', + 'DB_PERF_SEL_RMI_rd_z_32byte_req', + 'DB_PERF_SEL_RMI_rd_z_32byte_ret', + 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack', + 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_req', + 'DB_PERF_SEL_RMI_wr_s_32byte_ack', + 'DB_PERF_SEL_RMI_wr_s_32byte_req', + 'DB_PERF_SEL_RMI_wr_tile_32byte_ack', + 'DB_PERF_SEL_RMI_wr_tile_32byte_req', + 'DB_PERF_SEL_RMI_wr_z_32byte_ack', + 'DB_PERF_SEL_RMI_wr_z_32byte_req', 'DB_PERF_SEL_SC_DB_quad_busy', + 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 'DB_PERF_SEL_SC_DB_quad_pixels', 'DB_PERF_SEL_SC_DB_quad_quads', + 'DB_PERF_SEL_SC_DB_quad_quads_pipe0', + 'DB_PERF_SEL_SC_DB_quad_quads_pipe1', + 'DB_PERF_SEL_SC_DB_quad_sends', 'DB_PERF_SEL_SC_DB_quad_squads', + 'DB_PERF_SEL_SC_DB_quad_tiles', 'DB_PERF_SEL_SC_DB_tile_backface', + 'DB_PERF_SEL_SC_DB_tile_busy', 'DB_PERF_SEL_SC_DB_tile_covered', + 'DB_PERF_SEL_SC_DB_tile_events', 'DB_PERF_SEL_SC_DB_tile_sends', + 'DB_PERF_SEL_SC_DB_tile_stalls', 'DB_PERF_SEL_SC_DB_tile_tiles', + 'DB_PERF_SEL_SC_DB_tile_tiles_pipe0', + 'DB_PERF_SEL_SC_DB_tile_tiles_pipe1', + 'DB_PERF_SEL_SH_quads_outstanding_sum', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 'DB_PERF_SEL_SX_DB_quad_busy', + 'DB_PERF_SEL_SX_DB_quad_double_format', + 'DB_PERF_SEL_SX_DB_quad_export_quads', + 'DB_PERF_SEL_SX_DB_quad_exports', + 'DB_PERF_SEL_SX_DB_quad_fast_format', + 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 'DB_PERF_SEL_SX_DB_quad_pixels', 'DB_PERF_SEL_SX_DB_quad_quads', + 'DB_PERF_SEL_SX_DB_quad_sends', + 'DB_PERF_SEL_SX_DB_quad_slow_format', + 'DB_PERF_SEL_SX_DB_quad_stalls', + 'DB_PERF_SEL_Stencil_Cache_flushes', + 'DB_PERF_SEL_Stencil_Cache_frees', + 'DB_PERF_SEL_Stencil_Cache_hits', + 'DB_PERF_SEL_Stencil_Cache_misses', + 'DB_PERF_SEL_Stencil_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_flushes', 'DB_PERF_SEL_Tile_Cache_hits', + 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Tile_Cache_misses', 'DB_PERF_SEL_Tile_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_surface_stall', + 'DB_PERF_SEL_Z_Cache_frees', 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 'DB_PERF_SEL_Z_Cache_pmask_hits', + 'DB_PERF_SEL_Z_Cache_pmask_misses', + 'DB_PERF_SEL_Z_Cache_pmask_starves', + 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 'DB_PERF_SEL_clock_main_active', + 'DB_PERF_SEL_clock_mem_export_active', + 'DB_PERF_SEL_clock_reg_active', + 'DB_PERF_SEL_cs_events_pws_enable', + 'DB_PERF_SEL_depth_bounds_tile_culled', 'DB_PERF_SEL_di_dt_stall', + 'DB_PERF_SEL_dk_squad_busy', 'DB_PERF_SEL_dk_squad_sends', + 'DB_PERF_SEL_dk_squad_stalls', 'DB_PERF_SEL_dk_tile_busy', + 'DB_PERF_SEL_dk_tile_quad_starves', 'DB_PERF_SEL_dk_tile_sends', + 'DB_PERF_SEL_dk_tile_stalls', 'DB_PERF_SEL_dkg_tile_rate_tile', + 'DB_PERF_SEL_dtt_sm_clash_stall', 'DB_PERF_SEL_dtt_sm_miss_stall', + 'DB_PERF_SEL_dtt_sm_slot_stall', + 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 'DB_PERF_SEL_esr_eot_fwd_busy', 'DB_PERF_SEL_esr_eot_fwd_forward', + 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 'DB_PERF_SEL_esr_ps_lqf_busy', 'DB_PERF_SEL_esr_ps_lqf_stall', + 'DB_PERF_SEL_esr_ps_out_busy', 'DB_PERF_SEL_esr_ps_src_in_sends', + 'DB_PERF_SEL_esr_ps_src_in_squads', + 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_stall', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 'DB_PERF_SEL_esr_ps_src_out_stall', 'DB_PERF_SEL_esr_ps_vic_busy', + 'DB_PERF_SEL_esr_ps_vic_stall', + 'DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut', + 'DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut', + 'DB_PERF_SEL_esr_psi_vic_tile_rate', + 'DB_PERF_SEL_esr_sqq_zi_busy', 'DB_PERF_SEL_esr_sqq_zi_stall', + 'DB_PERF_SEL_esr_vic_footprint_match_1x2', + 'DB_PERF_SEL_esr_vic_footprint_match_2x1', + 'DB_PERF_SEL_esr_vic_footprint_match_2x2', + 'DB_PERF_SEL_esr_vic_sqq_busy', 'DB_PERF_SEL_esr_vic_sqq_stall', + 'DB_PERF_SEL_etr_out_busy', 'DB_PERF_SEL_etr_out_cb_tile_stall', + 'DB_PERF_SEL_etr_out_esr_stall', + 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 'DB_PERF_SEL_etr_out_send', 'DB_PERF_SEL_flush_10plane', + 'DB_PERF_SEL_flush_11plane', 'DB_PERF_SEL_flush_12plane', + 'DB_PERF_SEL_flush_13plane', 'DB_PERF_SEL_flush_14plane', + 'DB_PERF_SEL_flush_15plane', 'DB_PERF_SEL_flush_16plane', + 'DB_PERF_SEL_flush_1plane', 'DB_PERF_SEL_flush_2plane', + 'DB_PERF_SEL_flush_3plane', 'DB_PERF_SEL_flush_4plane', + 'DB_PERF_SEL_flush_5plane', 'DB_PERF_SEL_flush_6plane', + 'DB_PERF_SEL_flush_7plane', 'DB_PERF_SEL_flush_8plane', + 'DB_PERF_SEL_flush_9plane', 'DB_PERF_SEL_flush_compressed', + 'DB_PERF_SEL_flush_compressed_stencil', + 'DB_PERF_SEL_flush_expanded_stencil', + 'DB_PERF_SEL_flush_expanded_z', 'DB_PERF_SEL_flush_plane_le4', + 'DB_PERF_SEL_flush_single_stencil', + 'DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1', + 'DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1', + 'DB_PERF_SEL_his_tile_culled', 'DB_PERF_SEL_hiz_tc_read_starved', + 'DB_PERF_SEL_hiz_tc_write_stall', 'DB_PERF_SEL_hiz_tile_culled', + 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 'DB_PERF_SEL_mi_rdreq_busy', 'DB_PERF_SEL_mi_rdreq_stall', + 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 'DB_PERF_SEL_mi_wrreq_busy', 'DB_PERF_SEL_mi_wrreq_stall', + 'DB_PERF_SEL_noz_waiting_for_postz_done', + 'DB_PERF_SEL_planes_flushed', + 'DB_PERF_SEL_postz_ps_invoked_pixel_cnt', + 'DB_PERF_SEL_postzl_full_launch', + 'DB_PERF_SEL_postzl_partial_launch', + 'DB_PERF_SEL_postzl_partial_waiting', + 'DB_PERF_SEL_postzl_se_busy', 'DB_PERF_SEL_postzl_se_stall', + 'DB_PERF_SEL_postzl_sq_pt_busy', 'DB_PERF_SEL_postzl_sq_pt_stall', + 'DB_PERF_SEL_postzl_src_in_sends', + 'DB_PERF_SEL_postzl_src_in_squads', + 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 'DB_PERF_SEL_postzl_src_in_stall', + 'DB_PERF_SEL_postzl_src_in_tile_rate', + 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_postzl_src_out_stall', + 'DB_PERF_SEL_postzl_tile_init_stall', + 'DB_PERF_SEL_postzl_tile_mem_stall', + 'DB_PERF_SEL_prez_ps_invoked_pixel_cnt', + 'DB_PERF_SEL_prezl_src_in_sends', + 'DB_PERF_SEL_prezl_src_in_squads', + 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 'DB_PERF_SEL_prezl_src_in_stall', + 'DB_PERF_SEL_prezl_src_in_tile_rate', + 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_prezl_src_out_stall', + 'DB_PERF_SEL_prezl_tile_init_stall', + 'DB_PERF_SEL_prezl_tile_mem_stall', + 'DB_PERF_SEL_ps_events_pws_enable', 'DB_PERF_SEL_qc_busy', + 'DB_PERF_SEL_qc_conflicts', 'DB_PERF_SEL_qc_full_stall', + 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', 'DB_PERF_SEL_qc_xfc', + 'DB_PERF_SEL_quad_rd_32byte_reqs', 'DB_PERF_SEL_quad_rd_busy', + 'DB_PERF_SEL_quad_rd_mi_stall', + 'DB_PERF_SEL_quad_rd_mi_stall_unc', 'DB_PERF_SEL_quad_rd_panic', + 'DB_PERF_SEL_quad_rd_rw_collision', 'DB_PERF_SEL_quad_rd_sends', + 'DB_PERF_SEL_quad_rd_sends_unc', 'DB_PERF_SEL_quad_rd_tag_stall', + 'DB_PERF_SEL_quad_rdret_busy', 'DB_PERF_SEL_quad_rdret_sends', + 'DB_PERF_SEL_quad_wr_acks', 'DB_PERF_SEL_quad_wr_busy', + 'DB_PERF_SEL_quad_wr_coherency_stall', + 'DB_PERF_SEL_quad_wr_mi_stall', 'DB_PERF_SEL_quad_wr_sends', + 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 'DB_PERF_SEL_sc_kick_end', 'DB_PERF_SEL_sc_kick_start', + 'DB_PERF_SEL_tcp_dispatcher_flushes', + 'DB_PERF_SEL_tcp_dispatcher_reads', + 'DB_PERF_SEL_tcp_prefetcher_flushes', + 'DB_PERF_SEL_tcp_prefetcher_reads', + 'DB_PERF_SEL_tcp_preloader_flushes', + 'DB_PERF_SEL_tcp_preloader_reads', 'DB_PERF_SEL_tile_rd_sends', + 'DB_PERF_SEL_tile_wr_acks', 'DB_PERF_SEL_tile_wr_sends', + 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 'DB_PERF_SEL_tiles_decomp_on_expclear', + 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 'DB_PERF_SEL_tiles_z_fully_summarized', 'DB_PERF_SEL_tl_busy', + 'DB_PERF_SEL_tl_dtc_read_starved', 'DB_PERF_SEL_tl_events', + 'DB_PERF_SEL_tl_expand_squads', + 'DB_PERF_SEL_tl_flush_expand_squads', + 'DB_PERF_SEL_tl_in_fast_z_stall', + 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 'DB_PERF_SEL_tl_in_xfc', 'DB_PERF_SEL_tl_out_squads', + 'DB_PERF_SEL_tl_out_xfc', 'DB_PERF_SEL_tl_postZ_noop_squads', + 'DB_PERF_SEL_tl_postZ_squads', 'DB_PERF_SEL_tl_preZ_noop_squads', + 'DB_PERF_SEL_tl_preZ_squads', + 'DB_PERF_SEL_tl_stencil_locked_stall', + 'DB_PERF_SEL_tl_stencil_stall', 'DB_PERF_SEL_tl_summarize_squads', + 'DB_PERF_SEL_tl_tile_ops', 'DB_PERF_SEL_tl_z_decompress_stall', + 'DB_PERF_SEL_tl_z_fetch_stall', + 'DB_PERF_SEL_ts_events_pws_enable', + 'DB_PERF_SEL_ts_tc_update_stall', + 'DB_PERF_SEL_tsc_insert_summarize_stall', + 'DB_PERF_SEL_unmapped_z_tile_culled', + 'DB_PERF_SEL_zf_plane_multicycle', 'DB_VPORT_CHANGED_EVENT', + 'DCCG_AUDIO_DTO0_SOURCE_SEL', 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', + 'DCCG_AUDIO_DTO2_SOURCE_SEL', 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2', 'DCCG_AUDIO_DTO_SEL', + 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO_DTBCLK', + 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', + 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 'DCCG_AUDIO_DTO_USE_512FBR_DTO', + 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', 'DCCG_DBG_BLOCK_SEL', + 'DCCG_DBG_BLOCK_SEL_DCCG', 'DCCG_DBG_BLOCK_SEL_PMON', + 'DCCG_DBG_BLOCK_SEL_PMON2', 'DCCG_DBG_EN', 'DCCG_DBG_EN_DISABLE', + 'DCCG_DBG_EN_ENABLE', 'DCCG_DEEP_COLOR_CNTL', + 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', 'DCCG_DEEP_COLOR_DTO_DISABLE', + 'DCCG_FIFO_ERRDET_OVR_DISABLE', 'DCCG_FIFO_ERRDET_OVR_EN', + 'DCCG_FIFO_ERRDET_OVR_ENABLE', 'DCCG_FIFO_ERRDET_RESET', + 'DCCG_FIFO_ERRDET_RESET_FORCE', 'DCCG_FIFO_ERRDET_RESET_NOOP', + 'DCCG_FIFO_ERRDET_STATE', 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 'DCCG_FIFO_ERRDET_STATE_DETECTION', 'DCCG_PERF_MODE_HSYNC', + 'DCCG_PERF_MODE_HSYNC_NOOP', 'DCCG_PERF_MODE_HSYNC_START', + 'DCCG_PERF_MODE_VSYNC', 'DCCG_PERF_MODE_VSYNC_NOOP', + 'DCCG_PERF_MODE_VSYNC_START', 'DCCG_PERF_OTG_SELECT', + 'DCCG_PERF_RUN', 'DCCG_PERF_RUN_NOOP', 'DCCG_PERF_RUN_START', + 'DCCG_PERF_SEL_OTG0', 'DCCG_PERF_SEL_OTG1', 'DCCG_PERF_SEL_OTG2', + 'DCCG_PERF_SEL_OTG3', 'DCCG_PERF_SEL_RESERVED', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE', + 'DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE', + 'DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE', + 'DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP', + 'DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP', + 'DCHUBBUB_MEM_POWER_MODE_OFF', + 'DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN', 'DCHUBBUB_MEM_PWR_DIS_MODE', + 'DCHUBBUB_MEM_PWR_MODE', 'DCIOCHIP_AUX_ALL_PWR_OK', + 'DCIOCHIP_AUX_ALL_PWR_OK_0', 'DCIOCHIP_AUX_ALL_PWR_OK_1', + 'DCIOCHIP_AUX_CSEL0P9', 'DCIOCHIP_AUX_CSEL1P1', + 'DCIOCHIP_AUX_CSEL_DEC0P9', 'DCIOCHIP_AUX_CSEL_DEC1P0', + 'DCIOCHIP_AUX_CSEL_INC1P0', 'DCIOCHIP_AUX_CSEL_INC1P1', + 'DCIOCHIP_AUX_FALLSLEWSEL', 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', 'DCIOCHIP_AUX_HYS_TUNE', + 'DCIOCHIP_AUX_HYS_TUNE_0', 'DCIOCHIP_AUX_HYS_TUNE_1', + 'DCIOCHIP_AUX_HYS_TUNE_2', 'DCIOCHIP_AUX_HYS_TUNE_3', + 'DCIOCHIP_AUX_RECEIVER_SEL', 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 'DCIOCHIP_AUX_RECEIVER_SEL_1', 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 'DCIOCHIP_AUX_RECEIVER_SEL_3', 'DCIOCHIP_AUX_RSEL0P9', + 'DCIOCHIP_AUX_RSEL1P1', 'DCIOCHIP_AUX_RSEL_DEC0P9', + 'DCIOCHIP_AUX_RSEL_DEC1P0', 'DCIOCHIP_AUX_RSEL_INC1P0', + 'DCIOCHIP_AUX_RSEL_INC1P1', 'DCIOCHIP_AUX_SPIKESEL', + 'DCIOCHIP_AUX_SPIKESEL_10NS', 'DCIOCHIP_AUX_SPIKESEL_50NS', + 'DCIOCHIP_AUX_VOD_TUNE', 'DCIOCHIP_AUX_VOD_TUNE_0', + 'DCIOCHIP_AUX_VOD_TUNE_1', 'DCIOCHIP_AUX_VOD_TUNE_2', + 'DCIOCHIP_AUX_VOD_TUNE_3', 'DCIOCHIP_GPIO_MASK_EN', + 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', 'DCIOCHIP_HPD_SEL', + 'DCIOCHIP_HPD_SEL_ASYNC', 'DCIOCHIP_HPD_SEL_CLOCKED', + 'DCIOCHIP_I2C_COMPSEL', 'DCIOCHIP_I2C_FALLSLEWSEL', + 'DCIOCHIP_I2C_FALLSLEWSEL_00', 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 'DCIOCHIP_I2C_FALLSLEWSEL_10', 'DCIOCHIP_I2C_FALLSLEWSEL_11', + 'DCIOCHIP_I2C_RECEIVER_SEL', 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 'DCIOCHIP_I2C_RECEIVER_SEL_1', 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 'DCIOCHIP_I2C_RECEIVER_SEL_3', 'DCIOCHIP_I2C_REC_COMPARATOR', + 'DCIOCHIP_I2C_REC_SCHMIT', 'DCIOCHIP_I2C_VPH_1V2_EN', + 'DCIOCHIP_I2C_VPH_1V2_EN_0', 'DCIOCHIP_I2C_VPH_1V2_EN_1', + 'DCIOCHIP_INVERT', 'DCIOCHIP_MASK', 'DCIOCHIP_MASK_DISABLE', + 'DCIOCHIP_MASK_ENABLE', 'DCIOCHIP_PAD_MODE', + 'DCIOCHIP_PAD_MODE_DDC', 'DCIOCHIP_PAD_MODE_DP', 'DCIOCHIP_PD_EN', + 'DCIOCHIP_PD_EN_ALLOW', 'DCIOCHIP_PD_EN_NOTALLOW', + 'DCIOCHIP_POL_INVERT', 'DCIOCHIP_POL_NON_INVERT', + 'DCIOCHIP_REF_27_SRC_SEL', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', + 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL', + 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS', + 'DCIO_DBG_ASYNC_4BIT_SEL', 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', 'DCIO_DBG_ASYNC_BLOCK_SEL', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DIO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', 'DCIO_DCRXPHY_SOFT_RESET', + 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', + 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', 'DCIO_DC_GENERICA_SEL', + 'DCIO_DC_GENERICB_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL', + 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE', + 'DCIO_DC_GPU_TIMER_READ_SELECT', + 'DCIO_DC_GPU_TIMER_START_POSITION', + 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL', + 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL', + 'DCIO_DIO_EXT_VSYNC_MASK', 'DCIO_DIO_OTG_EXT_VSYNC_MUX', + 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', 'DCIO_DPCS_INTERRUPT_DISABLE', + 'DCIO_DPCS_INTERRUPT_ENABLE', 'DCIO_DPCS_INTERRUPT_MASK', + 'DCIO_DPCS_INTERRUPT_TYPE', + 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', + 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', + 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', 'DCIO_DSYNC_SOFT_RESET', + 'DCIO_DSYNC_SOFT_RESET_ASSERT', 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 'DCIO_EXT_VSYNC_MASK_NONE', 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', + 'DCIO_EXT_VSYNC_MASK_PIPE0', 'DCIO_EXT_VSYNC_MASK_PIPE1', + 'DCIO_EXT_VSYNC_MASK_PIPE2', 'DCIO_EXT_VSYNC_MASK_PIPE3', + 'DCIO_EXT_VSYNC_MASK_PIPE4', 'DCIO_EXT_VSYNC_MASK_PIPE5', + 'DCIO_EXT_VSYNC_MUX_GENERICB', 'DCIO_EXT_VSYNC_MUX_OTG0', + 'DCIO_EXT_VSYNC_MUX_OTG1', 'DCIO_EXT_VSYNC_MUX_OTG2', + 'DCIO_EXT_VSYNC_MUX_OTG3', 'DCIO_EXT_VSYNC_MUX_OTG4', + 'DCIO_EXT_VSYNC_MUX_OTG5', 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 'DCIO_GENERICA_SEL_GENERICA_DCCG', 'DCIO_GENERICA_SEL_STEREOSYNC', + 'DCIO_GENERICA_SEL_SYNCEN', 'DCIO_GENERICB_SEL_GENERICB_DCCG', + 'DCIO_GENERICB_SEL_STEREOSYNC', 'DCIO_GENERICB_SEL_SYNCEN', + 'DCIO_GENLK_CLK_GSL_MASK', 'DCIO_GENLK_CLK_GSL_MASK_NO', + 'DCIO_GENLK_CLK_GSL_MASK_STEREO', + 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', + 'DCIO_GENLK_VSYNC_GSL_MASK', 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', + 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_START_0_END_27', 'DCIO_GPU_TIMER_START_10_END_37', + 'DCIO_GPU_TIMER_START_1_END_28', 'DCIO_GPU_TIMER_START_2_END_29', + 'DCIO_GPU_TIMER_START_3_END_30', 'DCIO_GPU_TIMER_START_4_END_31', + 'DCIO_GPU_TIMER_START_6_END_33', 'DCIO_GPU_TIMER_START_8_END_35', + 'DCIO_GSL_SEL', 'DCIO_GSL_SEL_GROUP_0', 'DCIO_GSL_SEL_GROUP_1', + 'DCIO_GSL_SEL_GROUP_2', 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', + 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', + 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', 'DCIO_PHY_HPO_ENC_SRC_SEL', + 'DCIO_SWAPLOCK_A_GSL_MASK', 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', 'DCIO_SWAPLOCK_B_GSL_MASK', + 'DCIO_SWAPLOCK_B_GSL_MASK_NO', 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', 'DCIO_TEST_CLK_SEL_DISPCLK', + 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', 'DCIO_TEST_CLK_SEL_SOCCLK', + 'DCIO_UNIPHYA_FBDIV_CLK', 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYA_TEST_REFDIV_CLK', 'DCIO_UNIPHYB_FBDIV_CLK', + 'DCIO_UNIPHYB_FBDIV_SSC_CLK', 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYB_TEST_REFDIV_CLK', 'DCIO_UNIPHYC_FBDIV_CLK', + 'DCIO_UNIPHYC_FBDIV_SSC_CLK', 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYC_TEST_REFDIV_CLK', 'DCIO_UNIPHYD_FBDIV_CLK', + 'DCIO_UNIPHYD_FBDIV_SSC_CLK', 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYD_TEST_REFDIV_CLK', 'DCIO_UNIPHYE_FBDIV_CLK', + 'DCIO_UNIPHYE_FBDIV_SSC_CLK', 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYE_TEST_REFDIV_CLK', 'DCIO_UNIPHYF_FBDIV_CLK', + 'DCIO_UNIPHYF_FBDIV_SSC_CLK', 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYF_TEST_REFDIV_CLK', 'DCIO_UNIPHYG_FBDIV_CLK', + 'DCIO_UNIPHYG_FBDIV_SSC_CLK', 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYG_TEST_REFDIV_CLK', 'DCIO_UNIPHY_CHANNEL_INVERTED', + 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', 'DCIO_UNIPHY_IMPCAL_SEL', + 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', + 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT', + 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', 'DC_DMCUB_INT_TYPE', + 'DC_DMCUB_TIMER_WINDOW', 'DC_MEM_GLOBAL_PWR_REQ_DIS', + 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 'DC_SMU_INTERRUPT_ENABLE', 'DDID_VMID_CNTL', 'DDID_VMID_PIPE', + 'DEBUG_BUS_SELECT_ABM0', 'DEBUG_BUS_SELECT_ABM1', + 'DEBUG_BUS_SELECT_ABM2', 'DEBUG_BUS_SELECT_ABM3', + 'DEBUG_BUS_SELECT_ABM_RESERVED0', + 'DEBUG_BUS_SELECT_ABM_RESERVED1', 'DEBUG_BUS_SELECT_DPG0', + 'DEBUG_BUS_SELECT_DPG1', 'DEBUG_BUS_SELECT_DPG2', + 'DEBUG_BUS_SELECT_DPG3', 'DEBUG_BUS_SELECT_DPG_RESERVED0', + 'DEBUG_BUS_SELECT_DPG_RESERVED1', 'DEBUG_BUS_SELECT_FMT0', + 'DEBUG_BUS_SELECT_FMT1', 'DEBUG_BUS_SELECT_FMT2', + 'DEBUG_BUS_SELECT_FMT3', 'DEBUG_BUS_SELECT_FMT_RESERVED0', + 'DEBUG_BUS_SELECT_FMT_RESERVED1', 'DEBUG_BUS_SELECT_OPPBUF0', + 'DEBUG_BUS_SELECT_OPPBUF1', 'DEBUG_BUS_SELECT_OPPBUF2', + 'DEBUG_BUS_SELECT_OPPBUF3', 'DEBUG_BUS_SELECT_OPPBUF_RESERVED0', + 'DEBUG_BUS_SELECT_OPPBUF_RESERVED1', 'DEBUG_BUS_SELECT_OPP_PIPE0', + 'DEBUG_BUS_SELECT_OPP_PIPE1', 'DEBUG_BUS_SELECT_OPP_PIPE2', + 'DEBUG_BUS_SELECT_OPP_PIPE3', + 'DEBUG_BUS_SELECT_OPP_PIPE_RESERVED0', + 'DEBUG_BUS_SELECT_OPP_PIPE_RESERVED1', 'DECERR', + 'DENORM_TRUNCATE', 'DETILE_BUFFER_PACKER_ENABLE', + 'DETILE_BUFFER_PACKER_IS_DISABLE', + 'DETILE_BUFFER_PACKER_IS_ENABLE', 'DFQ_MIN_FREE_ENTRIES', + 'DFQ_MIN_FREE_ENTRIES_0', 'DFQ_MIN_FREE_ENTRIES_1', + 'DFQ_MIN_FREE_ENTRIES_2', 'DFQ_MIN_FREE_ENTRIES_3', + 'DFQ_MIN_FREE_ENTRIES_4', 'DFQ_MIN_FREE_ENTRIES_5', + 'DFQ_MIN_FREE_ENTRIES_6', 'DFQ_MIN_FREE_ENTRIES_7', + 'DFQ_NUM_ENTRIES', 'DFQ_NUM_ENTRIES_0', 'DFQ_NUM_ENTRIES_1', + 'DFQ_NUM_ENTRIES_2', 'DFQ_NUM_ENTRIES_3', 'DFQ_NUM_ENTRIES_4', + 'DFQ_NUM_ENTRIES_5', 'DFQ_NUM_ENTRIES_6', 'DFQ_NUM_ENTRIES_7', + 'DFQ_NUM_ENTRIES_8', 'DFQ_SIZE', 'DFQ_SIZE_0', 'DFQ_SIZE_1', + 'DFQ_SIZE_2', 'DFQ_SIZE_3', 'DFQ_SIZE_4', 'DFQ_SIZE_5', + 'DFQ_SIZE_6', 'DFQ_SIZE_7', 'DFSMFlushEvents', 'DIFFERENT_RGB', + 'DIG_10BIT_TEST_PATTERN', 'DIG_ALL_PIXEL', + 'DIG_ALTERNATING_TEST_PATTERN', 'DIG_BE_CNTL_HPD1', + 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', 'DIG_BE_CNTL_HPD4', + 'DIG_BE_CNTL_HPD5', 'DIG_BE_CNTL_HPD_SELECT', 'DIG_BE_CNTL_MODE', + 'DIG_BE_CNTL_NO_HPD', 'DIG_BE_DP_MST_MODE', 'DIG_BE_DP_SST_MODE', + 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', 'DIG_BE_RESERVED3', + 'DIG_BE_RESERVED4', 'DIG_BE_TMDS_DVI_MODE', + 'DIG_BE_TMDS_HDMI_MODE', 'DIG_DIGITAL_BYPASS_ENABLE', + 'DIG_DIGITAL_BYPASS_OFF', 'DIG_DIGITAL_BYPASS_ON', + 'DIG_DIGITAL_BYPASS_SEL', 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 'DIG_DIGITAL_BYPASS_SEL_ALPHA', 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 'DIG_EVEN_PIXEL_ONLY', 'DIG_FE_CNTL_SOURCE_SELECT', + 'DIG_FE_CNTL_STEREOSYNC_SELECT', 'DIG_FE_SOURCE_FROM_OTG0', + 'DIG_FE_SOURCE_FROM_OTG1', 'DIG_FE_SOURCE_FROM_OTG2', + 'DIG_FE_SOURCE_FROM_OTG3', 'DIG_FE_SOURCE_RESERVED', + 'DIG_FE_STEREOSYNC_FROM_OTG0', 'DIG_FE_STEREOSYNC_FROM_OTG1', + 'DIG_FE_STEREOSYNC_FROM_OTG2', 'DIG_FE_STEREOSYNC_FROM_OTG3', + 'DIG_FE_STEREOSYNC_RESERVED', 'DIG_FIFO_1_PIX_PER_CYCLE', + 'DIG_FIFO_2_PIX_PER_CYCLE', 'DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL', + 'DIG_FIFO_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', + 'DIG_FIFO_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', 'DIG_FIFO_NO_ERROR_OCCURRED', + 'DIG_FIFO_OUTPUT_PROCESSING_MODE', 'DIG_FIFO_OVERFLOW_OCCURRED', + 'DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR', 'DIG_FIFO_READ_CLOCK_SRC', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', + 'DIG_FIFO_UNDERFLOW_OCCURRED', 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', + 'DIG_FIFO_USE_OVERWRITE_LEVEL', 'DIG_INPUT_PIXEL_SEL', + 'DIG_IN_DEBUG_MODE', 'DIG_IN_NORMAL_OPERATION', + 'DIG_ODD_PIXEL_ONLY', 'DIG_OUTPUT_CRC_CNTL_LINK_SEL', + 'DIG_OUTPUT_CRC_DATA_SEL', 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', + 'DIG_OUTPUT_CRC_FOR_AUDIO', 'DIG_OUTPUT_CRC_FOR_FULLFRAME', + 'DIG_OUTPUT_CRC_FOR_VBI', 'DIG_OUTPUT_CRC_ON_LINK0', + 'DIG_OUTPUT_CRC_ON_LINK1', 'DIG_PAIR_PIXELS', + 'DIG_RANDOM_PATTERN_ENABLED', 'DIG_RANDOM_PATTERN_RESETED', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', 'DIG_SINGLETON_PIXELS', + 'DIG_SL_PIXEL_GROUPING', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL', + 'DIG_TEST_PATTERN_NORMAL', 'DIG_TEST_PATTERN_RANDOM', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET', + 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN', 'DIG_UPDATE_EYE_SEL_BOTH', + 'DIG_UPDATE_EYE_SEL_LEFT', 'DIG_UPDATE_EYE_SEL_RIGHT', + 'DIG_UPDATE_FIELD_SEL_BOTH', 'DIG_UPDATE_FIELD_SEL_BOTTOM', + 'DIG_UPDATE_FIELD_SEL_RESERVED', 'DIG_UPDATE_FIELD_SEL_TOP', + 'DIOMEM_DISABLE_MEM_PWR_CTRL', 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', + 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', 'DIOMEM_NO_FORCE_REQ', + 'DIOMEM_NO_FORCE_REQUEST', 'DIOMEM_PWR_DIS_CTRL', + 'DIOMEM_PWR_FORCE_CTRL', 'DIOMEM_PWR_FORCE_CTRL2', + 'DIOMEM_PWR_SEL_CTRL', 'DIOMEM_PWR_SEL_CTRL2', + 'DIO_DBG_BLOCK_SEL', 'DIO_DBG_BLOCK_SEL_AUX0', + 'DIO_DBG_BLOCK_SEL_AUX1', 'DIO_DBG_BLOCK_SEL_AUX2', + 'DIO_DBG_BLOCK_SEL_AUX3', 'DIO_DBG_BLOCK_SEL_AUX4', + 'DIO_DBG_BLOCK_SEL_DIGA', 'DIO_DBG_BLOCK_SEL_DIGB', + 'DIO_DBG_BLOCK_SEL_DIGC', 'DIO_DBG_BLOCK_SEL_DIGD', + 'DIO_DBG_BLOCK_SEL_DIGE', 'DIO_DBG_BLOCK_SEL_DIGFE_A', + 'DIO_DBG_BLOCK_SEL_DIGFE_B', 'DIO_DBG_BLOCK_SEL_DIGFE_C', + 'DIO_DBG_BLOCK_SEL_DIGFE_D', 'DIO_DBG_BLOCK_SEL_DIGFE_E', + 'DIO_DBG_BLOCK_SEL_DIO', 'DIO_DBG_BLOCK_SEL_DPA', + 'DIO_DBG_BLOCK_SEL_DPB', 'DIO_DBG_BLOCK_SEL_DPC', + 'DIO_DBG_BLOCK_SEL_DPD', 'DIO_DBG_BLOCK_SEL_DPE', + 'DIO_DBG_BLOCK_SEL_DPFE_A', 'DIO_DBG_BLOCK_SEL_DPFE_B', + 'DIO_DBG_BLOCK_SEL_DPFE_C', 'DIO_DBG_BLOCK_SEL_DPFE_D', + 'DIO_DBG_BLOCK_SEL_DPFE_E', 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', + 'DIO_DBG_BLOCK_SEL_RESERVED', 'DIO_FIFO_ERROR', + 'DIO_FIFO_ERROR_00', 'DIO_FIFO_ERROR_01', 'DIO_FIFO_ERROR_10', + 'DIO_FIFO_ERROR_11', + 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', + 'DISABLE_BINNING_USE_LEGACY_SC', 'DISABLE_BINNING_USE_NEW_SC', + 'DISABLE_CLOCK_GATING', 'DISABLE_CLOCK_GATING_IN_DCO', + 'DISABLE_DEBUG', 'DISABLE_JITTER_REMOVAL', 'DISABLE_MEM_PWR_CTRL', + 'DISABLE_PWL', 'DISABLE_TF0_OPT', 'DISABLE_TF1_OPT', + 'DISABLE_THE_FEATURE', 'DISABLE_THE_INTERRUPT', + 'DISPCLK_CHG_FWD_CORR_DISABLE', + 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', + 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 'DISPCLK_FREQ_RAMP_COMPLETED', 'DISPCLK_FREQ_RAMP_DONE', + 'DISPCLK_FREQ_RAMP_IN_PROGRESS', 'DIVISOR_BY1', + 'DIVISOR_BY2_RESERVED', 'DIVISOR_BY3', 'DIVISOR_BY4_RESERVED', + 'DIVISOR_BY5_RESERVED', 'DIVISOR_BY6_RESERVED', + 'DIVISOR_BY7_RESERVED', 'DIVISOR_BY8_RESERVED', 'DIV_2', 'DIV_4', + 'DIV_8', 'DI_INDEX_SIZE_16_BIT', 'DI_INDEX_SIZE_32_BIT', + 'DI_INDEX_SIZE_8_BIT', 'DI_MAJOR_MODE_0', 'DI_MAJOR_MODE_1', + 'DI_PT_2D_RECTANGLE', 'DI_PT_LINELIST', 'DI_PT_LINELIST_ADJ', + 'DI_PT_LINELOOP', 'DI_PT_LINESTRIP', 'DI_PT_LINESTRIP_ADJ', + 'DI_PT_NONE', 'DI_PT_PATCH', 'DI_PT_POINTLIST', 'DI_PT_POLYGON', + 'DI_PT_QUADLIST', 'DI_PT_QUADSTRIP', 'DI_PT_RECTLIST', + 'DI_PT_TRIFAN', 'DI_PT_TRILIST', 'DI_PT_TRILIST_ADJ', + 'DI_PT_TRISTRIP', 'DI_PT_TRISTRIP_ADJ', 'DI_PT_UNUSED_1', + 'DI_PT_UNUSED_3', 'DI_PT_UNUSED_4', 'DI_PT_UNUSED_5', + 'DI_SRC_SEL_AUTO_INDEX', 'DI_SRC_SEL_DMA', 'DI_SRC_SEL_IMMEDIATE', + 'DI_SRC_SEL_RESERVED', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', + 'DMDATA_CLEAR_UNDERFLOW_STATUS', 'DMDATA_DONE', + 'DMDATA_DONT_CLEAR', 'DMDATA_HARDWARE_UPDATE_MODE', 'DMDATA_MODE', + 'DMDATA_NOT_SENT_TO_DIG', 'DMDATA_NOT_UNDERFLOW', + 'DMDATA_NOT_UPDATED', 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', + 'DMDATA_QOS_LEVEL_FROM_TTU', 'DMDATA_QOS_MODE', 'DMDATA_REPEAT', + 'DMDATA_SENT_TO_DIG', 'DMDATA_SOFTWARE_UPDATE_MODE', + 'DMDATA_UNDERFLOW', 'DMDATA_UNDERFLOWED', + 'DMDATA_UNDERFLOW_CLEAR', 'DMDATA_UPDATED', + 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', + 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', 'DMDATA_VM_DONE', + 'DMDATA_VM_IS_DONE', 'DMDATA_VM_IS_NOT_DONE', + 'DMDATA_WAS_UPDATED', 'DME_MEM_DISABLE_MEM_PWR_CTRL', + 'DME_MEM_ENABLE_MEM_PWR_CTRL', 'DME_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'DME_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'DME_MEM_FORCE_SHUT_DOWN_REQUEST', 'DME_MEM_NO_FORCE_REQUEST', + 'DME_MEM_POWER_STATE_ENUM', 'DME_MEM_POWER_STATE_ENUM_DS', + 'DME_MEM_POWER_STATE_ENUM_LS', 'DME_MEM_POWER_STATE_ENUM_ON', + 'DME_MEM_POWER_STATE_ENUM_SD', 'DME_MEM_PWR_DIS_CTRL', + 'DME_MEM_PWR_FORCE_CTRL', 'DMU_CLOCK_ON', 'DMU_CLOCK_STATUS_OFF', + 'DMU_CLOCK_STATUS_ON', 'DMU_DC_GPU_TIMER_READ_SELECT', + 'DMU_DC_GPU_TIMER_START_POSITION', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 'DMU_GPU_TIMER_START_0_END_27', 'DMU_GPU_TIMER_START_10_END_37', + 'DMU_GPU_TIMER_START_1_END_28', 'DMU_GPU_TIMER_START_2_END_29', + 'DMU_GPU_TIMER_START_3_END_30', 'DMU_GPU_TIMER_START_4_END_31', + 'DMU_GPU_TIMER_START_6_END_33', 'DMU_GPU_TIMER_START_8_END_35', + 'DOLBY_VISION_DISABLED', 'DOLBY_VISION_ENABLE', + 'DOLBY_VISION_ENABLED', 'DONUTS', 'DOUT_I2C_ACK', + 'DOUT_I2C_ACK_TO_CLEAN', + 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_ABORT_XFER', + 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', + 'DOUT_I2C_CONTROL_DBG_REF_SEL', 'DOUT_I2C_CONTROL_DDC_SELECT', + 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', 'DOUT_I2C_CONTROL_GO', + 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_SELECT_DDC1', 'DOUT_I2C_CONTROL_SELECT_DDC2', + 'DOUT_I2C_CONTROL_SELECT_DDC3', 'DOUT_I2C_CONTROL_SELECT_DDC4', + 'DOUT_I2C_CONTROL_SELECT_DDC5', 'DOUT_I2C_CONTROL_SELECT_DDCVGA', + 'DOUT_I2C_CONTROL_SEND_RESET', + 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH', + 'DOUT_I2C_CONTROL_SOFT_RESET', 'DOUT_I2C_CONTROL_START_TRANSFER', + 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 'DOUT_I2C_CONTROL_SW_STATUS_RESET', 'DOUT_I2C_CONTROL_TRANS0', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', + 'DOUT_I2C_CONTROL_TRANSACTION_COUNT', + 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 'DOUT_I2C_DATA_INDEX_WRITE', 'DOUT_I2C_DATA__INDEX_WRITE', + 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', + 'DOUT_I2C_DDC_SPEED_THRESHOLD', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', + 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET', + 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_NO_ACK', 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', + 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DPHY_8B10B_CUR_DISP', + 'DPHY_8B10B_CUR_DISP_ONE', 'DPHY_8B10B_CUR_DISP_ZERO', + 'DPHY_8B10B_NOT_RESET', 'DPHY_8B10B_OUTPUT', 'DPHY_8B10B_RESET', + 'DPHY_8B10B_RESETET', + 'DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION', + 'DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE', + 'DPHY_ALT_SCRAMBLER_RESET_EN', 'DPHY_ALT_SCRAMBLER_RESET_SEL', + 'DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE', + 'DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE', + 'DPHY_ATEST_LANE0_PRBS_PATTERN', 'DPHY_ATEST_LANE0_REG_PATTERN', + 'DPHY_ATEST_LANE1_PRBS_PATTERN', 'DPHY_ATEST_LANE1_REG_PATTERN', + 'DPHY_ATEST_LANE2_PRBS_PATTERN', 'DPHY_ATEST_LANE2_REG_PATTERN', + 'DPHY_ATEST_LANE3_PRBS_PATTERN', 'DPHY_ATEST_LANE3_REG_PATTERN', + 'DPHY_ATEST_SEL_LANE0', 'DPHY_ATEST_SEL_LANE1', + 'DPHY_ATEST_SEL_LANE2', 'DPHY_ATEST_SEL_LANE3', 'DPHY_BYPASS', + 'DPHY_CRC_CONTINUOUS', 'DPHY_CRC_CONT_EN', 'DPHY_CRC_DISABLED', + 'DPHY_CRC_EN', 'DPHY_CRC_ENABLED', 'DPHY_CRC_FIELD', + 'DPHY_CRC_LANE0_SELECTED', 'DPHY_CRC_LANE1_SELECTED', + 'DPHY_CRC_LANE2_SELECTED', 'DPHY_CRC_LANE3_SELECTED', + 'DPHY_CRC_MST_PHASE_ERROR_ACK', 'DPHY_CRC_MST_PHASE_ERROR_ACKED', + 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', 'DPHY_CRC_ONE_SHOT', + 'DPHY_CRC_SEL', 'DPHY_CRC_START_FROM_BOTTOM_FIELD', + 'DPHY_CRC_START_FROM_TOP_FIELD', 'DPHY_DBG_OUTPUT', + 'DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY', + 'DPHY_FAST_TRAINING_CAPABLE', 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 'DPHY_FEC_ACTIVE', 'DPHY_FEC_DISABLED', 'DPHY_FEC_ENABLE', + 'DPHY_FEC_ENABLED', 'DPHY_FEC_NOT_ACTIVE', 'DPHY_FEC_READY', + 'DPHY_FEC_READY_DIS', 'DPHY_FEC_READY_EN', + 'DPHY_LOAD_BS_COUNT_NOT_STARTED', 'DPHY_LOAD_BS_COUNT_START', + 'DPHY_LOAD_BS_COUNT_STARTED', 'DPHY_NO_SKEW', + 'DPHY_PRBS11_SELECTED', 'DPHY_PRBS23_SELECTED', + 'DPHY_PRBS7_SELECTED', 'DPHY_PRBS_DISABLE', 'DPHY_PRBS_EN', + 'DPHY_PRBS_ENABLE', 'DPHY_PRBS_SEL', + 'DPHY_RX_FAST_TRAINING_CAPABLE', 'DPHY_SCRAMBLER_ADVANCE', + 'DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL', + 'DPHY_SCRAMBLER_DIS', 'DPHY_SCRAMBLER_KCODE', + 'DPHY_SCRAMBLER_KCODE_DISABLED', 'DPHY_SCRAMBLER_KCODE_ENABLED', + 'DPHY_SCRAMBLER_SEL', 'DPHY_SCRAMBLER_SEL_DBG_DATA', + 'DPHY_SCRAMBLER_SEL_LANE_DATA', 'DPHY_SCR_DISABLED', + 'DPHY_SCR_ENABLED', 'DPHY_SKEW_BYPASS', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET', + 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 'DPHY_SW_FAST_TRAINING_START', 'DPHY_SW_FAST_TRAINING_STARTED', + 'DPHY_TRAINING_PATTERN_1', 'DPHY_TRAINING_PATTERN_2', + 'DPHY_TRAINING_PATTERN_3', 'DPHY_TRAINING_PATTERN_4', + 'DPHY_TRAINING_PATTERN_SEL', 'DPHY_WITH_SKEW', 'DPREFCLK_SRC_SEL', + 'DPREFCLK_SRC_SEL_CK', 'DPREFCLK_SRC_SEL_P0PLL', + 'DPREFCLK_SRC_SEL_P1PLL', 'DPREFCLK_SRC_SEL_P2PLL', + 'DPTE_GROUP_SIZE', 'DPTE_GROUP_SIZE_1024B', + 'DPTE_GROUP_SIZE_128B', 'DPTE_GROUP_SIZE_2048B', + 'DPTE_GROUP_SIZE_256B', 'DPTE_GROUP_SIZE_512B', + 'DPTE_GROUP_SIZE_64B', 'DP_128B132B', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', 'DP_AUX_ARB_STATUS', + 'DP_AUX_CONTROL_HPD1_SELECTED', 'DP_AUX_CONTROL_HPD2_SELECTED', + 'DP_AUX_CONTROL_HPD3_SELECTED', 'DP_AUX_CONTROL_HPD4_SELECTED', + 'DP_AUX_CONTROL_HPD5_SELECTED', 'DP_AUX_CONTROL_HPD_SEL', + 'DP_AUX_CONTROL_NO_HPD_SELECTED', 'DP_AUX_CONTROL_TEST_MODE', + 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 'DP_AUX_CONTROL_TEST_MODE_ENABLE', + 'DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', + 'DP_AUX_ERR_OCCURRED_ACK', 'DP_AUX_ERR_OCCURRED__ACK', + 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 'DP_AUX_IDLE', 'DP_AUX_INT_ACK', 'DP_AUX_INT_LS_UPDATE_ACK', + 'DP_AUX_INT_LS_UPDATE_NOT_ACK', 'DP_AUX_INT__ACK', + 'DP_AUX_INT__NOT_ACK', 'DP_AUX_IN_USE_GTC', 'DP_AUX_IN_USE_LS', + 'DP_AUX_IN_USE_PHYWAKE', 'DP_AUX_IN_USE_SW', + 'DP_AUX_LS_UPDATE_ACK', 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', + 'DP_AUX_PHY_WAKE_LOW_PRIORITY', 'DP_AUX_PHY_WAKE_PRIORITY', + 'DP_AUX_POTENTIAL_ERR_REACHED_ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', 'DP_AUX_RESET', + 'DP_AUX_RESET_ASSERTED', 'DP_AUX_RESET_DEASSERTED', + 'DP_AUX_RESET_DONE', 'DP_AUX_RESET_SEQUENCE_DONE', + 'DP_AUX_RESET_SEQUENCE_NOT_DONE', 'DP_AUX_RX_TIMEOUT_LEN_MUL', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 'DP_AUX_SW_CONTROL_LS_READ_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__TRIG', 'DP_AUX_SW_CONTROL_SW_GO', + 'DP_AUX_SW_CONTROL_SW__GO', 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 'DP_AUX_TX_PRECHARGE_LEN_MUL', 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', + 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', 'DP_COMPONENT_DEPTH', + 'DP_COMPONENT_DEPTH_10BPC', 'DP_COMPONENT_DEPTH_12BPC', + 'DP_COMPONENT_DEPTH_16BPC', 'DP_COMPONENT_DEPTH_6BPC', + 'DP_COMPONENT_DEPTH_8BPC', 'DP_CP_ENCRYPTION_TYPE', + 'DP_CP_ENCRYPTION_TYPE_0', 'DP_CP_ENCRYPTION_TYPE_1', + 'DP_DPHY_8B10B_EXT_DISP', 'DP_DPHY_8B10B_EXT_DISP_ONE', + 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', + 'DP_DPHY_HBR2_PASS_THROUGH', 'DP_DPHY_HBR2_PATTERN_1', + 'DP_DPHY_HBR2_PATTERN_2_NEG', 'DP_DPHY_HBR2_PATTERN_2_POS', + 'DP_DPHY_HBR2_PATTERN_3', 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE', + 'DP_DPHY_SYM32_1LANE', 'DP_DPHY_SYM32_2LANE', + 'DP_DPHY_SYM32_4LANE', 'DP_DPHY_SYM32_ACTIVE', + 'DP_DPHY_SYM32_CRC_END_LLCP', 'DP_DPHY_SYM32_CRC_END_PS_ANY', + 'DP_DPHY_SYM32_CRC_END_PS_LT_SR', 'DP_DPHY_SYM32_CRC_END_PS_ONLY', + 'DP_DPHY_SYM32_CRC_START_LLCP', + 'DP_DPHY_SYM32_CRC_START_PS_LT_SR', + 'DP_DPHY_SYM32_CRC_START_PS_ONLY', + 'DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR', + 'DP_DPHY_SYM32_CRC_START_TP_START', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX', + 'DP_DPHY_SYM32_CRC_USE_END_EVENT', + 'DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', 'DP_DPHY_SYM32_DISABLE', + 'DP_DPHY_SYM32_ENABLE', 'DP_DPHY_SYM32_ENCRYPT_TYPE0', + 'DP_DPHY_SYM32_ENCRYPT_TYPE1', 'DP_DPHY_SYM32_LT_TPS1', + 'DP_DPHY_SYM32_LT_TPS2', 'DP_DPHY_SYM32_NOT_RESET', + 'DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING', + 'DP_DPHY_SYM32_RATE_UPDATE_PENDING', 'DP_DPHY_SYM32_RESERVED', + 'DP_DPHY_SYM32_RESET', 'DP_DPHY_SYM32_RESET_STATUS_ASSERTED', + 'DP_DPHY_SYM32_RESET_STATUS_DEASSERTED', + 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE', + 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING', + 'DP_DPHY_SYM32_SAT_NO_UPDATE', + 'DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING', + 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE', + 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING', + 'DP_DPHY_SYM32_STATUS_ENABLED', 'DP_DPHY_SYM32_STATUS_IDLE', + 'DP_DPHY_SYM32_STREAM_OVR_ALWAYS', + 'DP_DPHY_SYM32_STREAM_OVR_NONE', + 'DP_DPHY_SYM32_STREAM_OVR_REPLACE', + 'DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL', + 'DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA', 'DP_DPHY_SYM32_TEST', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9', + 'DP_DPHY_SYM32_TP_SELECT_CUSTOM', 'DP_DPHY_SYM32_TP_SELECT_PRBS', + 'DP_DPHY_SYM32_TP_SELECT_SQUARE', 'DP_DPHY_SYM32_TP_SELECT_TPS1', + 'DP_DPHY_SYM32_TP_SELECT_TPS2', 'DP_DSC_444_SIMPLE_422', + 'DP_DSC_DISABLE', 'DP_DSC_MODE', 'DP_DSC_NATIVE_422_420', + 'DP_DTO_DESPREAD_DISABLE', 'DP_DTO_DESPREAD_ENABLE', + 'DP_DTO_DS_DISABLE', 'DP_EMBEDDED_PANEL', + 'DP_EMBEDDED_PANEL_MODE', 'DP_EXTERNAL_PANEL', + 'DP_LINK_TRAINING_ALREADY_COMPLETE', 'DP_LINK_TRAINING_COMPLETE', + 'DP_LINK_TRAINING_NOT_COMPLETE', 'DP_LINK_TRAINING_SWITCH_MODE', + 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', 'DP_ML_PHY_SEQ_IMMEDIATE', + 'DP_ML_PHY_SEQ_LINE_NUM', 'DP_ML_PHY_SEQ_MODE', + 'DP_MSA_V_TIMING_OVERRIDE_EN', 'DP_MSE_BLANK_CODE', + 'DP_MSE_BLANK_CODE_SF_FILLED', 'DP_MSE_BLANK_CODE_ZERO_FILLED', + 'DP_MSE_LINK_LINE', 'DP_MSE_LINK_LINE_128_MTP_LONG', + 'DP_MSE_LINK_LINE_256_MTP_LONG', 'DP_MSE_LINK_LINE_32_MTP_LONG', + 'DP_MSE_LINK_LINE_64_MTP_LONG', 'DP_MSE_NOT_ZERO_FE_ENCODER', + 'DP_MSE_SAT_ENCRYPT0', 'DP_MSE_SAT_ENCRYPT0_DISABLED', + 'DP_MSE_SAT_ENCRYPT0_ENABLED', 'DP_MSE_SAT_ENCRYPT1', + 'DP_MSE_SAT_ENCRYPT1_DISABLED', 'DP_MSE_SAT_ENCRYPT1_ENABLED', + 'DP_MSE_SAT_ENCRYPT2', 'DP_MSE_SAT_ENCRYPT2_DISABLED', + 'DP_MSE_SAT_ENCRYPT2_ENABLED', 'DP_MSE_SAT_ENCRYPT3', + 'DP_MSE_SAT_ENCRYPT3_DISABLED', 'DP_MSE_SAT_ENCRYPT3_ENABLED', + 'DP_MSE_SAT_ENCRYPT4', 'DP_MSE_SAT_ENCRYPT4_DISABLED', + 'DP_MSE_SAT_ENCRYPT4_ENABLED', 'DP_MSE_SAT_ENCRYPT5', + 'DP_MSE_SAT_ENCRYPT5_DISABLED', 'DP_MSE_SAT_ENCRYPT5_ENABLED', + 'DP_MSE_SAT_UPDATE_ACT', 'DP_MSE_SAT_UPDATE_NO_ACTION', + 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', + 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', 'DP_MSE_TIMESTAMP_MODE', + 'DP_MSE_ZERO_ENCODER', 'DP_MSE_ZERO_FE_ENCODER', + 'DP_MSO_FOUR_SSTLINK', 'DP_MSO_NUM_OF_SST_LINKS', + 'DP_MSO_ONE_SSTLINK', 'DP_MSO_TWO_SSTLINK', + 'DP_ONE_PIXEL_PER_CYCLE', 'DP_PIXEL_ENCODING', + 'DP_PIXEL_ENCODING_RGB444', 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', + 'DP_PIXEL_ENCODING_YCBCR420', 'DP_PIXEL_ENCODING_YCBCR422', + 'DP_PIXEL_ENCODING_YCBCR444', 'DP_PIXEL_ENCODING_Y_ONLY', + 'DP_PIXEL_PER_CYCLE_PROCESSING_NUM', + 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'DP_SEC_ASP_HIGH_PRIORITY', 'DP_SEC_ASP_LOW_PRIORITY', + 'DP_SEC_ASP_PRIORITY', 'DP_SEC_AUDIO_MUTE', + 'DP_SEC_AUDIO_MUTE_HW_CTRL', 'DP_SEC_AUDIO_MUTE_SW_CTRL', + 'DP_SEC_COLLISION_ACK', 'DP_SEC_COLLISION_ACK_CLR_FLAG', + 'DP_SEC_COLLISION_ACK_NO_EFFECT', 'DP_SEC_GSP0_PRIORITY', + 'DP_SEC_GSP_SEND', 'DP_SEC_GSP_SEND_ANY_LINE', + 'DP_SEC_GSP_SEND_PPS', 'DP_SEC_LINE_REFERENCE', + 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', 'DP_SEC_TIMESTAMP_MODE', + 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', 'DP_STEER_OVERFLOW_ACK', + 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', 'DP_STEER_OVERFLOW_MASK', + 'DP_STEER_OVERFLOW_MASKED', 'DP_STEER_OVERFLOW_UNMASK', + 'DP_STREAM_ENC_DCCG', 'DP_STREAM_ENC_DISPLAY_PIPE', + 'DP_STREAM_ENC_HARDWARE', 'DP_STREAM_ENC_NOT_RESET', + 'DP_STREAM_ENC_NO_ERROR_OCCURRED', + 'DP_STREAM_ENC_OVERFLOW_OCCURRED', + 'DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR', + 'DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT', + 'DP_STREAM_ENC_PROGRAMMABLE', 'DP_STREAM_ENC_READ_CLOCK_CONTROL', + 'DP_STREAM_ENC_RESET', 'DP_STREAM_ENC_RESET_CONTROL', + 'DP_STREAM_ENC_STREAM_ACTIVE', 'DP_STREAM_ENC_UNDERFLOW_OCCURRED', + 'DP_STREAM_ENC_VIDEO_STREAM_ACTIVE', + 'DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', + 'DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET', + 'DP_STREAM_MAPPER_LINK0', 'DP_STREAM_MAPPER_LINK1', + 'DP_STREAM_MAPPER_RESERVED', 'DP_SYM32_ENC_COMPONENT_DEPTH_10BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_12BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_6BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_8BPC', + 'DP_SYM32_ENC_COMPRESSED_FORMAT', 'DP_SYM32_ENC_CONTINUOUS_MODE', + 'DP_SYM32_ENC_CRC_NOT_VALID', 'DP_SYM32_ENC_CRC_VALID', + 'DP_SYM32_ENC_DISABLE', 'DP_SYM32_ENC_DP_SOF', + 'DP_SYM32_ENC_ENABLE', 'DP_SYM32_ENC_GSP_DEADLINE_MISSED', + 'DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1', + 'DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME', + 'DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER', + 'DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING', + 'DP_SYM32_ENC_GSP_TRIGGER_PENDING', + 'DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST', + 'DP_SYM32_ENC_NOT_PENDING', 'DP_SYM32_ENC_NOT_RESET', + 'DP_SYM32_ENC_NO_OVERFLOW_OCCURRED', 'DP_SYM32_ENC_ONE_SHOT_MODE', + 'DP_SYM32_ENC_OTG_SOF', 'DP_SYM32_ENC_OVERFLOW_OCCURRED', + 'DP_SYM32_ENC_PENDING', + 'DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444', + 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420', + 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422', + 'DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY', + 'DP_SYM32_ENC_POWER_STATE_ENUM_DS', + 'DP_SYM32_ENC_POWER_STATE_ENUM_LS', + 'DP_SYM32_ENC_POWER_STATE_ENUM_ON', + 'DP_SYM32_ENC_POWER_STATE_ENUM_SD', 'DP_SYM32_ENC_RESET', + 'DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED', + 'DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED', + 'DP_SYM32_ENC_SDP_HIGH_PRIORITY', 'DP_SYM32_ENC_SDP_LOW_PRIORITY', + 'DP_SYM32_ENC_UNCOMPRESSED_FORMAT', + 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK', + 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK', + 'DP_SYM32_ENC_VID_STREAM_NO_DEFER', 'DP_SYNC_POLARITY', + 'DP_SYNC_POLARITY_ACTIVE_HIGH', 'DP_SYNC_POLARITY_ACTIVE_LOW', + 'DP_TU_OVERFLOW_ACK', 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_TU_OVERFLOW_ACK_NO_EFFECT', 'DP_TWO_PIXEL_PER_CYCLE', + 'DP_UDI_1_LANE', 'DP_UDI_2_LANES', 'DP_UDI_4_LANES', + 'DP_UDI_LANES', 'DP_UDI_LANES_RESERVED', + 'DP_VID_ENHANCED_FRAME_MODE', 'DP_VID_M_1X_INPUT_PIXEL_RATE', + 'DP_VID_M_2X_INPUT_PIXEL_RATE', 'DP_VID_M_4X_INPUT_PIXEL_RATE', + 'DP_VID_M_8X_INPUT_PIXEL_RATE', 'DP_VID_M_N_CALC_AUTO', + 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', + 'DP_VID_M_N_DOUBLE_BUFFER_MODE', 'DP_VID_M_N_GEN_EN', + 'DP_VID_M_N_PROGRAMMED_VIA_REG', 'DP_VID_N_MUL', + 'DP_VID_STREAM_DISABLE_ACK', 'DP_VID_STREAM_DISABLE_MASK', + 'DP_VID_STREAM_DIS_DEFER', 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', 'DP_VID_STREAM_DIS_NO_DEFER', + 'DP_VID_VBID_FIELD_POL', 'DP_VID_VBID_FIELD_POL_INV', + 'DP_VID_VBID_FIELD_POL_NORMAL', 'DRAW_DONE', + 'DSCCIF_BITS_PER_COMPONENT_ENUM', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCCIF_ENABLE_ENUM', 'DSCCIF_ENABLE_ENUM_DISABLED', + 'DSCCIF_ENABLE_ENUM_ENABLED', 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 'DSCC_BITS_PER_COMPONENT_ENUM', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCC_DSC_VERSION_MAJOR_ENUM', + 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', + 'DSCC_ENABLE_ENUM', 'DSCC_ENABLE_ENUM_DISABLED', + 'DSCC_ENABLE_ENUM_ENABLED', 'DSCC_ICH_RESET_ENUM', + 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', 'DSCC_LINEBUF_DEPTH_ENUM', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 'DSCC_MEM_PWR_DIS_ENUM', 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', + 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', 'DSCC_MEM_PWR_FORCE_ENUM', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 'DSCL_MODE_CHROMA_SCALING_BYPASS', 'DSCL_MODE_DSCL_BYPASS', + 'DSCL_MODE_LUMA_SCALING_BYPASS', 'DSCL_MODE_SCALING_444_BYPASS', + 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 'DSCL_MODE_SCALING_YCBCR_ENABLE', 'DSCL_MODE_SEL', 'DSM_DATA_SEL', + 'DSM_DATA_SEL_0', 'DSM_DATA_SEL_1', 'DSM_DATA_SEL_BOTH', + 'DSM_DATA_SEL_DISABLE', 'DSM_ENABLE_ERROR_INJECT', + 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 'DSM_ENABLE_ERROR_INJECT_SINGLE', + 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE', + 'DSM_ENABLE_ERROR_INJECT_UNCORRECTABLE_LIMITED', + 'DSM_SELECT_INJECT_DELAY', 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', + 'DSM_SELECT_INJECT_DELAY_NO_DELAY', 'DSM_SINGLE_WRITE', + 'DSM_SINGLE_WRITE_DIS', 'DSM_SINGLE_WRITE_EN', 'DS_HW_CAL_DIS', + 'DS_HW_CAL_EN', 'DS_HW_CAL_ENABLE', 'DS_JITTER_COUNT_SRC_SEL', + 'DS_JITTER_COUNT_SRC_SEL0', 'DS_JITTER_COUNT_SRC_SEL1', + 'DS_REF_IS_EXT_GENLOCK', 'DS_REF_IS_PCIE', 'DS_REF_IS_XTALIN', + 'DS_REF_SRC', 'DTO_FORCE_BYPASS', 'DTO_FORCE_NO_BYPASS', + 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', 'DVOACLKC_IN_PHASE', + 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_PHASE', 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', + 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', 'DVOACLKD_IN_PHASE', + 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', 'DVOACLK_COARSE_SKEW_CNTL', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 'DVOACLK_FINE_SKEW_CNTL', 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', 'DVO_ENABLE_RST', + 'DVO_ENABLE_RST_DISABLE', 'DVO_ENABLE_RST_ENABLE', + 'DWB_CRC_CONT_EN_CONT', 'DWB_CRC_CONT_EN_ENUM', + 'DWB_CRC_CONT_EN_ONE_SHOT', 'DWB_CRC_SRC_SEL_DWB_IN', + 'DWB_CRC_SRC_SEL_DWB_OUT', 'DWB_CRC_SRC_SEL_ENUM', + 'DWB_CRC_SRC_SEL_OGAM_OUT', 'DWB_DATA_OVERFLOW_INT_TYPE_0', + 'DWB_DATA_OVERFLOW_INT_TYPE_1', 'DWB_DATA_OVERFLOW_INT_TYPE_ENUM', + 'DWB_DATA_OVERFLOW_TYPE_BUFFER', 'DWB_DATA_OVERFLOW_TYPE_ENUM', + 'DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW', + 'DWB_DATA_OVERFLOW_TYPE_VREADY', 'DWB_DATA_OVERFLOW_TYPE_VUPDATE', + 'DWB_DEBUG_SEL_DWBCP', 'DWB_DEBUG_SEL_ENUM', 'DWB_DEBUG_SEL_FC', + 'DWB_DEBUG_SEL_PERFMON', 'DWB_DEBUG_SEL_RESERVED', + 'DWB_GAMUT_REMAP_COEF_FORMAT_ENUM', + 'DWB_GAMUT_REMAP_COEF_FORMAT_S2_13', + 'DWB_GAMUT_REMAP_COEF_FORMAT_S3_12', + 'DWB_GAMUT_REMAP_MODE_BYPASS', 'DWB_GAMUT_REMAP_MODE_COEF_A', + 'DWB_GAMUT_REMAP_MODE_COEF_B', 'DWB_GAMUT_REMAP_MODE_ENUM', + 'DWB_GAMUT_REMAP_MODE_RESERVED', 'DWB_LUT_NUM_SEG', + 'DWB_MEM_PWR_FORCE_DIS', 'DWB_MEM_PWR_FORCE_DS', + 'DWB_MEM_PWR_FORCE_ENUM', 'DWB_MEM_PWR_FORCE_LS', + 'DWB_MEM_PWR_FORCE_SD', 'DWB_MEM_PWR_STATE_DS', + 'DWB_MEM_PWR_STATE_ENUM', 'DWB_MEM_PWR_STATE_LS', + 'DWB_MEM_PWR_STATE_ON', 'DWB_MEM_PWR_STATE_SD', + 'DWB_OGAM_LUT_CONFIG_MODE_DIFF', 'DWB_OGAM_LUT_CONFIG_MODE_ENUM', + 'DWB_OGAM_LUT_CONFIG_MODE_SAME', 'DWB_OGAM_LUT_HOST_SEL_ENUM', + 'DWB_OGAM_LUT_HOST_SEL_RAMA', 'DWB_OGAM_LUT_HOST_SEL_RAMB', + 'DWB_OGAM_LUT_READ_COLOR_SEL_B', + 'DWB_OGAM_LUT_READ_COLOR_SEL_ENUM', + 'DWB_OGAM_LUT_READ_COLOR_SEL_G', 'DWB_OGAM_LUT_READ_COLOR_SEL_R', + 'DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED', + 'DWB_OGAM_LUT_READ_DBG_DISABLE', 'DWB_OGAM_LUT_READ_DBG_ENABLE', + 'DWB_OGAM_LUT_READ_DBG_ENUM', 'DWB_OGAM_MODE_BYPASS', + 'DWB_OGAM_MODE_ENUM', 'DWB_OGAM_MODE_RAM_LUT_ENABLED', + 'DWB_OGAM_MODE_RESERVED', 'DWB_OGAM_PWL_DISABLE_ENUM', + 'DWB_OGAM_PWL_DISABLE_FALSE', 'DWB_OGAM_PWL_DISABLE_TRUE', + 'DWB_OGAM_SELECT_A', 'DWB_OGAM_SELECT_B', 'DWB_OGAM_SELECT_ENUM', + 'DWB_SEGMENTS_1', 'DWB_SEGMENTS_128', 'DWB_SEGMENTS_16', + 'DWB_SEGMENTS_2', 'DWB_SEGMENTS_32', 'DWB_SEGMENTS_4', + 'DWB_SEGMENTS_64', 'DWB_SEGMENTS_8', 'DWB_TEST_CLK_SEL_ENUM', + 'DWB_TEST_CLK_SEL_G', 'DWB_TEST_CLK_SEL_P', 'DWB_TEST_CLK_SEL_R', + 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE', + 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_0', + 'DX_PROTECTION_DX_PIPE_ENC_REQUIRED_TYPE_1', + 'DYNAMIC_DEEP_SLEEP_EN', 'DYNAMIC_DEEP_SLEEP_ENABLE', + 'DYNAMIC_LIGHT_SLEEP_EN', 'DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DYNAMIC_SHUT_DOWN_ENABLE', 'DbMemArbWatermarks', + 'DbPRTFaultBehavior', 'DbPSLControl', 'EARLY', + 'EARLY_Z_THEN_LATE_Z', 'EARLY_Z_THEN_RE_Z', + 'EFC_ACrYCb16161616_10LSB', 'EFC_ACrYCb16161616_10MSB', + 'EFC_ACrYCb16161616_12LSB', 'EFC_ACrYCb16161616_12MSB', + 'EFC_ACrYCb2101010', 'EFC_ACrYCb8888', 'EFC_ARGB1555', + 'EFC_ARGB16161616_10LSB', 'EFC_ARGB16161616_10MSB', + 'EFC_ARGB16161616_12LSB', 'EFC_ARGB16161616_12MSB', + 'EFC_ARGB16161616_FLOAT', 'EFC_ARGB16161616_SNORM', + 'EFC_ARGB16161616_UNORM', 'EFC_ARGB2101010', 'EFC_ARGB4444', + 'EFC_ARGB8888', 'EFC_AYCrCb16161616_10LSB', + 'EFC_AYCrCb16161616_10MSB', 'EFC_AYCrCb16161616_12LSB', + 'EFC_AYCrCb16161616_12MSB', 'EFC_AYCrCb8888', 'EFC_BGR101111_FIX', + 'EFC_BGR101111_FLOAT', 'EFC_BGR565', + 'EFC_CbYCrY10101010_422_PACKED', 'EFC_CbYCrY12121212_422_PACKED', + 'EFC_CbYCrY8888_422_PACKED', 'EFC_CrYCbA1010102', + 'EFC_CrYCbA16161616_10LSB', 'EFC_CrYCbA16161616_10MSB', + 'EFC_CrYCbA16161616_12LSB', 'EFC_CrYCbA16161616_12MSB', + 'EFC_CrYCbA8888', 'EFC_CrYCbY10101010_422_PACKED', + 'EFC_CrYCbY12121212_422_PACKED', 'EFC_CrYCbY8888_422_PACKED', + 'EFC_MONO_10LSB', 'EFC_MONO_10MSB', 'EFC_MONO_12LSB', + 'EFC_MONO_12MSB', 'EFC_MONO_16', 'EFC_MONO_8', + 'EFC_RGB111110_FIX', 'EFC_RGB111110_FLOAT', 'EFC_RGB565', + 'EFC_RGBA1010102', 'EFC_RGBA16161616_10LSB', + 'EFC_RGBA16161616_10MSB', 'EFC_RGBA16161616_12LSB', + 'EFC_RGBA16161616_12MSB', 'EFC_RGBA16161616_FLOAT', + 'EFC_RGBA16161616_SNORM', 'EFC_RGBA16161616_UNORM', + 'EFC_RGBA4444', 'EFC_RGBA5551', 'EFC_RGBA8888', + 'EFC_SURFACE_PIXEL_FORMAT', 'EFC_Y10_CbCr1010_420_PLANAR', + 'EFC_Y10_CrCb1010_420_PLANAR', 'EFC_Y12_CbCr1212_420_PLANAR', + 'EFC_Y12_CrCb1212_420_PLANAR', 'EFC_Y8_CbCr88_420_PLANAR', + 'EFC_Y8_CrCb88_420_PLANAR', 'EFC_YCbYCr10101010_422_PACKED', + 'EFC_YCbYCr12121212_422_PACKED', 'EFC_YCbYCr8888_422_PACKED', + 'EFC_YCrCbA16161616_10LSB', 'EFC_YCrCbA16161616_10MSB', + 'EFC_YCrCbA16161616_12LSB', 'EFC_YCrCbA16161616_12MSB', + 'EFC_YCrCbA8888', 'EFC_YCrYCb10101010_422_PACKED', + 'EFC_YCrYCb12121212_422_PACKED', 'EFC_YCrYCb8888_422_PACKED', + 'ENABLE', 'ENABLE_AMCLK0', 'ENABLE_AMCLK1', 'ENABLE_CLOCK', + 'ENABLE_DEBUG', 'ENABLE_ENUM', 'ENABLE_ENUM_DISABLED', + 'ENABLE_ENUM_ENABLED', 'ENABLE_JITTER_REMOVAL', + 'ENABLE_LEGACY_PIPELINE', 'ENABLE_MEM_PWR_CTRL', + 'ENABLE_NGG_PIPELINE', 'ENABLE_PWL', 'ENABLE_TF0_OPT', + 'ENABLE_TF1_OPT', 'ENABLE_THE_FEATURE', 'ENABLE_THE_FUNC_CLOCK', + 'ENABLE_THE_INTERRUPT', 'ENABLE_THE_REFCLK', 'END_OF_PIPE_IB_END', + 'END_OF_PIPE_INCR_DE', 'END_OF_ROW_MODE', 'ENUM_DCN_ACTIVE', + 'ENUM_DCN_NOT_ACTIVE', 'ENUM_DIO_DCN_ACTIVE_STATUS', + 'ENUM_DPG_BIT_DEPTH', 'ENUM_DPG_BIT_DEPTH_10BPC', + 'ENUM_DPG_BIT_DEPTH_12BPC', 'ENUM_DPG_BIT_DEPTH_6BPC', + 'ENUM_DPG_BIT_DEPTH_8BPC', 'ENUM_DPG_DISABLE', + 'ENUM_DPG_DYNAMIC_RANGE', 'ENUM_DPG_DYNAMIC_RANGE_CEA', + 'ENUM_DPG_DYNAMIC_RANGE_VESA', 'ENUM_DPG_EN', 'ENUM_DPG_ENABLE', + 'ENUM_DPG_FIELD_POLARITY', + 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', 'ENUM_DPG_MODE', + 'ENUM_DPG_MODE_HORIZONTAL_BAR', 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 'ENUM_DPG_MODE_RGB_DUAL_RAMP', 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 'ENUM_DPG_MODE_RGB_XR_BIAS', 'ENUM_DPG_MODE_VERTICAL_BAR', + 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 'ENUM_DP_DPHY_SYM32_CRC_END_EVENT', + 'ENUM_DP_DPHY_SYM32_CRC_START_EVENT', + 'ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE', + 'ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', + 'ENUM_DP_DPHY_SYM32_ENABLE', 'ENUM_DP_DPHY_SYM32_ENCRYPT_TYPE', + 'ENUM_DP_DPHY_SYM32_MODE', 'ENUM_DP_DPHY_SYM32_NUM_LANES', + 'ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING', + 'ENUM_DP_DPHY_SYM32_RESET', 'ENUM_DP_DPHY_SYM32_RESET_STATUS', + 'ENUM_DP_DPHY_SYM32_SAT_UPDATE', + 'ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING', + 'ENUM_DP_DPHY_SYM32_STATUS', + 'ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE', + 'ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE', + 'ENUM_DP_DPHY_SYM32_TP_PRBS_SEL', 'ENUM_DP_DPHY_SYM32_TP_SELECT', + 'ENUM_DP_SYM32_ENC_AUDIO_MUTE', + 'ENUM_DP_SYM32_ENC_CONTINUOUS_MODE', + 'ENUM_DP_SYM32_ENC_CRC_VALID', + 'ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH', + 'ENUM_DP_SYM32_ENC_ENABLE', + 'ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED', + 'ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION', + 'ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE', + 'ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING', + 'ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM', + 'ENUM_DP_SYM32_ENC_OVERFLOW_STATUS', 'ENUM_DP_SYM32_ENC_PENDING', + 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING', + 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE', + 'ENUM_DP_SYM32_ENC_POWER_STATE_ENUM', 'ENUM_DP_SYM32_ENC_RESET', + 'ENUM_DP_SYM32_ENC_SDP_PRIORITY', + 'ENUM_DP_SYM32_ENC_SOF_REFERENCE', + 'ENUM_DP_SYM32_ENC_VID_STREAM_DEFER', 'ENUM_DSCRM_DISABLE', + 'ENUM_DSCRM_EN', 'ENUM_DSCRM_ENABLE', 'ENUM_NUM_SIMD_PER_CU', + 'ES_STAGE_DS', 'ES_STAGE_OFF', 'ES_STAGE_REAL', 'EXOKAY', + 'EXPANSION_MODE', 'EXPANSION_MODE_CONSERVATIVE', + 'EXPANSION_MODE_OPTIMAL', 'EXPANSION_MODE_ZERO', + 'EXPORT_2C_32BPC_AR', 'EXPORT_2C_32BPC_GR', 'EXPORT_4C_16BPC', + 'EXPORT_4C_32BPC', 'EXPORT_ANY_Z', 'EXPORT_GREATER_THAN_Z', + 'EXPORT_LESS_THAN_Z', 'EXPORT_RESERVED', 'FAULT_FAIL', + 'FAULT_ONE', 'FAULT_PASS', 'FAULT_ZERO', 'FC_EYE_SELECTION_ENUM', + 'FC_EYE_SELECTION_LEFT_EYE', 'FC_EYE_SELECTION_RIGHT_EYE', + 'FC_EYE_SELECTION_STEREO_DIS', 'FC_FRAME_CAPTURE_RATE_ENUM', + 'FC_FRAME_CAPTURE_RATE_FULL', 'FC_FRAME_CAPTURE_RATE_HALF', + 'FC_FRAME_CAPTURE_RATE_QUARTER', 'FC_FRAME_CAPTURE_RATE_THIRD', + 'FC_STEREO_EYE_POLARITY_ENUM', 'FC_STEREO_EYE_POLARITY_LEFT', + 'FC_STEREO_EYE_POLARITY_RIGHT', 'FEC_ACTIVE_STATUS', 'FIX_S2_13', + 'FIX_S3_12', 'FLIP_ANY_FRAME', 'FLIP_LEFT_EYE', 'FLIP_RATE', + 'FLIP_RATE_0', 'FLIP_RATE_1', 'FLIP_RATE_2', 'FLIP_RATE_3', + 'FLIP_RATE_4', 'FLIP_RATE_5', 'FLIP_RATE_6', 'FLIP_RATE_7', + 'FLIP_RIGHT_EYE', 'FLUSH_AND_INV_CB_DATA_TS', + 'FLUSH_AND_INV_CB_META', 'FLUSH_AND_INV_CB_PIXEL_DATA', + 'FLUSH_AND_INV_DB_DATA_TS', 'FLUSH_AND_INV_DB_META', + 'FLUSH_CONTROL_FLUSH_NOT_STARTED', 'FLUSH_CONTROL_FLUSH_STARTED', + 'FLUSH_DFSM', 'FLUSH_ES_OUTPUT', 'FLUSH_HS_OUTPUT', 'FLUSH_SX_TS', + 'FMTMEM_DISABLE_MEM_PWR_CTRL', 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', 'FMTMEM_NO_FORCE_REQUEST', + 'FMTMEM_PWR_DIS_CTRL', 'FMTMEM_PWR_FORCE_CTRL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 'FMT_CLAMP_CNTL_COLOR_FORMAT', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', + 'FMT_CONTROL_PIXEL_ENCODING', + 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', + 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 'FMT_CONTROL_SUBSAMPLING_MODE', + 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', + 'FMT_CONTROL_SUBSAMPLING_ORDER', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', + 'FMT_DEBUG_CNTL_COLOR_SELECT', 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', 'FMT_DYNAMIC_EXP_MODE', + 'FMT_DYNAMIC_EXP_MODE_10to12', 'FMT_DYNAMIC_EXP_MODE_8to12', + 'FMT_FRAME_RANDOM_ENABLE_CONTROL', + 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', 'FMT_POWER_STATE_ENUM', + 'FMT_POWER_STATE_ENUM_DS', 'FMT_POWER_STATE_ENUM_LS', + 'FMT_POWER_STATE_ENUM_ON', 'FMT_POWER_STATE_ENUM_SD', + 'FMT_RGB_RANDOM_ENABLE_CONTROL', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', + 'FMT_SPATIAL_DITHER_MODE', 'FMT_SPATIAL_DITHER_MODE_0', + 'FMT_SPATIAL_DITHER_MODE_1', 'FMT_SPATIAL_DITHER_MODE_2', + 'FMT_SPATIAL_DITHER_MODE_3', 'FMT_STEREOSYNC_OVERRIDE_CONTROL', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', 'FORCE_00', + 'FORCE_BINNING_ON', 'FORCE_DEEP_SLEEP_REQUEST', 'FORCE_DISABLE', + 'FORCE_DISABLE_CLOCK', 'FORCE_EARLY_Z', 'FORCE_ENABLE', + 'FORCE_FF', 'FORCE_LATE_Z', 'FORCE_LIGHT_SLEEP_REQ', + 'FORCE_LIGHT_SLEEP_REQUEST', 'FORCE_OFF', + 'FORCE_ONE_ROW_FOR_FRAME', 'FORCE_ONE_ROW_FOR_FRAME_0', + 'FORCE_ONE_ROW_FOR_FRAME_1', 'FORCE_OPT_AUTO', + 'FORCE_OPT_DISABLE', 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 'FORCE_OPT_ENABLE_IF_SRC_A_1', 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', 'FORCE_RESERVED', 'FORCE_RE_Z', + 'FORCE_SENT', 'FORCE_SHUT_DOWN_REQUEST', 'FORCE_SUMM_BOTH', + 'FORCE_SUMM_MAXZ', 'FORCE_SUMM_MINZ', 'FORCE_SUMM_OFF', + 'FORCE_THE_CLOCK_DISABLED', 'FORMAT_CROSSBAR', + 'FORMAT_CROSSBAR_B', 'FORMAT_CROSSBAR_G', 'FORMAT_CROSSBAR_R', + 'FRAG_ALWAYS', 'FRAG_EQUAL', 'FRAG_GEQUAL', 'FRAG_GREATER', + 'FRAG_LEQUAL', 'FRAG_LESS', 'FRAG_NEVER', 'FRAG_NOTEQUAL', + 'ForceControl', 'GAMUT_COEF', 'GAMUT_COEF_B', 'GATCL1RequestType', + 'GATCL1_TYPE_BYPASS', 'GATCL1_TYPE_NORMAL', + 'GATCL1_TYPE_SHOOTDOWN', 'GB_EDC_DED_MODE', + 'GB_EDC_DED_MODE_HALT', 'GB_EDC_DED_MODE_INT_HALT', + 'GB_EDC_DED_MODE_LOG', 'GB_TILING_CONFIG_MACROTABLE_SIZE', + 'GB_TILING_CONFIG_TABLE_SIZE', 'GCRPerfSel', + 'GCR_PERF_SEL_ALL_REQ', + 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CPC_ALL_REQ', 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPC_METADATA_REQ', + 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 'GCR_PERF_SEL_CPC_TCP_REQ', + 'GCR_PERF_SEL_CPC_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPF_ALL_REQ', 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPF_METADATA_REQ', + 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 'GCR_PERF_SEL_CPF_TCP_REQ', + 'GCR_PERF_SEL_CPF_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPG_ALL_REQ', 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPG_METADATA_REQ', + 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 'GCR_PERF_SEL_CPG_TCP_REQ', + 'GCR_PERF_SEL_CPG_TCP_TLB_SHOOTDOWN_REQ', 'GCR_PERF_SEL_NONE', + 'GCR_PERF_SEL_PHY_REQ', 'GCR_PERF_SEL_PIO_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL1_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_REQ', 'GCR_PERF_SEL_PIO_GL2_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_REQ', 'GCR_PERF_SEL_PIO_METADATA_REQ', + 'GCR_PERF_SEL_PIO_SQC_DATA_REQ', 'GCR_PERF_SEL_PIO_SQC_INST_REQ', + 'GCR_PERF_SEL_PIO_TCP_REQ', + 'GCR_PERF_SEL_PIO_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_PM_ALL_REQ', 'GCR_PERF_SEL_PM_GL1_ALL_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_REQ', 'GCR_PERF_SEL_PM_GL2_ALL_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_REQ', 'GCR_PERF_SEL_PM_METADATA_REQ', + 'GCR_PERF_SEL_PM_SQC_DATA_REQ', 'GCR_PERF_SEL_PM_SQC_INST_REQ', + 'GCR_PERF_SEL_PM_TCP_REQ', + 'GCR_PERF_SEL_PM_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_RLC_ALL_REQ', 'GCR_PERF_SEL_RLC_GL1_ALL_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_REQ', 'GCR_PERF_SEL_RLC_GL2_ALL_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_REQ', 'GCR_PERF_SEL_RLC_METADATA_REQ', + 'GCR_PERF_SEL_RLC_SQC_DATA_REQ', 'GCR_PERF_SEL_RLC_SQC_INST_REQ', + 'GCR_PERF_SEL_RLC_TCP_REQ', + 'GCR_PERF_SEL_RLC_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_SDMA0_ALL_REQ', 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 'GCR_PERF_SEL_SDMA0_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_SDMA1_ALL_REQ', 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 'GCR_PERF_SEL_SDMA1_TCP_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_FILTERED_RET', + 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 'GCR_PERF_SEL_UTCL2_REQ', 'GCR_PERF_SEL_UTCL2_RET', + 'GCR_PERF_SEL_VIRT_REQ', 'GDS_PERFCOUNT_SELECT', + 'GDS_PERF_SEL_GWS_BYPASS', 'GDS_PERF_SEL_GWS_RELEASED', + 'GDS_PERF_SEL_SE0_2COMP_REQ', 'GDS_PERF_SEL_SE0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE0_GDS_BYTE_OP', 'GDS_PERF_SEL_SE0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE0_GDS_RD_OP', 'GDS_PERF_SEL_SE0_GDS_REL_OP', + 'GDS_PERF_SEL_SE0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE0_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE0_GDS_WR_OP', + 'GDS_PERF_SEL_SE0_NORET', 'GDS_PERF_SEL_SE0_ORD_CNT', + 'GDS_PERF_SEL_SE0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_RET', + 'GDS_PERF_SEL_SE1_2COMP_REQ', 'GDS_PERF_SEL_SE1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE1_GDS_BYTE_OP', 'GDS_PERF_SEL_SE1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE1_GDS_RD_OP', 'GDS_PERF_SEL_SE1_GDS_REL_OP', + 'GDS_PERF_SEL_SE1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE1_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE1_GDS_WR_OP', + 'GDS_PERF_SEL_SE1_NORET', 'GDS_PERF_SEL_SE1_ORD_CNT', + 'GDS_PERF_SEL_SE1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE1_RET', + 'GDS_PERF_SEL_SE2_2COMP_REQ', 'GDS_PERF_SEL_SE2_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE2_GDS_BYTE_OP', 'GDS_PERF_SEL_SE2_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE2_GDS_RD_OP', 'GDS_PERF_SEL_SE2_GDS_REL_OP', + 'GDS_PERF_SEL_SE2_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE2_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE2_GDS_WR_OP', + 'GDS_PERF_SEL_SE2_NORET', 'GDS_PERF_SEL_SE2_ORD_CNT', + 'GDS_PERF_SEL_SE2_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE2_RET', + 'GDS_PERF_SEL_SE3_2COMP_REQ', 'GDS_PERF_SEL_SE3_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE3_GDS_BYTE_OP', 'GDS_PERF_SEL_SE3_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE3_GDS_RD_OP', 'GDS_PERF_SEL_SE3_GDS_REL_OP', + 'GDS_PERF_SEL_SE3_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE3_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE3_GDS_WR_OP', + 'GDS_PERF_SEL_SE3_NORET', 'GDS_PERF_SEL_SE3_ORD_CNT', + 'GDS_PERF_SEL_SE3_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE3_RET', + 'GDS_PERF_SEL_SE4_2COMP_REQ', 'GDS_PERF_SEL_SE4_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE4_GDS_BYTE_OP', 'GDS_PERF_SEL_SE4_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE4_GDS_RD_OP', 'GDS_PERF_SEL_SE4_GDS_REL_OP', + 'GDS_PERF_SEL_SE4_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE4_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE4_GDS_WR_OP', + 'GDS_PERF_SEL_SE4_NORET', 'GDS_PERF_SEL_SE4_ORD_CNT', + 'GDS_PERF_SEL_SE4_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE4_RET', + 'GDS_PERF_SEL_SE5_2COMP_REQ', 'GDS_PERF_SEL_SE5_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE5_GDS_BYTE_OP', 'GDS_PERF_SEL_SE5_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE5_GDS_RD_OP', 'GDS_PERF_SEL_SE5_GDS_REL_OP', + 'GDS_PERF_SEL_SE5_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE5_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE5_GDS_WR_OP', + 'GDS_PERF_SEL_SE5_NORET', 'GDS_PERF_SEL_SE5_ORD_CNT', + 'GDS_PERF_SEL_SE5_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE5_RET', + 'GDS_PERF_SEL_SE6_2COMP_REQ', 'GDS_PERF_SEL_SE6_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE6_GDS_BYTE_OP', 'GDS_PERF_SEL_SE6_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE6_GDS_RD_OP', 'GDS_PERF_SEL_SE6_GDS_REL_OP', + 'GDS_PERF_SEL_SE6_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE6_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE6_GDS_WR_OP', + 'GDS_PERF_SEL_SE6_NORET', 'GDS_PERF_SEL_SE6_ORD_CNT', + 'GDS_PERF_SEL_SE6_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE6_RET', + 'GDS_PERF_SEL_SE7_2COMP_REQ', 'GDS_PERF_SEL_SE7_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE7_GDS_BYTE_OP', 'GDS_PERF_SEL_SE7_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE7_GDS_RD_OP', 'GDS_PERF_SEL_SE7_GDS_REL_OP', + 'GDS_PERF_SEL_SE7_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE7_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE7_GDS_WR_OP', + 'GDS_PERF_SEL_SE7_NORET', 'GDS_PERF_SEL_SE7_ORD_CNT', + 'GDS_PERF_SEL_SE7_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE7_RET', + 'GDS_PERF_SEL_WBUF_WR', 'GDS_PERF_SEL_WR_COMP', + 'GE1_PERFCOUNT_SELECT', 'GE2_DIST_PERFCOUNT_SELECT', + 'GE2_SE_PERFCOUNT_SELECT', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', + 'GENERIC_STEREOSYNC_SEL', 'GENERIC_STEREOSYNC_SEL_D1', + 'GENERIC_STEREOSYNC_SEL_D2', 'GENERIC_STEREOSYNC_SEL_D3', + 'GENERIC_STEREOSYNC_SEL_D4', 'GENERIC_STEREOSYNC_SEL_RESERVED', + 'GEN_ONE', 'GEN_RESERVED', 'GEN_TWO', 'GEN_ZERO', + 'GL0V_CACHE_POLICIES', 'GL0V_CACHE_POLICY_HIT_EVICT', + 'GL0V_CACHE_POLICY_HIT_LRU', 'GL0V_CACHE_POLICY_MISS_EVICT', + 'GL0V_CACHE_POLICY_MISS_LRU', 'GL1A_PERF_SEL', + 'GL1A_PERF_SEL_ARB_REQUESTS', 'GL1A_PERF_SEL_BURST_COUNT_GL1C0', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C1', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C2', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C3', 'GL1A_PERF_SEL_BUSY', + 'GL1A_PERF_SEL_CYCLE', 'GL1A_PERF_SEL_REQUEST_GL1C0', + 'GL1A_PERF_SEL_REQUEST_GL1C1', 'GL1A_PERF_SEL_REQUEST_GL1C2', + 'GL1A_PERF_SEL_REQUEST_GL1C3', 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'GL1A_PERF_SEL_STALL_GL1C0', 'GL1A_PERF_SEL_STALL_GL1C1', + 'GL1A_PERF_SEL_STALL_GL1C2', 'GL1A_PERF_SEL_STALL_GL1C3', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 'GL1A_PERF_SEL_WDS_32B_GL1C0', 'GL1A_PERF_SEL_WDS_32B_GL1C1', + 'GL1A_PERF_SEL_WDS_32B_GL1C2', 'GL1A_PERF_SEL_WDS_32B_GL1C3', + 'GL1C_PERF_SEL', 'GL1C_PERF_SEL_ARB_RET_LEVEL', + 'GL1C_PERF_SEL_BUSY', 'GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 'GL1C_PERF_SEL_CYCLE', 'GL1C_PERF_SEL_GL2_REQ_PREFETCH', + 'GL1C_PERF_SEL_GL2_REQ_READ', 'GL1C_PERF_SEL_GL2_REQ_READ_128B', + 'GL1C_PERF_SEL_GL2_REQ_READ_32B', + 'GL1C_PERF_SEL_GL2_REQ_READ_64B', + 'GL1C_PERF_SEL_GL2_REQ_READ_LATENCY', + 'GL1C_PERF_SEL_GL2_REQ_WRITE', 'GL1C_PERF_SEL_GL2_REQ_WRITE_32B', + 'GL1C_PERF_SEL_GL2_REQ_WRITE_64B', + 'GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'GL1C_PERF_SEL_REQ', + 'GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET', 'GL1C_PERF_SEL_REQ_CLIENT0', + 'GL1C_PERF_SEL_REQ_CLIENT1', 'GL1C_PERF_SEL_REQ_CLIENT10', + 'GL1C_PERF_SEL_REQ_CLIENT11', 'GL1C_PERF_SEL_REQ_CLIENT12', + 'GL1C_PERF_SEL_REQ_CLIENT13', 'GL1C_PERF_SEL_REQ_CLIENT14', + 'GL1C_PERF_SEL_REQ_CLIENT15', 'GL1C_PERF_SEL_REQ_CLIENT16', + 'GL1C_PERF_SEL_REQ_CLIENT17', 'GL1C_PERF_SEL_REQ_CLIENT18', + 'GL1C_PERF_SEL_REQ_CLIENT19', 'GL1C_PERF_SEL_REQ_CLIENT2', + 'GL1C_PERF_SEL_REQ_CLIENT20', 'GL1C_PERF_SEL_REQ_CLIENT21', + 'GL1C_PERF_SEL_REQ_CLIENT22', 'GL1C_PERF_SEL_REQ_CLIENT23', + 'GL1C_PERF_SEL_REQ_CLIENT24', 'GL1C_PERF_SEL_REQ_CLIENT25', + 'GL1C_PERF_SEL_REQ_CLIENT26', 'GL1C_PERF_SEL_REQ_CLIENT27', + 'GL1C_PERF_SEL_REQ_CLIENT3', 'GL1C_PERF_SEL_REQ_CLIENT4', + 'GL1C_PERF_SEL_REQ_CLIENT5', 'GL1C_PERF_SEL_REQ_CLIENT6', + 'GL1C_PERF_SEL_REQ_CLIENT7', 'GL1C_PERF_SEL_REQ_CLIENT8', + 'GL1C_PERF_SEL_REQ_CLIENT9', 'GL1C_PERF_SEL_REQ_MISS', + 'GL1C_PERF_SEL_REQ_NOP_ACK', 'GL1C_PERF_SEL_REQ_NOP_RTN0', + 'GL1C_PERF_SEL_REQ_READ', 'GL1C_PERF_SEL_REQ_READ_128B', + 'GL1C_PERF_SEL_REQ_READ_32B', 'GL1C_PERF_SEL_REQ_READ_64B', + 'GL1C_PERF_SEL_REQ_READ_POLICY_HIT_EVICT', + 'GL1C_PERF_SEL_REQ_READ_POLICY_HIT_LRU', + 'GL1C_PERF_SEL_REQ_READ_POLICY_MISS_EVICT', + 'GL1C_PERF_SEL_REQ_SHADER_INV', 'GL1C_PERF_SEL_REQ_WRITE', + 'GL1C_PERF_SEL_REQ_WRITE_32B', 'GL1C_PERF_SEL_REQ_WRITE_64B', + 'GL1C_PERF_SEL_STALL_GCR_INV', 'GL1C_PERF_SEL_STALL_GL2_GL1', + 'GL1C_PERF_SEL_STALL_LFIFO_FULL', + 'GL1C_PERF_SEL_STALL_NOTHING_REPLACEABLE', + 'GL1C_PERF_SEL_STALL_NO_AVAILABLE_ACK_ALLOC', + 'GL1C_PERF_SEL_STALL_VM', 'GL1C_PERF_SEL_STARVE', + 'GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 'GL1C_PERF_SEL_UTCL0_LFIFO_FULL', + 'GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 'GL1C_PERF_SEL_UTCL0_PERMISSION_MISS', + 'GL1C_PERF_SEL_UTCL0_REQUEST', + 'GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 'GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 'GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 'GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 'GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 'GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT', + 'GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS', + 'GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', + 'GL1H_REQ_PERF_SEL', 'GL1H_REQ_PERF_SEL_ARB_REQUESTS', + 'GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_0', + 'GL1H_REQ_PERF_SEL_BURST_COUNT_GL1_1', 'GL1H_REQ_PERF_SEL_BUSY', + 'GL1H_REQ_PERF_SEL_CYCLE', 'GL1H_REQ_PERF_SEL_REQUEST_GL1_0', + 'GL1H_REQ_PERF_SEL_REQUEST_GL1_1', + 'GL1H_REQ_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'GL1H_REQ_PERF_SEL_STALL_GL1_0', 'GL1H_REQ_PERF_SEL_STALL_GL1_1', + 'GL1H_REQ_PERF_SEL_WDS_32B_GL1_0', + 'GL1H_REQ_PERF_SEL_WDS_32B_GL1_1', 'GL1_CACHE_POLICIES', + 'GL1_CACHE_POLICY_HIT_EVICT', 'GL1_CACHE_POLICY_HIT_LRU', + 'GL1_CACHE_POLICY_MISS_EVICT', 'GL1_CACHE_POLICY_MISS_LRU', + 'GL1_CACHE_STORE_POLICIES', 'GL1_CACHE_STORE_POLICY_BYPASS', + 'GL2A_PERF_SEL', 'GL2A_PERF_SEL_BUSY', 'GL2A_PERF_SEL_CYCLE', + 'GL2A_PERF_SEL_NONE', 'GL2A_PERF_SEL_REQ_BURST_CLIENT0', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT1', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT10', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT11', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT12', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT13', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT14', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT15', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT2', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT3', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT4', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT5', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT6', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT7', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT8', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT9', + 'GL2A_PERF_SEL_REQ_BURST_GL2C0', 'GL2A_PERF_SEL_REQ_BURST_GL2C1', + 'GL2A_PERF_SEL_REQ_BURST_GL2C2', 'GL2A_PERF_SEL_REQ_BURST_GL2C3', + 'GL2A_PERF_SEL_REQ_BURST_GL2C4', 'GL2A_PERF_SEL_REQ_BURST_GL2C5', + 'GL2A_PERF_SEL_REQ_BURST_GL2C6', 'GL2A_PERF_SEL_REQ_BURST_GL2C7', + 'GL2A_PERF_SEL_REQ_GL2C0', 'GL2A_PERF_SEL_REQ_GL2C1', + 'GL2A_PERF_SEL_REQ_GL2C2', 'GL2A_PERF_SEL_REQ_GL2C3', + 'GL2A_PERF_SEL_REQ_GL2C4', 'GL2A_PERF_SEL_REQ_GL2C5', + 'GL2A_PERF_SEL_REQ_GL2C6', 'GL2A_PERF_SEL_REQ_GL2C7', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C0', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C1', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C2', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C3', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C4', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C5', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C6', + 'GL2A_PERF_SEL_REQ_HI_PRIO_GL2C7', + 'GL2A_PERF_SEL_REQ_STALL_GL2C0', 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 'GL2A_PERF_SEL_REQ_STALL_GL2C2', 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 'GL2A_PERF_SEL_REQ_STALL_GL2C4', 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 'GL2A_PERF_SEL_REQ_STALL_GL2C6', 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9', + 'GL2A_PERF_SEL_RTN_CLIENT0', 'GL2A_PERF_SEL_RTN_CLIENT1', + 'GL2A_PERF_SEL_RTN_CLIENT10', 'GL2A_PERF_SEL_RTN_CLIENT11', + 'GL2A_PERF_SEL_RTN_CLIENT12', 'GL2A_PERF_SEL_RTN_CLIENT13', + 'GL2A_PERF_SEL_RTN_CLIENT14', 'GL2A_PERF_SEL_RTN_CLIENT15', + 'GL2A_PERF_SEL_RTN_CLIENT2', 'GL2A_PERF_SEL_RTN_CLIENT3', + 'GL2A_PERF_SEL_RTN_CLIENT4', 'GL2A_PERF_SEL_RTN_CLIENT5', + 'GL2A_PERF_SEL_RTN_CLIENT6', 'GL2A_PERF_SEL_RTN_CLIENT7', + 'GL2A_PERF_SEL_RTN_CLIENT8', 'GL2A_PERF_SEL_RTN_CLIENT9', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9', + 'GL2A_PERF_SEL_RTN_STALL_GL2C0', 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 'GL2A_PERF_SEL_RTN_STALL_GL2C2', 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 'GL2A_PERF_SEL_RTN_STALL_GL2C4', 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 'GL2A_PERF_SEL_RTN_STALL_GL2C6', 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 'GL2C_PERF_SEL', 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 'GL2C_PERF_SEL_ATOMIC', 'GL2C_PERF_SEL_BUBBLE', + 'GL2C_PERF_SEL_BUSY', 'GL2C_PERF_SEL_BYPASS_REQ', + 'GL2C_PERF_SEL_CLIENT0_REQ', 'GL2C_PERF_SEL_CLIENT10_REQ', + 'GL2C_PERF_SEL_CLIENT11_REQ', 'GL2C_PERF_SEL_CLIENT12_REQ', + 'GL2C_PERF_SEL_CLIENT13_REQ', 'GL2C_PERF_SEL_CLIENT14_REQ', + 'GL2C_PERF_SEL_CLIENT15_REQ', 'GL2C_PERF_SEL_CLIENT1_REQ', + 'GL2C_PERF_SEL_CLIENT2_REQ', 'GL2C_PERF_SEL_CLIENT3_REQ', + 'GL2C_PERF_SEL_CLIENT4_REQ', 'GL2C_PERF_SEL_CLIENT5_REQ', + 'GL2C_PERF_SEL_CLIENT6_REQ', 'GL2C_PERF_SEL_CLIENT7_REQ', + 'GL2C_PERF_SEL_CLIENT8_REQ', 'GL2C_PERF_SEL_CLIENT9_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL0_REQ', 'GL2C_PERF_SEL_CM_CHANNEL10_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL11_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL12_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL13_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL14_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL15_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL16_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL17_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL18_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL19_REQ', 'GL2C_PERF_SEL_CM_CHANNEL1_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL20_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL21_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL22_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL23_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL24_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL25_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL26_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL27_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL28_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL29_REQ', 'GL2C_PERF_SEL_CM_CHANNEL2_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL30_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL31_REQ', 'GL2C_PERF_SEL_CM_CHANNEL3_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL4_REQ', 'GL2C_PERF_SEL_CM_CHANNEL5_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL6_REQ', 'GL2C_PERF_SEL_CM_CHANNEL7_REQ', + 'GL2C_PERF_SEL_CM_CHANNEL8_REQ', 'GL2C_PERF_SEL_CM_CHANNEL9_REQ', + 'GL2C_PERF_SEL_CM_COLOR_32B_WR_REQ', + 'GL2C_PERF_SEL_CM_COLOR_64B_WR_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_COLOR_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_ATOMIC_STENCIL_REQ', + 'GL2C_PERF_SEL_CM_COMP_COLOR_DIS_REQ', + 'GL2C_PERF_SEL_CM_COMP_COLOR_EN_REQ', + 'GL2C_PERF_SEL_CM_COMP_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_RB_SKIP_REQ', + 'GL2C_PERF_SEL_CM_COMP_READ_REQ', + 'GL2C_PERF_SEL_CM_COMP_STENCIL_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_COLOR_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH16_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_DEPTH32_REQ', + 'GL2C_PERF_SEL_CM_COMP_WRITE_STENCIL_REQ', + 'GL2C_PERF_SEL_CM_DCC_IN_XFC', 'GL2C_PERF_SEL_CM_DCC_OUT_1x1', + 'GL2C_PERF_SEL_CM_DCC_OUT_1x2', 'GL2C_PERF_SEL_CM_DCC_OUT_2x1', + 'GL2C_PERF_SEL_CM_DCC_OUT_2x2', 'GL2C_PERF_SEL_CM_DCC_OUT_CONST', + 'GL2C_PERF_SEL_CM_DCC_OUT_UNCOMP', 'GL2C_PERF_SEL_CM_DCC_OUT_XFC', + 'GL2C_PERF_SEL_CM_DCC_STALL', 'GL2C_PERF_SEL_CM_FULL_WRITE_REQ', + 'GL2C_PERF_SEL_CM_MERGE_BUF_FULL', + 'GL2C_PERF_SEL_CM_METADATA_WR_REQ', 'GL2C_PERF_SEL_CM_NOOP_REQ', + 'GL2C_PERF_SEL_CM_NO_ACK_REQ', 'GL2C_PERF_SEL_CM_READ_BACK_REQ', + 'GL2C_PERF_SEL_CM_RVF_FULL', 'GL2C_PERF_SEL_CM_SDR_FULL', + 'GL2C_PERF_SEL_CM_WR_ACK_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', 'GL2C_PERF_SEL_CYCLE', + 'GL2C_PERF_SEL_C_RO_S_REQ', 'GL2C_PERF_SEL_C_RO_US_REQ', + 'GL2C_PERF_SEL_C_RW_S_REQ', 'GL2C_PERF_SEL_C_RW_US_REQ', + 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', 'GL2C_PERF_SEL_EA_ATOMIC', + 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', 'GL2C_PERF_SEL_EA_OUTSTANDING', + 'GL2C_PERF_SEL_EA_RDREQ_128B', 'GL2C_PERF_SEL_EA_RDREQ_32B', + 'GL2C_PERF_SEL_EA_RDREQ_64B', 'GL2C_PERF_SEL_EA_RDREQ_96B', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM', 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_SNOOP', 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', + 'GL2C_PERF_SEL_EA_RDRET_NACK', + 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 'GL2C_PERF_SEL_EA_RD_MDC_32B', 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', + 'GL2C_PERF_SEL_EA_WRREQ_64B', 'GL2C_PERF_SEL_EA_WRREQ_DRAM', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 'GL2C_PERF_SEL_EA_WRREQ_SNOOP', 'GL2C_PERF_SEL_EA_WRRET_NACK', + 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', 'GL2C_PERF_SEL_EVICT', + 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', 'GL2C_PERF_SEL_FULL_HIT', + 'GL2C_PERF_SEL_GARLIC_READ', 'GL2C_PERF_SEL_GARLIC_WRITE', + 'GL2C_PERF_SEL_GCR_ALL', 'GL2C_PERF_SEL_GCR_DISCARD', + 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', 'GL2C_PERF_SEL_GCR_INV', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', 'GL2C_PERF_SEL_GCR_MDC_INV', + 'GL2C_PERF_SEL_GCR_MDC_INV_ALL', + 'GL2C_PERF_SEL_GCR_MDC_INV_RANGE', 'GL2C_PERF_SEL_GCR_RANGE', + 'GL2C_PERF_SEL_GCR_UNSHARED', 'GL2C_PERF_SEL_GCR_VOL', + 'GL2C_PERF_SEL_GCR_WB', 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', 'GL2C_PERF_SEL_GL2A_LEVEL', + 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', 'GL2C_PERF_SEL_HIT', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9', + 'GL2C_PERF_SEL_IB_CM_STALL', 'GL2C_PERF_SEL_IB_REQ', + 'GL2C_PERF_SEL_IB_STALL', 'GL2C_PERF_SEL_IB_TAG_STALL', + 'GL2C_PERF_SEL_INTERNAL_PROBE', 'GL2C_PERF_SEL_IO_READ', + 'GL2C_PERF_SEL_IO_WRITE', 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', + 'GL2C_PERF_SEL_LRU_REQ', 'GL2C_PERF_SEL_MC_RDREQ', + 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', 'GL2C_PERF_SEL_MC_WRREQ', + 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', 'GL2C_PERF_SEL_MC_WRREQ_STALL', + 'GL2C_PERF_SEL_MDC_INV_METADATA', 'GL2C_PERF_SEL_MDC_LEVEL', + 'GL2C_PERF_SEL_MDC_REQ', 'GL2C_PERF_SEL_MDC_SECTOR_HIT', + 'GL2C_PERF_SEL_MDC_SECTOR_MISS', + 'GL2C_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_MDC_TAG_HIT', + 'GL2C_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 'GL2C_PERF_SEL_MDC_TAG_STALL', + 'GL2C_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 'GL2C_PERF_SEL_METADATA_READ_REQ', 'GL2C_PERF_SEL_MISS', + 'GL2C_PERF_SEL_NOA_REQ', 'GL2C_PERF_SEL_NONE', + 'GL2C_PERF_SEL_NOP_ACK', 'GL2C_PERF_SEL_NOP_RTN0', + 'GL2C_PERF_SEL_NORMAL_EVICT', 'GL2C_PERF_SEL_NORMAL_WRITEBACK', + 'GL2C_PERF_SEL_ONION_READ', 'GL2C_PERF_SEL_ONION_WRITE', + 'GL2C_PERF_SEL_PARTIAL_32B_HIT', 'GL2C_PERF_SEL_PARTIAL_64B_HIT', + 'GL2C_PERF_SEL_PARTIAL_96B_HIT', 'GL2C_PERF_SEL_PROBE', + 'GL2C_PERF_SEL_PROBE_ALL', 'GL2C_PERF_SEL_PROBE_EVICT', + 'GL2C_PERF_SEL_PROBE_FILTER_DISABLED', + 'GL2C_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 'GL2C_PERF_SEL_READ', 'GL2C_PERF_SEL_READ_128_REQ', + 'GL2C_PERF_SEL_READ_32_REQ', 'GL2C_PERF_SEL_READ_64_REQ', + 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', 'GL2C_PERF_SEL_REQ', + 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', 'GL2C_PERF_SEL_RETURN_ACK', + 'GL2C_PERF_SEL_RETURN_DATA', 'GL2C_PERF_SEL_SHARED_REQ', + 'GL2C_PERF_SEL_SRC_FIFO_FULL', 'GL2C_PERF_SEL_STREAM_REQ', + 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_FILTER_STALL', + 'GL2C_PERF_SEL_TAG_PROBE_STALL', + 'GL2C_PERF_SEL_TAG_READ_DST_STALL', 'GL2C_PERF_SEL_TAG_STALL', + 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', 'GL2C_PERF_SEL_UC_REQ', + 'GL2C_PERF_SEL_UNCACHED_WRITE', 'GL2C_PERF_SEL_VOL_REQ', + 'GL2C_PERF_SEL_WRITE', 'GL2C_PERF_SEL_WRITEBACK', + 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 'GL2C_PERF_SEL_WRITE_32_REQ', 'GL2C_PERF_SEL_WRITE_64_REQ', + 'GL2_CACHE_POLICIES', 'GL2_CACHE_POLICY_BYPASS', + 'GL2_CACHE_POLICY_LRU', 'GL2_CACHE_POLICY_NOA', + 'GL2_CACHE_POLICY_STREAM', 'GL2_EA_CID', 'GL2_EA_CID_CLIENT', + 'GL2_EA_CID_CP', 'GL2_EA_CID_CPDMA', 'GL2_EA_CID_DCC', + 'GL2_EA_CID_FMASK', 'GL2_EA_CID_HTILE', 'GL2_EA_CID_MES', + 'GL2_EA_CID_RLC', 'GL2_EA_CID_RT', 'GL2_EA_CID_SDMA', + 'GL2_EA_CID_SQC', 'GL2_EA_CID_TCPMETA', 'GL2_EA_CID_UTCL2', + 'GL2_EA_CID_ZPCPSD', 'GL2_EA_CID_Z_STENCIL', 'GL2_NACKS', + 'GL2_NACK_DATA_ERROR', 'GL2_NACK_NO_FAULT', 'GL2_NACK_PAGE_FAULT', + 'GL2_NACK_PROTECTION_FAULT', 'GL2_OP', 'GL2_OP_ATOMIC_ADD_32', + 'GL2_OP_ATOMIC_ADD_64', 'GL2_OP_ATOMIC_ADD_RTN_32', + 'GL2_OP_ATOMIC_ADD_RTN_64', 'GL2_OP_ATOMIC_AND_32', + 'GL2_OP_ATOMIC_AND_64', 'GL2_OP_ATOMIC_AND_RTN_32', + 'GL2_OP_ATOMIC_AND_RTN_64', 'GL2_OP_ATOMIC_CLAMP_SUB_RTN_32', + 'GL2_OP_ATOMIC_CMPSWAP_32', 'GL2_OP_ATOMIC_CMPSWAP_64', + 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_DEC_32', 'GL2_OP_ATOMIC_DEC_64', + 'GL2_OP_ATOMIC_DEC_RTN_32', 'GL2_OP_ATOMIC_DEC_RTN_64', + 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FCMPSWAP_32', 'GL2_OP_ATOMIC_FCMPSWAP_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_FMAX_32', 'GL2_OP_ATOMIC_FMAX_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMAX_RTN_32', 'GL2_OP_ATOMIC_FMAX_RTN_64', + 'GL2_OP_ATOMIC_FMIN_32', 'GL2_OP_ATOMIC_FMIN_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMIN_RTN_32', 'GL2_OP_ATOMIC_FMIN_RTN_64', + 'GL2_OP_ATOMIC_INC_32', 'GL2_OP_ATOMIC_INC_64', + 'GL2_OP_ATOMIC_INC_RTN_32', 'GL2_OP_ATOMIC_INC_RTN_64', + 'GL2_OP_ATOMIC_OR_32', 'GL2_OP_ATOMIC_OR_64', + 'GL2_OP_ATOMIC_OR_RTN_32', 'GL2_OP_ATOMIC_OR_RTN_64', + 'GL2_OP_ATOMIC_SMAX_32', 'GL2_OP_ATOMIC_SMAX_64', + 'GL2_OP_ATOMIC_SMAX_RTN_32', 'GL2_OP_ATOMIC_SMAX_RTN_64', + 'GL2_OP_ATOMIC_SMIN_32', 'GL2_OP_ATOMIC_SMIN_64', + 'GL2_OP_ATOMIC_SMIN_RTN_32', 'GL2_OP_ATOMIC_SMIN_RTN_64', + 'GL2_OP_ATOMIC_SUB_32', 'GL2_OP_ATOMIC_SUB_64', + 'GL2_OP_ATOMIC_SUB_RTN_32', 'GL2_OP_ATOMIC_SUB_RTN_64', + 'GL2_OP_ATOMIC_SWAP_32', 'GL2_OP_ATOMIC_SWAP_64', + 'GL2_OP_ATOMIC_SWAP_RTN_32', 'GL2_OP_ATOMIC_SWAP_RTN_64', + 'GL2_OP_ATOMIC_UMAX_32', 'GL2_OP_ATOMIC_UMAX_64', + 'GL2_OP_ATOMIC_UMAX_8', 'GL2_OP_ATOMIC_UMAX_RTN_32', + 'GL2_OP_ATOMIC_UMAX_RTN_64', 'GL2_OP_ATOMIC_UMIN_32', + 'GL2_OP_ATOMIC_UMIN_64', 'GL2_OP_ATOMIC_UMIN_8', + 'GL2_OP_ATOMIC_UMIN_RTN_32', 'GL2_OP_ATOMIC_UMIN_RTN_64', + 'GL2_OP_ATOMIC_XOR_32', 'GL2_OP_ATOMIC_XOR_64', + 'GL2_OP_ATOMIC_XOR_RTN_32', 'GL2_OP_ATOMIC_XOR_RTN_64', + 'GL2_OP_GL1_INV', 'GL2_OP_MASKS', 'GL2_OP_MASK_64', + 'GL2_OP_MASK_FLUSH_DENROM', 'GL2_OP_MASK_NO_RTN', + 'GL2_OP_NOP_ACK', 'GL2_OP_NOP_RTN0', 'GL2_OP_PROBE_FILTER', + 'GL2_OP_READ', 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 'GL2_OP_WRITE', 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE', + 'GLOBAL_CONTROL_CONTROLLER_RESET', 'GLOBAL_CONTROL_FLUSH_CONTROL', + 'GLOBAL_STATUS_FLUSH_STATUS', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 'GL__CONSTANT_ALPHA', 'GL__CONSTANT_COLOR', 'GL__DST_ALPHA', + 'GL__DST_COLOR', 'GL__ONE', 'GL__ONE_MINUS_CONSTANT_ALPHA', + 'GL__ONE_MINUS_CONSTANT_COLOR', 'GL__ONE_MINUS_DST_ALPHA', + 'GL__ONE_MINUS_DST_COLOR', 'GL__ONE_MINUS_SRC_ALPHA', + 'GL__ONE_MINUS_SRC_COLOR', 'GL__SRC_ALPHA', + 'GL__SRC_ALPHA_SATURATE', 'GL__SRC_COLOR', 'GL__ZERO', + 'GRBM_PERF_SEL', 'GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY', + 'GRBM_PERF_SEL_BCI_BUSY', 'GRBM_PERF_SEL_CB_BUSY', + 'GRBM_PERF_SEL_CB_CLEAN', 'GRBM_PERF_SEL_CH_BUSY', + 'GRBM_PERF_SEL_COUNT', 'GRBM_PERF_SEL_CPAXI_BUSY', + 'GRBM_PERF_SEL_CPC_BUSY', 'GRBM_PERF_SEL_CPF_BUSY', + 'GRBM_PERF_SEL_CPG_BUSY', 'GRBM_PERF_SEL_CP_BUSY', + 'GRBM_PERF_SEL_CP_COHER_BUSY', 'GRBM_PERF_SEL_CP_DMA_BUSY', + 'GRBM_PERF_SEL_DB_BUSY', 'GRBM_PERF_SEL_DB_CLEAN', + 'GRBM_PERF_SEL_EA_BUSY', 'GRBM_PERF_SEL_GDS_BUSY', + 'GRBM_PERF_SEL_GE_BUSY', 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', + 'GRBM_PERF_SEL_GL1CC_BUSY', 'GRBM_PERF_SEL_GL1H_BUSY', + 'GRBM_PERF_SEL_GL2CC_BUSY', 'GRBM_PERF_SEL_GUI_ACTIVE', + 'GRBM_PERF_SEL_GUS_BUSY', 'GRBM_PERF_SEL_PA_BUSY', + 'GRBM_PERF_SEL_PC_BUSY', 'GRBM_PERF_SEL_PH_BUSY', + 'GRBM_PERF_SEL_PMM_BUSY', 'GRBM_PERF_SEL_RLC_BUSY', + 'GRBM_PERF_SEL_RMI_BUSY', 'GRBM_PERF_SEL_SC_BUSY', + 'GRBM_PERF_SEL_SDMA_BUSY', 'GRBM_PERF_SEL_SPI_BUSY', + 'GRBM_PERF_SEL_SX_BUSY', 'GRBM_PERF_SEL_TA_BUSY', + 'GRBM_PERF_SEL_TCP_BUSY', 'GRBM_PERF_SEL_USER_DEFINED', + 'GRBM_PERF_SEL_UTCL1_BUSY', 'GRBM_PERF_SEL_UTCL2_BUSY', + 'GRBM_SE0_PERF_SEL', 'GRBM_SE0_PERF_SEL_BCI_BUSY', + 'GRBM_SE0_PERF_SEL_CB_BUSY', 'GRBM_SE0_PERF_SEL_CB_CLEAN', + 'GRBM_SE0_PERF_SEL_COUNT', 'GRBM_SE0_PERF_SEL_DB_BUSY', + 'GRBM_SE0_PERF_SEL_DB_CLEAN', 'GRBM_SE0_PERF_SEL_GL1CC_BUSY', + 'GRBM_SE0_PERF_SEL_GL1H_BUSY', 'GRBM_SE0_PERF_SEL_PA_BUSY', + 'GRBM_SE0_PERF_SEL_PC_BUSY', 'GRBM_SE0_PERF_SEL_RMI_BUSY', + 'GRBM_SE0_PERF_SEL_SC_BUSY', 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 'GRBM_SE0_PERF_SEL_SX_BUSY', 'GRBM_SE0_PERF_SEL_TA_BUSY', + 'GRBM_SE0_PERF_SEL_TCP_BUSY', 'GRBM_SE0_PERF_SEL_USER_DEFINED', + 'GRBM_SE0_PERF_SEL_UTCL1_BUSY', 'GRBM_SE1_PERF_SEL', + 'GRBM_SE1_PERF_SEL_BCI_BUSY', 'GRBM_SE1_PERF_SEL_CB_BUSY', + 'GRBM_SE1_PERF_SEL_CB_CLEAN', 'GRBM_SE1_PERF_SEL_COUNT', + 'GRBM_SE1_PERF_SEL_DB_BUSY', 'GRBM_SE1_PERF_SEL_DB_CLEAN', + 'GRBM_SE1_PERF_SEL_GL1CC_BUSY', 'GRBM_SE1_PERF_SEL_GL1H_BUSY', + 'GRBM_SE1_PERF_SEL_PA_BUSY', 'GRBM_SE1_PERF_SEL_PC_BUSY', + 'GRBM_SE1_PERF_SEL_RMI_BUSY', 'GRBM_SE1_PERF_SEL_SC_BUSY', + 'GRBM_SE1_PERF_SEL_SPI_BUSY', 'GRBM_SE1_PERF_SEL_SX_BUSY', + 'GRBM_SE1_PERF_SEL_TA_BUSY', 'GRBM_SE1_PERF_SEL_TCP_BUSY', + 'GRBM_SE1_PERF_SEL_USER_DEFINED', 'GRBM_SE1_PERF_SEL_UTCL1_BUSY', + 'GRBM_SE2_PERF_SEL', 'GRBM_SE2_PERF_SEL_BCI_BUSY', + 'GRBM_SE2_PERF_SEL_CB_BUSY', 'GRBM_SE2_PERF_SEL_CB_CLEAN', + 'GRBM_SE2_PERF_SEL_COUNT', 'GRBM_SE2_PERF_SEL_DB_BUSY', + 'GRBM_SE2_PERF_SEL_DB_CLEAN', 'GRBM_SE2_PERF_SEL_GL1CC_BUSY', + 'GRBM_SE2_PERF_SEL_GL1H_BUSY', 'GRBM_SE2_PERF_SEL_PA_BUSY', + 'GRBM_SE2_PERF_SEL_PC_BUSY', 'GRBM_SE2_PERF_SEL_RMI_BUSY', + 'GRBM_SE2_PERF_SEL_SC_BUSY', 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 'GRBM_SE2_PERF_SEL_SX_BUSY', 'GRBM_SE2_PERF_SEL_TA_BUSY', + 'GRBM_SE2_PERF_SEL_TCP_BUSY', 'GRBM_SE2_PERF_SEL_USER_DEFINED', + 'GRBM_SE2_PERF_SEL_UTCL1_BUSY', 'GRBM_SE3_PERF_SEL', + 'GRBM_SE3_PERF_SEL_BCI_BUSY', 'GRBM_SE3_PERF_SEL_CB_BUSY', + 'GRBM_SE3_PERF_SEL_CB_CLEAN', 'GRBM_SE3_PERF_SEL_COUNT', + 'GRBM_SE3_PERF_SEL_DB_BUSY', 'GRBM_SE3_PERF_SEL_DB_CLEAN', + 'GRBM_SE3_PERF_SEL_GL1CC_BUSY', 'GRBM_SE3_PERF_SEL_GL1H_BUSY', + 'GRBM_SE3_PERF_SEL_PA_BUSY', 'GRBM_SE3_PERF_SEL_PC_BUSY', + 'GRBM_SE3_PERF_SEL_RMI_BUSY', 'GRBM_SE3_PERF_SEL_SC_BUSY', + 'GRBM_SE3_PERF_SEL_SPI_BUSY', 'GRBM_SE3_PERF_SEL_SX_BUSY', + 'GRBM_SE3_PERF_SEL_TA_BUSY', 'GRBM_SE3_PERF_SEL_TCP_BUSY', + 'GRBM_SE3_PERF_SEL_USER_DEFINED', 'GRBM_SE3_PERF_SEL_UTCL1_BUSY', + 'GRBM_SE4_PERF_SEL', 'GRBM_SE4_PERF_SEL_BCI_BUSY', + 'GRBM_SE4_PERF_SEL_CB_BUSY', 'GRBM_SE4_PERF_SEL_CB_CLEAN', + 'GRBM_SE4_PERF_SEL_COUNT', 'GRBM_SE4_PERF_SEL_DB_BUSY', + 'GRBM_SE4_PERF_SEL_DB_CLEAN', 'GRBM_SE4_PERF_SEL_GL1CC_BUSY', + 'GRBM_SE4_PERF_SEL_GL1H_BUSY', 'GRBM_SE4_PERF_SEL_PA_BUSY', + 'GRBM_SE4_PERF_SEL_PC_BUSY', 'GRBM_SE4_PERF_SEL_RMI_BUSY', + 'GRBM_SE4_PERF_SEL_SC_BUSY', 'GRBM_SE4_PERF_SEL_SPI_BUSY', + 'GRBM_SE4_PERF_SEL_SX_BUSY', 'GRBM_SE4_PERF_SEL_TA_BUSY', + 'GRBM_SE4_PERF_SEL_TCP_BUSY', 'GRBM_SE4_PERF_SEL_USER_DEFINED', + 'GRBM_SE4_PERF_SEL_UTCL1_BUSY', 'GRBM_SE5_PERF_SEL', + 'GRBM_SE5_PERF_SEL_BCI_BUSY', 'GRBM_SE5_PERF_SEL_CB_BUSY', + 'GRBM_SE5_PERF_SEL_CB_CLEAN', 'GRBM_SE5_PERF_SEL_COUNT', + 'GRBM_SE5_PERF_SEL_DB_BUSY', 'GRBM_SE5_PERF_SEL_DB_CLEAN', + 'GRBM_SE5_PERF_SEL_GL1CC_BUSY', 'GRBM_SE5_PERF_SEL_GL1H_BUSY', + 'GRBM_SE5_PERF_SEL_PA_BUSY', 'GRBM_SE5_PERF_SEL_PC_BUSY', + 'GRBM_SE5_PERF_SEL_RMI_BUSY', 'GRBM_SE5_PERF_SEL_SC_BUSY', + 'GRBM_SE5_PERF_SEL_SPI_BUSY', 'GRBM_SE5_PERF_SEL_SX_BUSY', + 'GRBM_SE5_PERF_SEL_TA_BUSY', 'GRBM_SE5_PERF_SEL_TCP_BUSY', + 'GRBM_SE5_PERF_SEL_USER_DEFINED', 'GRBM_SE5_PERF_SEL_UTCL1_BUSY', + 'GRBM_SE6_PERF_SEL', 'GRBM_SE6_PERF_SEL_BCI_BUSY', + 'GRBM_SE6_PERF_SEL_CB_BUSY', 'GRBM_SE6_PERF_SEL_CB_CLEAN', + 'GRBM_SE6_PERF_SEL_COUNT', 'GRBM_SE6_PERF_SEL_DB_BUSY', + 'GRBM_SE6_PERF_SEL_DB_CLEAN', 'GRBM_SE6_PERF_SEL_GL1CC_BUSY', + 'GRBM_SE6_PERF_SEL_GL1H_BUSY', 'GRBM_SE6_PERF_SEL_PA_BUSY', + 'GRBM_SE6_PERF_SEL_PC_BUSY', 'GRBM_SE6_PERF_SEL_RMI_BUSY', + 'GRBM_SE6_PERF_SEL_SC_BUSY', 'GRBM_SE6_PERF_SEL_SPI_BUSY', + 'GRBM_SE6_PERF_SEL_SX_BUSY', 'GRBM_SE6_PERF_SEL_TA_BUSY', + 'GRBM_SE6_PERF_SEL_TCP_BUSY', 'GRBM_SE6_PERF_SEL_USER_DEFINED', + 'GRBM_SE6_PERF_SEL_UTCL1_BUSY', 'GRBM_SE7_PERF_SEL', + 'GRBM_SE7_PERF_SEL_BCI_BUSY', 'GRBM_SE7_PERF_SEL_CB_BUSY', + 'GRBM_SE7_PERF_SEL_CB_CLEAN', 'GRBM_SE7_PERF_SEL_COUNT', + 'GRBM_SE7_PERF_SEL_DB_BUSY', 'GRBM_SE7_PERF_SEL_DB_CLEAN', + 'GRBM_SE7_PERF_SEL_GL1CC_BUSY', 'GRBM_SE7_PERF_SEL_GL1H_BUSY', + 'GRBM_SE7_PERF_SEL_PA_BUSY', 'GRBM_SE7_PERF_SEL_PC_BUSY', + 'GRBM_SE7_PERF_SEL_RMI_BUSY', 'GRBM_SE7_PERF_SEL_SC_BUSY', + 'GRBM_SE7_PERF_SEL_SPI_BUSY', 'GRBM_SE7_PERF_SEL_SX_BUSY', + 'GRBM_SE7_PERF_SEL_TA_BUSY', 'GRBM_SE7_PERF_SEL_TCP_BUSY', + 'GRBM_SE7_PERF_SEL_USER_DEFINED', 'GRBM_SE7_PERF_SEL_UTCL1_BUSY', + 'GREEN_LUT', 'GSTHREADID_SIZE', 'GS_OFF', 'GS_SCENARIO_A', + 'GS_SCENARIO_B', 'GS_SCENARIO_C', 'GS_SCENARIO_G', 'GS_STAGE_OFF', + 'GS_STAGE_ON', 'HDMICHARCLK_SRC_SEL', + 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', 'HDMICHARCLK_SRC_SEL_UNIPHYA', + 'HDMICHARCLK_SRC_SEL_UNIPHYB', 'HDMICHARCLK_SRC_SEL_UNIPHYC', + 'HDMICHARCLK_SRC_SEL_UNIPHYD', 'HDMICHARCLK_SRC_SEL_UNIPHYE', + 'HDMISTREAMCLK_DTO_FORCE_DIS', 'HDMISTREAMCLK_SRC_SEL', + 'HDMI_ACP_NOT_SEND', 'HDMI_ACP_PKT_SEND', 'HDMI_ACP_SEND', + 'HDMI_ACR_0_MULTIPLE_RESERVED', 'HDMI_ACR_1_MULTIPLE', + 'HDMI_ACR_2_MULTIPLE', 'HDMI_ACR_3_MULTIPLE_RESERVED', + 'HDMI_ACR_4_MULTIPLE', 'HDMI_ACR_5_MULTIPLE_RESERVED', + 'HDMI_ACR_6_MULTIPLE_RESERVED', 'HDMI_ACR_7_MULTIPLE_RESERVED', + 'HDMI_ACR_AUDIO_PRIORITY', 'HDMI_ACR_CONT', + 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', + 'HDMI_ACR_NOT_SEND', 'HDMI_ACR_N_MULTIPLE', + 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 'HDMI_ACR_PKT_SEND', 'HDMI_ACR_SELECT', 'HDMI_ACR_SELECT_32K', + 'HDMI_ACR_SELECT_44K', 'HDMI_ACR_SELECT_48K', + 'HDMI_ACR_SELECT_HW', 'HDMI_ACR_SEND', 'HDMI_ACR_SOURCE', + 'HDMI_ACR_SOURCE_HW', 'HDMI_ACR_SOURCE_SW', + 'HDMI_AUDIO_DELAY_56CLK', 'HDMI_AUDIO_DELAY_58CLK', + 'HDMI_AUDIO_DELAY_DISABLE', 'HDMI_AUDIO_DELAY_EN', + 'HDMI_AUDIO_DELAY_RESERVED', 'HDMI_AUDIO_INFO_CONT', + 'HDMI_AUDIO_INFO_CONT_DISABLE', 'HDMI_AUDIO_INFO_CONT_ENABLE', + 'HDMI_AUDIO_INFO_NOT_SEND', 'HDMI_AUDIO_INFO_PKT_SEND', + 'HDMI_AUDIO_INFO_SEND', + 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', + 'HDMI_BORROW_MODE', 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_RATE', 'HDMI_DATA_SCRAMBLE_DISABLE', + 'HDMI_DATA_SCRAMBLE_EN', 'HDMI_DATA_SCRAMBLE_ENABLE', + 'HDMI_DEEP_COLOR_DEPTH', 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 'HDMI_DEEP_COLOR_DEPTH_30BPP', 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 'HDMI_DEEP_COLOR_DEPTH_48BPP', 'HDMI_DEFAULT_PAHSE', + 'HDMI_DEFAULT_PHASE_IS_0', 'HDMI_DEFAULT_PHASE_IS_1', + 'HDMI_ERROR_ACK', 'HDMI_ERROR_ACK_INT', 'HDMI_ERROR_MASK', + 'HDMI_ERROR_MASK_INT', 'HDMI_ERROR_NOT_ACK', + 'HDMI_ERROR_NOT_MASK', 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', + 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', 'HDMI_FRL', + 'HDMI_GC_AVMUTE', 'HDMI_GC_AVMUTE_CONT', + 'HDMI_GC_AVMUTE_CONT_DISABLE', 'HDMI_GC_AVMUTE_CONT_ENABLE', + 'HDMI_GC_AVMUTE_SET', 'HDMI_GC_AVMUTE_UNSET', 'HDMI_GC_CONT', + 'HDMI_GC_CONT_DISABLE', 'HDMI_GC_CONT_ENABLE', 'HDMI_GC_NOT_SEND', + 'HDMI_GC_PKT_SEND', 'HDMI_GC_SEND', 'HDMI_GENERIC_CONT', + 'HDMI_GENERIC_CONT_DISABLE', 'HDMI_GENERIC_CONT_ENABLE', + 'HDMI_GENERIC_NOT_SEND', 'HDMI_GENERIC_PKT_SEND', + 'HDMI_GENERIC_SEND', 'HDMI_ISRC_CONT', 'HDMI_ISRC_CONT_DISABLE', + 'HDMI_ISRC_CONT_ENABLE', 'HDMI_ISRC_NOT_SEND', + 'HDMI_ISRC_PKT_SEND', 'HDMI_ISRC_SEND', + 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', 'HDMI_KEEPOUT_MODE', + 'HDMI_METADATA_ENABLE', 'HDMI_METADATA_NOT_SEND', + 'HDMI_METADATA_PKT_SEND', 'HDMI_MPEG_INFO_CONT', + 'HDMI_MPEG_INFO_CONT_DISABLE', 'HDMI_MPEG_INFO_CONT_ENABLE', + 'HDMI_MPEG_INFO_NOT_SEND', 'HDMI_MPEG_INFO_PKT_SEND', + 'HDMI_MPEG_INFO_SEND', 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 'HDMI_NO_EXTRA_NULL_PACKET_FILLED', 'HDMI_NULL_NOT_SEND', + 'HDMI_NULL_PKT_SEND', 'HDMI_NULL_SEND', 'HDMI_PACKET_GEN_VERSION', + 'HDMI_PACKET_GEN_VERSION_NEW', 'HDMI_PACKET_GEN_VERSION_OLD', + 'HDMI_PACKET_LINE_REFERENCE', 'HDMI_PACKING_PHASE_OVERRIDE', + 'HDMI_PACKING_PHASE_SET_BY_HW', 'HDMI_PACKING_PHASE_SET_BY_SW', + 'HDMI_PKT_LINE_REF_OTGSOF', 'HDMI_PKT_LINE_REF_VSYNC', + 'HDMI_SEND_MAX_AUDIO_PACKETS', 'HDMI_STREAM_ENC_DB_DISABLE', + 'HDMI_STREAM_ENC_DB_DISABLE_CONTROL', 'HDMI_STREAM_ENC_DB_ENABLE', + 'HDMI_STREAM_ENC_DCCG', 'HDMI_STREAM_ENC_DISABLE', + 'HDMI_STREAM_ENC_DISPLAY_PIPE', 'HDMI_STREAM_ENC_DSC_MODE', + 'HDMI_STREAM_ENC_ENABLE', 'HDMI_STREAM_ENC_ENABLE_CONTROL', + 'HDMI_STREAM_ENC_HARDWARE', 'HDMI_STREAM_ENC_NOT_RESET', + 'HDMI_STREAM_ENC_NO_ERROR_OCCURRED', + 'HDMI_STREAM_ENC_ODM_COMBINE_MODE', + 'HDMI_STREAM_ENC_OVERFLOW_OCCURRED', + 'HDMI_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR', + 'HDMI_STREAM_ENC_OVERWRITE_LEVEL_SELECT', + 'HDMI_STREAM_ENC_PIXEL_ENCODING', 'HDMI_STREAM_ENC_PROGRAMMABLE', + 'HDMI_STREAM_ENC_READ_CLOCK_CONTROL', 'HDMI_STREAM_ENC_RESET', + 'HDMI_STREAM_ENC_RESET_CONTROL', 'HDMI_STREAM_ENC_STREAM_ACTIVE', + 'HDMI_STREAM_ENC_UNDERFLOW_OCCURRED', + 'HDMI_STREAM_ENC_VIDEO_STREAM_ACTIVE', + 'HDMI_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', 'HDMI_TB_ENC_ACP_SEND', + 'HDMI_TB_ENC_ACR_AUDIO_PRIORITY', 'HDMI_TB_ENC_ACR_CONT', + 'HDMI_TB_ENC_ACR_N_MULTIPLE', 'HDMI_TB_ENC_ACR_SELECT', + 'HDMI_TB_ENC_ACR_SEND', 'HDMI_TB_ENC_ACR_SOURCE', + 'HDMI_TB_ENC_AUDIO_INFO_CONT', 'HDMI_TB_ENC_AUDIO_INFO_SEND', + 'HDMI_TB_ENC_CRC_SRC_SEL', 'HDMI_TB_ENC_CRC_TYPE', + 'HDMI_TB_ENC_DEEP_COLOR_DEPTH', 'HDMI_TB_ENC_DEFAULT_PAHSE', + 'HDMI_TB_ENC_DSC_MODE', 'HDMI_TB_ENC_ENABLE', + 'HDMI_TB_ENC_GC_AVMUTE', 'HDMI_TB_ENC_GC_AVMUTE_CONT', + 'HDMI_TB_ENC_GC_CONT', 'HDMI_TB_ENC_GC_SEND', + 'HDMI_TB_ENC_GENERIC_CONT', 'HDMI_TB_ENC_GENERIC_LOCK_DISABLE', + 'HDMI_TB_ENC_GENERIC_LOCK_EN', 'HDMI_TB_ENC_GENERIC_LOCK_ENABLE', + 'HDMI_TB_ENC_GENERIC_SEND', 'HDMI_TB_ENC_ISRC_CONT', + 'HDMI_TB_ENC_ISRC_SEND', 'HDMI_TB_ENC_METADATA_ENABLE', + 'HDMI_TB_ENC_PACKET_LINE_REFERENCE', 'HDMI_TB_ENC_PIXEL_ENCODING', + 'HDMI_TB_ENC_RESET', 'HDMI_TB_ENC_SYNC_PHASE', + 'HDMI_TMDS_OR_DP_8B10B', 'HDP_ENDIAN_8IN16', 'HDP_ENDIAN_8IN32', + 'HDP_ENDIAN_8IN64', 'HDP_ENDIAN_NONE', 'HPD_INT_CONTROL_ACK', + 'HPD_INT_CONTROL_ACK_0', 'HPD_INT_CONTROL_ACK_1', + 'HPD_INT_CONTROL_GEN_INT_ON_CON', + 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', 'HPD_INT_CONTROL_POLARITY', + 'HPD_INT_CONTROL_RX_INT_ACK', 'HPD_INT_CONTROL_RX_INT_ACK_0', + 'HPD_INT_CONTROL_RX_INT_ACK_1', 'HPO_SRC0', 'HPO_SRC_RESERVED', + 'HPO_TOP_CLOCK_GATING_DIS', 'HPO_TOP_CLOCK_GATING_DISABLE', + 'HPO_TOP_CLOCK_GATING_EN', + 'HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0', + 'HPO_TOP_FEATURE_GATED_HDMICHARCLK0', + 'HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0', + 'HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0', + 'HPO_TOP_PERMANENT_DISPCLK', 'HPO_TOP_PERMANENT_HDMICHARCLK0', + 'HPO_TOP_PERMANENT_HDMISTREAMCLK0', 'HPO_TOP_PERMANENT_SOCCLK', + 'HPO_TOP_REGISTER_GATED_DISPCLK', + 'HPO_TOP_REGISTER_GATED_HDMICHARCLK0', + 'HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0', 'HPO_TOP_TEST_CLK_SEL', + 'HPO_TOP_TEST_CLOCK_RESERVED', 'HS_GS', 'HS_STAGE_OFF', + 'HS_STAGE_ON', 'HUBP_BLANK_EN', 'HUBP_BLANK_SW_ASSERT', + 'HUBP_BLANK_SW_DEASSERT', 'HUBP_IN_ACTIVE', 'HUBP_IN_BLANK', + 'HUBP_IN_VBLANK', 'HUBP_MEASURE_WIN_MODE_DCFCLK', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', 'HUBP_NO_OUTSTANDING_REQ', + 'HUBP_SOFT_RESET', 'HUBP_SOFT_RESET_OFF', 'HUBP_SOFT_RESET_ON', + 'HUBP_TTU_DISABLE', 'HUBP_TTU_DISABLED', 'HUBP_TTU_ENABLED', + 'HUBP_VREADY_AT_OR_AFTER_VSYNC', 'HUBP_VTG_SEL', + 'HW_MIRRORING_DISABLE', 'HW_MIRRORING_ENABLE', 'H_MIRROR_EN', + 'Hdp_SurfaceEndian', 'ID_STREAM_DISABLE_ACKED', + 'ID_STREAM_DISABLE_NO_ACK', 'IHC_INTERRUPT_DEST', + 'IHC_INTERRUPT_LINE_STATUS', 'IH_CLIENT_TYPE', + 'IH_CLIENT_TYPE_RESERVED', 'IH_GFX_VMID_CLIENT', + 'IH_INTERFACE_TYPE', 'IH_LEGACY_INTERFACE', 'IH_MM_VMID_CLIENT', + 'IH_MULTI_VMID_CLIENT', 'IH_PERF_SEL', + 'IH_PERF_SEL_BIF_LINE0_FALLING', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 'IH_PERF_SEL_BIF_LINE0_RISING', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', + 'IH_PERF_SEL_BUFFER_FIFO_FULL', 'IH_PERF_SEL_BUFFER_IDLE', + 'IH_PERF_SEL_CLIENT0_INT', 'IH_PERF_SEL_CLIENT10_INT', + 'IH_PERF_SEL_CLIENT11_INT', 'IH_PERF_SEL_CLIENT12_INT', + 'IH_PERF_SEL_CLIENT13_INT', 'IH_PERF_SEL_CLIENT14_INT', + 'IH_PERF_SEL_CLIENT15_INT', 'IH_PERF_SEL_CLIENT16_INT', + 'IH_PERF_SEL_CLIENT17_INT', 'IH_PERF_SEL_CLIENT18_INT', + 'IH_PERF_SEL_CLIENT19_INT', 'IH_PERF_SEL_CLIENT1_INT', + 'IH_PERF_SEL_CLIENT20_INT', 'IH_PERF_SEL_CLIENT21_INT', + 'IH_PERF_SEL_CLIENT22_INT', 'IH_PERF_SEL_CLIENT23_INT', + 'IH_PERF_SEL_CLIENT24_INT', 'IH_PERF_SEL_CLIENT25_INT', + 'IH_PERF_SEL_CLIENT26_INT', 'IH_PERF_SEL_CLIENT27_INT', + 'IH_PERF_SEL_CLIENT28_INT', 'IH_PERF_SEL_CLIENT29_INT', + 'IH_PERF_SEL_CLIENT2_INT', 'IH_PERF_SEL_CLIENT30_INT', + 'IH_PERF_SEL_CLIENT31_INT', 'IH_PERF_SEL_CLIENT3_INT', + 'IH_PERF_SEL_CLIENT4_INT', 'IH_PERF_SEL_CLIENT5_INT', + 'IH_PERF_SEL_CLIENT6_INT', 'IH_PERF_SEL_CLIENT7_INT', + 'IH_PERF_SEL_CLIENT8_INT', 'IH_PERF_SEL_CLIENT9_INT', + 'IH_PERF_SEL_CLIENT_CREDIT_ERROR', 'IH_PERF_SEL_COOKIE_REC_ERROR', + 'IH_PERF_SEL_CYCLE', 'IH_PERF_SEL_IDLE', 'IH_PERF_SEL_INPUT_IDLE', + 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 'IH_PERF_SEL_MC_WR_CLEAN_STALL', 'IH_PERF_SEL_MC_WR_COUNT', + 'IH_PERF_SEL_MC_WR_IDLE', 'IH_PERF_SEL_MC_WR_STALL', + 'IH_PERF_SEL_RB0_FULL', 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB0_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB0_FULL_VF0', + 'IH_PERF_SEL_RB0_FULL_VF1', 'IH_PERF_SEL_RB0_FULL_VF10', + 'IH_PERF_SEL_RB0_FULL_VF11', 'IH_PERF_SEL_RB0_FULL_VF12', + 'IH_PERF_SEL_RB0_FULL_VF13', 'IH_PERF_SEL_RB0_FULL_VF14', + 'IH_PERF_SEL_RB0_FULL_VF15', 'IH_PERF_SEL_RB0_FULL_VF2', + 'IH_PERF_SEL_RB0_FULL_VF3', 'IH_PERF_SEL_RB0_FULL_VF4', + 'IH_PERF_SEL_RB0_FULL_VF5', 'IH_PERF_SEL_RB0_FULL_VF6', + 'IH_PERF_SEL_RB0_FULL_VF7', 'IH_PERF_SEL_RB0_FULL_VF8', + 'IH_PERF_SEL_RB0_FULL_VF9', 'IH_PERF_SEL_RB0_LOAD_RPTR', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF0', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF1', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF15', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF3', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB0_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB0_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB0_OVERFLOW', + 'IH_PERF_SEL_RB0_OVERFLOW_VF0', 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 'IH_PERF_SEL_RB0_OVERFLOW_VF10', 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 'IH_PERF_SEL_RB0_OVERFLOW_VF12', 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 'IH_PERF_SEL_RB0_OVERFLOW_VF14', 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 'IH_PERF_SEL_RB0_OVERFLOW_VF2', 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 'IH_PERF_SEL_RB0_OVERFLOW_VF4', 'IH_PERF_SEL_RB0_OVERFLOW_VF5', + 'IH_PERF_SEL_RB0_OVERFLOW_VF6', 'IH_PERF_SEL_RB0_OVERFLOW_VF7', + 'IH_PERF_SEL_RB0_OVERFLOW_VF8', 'IH_PERF_SEL_RB0_OVERFLOW_VF9', + 'IH_PERF_SEL_RB0_RPTR_WRAP', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRAP', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', 'IH_PERF_SEL_RB1_FULL', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB1_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB1_FULL_VF0', + 'IH_PERF_SEL_RB1_FULL_VF1', 'IH_PERF_SEL_RB1_FULL_VF10', + 'IH_PERF_SEL_RB1_FULL_VF11', 'IH_PERF_SEL_RB1_FULL_VF12', + 'IH_PERF_SEL_RB1_FULL_VF13', 'IH_PERF_SEL_RB1_FULL_VF14', + 'IH_PERF_SEL_RB1_FULL_VF15', 'IH_PERF_SEL_RB1_FULL_VF2', + 'IH_PERF_SEL_RB1_FULL_VF3', 'IH_PERF_SEL_RB1_FULL_VF4', + 'IH_PERF_SEL_RB1_FULL_VF5', 'IH_PERF_SEL_RB1_FULL_VF6', + 'IH_PERF_SEL_RB1_FULL_VF7', 'IH_PERF_SEL_RB1_FULL_VF8', + 'IH_PERF_SEL_RB1_FULL_VF9', 'IH_PERF_SEL_RB1_LOAD_RPTR', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF0', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF1', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF15', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF3', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB1_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB1_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB1_OVERFLOW', + 'IH_PERF_SEL_RB1_OVERFLOW_VF0', 'IH_PERF_SEL_RB1_OVERFLOW_VF1', + 'IH_PERF_SEL_RB1_OVERFLOW_VF10', 'IH_PERF_SEL_RB1_OVERFLOW_VF11', + 'IH_PERF_SEL_RB1_OVERFLOW_VF12', 'IH_PERF_SEL_RB1_OVERFLOW_VF13', + 'IH_PERF_SEL_RB1_OVERFLOW_VF14', 'IH_PERF_SEL_RB1_OVERFLOW_VF15', + 'IH_PERF_SEL_RB1_OVERFLOW_VF2', 'IH_PERF_SEL_RB1_OVERFLOW_VF3', + 'IH_PERF_SEL_RB1_OVERFLOW_VF4', 'IH_PERF_SEL_RB1_OVERFLOW_VF5', + 'IH_PERF_SEL_RB1_OVERFLOW_VF6', 'IH_PERF_SEL_RB1_OVERFLOW_VF7', + 'IH_PERF_SEL_RB1_OVERFLOW_VF8', 'IH_PERF_SEL_RB1_OVERFLOW_VF9', + 'IH_PERF_SEL_RB1_RPTR_WRAP', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB1_WPTR_WRAP', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_FULL', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF0', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF1', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF10', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF11', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF12', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF13', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF14', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF15', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF2', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF3', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF4', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF5', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF6', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF7', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF8', + 'IH_PERF_SEL_RB2_FULL_DRAIN_DROP_VF9', 'IH_PERF_SEL_RB2_FULL_VF0', + 'IH_PERF_SEL_RB2_FULL_VF1', 'IH_PERF_SEL_RB2_FULL_VF10', + 'IH_PERF_SEL_RB2_FULL_VF11', 'IH_PERF_SEL_RB2_FULL_VF12', + 'IH_PERF_SEL_RB2_FULL_VF13', 'IH_PERF_SEL_RB2_FULL_VF14', + 'IH_PERF_SEL_RB2_FULL_VF15', 'IH_PERF_SEL_RB2_FULL_VF2', + 'IH_PERF_SEL_RB2_FULL_VF3', 'IH_PERF_SEL_RB2_FULL_VF4', + 'IH_PERF_SEL_RB2_FULL_VF5', 'IH_PERF_SEL_RB2_FULL_VF6', + 'IH_PERF_SEL_RB2_FULL_VF7', 'IH_PERF_SEL_RB2_FULL_VF8', + 'IH_PERF_SEL_RB2_FULL_VF9', 'IH_PERF_SEL_RB2_LOAD_RPTR', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF0', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF1', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF10', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF11', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF12', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF13', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF14', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF15', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF2', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF3', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF4', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF5', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF6', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF7', 'IH_PERF_SEL_RB2_LOAD_RPTR_VF8', + 'IH_PERF_SEL_RB2_LOAD_RPTR_VF9', 'IH_PERF_SEL_RB2_OVERFLOW', + 'IH_PERF_SEL_RB2_OVERFLOW_VF0', 'IH_PERF_SEL_RB2_OVERFLOW_VF1', + 'IH_PERF_SEL_RB2_OVERFLOW_VF10', 'IH_PERF_SEL_RB2_OVERFLOW_VF11', + 'IH_PERF_SEL_RB2_OVERFLOW_VF12', 'IH_PERF_SEL_RB2_OVERFLOW_VF13', + 'IH_PERF_SEL_RB2_OVERFLOW_VF14', 'IH_PERF_SEL_RB2_OVERFLOW_VF15', + 'IH_PERF_SEL_RB2_OVERFLOW_VF2', 'IH_PERF_SEL_RB2_OVERFLOW_VF3', + 'IH_PERF_SEL_RB2_OVERFLOW_VF4', 'IH_PERF_SEL_RB2_OVERFLOW_VF5', + 'IH_PERF_SEL_RB2_OVERFLOW_VF6', 'IH_PERF_SEL_RB2_OVERFLOW_VF7', + 'IH_PERF_SEL_RB2_OVERFLOW_VF8', 'IH_PERF_SEL_RB2_OVERFLOW_VF9', + 'IH_PERF_SEL_RB2_RPTR_WRAP', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_WPTR_WRAP', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', 'IH_PERF_SEL_SELF_IV_VALID', + 'IH_PERF_SEL_STORM_CLIENT_INT_DROP', + 'IH_REGISTER_WRITE_INTERFACE', 'IH_RING_ID', + 'IH_RING_ID_INTERRUPT', 'IH_RING_ID_REQUEST', + 'IH_RING_ID_RESERVED', 'IH_RING_ID_TRANSLATION', + 'IH_VF_RB_SELECT', 'IH_VF_RB_SELECT_CLIENT_FCN_ID', + 'IH_VF_RB_SELECT_IH_FCN_ID', 'IH_VF_RB_SELECT_PF', + 'IH_VF_RB_SELECT_RESERVED', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 'INPUT_COVERAGE', 'INPUT_DEPTH_COVERAGE', 'INPUT_FIFO_ERROR_TYPE', + 'INPUT_INNER_COVERAGE', 'INST_ID_ECC_INTERRUPT_MSG', + 'INST_ID_HOST_REG_TRAP_MSG', 'INST_ID_HW_TRAP', + 'INST_ID_HW_TRAP_GET_TBA', 'INST_ID_KILL_SEQ', + 'INST_ID_PRIV_START', 'INST_ID_SPI_WREXEC', + 'INST_ID_TTRACE_NEW_PC_MSG', 'INTERRUPT_LINE_ASSERTED', + 'INTERRUPT_LINE_NOT_ASSERTED', 'INTERRUPT_SENT_TO_DMCUB', + 'INTERRUPT_SENT_TO_IH', 'INT_DISABLED', 'INT_ENABLED', + 'INT_LEVEL', 'INT_MASK', 'INT_PULSE', 'INVALID_REG_ACCESS_TYPE', + 'IQ_DEQUEUE_RETRY', 'IQ_INTR_TYPE_IB', 'IQ_INTR_TYPE_MQD', + 'IQ_INTR_TYPE_PQ', 'IQ_OFFLOAD_RETRY', 'IQ_QUEUE_SLEEP', + 'IQ_SCH_WAVE_MSG', 'IQ_SEM_REARM', 'JITTER_REMOVE_DISABLE', + 'LATE_Z', 'LB_ALPHA_DISABLE', 'LB_ALPHA_EN', 'LB_ALPHA_ENABLE', + 'LB_INTERLEAVE_DISABLE', 'LB_INTERLEAVE_EN', + 'LB_INTERLEAVE_ENABLE', 'LB_MEMORY_CONFIG', 'LB_MEMORY_CONFIG_0', + 'LB_MEMORY_CONFIG_1', 'LB_MEMORY_CONFIG_2', 'LB_MEMORY_CONFIG_3', + 'LEGACY_PIPE_INTERLEAVE', 'LEGACY_PIPE_INTERLEAVE_256B', + 'LEGACY_PIPE_INTERLEAVE_512B', 'LINESTRIP', 'LOOSE_PACK', + 'LSDMA_PERF_SEL', 'LSDMA_PERF_SEL_ATCL2_FREE', + 'LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 'LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 'LSDMA_PERF_SEL_ATCL2_RET_ACK', 'LSDMA_PERF_SEL_ATCL2_RET_XNACK', + 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ', + 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET', + 'LSDMA_PERF_SEL_CE_AFIFO_FULL', 'LSDMA_PERF_SEL_CE_BUSY', + 'LSDMA_PERF_SEL_CE_BUSY_END', 'LSDMA_PERF_SEL_CE_BUSY_START', + 'LSDMA_PERF_SEL_CE_DST_IDLE', 'LSDMA_PERF_SEL_CE_INFO1_FULL', + 'LSDMA_PERF_SEL_CE_INFO_FULL', 'LSDMA_PERF_SEL_CE_IN_IDLE', + 'LSDMA_PERF_SEL_CE_L1_STALL', 'LSDMA_PERF_SEL_CE_L1_WR_VLD', + 'LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND', + 'LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET', + 'LSDMA_PERF_SEL_CE_OUT_IDLE', 'LSDMA_PERF_SEL_CE_RD_STALL', + 'LSDMA_PERF_SEL_CE_RREQ_IDLE', 'LSDMA_PERF_SEL_CE_SPLIT_IDLE', + 'LSDMA_PERF_SEL_CE_WREQ_IDLE', 'LSDMA_PERF_SEL_CE_WR_IDLE', + 'LSDMA_PERF_SEL_CE_WR_STALL', 'LSDMA_PERF_SEL_CMD_OP_END', + 'LSDMA_PERF_SEL_CMD_OP_MATCH', 'LSDMA_PERF_SEL_CMD_OP_START', + 'LSDMA_PERF_SEL_CTX_CHANGE', + 'LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'LSDMA_PERF_SEL_CYCLE', + 'LSDMA_PERF_SEL_DMA_L1_RD_SEND', 'LSDMA_PERF_SEL_DMA_L1_WR_SEND', + 'LSDMA_PERF_SEL_DMA_MC_RD_SEND', 'LSDMA_PERF_SEL_DMA_MC_WR_SEND', + 'LSDMA_PERF_SEL_DOORBELL', 'LSDMA_PERF_SEL_DRAM_ECC', + 'LSDMA_PERF_SEL_EX_IDLE', + 'LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'LSDMA_PERF_SEL_F32_L1_WR_VLD', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 'LSDMA_PERF_SEL_GFX_SELECT', 'LSDMA_PERF_SEL_IB_CMD_FULL', + 'LSDMA_PERF_SEL_IB_CMD_IDLE', 'LSDMA_PERF_SEL_IB_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_IB_MMHUB_RD_RET', 'LSDMA_PERF_SEL_IDLE', + 'LSDMA_PERF_SEL_INT_IDLE', 'LSDMA_PERF_SEL_INT_REQ_COUNT', + 'LSDMA_PERF_SEL_INT_REQ_STALL', + 'LSDMA_PERF_SEL_INT_RESP_ACCEPTED', + 'LSDMA_PERF_SEL_INT_RESP_RETRY', + 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR', + 'LSDMA_PERF_SEL_L1_INV_MIDDLE', 'LSDMA_PERF_SEL_L1_RDL2_IDLE', + 'LSDMA_PERF_SEL_L1_RDMC_IDLE', 'LSDMA_PERF_SEL_L1_RD_FIFO_IDLE', + 'LSDMA_PERF_SEL_L1_RD_INV_EN', 'LSDMA_PERF_SEL_L1_RD_INV_IDLE', + 'LSDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 'LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', + 'LSDMA_PERF_SEL_L1_WRL2_IDLE', 'LSDMA_PERF_SEL_L1_WRMC_IDLE', + 'LSDMA_PERF_SEL_L1_WR_FIFO_IDLE', 'LSDMA_PERF_SEL_L1_WR_INV_EN', + 'LSDMA_PERF_SEL_L1_WR_INV_IDLE', + 'LSDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 'LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', + 'LSDMA_PERF_SEL_MC_RD_COUNT', 'LSDMA_PERF_SEL_MC_RD_IDLE', + 'LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'LSDMA_PERF_SEL_MC_RD_RET_STALL', 'LSDMA_PERF_SEL_MC_WR_COUNT', + 'LSDMA_PERF_SEL_MC_WR_IDLE', + 'LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID', + 'LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID', + 'LSDMA_PERF_SEL_NACK_GEN_ERR', 'LSDMA_PERF_SEL_NUM_PACKET', + 'LSDMA_PERF_SEL_PAGE_SELECT', 'LSDMA_PERF_SEL_RB_CMD_FULL', + 'LSDMA_PERF_SEL_RB_CMD_IDLE', 'LSDMA_PERF_SEL_RB_EMPTY', + 'LSDMA_PERF_SEL_RB_FULL', 'LSDMA_PERF_SEL_RB_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_RB_MMHUB_RD_RET', 'LSDMA_PERF_SEL_RB_RPTR_WB', + 'LSDMA_PERF_SEL_RB_RPTR_WRAP', 'LSDMA_PERF_SEL_RB_WPTR_POLL_READ', + 'LSDMA_PERF_SEL_RB_WPTR_WRAP', 'LSDMA_PERF_SEL_RD_BA_RTR', + 'LSDMA_PERF_SEL_REG_IDLE', 'LSDMA_PERF_SEL_RLC0_SELECT', + 'LSDMA_PERF_SEL_RLC1_SELECT', 'LSDMA_PERF_SEL_SDMA_ATCL2_SEND', + 'LSDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 'LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH', 'LSDMA_PERF_SEL_SEM_IDLE', + 'LSDMA_PERF_SEL_SEM_REQ_COUNT', 'LSDMA_PERF_SEL_SEM_REQ_STALL', + 'LSDMA_PERF_SEL_SEM_RESP_FAIL', + 'LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'LSDMA_PERF_SEL_SEM_RESP_PASS', 'LSDMA_PERF_SEL_SRBM_REG_SEND', + 'LSDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 'LSDMA_PERF_SEL_UTCL1_UTCL2_RET', + 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET', 'LSDMA_PERF_SEL_WR_BA_RTR', + 'LS_STAGE_OFF', 'LS_STAGE_ON', 'LUT_2CFG_MEMORY_A', + 'LUT_2CFG_MEMORY_B', 'LUT_2CFG_NO_MEMORY', 'LUT_2_MODE_BYPASS', + 'LUT_2_MODE_RAMA_LUT', 'LUT_2_MODE_RAMB_LUT', 'LUT_4CFG_MEMORY_A', + 'LUT_4CFG_MEMORY_B', 'LUT_4CFG_NO_MEMORY', 'LUT_4CFG_ROM_A', + 'LUT_4CFG_ROM_B', 'LUT_4_MODE_BYPASS', 'LUT_4_MODE_RAMA_LUT', + 'LUT_4_MODE_RAMB_LUT', 'LUT_4_MODE_ROMA_LUT', + 'LUT_4_MODE_ROMB_LUT', 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', + 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT', + 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 'MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM', + 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', + 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_LOCK_SEL', 'MASTER_UPDATE_LOCK_SEL_0', + 'MASTER_UPDATE_LOCK_SEL_1', 'MASTER_UPDATE_LOCK_SEL_2', + 'MASTER_UPDATE_LOCK_SEL_3', 'MASTER_UPDATE_LOCK_SEL_RESERVED4', + 'MASTER_UPDATE_LOCK_SEL_RESERVED5', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 'MEM_ARB_MODE_AGE', 'MEM_ARB_MODE_BOTH', 'MEM_ARB_MODE_FIXED', + 'MEM_ARB_MODE_WEIGHT', 'MEM_POWER_DIS_MODE_DISABLE', + 'MEM_POWER_DIS_MODE_ENABLE', 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', + 'MEM_POWER_FORCE_MODE_LIGHT_SLEEP', 'MEM_POWER_FORCE_MODE_OFF', + 'MEM_POWER_FORCE_MODE_SHUT_DOWN', 'MEM_POWER_STATUS_DEEP_SLEEP', + 'MEM_POWER_STATUS_LIGHT_SLEEP', 'MEM_POWER_STATUS_ON', + 'MEM_POWER_STATUS_SHUT_DOWN', 'MEM_PWR_DIS_CTRL', + 'MEM_PWR_DIS_MODE', 'MEM_PWR_FORCE_CTRL', 'MEM_PWR_FORCE_CTRL2', + 'MEM_PWR_FORCE_MODE', 'MEM_PWR_SEL_CTRL', 'MEM_PWR_SEL_CTRL2', + 'MEM_PWR_STATUS', 'METADATA_HUBP_SEL', 'METADATA_HUBP_SEL_0', + 'METADATA_HUBP_SEL_1', 'METADATA_HUBP_SEL_2', + 'METADATA_HUBP_SEL_3', 'METADATA_HUBP_SEL_RESERVED', + 'METADATA_STREAM_DP', 'METADATA_STREAM_DVE', + 'METADATA_STREAM_TYPE_SEL', 'META_CHUNK_SIZE', + 'META_CHUNK_SIZE_1KB', 'META_CHUNK_SIZE_2KB', + 'META_CHUNK_SIZE_4KB', 'META_CHUNK_SIZE_8KB', 'META_LINEAR', + 'META_SURF_LINEAR', 'META_SURF_TILED', 'ME_ID0', 'ME_ID1', + 'ME_ID2', 'ME_ID3', 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL', + 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL', 'MIN_CHUNK_SIZE', + 'MIN_CHUNK_SIZE_1024B', 'MIN_CHUNK_SIZE_256B', + 'MIN_CHUNK_SIZE_512B', 'MIN_META_CHUNK_SIZE', + 'MIN_META_CHUNK_SIZE_128B', 'MIN_META_CHUNK_SIZE_256B', + 'MIN_META_CHUNK_SIZE_64B', 'MONO_10LSB', 'MONO_10MSB', + 'MONO_12LSB', 'MONO_12MSB', 'MONO_16', 'MONO_2BIT', 'MONO_8', + 'MPCC_BG_COLOR_BPC', 'MPCC_BG_COLOR_BPC_10bit', + 'MPCC_BG_COLOR_BPC_11bit', 'MPCC_BG_COLOR_BPC_12bit', + 'MPCC_BG_COLOR_BPC_8bit', 'MPCC_BG_COLOR_BPC_9bit', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', 'MPCC_CONTROL_MPCC_MODE', + 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12', 'MPCC_GAMUT_REMAP_MODE_0', + 'MPCC_GAMUT_REMAP_MODE_1', 'MPCC_GAMUT_REMAP_MODE_2', + 'MPCC_GAMUT_REMAP_MODE_ENUM', 'MPCC_GAMUT_REMAP_MODE_RSV', + 'MPCC_MCM_3DLUT_17CUBE', 'MPCC_MCM_3DLUT_30BIT', + 'MPCC_MCM_3DLUT_30BIT_ENUM', 'MPCC_MCM_3DLUT_36BIT', + 'MPCC_MCM_3DLUT_9CUBE', 'MPCC_MCM_3DLUT_RAM_SEL', + 'MPCC_MCM_3DLUT_SIZE_ENUM', 'MPCC_MCM_GAMMA_LUT_BYPASS', + 'MPCC_MCM_GAMMA_LUT_DISABLE_PWL', 'MPCC_MCM_GAMMA_LUT_ENABLE_PWL', + 'MPCC_MCM_GAMMA_LUT_MODE_ENUM', + 'MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM', 'MPCC_MCM_GAMMA_LUT_RAMA', + 'MPCC_MCM_GAMMA_LUT_RAMB', 'MPCC_MCM_GAMMA_LUT_RAM_LUT', + 'MPCC_MCM_GAMMA_LUT_RESERVED_1', 'MPCC_MCM_GAMMA_LUT_RESERVED_3', + 'MPCC_MCM_GAMMA_LUT_SEL_ENUM', 'MPCC_MCM_LUT_2_MODE_BYPASS', + 'MPCC_MCM_LUT_2_MODE_ENUM', 'MPCC_MCM_LUT_2_MODE_RAMA_LUT', + 'MPCC_MCM_LUT_2_MODE_RAMB_LUT', 'MPCC_MCM_LUT_ALL_USE_R', + 'MPCC_MCM_LUT_BLUE_LUT', 'MPCC_MCM_LUT_CONFIG_MODE', + 'MPCC_MCM_LUT_DIFFERENT_RGB', 'MPCC_MCM_LUT_DISABLE_DEBUG', + 'MPCC_MCM_LUT_ENABLE_DEBUG', 'MPCC_MCM_LUT_GREEN_LUT', + 'MPCC_MCM_LUT_NUM_SEG', 'MPCC_MCM_LUT_RAMA_ACCESS', + 'MPCC_MCM_LUT_RAMB_ACCESS', 'MPCC_MCM_LUT_RAM_SEL', + 'MPCC_MCM_LUT_READ_COLOR_SEL', 'MPCC_MCM_LUT_READ_DBG', + 'MPCC_MCM_LUT_RED_LUT', 'MPCC_MCM_LUT_SEGMENTS_1', + 'MPCC_MCM_LUT_SEGMENTS_128', 'MPCC_MCM_LUT_SEGMENTS_16', + 'MPCC_MCM_LUT_SEGMENTS_2', 'MPCC_MCM_LUT_SEGMENTS_32', + 'MPCC_MCM_LUT_SEGMENTS_4', 'MPCC_MCM_LUT_SEGMENTS_64', + 'MPCC_MCM_LUT_SEGMENTS_8', 'MPCC_MCM_MEM_PWR_FORCE_DIS', + 'MPCC_MCM_MEM_PWR_FORCE_DS', 'MPCC_MCM_MEM_PWR_FORCE_ENUM', + 'MPCC_MCM_MEM_PWR_FORCE_LS', 'MPCC_MCM_MEM_PWR_FORCE_SD', + 'MPCC_MCM_MEM_PWR_STATE_DS', 'MPCC_MCM_MEM_PWR_STATE_ENUM', + 'MPCC_MCM_MEM_PWR_STATE_LS', 'MPCC_MCM_MEM_PWR_STATE_ON', + 'MPCC_MCM_MEM_PWR_STATE_SD', 'MPCC_MCM_RAM0_ACCESS', + 'MPCC_MCM_RAM1_ACCESS', 'MPCC_MCM_RAM2_ACCESS', + 'MPCC_MCM_RAM3_ACCESS', 'MPCC_OGAM_ALL_USE_R', + 'MPCC_OGAM_BLUE_LUT', 'MPCC_OGAM_DIFFERENT_RGB', + 'MPCC_OGAM_DISABLE_DEBUG', 'MPCC_OGAM_DISABLE_PWL', + 'MPCC_OGAM_ENABLE_DEBUG', 'MPCC_OGAM_ENABLE_PWL', + 'MPCC_OGAM_GREEN_LUT', 'MPCC_OGAM_LUT_2CFG_MEMORY_A', + 'MPCC_OGAM_LUT_2CFG_MEMORY_B', 'MPCC_OGAM_LUT_2CFG_NO_MEMORY', + 'MPCC_OGAM_LUT_2_CONFIG_ENUM', 'MPCC_OGAM_LUT_CONFIG_MODE', + 'MPCC_OGAM_LUT_PWL_DISABLE_ENUM', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', + 'MPCC_OGAM_LUT_RAM_SEL', 'MPCC_OGAM_LUT_READ_COLOR_SEL', + 'MPCC_OGAM_LUT_READ_DBG', 'MPCC_OGAM_LUT_SEL_ENUM', + 'MPCC_OGAM_MODE_0', 'MPCC_OGAM_MODE_2', + 'MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM', 'MPCC_OGAM_MODE_RSV', + 'MPCC_OGAM_MODE_RSV1', 'MPCC_OGAM_NUM_SEG', 'MPCC_OGAM_RAMA', + 'MPCC_OGAM_RAMA_ACCESS', 'MPCC_OGAM_RAMB', + 'MPCC_OGAM_RAMB_ACCESS', 'MPCC_OGAM_RED_LUT', + 'MPCC_OGAM_SEGMENTS_1', 'MPCC_OGAM_SEGMENTS_128', + 'MPCC_OGAM_SEGMENTS_16', 'MPCC_OGAM_SEGMENTS_2', + 'MPCC_OGAM_SEGMENTS_32', 'MPCC_OGAM_SEGMENTS_4', + 'MPCC_OGAM_SEGMENTS_64', 'MPCC_OGAM_SEGMENTS_8', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_EN', 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN', + 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_FALSE', + 'MPCC_TEST_DEBUG_INDEX_MPCC_TEST_DEBUG_WRITE_EN_TRUE', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', 'MPC_CFG_MPC_TEST_CLK_SEL', + 'MPC_CFG_MPC_TEST_CLK_SEL_0', 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 'MPC_CFG_MPC_TEST_CLK_SEL_2', 'MPC_CFG_MPC_TEST_CLK_SEL_3', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE', + 'MPC_CRC_CALC_INTERLACE_MODE', 'MPC_CRC_CALC_MODE', + 'MPC_CRC_CALC_STEREO_MODE', 'MPC_CRC_CONTINUOUS_MODE', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', + 'MPC_CRC_INTERLACE_MODE_BOTTOM', 'MPC_CRC_INTERLACE_MODE_TOP', + 'MPC_CRC_ONE_SHOT_MODE', 'MPC_CRC_SOURCE_SELECT', + 'MPC_CRC_SOURCE_SEL_DPP', 'MPC_CRC_SOURCE_SEL_DWB', + 'MPC_CRC_SOURCE_SEL_OPP', 'MPC_CRC_SOURCE_SEL_OTHER', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 'MPC_CRC_STEREO_MODE_LEFT', 'MPC_CRC_STEREO_MODE_RIGHT', + 'MPC_DEBUG_BUS1_DATA_SELECT', + 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_CFG', + 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_CONT', + 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV', + 'MPC_DEBUG_BUS1_DATA_SELECT_MPC_RSV1', + 'MPC_DEBUG_BUS2_DATA_SELECT', 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC', + 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC_CONT', + 'MPC_DEBUG_BUS2_DATA_SELECT_MPCC_MCM', + 'MPC_DEBUG_BUS2_DATA_SELECT_RES', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_DEBUG_ID', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_MCM_DEBUG_ID', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPCC_OGAM_DEBUG_ID', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_DEBUG_ID', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_MPC_OCSC_DEBUG_ID', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_RSV1', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFR_DEBUG_DATA', + 'MPC_DEBUG_BUS_DIRECT_OUT_DATA_SELECT_SFT_DEBUG_DATA', + 'MPC_DEBUG_BUS_MPCC_BYTE0', 'MPC_DEBUG_BUS_MPCC_BYTE1', + 'MPC_DEBUG_BUS_MPCC_BYTE2', 'MPC_DEBUG_BUS_MPCC_BYTE3', + 'MPC_DEBUG_BUS_MPCC_BYTE_SELECT', 'MPC_OCSC_COEF_FORMAT', + 'MPC_OCSC_COEF_FORMAT_S2_13', 'MPC_OCSC_COEF_FORMAT_S3_12', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE', + 'MPC_OUT_CSC_MODE', 'MPC_OUT_CSC_MODE_0', 'MPC_OUT_CSC_MODE_1', + 'MPC_OUT_CSC_MODE_2', 'MPC_OUT_CSC_MODE_RSV', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', + 'MPC_OUT_RATE_CONTROL_DISABLE_SET', + 'MPC_OUT_RATE_CONTROL_SET_DISABLE', + 'MPC_OUT_RATE_CONTROL_SET_ENABLE', + 'MSA_V_TIMING_OVERRIDE_DISABLED', 'MSA_V_TIMING_OVERRIDE_ENABLED', + 'MTYPE', 'MTYPE_CC', 'MTYPE_C_RO_S', 'MTYPE_C_RO_US', + 'MTYPE_C_RW_S', 'MTYPE_C_RW_US', 'MTYPE_NC', 'MTYPE_RESERVED_1', + 'MTYPE_RESERVED_5', 'MTYPE_RESERVED_7', 'MTYPE_UC', 'MTYPE_WC', + 'MULTIPLE_BY1', 'MULTIPLE_BY2', 'MULTIPLE_BY3_RESERVED', + 'MULTIPLE_BY4', 'MULTIPLE_RESERVED', 'MULT_16', 'MULT_8', + 'MemArbMode', 'NON_BYPASS', 'NOT_FORCE_THE_CLOCK_DISABLED', + 'NOT_SENT', 'NO_DIST', 'NO_DIV', 'NO_FORCE', 'NO_FORCE_REQ', + 'NO_FORCE_REQUEST', 'NO_MIN_CHUNK_SIZE', 'NO_MIN_META_CHUNK_SIZE', + 'NO_OUTSTANDING_REQ', 'NUM_SIMD_PER_CU', 'OBUF_BYPASS_DIS', + 'OBUF_BYPASS_EN', 'OBUF_BYPASS_SEL', 'OBUF_FULL', + 'OBUF_FULL_RECOUT', 'OBUF_HALF_RECOUT', + 'OBUF_IS_HALF_RECOUT_WIDTH_SEL', 'OBUF_RECOUT', + 'OBUF_USE_FULL_BUFFER_SEL', 'OFFCHIP_HS_DEALLOC', 'OFF_SEQ', + 'OKAY', 'OKAY_NODATA', 'OMODE_BLEND', 'OMODE_O_THEN_B', + 'OMODE_P_THEN_O_THEN_B', 'OMODE_RESERVED_3', 'ON_SEQ', + 'OPPBUF_DISPLAY_SEGMENTATION', + 'OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT', + 'OPP_ABM_DEBUG_BUS_SELECT_CONTROL', + 'OPP_DPG_DEBUG_BUS_SELECT_CONTROL', + 'OPP_FMT_DEBUG_BUS_SELECT_CONTROL', + 'OPP_OPPBUF_DEBUG_BUS_SELECT_CONTROL', + 'OPP_OPP_PIPE_DEBUG_BUS_SELECT_CONTROL', 'OPP_PIPE_CLOCK_DISABLE', + 'OPP_PIPE_CLOCK_ENABLE', 'OPP_PIPE_CLOCK_ENABLE_CONTROL', + 'OPP_PIPE_CRC_CONT_EN', 'OPP_PIPE_CRC_DISABLE', 'OPP_PIPE_CRC_EN', + 'OPP_PIPE_CRC_ENABLE', 'OPP_PIPE_CRC_INTERLACE_EN', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 'OPP_PIPE_CRC_INTERLACE_MODE', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', 'OPP_PIPE_CRC_MODE_CONTINUOUS', + 'OPP_PIPE_CRC_MODE_ONE_SHOT', 'OPP_PIPE_CRC_ONE_SHOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', + 'OPP_PIPE_CRC_PIXEL_SELECT', + 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 'OPP_PIPE_CRC_SOURCE_SELECT', 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', 'OPP_PIPE_CRC_STEREO_EN', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', + 'OPP_PIPE_CRC_STEREO_MODE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_LEFT', 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL', + 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', 'OPP_TEST_CLK_SEL_CONTROL', + 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', 'OPP_TEST_CLK_SEL_DISPCLK_ABM1', + 'OPP_TEST_CLK_SEL_DISPCLK_ABM2', 'OPP_TEST_CLK_SEL_DISPCLK_ABM3', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', + 'OPP_TEST_CLK_SEL_DISPCLK_P', 'OPP_TEST_CLK_SEL_DISPCLK_R', + 'OPP_TEST_CLK_SEL_RESERVED0', 'OPP_TEST_CLK_SEL_RESERVED1', + 'OPP_TEST_CLK_SEL_RESERVED2', 'OPP_TEST_CLK_SEL_RESERVED3', + 'OPP_TOP_CLOCK_DISABLED_STATUS', 'OPP_TOP_CLOCK_ENABLED_STATUS', + 'OPP_TOP_CLOCK_ENABLE_STATUS', 'OPP_TOP_CLOCK_GATING_CONTROL', + 'OPP_TOP_CLOCK_GATING_DISABLED', 'OPP_TOP_CLOCK_GATING_ENABLED', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5', + 'OPT_COMB_ADD', 'OPT_COMB_BLEND_DISABLED', 'OPT_COMB_MAX', + 'OPT_COMB_MIN', 'OPT_COMB_NONE', 'OPT_COMB_REVSUBTRACT', + 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', + 'OTG_ADD_PIXEL', 'OTG_ADD_PIXEL_FORCE', 'OTG_ADD_PIXEL_NOOP', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', + 'OTG_CONTROL_OTG_MASTER_EN', 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 'OTG_CONTROL_OTG_MASTER_EN_TRUE', 'OTG_CONTROL_OTG_OUT_MUX', + 'OTG_CONTROL_OTG_OUT_MUX_0', 'OTG_CONTROL_OTG_OUT_MUX_1', + 'OTG_CONTROL_OTG_OUT_MUX_2', 'OTG_CONTROL_OTG_START_POINT_CNTL', + 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', + 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC1_EN', 'OTG_CRC_CNTL_OTG_CRC1_EN_FALSE', + 'OTG_CRC_CNTL_OTG_CRC1_EN_TRUE', 'OTG_CRC_CNTL_OTG_CRC_CONT_EN', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET', 'OTG_CRC_CNTL_OTG_CRC_EN', + 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 'OTG_DIG_UPDATE_VCOUNT_0', 'OTG_DIG_UPDATE_VCOUNT_1', + 'OTG_DIG_UPDATE_VCOUNT_MODE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', + 'OTG_DROP_PIXEL', 'OTG_DROP_PIXEL_FORCE', 'OTG_DROP_PIXEL_NOOP', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5', + 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL', + 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL', + 'OTG_GLOBAL_UPDATE_LOCK_DISABLE', 'OTG_GLOBAL_UPDATE_LOCK_EN', + 'OTG_GLOBAL_UPDATE_LOCK_ENABLE', 'OTG_GSL_MASTER_MODE', + 'OTG_GSL_MASTER_MODE_0', 'OTG_GSL_MASTER_MODE_1', + 'OTG_GSL_MASTER_MODE_2', 'OTG_GSL_MASTER_MODE_3', + 'OTG_HORZ_REPETITION_COUNT', 'OTG_HORZ_REPETITION_COUNT_0', + 'OTG_HORZ_REPETITION_COUNT_1', 'OTG_HORZ_REPETITION_COUNT_10', + 'OTG_HORZ_REPETITION_COUNT_11', 'OTG_HORZ_REPETITION_COUNT_12', + 'OTG_HORZ_REPETITION_COUNT_13', 'OTG_HORZ_REPETITION_COUNT_14', + 'OTG_HORZ_REPETITION_COUNT_15', 'OTG_HORZ_REPETITION_COUNT_2', + 'OTG_HORZ_REPETITION_COUNT_3', 'OTG_HORZ_REPETITION_COUNT_4', + 'OTG_HORZ_REPETITION_COUNT_5', 'OTG_HORZ_REPETITION_COUNT_6', + 'OTG_HORZ_REPETITION_COUNT_7', 'OTG_HORZ_REPETITION_COUNT_8', + 'OTG_HORZ_REPETITION_COUNT_9', 'OTG_H_SYNC_A_POL', + 'OTG_H_SYNC_A_POL_HIGH', 'OTG_H_SYNC_A_POL_LOW', + 'OTG_H_TIMING_DIV_MODE', 'OTG_H_TIMING_DIV_MODE_AUTO', + 'OTG_H_TIMING_DIV_MODE_DIV_BY2', 'OTG_H_TIMING_DIV_MODE_DIV_BY4', + 'OTG_H_TIMING_DIV_MODE_MANUAL', 'OTG_H_TIMING_DIV_MODE_NOAUTO', + 'OTG_H_TIMING_DIV_MODE_NO_DIV', 'OTG_H_TIMING_DIV_MODE_RESERVED', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', + 'OTG_MASTER_UPDATE_LOCK_DB_EN', 'OTG_MASTER_UPDATE_LOCK_DISABLE', + 'OTG_MASTER_UPDATE_LOCK_ENABLE', 'OTG_MASTER_UPDATE_LOCK_GSL_EN', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_0', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_1', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGA_FREQUENCY_SELECT', 'OTG_TRIGA_FREQUENCY_SELECT_0', + 'OTG_TRIGA_FREQUENCY_SELECT_1', 'OTG_TRIGA_FREQUENCY_SELECT_2', + 'OTG_TRIGA_FREQUENCY_SELECT_3', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_FREQUENCY_SELECT', 'OTG_TRIGB_FREQUENCY_SELECT_0', + 'OTG_TRIGB_FREQUENCY_SELECT_1', 'OTG_TRIGB_FREQUENCY_SELECT_2', + 'OTG_TRIGB_FREQUENCY_SELECT_3', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', + 'OTG_VUPDATE_BLOCK_DISABLE', 'OTG_VUPDATE_BLOCK_DISABLE_OFF', + 'OTG_VUPDATE_BLOCK_DISABLE_ON', 'OTG_V_SYNC_A_POL', + 'OTG_V_SYNC_A_POL_HIGH', 'OTG_V_SYNC_A_POL_LOW', + 'OTG_V_SYNC_MODE', 'OTG_V_SYNC_MODE_HBLANK', + 'OTG_V_SYNC_MODE_HSYNC', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE', + 'OUTPUT_LINE', 'OUTPUT_POINT', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'OUTPUT_TRIANGLE_CCW', 'OUTPUT_TRIANGLE_CW', 'OUTSTANDING_REQ', + 'OVERRUN', 'OreoMode', 'PART_FRAC_EVEN', 'PART_FRAC_ODD', + 'PART_INTEGER', 'PART_POW2', 'PATCHES', 'PERFCOUNTER_ACTIVE', + 'PERFCOUNTER_CNT0_STATE', 'PERFCOUNTER_CNT0_STATE_FREEZE', + 'PERFCOUNTER_CNT0_STATE_HW', 'PERFCOUNTER_CNT0_STATE_RESET', + 'PERFCOUNTER_CNT0_STATE_START', 'PERFCOUNTER_CNT1_STATE', + 'PERFCOUNTER_CNT1_STATE_FREEZE', 'PERFCOUNTER_CNT1_STATE_HW', + 'PERFCOUNTER_CNT1_STATE_RESET', 'PERFCOUNTER_CNT1_STATE_START', + 'PERFCOUNTER_CNT2_STATE', 'PERFCOUNTER_CNT2_STATE_FREEZE', + 'PERFCOUNTER_CNT2_STATE_HW', 'PERFCOUNTER_CNT2_STATE_RESET', + 'PERFCOUNTER_CNT2_STATE_START', 'PERFCOUNTER_CNT3_STATE', + 'PERFCOUNTER_CNT3_STATE_FREEZE', 'PERFCOUNTER_CNT3_STATE_HW', + 'PERFCOUNTER_CNT3_STATE_RESET', 'PERFCOUNTER_CNT3_STATE_START', + 'PERFCOUNTER_CNT4_STATE', 'PERFCOUNTER_CNT4_STATE_FREEZE', + 'PERFCOUNTER_CNT4_STATE_HW', 'PERFCOUNTER_CNT4_STATE_RESET', + 'PERFCOUNTER_CNT4_STATE_START', 'PERFCOUNTER_CNT5_STATE', + 'PERFCOUNTER_CNT5_STATE_FREEZE', 'PERFCOUNTER_CNT5_STATE_HW', + 'PERFCOUNTER_CNT5_STATE_RESET', 'PERFCOUNTER_CNT5_STATE_START', + 'PERFCOUNTER_CNT6_STATE', 'PERFCOUNTER_CNT6_STATE_FREEZE', + 'PERFCOUNTER_CNT6_STATE_HW', 'PERFCOUNTER_CNT6_STATE_RESET', + 'PERFCOUNTER_CNT6_STATE_START', 'PERFCOUNTER_CNT7_STATE', + 'PERFCOUNTER_CNT7_STATE_FREEZE', 'PERFCOUNTER_CNT7_STATE_HW', + 'PERFCOUNTER_CNT7_STATE_RESET', 'PERFCOUNTER_CNT7_STATE_START', + 'PERFCOUNTER_CNTL_SEL', 'PERFCOUNTER_CNTL_SEL_0', + 'PERFCOUNTER_CNTL_SEL_1', 'PERFCOUNTER_CNTL_SEL_2', + 'PERFCOUNTER_CNTL_SEL_3', 'PERFCOUNTER_CNTL_SEL_4', + 'PERFCOUNTER_CNTL_SEL_5', 'PERFCOUNTER_CNTL_SEL_6', + 'PERFCOUNTER_CNTL_SEL_7', 'PERFCOUNTER_CNTOFF_START_DIS', + 'PERFCOUNTER_CNTOFF_START_DISABLE', + 'PERFCOUNTER_CNTOFF_START_ENABLE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', 'PERFCOUNTER_CVALUE_SEL', + 'PERFCOUNTER_CVALUE_SEL_11_0', 'PERFCOUNTER_CVALUE_SEL_15_0', + 'PERFCOUNTER_CVALUE_SEL_23_12', 'PERFCOUNTER_CVALUE_SEL_31_16', + 'PERFCOUNTER_CVALUE_SEL_35_24', 'PERFCOUNTER_CVALUE_SEL_47_0', + 'PERFCOUNTER_CVALUE_SEL_47_32', 'PERFCOUNTER_CVALUE_SEL_47_36', + 'PERFCOUNTER_HW_CNTL_SEL', 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', + 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', 'PERFCOUNTER_HW_STOP1_0', + 'PERFCOUNTER_HW_STOP1_1', 'PERFCOUNTER_HW_STOP1_SEL', + 'PERFCOUNTER_HW_STOP2_0', 'PERFCOUNTER_HW_STOP2_1', + 'PERFCOUNTER_HW_STOP2_SEL', 'PERFCOUNTER_INC_MODE', + 'PERFCOUNTER_INC_MODE_BOTH_EDGE', 'PERFCOUNTER_INC_MODE_LSB', + 'PERFCOUNTER_INC_MODE_MULTI_BIT', 'PERFCOUNTER_INC_MODE_NEG_EDGE', + 'PERFCOUNTER_INC_MODE_POS_EDGE', 'PERFCOUNTER_INT_DISABLE', + 'PERFCOUNTER_INT_EN', 'PERFCOUNTER_INT_ENABLE', + 'PERFCOUNTER_INT_TYPE', 'PERFCOUNTER_INT_TYPE_LEVEL', + 'PERFCOUNTER_INT_TYPE_PULSE', 'PERFCOUNTER_IS_ACTIVE', + 'PERFCOUNTER_IS_IDLE', 'PERFCOUNTER_OFF_MASK', + 'PERFCOUNTER_OFF_MASK_DISABLE', 'PERFCOUNTER_OFF_MASK_ENABLE', + 'PERFCOUNTER_RESTART_DISABLE', 'PERFCOUNTER_RESTART_EN', + 'PERFCOUNTER_RESTART_ENABLE', 'PERFCOUNTER_RUNEN_MODE', + 'PERFCOUNTER_RUNEN_MODE_EDGE', 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 'PERFCOUNTER_SAMPLE', 'PERFCOUNTER_START', + 'PERFCOUNTER_STATE_SEL0', 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 'PERFCOUNTER_STATE_SEL0_LOCAL', 'PERFCOUNTER_STATE_SEL1', + 'PERFCOUNTER_STATE_SEL1_GLOBAL', 'PERFCOUNTER_STATE_SEL1_LOCAL', + 'PERFCOUNTER_STATE_SEL2', 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 'PERFCOUNTER_STATE_SEL2_LOCAL', 'PERFCOUNTER_STATE_SEL3', + 'PERFCOUNTER_STATE_SEL3_GLOBAL', 'PERFCOUNTER_STATE_SEL3_LOCAL', + 'PERFCOUNTER_STATE_SEL4', 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 'PERFCOUNTER_STATE_SEL4_LOCAL', 'PERFCOUNTER_STATE_SEL5', + 'PERFCOUNTER_STATE_SEL5_GLOBAL', 'PERFCOUNTER_STATE_SEL5_LOCAL', + 'PERFCOUNTER_STATE_SEL6', 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 'PERFCOUNTER_STATE_SEL6_LOCAL', 'PERFCOUNTER_STATE_SEL7', + 'PERFCOUNTER_STATE_SEL7_GLOBAL', 'PERFCOUNTER_STATE_SEL7_LOCAL', + 'PERFCOUNTER_STOP', 'PERFMON_CNTOFF_AND', 'PERFMON_CNTOFF_AND_OR', + 'PERFMON_CNTOFF_INT_DISABLE', 'PERFMON_CNTOFF_INT_EN', + 'PERFMON_CNTOFF_INT_ENABLE', 'PERFMON_CNTOFF_INT_TYPE', + 'PERFMON_CNTOFF_INT_TYPE_LEVEL', 'PERFMON_CNTOFF_INT_TYPE_PULSE', + 'PERFMON_CNTOFF_OR', 'PERFMON_COUNTER_MODE', + 'PERFMON_COUNTER_MODE_ACCUM', + 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 'PERFMON_COUNTER_MODE_DIRTY', + 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_MAX', 'PERFMON_COUNTER_MODE_RESERVED', + 'PERFMON_COUNTER_MODE_SAMPLE', 'PERFMON_SPM_MODE', + 'PERFMON_SPM_MODE_16BIT_CLAMP', 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_32BIT_CLAMP', 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_OFF', 'PERFMON_SPM_MODE_RESERVED_5', + 'PERFMON_SPM_MODE_RESERVED_6', 'PERFMON_SPM_MODE_RESERVED_7', + 'PERFMON_SPM_MODE_TEST_MODE_0', 'PERFMON_SPM_MODE_TEST_MODE_1', + 'PERFMON_SPM_MODE_TEST_MODE_2', 'PERFMON_STATE', + 'PERFMON_STATE_FREEZE', 'PERFMON_STATE_HW', 'PERFMON_STATE_RESET', + 'PERFMON_STATE_START', 'PERF_CLIPSM_CULL_PRIMS_CNT', + 'PERF_ENGG_BUSY', 'PERF_ENGG_CSB_DELAY_BIN00', + 'PERF_ENGG_CSB_DELAY_BIN01', 'PERF_ENGG_CSB_DELAY_BIN02', + 'PERF_ENGG_CSB_DELAY_BIN03', 'PERF_ENGG_CSB_DELAY_BIN04', + 'PERF_ENGG_CSB_DELAY_BIN05', 'PERF_ENGG_CSB_DELAY_BIN06', + 'PERF_ENGG_CSB_DELAY_BIN07', 'PERF_ENGG_CSB_DELAY_BIN08', + 'PERF_ENGG_CSB_DELAY_BIN09', 'PERF_ENGG_CSB_DELAY_BIN10', + 'PERF_ENGG_CSB_DELAY_BIN11', 'PERF_ENGG_CSB_DELAY_BIN12', + 'PERF_ENGG_CSB_DELAY_BIN13', 'PERF_ENGG_CSB_DELAY_BIN14', + 'PERF_ENGG_CSB_DELAY_BIN15', 'PERF_ENGG_CSB_GE_INPUT_FIFO_FULL', + 'PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT', + 'PERF_ENGG_CSB_GE_MEMORY_EMPTY', 'PERF_ENGG_CSB_GE_MEMORY_FULL', + 'PERF_ENGG_CSB_GE_SENDING_SUBGROUP', + 'PERF_ENGG_CSB_MACHINE_IS_STARVED', + 'PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 'PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI', + 'PERF_ENGG_CSB_NULL_SUBGROUP', + 'PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL', + 'PERF_ENGG_CSB_PRIM_COUNT_EQ0', 'PERF_ENGG_CSB_SPI_DELAY_BIN00', + 'PERF_ENGG_CSB_SPI_DELAY_BIN01', 'PERF_ENGG_CSB_SPI_DELAY_BIN02', + 'PERF_ENGG_CSB_SPI_DELAY_BIN03', 'PERF_ENGG_CSB_SPI_DELAY_BIN04', + 'PERF_ENGG_CSB_SPI_DELAY_BIN05', 'PERF_ENGG_CSB_SPI_DELAY_BIN06', + 'PERF_ENGG_CSB_SPI_DELAY_BIN07', 'PERF_ENGG_CSB_SPI_DELAY_BIN08', + 'PERF_ENGG_CSB_SPI_DELAY_BIN09', 'PERF_ENGG_CSB_SPI_DELAY_BIN10', + 'PERF_ENGG_CSB_SPI_INPUT_FIFO_FULL', + 'PERF_ENGG_CSB_SPI_MEMORY_EMPTY', 'PERF_ENGG_CSB_SPI_MEMORY_FULL', + 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB', + 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 'PERF_ENGG_INDEX_REQ_0_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_REQ_1_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_REQ_2_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_REQ_3_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_REQ_NULL_REQUEST', + 'PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', + 'PERF_ENGG_INDEX_REQ_STARVED', + 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_READING_EVENT', + 'PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_NULL_PRIMS', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_NULL_PRIMS', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_NULL_PRIMS', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_NULL_PRIMS', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_NULL_PRIMS', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 'PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 'PERF_ENGG_POS_REQ_STARVED', 'PERF_OUTPUT_PRIM_1_SC', + 'PERF_OUTPUT_PRIM_2_SC', 'PERF_OUTPUT_PRIM_3_SC', + 'PERF_OUTPUT_PRIM_4_SC', 'PERF_PAPC_CCGSM_BUSY', + 'PERF_PAPC_CCGSM_IDLE', 'PERF_PAPC_CCGSM_STALLED', + 'PERF_PAPC_CLIPGA_BUSY', 'PERF_PAPC_CLIPGA_IDLE', + 'PERF_PAPC_CLIPGA_STALLED', 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', 'PERF_PAPC_CLIPSM_BUSY', + 'PERF_PAPC_CLIPSM_IDLE', 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', 'PERF_PAPC_CLIP_BUSY', + 'PERF_PAPC_CLIP_IDLE', 'PERF_PAPC_CLPRIM_BUSY', + 'PERF_PAPC_CLPRIM_IDLE', 'PERF_PAPC_CLPRIM_STALLED', + 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', 'PERF_PAPC_CLPR_CULL_PRIM', + 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 'PERF_PAPC_CLPR_VV_CULL_PRIM', 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', 'PERF_PAPC_CLSM_NULL_PRIM', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 'PERF_PAPC_CL_DYN_SCLK_VLD', 'PERF_PAPC_PASX_DISABLE_PIPE', + 'PERF_PAPC_PASX_FIRST_DEAD', 'PERF_PAPC_PASX_FIRST_VECTOR', + 'PERF_PAPC_PASX_REC_BUSY', 'PERF_PAPC_PASX_REC_IDLE', + 'PERF_PAPC_PASX_REC_STALLED', + 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 'PERF_PAPC_PASX_REC_STARVED_SX', 'PERF_PAPC_PASX_REQ', + 'PERF_PAPC_PASX_REQ_BUSY', 'PERF_PAPC_PASX_REQ_IDLE', + 'PERF_PAPC_PASX_REQ_STALLED', 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 'PERF_PAPC_PASX_SE0_REQ', 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', 'PERF_PAPC_PASX_SE1_REQ', + 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', 'PERF_PAPC_PASX_SECOND_DEAD', + 'PERF_PAPC_PASX_SECOND_VECTOR', 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_PA_INPUT_NULL_PRIM', 'PERF_PAPC_PA_INPUT_PRIM', + 'PERF_PAPC_PA_REG_SCLK_VLD', 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 'PERF_PAPC_SU_BUSY', 'PERF_PAPC_SU_CULLED_PRIM', + 'PERF_PAPC_SU_DYN_SCLK_VLD', 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 'PERF_PAPC_SU_IDLE', 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_INPUT_NULL_PRIM', 'PERF_PAPC_SU_INPUT_PRIM', + 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', 'PERF_PAPC_SU_OUTPUT_EOPG', + 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', 'PERF_PAPC_SU_OUTPUT_PRIM', + 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE01_STALLED_SC', + 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE0_STALLED_SC', + 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE1_STALLED_SC', + 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE2_STALLED_SC', + 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE3_STALLED_SC', 'PERF_PAPC_SU_STALLED_SC', + 'PERF_PAPC_SU_STARVED_CLIP', 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 'PERF_PA_FETCH_TO_SXIF_FIFO_FULL', 'PERF_PA_PIPE0_SWITCHED_GEN', + 'PERF_PA_PIPE1_SWITCHED_GEN', + 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', 'PERF_PA_VERTEX_FIFO_FULL', + 'PERF_PH_SEND_1_SC', 'PERF_PH_SEND_2_SC', 'PERF_PH_SEND_3_SC', + 'PERF_PH_SEND_4_SC', 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_1X1', 'PERF_SMALL_PRIM_CULL_PRIM_1X2', + 'PERF_SMALL_PRIM_CULL_PRIM_1X3', 'PERF_SMALL_PRIM_CULL_PRIM_1XN', + 'PERF_SMALL_PRIM_CULL_PRIM_2X1', 'PERF_SMALL_PRIM_CULL_PRIM_2X2', + 'PERF_SMALL_PRIM_CULL_PRIM_2X3', 'PERF_SMALL_PRIM_CULL_PRIM_2XN', + 'PERF_SMALL_PRIM_CULL_PRIM_3X1', 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 'PERF_SMALL_PRIM_CULL_PRIM_FULL_RES_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_HALF_RES_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_NX1', 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 'PERF_SMALL_PRIM_CULL_PRIM_QUARTER_RES_EVENT', + 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', 'PERSISTENT_SPACE_END', + 'PERSISTENT_SPACE_START', 'PHYSYMCLK_FORCE_EN', + 'PHYSYMCLK_FORCE_EN_DISABLE', 'PHYSYMCLK_FORCE_EN_ENABLE', + 'PHYSYMCLK_FORCE_SRC_PHYD18CLK', 'PHYSYMCLK_FORCE_SRC_PHYD32CLK', + 'PHYSYMCLK_FORCE_SRC_SEL', 'PHYSYMCLK_FORCE_SRC_SYMCLK', + 'PHY_CUSTOM_RATE', 'PHY_DP_RATE_10P', 'PHY_DP_RATE_13P5', + 'PHY_DP_RATE_1P62', 'PHY_DP_RATE_20P', 'PHY_DP_RATE_2P16', + 'PHY_DP_RATE_2P43', 'PHY_DP_RATE_2P7', 'PHY_DP_RATE_3P24', + 'PHY_DP_RATE_4P32', 'PHY_DP_RATE_5P4', 'PHY_DP_RATE_8P1', + 'PHY_IF_WIDTH_10BIT', 'PHY_IF_WIDTH_20BIT', 'PHY_IF_WIDTH_40BIT', + 'PHY_IF_WIDTH_80BIT', 'PH_PERFCNT_SEL', + 'PH_PERF_SC0_FIFO_STATUS_0', 'PH_PERF_SC0_FIFO_STATUS_1', + 'PH_PERF_SC0_FIFO_STATUS_2', 'PH_PERF_SC0_FIFO_STATUS_3', + 'PH_PERF_SC1_FIFO_STATUS_0', 'PH_PERF_SC1_FIFO_STATUS_1', + 'PH_PERF_SC1_FIFO_STATUS_2', 'PH_PERF_SC1_FIFO_STATUS_3', + 'PH_PERF_SC2_FIFO_STATUS_0', 'PH_PERF_SC2_FIFO_STATUS_1', + 'PH_PERF_SC2_FIFO_STATUS_2', 'PH_PERF_SC2_FIFO_STATUS_3', + 'PH_PERF_SC3_FIFO_STATUS_0', 'PH_PERF_SC3_FIFO_STATUS_1', + 'PH_PERF_SC3_FIFO_STATUS_2', 'PH_PERF_SC3_FIFO_STATUS_3', + 'PH_PERF_SC4_FIFO_STATUS_0', 'PH_PERF_SC4_FIFO_STATUS_1', + 'PH_PERF_SC4_FIFO_STATUS_2', 'PH_PERF_SC4_FIFO_STATUS_3', + 'PH_PERF_SC5_FIFO_STATUS_0', 'PH_PERF_SC5_FIFO_STATUS_1', + 'PH_PERF_SC5_FIFO_STATUS_2', 'PH_PERF_SC5_FIFO_STATUS_3', + 'PH_PERF_SC6_FIFO_STATUS_0', 'PH_PERF_SC6_FIFO_STATUS_1', + 'PH_PERF_SC6_FIFO_STATUS_2', 'PH_PERF_SC6_FIFO_STATUS_3', + 'PH_PERF_SC7_FIFO_STATUS_0', 'PH_PERF_SC7_FIFO_STATUS_1', + 'PH_PERF_SC7_FIFO_STATUS_2', 'PH_PERF_SC7_FIFO_STATUS_3', + 'PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC0_ARB_BUSY', + 'PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC0_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC0_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA0_EOPG_WE', 'PH_PERF_SEL_SC0_PA0_EOP_WE', + 'PH_PERF_SEL_SC0_PA0_EVENT_WE', 'PH_PERF_SEL_SC0_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA0_FIFO_FULL', 'PH_PERF_SEL_SC0_PA0_FPOV_WE', + 'PH_PERF_SEL_SC0_PA0_LPOV_WE', 'PH_PERF_SEL_SC0_PA0_NULL_WE', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA1_EOPG_WE', 'PH_PERF_SEL_SC0_PA1_EOP_WE', + 'PH_PERF_SEL_SC0_PA1_EVENT_WE', 'PH_PERF_SEL_SC0_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA1_FIFO_FULL', 'PH_PERF_SEL_SC0_PA1_FPOV_WE', + 'PH_PERF_SEL_SC0_PA1_LPOV_WE', 'PH_PERF_SEL_SC0_PA1_NULL_WE', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA2_EOPG_WE', 'PH_PERF_SEL_SC0_PA2_EOP_WE', + 'PH_PERF_SEL_SC0_PA2_EVENT_WE', 'PH_PERF_SEL_SC0_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA2_FIFO_FULL', 'PH_PERF_SEL_SC0_PA2_FPOV_WE', + 'PH_PERF_SEL_SC0_PA2_LPOV_WE', 'PH_PERF_SEL_SC0_PA2_NULL_WE', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA3_EOPG_WE', 'PH_PERF_SEL_SC0_PA3_EOP_WE', + 'PH_PERF_SEL_SC0_PA3_EVENT_WE', 'PH_PERF_SEL_SC0_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA3_FIFO_FULL', 'PH_PERF_SEL_SC0_PA3_FPOV_WE', + 'PH_PERF_SEL_SC0_PA3_LPOV_WE', 'PH_PERF_SEL_SC0_PA3_NULL_WE', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA4_EOPG_WE', 'PH_PERF_SEL_SC0_PA4_EOP_WE', + 'PH_PERF_SEL_SC0_PA4_EVENT_WE', 'PH_PERF_SEL_SC0_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA4_FIFO_FULL', 'PH_PERF_SEL_SC0_PA4_FPOV_WE', + 'PH_PERF_SEL_SC0_PA4_LPOV_WE', 'PH_PERF_SEL_SC0_PA4_NULL_WE', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA5_EOPG_WE', 'PH_PERF_SEL_SC0_PA5_EOP_WE', + 'PH_PERF_SEL_SC0_PA5_EVENT_WE', 'PH_PERF_SEL_SC0_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA5_FIFO_FULL', 'PH_PERF_SEL_SC0_PA5_FPOV_WE', + 'PH_PERF_SEL_SC0_PA5_LPOV_WE', 'PH_PERF_SEL_SC0_PA5_NULL_WE', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA6_EOPG_WE', 'PH_PERF_SEL_SC0_PA6_EOP_WE', + 'PH_PERF_SEL_SC0_PA6_EVENT_WE', 'PH_PERF_SEL_SC0_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA6_FIFO_FULL', 'PH_PERF_SEL_SC0_PA6_FPOV_WE', + 'PH_PERF_SEL_SC0_PA6_LPOV_WE', 'PH_PERF_SEL_SC0_PA6_NULL_WE', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC0_PA7_EOPG_WE', 'PH_PERF_SEL_SC0_PA7_EOP_WE', + 'PH_PERF_SEL_SC0_PA7_EVENT_WE', 'PH_PERF_SEL_SC0_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC0_PA7_FIFO_FULL', 'PH_PERF_SEL_SC0_PA7_FPOV_WE', + 'PH_PERF_SEL_SC0_PA7_LPOV_WE', 'PH_PERF_SEL_SC0_PA7_NULL_WE', + 'PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC0_SEND', 'PH_PERF_SEL_SC0_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC1_ARB_BUSY', + 'PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC1_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC1_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA0_EOPG_WE', 'PH_PERF_SEL_SC1_PA0_EOP_WE', + 'PH_PERF_SEL_SC1_PA0_EVENT_WE', 'PH_PERF_SEL_SC1_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA0_FIFO_FULL', 'PH_PERF_SEL_SC1_PA0_FPOV_WE', + 'PH_PERF_SEL_SC1_PA0_LPOV_WE', 'PH_PERF_SEL_SC1_PA0_NULL_WE', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA1_EOPG_WE', 'PH_PERF_SEL_SC1_PA1_EOP_WE', + 'PH_PERF_SEL_SC1_PA1_EVENT_WE', 'PH_PERF_SEL_SC1_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA1_FIFO_FULL', 'PH_PERF_SEL_SC1_PA1_FPOV_WE', + 'PH_PERF_SEL_SC1_PA1_LPOV_WE', 'PH_PERF_SEL_SC1_PA1_NULL_WE', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA2_EOPG_WE', 'PH_PERF_SEL_SC1_PA2_EOP_WE', + 'PH_PERF_SEL_SC1_PA2_EVENT_WE', 'PH_PERF_SEL_SC1_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA2_FIFO_FULL', 'PH_PERF_SEL_SC1_PA2_FPOV_WE', + 'PH_PERF_SEL_SC1_PA2_LPOV_WE', 'PH_PERF_SEL_SC1_PA2_NULL_WE', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA3_EOPG_WE', 'PH_PERF_SEL_SC1_PA3_EOP_WE', + 'PH_PERF_SEL_SC1_PA3_EVENT_WE', 'PH_PERF_SEL_SC1_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA3_FIFO_FULL', 'PH_PERF_SEL_SC1_PA3_FPOV_WE', + 'PH_PERF_SEL_SC1_PA3_LPOV_WE', 'PH_PERF_SEL_SC1_PA3_NULL_WE', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA4_EOPG_WE', 'PH_PERF_SEL_SC1_PA4_EOP_WE', + 'PH_PERF_SEL_SC1_PA4_EVENT_WE', 'PH_PERF_SEL_SC1_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA4_FIFO_FULL', 'PH_PERF_SEL_SC1_PA4_FPOV_WE', + 'PH_PERF_SEL_SC1_PA4_LPOV_WE', 'PH_PERF_SEL_SC1_PA4_NULL_WE', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA5_EOPG_WE', 'PH_PERF_SEL_SC1_PA5_EOP_WE', + 'PH_PERF_SEL_SC1_PA5_EVENT_WE', 'PH_PERF_SEL_SC1_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA5_FIFO_FULL', 'PH_PERF_SEL_SC1_PA5_FPOV_WE', + 'PH_PERF_SEL_SC1_PA5_LPOV_WE', 'PH_PERF_SEL_SC1_PA5_NULL_WE', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA6_EOPG_WE', 'PH_PERF_SEL_SC1_PA6_EOP_WE', + 'PH_PERF_SEL_SC1_PA6_EVENT_WE', 'PH_PERF_SEL_SC1_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA6_FIFO_FULL', 'PH_PERF_SEL_SC1_PA6_FPOV_WE', + 'PH_PERF_SEL_SC1_PA6_LPOV_WE', 'PH_PERF_SEL_SC1_PA6_NULL_WE', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC1_PA7_EOPG_WE', 'PH_PERF_SEL_SC1_PA7_EOP_WE', + 'PH_PERF_SEL_SC1_PA7_EVENT_WE', 'PH_PERF_SEL_SC1_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC1_PA7_FIFO_FULL', 'PH_PERF_SEL_SC1_PA7_FPOV_WE', + 'PH_PERF_SEL_SC1_PA7_LPOV_WE', 'PH_PERF_SEL_SC1_PA7_NULL_WE', + 'PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC1_SEND', 'PH_PERF_SEL_SC1_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC2_ARB_BUSY', + 'PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC2_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC2_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA0_EOPG_WE', 'PH_PERF_SEL_SC2_PA0_EOP_WE', + 'PH_PERF_SEL_SC2_PA0_EVENT_WE', 'PH_PERF_SEL_SC2_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA0_FIFO_FULL', 'PH_PERF_SEL_SC2_PA0_FPOV_WE', + 'PH_PERF_SEL_SC2_PA0_LPOV_WE', 'PH_PERF_SEL_SC2_PA0_NULL_WE', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA1_EOPG_WE', 'PH_PERF_SEL_SC2_PA1_EOP_WE', + 'PH_PERF_SEL_SC2_PA1_EVENT_WE', 'PH_PERF_SEL_SC2_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA1_FIFO_FULL', 'PH_PERF_SEL_SC2_PA1_FPOV_WE', + 'PH_PERF_SEL_SC2_PA1_LPOV_WE', 'PH_PERF_SEL_SC2_PA1_NULL_WE', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA2_EOPG_WE', 'PH_PERF_SEL_SC2_PA2_EOP_WE', + 'PH_PERF_SEL_SC2_PA2_EVENT_WE', 'PH_PERF_SEL_SC2_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA2_FIFO_FULL', 'PH_PERF_SEL_SC2_PA2_FPOV_WE', + 'PH_PERF_SEL_SC2_PA2_LPOV_WE', 'PH_PERF_SEL_SC2_PA2_NULL_WE', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA3_EOPG_WE', 'PH_PERF_SEL_SC2_PA3_EOP_WE', + 'PH_PERF_SEL_SC2_PA3_EVENT_WE', 'PH_PERF_SEL_SC2_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA3_FIFO_FULL', 'PH_PERF_SEL_SC2_PA3_FPOV_WE', + 'PH_PERF_SEL_SC2_PA3_LPOV_WE', 'PH_PERF_SEL_SC2_PA3_NULL_WE', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA4_EOPG_WE', 'PH_PERF_SEL_SC2_PA4_EOP_WE', + 'PH_PERF_SEL_SC2_PA4_EVENT_WE', 'PH_PERF_SEL_SC2_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA4_FIFO_FULL', 'PH_PERF_SEL_SC2_PA4_FPOV_WE', + 'PH_PERF_SEL_SC2_PA4_LPOV_WE', 'PH_PERF_SEL_SC2_PA4_NULL_WE', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA5_EOPG_WE', 'PH_PERF_SEL_SC2_PA5_EOP_WE', + 'PH_PERF_SEL_SC2_PA5_EVENT_WE', 'PH_PERF_SEL_SC2_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA5_FIFO_FULL', 'PH_PERF_SEL_SC2_PA5_FPOV_WE', + 'PH_PERF_SEL_SC2_PA5_LPOV_WE', 'PH_PERF_SEL_SC2_PA5_NULL_WE', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA6_EOPG_WE', 'PH_PERF_SEL_SC2_PA6_EOP_WE', + 'PH_PERF_SEL_SC2_PA6_EVENT_WE', 'PH_PERF_SEL_SC2_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA6_FIFO_FULL', 'PH_PERF_SEL_SC2_PA6_FPOV_WE', + 'PH_PERF_SEL_SC2_PA6_LPOV_WE', 'PH_PERF_SEL_SC2_PA6_NULL_WE', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC2_PA7_EOPG_WE', 'PH_PERF_SEL_SC2_PA7_EOP_WE', + 'PH_PERF_SEL_SC2_PA7_EVENT_WE', 'PH_PERF_SEL_SC2_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC2_PA7_FIFO_FULL', 'PH_PERF_SEL_SC2_PA7_FPOV_WE', + 'PH_PERF_SEL_SC2_PA7_LPOV_WE', 'PH_PERF_SEL_SC2_PA7_NULL_WE', + 'PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC2_SEND', 'PH_PERF_SEL_SC2_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC3_ARB_BUSY', + 'PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC3_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC3_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA0_EOPG_WE', 'PH_PERF_SEL_SC3_PA0_EOP_WE', + 'PH_PERF_SEL_SC3_PA0_EVENT_WE', 'PH_PERF_SEL_SC3_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA0_FIFO_FULL', 'PH_PERF_SEL_SC3_PA0_FPOV_WE', + 'PH_PERF_SEL_SC3_PA0_LPOV_WE', 'PH_PERF_SEL_SC3_PA0_NULL_WE', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA1_EOPG_WE', 'PH_PERF_SEL_SC3_PA1_EOP_WE', + 'PH_PERF_SEL_SC3_PA1_EVENT_WE', 'PH_PERF_SEL_SC3_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA1_FIFO_FULL', 'PH_PERF_SEL_SC3_PA1_FPOV_WE', + 'PH_PERF_SEL_SC3_PA1_LPOV_WE', 'PH_PERF_SEL_SC3_PA1_NULL_WE', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA2_EOPG_WE', 'PH_PERF_SEL_SC3_PA2_EOP_WE', + 'PH_PERF_SEL_SC3_PA2_EVENT_WE', 'PH_PERF_SEL_SC3_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA2_FIFO_FULL', 'PH_PERF_SEL_SC3_PA2_FPOV_WE', + 'PH_PERF_SEL_SC3_PA2_LPOV_WE', 'PH_PERF_SEL_SC3_PA2_NULL_WE', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA3_EOPG_WE', 'PH_PERF_SEL_SC3_PA3_EOP_WE', + 'PH_PERF_SEL_SC3_PA3_EVENT_WE', 'PH_PERF_SEL_SC3_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA3_FIFO_FULL', 'PH_PERF_SEL_SC3_PA3_FPOV_WE', + 'PH_PERF_SEL_SC3_PA3_LPOV_WE', 'PH_PERF_SEL_SC3_PA3_NULL_WE', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA4_EOPG_WE', 'PH_PERF_SEL_SC3_PA4_EOP_WE', + 'PH_PERF_SEL_SC3_PA4_EVENT_WE', 'PH_PERF_SEL_SC3_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA4_FIFO_FULL', 'PH_PERF_SEL_SC3_PA4_FPOV_WE', + 'PH_PERF_SEL_SC3_PA4_LPOV_WE', 'PH_PERF_SEL_SC3_PA4_NULL_WE', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA5_EOPG_WE', 'PH_PERF_SEL_SC3_PA5_EOP_WE', + 'PH_PERF_SEL_SC3_PA5_EVENT_WE', 'PH_PERF_SEL_SC3_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA5_FIFO_FULL', 'PH_PERF_SEL_SC3_PA5_FPOV_WE', + 'PH_PERF_SEL_SC3_PA5_LPOV_WE', 'PH_PERF_SEL_SC3_PA5_NULL_WE', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA6_EOPG_WE', 'PH_PERF_SEL_SC3_PA6_EOP_WE', + 'PH_PERF_SEL_SC3_PA6_EVENT_WE', 'PH_PERF_SEL_SC3_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA6_FIFO_FULL', 'PH_PERF_SEL_SC3_PA6_FPOV_WE', + 'PH_PERF_SEL_SC3_PA6_LPOV_WE', 'PH_PERF_SEL_SC3_PA6_NULL_WE', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC3_PA7_EOPG_WE', 'PH_PERF_SEL_SC3_PA7_EOP_WE', + 'PH_PERF_SEL_SC3_PA7_EVENT_WE', 'PH_PERF_SEL_SC3_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC3_PA7_FIFO_FULL', 'PH_PERF_SEL_SC3_PA7_FPOV_WE', + 'PH_PERF_SEL_SC3_PA7_LPOV_WE', 'PH_PERF_SEL_SC3_PA7_NULL_WE', + 'PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC3_SEND', 'PH_PERF_SEL_SC3_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC4_ARB_BUSY', + 'PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC4_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC4_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA0_EOPG_WE', 'PH_PERF_SEL_SC4_PA0_EOP_WE', + 'PH_PERF_SEL_SC4_PA0_EVENT_WE', 'PH_PERF_SEL_SC4_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA0_FIFO_FULL', 'PH_PERF_SEL_SC4_PA0_FPOV_WE', + 'PH_PERF_SEL_SC4_PA0_LPOV_WE', 'PH_PERF_SEL_SC4_PA0_NULL_WE', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA1_EOPG_WE', 'PH_PERF_SEL_SC4_PA1_EOP_WE', + 'PH_PERF_SEL_SC4_PA1_EVENT_WE', 'PH_PERF_SEL_SC4_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA1_FIFO_FULL', 'PH_PERF_SEL_SC4_PA1_FPOV_WE', + 'PH_PERF_SEL_SC4_PA1_LPOV_WE', 'PH_PERF_SEL_SC4_PA1_NULL_WE', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA2_EOPG_WE', 'PH_PERF_SEL_SC4_PA2_EOP_WE', + 'PH_PERF_SEL_SC4_PA2_EVENT_WE', 'PH_PERF_SEL_SC4_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA2_FIFO_FULL', 'PH_PERF_SEL_SC4_PA2_FPOV_WE', + 'PH_PERF_SEL_SC4_PA2_LPOV_WE', 'PH_PERF_SEL_SC4_PA2_NULL_WE', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA3_EOPG_WE', 'PH_PERF_SEL_SC4_PA3_EOP_WE', + 'PH_PERF_SEL_SC4_PA3_EVENT_WE', 'PH_PERF_SEL_SC4_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA3_FIFO_FULL', 'PH_PERF_SEL_SC4_PA3_FPOV_WE', + 'PH_PERF_SEL_SC4_PA3_LPOV_WE', 'PH_PERF_SEL_SC4_PA3_NULL_WE', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA4_EOPG_WE', 'PH_PERF_SEL_SC4_PA4_EOP_WE', + 'PH_PERF_SEL_SC4_PA4_EVENT_WE', 'PH_PERF_SEL_SC4_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA4_FIFO_FULL', 'PH_PERF_SEL_SC4_PA4_FPOV_WE', + 'PH_PERF_SEL_SC4_PA4_LPOV_WE', 'PH_PERF_SEL_SC4_PA4_NULL_WE', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA5_EOPG_WE', 'PH_PERF_SEL_SC4_PA5_EOP_WE', + 'PH_PERF_SEL_SC4_PA5_EVENT_WE', 'PH_PERF_SEL_SC4_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA5_FIFO_FULL', 'PH_PERF_SEL_SC4_PA5_FPOV_WE', + 'PH_PERF_SEL_SC4_PA5_LPOV_WE', 'PH_PERF_SEL_SC4_PA5_NULL_WE', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA6_EOPG_WE', 'PH_PERF_SEL_SC4_PA6_EOP_WE', + 'PH_PERF_SEL_SC4_PA6_EVENT_WE', 'PH_PERF_SEL_SC4_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA6_FIFO_FULL', 'PH_PERF_SEL_SC4_PA6_FPOV_WE', + 'PH_PERF_SEL_SC4_PA6_LPOV_WE', 'PH_PERF_SEL_SC4_PA6_NULL_WE', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC4_PA7_EOPG_WE', 'PH_PERF_SEL_SC4_PA7_EOP_WE', + 'PH_PERF_SEL_SC4_PA7_EVENT_WE', 'PH_PERF_SEL_SC4_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC4_PA7_FIFO_FULL', 'PH_PERF_SEL_SC4_PA7_FPOV_WE', + 'PH_PERF_SEL_SC4_PA7_LPOV_WE', 'PH_PERF_SEL_SC4_PA7_NULL_WE', + 'PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC4_SEND', 'PH_PERF_SEL_SC4_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC5_ARB_BUSY', + 'PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC5_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC5_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA0_EOPG_WE', 'PH_PERF_SEL_SC5_PA0_EOP_WE', + 'PH_PERF_SEL_SC5_PA0_EVENT_WE', 'PH_PERF_SEL_SC5_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA0_FIFO_FULL', 'PH_PERF_SEL_SC5_PA0_FPOV_WE', + 'PH_PERF_SEL_SC5_PA0_LPOV_WE', 'PH_PERF_SEL_SC5_PA0_NULL_WE', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA1_EOPG_WE', 'PH_PERF_SEL_SC5_PA1_EOP_WE', + 'PH_PERF_SEL_SC5_PA1_EVENT_WE', 'PH_PERF_SEL_SC5_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA1_FIFO_FULL', 'PH_PERF_SEL_SC5_PA1_FPOV_WE', + 'PH_PERF_SEL_SC5_PA1_LPOV_WE', 'PH_PERF_SEL_SC5_PA1_NULL_WE', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA2_EOPG_WE', 'PH_PERF_SEL_SC5_PA2_EOP_WE', + 'PH_PERF_SEL_SC5_PA2_EVENT_WE', 'PH_PERF_SEL_SC5_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA2_FIFO_FULL', 'PH_PERF_SEL_SC5_PA2_FPOV_WE', + 'PH_PERF_SEL_SC5_PA2_LPOV_WE', 'PH_PERF_SEL_SC5_PA2_NULL_WE', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA3_EOPG_WE', 'PH_PERF_SEL_SC5_PA3_EOP_WE', + 'PH_PERF_SEL_SC5_PA3_EVENT_WE', 'PH_PERF_SEL_SC5_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA3_FIFO_FULL', 'PH_PERF_SEL_SC5_PA3_FPOV_WE', + 'PH_PERF_SEL_SC5_PA3_LPOV_WE', 'PH_PERF_SEL_SC5_PA3_NULL_WE', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA4_EOPG_WE', 'PH_PERF_SEL_SC5_PA4_EOP_WE', + 'PH_PERF_SEL_SC5_PA4_EVENT_WE', 'PH_PERF_SEL_SC5_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA4_FIFO_FULL', 'PH_PERF_SEL_SC5_PA4_FPOV_WE', + 'PH_PERF_SEL_SC5_PA4_LPOV_WE', 'PH_PERF_SEL_SC5_PA4_NULL_WE', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA5_EOPG_WE', 'PH_PERF_SEL_SC5_PA5_EOP_WE', + 'PH_PERF_SEL_SC5_PA5_EVENT_WE', 'PH_PERF_SEL_SC5_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA5_FIFO_FULL', 'PH_PERF_SEL_SC5_PA5_FPOV_WE', + 'PH_PERF_SEL_SC5_PA5_LPOV_WE', 'PH_PERF_SEL_SC5_PA5_NULL_WE', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA6_EOPG_WE', 'PH_PERF_SEL_SC5_PA6_EOP_WE', + 'PH_PERF_SEL_SC5_PA6_EVENT_WE', 'PH_PERF_SEL_SC5_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA6_FIFO_FULL', 'PH_PERF_SEL_SC5_PA6_FPOV_WE', + 'PH_PERF_SEL_SC5_PA6_LPOV_WE', 'PH_PERF_SEL_SC5_PA6_NULL_WE', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC5_PA7_EOPG_WE', 'PH_PERF_SEL_SC5_PA7_EOP_WE', + 'PH_PERF_SEL_SC5_PA7_EVENT_WE', 'PH_PERF_SEL_SC5_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC5_PA7_FIFO_FULL', 'PH_PERF_SEL_SC5_PA7_FPOV_WE', + 'PH_PERF_SEL_SC5_PA7_LPOV_WE', 'PH_PERF_SEL_SC5_PA7_NULL_WE', + 'PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC5_SEND', 'PH_PERF_SEL_SC5_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC6_ARB_BUSY', + 'PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC6_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC6_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA0_EOPG_WE', 'PH_PERF_SEL_SC6_PA0_EOP_WE', + 'PH_PERF_SEL_SC6_PA0_EVENT_WE', 'PH_PERF_SEL_SC6_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA0_FIFO_FULL', 'PH_PERF_SEL_SC6_PA0_FPOV_WE', + 'PH_PERF_SEL_SC6_PA0_LPOV_WE', 'PH_PERF_SEL_SC6_PA0_NULL_WE', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA1_EOPG_WE', 'PH_PERF_SEL_SC6_PA1_EOP_WE', + 'PH_PERF_SEL_SC6_PA1_EVENT_WE', 'PH_PERF_SEL_SC6_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA1_FIFO_FULL', 'PH_PERF_SEL_SC6_PA1_FPOV_WE', + 'PH_PERF_SEL_SC6_PA1_LPOV_WE', 'PH_PERF_SEL_SC6_PA1_NULL_WE', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA2_EOPG_WE', 'PH_PERF_SEL_SC6_PA2_EOP_WE', + 'PH_PERF_SEL_SC6_PA2_EVENT_WE', 'PH_PERF_SEL_SC6_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA2_FIFO_FULL', 'PH_PERF_SEL_SC6_PA2_FPOV_WE', + 'PH_PERF_SEL_SC6_PA2_LPOV_WE', 'PH_PERF_SEL_SC6_PA2_NULL_WE', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA3_EOPG_WE', 'PH_PERF_SEL_SC6_PA3_EOP_WE', + 'PH_PERF_SEL_SC6_PA3_EVENT_WE', 'PH_PERF_SEL_SC6_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA3_FIFO_FULL', 'PH_PERF_SEL_SC6_PA3_FPOV_WE', + 'PH_PERF_SEL_SC6_PA3_LPOV_WE', 'PH_PERF_SEL_SC6_PA3_NULL_WE', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA4_EOPG_WE', 'PH_PERF_SEL_SC6_PA4_EOP_WE', + 'PH_PERF_SEL_SC6_PA4_EVENT_WE', 'PH_PERF_SEL_SC6_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA4_FIFO_FULL', 'PH_PERF_SEL_SC6_PA4_FPOV_WE', + 'PH_PERF_SEL_SC6_PA4_LPOV_WE', 'PH_PERF_SEL_SC6_PA4_NULL_WE', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA5_EOPG_WE', 'PH_PERF_SEL_SC6_PA5_EOP_WE', + 'PH_PERF_SEL_SC6_PA5_EVENT_WE', 'PH_PERF_SEL_SC6_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA5_FIFO_FULL', 'PH_PERF_SEL_SC6_PA5_FPOV_WE', + 'PH_PERF_SEL_SC6_PA5_LPOV_WE', 'PH_PERF_SEL_SC6_PA5_NULL_WE', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA6_EOPG_WE', 'PH_PERF_SEL_SC6_PA6_EOP_WE', + 'PH_PERF_SEL_SC6_PA6_EVENT_WE', 'PH_PERF_SEL_SC6_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA6_FIFO_FULL', 'PH_PERF_SEL_SC6_PA6_FPOV_WE', + 'PH_PERF_SEL_SC6_PA6_LPOV_WE', 'PH_PERF_SEL_SC6_PA6_NULL_WE', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC6_PA7_EOPG_WE', 'PH_PERF_SEL_SC6_PA7_EOP_WE', + 'PH_PERF_SEL_SC6_PA7_EVENT_WE', 'PH_PERF_SEL_SC6_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC6_PA7_FIFO_FULL', 'PH_PERF_SEL_SC6_PA7_FPOV_WE', + 'PH_PERF_SEL_SC6_PA7_LPOV_WE', 'PH_PERF_SEL_SC6_PA7_NULL_WE', + 'PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC6_SEND', 'PH_PERF_SEL_SC6_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC7_ARB_BUSY', + 'PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC7_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC7_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA0_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA0_EOPG_WE', 'PH_PERF_SEL_SC7_PA0_EOP_WE', + 'PH_PERF_SEL_SC7_PA0_EVENT_WE', 'PH_PERF_SEL_SC7_PA0_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA0_FIFO_FULL', 'PH_PERF_SEL_SC7_PA0_FPOV_WE', + 'PH_PERF_SEL_SC7_PA0_LPOV_WE', 'PH_PERF_SEL_SC7_PA0_NULL_WE', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA1_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA1_EOPG_WE', 'PH_PERF_SEL_SC7_PA1_EOP_WE', + 'PH_PERF_SEL_SC7_PA1_EVENT_WE', 'PH_PERF_SEL_SC7_PA1_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA1_FIFO_FULL', 'PH_PERF_SEL_SC7_PA1_FPOV_WE', + 'PH_PERF_SEL_SC7_PA1_LPOV_WE', 'PH_PERF_SEL_SC7_PA1_NULL_WE', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA2_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA2_EOPG_WE', 'PH_PERF_SEL_SC7_PA2_EOP_WE', + 'PH_PERF_SEL_SC7_PA2_EVENT_WE', 'PH_PERF_SEL_SC7_PA2_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA2_FIFO_FULL', 'PH_PERF_SEL_SC7_PA2_FPOV_WE', + 'PH_PERF_SEL_SC7_PA2_LPOV_WE', 'PH_PERF_SEL_SC7_PA2_NULL_WE', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA3_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA3_EOPG_WE', 'PH_PERF_SEL_SC7_PA3_EOP_WE', + 'PH_PERF_SEL_SC7_PA3_EVENT_WE', 'PH_PERF_SEL_SC7_PA3_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA3_FIFO_FULL', 'PH_PERF_SEL_SC7_PA3_FPOV_WE', + 'PH_PERF_SEL_SC7_PA3_LPOV_WE', 'PH_PERF_SEL_SC7_PA3_NULL_WE', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA4_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA4_EOPG_WE', 'PH_PERF_SEL_SC7_PA4_EOP_WE', + 'PH_PERF_SEL_SC7_PA4_EVENT_WE', 'PH_PERF_SEL_SC7_PA4_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA4_FIFO_FULL', 'PH_PERF_SEL_SC7_PA4_FPOV_WE', + 'PH_PERF_SEL_SC7_PA4_LPOV_WE', 'PH_PERF_SEL_SC7_PA4_NULL_WE', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA5_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA5_EOPG_WE', 'PH_PERF_SEL_SC7_PA5_EOP_WE', + 'PH_PERF_SEL_SC7_PA5_EVENT_WE', 'PH_PERF_SEL_SC7_PA5_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA5_FIFO_FULL', 'PH_PERF_SEL_SC7_PA5_FPOV_WE', + 'PH_PERF_SEL_SC7_PA5_LPOV_WE', 'PH_PERF_SEL_SC7_PA5_NULL_WE', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA6_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA6_EOPG_WE', 'PH_PERF_SEL_SC7_PA6_EOP_WE', + 'PH_PERF_SEL_SC7_PA6_EVENT_WE', 'PH_PERF_SEL_SC7_PA6_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA6_FIFO_FULL', 'PH_PERF_SEL_SC7_PA6_FPOV_WE', + 'PH_PERF_SEL_SC7_PA6_LPOV_WE', 'PH_PERF_SEL_SC7_PA6_NULL_WE', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA7_DEALLOC_4_0_RD', + 'PH_PERF_SEL_SC7_PA7_EOPG_WE', 'PH_PERF_SEL_SC7_PA7_EOP_WE', + 'PH_PERF_SEL_SC7_PA7_EVENT_WE', 'PH_PERF_SEL_SC7_PA7_FIFO_EMPTY', + 'PH_PERF_SEL_SC7_PA7_FIFO_FULL', 'PH_PERF_SEL_SC7_PA7_FPOV_WE', + 'PH_PERF_SEL_SC7_PA7_LPOV_WE', 'PH_PERF_SEL_SC7_PA7_NULL_WE', + 'PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC7_SEND', 'PH_PERF_SEL_SC7_SRPS_WINDOW_VALID', + 'PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT', + 'PH_SPI_MODE_DISABLED', 'PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT', + 'PIPELINESTAT_START', 'PIPELINESTAT_STOP', 'PIPE_ALIGNED', + 'PIPE_ALIGNED_SURF', 'PIPE_COMPAT_LEVEL', 'PIPE_ID0', 'PIPE_ID1', + 'PIPE_ID2', 'PIPE_ID3', 'PIPE_INT_MASK_MODE', + 'PIPE_INT_MASK_MODE_DISABLE', 'PIPE_INT_MASK_MODE_ENABLE', + 'PIPE_INT_TYPE_MODE', 'PIPE_INT_TYPE_MODE_DISABLE', + 'PIPE_INT_TYPE_MODE_ENABLE', 'PIPE_IN_FLUSH_URGENT', + 'PIPE_IN_FLUSH_URGENT_DISABLE', 'PIPE_IN_FLUSH_URGENT_ENABLE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 'PIPE_PIXEL_RATE_PLL_SOURCE', + 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', + 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', 'PIPE_PIXEL_RATE_SOURCE', + 'PIPE_PIXEL_RATE_SOURCE_P0PLL', 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 'PIPE_PIXEL_RATE_SOURCE_P2PLL', 'PIPE_UNALIGNED_SURF', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE', 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 'PIXEL_PIPE_OCCLUSION_COUNT_1', 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 'PIXEL_PIPE_OCCLUSION_COUNT_3', 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', 'PIXEL_PIPE_STAT_CONTROL', + 'PIXEL_PIPE_STAT_DUMP', 'PIXEL_PIPE_STAT_RESET', + 'PIXEL_PIPE_STRIDE_128_BITS', 'PIXEL_PIPE_STRIDE_256_BITS', + 'PIXEL_PIPE_STRIDE_32_BITS', 'PIXEL_PIPE_STRIDE_64_BITS', + 'PIX_DYNAMIC_EXPANSION', 'PIX_EXPAND_MODE', 'PIX_ZERO_EXPANSION', + 'PLL_CFG_IF_SOFT_RESET', 'PLL_CFG_IF_SOFT_RESET_FORCE', + 'PLL_CFG_IF_SOFT_RESET_NOOP', 'PM_ASSERT_RESET', + 'PM_ASSERT_RESET_0', 'PM_ASSERT_RESET_1', 'POINTLIST', + 'POWER_STATE_ENUM', 'POWER_STATE_ENUM_DS', 'POWER_STATE_ENUM_LS', + 'POWER_STATE_ENUM_ON', 'POWER_STATE_ENUM_SD', 'PRE_CSC_BYPASS', + 'PRE_CSC_MODE_ENUM', 'PRE_CSC_SET_A', 'PRE_CSC_SET_B', + 'PRE_DEGAM_BT2020', 'PRE_DEGAM_BT2100HLG', 'PRE_DEGAM_BT2100PQ', + 'PRE_DEGAM_BYPASS', 'PRE_DEGAM_ENABLE', 'PRE_DEGAM_GAMMA_22', + 'PRE_DEGAM_GAMMA_24', 'PRE_DEGAM_GAMMA_26', 'PRE_DEGAM_MODE', + 'PRE_DEGAM_SELECT', 'PRE_DEGAM_SRGB', 'PROG_SEQ', 'PROTVIOL', + 'PRQ_MRQ_FLUSH_URGENT', 'PRQ_MRQ_FLUSH_URGENT_DISABLE', + 'PRQ_MRQ_FLUSH_URGENT_ENABLE', 'PS', 'PSLC_ASAP', 'PSLC_AUTO', + 'PSLC_COUNTDOWN', 'PSLC_ON_HANG_ONLY', 'PS_DONE', + 'PS_PARTIAL_FLUSH', 'PTE_BUFFER_MODE', 'PTE_BUFFER_MODE_0', + 'PTE_BUFFER_MODE_1', 'PTE_ROW_HEIGHT_LINEAR', + 'PTE_ROW_HEIGHT_LINEAR_1024L', 'PTE_ROW_HEIGHT_LINEAR_128L', + 'PTE_ROW_HEIGHT_LINEAR_16L', 'PTE_ROW_HEIGHT_LINEAR_256L', + 'PTE_ROW_HEIGHT_LINEAR_32L', 'PTE_ROW_HEIGHT_LINEAR_512L', + 'PTE_ROW_HEIGHT_LINEAR_64L', 'PTE_ROW_HEIGHT_LINEAR_8L', + 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN', + 'PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT', + 'PWRSEQ_BL_PWM_CNTL_BL_PWM_EN', + 'PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN', + 'PWRSEQ_BL_PWM_DISABLE', 'PWRSEQ_BL_PWM_ENABLE', + 'PWRSEQ_BL_PWM_FRACTIONAL_DISABLE', + 'PWRSEQ_BL_PWM_FRACTIONAL_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL', + 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 'PWRSEQ_GPIO_MASK_EN', 'PWRSEQ_GPIO_MASK_EN_HARDWARE', + 'PWRSEQ_GPIO_MASK_EN_SOFTWARE', 'PWRSEQ_PANEL_BLON_OFF', + 'PWRSEQ_PANEL_BLON_ON', 'PWRSEQ_PANEL_BLON_POL_INVERT', + 'PWRSEQ_PANEL_BLON_POL_NON_INVERT', 'PWRSEQ_PANEL_DIGON_OFF', + 'PWRSEQ_PANEL_DIGON_ON', 'PWRSEQ_PANEL_DIGON_POL_INVERT', + 'PWRSEQ_PANEL_DIGON_POL_NON_INVERT', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE', + 'PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN', + 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF', + 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON', + 'PWRSEQ_PANEL_SYNCEN_POL_INVERT', + 'PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT', + 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON', + 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE', 'PerfCounter_Vals', + 'PhSPIstatusMode', 'PixelPipeCounterId', 'PixelPipeStride', + 'PkrMap', 'PkrXsel', 'PkrXsel2', 'PkrYsel', 'RAMA', 'RAMA_ACCESS', + 'RAMB', 'RAMB_ACCESS', 'RAM_LUT', 'RANGE_00', 'RANGE_FF', + 'RASTER_CONFIG_PKR_MAP_0', 'RASTER_CONFIG_PKR_MAP_1', + 'RASTER_CONFIG_PKR_MAP_2', 'RASTER_CONFIG_PKR_MAP_3', + 'RASTER_CONFIG_PKR_XSEL2_0', 'RASTER_CONFIG_PKR_XSEL2_1', + 'RASTER_CONFIG_PKR_XSEL2_2', 'RASTER_CONFIG_PKR_XSEL2_3', + 'RASTER_CONFIG_PKR_XSEL_0', 'RASTER_CONFIG_PKR_XSEL_1', + 'RASTER_CONFIG_PKR_XSEL_2', 'RASTER_CONFIG_PKR_XSEL_3', + 'RASTER_CONFIG_PKR_YSEL_0', 'RASTER_CONFIG_PKR_YSEL_1', + 'RASTER_CONFIG_PKR_YSEL_2', 'RASTER_CONFIG_PKR_YSEL_3', + 'RASTER_CONFIG_RB_MAP_0', 'RASTER_CONFIG_RB_MAP_1', + 'RASTER_CONFIG_RB_MAP_2', 'RASTER_CONFIG_RB_MAP_3', + 'RASTER_CONFIG_RB_XSEL2_0', 'RASTER_CONFIG_RB_XSEL2_1', + 'RASTER_CONFIG_RB_XSEL2_2', 'RASTER_CONFIG_RB_XSEL2_3', + 'RASTER_CONFIG_RB_XSEL_0', 'RASTER_CONFIG_RB_XSEL_1', + 'RASTER_CONFIG_RB_YSEL_0', 'RASTER_CONFIG_RB_YSEL_1', + 'RASTER_CONFIG_SC_MAP_0', 'RASTER_CONFIG_SC_MAP_1', + 'RASTER_CONFIG_SC_MAP_2', 'RASTER_CONFIG_SC_MAP_3', + 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', 'RASTER_CONFIG_SE_MAP_0', + 'RASTER_CONFIG_SE_MAP_1', 'RASTER_CONFIG_SE_MAP_2', + 'RASTER_CONFIG_SE_MAP_3', 'RASTER_CONFIG_SE_PAIR_MAP_0', + 'RASTER_CONFIG_SE_PAIR_MAP_1', 'RASTER_CONFIG_SE_PAIR_MAP_2', + 'RASTER_CONFIG_SE_PAIR_MAP_3', + 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', 'RAW', + 'RDPCSPIPE_APBCLK_DISABLE', 'RDPCSPIPE_APBCLK_ENABLE', + 'RDPCSPIPE_APB_PSLVERR_MASK_DISABLE', + 'RDPCSPIPE_APB_PSLVERR_MASK_ENABLE', + 'RDPCSPIPE_CLOCK_CNTL_LANE_CLK_EN', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_APBCLK_EN', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_CLOCK_ON', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_EN', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_CLK_GATE_DIS', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_PIPE_PHYD32CLK_CLOCK_ON', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_EN', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS', + 'RDPCSPIPE_CLOCK_CNTL_RDPCS_SRAMCLK_PASS', + 'RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_EN', + 'RDPCSPIPE_CNTL_RDPCS_PIPE_FIFO_LANE_EN', + 'RDPCSPIPE_CNTL_RDPCS_PIPE_SOFT_RESET', + 'RDPCSPIPE_CNTL_RDPCS_SRAM_SOFT_RESET', + 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK', + 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_DISABLE', + 'RDPCSPIPE_DBG_APB_COUNT_EXPIRE_MASK_ENABLE', + 'RDPCSPIPE_DBG_OCLA_SEL', 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_15_8', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_23_16', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_31_24', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_39_32', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_47_40', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_55_48', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_63_56', + 'RDPCSPIPE_DBG_OCLA_SEL_MON_OUT_7_0', + 'RDPCSPIPE_DPALT_4LANE_TOGGLE_2LANE', + 'RDPCSPIPE_DPALT_4LANE_TOGGLE_4LANE', + 'RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 'RDPCSPIPE_DPALT_4LANE_TOGGLE_MASK_ENABLE', + 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_DISABLE', + 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_ENABLE', + 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 'RDPCSPIPE_DPALT_DISABLE_TOGGLE_MASK_ENABLE', + 'RDPCSPIPE_ENC_TYPE', 'RDPCSPIPE_EXT_PCLK_EN_DISABLE', + 'RDPCSPIPE_EXT_PCLK_EN_ENABLE', 'RDPCSPIPE_FIFO_EMPTY', + 'RDPCSPIPE_FIFO_FULL', 'RDPCSPIPE_FIFO_IS_EMPTY', + 'RDPCSPIPE_FIFO_IS_FULL', 'RDPCSPIPE_FIFO_NOT_EMPTY', + 'RDPCSPIPE_FIFO_NOT_FULL', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_APB_PSLVERR_MASK', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_PIPE_FIFO_ERROR_MASK', + 'RDPCSPIPE_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK', + 'RDPCSPIPE_LANE_BIT_ORDER_REVERSE_DISABLE', + 'RDPCSPIPE_LANE_BIT_ORDER_REVERSE_ENABLE', + 'RDPCSPIPE_LANE_PACK_FROM_MSB_DISABLE', + 'RDPCSPIPE_LANE_PACK_FROM_MSB_ENABLE', + 'RDPCSPIPE_MEM_PWR_DEEP_SLEEP', 'RDPCSPIPE_MEM_PWR_LIGHT_SLEEP', + 'RDPCSPIPE_MEM_PWR_NO_FORCE', + 'RDPCSPIPE_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 'RDPCSPIPE_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 'RDPCSPIPE_MEM_PWR_PWR_STATE_ON', + 'RDPCSPIPE_MEM_PWR_PWR_STATE_SHUT_DOWN', + 'RDPCSPIPE_MEM_PWR_SHUT_DOWN', + 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK', + 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_DISABLE', + 'RDPCSPIPE_MSG_BUS_COUNT_EXPIRE_MASK_ENABLE', + 'RDPCSPIPE_PACK_MODE', 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL', + 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL', + 'RDPCSPIPE_PHY_CNTL0_RDPCS_PHY_REF_RANGE', + 'RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE', + 'RDPCSPIPE_PHY_CNTL0_RDPCS_SRAM_INIT_DONE', + 'RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV', + 'RDPCSPIPE_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV', + 'RDPCSPIPE_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCSPIPE_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL', + 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT', + 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_RATE', + 'RDPCSPIPE_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH', + 'RDPCSPIPE_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE', + 'RDPCSPIPE_PHY_CR_MUX_SEL_FOR_DC', + 'RDPCSPIPE_PHY_CR_MUX_SEL_FOR_USB', + 'RDPCSPIPE_PHY_CR_PARA_SEL_CR', 'RDPCSPIPE_PHY_CR_PARA_SEL_JTAG', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV10', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV2', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV3', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV4', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV5', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV6', + 'RDPCSPIPE_PHY_DP_MPLLB_TX_CLK_DIV8', + 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV1', + 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV16', + 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV2', + 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV3', + 'RDPCSPIPE_PHY_DP_REF_CLK_MPLLB_DIV8', + 'RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_DETECT', + 'RDPCSPIPE_PHY_DP_TX_DETRX_RESULT_NO_DETECT', + 'RDPCSPIPE_PHY_DP_TX_RATE', 'RDPCSPIPE_PHY_DP_TX_RATE_DIV2', + 'RDPCSPIPE_PHY_DP_TX_RATE_DIV4', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_40', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_42', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_44', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_46', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_48', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_50', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_52', + 'RDPCSPIPE_PHY_DP_TX_TERM_CTRL_54', + 'RDPCSPIPE_PHY_DP_TX_WIDTH_10', 'RDPCSPIPE_PHY_DP_TX_WIDTH_16', + 'RDPCSPIPE_PHY_DP_TX_WIDTH_20', 'RDPCSPIPE_PHY_DP_TX_WIDTH_8', + 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 'RDPCSPIPE_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', + 'RDPCSPIPE_PHY_IF_WIDTH', 'RDPCSPIPE_PHY_RATE', + 'RDPCSPIPE_PHY_REF_ALT_CLK_DISABLE', + 'RDPCSPIPE_PHY_REF_ALT_CLK_EN', + 'RDPCSPIPE_PHY_REF_ALT_CLK_ENABLE', 'RDPCSPIPE_PHY_REF_RANGE_0', + 'RDPCSPIPE_PHY_REF_RANGE_1', 'RDPCSPIPE_PHY_REF_RANGE_2', + 'RDPCSPIPE_PHY_REF_RANGE_3', 'RDPCSPIPE_PHY_REF_RANGE_4', + 'RDPCSPIPE_PHY_REF_RANGE_5', 'RDPCSPIPE_PHY_REF_RANGE_6', + 'RDPCSPIPE_PHY_REF_RANGE_7', + 'RDPCSPIPE_PIPE_FIFO_ERROR_MASK_DISABLE', + 'RDPCSPIPE_PIPE_FIFO_ERROR_MASK_ENABLE', + 'RDPCSPIPE_REG_FIFO_ERROR_MASK_DISABLE', + 'RDPCSPIPE_REG_FIFO_ERROR_MASK_ENABLE', + 'RDPCSPIPE_SRAMCLK_DISABLE', 'RDPCSPIPE_SRAMCLK_ENABLE', + 'RDPCSPIPE_SRAMCLK_GATE_DISABLE', 'RDPCSPIPE_SRAMCLK_GATE_ENABLE', + 'RDPCSPIPE_SRAMCLK_NOT_PASS', 'RDPCSPIPE_SRAMCLK_PASS', + 'RDPCSPIPE_SRAM_EXT_LD_DONE', 'RDPCSPIPE_SRAM_EXT_LD_NOT_DONE', + 'RDPCSPIPE_SRAM_INIT_DONE', 'RDPCSPIPE_SRAM_INIT_NOT_DONE', + 'RDPCSPIPE_SRAM_SRAM_RESET_DISABLE', + 'RDPCSPIPE_SRAM_SRAM_RESET_ENABLE', + 'RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_OFF', + 'RDPCSPIPE_SYMCLK_SRAMCLK_CLOCK_ON', 'RDPCSPIPE_TEST_CLK_SEL', + 'RDPCSPIPE_TEST_CLK_SEL_CFGCLK', + 'RDPCSPIPE_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_EXT_CR_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_NONE', + 'RDPCSPIPE_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 'RDPCSPIPE_TEST_CLK_SEL_REF_DIG_FR_clk', + 'RDPCSPIPE_TEST_CLK_SEL_SRAMCLK', + 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 'RDPCSPIPE_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 'RDPCSPIPE_TEST_CLK_SEL_dtb_out0', + 'RDPCSPIPE_TEST_CLK_SEL_dtb_out1', 'RDPCS_PIPE_CLK_CLOCK_OFF', + 'RDPCS_PIPE_CLK_CLOCK_ON', 'RDPCS_PIPE_CLK_DISABLE', + 'RDPCS_PIPE_CLK_ENABLE', 'RDPCS_PIPE_CLK_GATE_DISABLE', + 'RDPCS_PIPE_CLK_GATE_ENABLE', + 'RDPCS_PIPE_CNTL_TX_LANE_PACK_FROM_MSB', + 'RDPCS_PIPE_FIFO_DISABLE', 'RDPCS_PIPE_FIFO_ENABLE', + 'RDPCS_PIPE_FIFO_LANE_DISABLE', 'RDPCS_PIPE_FIFO_LANE_ENABLE', + 'RDPCS_PIPE_PHYD32CLK_CLOCK_OFF', 'RDPCS_PIPE_PHYD32CLK_CLOCK_ON', + 'RDPCS_PIPE_SOFT_RESET_DISABLE', 'RDPCS_PIPE_SOFT_RESET_ENABLE', + 'RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_FORCE', + 'RDPCS_PIPE_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE', 'READ_SEQ', + 'RECTLIST', 'RECT_2D', 'RED_LUT', 'REFER_TO_DP_SOF', + 'REFER_TO_OTG_SOF', 'REG_SECURE_VIOLATE_READ', + 'REG_SECURE_VIOLATE_WRITE', 'REG_UNALLOCATED_ADDR_READ', + 'REG_UNALLOCATED_ADDR_WRITE', 'REG_VIRTUAL_READ', + 'REG_VIRTUAL_WRITE', 'RESERVED_1', 'RESERVED_10', 'RESERVED_11', + 'RESERVED_20', 'RESERVED_21', 'RESERVED_22', 'RESERVED_23', + 'RESERVED_3', 'RESERVED_32', 'RESERVED_33', 'RESERVED_34', + 'RESERVED_35', 'RESERVED_44', 'RESERVED_45', 'RESERVED_46', + 'RESERVED_47', 'RESERVED_56', 'RESERVED_57', 'RESERVED_58', + 'RESERVED_59', 'RESERVED_60', 'RESERVED_61', 'RESERVED_62', + 'RESERVED_63', 'RESERVED_72', 'RESERVED_73', 'RESERVED_74', + 'RESERVED_75', 'RESERVED_8', 'RESERVED_84', 'RESERVED_85', + 'RESERVED_86', 'RESERVED_87', 'RESERVED_88', 'RESERVED_89', + 'RESERVED_9', 'RESERVED_90', 'RESERVED_91', 'RESERVED_ES', + 'RESERVED_LS', 'RESERVED_RDPOLICY', 'RESERVED_VS', + 'RESET_TO_LOWEST_VGT', 'RESET_VTX_CNT', 'RESPONSE_STATUS', 'RE_Z', + 'RGB111110_FIX', 'RGB111110_FLOAT', 'RGB565', 'RGBA1010102', + 'RGBA16161616_10LSB', 'RGBA16161616_10MSB', 'RGBA16161616_12LSB', + 'RGBA16161616_12MSB', 'RGBA16161616_FLOAT', 'RGBA16161616_SNORM', + 'RGBA16161616_UNORM', 'RGBA4444', 'RGBA5551', 'RGBA8888', 'RGBE', + 'RINGID0', 'RINGID1', 'RINGID2', 'RINGID3', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RLC_DOORBELL_MODE', 'RLC_DOORBELL_MODE_DISABLE', + 'RLC_DOORBELL_MODE_ENABLE', 'RLC_DOORBELL_MODE_ENABLE_PF', + 'RLC_DOORBELL_MODE_ENABLE_PF_VF', 'RLC_PERFCOUNTER_SEL', + 'RLC_PERFMON_STATE', 'RLC_PERFMON_STATE_DISABLE', + 'RLC_PERFMON_STATE_ENABLE', 'RLC_PERFMON_STATE_RESERVED_3', + 'RLC_PERFMON_STATE_RESERVED_4', 'RLC_PERFMON_STATE_RESERVED_5', + 'RLC_PERFMON_STATE_RESERVED_6', 'RLC_PERFMON_STATE_RESET', + 'RLC_PERFMON_STATE_ROLLOVER', 'RLC_PERF_SEL_CP_INTERRUPT', + 'RLC_PERF_SEL_GRBM_INTERRUPT', 'RLC_PERF_SEL_IH_INTERRUPT', + 'RLC_PERF_SEL_POWER_FEATURE_0', 'RLC_PERF_SEL_POWER_FEATURE_1', + 'RLC_PERF_SEL_SERDES_COMMAND_WRITE', 'RLC_PERF_SEL_SPM_INTERRUPT', + 'RMIPerfSel', 'RMI_CID', 'RMI_CID_CC', 'RMI_CID_CM', 'RMI_CID_DC', + 'RMI_CID_FC', 'RMI_CID_S', 'RMI_CID_TILE', 'RMI_CID_Z', + 'RMI_CID_ZPCPSD', 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', 'ROM_SIGNATURE', + 'ROTATE_0_DEGREES', 'ROTATE_180_DEGREES', 'ROTATE_270_DEGREES', + 'ROTATE_90_DEGREES', 'ROTATION_ANGLE', 'ROW_TTU_MODE', + 'RPDCSPIPE_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK', + 'RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD', + 'RRDPCSPIPE_PHY_DP_TX_PSTATE_HOLD_OFF', + 'RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_DOWN', + 'RRDPCSPIPE_PHY_DP_TX_PSTATE_POWER_UP', 'RSPM_CMD', + 'RSPM_CMD_CALIBRATE', 'RSPM_CMD_FORCE_SAMPLE', 'RSPM_CMD_IDLE', + 'RSPM_CMD_INVALID', 'RSPM_CMD_PERF_RESET', 'RSPM_CMD_PERF_SAMPLE', + 'RSPM_CMD_PROF_START', 'RSPM_CMD_PROF_STOP', 'RSPM_CMD_SPM_RESET', + 'RSPM_CMD_SPM_START', 'RSPM_CMD_SPM_STOP', 'RST_PIX_CNT', + 'RSV_TAG_RAM', 'RbMap', 'RbXsel', 'RbXsel2', 'RbYsel', + 'ReadPolicy', 'Reserved_0x00', 'Reserved_0x09', + 'RingCounterControl', 'SAMPLE_PIPELINESTAT', + 'SAMPLE_STREAMOUTSTATS', 'SAMPLE_STREAMOUTSTATS1', + 'SAMPLE_STREAMOUTSTATS2', 'SAMPLE_STREAMOUTSTATS3', + 'SCL_2TAP_HARDCODE', 'SCL_ALPHA_COEF', 'SCL_ALPHA_COEF_FIRST', + 'SCL_ALPHA_COEF_SECOND', 'SCL_AUTOCAL_MODE', 'SCL_BOUNDARY', + 'SCL_BOUNDARY_BLACK', 'SCL_BOUNDARY_EDGE', 'SCL_CHROMA_COEF', + 'SCL_CHROMA_COEF_FIRST', 'SCL_CHROMA_COEF_SECOND', + 'SCL_COEF_2TAP_HARDCODE_OFF', 'SCL_COEF_2TAP_HARDCODE_ON', + 'SCL_COEF_CHROMA_HORZ_FILTER', 'SCL_COEF_CHROMA_VERT_FILTER', + 'SCL_COEF_FILTER_TYPE_SEL', 'SCL_COEF_LUMA_HORZ_FILTER', + 'SCL_COEF_LUMA_VERT_FILTER', 'SCL_COEF_RAM_SEL', + 'SCL_COEF_RAM_SEL_0', 'SCL_COEF_RAM_SEL_1', 'SCL_SHARP_DISABLE', + 'SCL_SHARP_EN', 'SCL_SHARP_ENABLE', 'SC_BACKEND_BUSY', + 'SC_BACKEND_PRIM_FIFO_FULL', 'SC_BB_DISCARD', + 'SC_BCI_CREDIT_AT_MAX', 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_BCI_SEND', + 'SC_BM_BE0_STALLED', 'SC_BM_BE1_STALLED', 'SC_BM_BE2_STALLED', + 'SC_BM_BE3_STALLED', 'SC_BM_BUSY', + 'SC_BM_MULTI_ACCUM_1_BE_STALLED', + 'SC_BM_MULTI_ACCUM_2_BE_STALLED', + 'SC_BM_MULTI_ACCUM_3_BE_STALLED', + 'SC_BM_MULTI_ACCUM_4_BE_STALLED', 'SC_BUSY_CNT_NOT_ZERO', + 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', 'SC_DB0_QUAD_INTF_BUSY', + 'SC_DB0_QUAD_INTF_CREDIT_AT_MAX', 'SC_DB0_QUAD_INTF_IDLE', + 'SC_DB0_QUAD_INTF_SEND', 'SC_DB0_QUAD_INTF_STALLED_BY_DB', + 'SC_DB0_TILE_INTERFACE_BUSY', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_SEND', 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 'SC_DB0_TILE_INTERFACE_SEND_SOP', + 'SC_DB0_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 'SC_DB0_TILE_MASK_FIFO_FULL', + 'SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL', + 'SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 'SC_DB1_QUAD_INTF_BUSY', 'SC_DB1_QUAD_INTF_CREDIT_AT_MAX', + 'SC_DB1_QUAD_INTF_IDLE', 'SC_DB1_QUAD_INTF_SEND', + 'SC_DB1_QUAD_INTF_STALLED_BY_DB', 'SC_DB1_TILE_INTERFACE_BUSY', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 'SC_DB1_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'SC_DB1_TILE_INTERFACE_SEND', 'SC_DB1_TILE_INTERFACE_SEND_EVENT', + 'SC_DB1_TILE_INTERFACE_SEND_SOP', + 'SC_DB1_TILE_INTERFACE_SEND_SOP_ONLY_EVENT', + 'SC_DB1_TILE_MASK_FIFO_FULL', + 'SC_DB1_WE_STALLED_BY_RSLT_FIFO_FULL', + 'SC_DB1_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 'SC_EARLYZ_QUAD_COUNT', 'SC_EARLYZ_QUAD_WITH_1_PIX', + 'SC_EARLYZ_QUAD_WITH_2_PIX', 'SC_EARLYZ_QUAD_WITH_3_PIX', + 'SC_EARLYZ_QUAD_WITH_4_PIX', 'SC_EOP_SYNC_WINDOW', + 'SC_FSR_WALKED', 'SC_FULL_FULL_QUAD', 'SC_FULL_HALF_QUAD', + 'SC_FULL_QTR_QUAD', 'SC_GRP0_DYN_SCLK_BUSY', + 'SC_GRP1_DYN_SCLK_BUSY', 'SC_GRP2_DYN_SCLK_BUSY', + 'SC_GRP3_DYN_SCLK_BUSY', 'SC_GRP4_DYN_SCLK_BUSY', + 'SC_GRP5_DYN_SCLK_BUSY', 'SC_GRP6_DYN_SCLK_BUSY', + 'SC_GRP7_DYN_SCLK_BUSY', 'SC_GRP8_DYN_SCLK_BUSY', + 'SC_GRP9_DYN_SCLK_BUSY', 'SC_HALF_FULL_QUAD', 'SC_HALF_HALF_QUAD', + 'SC_HALF_LSB', 'SC_HALF_QTR_QUAD', 'SC_LSB_ONE_SIDED', + 'SC_LSB_TWO_SIDED', 'SC_MULTICYCLE_BUBBLE_FREEZE', + 'SC_P0_DETAIL_QUAD_COUNT', 'SC_P0_DETAIL_QUAD_WITH_1_PIX', + 'SC_P0_DETAIL_QUAD_WITH_2_PIX', 'SC_P0_DETAIL_QUAD_WITH_3_PIX', + 'SC_P0_DETAIL_QUAD_WITH_4_PIX', 'SC_P0_HIZ_QUAD_COUNT', + 'SC_P0_HIZ_QUAD_PER_TILE_H0', 'SC_P0_HIZ_QUAD_PER_TILE_H1', + 'SC_P0_HIZ_QUAD_PER_TILE_H10', 'SC_P0_HIZ_QUAD_PER_TILE_H11', + 'SC_P0_HIZ_QUAD_PER_TILE_H12', 'SC_P0_HIZ_QUAD_PER_TILE_H13', + 'SC_P0_HIZ_QUAD_PER_TILE_H14', 'SC_P0_HIZ_QUAD_PER_TILE_H15', + 'SC_P0_HIZ_QUAD_PER_TILE_H16', 'SC_P0_HIZ_QUAD_PER_TILE_H2', + 'SC_P0_HIZ_QUAD_PER_TILE_H3', 'SC_P0_HIZ_QUAD_PER_TILE_H4', + 'SC_P0_HIZ_QUAD_PER_TILE_H5', 'SC_P0_HIZ_QUAD_PER_TILE_H6', + 'SC_P0_HIZ_QUAD_PER_TILE_H7', 'SC_P0_HIZ_QUAD_PER_TILE_H8', + 'SC_P0_HIZ_QUAD_PER_TILE_H9', 'SC_P0_HIZ_TILE_COUNT', + 'SC_P1_DETAIL_QUAD_COUNT', 'SC_P1_DETAIL_QUAD_WITH_1_PIX', + 'SC_P1_DETAIL_QUAD_WITH_2_PIX', 'SC_P1_DETAIL_QUAD_WITH_3_PIX', + 'SC_P1_DETAIL_QUAD_WITH_4_PIX', 'SC_P1_HIZ_QUAD_COUNT', + 'SC_P1_HIZ_QUAD_PER_TILE_H0', 'SC_P1_HIZ_QUAD_PER_TILE_H1', + 'SC_P1_HIZ_QUAD_PER_TILE_H10', 'SC_P1_HIZ_QUAD_PER_TILE_H11', + 'SC_P1_HIZ_QUAD_PER_TILE_H12', 'SC_P1_HIZ_QUAD_PER_TILE_H13', + 'SC_P1_HIZ_QUAD_PER_TILE_H14', 'SC_P1_HIZ_QUAD_PER_TILE_H15', + 'SC_P1_HIZ_QUAD_PER_TILE_H16', 'SC_P1_HIZ_QUAD_PER_TILE_H2', + 'SC_P1_HIZ_QUAD_PER_TILE_H3', 'SC_P1_HIZ_QUAD_PER_TILE_H4', + 'SC_P1_HIZ_QUAD_PER_TILE_H5', 'SC_P1_HIZ_QUAD_PER_TILE_H6', + 'SC_P1_HIZ_QUAD_PER_TILE_H7', 'SC_P1_HIZ_QUAD_PER_TILE_H8', + 'SC_P1_HIZ_QUAD_PER_TILE_H9', 'SC_P1_HIZ_TILE_COUNT', + 'SC_P2_DETAIL_QUAD_COUNT', 'SC_P2_DETAIL_QUAD_WITH_1_PIX', + 'SC_P2_DETAIL_QUAD_WITH_2_PIX', 'SC_P2_DETAIL_QUAD_WITH_3_PIX', + 'SC_P2_DETAIL_QUAD_WITH_4_PIX', 'SC_P2_HIZ_QUAD_COUNT', + 'SC_P2_HIZ_QUAD_PER_TILE_H0', 'SC_P2_HIZ_QUAD_PER_TILE_H1', + 'SC_P2_HIZ_QUAD_PER_TILE_H10', 'SC_P2_HIZ_QUAD_PER_TILE_H11', + 'SC_P2_HIZ_QUAD_PER_TILE_H12', 'SC_P2_HIZ_QUAD_PER_TILE_H13', + 'SC_P2_HIZ_QUAD_PER_TILE_H14', 'SC_P2_HIZ_QUAD_PER_TILE_H15', + 'SC_P2_HIZ_QUAD_PER_TILE_H16', 'SC_P2_HIZ_QUAD_PER_TILE_H2', + 'SC_P2_HIZ_QUAD_PER_TILE_H3', 'SC_P2_HIZ_QUAD_PER_TILE_H4', + 'SC_P2_HIZ_QUAD_PER_TILE_H5', 'SC_P2_HIZ_QUAD_PER_TILE_H6', + 'SC_P2_HIZ_QUAD_PER_TILE_H7', 'SC_P2_HIZ_QUAD_PER_TILE_H8', + 'SC_P2_HIZ_QUAD_PER_TILE_H9', 'SC_P2_HIZ_TILE_COUNT', + 'SC_P3_DETAIL_QUAD_COUNT', 'SC_P3_DETAIL_QUAD_WITH_1_PIX', + 'SC_P3_DETAIL_QUAD_WITH_2_PIX', 'SC_P3_DETAIL_QUAD_WITH_3_PIX', + 'SC_P3_DETAIL_QUAD_WITH_4_PIX', 'SC_P3_HIZ_QUAD_COUNT', + 'SC_P3_HIZ_QUAD_PER_TILE_H0', 'SC_P3_HIZ_QUAD_PER_TILE_H1', + 'SC_P3_HIZ_QUAD_PER_TILE_H10', 'SC_P3_HIZ_QUAD_PER_TILE_H11', + 'SC_P3_HIZ_QUAD_PER_TILE_H12', 'SC_P3_HIZ_QUAD_PER_TILE_H13', + 'SC_P3_HIZ_QUAD_PER_TILE_H14', 'SC_P3_HIZ_QUAD_PER_TILE_H15', + 'SC_P3_HIZ_QUAD_PER_TILE_H16', 'SC_P3_HIZ_QUAD_PER_TILE_H2', + 'SC_P3_HIZ_QUAD_PER_TILE_H3', 'SC_P3_HIZ_QUAD_PER_TILE_H4', + 'SC_P3_HIZ_QUAD_PER_TILE_H5', 'SC_P3_HIZ_QUAD_PER_TILE_H6', + 'SC_P3_HIZ_QUAD_PER_TILE_H7', 'SC_P3_HIZ_QUAD_PER_TILE_H8', + 'SC_P3_HIZ_QUAD_PER_TILE_H9', 'SC_P3_HIZ_TILE_COUNT', + 'SC_PA0_SC_DATA_FIFO_EOPG_RD', 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 'SC_PA0_SC_DATA_FIFO_RD', 'SC_PA0_SC_DATA_FIFO_WE', + 'SC_PA0_SC_DEALLOC_0_RD', 'SC_PA0_SC_DEALLOC_1_RD', + 'SC_PA0_SC_EOPG_WE', 'SC_PA0_SC_EOP_WE', 'SC_PA0_SC_EVENT_WE', + 'SC_PA0_SC_FPOV_WE', 'SC_PA0_SC_LPOV_WE', + 'SC_PA0_SC_NULL_DEALLOC_WE', 'SC_PA0_SC_NULL_WE', + 'SC_PA1_SC_DATA_FIFO_EOPG_RD', 'SC_PA1_SC_DATA_FIFO_EOP_RD', + 'SC_PA1_SC_DATA_FIFO_RD', 'SC_PA1_SC_DATA_FIFO_WE', + 'SC_PA1_SC_DEALLOC_0_RD', 'SC_PA1_SC_DEALLOC_1_RD', + 'SC_PA1_SC_EOPG_WE', 'SC_PA1_SC_EOP_WE', 'SC_PA1_SC_EVENT_WE', + 'SC_PA1_SC_FPOV_WE', 'SC_PA1_SC_LPOV_WE', + 'SC_PA1_SC_NULL_DEALLOC_WE', 'SC_PA1_SC_NULL_WE', + 'SC_PA2_SC_DATA_FIFO_EOPG_RD', 'SC_PA2_SC_DATA_FIFO_EOP_RD', + 'SC_PA2_SC_DATA_FIFO_RD', 'SC_PA2_SC_DATA_FIFO_WE', + 'SC_PA2_SC_DEALLOC_0_RD', 'SC_PA2_SC_DEALLOC_1_RD', + 'SC_PA2_SC_EOPG_WE', 'SC_PA2_SC_EOP_WE', 'SC_PA2_SC_EVENT_WE', + 'SC_PA2_SC_FPOV_WE', 'SC_PA2_SC_LPOV_WE', + 'SC_PA2_SC_NULL_DEALLOC_WE', 'SC_PA2_SC_NULL_WE', + 'SC_PA3_SC_DATA_FIFO_EOPG_RD', 'SC_PA3_SC_DATA_FIFO_EOP_RD', + 'SC_PA3_SC_DATA_FIFO_RD', 'SC_PA3_SC_DATA_FIFO_WE', + 'SC_PA3_SC_DEALLOC_0_RD', 'SC_PA3_SC_DEALLOC_1_RD', + 'SC_PA3_SC_EOPG_WE', 'SC_PA3_SC_EOP_WE', 'SC_PA3_SC_EVENT_WE', + 'SC_PA3_SC_FPOV_WE', 'SC_PA3_SC_LPOV_WE', + 'SC_PA3_SC_NULL_DEALLOC_WE', 'SC_PA3_SC_NULL_WE', + 'SC_PA_SC_DEALLOC_0_0_WE', 'SC_PA_SC_DEALLOC_0_1_WE', + 'SC_PA_SC_DEALLOC_1_0_WE', 'SC_PA_SC_DEALLOC_1_1_WE', + 'SC_PA_SC_DEALLOC_2_0_WE', 'SC_PA_SC_DEALLOC_2_1_WE', + 'SC_PA_SC_DEALLOC_3_0_WE', 'SC_PA_SC_DEALLOC_3_1_WE', + 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_MODE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET', + 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BIN_HIST_NUM_PRIMS', 'SC_PBB_BUSY', + 'SC_PBB_BUSY_AND_NO_SENDS', + 'SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN', 'SC_PBB_END_OF_BATCH', + 'SC_PBB_END_OF_BIN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 'SC_PBB_NONBINNED_PRIM', 'SC_PBB_NUM_BINS', + 'SC_PBB_PRIMBIN_PROCESSED', 'SC_PBB_PRIM_ADDED_TO_BATCH', + 'SC_PBB_RESERVED', 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', 'SC_PERFCNT_SEL', + 'SC_PKR_4X2_FILL_QUAD', 'SC_PKR_4X2_QUAD_SPLIT', + 'SC_PKR_CONTROL_XFER', 'SC_PKR_DBHANG_FORCE_EOV', + 'SC_PKR_END_OF_VECTOR', 'SC_PKR_QUAD_OVLP_FOUND_IN_WAVE_TABLE', + 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_NO_CHANGE_TO_WAVES_SINCE_OVLP', + 'SC_PKR_QUAD_OVLP_NOT_FOUND_IN_WAVE_TABLE_AND_WAVES_SINCE_OVLP_SET_TO_MAX', + 'SC_PKR_QUAD_PER_ROW_H1', 'SC_PKR_QUAD_PER_ROW_H2', + 'SC_PKR_WAVE_BREAK_FULL_TILE', 'SC_PKR_WAVE_BREAK_OUTSIDE_REGION', + 'SC_PK_BUSY', 'SC_PK_DEALLOC_WAVE_BREAK', + 'SC_PK_MAX_DEALLOC_FORCE_EOV', 'SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H', + 'SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H', + 'SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 'SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H', + 'SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H', + 'SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H', + 'SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H', + 'SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 'SC_PK_PM_FULL_TILE_WAVE_BRK_1H', + 'SC_PK_PM_LAST_AND_DEALLOC_WAVE_BRK_1H', + 'SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H', + 'SC_PK_PM_POPS_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_QD1_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 'SC_PK_PM_QD1_FD_CONFLICT_WAVE_BRK_1H', + 'SC_PK_PM_QD1_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 'SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H', + 'SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD', + 'SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H', + 'SC_POPS_FORCE_EOV', 'SC_POPS_INTRA_WAVE_OVERLAPS', + 'SC_PSSW_WINDOW_VALID', 'SC_PSSW_WINDOW_VALID_BUSY', + 'SC_PS_ARB_EOP_POP_SYNC_POP', 'SC_PS_ARB_EVENT_SYNC_POP', + 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 'SC_PS_ARB_PA_SC_BUSY', 'SC_PS_ARB_SC_BUSY', + 'SC_PS_ARB_STALLED_FROM_BELOW', 'SC_PS_ARB_STARVED_FROM_ABOVE', + 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', 'SC_PS_CTX_DONE_FIFO_POP', + 'SC_PS_CTX_DONE_FIFO_PUSH', 'SC_PS_ENG_MULTICYCLE_BUBBLE', + 'SC_PS_PA0_SC_FIFO_EMPTY', 'SC_PS_PA0_SC_FIFO_FULL', + 'SC_PS_PA1_SC_FIFO_EMPTY', 'SC_PS_PA1_SC_FIFO_FULL', + 'SC_PS_PA2_SC_FIFO_EMPTY', 'SC_PS_PA2_SC_FIFO_FULL', + 'SC_PS_PA3_SC_FIFO_EMPTY', 'SC_PS_PA3_SC_FIFO_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL', + 'SC_PS_PM_PFF_PW_FULL', 'SC_PS_PM_ZFF_PW_FULL', + 'SC_PS_TO_BE_SCLK_GATE_STALL', 'SC_PS_TS_EVENT_FIFO_POP', + 'SC_PS_TS_EVENT_FIFO_PUSH', 'SC_PW_BM_PASS_EMPTY_PRIM', + 'SC_QTR_FULL_QUAD', 'SC_QTR_HALF_QUAD', 'SC_QTR_QTR_QUAD', + 'SC_QZ0_QUAD_COUNT', 'SC_QZ0_QUAD_PER_TILE_H0', + 'SC_QZ0_QUAD_PER_TILE_H1', 'SC_QZ0_QUAD_PER_TILE_H10', + 'SC_QZ0_QUAD_PER_TILE_H11', 'SC_QZ0_QUAD_PER_TILE_H12', + 'SC_QZ0_QUAD_PER_TILE_H13', 'SC_QZ0_QUAD_PER_TILE_H14', + 'SC_QZ0_QUAD_PER_TILE_H15', 'SC_QZ0_QUAD_PER_TILE_H16', + 'SC_QZ0_QUAD_PER_TILE_H2', 'SC_QZ0_QUAD_PER_TILE_H3', + 'SC_QZ0_QUAD_PER_TILE_H4', 'SC_QZ0_QUAD_PER_TILE_H5', + 'SC_QZ0_QUAD_PER_TILE_H6', 'SC_QZ0_QUAD_PER_TILE_H7', + 'SC_QZ0_QUAD_PER_TILE_H8', 'SC_QZ0_QUAD_PER_TILE_H9', + 'SC_QZ0_TILE_COUNT', 'SC_QZ0_TILE_COVERED_COUNT', + 'SC_QZ0_TILE_NOT_COVERED_COUNT', 'SC_QZ1_QUAD_COUNT', + 'SC_QZ1_QUAD_PER_TILE_H0', 'SC_QZ1_QUAD_PER_TILE_H1', + 'SC_QZ1_QUAD_PER_TILE_H10', 'SC_QZ1_QUAD_PER_TILE_H11', + 'SC_QZ1_QUAD_PER_TILE_H12', 'SC_QZ1_QUAD_PER_TILE_H13', + 'SC_QZ1_QUAD_PER_TILE_H14', 'SC_QZ1_QUAD_PER_TILE_H15', + 'SC_QZ1_QUAD_PER_TILE_H16', 'SC_QZ1_QUAD_PER_TILE_H2', + 'SC_QZ1_QUAD_PER_TILE_H3', 'SC_QZ1_QUAD_PER_TILE_H4', + 'SC_QZ1_QUAD_PER_TILE_H5', 'SC_QZ1_QUAD_PER_TILE_H6', + 'SC_QZ1_QUAD_PER_TILE_H7', 'SC_QZ1_QUAD_PER_TILE_H8', + 'SC_QZ1_QUAD_PER_TILE_H9', 'SC_QZ1_TILE_COUNT', + 'SC_QZ1_TILE_COVERED_COUNT', 'SC_QZ1_TILE_NOT_COVERED_COUNT', + 'SC_QZ2_QUAD_COUNT', 'SC_QZ2_QUAD_PER_TILE_H0', + 'SC_QZ2_QUAD_PER_TILE_H1', 'SC_QZ2_QUAD_PER_TILE_H10', + 'SC_QZ2_QUAD_PER_TILE_H11', 'SC_QZ2_QUAD_PER_TILE_H12', + 'SC_QZ2_QUAD_PER_TILE_H13', 'SC_QZ2_QUAD_PER_TILE_H14', + 'SC_QZ2_QUAD_PER_TILE_H15', 'SC_QZ2_QUAD_PER_TILE_H16', + 'SC_QZ2_QUAD_PER_TILE_H2', 'SC_QZ2_QUAD_PER_TILE_H3', + 'SC_QZ2_QUAD_PER_TILE_H4', 'SC_QZ2_QUAD_PER_TILE_H5', + 'SC_QZ2_QUAD_PER_TILE_H6', 'SC_QZ2_QUAD_PER_TILE_H7', + 'SC_QZ2_QUAD_PER_TILE_H8', 'SC_QZ2_QUAD_PER_TILE_H9', + 'SC_QZ2_TILE_COUNT', 'SC_QZ2_TILE_COVERED_COUNT', + 'SC_QZ2_TILE_NOT_COVERED_COUNT', 'SC_QZ3_QUAD_COUNT', + 'SC_QZ3_QUAD_PER_TILE_H0', 'SC_QZ3_QUAD_PER_TILE_H1', + 'SC_QZ3_QUAD_PER_TILE_H10', 'SC_QZ3_QUAD_PER_TILE_H11', + 'SC_QZ3_QUAD_PER_TILE_H12', 'SC_QZ3_QUAD_PER_TILE_H13', + 'SC_QZ3_QUAD_PER_TILE_H14', 'SC_QZ3_QUAD_PER_TILE_H15', + 'SC_QZ3_QUAD_PER_TILE_H16', 'SC_QZ3_QUAD_PER_TILE_H2', + 'SC_QZ3_QUAD_PER_TILE_H3', 'SC_QZ3_QUAD_PER_TILE_H4', + 'SC_QZ3_QUAD_PER_TILE_H5', 'SC_QZ3_QUAD_PER_TILE_H6', + 'SC_QZ3_QUAD_PER_TILE_H7', 'SC_QZ3_QUAD_PER_TILE_H8', + 'SC_QZ3_QUAD_PER_TILE_H9', 'SC_QZ3_TILE_COUNT', + 'SC_QZ3_TILE_COVERED_COUNT', 'SC_QZ3_TILE_NOT_COVERED_COUNT', + 'SC_QZQP_WINDOW_VALID', 'SC_QZQP_WINDOW_VALID_BUSY', + 'SC_REG_SCLK_BUSY', 'SC_RESERVED_0', 'SC_RESERVED_1', + 'SC_RESERVED_2', 'SC_RESERVED_3', 'SC_SCB_BUSY', + 'SC_SCF_SCB_INTERFACE_BUSY', 'SC_SCISSOR_DISCARD', + 'SC_SEND_DB_VPZ', 'SC_SPIBC_FULL_FREEZE', 'SC_SPI_CREDIT_AT_MAX', + 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_SPI_DEALLOC_0_0', + 'SC_SPI_DEALLOC_0_1', 'SC_SPI_DEALLOC_0_2', 'SC_SPI_DEALLOC_1_0', + 'SC_SPI_DEALLOC_1_1', 'SC_SPI_DEALLOC_1_2', 'SC_SPI_DEALLOC_2_0', + 'SC_SPI_DEALLOC_2_1', 'SC_SPI_DEALLOC_2_2', 'SC_SPI_DEALLOC_3_0', + 'SC_SPI_DEALLOC_3_1', 'SC_SPI_DEALLOC_3_2', 'SC_SPI_EVENT', + 'SC_SPI_FPOV_0', 'SC_SPI_FPOV_1', 'SC_SPI_FPOV_2', + 'SC_SPI_FPOV_3', 'SC_SPI_SEND', 'SC_SRPS_WINDOW_VALID', + 'SC_SRPS_WINDOW_VALID_BUSY', 'SC_STALLED_BY_BCI', + 'SC_STALLED_BY_DB0_TILEFIFO', 'SC_STALLED_BY_DB1_TILEFIFO', + 'SC_STALLED_BY_DB_QUAD', 'SC_STALLED_BY_DB_TILE', + 'SC_STALLED_BY_PRIMFIFO', 'SC_STALLED_BY_QUADFIFO', + 'SC_STALLED_BY_SPI', 'SC_STALLED_BY_TILEFIFO', + 'SC_STALLED_BY_TILEORDERFIFO', 'SC_STARVED_BY_DB_QUAD', + 'SC_STARVED_BY_DB_TILE', 'SC_STARVED_BY_PA', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 'SC_SUPERTILE_COUNT', + 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 'SC_SUPERTILE_PER_PRIM_H0', 'SC_SUPERTILE_PER_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_H10', 'SC_SUPERTILE_PER_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_H12', 'SC_SUPERTILE_PER_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_H14', 'SC_SUPERTILE_PER_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_H16', 'SC_SUPERTILE_PER_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_H3', 'SC_SUPERTILE_PER_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_H5', 'SC_SUPERTILE_PER_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_H7', 'SC_SUPERTILE_PER_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_H9', 'SC_TILE_PER_PRIM_H0', + 'SC_TILE_PER_PRIM_H1', 'SC_TILE_PER_PRIM_H10', + 'SC_TILE_PER_PRIM_H11', 'SC_TILE_PER_PRIM_H12', + 'SC_TILE_PER_PRIM_H13', 'SC_TILE_PER_PRIM_H14', + 'SC_TILE_PER_PRIM_H15', 'SC_TILE_PER_PRIM_H16', + 'SC_TILE_PER_PRIM_H2', 'SC_TILE_PER_PRIM_H3', + 'SC_TILE_PER_PRIM_H4', 'SC_TILE_PER_PRIM_H5', + 'SC_TILE_PER_PRIM_H6', 'SC_TILE_PER_PRIM_H7', + 'SC_TILE_PER_PRIM_H8', 'SC_TILE_PER_PRIM_H9', + 'SC_TILE_PER_SUPERTILE_H0', 'SC_TILE_PER_SUPERTILE_H1', + 'SC_TILE_PER_SUPERTILE_H10', 'SC_TILE_PER_SUPERTILE_H11', + 'SC_TILE_PER_SUPERTILE_H12', 'SC_TILE_PER_SUPERTILE_H13', + 'SC_TILE_PER_SUPERTILE_H14', 'SC_TILE_PER_SUPERTILE_H15', + 'SC_TILE_PER_SUPERTILE_H16', 'SC_TILE_PER_SUPERTILE_H2', + 'SC_TILE_PER_SUPERTILE_H3', 'SC_TILE_PER_SUPERTILE_H4', + 'SC_TILE_PER_SUPERTILE_H5', 'SC_TILE_PER_SUPERTILE_H6', + 'SC_TILE_PER_SUPERTILE_H7', 'SC_TILE_PER_SUPERTILE_H8', + 'SC_TILE_PER_SUPERTILE_H9', 'SC_TILE_PICKED_H1', + 'SC_TILE_PICKED_H2', 'SC_TILE_PICKED_H3', 'SC_TILE_PICKED_H4', + 'SC_TPQZ_WINDOW_VALID', 'SC_TPQZ_WINDOW_VALID_BUSY', + 'SC_TRPK_WINDOW_VALID', 'SC_TRPK_WINDOW_VALID_BUSY', 'SC_UR_1X', + 'SC_UR_2X', 'SC_UR_4X', 'SC_UR_8X', 'SC_VRS_COMB_MODE_MAX', + 'SC_VRS_COMB_MODE_MIN', 'SC_VRS_COMB_MODE_OVERRIDE', + 'SC_VRS_COMB_MODE_PASSTHRU', 'SC_VRS_COMB_MODE_SATURATE', + 'SDMA_PERFMON_SEL', 'SDMA_PERFMON_SEL_CE_AFIFO_FULL', + 'SDMA_PERFMON_SEL_CE_DST_IDLE', 'SDMA_PERFMON_SEL_CE_INFO1_FULL', + 'SDMA_PERFMON_SEL_CE_INFO_FULL', 'SDMA_PERFMON_SEL_CE_IN_IDLE', + 'SDMA_PERFMON_SEL_CE_L1_WR_VLD', 'SDMA_PERFMON_SEL_CE_OUT_IDLE', + 'SDMA_PERFMON_SEL_CE_RD_STALL', 'SDMA_PERFMON_SEL_CE_RREQ_IDLE', + 'SDMA_PERFMON_SEL_CE_SPLIT_IDLE', 'SDMA_PERFMON_SEL_CE_WREQ_IDLE', + 'SDMA_PERFMON_SEL_CE_WR_IDLE', 'SDMA_PERFMON_SEL_CE_WR_STALL', + 'SDMA_PERFMON_SEL_CPF_SDMA_INVREQ', 'SDMA_PERFMON_SEL_CTX_CHANGE', + 'SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERFMON_SEL_CYCLE', + 'SDMA_PERFMON_SEL_DMA_L1_RD_SEND', + 'SDMA_PERFMON_SEL_DMA_L1_WR_SEND', + 'SDMA_PERFMON_SEL_DMA_MC_RD_SEND', + 'SDMA_PERFMON_SEL_DMA_MC_WR_SEND', 'SDMA_PERFMON_SEL_DOORBELL', + 'SDMA_PERFMON_SEL_EX_IDLE', + 'SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERFMON_SEL_F32_L1_WR_VLD', 'SDMA_PERFMON_SEL_GCR_RTN', + 'SDMA_PERFMON_SEL_GCR_SEND', 'SDMA_PERFMON_SEL_GFX_SELECT', + 'SDMA_PERFMON_SEL_GPUVM_INV_HIGH', + 'SDMA_PERFMON_SEL_GPUVM_INV_LOW', 'SDMA_PERFMON_SEL_IB_CMD_FULL', + 'SDMA_PERFMON_SEL_IB_CMD_IDLE', 'SDMA_PERFMON_SEL_IDLE', + 'SDMA_PERFMON_SEL_INT_IDLE', 'SDMA_PERFMON_SEL_INT_REQ_COUNT', + 'SDMA_PERFMON_SEL_INT_REQ_STALL', + 'SDMA_PERFMON_SEL_INT_RESP_ACCEPTED', + 'SDMA_PERFMON_SEL_INT_RESP_RETRY', + 'SDMA_PERFMON_SEL_L1_RDL2_IDLE', 'SDMA_PERFMON_SEL_L1_RDMC_IDLE', + 'SDMA_PERFMON_SEL_L1_RD_INV_IDLE', + 'SDMA_PERFMON_SEL_L1_WRL2_IDLE', 'SDMA_PERFMON_SEL_L1_WRMC_IDLE', + 'SDMA_PERFMON_SEL_L1_WR_INV_IDLE', + 'SDMA_PERFMON_SEL_L2_META_RET_VLD', + 'SDMA_PERFMON_SEL_MC_RD_COUNT', 'SDMA_PERFMON_SEL_MC_RD_IDLE', + 'SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERFMON_SEL_MC_RD_RET_STALL', + 'SDMA_PERFMON_SEL_MC_WR_COUNT', 'SDMA_PERFMON_SEL_MC_WR_IDLE', + 'SDMA_PERFMON_SEL_META_L2_REQ_SEND', + 'SDMA_PERFMON_SEL_META_REQ_SEND', 'SDMA_PERFMON_SEL_META_RTN_VLD', + 'SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER', + 'SDMA_PERFMON_SEL_NUM_PACKET', 'SDMA_PERFMON_SEL_PAGE_SELECT', + 'SDMA_PERFMON_SEL_RB_CMD_FULL', 'SDMA_PERFMON_SEL_RB_CMD_IDLE', + 'SDMA_PERFMON_SEL_RB_EMPTY', 'SDMA_PERFMON_SEL_RB_FULL', + 'SDMA_PERFMON_SEL_RB_RPTR_WB', 'SDMA_PERFMON_SEL_RB_RPTR_WRAP', + 'SDMA_PERFMON_SEL_RB_WPTR_POLL_READ', + 'SDMA_PERFMON_SEL_RB_WPTR_WRAP', 'SDMA_PERFMON_SEL_RD_BA_RTR', + 'SDMA_PERFMON_SEL_REG_IDLE', 'SDMA_PERFMON_SEL_RLC0_SELECT', + 'SDMA_PERFMON_SEL_RLC1_SELECT', + 'SDMA_PERFMON_SEL_SDMA_CPF_INVACK', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_SEND', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND', + 'SDMA_PERFMON_SEL_SEM_IDLE', 'SDMA_PERFMON_SEL_SEM_REQ_COUNT', + 'SDMA_PERFMON_SEL_SEM_REQ_STALL', + 'SDMA_PERFMON_SEL_SEM_RESP_FAIL', + 'SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERFMON_SEL_SEM_RESP_PASS', + 'SDMA_PERFMON_SEL_SRBM_REG_SEND', 'SDMA_PERFMON_SEL_TLBI_RTN', + 'SDMA_PERFMON_SEL_TLBI_SEND', + 'SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER', + 'SDMA_PERFMON_SEL_UTCL2_FREE', 'SDMA_PERFMON_SEL_UTCL2_RET_ACK', + 'SDMA_PERFMON_SEL_UTCL2_RET_XNACK', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN', + 'SDMA_PERFMON_SEL_WR_BA_RTR', 'SDMA_PERF_SEL', + 'SDMA_PERF_SEL_CE_AFIFO_FULL', 'SDMA_PERF_SEL_CE_BUSY', + 'SDMA_PERF_SEL_CE_BUSY_END', 'SDMA_PERF_SEL_CE_BUSY_START', + 'SDMA_PERF_SEL_CE_CH_RDREQ_SEND', + 'SDMA_PERF_SEL_CE_CH_WRREQ_SEND', 'SDMA_PERF_SEL_CE_CH_WR_REQ', + 'SDMA_PERF_SEL_CE_CH_WR_RET', 'SDMA_PERF_SEL_CE_DST_IDLE', + 'SDMA_PERF_SEL_CE_INFO1_FULL', 'SDMA_PERF_SEL_CE_INFO_FULL', + 'SDMA_PERF_SEL_CE_IN_IDLE', 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 'SDMA_PERF_SEL_CE_OR_F32_CH_RD_REQ', + 'SDMA_PERF_SEL_CE_OR_F32_CH_RD_RET', 'SDMA_PERF_SEL_CE_OUT_IDLE', + 'SDMA_PERF_SEL_CE_RD_STALL', 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 'SDMA_PERF_SEL_CE_SPLIT_IDLE', 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 'SDMA_PERF_SEL_CE_WR_IDLE', 'SDMA_PERF_SEL_CE_WR_STALL', + 'SDMA_PERF_SEL_CGCG_FENCE', 'SDMA_PERF_SEL_CH_CE_RDRET_VALID', + 'SDMA_PERF_SEL_CH_CE_WRRET_VALID', 'SDMA_PERF_SEL_CMD_OP_END', + 'SDMA_PERF_SEL_CMD_OP_MATCH', 'SDMA_PERF_SEL_CMD_OP_START', + 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', 'SDMA_PERF_SEL_CTX_CHANGE', + 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERF_SEL_CYCLE', + 'SDMA_PERF_SEL_DMA_L1_RD_SEND', 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 'SDMA_PERF_SEL_DMA_MC_RD_SEND', 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 'SDMA_PERF_SEL_DOORBELL', 'SDMA_PERF_SEL_EX_IDLE', + 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERF_SEL_F32_CH_WR_REQ', 'SDMA_PERF_SEL_F32_CH_WR_RET', + 'SDMA_PERF_SEL_F32_L1_WR_VLD', + 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 'SDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 'SDMA_PERF_SEL_GCR_RTN', 'SDMA_PERF_SEL_GCR_SEND', + 'SDMA_PERF_SEL_GFX_SELECT', 'SDMA_PERF_SEL_GPUVM_INV_HIGH', + 'SDMA_PERF_SEL_GPUVM_INV_LOW', 'SDMA_PERF_SEL_IB_CH_RD_REQ', + 'SDMA_PERF_SEL_IB_CH_RD_RET', 'SDMA_PERF_SEL_IB_CMD_FULL', + 'SDMA_PERF_SEL_IB_CMD_IDLE', 'SDMA_PERF_SEL_IDLE', + 'SDMA_PERF_SEL_INT_IDLE', 'SDMA_PERF_SEL_INT_REQ_COUNT', + 'SDMA_PERF_SEL_INT_REQ_STALL', 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 'SDMA_PERF_SEL_INT_RESP_RETRY', 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 'SDMA_PERF_SEL_L1_RDMC_IDLE', 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 'SDMA_PERF_SEL_L1_WRL2_IDLE', 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 'SDMA_PERF_SEL_L1_WR_INV_IDLE', 'SDMA_PERF_SEL_L2_META_RET_VLD', + 'SDMA_PERF_SEL_MC_RD_COUNT', 'SDMA_PERF_SEL_MC_RD_IDLE', + 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERF_SEL_MC_RD_RET_STALL', 'SDMA_PERF_SEL_MC_WR_COUNT', + 'SDMA_PERF_SEL_MC_WR_IDLE', 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 'SDMA_PERF_SEL_META_REQ_SEND', 'SDMA_PERF_SEL_META_RTN_VLD', + 'SDMA_PERF_SEL_NUM_PACKET', 'SDMA_PERF_SEL_PAGE_SELECT', + 'SDMA_PERF_SEL_RB_CH_RD_REQ', 'SDMA_PERF_SEL_RB_CH_RD_RET', + 'SDMA_PERF_SEL_RB_CMD_FULL', 'SDMA_PERF_SEL_RB_CMD_IDLE', + 'SDMA_PERF_SEL_RB_EMPTY', 'SDMA_PERF_SEL_RB_FULL', + 'SDMA_PERF_SEL_RB_RPTR_WB', 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 'SDMA_PERF_SEL_RD_BA_RTR', 'SDMA_PERF_SEL_REG_IDLE', + 'SDMA_PERF_SEL_RLC0_SELECT', 'SDMA_PERF_SEL_RLC1_SELECT', + 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', 'SDMA_PERF_SEL_SEM_IDLE', + 'SDMA_PERF_SEL_SEM_REQ_COUNT', 'SDMA_PERF_SEL_SEM_REQ_STALL', + 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERF_SEL_SEM_RESP_PASS', 'SDMA_PERF_SEL_SRBM_REG_SEND', + 'SDMA_PERF_SEL_TLBI_RTN', 'SDMA_PERF_SEL_TLBI_SEND', + 'SDMA_PERF_SEL_UTCL1_UTCL2_REQ', 'SDMA_PERF_SEL_UTCL1_UTCL2_RET', + 'SDMA_PERF_SEL_UTCL2_FREE', 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', 'SDMA_PERF_SEL_WPTR_CH_RD_REQ', + 'SDMA_PERF_SEL_WPTR_CH_RD_RET', 'SDMA_PERF_SEL_WR_BA_RTR', + 'SEC_GSP0_PRIORITY_HIGH', 'SEC_GSP0_PRIORITY_LOW', 'SEGMENTS_1', + 'SEGMENTS_128', 'SEGMENTS_16', 'SEGMENTS_2', 'SEGMENTS_32', + 'SEGMENTS_4', 'SEGMENTS_64', 'SEGMENTS_8', 'SEL_DTBCLK0', + 'SEL_DTBCLK1', 'SEL_REFCLK0', 'SEM_ECC_ERROR', 'SEM_PERF_SEL', + 'SEM_PERF_SEL_ACP_REQ_SIGNAL', 'SEM_PERF_SEL_ACP_REQ_WAIT', + 'SEM_PERF_SEL_ATC_INVALIDATION', 'SEM_PERF_SEL_ATC_REQ', + 'SEM_PERF_SEL_ATC_RET', 'SEM_PERF_SEL_ATC_VM_INVALIDATION', + 'SEM_PERF_SEL_ATC_XNACK', 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 'SEM_PERF_SEL_CYCLE', 'SEM_PERF_SEL_IDLE', + 'SEM_PERF_SEL_ISP_REQ_SIGNAL', 'SEM_PERF_SEL_ISP_REQ_WAIT', + 'SEM_PERF_SEL_MC_RD_REQ', 'SEM_PERF_SEL_MC_RD_RET', + 'SEM_PERF_SEL_MC_WR_REQ', 'SEM_PERF_SEL_MC_WR_RET', + 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 'SEM_PERF_SEL_SDMA2_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA2_REQ_WAIT', + 'SEM_PERF_SEL_SDMA3_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA3_REQ_WAIT', + 'SEM_PERF_SEL_UVD1_REQ_SIGNAL', 'SEM_PERF_SEL_UVD1_REQ_WAIT', + 'SEM_PERF_SEL_UVD_REQ_SIGNAL', 'SEM_PERF_SEL_UVD_REQ_WAIT', + 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 'SEM_PERF_SEL_VP8_REQ_SIGNAL', 'SEM_PERF_SEL_VP8_REQ_WAIT', + 'SEM_RESP_FAILED', 'SEM_RESP_PASSED', 'SEM_TRANS_ERROR', + 'SEND_AT_EARLIEST_TIME', 'SEND_AT_LINK_NUMBER', + 'SEND_NORMAL_PACKET', 'SEND_PPS_PACKET', 'SET_SMU_MSG_INTR', + 'SH_MEM_ADDRESS_MODE', 'SH_MEM_ADDRESS_MODE_32', + 'SH_MEM_ADDRESS_MODE_64', 'SH_MEM_ALIGNMENT_MODE', + 'SH_MEM_ALIGNMENT_MODE_DWORD', + 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 'SH_MEM_ALIGNMENT_MODE_STRICT', 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', + 'SIGNED', 'SIMM16_WAITCNT_DEPCTR_HOLD_CNT_SIZE', + 'SIMM16_WAITCNT_DEPCTR_HOLD_CNT_START', + 'SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_SA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_START', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_START', + 'SIMM16_WAITCNT_EXP_CNT_SIZE', 'SIMM16_WAITCNT_EXP_CNT_START', + 'SIMM16_WAITCNT_LGKM_CNT_SIZE', 'SIMM16_WAITCNT_LGKM_CNT_START', + 'SIMM16_WAITCNT_VM_CNT_SIZE', 'SIMM16_WAITCNT_VM_CNT_START', + 'SIMM16_WAIT_EVENT_EXP_RDY_SIZE', + 'SIMM16_WAIT_EVENT_EXP_RDY_START', 'SIZE_16K', 'SIZE_8K', + 'SLVERR', 'SMU_INTR', 'SMU_INTR_STATUS_CLEAR', + 'SMU_INTR_STATUS_NOOP', 'SMU_MSG_INTR_NOOP', 'SM_MODE_RESERVED', + 'SOFT_RESET', 'SOFT_RESET_0', 'SOFT_RESET_1', + 'SO_VGTSTREAMOUT_FLUSH', 'SPI_FOG_EXP', 'SPI_FOG_EXP2', + 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', 'SPI_FOG_NONE', + 'SPI_LB_WAVES_RSVD', 'SPI_LB_WAVES_SELECT', 'SPI_PERFCNT_SEL', + 'SPI_PERF_BUSY', 'SPI_PERF_CSGN_BUSY', + 'SPI_PERF_CSGN_CRAWLER_STALL', 'SPI_PERF_CSGN_EVENT_WAVE', + 'SPI_PERF_CSGN_NUM_THREADGROUPS', 'SPI_PERF_CSGN_PWS_STALL', + 'SPI_PERF_CSGN_WAVE', 'SPI_PERF_CSGN_WINDOW_VALID', + 'SPI_PERF_CSN_BUSY', 'SPI_PERF_CSN_CRAWLER_STALL', + 'SPI_PERF_CSN_EVENT_WAVE', 'SPI_PERF_CSN_NUM_THREADGROUPS', + 'SPI_PERF_CSN_WAVE', 'SPI_PERF_CSN_WINDOW_VALID', + 'SPI_PERF_EXPORT_DB0_STALL', 'SPI_PERF_EXPORT_DB1_STALL', + 'SPI_PERF_EXPORT_DB2_STALL', 'SPI_PERF_EXPORT_DB3_STALL', + 'SPI_PERF_EXPORT_DB4_STALL', 'SPI_PERF_EXPORT_DB5_STALL', + 'SPI_PERF_EXPORT_DB6_STALL', 'SPI_PERF_EXPORT_DB7_STALL', + 'SPI_PERF_EXPORT_SCB0_STALL', 'SPI_PERF_EXPORT_SCB1_STALL', + 'SPI_PERF_EXPORT_SCB2_STALL', 'SPI_PERF_EXPORT_SCB3_STALL', + 'SPI_PERF_EXP_ARB_COL_CNT', 'SPI_PERF_EXP_ARB_GDS_CNT', + 'SPI_PERF_EXP_ARB_IDX_CNT', 'SPI_PERF_EXP_ARB_POS_CNT', + 'SPI_PERF_EXP_THROT_CAUSALITY_DETECTED', + 'SPI_PERF_EXP_THROT_DOWNSTEP', 'SPI_PERF_EXP_THROT_UPSTEP', + 'SPI_PERF_EXP_WITH_CONFLICT', 'SPI_PERF_EXP_WITH_CONFLICT_CLEAR', + 'SPI_PERF_GS_BUSY', 'SPI_PERF_GS_CRAWLER_STALL', + 'SPI_PERF_GS_EVENT_WAVE', 'SPI_PERF_GS_EXP_DONE', + 'SPI_PERF_GS_FIRST_SUBGRP', 'SPI_PERF_GS_HS_DEALLOC', + 'SPI_PERF_GS_INDX0_STALL', 'SPI_PERF_GS_INDX1_STALL', + 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 'SPI_PERF_GS_NGG_STALL_MSG_VAL', 'SPI_PERF_GS_PERS_UPD_FULL0', + 'SPI_PERF_GS_PERS_UPD_FULL1', 'SPI_PERF_GS_POS0_STALL', + 'SPI_PERF_GS_POS1_STALL', 'SPI_PERF_GS_PWS_STALL', + 'SPI_PERF_GS_WAVE', 'SPI_PERF_GS_WINDOW_VALID', + 'SPI_PERF_HS_BUSY', 'SPI_PERF_HS_CRAWLER_STALL', + 'SPI_PERF_HS_EVENT_WAVE', 'SPI_PERF_HS_FIRST_WAVE', + 'SPI_PERF_HS_OFFCHIP_LDS_STALL', 'SPI_PERF_HS_PERS_UPD_FULL0', + 'SPI_PERF_HS_PERS_UPD_FULL1', 'SPI_PERF_HS_PWS_STALL', + 'SPI_PERF_HS_WAVE', 'SPI_PERF_HS_WINDOW_VALID', + 'SPI_PERF_NUM_EXPGRANT_EXPORTS', + 'SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS', + 'SPI_PERF_NUM_POS_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_POS_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_POS_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_POS_SA1SQ1_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS', + 'SPI_PERF_PIX_ALLOC_PEND_CNT', 'SPI_PERF_PS0_2_WAVE_GROUPS', + 'SPI_PERF_PS0_ACTIVE', 'SPI_PERF_PS0_BUSY', + 'SPI_PERF_PS0_CRAWLER_STALL', 'SPI_PERF_PS0_DEALLOC', + 'SPI_PERF_PS0_EVENT_WAVE', 'SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT', + 'SPI_PERF_PS0_OPT_WAVE', 'SPI_PERF_PS0_PRIM_BIN0', + 'SPI_PERF_PS0_PRIM_BIN1', 'SPI_PERF_PS0_WAVE', + 'SPI_PERF_PS0_WAVEID_STARVED', + 'SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS0_WINDOW_VALID', + 'SPI_PERF_PS1_2_WAVE_GROUPS', 'SPI_PERF_PS1_ACTIVE', + 'SPI_PERF_PS1_BUSY', 'SPI_PERF_PS1_CRAWLER_STALL', + 'SPI_PERF_PS1_DEALLOC', 'SPI_PERF_PS1_EVENT_WAVE', + 'SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT', 'SPI_PERF_PS1_OPT_WAVE', + 'SPI_PERF_PS1_PRIM_BIN0', 'SPI_PERF_PS1_PRIM_BIN1', + 'SPI_PERF_PS1_WAVE', 'SPI_PERF_PS1_WAVEID_STARVED', + 'SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS1_WINDOW_VALID', + 'SPI_PERF_PS2_2_WAVE_GROUPS', 'SPI_PERF_PS2_ACTIVE', + 'SPI_PERF_PS2_BUSY', 'SPI_PERF_PS2_CRAWLER_STALL', + 'SPI_PERF_PS2_DEALLOC', 'SPI_PERF_PS2_EVENT_WAVE', + 'SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT', 'SPI_PERF_PS2_OPT_WAVE', + 'SPI_PERF_PS2_PRIM_BIN0', 'SPI_PERF_PS2_PRIM_BIN1', + 'SPI_PERF_PS2_WAVE', 'SPI_PERF_PS2_WAVEID_STARVED', + 'SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS2_WINDOW_VALID', + 'SPI_PERF_PS3_2_WAVE_GROUPS', 'SPI_PERF_PS3_ACTIVE', + 'SPI_PERF_PS3_BUSY', 'SPI_PERF_PS3_CRAWLER_STALL', + 'SPI_PERF_PS3_DEALLOC', 'SPI_PERF_PS3_EVENT_WAVE', + 'SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT', 'SPI_PERF_PS3_OPT_WAVE', + 'SPI_PERF_PS3_PRIM_BIN0', 'SPI_PERF_PS3_PRIM_BIN1', + 'SPI_PERF_PS3_WAVE', 'SPI_PERF_PS3_WAVEID_STARVED', + 'SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS3_WINDOW_VALID', + 'SPI_PERF_PS_EXP_ALLOC', 'SPI_PERF_PS_EXP_ARB_CONFLICT', + 'SPI_PERF_PS_EXP_DONE', 'SPI_PERF_PS_PERS_UPD_FULL0', + 'SPI_PERF_PS_PERS_UPD_FULL1', 'SPI_PERF_PS_PWS_STALL', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_PS', 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 'SPI_PERF_RA_BAR_CU_FULL_CSN', 'SPI_PERF_RA_BAR_CU_FULL_HS', + 'SPI_PERF_RA_BULKY_CU_FULL_CSG', 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 'SPI_PERF_RA_CSC_UNDER_TUNNEL', 'SPI_PERF_RA_CSG_LOCK', + 'SPI_PERF_RA_CSN_LOCK', 'SPI_PERF_RA_GFX_UNDER_TUNNEL', + 'SPI_PERF_RA_GS_LOCK', 'SPI_PERF_RA_HS_LOCK', + 'SPI_PERF_RA_LDS_CU_FULL_CSG', 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 'SPI_PERF_RA_LDS_CU_FULL_GS', 'SPI_PERF_RA_LDS_CU_FULL_HS', + 'SPI_PERF_RA_LDS_CU_FULL_PS', 'SPI_PERF_RA_PIPE_REQ_BIN2', + 'SPI_PERF_RA_PRE_ALLOC_STALL', 'SPI_PERF_RA_REQ_NO_ALLOC', + 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', + 'SPI_PERF_RA_REQ_NO_ALLOC_GS', 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 'SPI_PERF_RA_REQ_NO_ALLOC_PS', 'SPI_PERF_RA_RES_STALL_CSG', + 'SPI_PERF_RA_RES_STALL_CSN', 'SPI_PERF_RA_RES_STALL_GS', + 'SPI_PERF_RA_RES_STALL_HS', 'SPI_PERF_RA_RES_STALL_PS', + 'SPI_PERF_RA_RSV_UPD', 'SPI_PERF_RA_TASK_REQ_BIN3', + 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 'SPI_PERF_RA_TMP_STALL_CSG', 'SPI_PERF_RA_TMP_STALL_CSN', + 'SPI_PERF_RA_TMP_STALL_GS', 'SPI_PERF_RA_TMP_STALL_HS', + 'SPI_PERF_RA_TMP_STALL_PS', 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 'SPI_PERF_RA_WR_CTL_FULL', 'SPI_PERF_RA_WVALLOC_STALL', + 'SPI_PERF_RA_WVLIM_STALL_CSG', 'SPI_PERF_RA_WVLIM_STALL_CSN', + 'SPI_PERF_RA_WVLIM_STALL_GS', 'SPI_PERF_RA_WVLIM_STALL_HS', + 'SPI_PERF_RA_WVLIM_STALL_PS', 'SPI_PERF_SWC_CSGN_WR', + 'SPI_PERF_SWC_CSN_WR', 'SPI_PERF_SWC_GS_WR', 'SPI_PERF_SWC_HS_WR', + 'SPI_PERF_SWC_PS_WR', 'SPI_PERF_VWC_CSGN_WR', + 'SPI_PERF_VWC_CSN_WR', 'SPI_PERF_VWC_ES_WR', 'SPI_PERF_VWC_GS_WR', + 'SPI_PERF_VWC_HS_WR', 'SPI_PERF_VWC_LS_WR', 'SPI_PERF_VWC_PS_WR', + 'SPI_PNT_SPRITE_OVERRIDE', 'SPI_PNT_SPRITE_SEL_0', + 'SPI_PNT_SPRITE_SEL_1', 'SPI_PNT_SPRITE_SEL_NONE', + 'SPI_PNT_SPRITE_SEL_S', 'SPI_PNT_SPRITE_SEL_T', + 'SPI_PS_LDS_GROUP_1', 'SPI_PS_LDS_GROUP_2', 'SPI_PS_LDS_GROUP_4', + 'SPI_PS_LDS_GROUP_SIZE', 'SPI_SAMPLE_CNTL', 'SPI_SHADER_1COMP', + 'SPI_SHADER_2COMP', 'SPI_SHADER_32_ABGR', 'SPI_SHADER_32_AR', + 'SPI_SHADER_32_GR', 'SPI_SHADER_32_R', 'SPI_SHADER_4COMP', + 'SPI_SHADER_4COMPRESS', 'SPI_SHADER_EX_FORMAT', + 'SPI_SHADER_FORMAT', 'SPI_SHADER_FP16_ABGR', 'SPI_SHADER_NONE', + 'SPI_SHADER_SINT16_ABGR', 'SPI_SHADER_SNORM16_ABGR', + 'SPI_SHADER_UINT16_ABGR', 'SPI_SHADER_UNORM16_ABGR', + 'SPI_SHADER_ZERO', 'SPM_PERFMON_STATE', 'SPRITE_EN', + 'SP_PERF_SEL_DST_BUF_ALLOC_STALL', + 'SP_PERF_SEL_DST_BUF_EVEN_DIRTY', 'SP_PERF_SEL_DST_BUF_ODD_DIRTY', + 'SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI', + 'SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS', 'SP_PERF_SEL_DUMMY_LAST', + 'SP_PERF_SEL_SRC_CACHE_HIT_B0', 'SP_PERF_SEL_SRC_CACHE_HIT_B1', + 'SP_PERF_SEL_SRC_CACHE_HIT_B2', 'SP_PERF_SEL_SRC_CACHE_HIT_B3', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B0', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B1', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B2', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B3', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3', + 'SP_PERF_SEL_VALU_COEXEC_WITH_TRANS', + 'SP_PERF_SEL_VALU_EXEC_MASK_CHANGE', + 'SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY', + 'SP_PERF_SEL_VALU_OPERAND', + 'SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF', + 'SP_PERF_SEL_VALU_PENDING_QUEUE_STALL', + 'SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL', 'SP_PERF_SEL_VALU_STALL', + 'SP_PERF_SEL_VALU_STALL_DST_STALL', + 'SP_PERF_SEL_VALU_STALL_SDST_FWD', + 'SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY', + 'SP_PERF_SEL_VALU_STALL_VDST_FWD', + 'SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY', + 'SP_PERF_SEL_VALU_VGPR_OPERAND', 'SP_PERF_SEL_VGPR_EXP_RD', + 'SP_PERF_SEL_VGPR_RD', 'SP_PERF_SEL_VGPR_SPI_WR', + 'SP_PERF_SEL_VGPR_TDLDS_DATA_WR', 'SP_PERF_SEL_VGPR_VMEM_RD', + 'SP_PERF_SEL_VGPR_WR', 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_DCACHE_FLAT_REQ', 'SQC_PERF_SEL_DCACHE_GCR', + 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', 'SQC_PERF_SEL_DCACHE_HITS', + 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_DCACHE_INVAL_INST', 'SQC_PERF_SEL_DCACHE_MISSES', + 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', 'SQC_PERF_SEL_DCACHE_REQ', + 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 'SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL', + 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DUMMY_LAST', 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_GCR', 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', 'SQC_PERF_SEL_ICACHE_HITS', + 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_ICACHE_INVAL_INST', 'SQC_PERF_SEL_ICACHE_MISSES', + 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', 'SQC_PERF_SEL_ICACHE_REQ', + 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 'SQC_PERF_SEL_LDS_ADDR_STALL', 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL', + 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', 'SQC_PERF_SEL_LDS_VGPR_BUSY', + 'SQC_PERF_SEL_SQ_DCACHE_REQS', 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', 'SQC_PERF_SEL_TC_INST_REQ', + 'SQC_PERF_SEL_TC_REQ', 'SQC_PERF_SEL_TC_STALL', + 'SQC_PERF_SEL_TC_STARVE', 'SQC_PERF_SEL_TD_VGPR_BUSY', + 'SQDEC_BEGIN', 'SQDEC_END', 'SQGFXUDEC_BEGIN', 'SQGFXUDEC_END', + 'SQG_PERF_SEL', 'SQG_PERF_SEL_ACCUM_PREV', + 'SQG_PERF_SEL_BUSY_CYCLES', 'SQG_PERF_SEL_CYCLES', + 'SQG_PERF_SEL_DUMMY_LAST', 'SQG_PERF_SEL_EVENTS', + 'SQG_PERF_SEL_EXP_BUS0_BUSY', 'SQG_PERF_SEL_EXP_BUS1_BUSY', + 'SQG_PERF_SEL_EXP_REQ0_BUS_BUSY', + 'SQG_PERF_SEL_EXP_REQ1_BUS_BUSY', 'SQG_PERF_SEL_ITEMS', + 'SQG_PERF_SEL_LEVEL_WAVES', 'SQG_PERF_SEL_MSG', + 'SQG_PERF_SEL_MSG_BUS_BUSY', 'SQG_PERF_SEL_MSG_INTERRUPT', + 'SQG_PERF_SEL_NONE', 'SQG_PERF_SEL_PS_QUADS', + 'SQG_PERF_SEL_TTRACE_INFLIGHT_REQS', + 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', 'SQG_PERF_SEL_TTRACE_REQS', + 'SQG_PERF_SEL_TTRACE_STALL', 'SQG_PERF_SEL_WAVE32_ITEMS', + 'SQG_PERF_SEL_WAVE64_ITEMS', 'SQG_PERF_SEL_WAVES', + 'SQG_PERF_SEL_WAVES_32', 'SQG_PERF_SEL_WAVES_64', + 'SQG_PERF_SEL_WAVES_EQ_32', 'SQG_PERF_SEL_WAVES_EQ_64', + 'SQG_PERF_SEL_WAVES_INITIAL_PREFETCH', 'SQG_PERF_SEL_WAVES_LT_16', + 'SQG_PERF_SEL_WAVES_LT_32', 'SQG_PERF_SEL_WAVES_LT_48', + 'SQG_PERF_SEL_WAVES_LT_64', 'SQG_PERF_SEL_WAVES_RESTORED', + 'SQG_PERF_SEL_WAVES_SAVED', 'SQG_PERF_SEL_WAVE_CYCLES', + 'SQIND_GLOBAL_REGS_OFFSET', 'SQIND_GLOBAL_REGS_SIZE', + 'SQIND_LOCAL_REGS_OFFSET', 'SQIND_LOCAL_REGS_SIZE', + 'SQIND_WAVE_HWREGS_OFFSET', 'SQIND_WAVE_HWREGS_SIZE', + 'SQIND_WAVE_SGPRS_OFFSET', 'SQIND_WAVE_SGPRS_SIZE', + 'SQIND_WAVE_VGPRS_OFFSET', 'SQIND_WAVE_VGPRS_SIZE', + 'SQPERFDDEC_BEGIN', 'SQPERFDDEC_END', 'SQPERFSDEC_BEGIN', + 'SQPERFSDEC_END', 'SQPWRDEC_BEGIN', 'SQPWRDEC_END', + 'SQ_CAC_POWER_ALU_BUSY', 'SQ_CAC_POWER_GPR_RD', + 'SQ_CAC_POWER_GPR_WR', 'SQ_CAC_POWER_LDS_BUSY', + 'SQ_CAC_POWER_SEL', 'SQ_CAC_POWER_TEX_BUSY', 'SQ_CAC_POWER_VALU', + 'SQ_CAC_POWER_VALU0', 'SQ_CAC_POWER_VALU1', 'SQ_CAC_POWER_VALU2', + 'SQ_DISPATCHER_GFX_CNT_PER_RING', 'SQ_DISPATCHER_GFX_MIN', + 'SQ_EDC_FUE_CNTL_LDS', 'SQ_EDC_FUE_CNTL_SIMD0', + 'SQ_EDC_FUE_CNTL_SIMD1', 'SQ_EDC_FUE_CNTL_SIMD2', + 'SQ_EDC_FUE_CNTL_SIMD3', 'SQ_EDC_FUE_CNTL_SQ', + 'SQ_EDC_FUE_CNTL_TA', 'SQ_EDC_FUE_CNTL_TCP', 'SQ_EDC_FUE_CNTL_TD', + 'SQ_EDC_INFO_SOURCE', 'SQ_EDC_INFO_SOURCE_GDS', + 'SQ_EDC_INFO_SOURCE_INST', 'SQ_EDC_INFO_SOURCE_INVALID', + 'SQ_EDC_INFO_SOURCE_LDS', 'SQ_EDC_INFO_SOURCE_SGPR', + 'SQ_EDC_INFO_SOURCE_TA', 'SQ_EDC_INFO_SOURCE_VGPR', + 'SQ_EX_MODE_EXCP_ADDR_WATCH0', 'SQ_EX_MODE_EXCP_DIV0', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH1', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH2', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH3', 'SQ_EX_MODE_EXCP_INEXACT', + 'SQ_EX_MODE_EXCP_INPUT_DENORM', 'SQ_EX_MODE_EXCP_INT_DIV0', + 'SQ_EX_MODE_EXCP_INVALID', 'SQ_EX_MODE_EXCP_MEM_VIOL', + 'SQ_EX_MODE_EXCP_OVERFLOW', 'SQ_EX_MODE_EXCP_UNDERFLOW', + 'SQ_EX_MODE_EXCP_VALU_BASE', 'SQ_EX_MODE_EXCP_VALU_SIZE', + 'SQ_GFXDEC_BEGIN', 'SQ_GFXDEC_END', 'SQ_GFXDEC_STATE_ID_SHIFT', + 'SQ_IBUF_IB_DRET', 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 'SQ_IBUF_IB_EMPTY_WAIT_GNT', 'SQ_IBUF_IB_IDLE', + 'SQ_IBUF_IB_INI_WAIT_DRET', 'SQ_IBUF_IB_INI_WAIT_GNT', + 'SQ_IBUF_IB_LE_4DW', 'SQ_IBUF_IB_WAIT_DRET', 'SQ_IBUF_ST', + 'SQ_IMG_FILTER_MODE_BLEND', 'SQ_IMG_FILTER_MODE_MAX', + 'SQ_IMG_FILTER_MODE_MIN', 'SQ_IMG_FILTER_TYPE', 'SQ_IND_CMD_CMD', + 'SQ_IND_CMD_CMD_KILL', 'SQ_IND_CMD_CMD_NULL', + 'SQ_IND_CMD_CMD_SAVECTX', 'SQ_IND_CMD_CMD_SETFATALHALT', + 'SQ_IND_CMD_CMD_SETHALT', 'SQ_IND_CMD_CMD_SET_SPI_PRIO', + 'SQ_IND_CMD_CMD_SINGLE_STEP', 'SQ_IND_CMD_CMD_TRAP', + 'SQ_IND_CMD_CMD_TRAP_AFTER_INST', 'SQ_IND_CMD_MODE', + 'SQ_IND_CMD_MODE_BROADCAST', 'SQ_IND_CMD_MODE_BROADCAST_ME', + 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', 'SQ_IND_CMD_MODE_SINGLE', + 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', 'SQ_INST_STR_IB_WAVE_NORML', + 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', 'SQ_INST_STR_ST', + 'SQ_INST_TYPE', 'SQ_INST_TYPE_BARRIER', + 'SQ_INST_TYPE_BRANCH_NOT_TAKEN', 'SQ_INST_TYPE_BRANCH_TAKEN', + 'SQ_INST_TYPE_EXP', 'SQ_INST_TYPE_JUMP', 'SQ_INST_TYPE_LDS', + 'SQ_INST_TYPE_LDS_DIRECT', 'SQ_INST_TYPE_MSG', + 'SQ_INST_TYPE_NONE', 'SQ_INST_TYPE_OTHER', 'SQ_INST_TYPE_SCALAR', + 'SQ_INST_TYPE_TEX', 'SQ_INST_TYPE_VALU', 'SQ_LLC_0', 'SQ_LLC_1', + 'SQ_LLC_BYPASS', 'SQ_LLC_CTL', 'SQ_LLC_RSVD_2', + 'SQ_MAX_PGM_SGPRS', 'SQ_MAX_PGM_VGPRS', 'SQ_NON_EVENT', + 'SQ_NO_INST_ISSUE', 'SQ_NO_INST_ISSUE_ALU_DEP', + 'SQ_NO_INST_ISSUE_BARRIER_WAIT', 'SQ_NO_INST_ISSUE_NO_ARB_WIN', + 'SQ_NO_INST_ISSUE_NO_INSTS', 'SQ_NO_INST_ISSUE_OTHER', + 'SQ_NO_INST_ISSUE_SLEEP_WAIT', 'SQ_NO_INST_ISSUE_S_WAITCNT', + 'SQ_OOB_COMPLETE', 'SQ_OOB_INDEX_AND_OFFSET', 'SQ_OOB_INDEX_ONLY', + 'SQ_OOB_NUM_RECORDS_0', 'SQ_OOB_SELECT', 'SQ_PERF_SEL', + 'SQ_PERF_SEL_ACCUM_PREV', 'SQ_PERF_SEL_BUSY_CYCLES', + 'SQ_PERF_SEL_CYCLES', 'SQ_PERF_SEL_DUMMY_END', + 'SQ_PERF_SEL_DUMMY_LAST', 'SQ_PERF_SEL_EVENTS', + 'SQ_PERF_SEL_EXP_BUS0_BUSY', 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 'SQ_PERF_SEL_IFETCH_LEVEL', 'SQ_PERF_SEL_IFETCH_REQS', + 'SQ_PERF_SEL_INSTS_ALL', 'SQ_PERF_SEL_INSTS_BRANCH', + 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', + 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN_HIT_IS', + 'SQ_PERF_SEL_INSTS_DELAY_ALU', + 'SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32', 'SQ_PERF_SEL_INSTS_EXP', + 'SQ_PERF_SEL_INSTS_EXP_GDS', 'SQ_PERF_SEL_INSTS_FLAT', + 'SQ_PERF_SEL_INSTS_GDS', 'SQ_PERF_SEL_INSTS_INTERNAL', + 'SQ_PERF_SEL_INSTS_LDS', 'SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD', + 'SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD', 'SQ_PERF_SEL_INSTS_SALU', + 'SQ_PERF_SEL_INSTS_SENDMSG', 'SQ_PERF_SEL_INSTS_SMEM', + 'SQ_PERF_SEL_INSTS_SMEM_NORM', 'SQ_PERF_SEL_INSTS_TEX', + 'SQ_PERF_SEL_INSTS_TEX_LOAD', 'SQ_PERF_SEL_INSTS_TEX_STORE', + 'SQ_PERF_SEL_INSTS_VALU', 'SQ_PERF_SEL_INSTS_VALU_1_PASS', + 'SQ_PERF_SEL_INSTS_VALU_2_PASS', 'SQ_PERF_SEL_INSTS_VALU_4_PASS', + 'SQ_PERF_SEL_INSTS_VALU_DP', + 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64', + 'SQ_PERF_SEL_INSTS_VALU_TRANS', 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 'SQ_PERF_SEL_INSTS_VALU_VINTERP', + 'SQ_PERF_SEL_INSTS_VALU_WAVE32_VINTERP', + 'SQ_PERF_SEL_INSTS_WAVE32', 'SQ_PERF_SEL_INSTS_WAVE32_FLAT', + 'SQ_PERF_SEL_INSTS_WAVE32_LDS', + 'SQ_PERF_SEL_INSTS_WAVE32_LDS_PARAM_LOAD', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX_LOAD', + 'SQ_PERF_SEL_INSTS_WAVE32_TEX_STORE', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_WAVE32_VALU_TRANS32', + 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', 'SQ_PERF_SEL_INST_CYCLES_EXP', + 'SQ_PERF_SEL_INST_CYCLES_EXP_GDS', 'SQ_PERF_SEL_INST_CYCLES_FLAT', + 'SQ_PERF_SEL_INST_CYCLES_GDS', 'SQ_PERF_SEL_INST_CYCLES_LDS', + 'SQ_PERF_SEL_INST_CYCLES_TEX', 'SQ_PERF_SEL_INST_CYCLES_VALU', + 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 'SQ_PERF_SEL_INST_LEVEL_EXP', 'SQ_PERF_SEL_INST_LEVEL_GDS', + 'SQ_PERF_SEL_INST_LEVEL_LDS', 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', 'SQ_PERF_SEL_ITEMS', + 'SQ_PERF_SEL_ITEMS_MAX_VALU', 'SQ_PERF_SEL_ITEMS_VALU', + 'SQ_PERF_SEL_ITEM_CYCLES_VALU', 'SQ_PERF_SEL_ITEM_CYCLES_VMEM', + 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_LEVEL_WAVES', 'SQ_PERF_SEL_MSG', + 'SQ_PERF_SEL_MSG_BUS_BUSY', 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 'SQ_PERF_SEL_MSG_INTERRUPT', 'SQ_PERF_SEL_NONE', + 'SQ_PERF_SEL_NONE2', 'SQ_PERF_SEL_OVERFLOW_PREV', + 'SQ_PERF_SEL_PS_QUADS', 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 'SQ_PERF_SEL_SALU_PIPE_STALL', 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_SMEM_DCACHE_FIFO_FULL_STALL', + 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 'SQ_PERF_SEL_SP_CONST_CYCLES', + 'SQ_PERF_SEL_SP_CONST_STALL_CYCLES', 'SQ_PERF_SEL_USER0', + 'SQ_PERF_SEL_USER1', 'SQ_PERF_SEL_USER10', 'SQ_PERF_SEL_USER11', + 'SQ_PERF_SEL_USER12', 'SQ_PERF_SEL_USER13', 'SQ_PERF_SEL_USER14', + 'SQ_PERF_SEL_USER15', 'SQ_PERF_SEL_USER2', 'SQ_PERF_SEL_USER3', + 'SQ_PERF_SEL_USER4', 'SQ_PERF_SEL_USER5', 'SQ_PERF_SEL_USER6', + 'SQ_PERF_SEL_USER7', 'SQ_PERF_SEL_USER8', 'SQ_PERF_SEL_USER9', + 'SQ_PERF_SEL_USER_LEVEL0', 'SQ_PERF_SEL_USER_LEVEL1', + 'SQ_PERF_SEL_USER_LEVEL10', 'SQ_PERF_SEL_USER_LEVEL11', + 'SQ_PERF_SEL_USER_LEVEL12', 'SQ_PERF_SEL_USER_LEVEL13', + 'SQ_PERF_SEL_USER_LEVEL14', 'SQ_PERF_SEL_USER_LEVEL15', + 'SQ_PERF_SEL_USER_LEVEL2', 'SQ_PERF_SEL_USER_LEVEL3', + 'SQ_PERF_SEL_USER_LEVEL4', 'SQ_PERF_SEL_USER_LEVEL5', + 'SQ_PERF_SEL_USER_LEVEL6', 'SQ_PERF_SEL_USER_LEVEL7', + 'SQ_PERF_SEL_USER_LEVEL8', 'SQ_PERF_SEL_USER_LEVEL9', + 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 'SQ_PERF_SEL_VALU_RETURN_SDST', + 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_VALU_STARVE', 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', 'SQ_PERF_SEL_VMEM_BUS_STALL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', + 'SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT', + 'SQ_PERF_SEL_WAIT_ANY', 'SQ_PERF_SEL_WAIT_BARRIER', + 'SQ_PERF_SEL_WAIT_CNT_ANY', 'SQ_PERF_SEL_WAIT_CNT_EXP', + 'SQ_PERF_SEL_WAIT_CNT_LGKM', 'SQ_PERF_SEL_WAIT_CNT_VMVS', + 'SQ_PERF_SEL_WAIT_DELAY_ALU', 'SQ_PERF_SEL_WAIT_DEPCTR', + 'SQ_PERF_SEL_WAIT_EXP_ALLOC', 'SQ_PERF_SEL_WAIT_IFETCH', + 'SQ_PERF_SEL_WAIT_INST_ANY', 'SQ_PERF_SEL_WAIT_INST_BR_MSG', + 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', 'SQ_PERF_SEL_WAIT_INST_FLAT', + 'SQ_PERF_SEL_WAIT_INST_LDS', 'SQ_PERF_SEL_WAIT_INST_SCA', + 'SQ_PERF_SEL_WAIT_INST_TEX', 'SQ_PERF_SEL_WAIT_INST_VALU', + 'SQ_PERF_SEL_WAIT_INST_VMEM', 'SQ_PERF_SEL_WAIT_OTHER', + 'SQ_PERF_SEL_WAIT_SLEEP', 'SQ_PERF_SEL_WAIT_TTRACE', + 'SQ_PERF_SEL_WAVE32_INSTS', 'SQ_PERF_SEL_WAVE32_INSTS_EXP_GDS', + 'SQ_PERF_SEL_WAVE32_ITEMS', 'SQ_PERF_SEL_WAVE64_HALF_SKIP', + 'SQ_PERF_SEL_WAVE64_INSTS', 'SQ_PERF_SEL_WAVE64_ITEMS', + 'SQ_PERF_SEL_WAVES', 'SQ_PERF_SEL_WAVES_32', + 'SQ_PERF_SEL_WAVES_64', 'SQ_PERF_SEL_WAVES_EQ_32', + 'SQ_PERF_SEL_WAVES_EQ_64', 'SQ_PERF_SEL_WAVES_INITIAL_PREFETCH', + 'SQ_PERF_SEL_WAVES_LT_16', 'SQ_PERF_SEL_WAVES_LT_32', + 'SQ_PERF_SEL_WAVES_LT_48', 'SQ_PERF_SEL_WAVES_LT_64', + 'SQ_PERF_SEL_WAVES_RESTORED', 'SQ_PERF_SEL_WAVES_SAVED', + 'SQ_PERF_SEL_WAVE_CYCLES', 'SQ_PERF_SEL_WAVE_READY', + 'SQ_ROUND_MINUS_INFINITY', 'SQ_ROUND_MODE', + 'SQ_ROUND_NEAREST_EVEN', 'SQ_ROUND_PLUS_INFINITY', + 'SQ_ROUND_TO_ZERO', 'SQ_RSRC_BUF', 'SQ_RSRC_BUF_RSVD_1', + 'SQ_RSRC_BUF_RSVD_2', 'SQ_RSRC_BUF_RSVD_3', 'SQ_RSRC_BUF_TYPE', + 'SQ_RSRC_FLAT', 'SQ_RSRC_FLAT_RSVD_0', 'SQ_RSRC_FLAT_RSVD_2', + 'SQ_RSRC_FLAT_RSVD_3', 'SQ_RSRC_FLAT_TYPE', 'SQ_RSRC_IMG_1D', + 'SQ_RSRC_IMG_1D_ARRAY', 'SQ_RSRC_IMG_2D', 'SQ_RSRC_IMG_2D_ARRAY', + 'SQ_RSRC_IMG_2D_MSAA', 'SQ_RSRC_IMG_2D_MSAA_ARRAY', + 'SQ_RSRC_IMG_3D', 'SQ_RSRC_IMG_CUBE', 'SQ_RSRC_IMG_RSVD_0', + 'SQ_RSRC_IMG_RSVD_1', 'SQ_RSRC_IMG_RSVD_2', 'SQ_RSRC_IMG_RSVD_3', + 'SQ_RSRC_IMG_RSVD_4', 'SQ_RSRC_IMG_RSVD_5', 'SQ_RSRC_IMG_RSVD_6', + 'SQ_RSRC_IMG_RSVD_7', 'SQ_RSRC_IMG_TYPE', 'SQ_SEL_0', 'SQ_SEL_1', + 'SQ_SEL_N_BC_1', 'SQ_SEL_RESERVED_1', 'SQ_SEL_W', 'SQ_SEL_X', + 'SQ_SEL_XYZW01', 'SQ_SEL_Y', 'SQ_SEL_Z', 'SQ_TEX_ANISO_RATIO', + 'SQ_TEX_ANISO_RATIO_1', 'SQ_TEX_ANISO_RATIO_16', + 'SQ_TEX_ANISO_RATIO_2', 'SQ_TEX_ANISO_RATIO_4', + 'SQ_TEX_ANISO_RATIO_8', 'SQ_TEX_BORDER_COLOR', + 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 'SQ_TEX_BORDER_COLOR_REGISTER', 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 'SQ_TEX_CLAMP', 'SQ_TEX_CLAMP_BORDER', 'SQ_TEX_CLAMP_HALF_BORDER', + 'SQ_TEX_CLAMP_LAST_TEXEL', 'SQ_TEX_DEPTH_COMPARE', + 'SQ_TEX_DEPTH_COMPARE_ALWAYS', 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 'SQ_TEX_DEPTH_COMPARE_GREATER', + 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', 'SQ_TEX_DEPTH_COMPARE_LESS', + 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', 'SQ_TEX_DEPTH_COMPARE_NEVER', + 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', 'SQ_TEX_MIP_FILTER', + 'SQ_TEX_MIP_FILTER_LINEAR', 'SQ_TEX_MIP_FILTER_NONE', + 'SQ_TEX_MIP_FILTER_POINT', 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', + 'SQ_TEX_MIRROR', 'SQ_TEX_MIRROR_ONCE_BORDER', + 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 'SQ_TEX_WRAP', 'SQ_TEX_XY_FILTER', + 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', 'SQ_TEX_XY_FILTER_ANISO_POINT', + 'SQ_TEX_XY_FILTER_BILINEAR', 'SQ_TEX_XY_FILTER_POINT', + 'SQ_TEX_Z_FILTER', 'SQ_TEX_Z_FILTER_LINEAR', + 'SQ_TEX_Z_FILTER_NONE', 'SQ_TEX_Z_FILTER_POINT', + 'SQ_TT_INST_EXCLUDE_EXPGNT234_BIT', + 'SQ_TT_INST_EXCLUDE_EXPGNT234_SHIFT', + 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_BIT', + 'SQ_TT_INST_EXCLUDE_VMEM_OTHER_SIMD_SHIFT', 'SQ_TT_MODE', + 'SQ_TT_MODE_DETAIL', 'SQ_TT_MODE_GLOBAL', 'SQ_TT_MODE_OFF', + 'SQ_TT_MODE_ON', 'SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_BIT', + 'SQ_TT_REG_EXCLUDE_CP_ME_MC_RADDR_SHIFT', + 'SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_BIT', + 'SQ_TT_REG_EXCLUDE_GRBM_COMPUTE_EXCLUDE_SHIFT', + 'SQ_TT_REG_EXCLUDE_USER_DATA_BIT', + 'SQ_TT_REG_EXCLUDE_USER_DATA_SHIFT', 'SQ_TT_RT_FREQ', + 'SQ_TT_RT_FREQ_1024_CLK', 'SQ_TT_RT_FREQ_4096_CLK', + 'SQ_TT_RT_FREQ_NEVER', 'SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_EVENT_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_INST_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT', 'SQ_TT_TOKEN_EXCLUDE_REG_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_UTILCTR_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_WAVEALLOC_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_WAVERDY_SHIFT', + 'SQ_TT_TOKEN_EXCLUDE_WAVESTARTEND_SHIFT', + 'SQ_TT_TOKEN_MASK_ALL_BIT', 'SQ_TT_TOKEN_MASK_ALL_SHIFT', + 'SQ_TT_TOKEN_MASK_COMP_BIT', 'SQ_TT_TOKEN_MASK_COMP_SHIFT', + 'SQ_TT_TOKEN_MASK_CONFIG_BIT', 'SQ_TT_TOKEN_MASK_CONFIG_SHIFT', + 'SQ_TT_TOKEN_MASK_CONTEXT_BIT', 'SQ_TT_TOKEN_MASK_CONTEXT_SHIFT', + 'SQ_TT_TOKEN_MASK_GFXUDEC_BIT', 'SQ_TT_TOKEN_MASK_GFXUDEC_SHIFT', + 'SQ_TT_TOKEN_MASK_INST_EXCLUDE', + 'SQ_TT_TOKEN_MASK_INST_EXCLUDE_SHIFT', + 'SQ_TT_TOKEN_MASK_REG_EXCLUDE', + 'SQ_TT_TOKEN_MASK_REG_EXCLUDE_SHIFT', + 'SQ_TT_TOKEN_MASK_REG_INCLUDE', + 'SQ_TT_TOKEN_MASK_REG_INCLUDE_SHIFT', 'SQ_TT_TOKEN_MASK_RSVD_BIT', + 'SQ_TT_TOKEN_MASK_RSVD_SHIFT', 'SQ_TT_TOKEN_MASK_SHDEC_BIT', + 'SQ_TT_TOKEN_MASK_SHDEC_SHIFT', 'SQ_TT_TOKEN_MASK_SQDEC_BIT', + 'SQ_TT_TOKEN_MASK_SQDEC_SHIFT', + 'SQ_TT_TOKEN_MASK_TOKEN_EXCLUDE_SHIFT', 'SQ_TT_UTIL_TIMER', + 'SQ_TT_UTIL_TIMER_100_CLK', 'SQ_TT_UTIL_TIMER_250_CLK', + 'SQ_TT_WAVESTART_MODE', 'SQ_TT_WAVESTART_MODE_ALLOC', + 'SQ_TT_WAVESTART_MODE_PBB_ID', 'SQ_TT_WAVESTART_MODE_SHORT', + 'SQ_TT_WTYPE_INCLUDE', 'SQ_TT_WTYPE_INCLUDE_CS_BIT', + 'SQ_TT_WTYPE_INCLUDE_CS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_GS_BIT', + 'SQ_TT_WTYPE_INCLUDE_GS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_HS_BIT', + 'SQ_TT_WTYPE_INCLUDE_HS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_PS_BIT', + 'SQ_TT_WTYPE_INCLUDE_PS_SHIFT', 'SQ_TT_WTYPE_INCLUDE_RSVD0_BIT', + 'SQ_TT_WTYPE_INCLUDE_RSVD0_SHIFT', + 'SQ_TT_WTYPE_INCLUDE_RSVD1_BIT', + 'SQ_TT_WTYPE_INCLUDE_RSVD1_SHIFT', + 'SQ_TT_WTYPE_INCLUDE_RSVD2_BIT', + 'SQ_TT_WTYPE_INCLUDE_RSVD2_SHIFT', 'SQ_TT_WTYPE_INCLUDE_SHIFT', + 'SQ_WATCH_MODES', 'SQ_WATCH_MODE_ALL', 'SQ_WATCH_MODE_ATOMIC', + 'SQ_WATCH_MODE_NONREAD', 'SQ_WATCH_MODE_READ', + 'SQ_WAVE_FWD_PROG_INTERVAL', 'SQ_WAVE_FWD_PROG_INTERVAL_1024', + 'SQ_WAVE_FWD_PROG_INTERVAL_256', 'SQ_WAVE_FWD_PROG_INTERVAL_4096', + 'SQ_WAVE_FWD_PROG_INTERVAL_NEVER', 'SQ_WAVE_IB_DEP_HOLD_CNT_SIZE', + 'SQ_WAVE_IB_DEP_LDS_DIR_SIZE', 'SQ_WAVE_IB_DEP_SA_EXEC_SIZE', + 'SQ_WAVE_IB_DEP_SA_M0_SIZE', 'SQ_WAVE_IB_DEP_SA_SDST_SIZE', + 'SQ_WAVE_IB_DEP_VA_EXEC_SIZE', 'SQ_WAVE_IB_DEP_VA_SDST_SIZE', + 'SQ_WAVE_IB_DEP_VA_SSRC_SIZE', 'SQ_WAVE_IB_DEP_VA_VCC_SIZE', + 'SQ_WAVE_IB_DEP_VA_VDST_SIZE', 'SQ_WAVE_IB_DEP_VM_VSRC_SIZE', + 'SQ_WAVE_IB_ECC_CLEAN', 'SQ_WAVE_IB_ECC_ERR_CONTINUE', + 'SQ_WAVE_IB_ECC_ERR_HALT', 'SQ_WAVE_IB_ECC_ST', + 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', 'SQ_WAVE_SCHED_MODES', + 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST', 'SQ_WAVE_SCHED_MODE_EXPERT', + 'SQ_WAVE_SCHED_MODE_NORMAL', 'SQ_WAVE_TYPE', 'SQ_WAVE_TYPE_CS', + 'SQ_WAVE_TYPE_GS', 'SQ_WAVE_TYPE_HS', 'SQ_WAVE_TYPE_PS', + 'SQ_WAVE_TYPE_PS0', 'SQ_WAVE_TYPE_PS1', 'SQ_WAVE_TYPE_PS2', + 'SQ_WAVE_TYPE_PS3', 'SQ_WAVE_TYPE_RSVD0', 'SQ_WAVE_TYPE_RSVD1', + 'SQ_WAVE_TYPE_RSVD2', 'SRCID_NONSECURE_CP', + 'SRCID_NONSECURE_CP_RCIU', 'SRCID_RLC', 'SRCID_RLCV', + 'SRCID_SECURE_CP', 'SRCID_SECURE_CP_RCIU', 'STALL', + 'STENCIL_ADD_CLAMP', 'STENCIL_ADD_WRAP', 'STENCIL_AND', + 'STENCIL_INVERT', 'STENCIL_KEEP', 'STENCIL_NAND', 'STENCIL_NOR', + 'STENCIL_ONES', 'STENCIL_OR', 'STENCIL_REPLACE_OP', + 'STENCIL_REPLACE_TEST', 'STENCIL_SUB_CLAMP', 'STENCIL_SUB_WRAP', + 'STENCIL_XNOR', 'STENCIL_XOR', 'STENCIL_ZERO', + 'STREAM_0_SYNCHRONIZATION', + 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_10_SYNCHRONIZATION', + 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION', + 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION', + 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION', + 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION', + 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION', + 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_1_SYNCHRONIZATION', + 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_2_SYNCHRONIZATION', + 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_3_SYNCHRONIZATION', + 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_4_SYNCHRONIZATION', + 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_5_SYNCHRONIZATION', + 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION', + 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION', + 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION', + 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION', + 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_DSC_444_RGB', 'STREAM_DSC_DISABLE', + 'STREAM_DSC_NATIVE_422_420', 'STREAM_ODM_COMBINE_1_SEGMENT', + 'STREAM_ODM_COMBINE_2_SEGMENT', 'STREAM_ODM_COMBINE_4_SEGMENT', + 'STREAM_ODM_COMBINE_RESERVED', 'STREAM_PIXEL_ENCODING_420', + 'STREAM_PIXEL_ENCODING_422', 'STREAM_PIXEL_ENCODING_444_RGB', + 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'STRM_PERFMON_STATE_RESERVED_3', + 'STRM_PERFMON_STATE_START_COUNTING', + 'STRM_PERFMON_STATE_STOP_COUNTING', 'SURFACE_DCC', + 'SURFACE_DCC_BLOCK_IS_IND_128B', 'SURFACE_DCC_BLOCK_IS_IND_64B', + 'SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL', + 'SURFACE_DCC_BLOCK_IS_UNCONSTRAINED', 'SURFACE_DCC_IND_128B', + 'SURFACE_DCC_IND_64B', 'SURFACE_DCC_IND_BLK', + 'SURFACE_DCC_IS_IND_128B', 'SURFACE_DCC_IS_IND_64B', + 'SURFACE_DCC_IS_NOT_IND_128B', 'SURFACE_DCC_IS_NOT_IND_64B', + 'SURFACE_FLIP_AWAY_INT_LEVEL', 'SURFACE_FLIP_AWAY_INT_PULSE', + 'SURFACE_FLIP_AWAY_INT_TYPE', 'SURFACE_FLIP_EXEC_DEBUG_MODE', + 'SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE', + 'SURFACE_FLIP_EXEC_NORMAL_MODE', 'SURFACE_FLIP_INT_LEVEL', + 'SURFACE_FLIP_INT_PULSE', 'SURFACE_FLIP_INT_TYPE', + 'SURFACE_FLIP_IN_STEREOSYNC', 'SURFACE_FLIP_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', + 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLED', + 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 'SURFACE_FLIP_TYPE', 'SURFACE_FLIP_VUPDATE_SKIP_NUM', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', 'SURFACE_INUSE_IS_LATCHED', + 'SURFACE_INUSE_IS_NOT_LATCHED', 'SURFACE_INUSE_RAED_NO_LATCH', + 'SURFACE_IS_DCC', 'SURFACE_IS_NOT_DCC', 'SURFACE_IS_NOT_TMZ', + 'SURFACE_IS_TMZ', 'SURFACE_I_FLIP', 'SURFACE_PIXEL_FORMAT', + 'SURFACE_TMZ', 'SURFACE_UPDATE_IS_LOCKED', + 'SURFACE_UPDATE_IS_UNLOCKED', 'SURFACE_UPDATE_LOCK', + 'SURFACE_V_FLIP', 'SU_PERFCNT_SEL', 'SWATH_HEIGHT', + 'SWATH_HEIGHT_16L', 'SWATH_HEIGHT_1L', 'SWATH_HEIGHT_2L', + 'SWATH_HEIGHT_4L', 'SWATH_HEIGHT_8L', 'SX_BLEND_OPT', + 'SX_CB_RAT_ACK_REQUEST', 'SX_DOWNCONVERT_FORMAT', + 'SX_OPT_COMB_FCN', 'SX_PERFCOUNTER_VALS', 'SX_PERF_SEL_CLOCK', + 'SX_PERF_SEL_CLOCK_DROP_STALL', 'SX_PERF_SEL_COL_BUSY', + 'SX_PERF_SEL_DB0_4X2_DISCARD', 'SX_PERF_SEL_DB0_END_OF_WAVE', + 'SX_PERF_SEL_DB0_HALF_QUADS', 'SX_PERF_SEL_DB0_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB0_PIXELS', + 'SX_PERF_SEL_DB0_PIXEL_IDLE', 'SX_PERF_SEL_DB0_PIXEL_STALL', + 'SX_PERF_SEL_DB0_PRED_PIXELS', 'SX_PERF_SEL_DB0_SIZE', + 'SX_PERF_SEL_DB1_4X2_DISCARD', 'SX_PERF_SEL_DB1_END_OF_WAVE', + 'SX_PERF_SEL_DB1_HALF_QUADS', 'SX_PERF_SEL_DB1_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB1_PIXELS', + 'SX_PERF_SEL_DB1_PIXEL_IDLE', 'SX_PERF_SEL_DB1_PIXEL_STALL', + 'SX_PERF_SEL_DB1_PRED_PIXELS', 'SX_PERF_SEL_DB1_SIZE', + 'SX_PERF_SEL_DB2_4X2_DISCARD', 'SX_PERF_SEL_DB2_END_OF_WAVE', + 'SX_PERF_SEL_DB2_HALF_QUADS', 'SX_PERF_SEL_DB2_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB2_PIXELS', + 'SX_PERF_SEL_DB2_PIXEL_IDLE', 'SX_PERF_SEL_DB2_PIXEL_STALL', + 'SX_PERF_SEL_DB2_PRED_PIXELS', 'SX_PERF_SEL_DB2_SIZE', + 'SX_PERF_SEL_DB3_4X2_DISCARD', 'SX_PERF_SEL_DB3_END_OF_WAVE', + 'SX_PERF_SEL_DB3_HALF_QUADS', 'SX_PERF_SEL_DB3_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB3_PIXELS', + 'SX_PERF_SEL_DB3_PIXEL_IDLE', 'SX_PERF_SEL_DB3_PIXEL_STALL', + 'SX_PERF_SEL_DB3_PRED_PIXELS', 'SX_PERF_SEL_DB3_SIZE', + 'SX_PERF_SEL_GATE_EN1', 'SX_PERF_SEL_GATE_EN2', + 'SX_PERF_SEL_GATE_EN3', 'SX_PERF_SEL_GATE_EN4', + 'SX_PERF_SEL_GATE_EN5', 'SX_PERF_SEL_GATE_EN6', + 'SX_PERF_SEL_GATE_EN7', 'SX_PERF_SEL_GATE_EN8', + 'SX_PERF_SEL_IDX_BUSY', 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 'SX_PERF_SEL_IDX_REQ', 'SX_PERF_SEL_IDX_REQ_LATENCY', + 'SX_PERF_SEL_IDX_RET', 'SX_PERF_SEL_IDX_SCBD_STALL', + 'SX_PERF_SEL_IDX_STALL_CYCLES', 'SX_PERF_SEL_PA_IDLE_CYCLES', + 'SX_PERF_SEL_PA_POS', 'SX_PERF_SEL_PA_POS_BANK_CONF', + 'SX_PERF_SEL_PA_REQ', 'SX_PERF_SEL_PA_REQ_LATENCY', + 'SX_PERF_SEL_POS_BUSY', 'SX_PERF_SEL_POS_SCBD_STALL', + 'SX_PERF_SEL_SH_COLOR_STALL', 'SX_PERF_SEL_SH_COLOR_STARVE', + 'SX_PERF_SEL_SH_IDX_STARVE', 'SX_PERF_SEL_SH_POS_STALL', + 'SX_PERF_SEL_SH_POS_STARVE', 'SX_RT_EXPORT_10_11_11', + 'SX_RT_EXPORT_16_16_AR', 'SX_RT_EXPORT_16_16_GR', + 'SX_RT_EXPORT_1_5_5_5', 'SX_RT_EXPORT_2_10_10_10', + 'SX_RT_EXPORT_2_10_10_10_6E4', 'SX_RT_EXPORT_2_10_10_10_7E3', + 'SX_RT_EXPORT_32_A', 'SX_RT_EXPORT_32_R', 'SX_RT_EXPORT_4_4_4_4', + 'SX_RT_EXPORT_5_6_5', 'SX_RT_EXPORT_8_8_8_8', + 'SX_RT_EXPORT_9_9_9_E5', 'SX_RT_EXPORT_NO_CONVERSION', + 'SYMCLK_FE_FORCE_EN', 'SYMCLK_FE_FORCE_EN_DISABLE', + 'SYMCLK_FE_FORCE_EN_ENABLE', 'SYMCLK_FE_FORCE_SRC', + 'SYMCLK_FE_FORCE_SRC_RESERVED', 'SYMCLK_FE_FORCE_SRC_UNIPHYA', + 'SYMCLK_FE_FORCE_SRC_UNIPHYB', 'SYMCLK_FE_FORCE_SRC_UNIPHYC', + 'SYMCLK_FE_FORCE_SRC_UNIPHYD', 'ScMap', 'ScUncertaintyRegionMode', + 'ScUncertaintyRegionMult', 'ScXsel', 'ScYsel', 'SeMap', + 'SePairMap', 'SePairXsel', 'SePairYsel', 'SeXsel', 'SeYsel', + 'SourceFormat', 'Spare_257', 'StencilOp', 'TA_PERFCOUNT_SEL', + 'TA_PERF_SEL_NULL', 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 'TA_PERF_SEL_addresser_busy', 'TA_PERF_SEL_addresser_fifo_busy', + 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 'TA_PERF_SEL_addresser_stalled_cycles', + 'TA_PERF_SEL_aligner_busy', + 'TA_PERF_SEL_aligner_clk_valid_cycles', + 'TA_PERF_SEL_aligner_cycles', 'TA_PERF_SEL_aniso_10_cycle_quads', + 'TA_PERF_SEL_aniso_12_cycle_quads', + 'TA_PERF_SEL_aniso_14_cycle_quads', + 'TA_PERF_SEL_aniso_16_cycle_quads', + 'TA_PERF_SEL_aniso_1_cycle_quads', + 'TA_PERF_SEL_aniso_2_cycle_quads', + 'TA_PERF_SEL_aniso_4_cycle_quads', + 'TA_PERF_SEL_aniso_6_cycle_quads', + 'TA_PERF_SEL_aniso_8_cycle_quads', + 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 'TA_PERF_SEL_aniso_stalled_cycles', + 'TA_PERF_SEL_atomic_2_write_data_vgpr_instructions', + 'TA_PERF_SEL_atomic_4_write_data_vgpr_instructions', + 'TA_PERF_SEL_atomic_write_data_input_cycles', + 'TA_PERF_SEL_atomic_write_data_output_cycles', + 'TA_PERF_SEL_bf_busy', + 'TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_buffer_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_buffer_2_address_input_vgpr_instructions', + 'TA_PERF_SEL_buffer_atomic_wavefronts', + 'TA_PERF_SEL_buffer_flat_1_op_burst', + 'TA_PERF_SEL_buffer_flat_2to3_op_burst', + 'TA_PERF_SEL_buffer_flat_4to31_op_burst', + 'TA_PERF_SEL_buffer_flat_clk_valid_cycles', + 'TA_PERF_SEL_buffer_flat_ge32_op_burst', + 'TA_PERF_SEL_buffer_has_index_instructions', + 'TA_PERF_SEL_buffer_has_offset_instructions', + 'TA_PERF_SEL_buffer_load_wavefronts', + 'TA_PERF_SEL_buffer_store_wavefronts', + 'TA_PERF_SEL_buffer_total_cycles', + 'TA_PERF_SEL_buffer_wavefronts', 'TA_PERF_SEL_bvh_total_cycles', + 'TA_PERF_SEL_color_1_cycle_quads', + 'TA_PERF_SEL_color_2_cycle_quads', + 'TA_PERF_SEL_color_3_cycle_quads', + 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 'TA_PERF_SEL_deriv_stalled_cycles', + 'TA_PERF_SEL_flat_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_flat_atomic_wavefronts', + 'TA_PERF_SEL_flat_load_wavefronts', + 'TA_PERF_SEL_flat_store_wavefronts', + 'TA_PERF_SEL_flat_total_cycles', 'TA_PERF_SEL_flat_wavefronts', + 'TA_PERF_SEL_gradient_busy', + 'TA_PERF_SEL_gradient_clk_valid_cycles', + 'TA_PERF_SEL_gradient_cycles', 'TA_PERF_SEL_gradient_fifo_busy', + 'TA_PERF_SEL_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_harvestable_register_clk_enabled_cycles', + 'TA_PERF_SEL_ibubble_16to31_cycle_burst', + 'TA_PERF_SEL_ibubble_1_cycle_burst', + 'TA_PERF_SEL_ibubble_2to3_cycle_burst', + 'TA_PERF_SEL_ibubble_32to63_cycle_burst', + 'TA_PERF_SEL_ibubble_4to15_cycle_burst', + 'TA_PERF_SEL_ibubble_ge64_cycle_burst', + 'TA_PERF_SEL_image_atomic_wavefronts', + 'TA_PERF_SEL_image_bvh_11_input_vgpr_instructions', + 'TA_PERF_SEL_image_bvh_12_input_vgpr_instructions', + 'TA_PERF_SEL_image_bvh_1_op_burst', + 'TA_PERF_SEL_image_bvh_2to3_op_burst', + 'TA_PERF_SEL_image_bvh_4to7_op_burst', + 'TA_PERF_SEL_image_bvh_8_input_vgpr_instructions', + 'TA_PERF_SEL_image_bvh_9_input_vgpr_instructions', + 'TA_PERF_SEL_image_bvh_ge8_op_burst', + 'TA_PERF_SEL_image_linked_1_op_burst', + 'TA_PERF_SEL_image_linked_2to3_op_burst', + 'TA_PERF_SEL_image_linked_4to7_op_burst', + 'TA_PERF_SEL_image_linked_ge8_op_burst', + 'TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_1_op_burst', + 'TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_2to3_op_burst', + 'TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_4to31_op_burst', + 'TA_PERF_SEL_image_nosampler_ge32_op_burst', + 'TA_PERF_SEL_image_nosampler_has_q_instructions', + 'TA_PERF_SEL_image_nosampler_has_r_instructions', + 'TA_PERF_SEL_image_nosampler_has_t_instructions', + 'TA_PERF_SEL_image_nosampler_total_cycles', + 'TA_PERF_SEL_image_read_wavefronts', + 'TA_PERF_SEL_image_sampler_10_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_11_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_12_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_1_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_1_op_burst', + 'TA_PERF_SEL_image_sampler_2_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_2to3_op_burst', + 'TA_PERF_SEL_image_sampler_3_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_4_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_4to7_op_burst', + 'TA_PERF_SEL_image_sampler_5_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_6_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_7_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_8_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_9_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_ge8_op_burst', + 'TA_PERF_SEL_image_sampler_has_bias_instructions', + 'TA_PERF_SEL_image_sampler_has_dr_instructions', + 'TA_PERF_SEL_image_sampler_has_ds_instructions', + 'TA_PERF_SEL_image_sampler_has_dt_instructions', + 'TA_PERF_SEL_image_sampler_has_offset_instructions', + 'TA_PERF_SEL_image_sampler_has_q_instructions', + 'TA_PERF_SEL_image_sampler_has_r_instructions', + 'TA_PERF_SEL_image_sampler_has_reference_instructions', + 'TA_PERF_SEL_image_sampler_has_t_instructions', + 'TA_PERF_SEL_image_sampler_total_cycles', + 'TA_PERF_SEL_image_sampler_wavefronts', + 'TA_PERF_SEL_image_store_wavefronts', + 'TA_PERF_SEL_image_wavefronts', 'TA_PERF_SEL_in_addr_cycles', + 'TA_PERF_SEL_in_busy', 'TA_PERF_SEL_in_cfifo_busy', + 'TA_PERF_SEL_in_data_cycles', 'TA_PERF_SEL_in_fifos_busy', + 'TA_PERF_SEL_in_qfifo_busy', 'TA_PERF_SEL_in_rfifo_busy', + 'TA_PERF_SEL_in_waiting_on_req_cycles', + 'TA_PERF_SEL_in_wfifo_busy', + 'TA_PERF_SEL_latency_ram_ref_required_instructions', + 'TA_PERF_SEL_latency_ram_weights_written_cycles', + 'TA_PERF_SEL_latency_ram_whv_required_instructions', + 'TA_PERF_SEL_latency_ram_whv_required_quads', + 'TA_PERF_SEL_latency_ram_ws_required_instructions', + 'TA_PERF_SEL_latency_ram_ws_required_quads', + 'TA_PERF_SEL_lod_aniso_clk_valid_cycles', 'TA_PERF_SEL_lod_busy', + 'TA_PERF_SEL_lod_fifo_busy', 'TA_PERF_SEL_mip_1_cycle_quads', + 'TA_PERF_SEL_mip_2_cycle_quads', + 'TA_PERF_SEL_mipmap_invalid_samples', + 'TA_PERF_SEL_mipmap_lod_0_samples', + 'TA_PERF_SEL_mipmap_lod_10_samples', + 'TA_PERF_SEL_mipmap_lod_11_samples', + 'TA_PERF_SEL_mipmap_lod_12_samples', + 'TA_PERF_SEL_mipmap_lod_13_samples', + 'TA_PERF_SEL_mipmap_lod_14_samples', + 'TA_PERF_SEL_mipmap_lod_1_samples', + 'TA_PERF_SEL_mipmap_lod_2_samples', + 'TA_PERF_SEL_mipmap_lod_3_samples', + 'TA_PERF_SEL_mipmap_lod_4_samples', + 'TA_PERF_SEL_mipmap_lod_5_samples', + 'TA_PERF_SEL_mipmap_lod_6_samples', + 'TA_PERF_SEL_mipmap_lod_7_samples', + 'TA_PERF_SEL_mipmap_lod_8_samples', + 'TA_PERF_SEL_mipmap_lod_9_samples', + 'TA_PERF_SEL_non_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_nonsampler_clk_valid_cycles', 'TA_PERF_SEL_ns_busy', + 'TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input', + 'TA_PERF_SEL_num_nodes_invalidated_due_to_oob', + 'TA_PERF_SEL_num_of_bvh_invalidated_first_tri', + 'TA_PERF_SEL_num_of_bvh_invalidated_fourth_tri', + 'TA_PERF_SEL_num_of_bvh_invalidated_fp16_box', + 'TA_PERF_SEL_num_of_bvh_invalidated_fp32_box', + 'TA_PERF_SEL_num_of_bvh_invalidated_second_tri', + 'TA_PERF_SEL_num_of_bvh_invalidated_third_tri', + 'TA_PERF_SEL_num_of_bvh_valid_first_tri', + 'TA_PERF_SEL_num_of_bvh_valid_fourth_tri', + 'TA_PERF_SEL_num_of_bvh_valid_fp16_box', + 'TA_PERF_SEL_num_of_bvh_valid_fp32_box', + 'TA_PERF_SEL_num_of_bvh_valid_second_tri', + 'TA_PERF_SEL_num_of_bvh_valid_third_tri', + 'TA_PERF_SEL_num_unlit_nodes_ta_opt', + 'TA_PERF_SEL_point_sampled_quads', + 'TA_PERF_SEL_register_clk_valid_cycles', + 'TA_PERF_SEL_sampler_addressing_clk_valid_cycles', + 'TA_PERF_SEL_sampler_clk_valid_cycles', + 'TA_PERF_SEL_sampler_op_quads', 'TA_PERF_SEL_smp_busy_ns_idle', + 'TA_PERF_SEL_smp_idle_ns_busy', + 'TA_PERF_SEL_store_2_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_3_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_4_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_has_w_instructions', + 'TA_PERF_SEL_store_has_x_instructions', + 'TA_PERF_SEL_store_has_y_instructions', + 'TA_PERF_SEL_store_has_z_instructions', + 'TA_PERF_SEL_store_write_data_input_cycles', + 'TA_PERF_SEL_store_write_data_output_cycles', + 'TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles', + 'TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles', + 'TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles', + 'TA_PERF_SEL_ta_busy', 'TA_PERF_SEL_tcreq_clk_valid_cycles', + 'TA_PERF_SEL_total_wavefronts', 'TA_PERF_SEL_vmemcmd_cycles', + 'TA_PERF_SEL_vmemreq_cycles', 'TA_PERF_SEL_vol_1_cycle_quads', + 'TA_PERF_SEL_vol_2_cycle_quads', 'TA_PERF_SEL_walker_cycles', + 'TA_PERF_SEL_write_1_op_burst', 'TA_PERF_SEL_write_2to3_op_burst', + 'TA_PERF_SEL_write_4to31_op_burst', + 'TA_PERF_SEL_write_data_clk_valid_cycles', + 'TA_PERF_SEL_write_ge32_op_burst', 'TA_PERF_SEL_write_path_busy', + 'TA_TC_ADDR_MODES', 'TA_TC_ADDR_MODE_BORDER_COLOR', + 'TA_TC_ADDR_MODE_COMP0', 'TA_TC_ADDR_MODE_COMP1', + 'TA_TC_ADDR_MODE_COMP2', 'TA_TC_ADDR_MODE_COMP3', + 'TA_TC_ADDR_MODE_DEFAULT', 'TA_TC_ADDR_MODE_UNALIGNED', + 'TA_TC_REQ_MODES', 'TA_TC_REQ_MODE_BORDER', 'TA_TC_REQ_MODE_BYTE', + 'TA_TC_REQ_MODE_BYTE_NV', 'TA_TC_REQ_MODE_DWORD', + 'TA_TC_REQ_MODE_NORMAL', 'TA_TC_REQ_MODE_TEX0', + 'TA_TC_REQ_MODE_TEX1', 'TA_TC_REQ_MODE_TEX2', 'TB_ACP_NOT_SEND', + 'TB_ACP_PKT_SEND', 'TB_ACR_0_MULTIPLE_RESERVED', + 'TB_ACR_1_MULTIPLE', 'TB_ACR_2_MULTIPLE', + 'TB_ACR_3_MULTIPLE_RESERVED', 'TB_ACR_4_MULTIPLE', + 'TB_ACR_5_MULTIPLE_RESERVED', 'TB_ACR_6_MULTIPLE_RESERVED', + 'TB_ACR_7_MULTIPLE_RESERVED', 'TB_ACR_CONT_DISABLE', + 'TB_ACR_CONT_ENABLE', 'TB_ACR_NOT_SEND', + 'TB_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', 'TB_ACR_PKT_SEND', + 'TB_ACR_SELECT_32K', 'TB_ACR_SELECT_44K', 'TB_ACR_SELECT_48K', + 'TB_ACR_SELECT_HW', 'TB_ACR_SOURCE_HW', 'TB_ACR_SOURCE_SW', + 'TB_AUDIO_INFO_CONT_DISABLE', 'TB_AUDIO_INFO_CONT_ENABLE', + 'TB_AUDIO_INFO_NOT_SEND', 'TB_AUDIO_INFO_PKT_SEND', + 'TB_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', + 'TB_BORROW_MODE_ACTIVE', 'TB_BORROW_MODE_BLANK', + 'TB_BORROW_MODE_NONE', 'TB_BORROW_MODE_RESERVED', + 'TB_CRC_ACTIVE_AND_DATAISLAND_TRIBYTES', 'TB_CRC_ACTIVE_TRIBYTES', + 'TB_CRC_ALL_TRIBYTES', 'TB_CRC_DATAISLAND_TRIBYTES', + 'TB_CRC_DEEP_COLOR_PACKER', 'TB_CRC_DSC_PACKER', + 'TB_CRC_ENCRYPTOR_INPUT', 'TB_CRC_TB_ENC_INPUT', + 'TB_DEEP_COLOR_DEPTH_24BPP', 'TB_DEEP_COLOR_DEPTH_30BPP', + 'TB_DEEP_COLOR_DEPTH_36BPP', 'TB_DEEP_COLOR_DEPTH_RESERVED', + 'TB_DEFAULT_PHASE_IS_0', 'TB_DEFAULT_PHASE_IS_1', 'TB_DISABLE', + 'TB_DSC_444_RGB', 'TB_DSC_DISABLE', 'TB_DSC_NATIVE_422_420', + 'TB_ENABLE', 'TB_GC_AVMUTE_CONT_DISABLE', + 'TB_GC_AVMUTE_CONT_ENABLE', 'TB_GC_AVMUTE_SET', + 'TB_GC_AVMUTE_UNSET', 'TB_GC_CONT_DISABLE', 'TB_GC_CONT_ENABLE', + 'TB_GC_NOT_SEND', 'TB_GC_PKT_SEND', 'TB_GENERIC_CONT_DISABLE', + 'TB_GENERIC_CONT_ENABLE', 'TB_GENERIC_NOT_SEND', + 'TB_GENERIC_PKT_SEND', 'TB_ISRC_CONT_DISABLE', + 'TB_ISRC_CONT_ENABLE', 'TB_ISRC_NOT_SEND', 'TB_ISRC_PKT_SEND', + 'TB_METADATA_NOT_SEND', 'TB_METADATA_PKT_SEND', 'TB_NOT_RESET', + 'TB_NOT_SYNC_PHASE_ON_FRAME_START', 'TB_NO_ERROR_OCCURRED', + 'TB_OVERFLOW_OCCURRED', 'TB_PIXEL_ENCODING_420', + 'TB_PIXEL_ENCODING_422', 'TB_PIXEL_ENCODING_444_RGB', + 'TB_PKT_LINE_REF_END_OF_ACTIVE', 'TB_PKT_LINE_REF_OTGSOF', + 'TB_RESET', 'TB_SYNC_PHASE_ON_FRAME_START', 'TCC_CACHE_POLICIES', + 'TCC_CACHE_POLICY_LRU', 'TCC_CACHE_POLICY_STREAM', 'TCC_MTYPE', + 'TCP_CACHE_POLICIES', 'TCP_CACHE_POLICY_HIT_EVICT', + 'TCP_CACHE_POLICY_HIT_LRU', 'TCP_CACHE_POLICY_MISS_EVICT', + 'TCP_CACHE_POLICY_MISS_LRU', 'TCP_CACHE_STORE_POLICIES', + 'TCP_CACHE_STORE_POLICY_WT_EVICT', + 'TCP_CACHE_STORE_POLICY_WT_LRU', 'TCP_DSM_DATA_SEL', + 'TCP_DSM_DISABLE', 'TCP_DSM_INJECT_SEL', 'TCP_DSM_INJECT_SEL0', + 'TCP_DSM_INJECT_SEL1', 'TCP_DSM_INJECT_SEL2', + 'TCP_DSM_INJECT_SEL3', 'TCP_DSM_SEL0', 'TCP_DSM_SEL1', + 'TCP_DSM_SEL_BOTH', 'TCP_DSM_SINGLE_WRITE', + 'TCP_DSM_SINGLE_WRITE_DIS', 'TCP_DSM_SINGLE_WRITE_EN', + 'TCP_OPCODE_ATOMIC', 'TCP_OPCODE_ATOMIC_CMPSWAP', + 'TCP_OPCODE_GATHERH', 'TCP_OPCODE_INV', 'TCP_OPCODE_LOAD', + 'TCP_OPCODE_READ', 'TCP_OPCODE_SAMPLER', 'TCP_OPCODE_TYPE', + 'TCP_OPCODE_WRITE', 'TCP_PERFCOUNT_SELECT', + 'TCP_PERF_SEL_ALLOC_STALL', + 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL', + 'TCP_PERF_SEL_COMP_TEX_LOAD_STALL', + 'TCP_PERF_SEL_DATA_FIFO_STALL', 'TCP_PERF_SEL_GATE_EN1', + 'TCP_PERF_SEL_GATE_EN2', 'TCP_PERF_SEL_GL1_GRANT_READ_STALL', + 'TCP_PERF_SEL_GL1_PENDING_STALL', 'TCP_PERF_SEL_GL1_READ_LATENCY', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_GL1_REQ_READ', 'TCP_PERF_SEL_GL1_REQ_READ_128B', + 'TCP_PERF_SEL_GL1_REQ_READ_64B', 'TCP_PERF_SEL_GL1_REQ_WRITE', + 'TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE', + 'TCP_PERF_SEL_GL1_TCP_RDRET_STALL', + 'TCP_PERF_SEL_GL1_WRITE_LATENCY', 'TCP_PERF_SEL_LFIFO_STALL', + 'TCP_PERF_SEL_LOD_STALL', 'TCP_PERF_SEL_MEM_REQ_FIFO_STALL', + 'TCP_PERF_SEL_OFIFO_AGE_ORDER_STALL', + 'TCP_PERF_SEL_OFIFO_INCOMPLETE_STALL', 'TCP_PERF_SEL_POWER_STALL', + 'TCP_PERF_SEL_READ_DATACONFLICT_STALL', + 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL', 'TCP_PERF_SEL_REQ', + 'TCP_PERF_SEL_REQ_MISS', 'TCP_PERF_SEL_REQ_MISS_TAGBANK0', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK1', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK2', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK3', 'TCP_PERF_SEL_REQ_NON_READ', + 'TCP_PERF_SEL_REQ_READ', 'TCP_PERF_SEL_REQ_READ_HIT_EVICT', + 'TCP_PERF_SEL_REQ_READ_HIT_LRU', + 'TCP_PERF_SEL_REQ_READ_MISS_EVICT', + 'TCP_PERF_SEL_REQ_TAGBANK0_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK0_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK1_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK1_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK2_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK2_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK3_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK3_SET1', 'TCP_PERF_SEL_REQ_WRITE', + 'TCP_PERF_SEL_REQ_WRITE_MISS_EVICT', + 'TCP_PERF_SEL_REQ_WRITE_MISS_LRU', 'TCP_PERF_SEL_TA_REQ', + 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_TA_REQ_GL0_INV', 'TCP_PERF_SEL_TA_REQ_READ', + 'TCP_PERF_SEL_TA_REQ_STATE_READ', 'TCP_PERF_SEL_TA_REQ_WRITE', + 'TCP_PERF_SEL_TA_TCP_REQ_STARVE', 'TCP_PERF_SEL_TCP_LATENCY', + 'TCP_PERF_SEL_TCP_TA_REQ_STALL', + 'TCP_PERF_SEL_TD_DATA_CYCLE_STALL', 'TCP_PERF_SEL_TD_TCP_STALL', + 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 'TCP_PERF_SEL_WRITE_DATACONFLICT_STALL', + 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL', 'TCP_WATCH_MODES', + 'TCP_WATCH_MODE_ALL', 'TCP_WATCH_MODE_ATOMIC', + 'TCP_WATCH_MODE_NONREAD', 'TCP_WATCH_MODE_READ', 'TC_EA_CID', + 'TC_EA_CID_CPF', 'TC_EA_CID_CPG', 'TC_EA_CID_DCC', + 'TC_EA_CID_FMASK', 'TC_EA_CID_HTILE', 'TC_EA_CID_IA', + 'TC_EA_CID_MISC', 'TC_EA_CID_PA', 'TC_EA_CID_RT', 'TC_EA_CID_SQC', + 'TC_EA_CID_STENCIL', 'TC_EA_CID_TCP', 'TC_EA_CID_TCPMETA', + 'TC_EA_CID_UTCL2_TPI', 'TC_EA_CID_WD', 'TC_EA_CID_Z', 'TC_NACKS', + 'TC_NACK_DATA_ERROR', 'TC_NACK_NO_FAULT', 'TC_NACK_PAGE_FAULT', + 'TC_NACK_PROTECTION_FAULT', 'TC_OP', 'TC_OP_ATOMIC_ADD_32', + 'TC_OP_ATOMIC_ADD_64', 'TC_OP_ATOMIC_ADD_RTN_32', + 'TC_OP_ATOMIC_ADD_RTN_64', 'TC_OP_ATOMIC_AND_32', + 'TC_OP_ATOMIC_AND_64', 'TC_OP_ATOMIC_AND_RTN_32', + 'TC_OP_ATOMIC_AND_RTN_64', 'TC_OP_ATOMIC_CMPSWAP_32', + 'TC_OP_ATOMIC_CMPSWAP_64', 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 'TC_OP_ATOMIC_CMPSWAP_RTN_64', 'TC_OP_ATOMIC_DEC_32', + 'TC_OP_ATOMIC_DEC_64', 'TC_OP_ATOMIC_DEC_RTN_32', + 'TC_OP_ATOMIC_DEC_RTN_64', 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_32', 'TC_OP_ATOMIC_FCMPSWAP_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 'TC_OP_ATOMIC_FMAX_32', 'TC_OP_ATOMIC_FMAX_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMAX_RTN_32', 'TC_OP_ATOMIC_FMAX_RTN_64', + 'TC_OP_ATOMIC_FMIN_32', 'TC_OP_ATOMIC_FMIN_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMIN_RTN_32', 'TC_OP_ATOMIC_FMIN_RTN_64', + 'TC_OP_ATOMIC_INC_32', 'TC_OP_ATOMIC_INC_64', + 'TC_OP_ATOMIC_INC_RTN_32', 'TC_OP_ATOMIC_INC_RTN_64', + 'TC_OP_ATOMIC_OR_32', 'TC_OP_ATOMIC_OR_64', + 'TC_OP_ATOMIC_OR_RTN_32', 'TC_OP_ATOMIC_OR_RTN_64', + 'TC_OP_ATOMIC_SMAX_32', 'TC_OP_ATOMIC_SMAX_64', + 'TC_OP_ATOMIC_SMAX_RTN_32', 'TC_OP_ATOMIC_SMAX_RTN_64', + 'TC_OP_ATOMIC_SMIN_32', 'TC_OP_ATOMIC_SMIN_64', + 'TC_OP_ATOMIC_SMIN_RTN_32', 'TC_OP_ATOMIC_SMIN_RTN_64', + 'TC_OP_ATOMIC_SUB_32', 'TC_OP_ATOMIC_SUB_64', + 'TC_OP_ATOMIC_SUB_RTN_32', 'TC_OP_ATOMIC_SUB_RTN_64', + 'TC_OP_ATOMIC_SWAP_32', 'TC_OP_ATOMIC_SWAP_64', + 'TC_OP_ATOMIC_SWAP_RTN_32', 'TC_OP_ATOMIC_SWAP_RTN_64', + 'TC_OP_ATOMIC_UMAX_32', 'TC_OP_ATOMIC_UMAX_64', + 'TC_OP_ATOMIC_UMAX_RTN_32', 'TC_OP_ATOMIC_UMAX_RTN_64', + 'TC_OP_ATOMIC_UMIN_32', 'TC_OP_ATOMIC_UMIN_64', + 'TC_OP_ATOMIC_UMIN_RTN_32', 'TC_OP_ATOMIC_UMIN_RTN_64', + 'TC_OP_ATOMIC_XOR_32', 'TC_OP_ATOMIC_XOR_64', + 'TC_OP_ATOMIC_XOR_RTN_32', 'TC_OP_ATOMIC_XOR_RTN_64', + 'TC_OP_INVL2_NC', 'TC_OP_INV_METADATA', 'TC_OP_MASKS', + 'TC_OP_MASK_64', 'TC_OP_MASK_FLUSH_DENROM', 'TC_OP_MASK_NO_RTN', + 'TC_OP_NOP_ACK', 'TC_OP_NOP_RTN0', 'TC_OP_PROBE_FILTER', + 'TC_OP_READ', 'TC_OP_RESERVED_FADD_32', + 'TC_OP_RESERVED_FADD_RTN_32', 'TC_OP_RESERVED_FOP_32_0', + 'TC_OP_RESERVED_FOP_32_2', 'TC_OP_RESERVED_FOP_64_0', + 'TC_OP_RESERVED_FOP_64_1', 'TC_OP_RESERVED_FOP_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_32_0', 'TC_OP_RESERVED_FOP_RTN_32_2', + 'TC_OP_RESERVED_FOP_RTN_64_0', 'TC_OP_RESERVED_FOP_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_64_2', 'TC_OP_RESERVED_NON_FLOAT_32_1', + 'TC_OP_RESERVED_NON_FLOAT_32_2', 'TC_OP_RESERVED_NON_FLOAT_32_3', + 'TC_OP_RESERVED_NON_FLOAT_32_4', 'TC_OP_RESERVED_NON_FLOAT_64_1', + 'TC_OP_RESERVED_NON_FLOAT_64_2', 'TC_OP_RESERVED_NON_FLOAT_64_3', + 'TC_OP_RESERVED_NON_FLOAT_64_4', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', 'TC_OP_WBINVL1', + 'TC_OP_WBINVL1_SD', 'TC_OP_WBINVL1_VOL', 'TC_OP_WBINVL2', + 'TC_OP_WBINVL2_NC', 'TC_OP_WBINVL2_SD', 'TC_OP_WBL2_NC', + 'TC_OP_WBL2_WC', 'TC_OP_WRITE', 'TD_PERFCOUNT_SEL', + 'TD_PERF_SEL_address_cmd_poison', + 'TD_PERF_SEL_all_pipes_sclk_on_at_same_time', + 'TD_PERF_SEL_blend_prt_with_prt_default_0', + 'TD_PERF_SEL_blend_prt_with_prt_default_1', + 'TD_PERF_SEL_bubble_bin_lds_stall_1to3', + 'TD_PERF_SEL_bubble_bin_lds_stall_4to7', + 'TD_PERF_SEL_bubble_bin_lds_stall_8to15', + 'TD_PERF_SEL_bubble_bin_lds_stall_gt15', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511', + 'TD_PERF_SEL_burst_bin_bvh4_1', 'TD_PERF_SEL_burst_bin_bvh4_2to8', + 'TD_PERF_SEL_burst_bin_bvh4_9to16', + 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_1', + 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_2to4', + 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_5to7', + 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_8to16', + 'TD_PERF_SEL_burst_bin_bvh4_box_nodes_gt16', + 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_1', + 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_2to8', + 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_9to16', + 'TD_PERF_SEL_burst_bin_bvh4_dropped_nodes_gt16', + 'TD_PERF_SEL_burst_bin_bvh4_gt16', + 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_1', + 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_2to8', + 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_9to16', + 'TD_PERF_SEL_burst_bin_bvh4_invalid_nodes_gt16', + 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_1', + 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_2to8', + 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_9to16', + 'TD_PERF_SEL_burst_bin_bvh4_tri_nodes_gt16', + 'TD_PERF_SEL_burst_bin_gather_1', + 'TD_PERF_SEL_burst_bin_gather_2to8', + 'TD_PERF_SEL_burst_bin_gather_9to16', + 'TD_PERF_SEL_burst_bin_gather_gt16', + 'TD_PERF_SEL_burst_bin_nofilter_1', + 'TD_PERF_SEL_burst_bin_nofilter_2to4', + 'TD_PERF_SEL_burst_bin_nofilter_5to7', + 'TD_PERF_SEL_burst_bin_nofilter_8to16', + 'TD_PERF_SEL_burst_bin_nofilter_gt16', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_1', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_2to4', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_5to7', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_8to16', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_gt16', + 'TD_PERF_SEL_burst_bin_sampler_1', + 'TD_PERF_SEL_burst_bin_sampler_2to8', + 'TD_PERF_SEL_burst_bin_sampler_9to16', + 'TD_PERF_SEL_burst_bin_sampler_gt16', + 'TD_PERF_SEL_bypassLerp_instr', + 'TD_PERF_SEL_core_state_ram_max_cnt', + 'TD_PERF_SEL_core_state_rams_read', 'TD_PERF_SEL_d16_en_instr', + 'TD_PERF_SEL_data_poison', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 'TD_PERF_SEL_done_scoreboard_is_full', + 'TD_PERF_SEL_done_scoreboard_max_stored_cnt', + 'TD_PERF_SEL_done_scoreboard_max_waiting_cnt', + 'TD_PERF_SEL_done_scoreboard_not_empty', + 'TD_PERF_SEL_four_comp_return_instr', 'TD_PERF_SEL_gather4_instr', + 'TD_PERF_SEL_gather4h_instr', + 'TD_PERF_SEL_input_bp_due_to_done_scoreboard_full', + 'TD_PERF_SEL_input_busy', 'TD_PERF_SEL_input_state_fifo_full', + 'TD_PERF_SEL_instruction_dest_is_lds', 'TD_PERF_SEL_ldfptr_instr', + 'TD_PERF_SEL_lds_stall', 'TD_PERF_SEL_load_instr', + 'TD_PERF_SEL_lod_warn_from_ta', + 'TD_PERF_SEL_min_max_filter_instr', 'TD_PERF_SEL_mixmode_instr', + 'TD_PERF_SEL_mixmode_resource', 'TD_PERF_SEL_msaa_load_instr', + 'TD_PERF_SEL_nofilter_and_bvh4_sclk_on_sampler_sclk_off', + 'TD_PERF_SEL_nofilter_busy', + 'TD_PERF_SEL_nofilter_byte_cycling_16cycles', + 'TD_PERF_SEL_nofilter_byte_cycling_4cycles', + 'TD_PERF_SEL_nofilter_byte_cycling_8cycles', + 'TD_PERF_SEL_nofilter_d16_sclk_en', + 'TD_PERF_SEL_nofilter_d32_sclk_en', + 'TD_PERF_SEL_nofilter_dword_cycling_2cycles', + 'TD_PERF_SEL_nofilter_dword_cycling_4cycles', + 'TD_PERF_SEL_nofilter_formatters_turned_on', + 'TD_PERF_SEL_nofilter_insert_extra_comps', + 'TD_PERF_SEL_nofilter_pkr_full', + 'TD_PERF_SEL_nofilter_pkr_full_due_to_arb', + 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_sclk_en', + 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 'TD_PERF_SEL_nofilter_total_num_comps_to_lds', 'TD_PERF_SEL_none', + 'TD_PERF_SEL_one_comp_return_instr', + 'TD_PERF_SEL_opaque_black_border', + 'TD_PERF_SEL_out_of_order_instr', + 'TD_PERF_SEL_preempting_nofilter_max_cnt', + 'TD_PERF_SEL_prt_ack_instr', + 'TD_PERF_SEL_ray_tracing_bvh4_box_grow_val_nonzero', + 'TD_PERF_SEL_ray_tracing_bvh4_box_sclk_en', + 'TD_PERF_SEL_ray_tracing_bvh4_box_sort_en', + 'TD_PERF_SEL_ray_tracing_bvh4_busy', + 'TD_PERF_SEL_ray_tracing_bvh4_dropped_box_node', + 'TD_PERF_SEL_ray_tracing_bvh4_dropped_tri_node', + 'TD_PERF_SEL_ray_tracing_bvh4_fp16_box_node', + 'TD_PERF_SEL_ray_tracing_bvh4_fp32_box_node', + 'TD_PERF_SEL_ray_tracing_bvh4_instr_invld_thread_cnt', + 'TD_PERF_SEL_ray_tracing_bvh4_invalid_box_node', + 'TD_PERF_SEL_ray_tracing_bvh4_invalid_tri_node', + 'TD_PERF_SEL_ray_tracing_bvh4_ip_sclk_en', + 'TD_PERF_SEL_ray_tracing_bvh4_num_box_misses', + 'TD_PERF_SEL_ray_tracing_bvh4_num_box_that_squashed_a_nan', + 'TD_PERF_SEL_ray_tracing_bvh4_num_box_with_inf_or_nan_vtx', + 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_misses', + 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_tie_breakers', + 'TD_PERF_SEL_ray_tracing_bvh4_num_tri_with_inf_or_nan_vtx', + 'TD_PERF_SEL_ray_tracing_bvh4_pkr_full', + 'TD_PERF_SEL_ray_tracing_bvh4_pkr_full_due_to_arb', + 'TD_PERF_SEL_ray_tracing_bvh4_sclk_en', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_0', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_1', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_17to31', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_2', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_32', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_3to4', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_5to8', + 'TD_PERF_SEL_ray_tracing_bvh4_threads_per_instruction_is_9to16', + 'TD_PERF_SEL_ray_tracing_bvh4_tri_node', + 'TD_PERF_SEL_ray_tracing_bvh4_tri_sclk_en', + 'TD_PERF_SEL_reference_data_rams_read', + 'TD_PERF_SEL_resmap_instr', + 'TD_PERF_SEL_resmap_with_aniso_filtering', + 'TD_PERF_SEL_resmap_with_cubemap_corner', + 'TD_PERF_SEL_resmap_with_no_more_filtering', + 'TD_PERF_SEL_resmap_with_volume_filtering', + 'TD_PERF_SEL_sample_c_instr', 'TD_PERF_SEL_sample_instr', + 'TD_PERF_SEL_sampler_accum_sclk_en', + 'TD_PERF_SEL_sampler_and_bvh4_sclk_on_nofilter_sclk_off', + 'TD_PERF_SEL_sampler_and_nofilter_sclk_on_bvh4_sclk_off', + 'TD_PERF_SEL_sampler_bilerp_sclk_en', + 'TD_PERF_SEL_sampler_bypass_sclk_en', + 'TD_PERF_SEL_sampler_core_sclk_en', + 'TD_PERF_SEL_sampler_format_flt_sclk_en', + 'TD_PERF_SEL_sampler_format_fxdpt_sclk_en', + 'TD_PERF_SEL_sampler_lerp0_active', + 'TD_PERF_SEL_sampler_lerp1_active', + 'TD_PERF_SEL_sampler_lerp2_active', + 'TD_PERF_SEL_sampler_lerp3_active', + 'TD_PERF_SEL_sampler_lerp_busy', + 'TD_PERF_SEL_sampler_minmax_sclk_en', + 'TD_PERF_SEL_sampler_out_busy', 'TD_PERF_SEL_sampler_out_sclk_en', + 'TD_PERF_SEL_sampler_pkr_full', + 'TD_PERF_SEL_sampler_pkr_full_due_to_arb', + 'TD_PERF_SEL_sampler_preformatter_sclk_en', + 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 'TD_PERF_SEL_status_packet', 'TD_PERF_SEL_ta_data_stall', + 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles', + 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles', + 'TD_PERF_SEL_tc_data_stall', 'TD_PERF_SEL_tc_ram_stall', + 'TD_PERF_SEL_tc_td_data_fifo_full', + 'TD_PERF_SEL_tc_td_ram_fifo_full', + 'TD_PERF_SEL_tc_td_ram_fifo_max_cnt', 'TD_PERF_SEL_td_busy', + 'TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles', + 'TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles', + 'TD_PERF_SEL_three_comp_return_instr', + 'TD_PERF_SEL_total_num_instr', + 'TD_PERF_SEL_total_num_instr_with_perf_wdw', + 'TD_PERF_SEL_total_num_nofilter_instr', + 'TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw', + 'TD_PERF_SEL_total_num_ray_tracing_bvh4_instr', + 'TD_PERF_SEL_total_num_ray_tracing_bvh4_instr_with_perf_wdw', + 'TD_PERF_SEL_total_num_sampler_instr', + 'TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw', + 'TD_PERF_SEL_two_comp_return_instr', + 'TD_PERF_SEL_user_defined_border', + 'TD_PERF_SEL_weight_data_rams_read', 'TD_PERF_SEL_white_border', + 'TD_PERF_SEL_write_ack_instr', 'TESS_ISOLINE', 'TESS_QUAD', + 'TESS_TRIANGLE', 'TEST_CLK_DIV_SEL', 'TEST_CLK_SEL', + 'TEST_CLK_SEL_0', 'TEST_CLK_SEL_1', 'TEST_CLK_SEL_2', + 'TEST_CLK_SEL_3', 'TEST_CLK_SEL_4', 'TEST_CLK_SEL_5', + 'TEST_CLK_SEL_6', 'TEST_CLK_SEL_7', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', 'TEST_CLOCK_MUX_SELECT_ENUM', + 'TEX_BC_SWIZZLE', 'TEX_BC_Swizzle_WXYZ', 'TEX_BC_Swizzle_WZYX', + 'TEX_BC_Swizzle_XWYZ', 'TEX_BC_Swizzle_XYZW', + 'TEX_BC_Swizzle_YXWZ', 'TEX_BC_Swizzle_ZYXW', + 'TEX_BORDER_COLOR_TYPE', 'TEX_BorderColor_OpaqueBlack', + 'TEX_BorderColor_OpaqueWhite', 'TEX_BorderColor_Register', + 'TEX_BorderColor_TransparentBlack', 'TEX_CHROMA_KEY', 'TEX_CLAMP', + 'TEX_COORD_TYPE', 'TEX_ChromaKey_Blend', 'TEX_ChromaKey_Disabled', + 'TEX_ChromaKey_Kill', 'TEX_ChromaKey_RESERVED_3', + 'TEX_Clamp_ClampHalfToBorder', 'TEX_Clamp_ClampToBorder', + 'TEX_Clamp_ClampToLast', 'TEX_Clamp_Mirror', + 'TEX_Clamp_MirrorOnceHalfToBorder', + 'TEX_Clamp_MirrorOnceToBorder', 'TEX_Clamp_MirrorOnceToLast', + 'TEX_Clamp_Repeat', 'TEX_CoordType_Normalized', + 'TEX_CoordType_Unnormalized', 'TEX_DEPTH_COMPARE_FUNCTION', + 'TEX_DepthCompareFunction_Always', + 'TEX_DepthCompareFunction_Equal', + 'TEX_DepthCompareFunction_Greater', + 'TEX_DepthCompareFunction_GreaterEqual', + 'TEX_DepthCompareFunction_Less', + 'TEX_DepthCompareFunction_LessEqual', + 'TEX_DepthCompareFunction_Never', + 'TEX_DepthCompareFunction_NotEqual', 'TEX_FORMAT_COMP', + 'TEX_FormatComp_RESERVED_3', 'TEX_FormatComp_Signed', + 'TEX_FormatComp_Unsigned', 'TEX_FormatComp_UnsignedBiased', + 'TEX_MAX_ANISO_RATIO', 'TEX_MIP_FILTER', + 'TEX_MaxAnisoRatio_16to1', 'TEX_MaxAnisoRatio_1to1', + 'TEX_MaxAnisoRatio_2to1', 'TEX_MaxAnisoRatio_4to1', + 'TEX_MaxAnisoRatio_8to1', 'TEX_MaxAnisoRatio_RESERVED_5', + 'TEX_MaxAnisoRatio_RESERVED_6', 'TEX_MaxAnisoRatio_RESERVED_7', + 'TEX_MipFilter_Linear', 'TEX_MipFilter_None', + 'TEX_MipFilter_Point', 'TEX_MipFilter_Point_Aniso_Adj', + 'TEX_REQUEST_SIZE', 'TEX_RequestSize_128B', + 'TEX_RequestSize_2X64B', 'TEX_RequestSize_32B', + 'TEX_RequestSize_64B', 'TEX_SAMPLER_TYPE', + 'TEX_SamplerType_Invalid', 'TEX_SamplerType_Valid', + 'TEX_XYFilter_AnisoLinear', 'TEX_XYFilter_AnisoPoint', + 'TEX_XYFilter_Linear', 'TEX_XYFilter_Point', 'TEX_XY_FILTER', + 'TEX_ZFilter_Linear', 'TEX_ZFilter_None', 'TEX_ZFilter_Point', + 'TEX_ZFilter_RESERVED_3', 'TEX_Z_FILTER', 'TGID_ROLLOVER', + 'THREAD_TRACE_DRAW', 'THREAD_TRACE_FINISH', 'THREAD_TRACE_MARKER', + 'THREAD_TRACE_START', 'THREAD_TRACE_STOP', 'TIGHT_PACK', + 'TMDS_COLOR_FORMAT', 'TMDS_COLOR_FORMAT_DUAL30BPP', + 'TMDS_COLOR_FORMAT_RESERVED', 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 'TMDS_CTL0_DATA_INVERT', 'TMDS_CTL0_DATA_INVERT_EN', + 'TMDS_CTL0_DATA_MODULATION', 'TMDS_CTL0_DATA_MODULATION_BIT0', + 'TMDS_CTL0_DATA_MODULATION_BIT1', + 'TMDS_CTL0_DATA_MODULATION_BIT2', + 'TMDS_CTL0_DATA_MODULATION_DISABLE', 'TMDS_CTL0_DATA_NORMAL', + 'TMDS_CTL0_DATA_SEL', 'TMDS_CTL0_DATA_SEL0_RESERVED', + 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL0_DATA_SEL2_VSYNC', + 'TMDS_CTL0_DATA_SEL3_RESERVED', 'TMDS_CTL0_DATA_SEL4_HSYNC', + 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', + 'TMDS_CTL0_PATTERN_OUT_DISABLE', 'TMDS_CTL0_PATTERN_OUT_EN', + 'TMDS_CTL0_PATTERN_OUT_ENABLE', 'TMDS_CTL1_DATA_INVERT', + 'TMDS_CTL1_DATA_INVERT_EN', 'TMDS_CTL1_DATA_MODULATION', + 'TMDS_CTL1_DATA_MODULATION_BIT0', + 'TMDS_CTL1_DATA_MODULATION_BIT1', + 'TMDS_CTL1_DATA_MODULATION_BIT2', + 'TMDS_CTL1_DATA_MODULATION_DISABLE', 'TMDS_CTL1_DATA_NORMAL', + 'TMDS_CTL1_DATA_SEL', 'TMDS_CTL1_DATA_SEL0_RESERVED', + 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL1_DATA_SEL2_VSYNC', + 'TMDS_CTL1_DATA_SEL3_RESERVED', 'TMDS_CTL1_DATA_SEL4_HSYNC', + 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL1_PATTERN_OUT_DISABLE', 'TMDS_CTL1_PATTERN_OUT_EN', + 'TMDS_CTL1_PATTERN_OUT_ENABLE', 'TMDS_CTL2_DATA_INVERT', + 'TMDS_CTL2_DATA_INVERT_EN', 'TMDS_CTL2_DATA_MODULATION', + 'TMDS_CTL2_DATA_MODULATION_BIT0', + 'TMDS_CTL2_DATA_MODULATION_BIT1', + 'TMDS_CTL2_DATA_MODULATION_BIT2', + 'TMDS_CTL2_DATA_MODULATION_DISABLE', 'TMDS_CTL2_DATA_NORMAL', + 'TMDS_CTL2_DATA_SEL', 'TMDS_CTL2_DATA_SEL0_RESERVED', + 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL2_DATA_SEL2_VSYNC', + 'TMDS_CTL2_DATA_SEL3_RESERVED', 'TMDS_CTL2_DATA_SEL4_HSYNC', + 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL2_PATTERN_OUT_DISABLE', 'TMDS_CTL2_PATTERN_OUT_EN', + 'TMDS_CTL2_PATTERN_OUT_ENABLE', 'TMDS_CTL3_DATA_INVERT', + 'TMDS_CTL3_DATA_INVERT_EN', 'TMDS_CTL3_DATA_MODULATION', + 'TMDS_CTL3_DATA_MODULATION_BIT0', + 'TMDS_CTL3_DATA_MODULATION_BIT1', + 'TMDS_CTL3_DATA_MODULATION_BIT2', + 'TMDS_CTL3_DATA_MODULATION_DISABLE', 'TMDS_CTL3_DATA_NORMAL', + 'TMDS_CTL3_DATA_SEL', 'TMDS_CTL3_DATA_SEL0_RESERVED', + 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL3_DATA_SEL2_VSYNC', + 'TMDS_CTL3_DATA_SEL3_RESERVED', 'TMDS_CTL3_DATA_SEL4_HSYNC', + 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL3_PATTERN_OUT_DISABLE', 'TMDS_CTL3_PATTERN_OUT_EN', + 'TMDS_CTL3_PATTERN_OUT_ENABLE', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', 'TMDS_MUX_SELECT', + 'TMDS_MUX_SELECT_B', 'TMDS_MUX_SELECT_G', 'TMDS_MUX_SELECT_R', + 'TMDS_MUX_SELECT_RESERVED', 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 'TMDS_PIXEL_ENCODING', 'TMDS_PIXEL_ENCODING_422', + 'TMDS_PIXEL_ENCODING_444_OR_420', 'TMDS_REG_TEST_OUTPUTA_CNTLA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 'TMDS_REG_TEST_OUTPUTB_CNTLB', 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', 'TMDS_STEREOSYNC_CTL0', + 'TMDS_STEREOSYNC_CTL1', 'TMDS_STEREOSYNC_CTL2', + 'TMDS_STEREOSYNC_CTL3', 'TMDS_STEREOSYNC_CTL_SEL_REG', + 'TMDS_SYNC_PHASE', 'TMDS_SYNC_PHASE_ON_FRAME_START', + 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB', + 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK', + 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', + 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', + 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', + 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', 'TRANSERR', + 'TRANSFERRED_1024_BYTES', 'TRANSFERRED_128_BYTES', + 'TRANSFERRED_2048_BYTES', 'TRANSFERRED_256_BYTES', + 'TRANSFERRED_4096_BYTES', 'TRANSFERRED_512_BYTES', + 'TRANSFERRED_64_BYTES', 'TRANSFERRED_8192_BYTES', 'TRAPEZOIDS', + 'TRISTRIP', 'TVX_TYPE', 'TVX_Type_InvalidTextureResource', + 'TVX_Type_InvalidVertexBuffer', 'TVX_Type_ValidTextureResource', + 'TVX_Type_ValidVertexBuffer', 'UCONFIG_SPACE_END', + 'UCONFIG_SPACE_START', 'UNDEF', 'UNSIGNED', 'USE_MALL_FOR_CURSOR', + 'USE_MALL_FOR_CURSOR_0', 'USE_MALL_FOR_CURSOR_1', + 'USE_MALL_FOR_PSTATE_CHANGE', 'USE_MALL_FOR_PSTATE_CHANGE_0', + 'USE_MALL_FOR_PSTATE_CHANGE_1', 'USE_MALL_FOR_STATIC_SCREEN', + 'USE_MALL_FOR_STATIC_SCREEN_0', 'USE_MALL_FOR_STATIC_SCREEN_1', + 'UTCL0FaultType', 'UTCL0RequestType', 'UTCL0_TYPE_BYPASS', + 'UTCL0_TYPE_NORMAL', 'UTCL0_TYPE_SHOOTDOWN', + 'UTCL0_XNACK_NO_RETRY', 'UTCL0_XNACK_PRT', 'UTCL0_XNACK_RETRY', + 'UTCL0_XNACK_SUCCESS', 'UTCL1FaultType', 'UTCL1PerfSel', + 'UTCL1RequestType', 'UTCL1_PERF_SEL_BYPASS_REQS', + 'UTCL1_PERF_SEL_CP_INVREQS', 'UTCL1_PERF_SEL_HITS', + 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 'UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS', + 'UTCL1_PERF_SEL_MH_DUPLICATE_DETECT', + 'UTCL1_PERF_SEL_MH_RECENT_BUF_HIT', 'UTCL1_PERF_SEL_MISSES', + 'UTCL1_PERF_SEL_NONE', 'UTCL1_PERF_SEL_RANGE_INVREQS', + 'UTCL1_PERF_SEL_REQS', 'UTCL1_PERF_SEL_RTNS', + 'UTCL1_PERF_SEL_STALL_MH_FULL', + 'UTCL1_PERF_SEL_STALL_UTCL2_CREDITS', 'UTCL1_PERF_SEL_UTCL2_REQS', + 'UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM', + 'UTCL1_PERF_SEL_UTCL2_RET_CNT', 'UTCL1_PERF_SEL_UTCL2_RET_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY', + 'UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS', + 'UTCL1_PERF_SEL_XLAT_REQ_BUSY', 'UTCL1_TYPE_BYPASS', + 'UTCL1_TYPE_NORMAL', 'UTCL1_TYPE_SHOOTDOWN', + 'UTCL1_XNACK_NO_RETRY', 'UTCL1_XNACK_PRT', 'UTCL1_XNACK_RETRY', + 'UTCL1_XNACK_SUCCESS', 'VGT_DETECT_ONE', 'VGT_DETECT_ZERO', + 'VGT_DIST_MODE', 'VGT_DI_INDEX_SIZE', 'VGT_DI_MAJOR_MODE_SELECT', + 'VGT_DI_PRIM_TYPE', 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', + 'VGT_DMA_BUF_RING', 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', + 'VGT_DMA_PTR_UPDATE', 'VGT_DMA_SWAP_16_BIT', + 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', 'VGT_DMA_SWAP_NONE', + 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', 'VGT_FLUSH', + 'VGT_GROUP_CONV_SEL', 'VGT_GRP_AUTO_PRIM', + 'VGT_GRP_FIX_1_23_TO_FLOAT', 'VGT_GRP_FLOAT_32', + 'VGT_GRP_INDEX_16', 'VGT_GRP_INDEX_32', 'VGT_GRP_SINT_16', + 'VGT_GRP_SINT_32', 'VGT_GRP_UINT_16', 'VGT_GRP_UINT_32', + 'VGT_GS_MODE_TYPE', 'VGT_GS_OUTPRIM_TYPE', 'VGT_INDEX_16', + 'VGT_INDEX_32', 'VGT_INDEX_8', 'VGT_INDEX_TYPE_MODE', + 'VGT_OUTPATH_GS_BLOCK', 'VGT_OUTPATH_HS_BLOCK', + 'VGT_OUTPATH_PRIM_GEN', 'VGT_OUTPATH_SELECT', + 'VGT_OUTPATH_TE_GS_BLOCK', 'VGT_OUTPATH_TE_OUTPUT', + 'VGT_OUTPATH_TE_PRIM_GEN', 'VGT_OUTPATH_VTX_REUSE', + 'VGT_OUT_2D_RECT', 'VGT_OUT_LINE', 'VGT_OUT_LINE_ADJ', + 'VGT_OUT_PATCH', 'VGT_OUT_POINT', 'VGT_OUT_PRIM_TYPE', + 'VGT_OUT_RECT_V0', 'VGT_OUT_RECT_V1', 'VGT_OUT_RECT_V2', + 'VGT_OUT_RECT_V3', 'VGT_OUT_TRI', 'VGT_OUT_TRI_ADJ', + 'VGT_POLICY_BYPASS', 'VGT_POLICY_LRU', 'VGT_POLICY_STREAM', + 'VGT_RDREQ_POLICY', 'VGT_STAGES_ES_EN', 'VGT_STAGES_GS_EN', + 'VGT_STAGES_HS_EN', 'VGT_STAGES_LS_EN', 'VGT_STAGES_VS_EN', + 'VGT_STREAMOUT_RESET', 'VGT_STREAMOUT_SYNC', 'VGT_TESS_PARTITION', + 'VGT_TESS_TOPOLOGY', 'VGT_TESS_TYPE', 'VGT_TE_PRIM_INDEX_LINE', + 'VGT_TE_PRIM_INDEX_QUAD', 'VGT_TE_PRIM_INDEX_TRI', 'VGT_TE_QUAD', + 'VID_ENHANCED_MODE', 'VID_NORMAL_FRAME_MODE', + 'VID_STREAM_DISABLE_MASKED', 'VID_STREAM_DISABLE_UNMASK', + 'VMEMCMD_RETURN_IN_ORDER', 'VMEMCMD_RETURN_IN_ORDER_READ', + 'VMEMCMD_RETURN_ORDER', 'VMEMCMD_RETURN_OUT_OF_ORDER', 'VMID_SZ', + 'VMPG_SIZE', 'VMPG_SIZE_4KB', 'VMPG_SIZE_64KB', 'VM_GROUP_SIZE', + 'VM_GROUP_SIZE_1024B', 'VM_GROUP_SIZE_128B', + 'VM_GROUP_SIZE_2048B', 'VM_GROUP_SIZE_256B', 'VM_GROUP_SIZE_512B', + 'VM_GROUP_SIZE_64B', 'VM_PG_SIZE_1024KB', 'VM_PG_SIZE_128KB', + 'VM_PG_SIZE_16KB', 'VM_PG_SIZE_2048KB', 'VM_PG_SIZE_256KB', + 'VM_PG_SIZE_32KB', 'VM_PG_SIZE_4KB', 'VM_PG_SIZE_512KB', + 'VM_PG_SIZE_64KB', 'VM_PG_SIZE_8KB', + 'VPG_MEM_DISABLE_MEM_PWR_CTRL', 'VPG_MEM_ENABLE_MEM_PWR_CTRL', + 'VPG_MEM_FORCE_LIGHT_SLEEP_REQ', 'VPG_MEM_NO_FORCE_REQ', + 'VPG_MEM_PWR_DIS_CTRL', 'VPG_MEM_PWR_FORCE_CTRL', + 'VREADY_AT_OR_AFTER_VSYNC', 'VREADY_BEFORE_VSYNC', + 'VRSCombinerModeSC', 'VRS_SHADING_RATE_16X_SSAA', + 'VRS_SHADING_RATE_1X1', 'VRS_SHADING_RATE_1X2', + 'VRS_SHADING_RATE_2X1', 'VRS_SHADING_RATE_2X2', + 'VRS_SHADING_RATE_2X4', 'VRS_SHADING_RATE_2X_SSAA', + 'VRS_SHADING_RATE_4X2', 'VRS_SHADING_RATE_4X4', + 'VRS_SHADING_RATE_4X_SSAA', 'VRS_SHADING_RATE_8X_SSAA', + 'VRS_SHADING_RATE_UNDEFINED0', 'VRS_SHADING_RATE_UNDEFINED1', + 'VRS_SHADING_RATE_UNDEFINED2', 'VRS_SHADING_RATE_UNDEFINED3', + 'VRS_SHADING_RATE_UNDEFINED4', 'VRSrate', 'VSYNC_CNT_LATCH_MASK', + 'VSYNC_CNT_LATCH_MASK_0', 'VSYNC_CNT_LATCH_MASK_1', + 'VSYNC_CNT_RESET_SEL', 'VSYNC_CNT_RESET_SEL_0', + 'VSYNC_CNT_RESET_SEL_1', 'VS_PARTIAL_FLUSH', + 'VS_STAGE_COPY_SHADER', 'VS_STAGE_DS', 'VS_STAGE_REAL', + 'VTG_SEL_0', 'VTG_SEL_1', 'VTG_SEL_2', 'VTG_SEL_3', 'VTG_SEL_4', + 'VTG_SEL_5', 'WAIT_SYNC', 'WATERMARK_MODE', 'WD_IA_DRAW_REG_XFER', + 'WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC', + 'WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE', + 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM', + 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1', + 'WD_IA_DRAW_REG_XFER_GE_CNTL', + 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN', + 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 'WD_IA_DRAW_SOURCE', 'WD_IA_DRAW_SOURCE_AUTO', + 'WD_IA_DRAW_SOURCE_DMA', 'WD_IA_DRAW_SOURCE_IMMD', + 'WD_IA_DRAW_SOURCE_OPAQ', 'WD_IA_DRAW_TYPE', + 'WD_IA_DRAW_TYPE_DI_MM0', 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 'WD_IA_DRAW_TYPE_EVENT_INIT', 'WD_IA_DRAW_TYPE_IMM_DATA', + 'WD_IA_DRAW_TYPE_INDX_OFF', 'WD_IA_DRAW_TYPE_MAX_INDX', + 'WD_IA_DRAW_TYPE_MIN_INDX', 'WD_IA_DRAW_TYPE_REG_XFER', + 'WRITE_BASE_ONLY', 'WRITE_BOTH', 'WritePolicy', 'XNORM', + 'XNORM_A', 'XNORM_B', 'XTAL_REF_CLOCK_SOURCE_SEL', + 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', + 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', 'XTAL_REF_SEL', + 'XTAL_REF_SEL_1X', 'XTAL_REF_SEL_2X', 'Y10_CbCr1010_420_PLANAR', + 'Y10_CrCb1010_420_PLANAR', 'Y12_CbCr1212_420_PLANAR', + 'Y12_CrCb1212_420_PLANAR', 'Y8_CbCr88_420_PLANAR', + 'Y8_CrCb88_420_PLANAR', 'YCbYCr10101010_422_PACKED', + 'YCbYCr12121212_422_PACKED', 'YCbYCr8888_422_PACKED', + 'YCrCbA16161616_10LSB', 'YCrCbA16161616_10MSB', + 'YCrCbA16161616_12LSB', 'YCrCbA16161616_12MSB', 'YCrCbA8888', + 'YCrYCb10101010_422_PACKED', 'YCrYCb12121212_422_PACKED', + 'YCrYCb8888_422_PACKED', 'Y_G_DATA_ONTO_ALPHA_PORT', + 'Y_G_DATA_ONTO_CB_B_PORT', 'Y_G_DATA_ONTO_CR_R_PORT', + 'Y_G_DATA_ONTO_Y_G_PORT', 'ZLimitSumm', 'ZModeForce', 'ZOrder', + 'ZPASS_DISABLE', 'ZPASS_PIXELS', 'ZPASS_SAMPLES', + 'ZSamplePosition', 'Z_SAMPLE_CENTER', 'Z_SAMPLE_CENTROID', + 'ZpassControl', '_soc21_ENUM_HEADER', 'ge1_assembler_busy', + 'ge1_assembler_dma_starved', 'ge1_assembler_stalled', + 'ge1_dma_busy', 'ge1_dma_lat_bin_0', 'ge1_dma_lat_bin_1', + 'ge1_dma_lat_bin_2', 'ge1_dma_lat_bin_3', 'ge1_dma_lat_bin_4', + 'ge1_dma_lat_bin_5', 'ge1_dma_lat_bin_6', 'ge1_dma_lat_bin_7', + 'ge1_dma_return_cl0', 'ge1_dma_return_cl1', + 'ge1_dma_return_size_cl0', 'ge1_dma_return_size_cl1', + 'ge1_dma_utcl1_consecutive_retry_event', + 'ge1_dma_utcl1_request_event', 'ge1_dma_utcl1_retry_event', + 'ge1_dma_utcl1_stall_event', 'ge1_dma_utcl1_stall_utcl2_event', + 'ge1_dma_utcl1_translation_hit_event', + 'ge1_dma_utcl1_translation_miss_event', 'ge1_pipe0_to_pipe1', + 'ge1_pipe1_to_pipe0', 'ge1_prim_group_limit_hit', + 'ge1_rbiu_di_fifo_stalled_p0', 'ge1_rbiu_di_fifo_stalled_p1', + 'ge1_rbiu_di_fifo_starved_p0', 'ge1_rbiu_di_fifo_starved_p1', + 'ge1_rbiu_dr_fifo_stalled_p0', 'ge1_rbiu_dr_fifo_stalled_p1', + 'ge1_rbiu_dr_fifo_starved_p0', 'ge1_rbiu_dr_fifo_starved_p1', + 'ge1_sclk_input_vld', 'ge1_sclk_reg_vld', + 'ge1_small_draws_one_instance', 'ge1_stat_busy', + 'ge1_stat_no_dma_busy', 'ge1_unopt_multi_instance_draws', + 'ge_agm_gcr_crd_stall', 'ge_agm_gcr_latency', 'ge_agm_gcr_req', + 'ge_agm_gcr_stall', 'ge_agm_gcr_tag_stall', 'ge_all_tf2', + 'ge_all_tf3', 'ge_all_tf4', 'ge_all_tf5', 'ge_all_tf6', + 'ge_all_tf_eq', 'ge_csb_spi_bp', 'ge_dist_distributer_busy', + 'ge_dist_hs_done', 'ge_dist_hs_done_latency', + 'ge_dist_hs_done_latency_se0', 'ge_dist_hs_done_latency_se1', + 'ge_dist_hs_done_latency_se2', 'ge_dist_hs_done_latency_se3', + 'ge_dist_hs_done_latency_se4', 'ge_dist_hs_done_latency_se5', + 'ge_dist_hs_done_latency_se6', 'ge_dist_hs_done_latency_se7', + 'ge_dist_hs_done_se0', 'ge_dist_hs_done_se1', + 'ge_dist_hs_done_se2', 'ge_dist_hs_done_se3', + 'ge_dist_hs_done_se4', 'ge_dist_hs_done_se5', + 'ge_dist_hs_done_se6', 'ge_dist_hs_done_se7', + 'ge_dist_inside_tf_bin_0', 'ge_dist_inside_tf_bin_1', + 'ge_dist_inside_tf_bin_2', 'ge_dist_inside_tf_bin_3', + 'ge_dist_inside_tf_bin_4', 'ge_dist_inside_tf_bin_5', + 'ge_dist_inside_tf_bin_6', 'ge_dist_inside_tf_bin_7', + 'ge_dist_inside_tf_bin_8', 'ge_dist_null_patch', + 'ge_dist_op_fifo_full_starve', 'ge_dist_pc_feorder_fifo_full', + 'ge_dist_pc_ge_manager_busy', 'ge_dist_pc_req_stall_se0', + 'ge_dist_pc_req_stall_se1', 'ge_dist_pc_req_stall_se2', + 'ge_dist_pc_req_stall_se3', 'ge_dist_pc_req_stall_se4', + 'ge_dist_pc_req_stall_se5', 'ge_dist_pc_req_stall_se6', + 'ge_dist_pc_req_stall_se7', 'ge_dist_pc_space_zero', + 'ge_dist_reserved', 'ge_dist_sclk_core_vld', + 'ge_dist_sclk_input_vld', 'ge_dist_sclk_wd_te11_vld', + 'ge_dist_switch_mode_stall', 'ge_dist_te11_starved', + 'ge_dist_tfreq_lat_bin_0', 'ge_dist_tfreq_lat_bin_1', + 'ge_dist_tfreq_lat_bin_2', 'ge_dist_tfreq_lat_bin_3', + 'ge_dist_tfreq_lat_bin_4', 'ge_dist_tfreq_lat_bin_5', + 'ge_dist_tfreq_lat_bin_6', 'ge_dist_tfreq_lat_bin_7', + 'ge_dist_tfreq_utcl1_consecutive_retry_event', + 'ge_dist_tfreq_utcl1_request_event', + 'ge_dist_tfreq_utcl1_retry_event', + 'ge_dist_tfreq_utcl1_stall_event', + 'ge_dist_tfreq_utcl1_stall_utcl2_event', + 'ge_dist_tfreq_utcl1_translation_hit_event', + 'ge_dist_tfreq_utcl1_translation_miss_event', + 'ge_dist_vs_pc_stall', 'ge_dist_wd_te11_busy', 'ge_distclk_vld', + 'ge_esvert_send', 'ge_gs_issue_rtr_stalled', 'ge_gsprim_send', + 'ge_gsprim_stalled_esvert', 'ge_gsthread_stalled', + 'ge_hs_stall_tfmm_fifo_full', 'ge_hs_tif_stall', + 'ge_ngg_agm_req_stall', 'ge_ngg_attr_discard_alloc', + 'ge_ngg_attr_grp_alloc', 'ge_ngg_attr_grp_latency', + 'ge_ngg_indx_bus_stall', 'ge_ngg_ord_id_req_stall', + 'ge_ngg_pc_space_not_avail', 'ge_ngg_reuse_prim_limit_hit', + 'ge_ngg_reuse_vert_limit_hit', 'ge_ngg_spi_esvert_partial_eov', + 'ge_ngg_spi_gsprim_partial_eov', 'ge_ngg_stall_tess_off_tess_on', + 'ge_ngg_stall_tess_on_tess_off', 'ge_ngg_starved_after_work', + 'ge_ngg_starved_idle', 'ge_ngg_starving_for_pc_grant', + 'ge_ngg_subgrp_fifo_stall', 'ge_num_of_donut_dist_patches', + 'ge_num_of_hs_alloc_events', 'ge_num_of_no_dist_patches', + 'ge_num_of_patch_dist_patches', + 'ge_num_of_se_switches_due_to_donut', + 'ge_num_of_se_switches_due_to_patch_accum', + 'ge_num_of_se_switches_due_to_trap', 'ge_pa0_csb_eop', + 'ge_pa1_csb_eop', 'ge_se0_te11_starved_on_hs_done', + 'ge_se1_te11_starved_on_hs_done', + 'ge_se2_te11_starved_on_hs_done', + 'ge_se3_te11_starved_on_hs_done', + 'ge_se4_te11_starved_on_hs_done', + 'ge_se5_te11_starved_on_hs_done', + 'ge_se6_te11_starved_on_hs_done', + 'ge_se7_te11_starved_on_hs_done', 'ge_se_ds_prims', + 'ge_se_es_thread_groups', 'ge_se_esvert_stalled_gsprim', + 'ge_se_hs_input_stall', 'ge_se_hs_tfm_stall', + 'ge_se_hs_tgs_active_high_water_mark', 'ge_se_hs_thread_groups', + 'ge_se_reused_es_indices', 'ge_se_sclk_input_vld', + 'ge_se_sclk_ngg_vld', 'ge_se_sclk_te11_vld', + 'ge_se_sending_vert_or_prim', 'ge_se_spi_esvert_eov', + 'ge_se_spi_esvert_stalled', 'ge_se_spi_esvert_starved_busy', + 'ge_se_spi_esvert_valid', 'ge_se_spi_gsprim_cont', + 'ge_se_spi_gsprim_eov', 'ge_se_spi_gsprim_stalled', + 'ge_se_spi_gsprim_starved_busy', 'ge_se_spi_gsprim_valid', + 'ge_se_spi_gssubgrp_event_window_active', + 'ge_se_spi_gssubgrp_is_event', 'ge_se_spi_gssubgrp_send', + 'ge_se_spi_hsvert_eov', 'ge_se_spi_hsvert_fifo_full_stall', + 'ge_se_spi_hsvert_stalled', 'ge_se_spi_hsvert_starved_busy', + 'ge_se_spi_hsvert_valid', 'ge_se_spi_hswave_is_event', + 'ge_se_spi_hswave_send', 'ge_se_spi_lsvert_eov', + 'ge_se_spi_lsvert_stalled', 'ge_se_spi_lsvert_starved_busy', + 'ge_se_spi_lsvert_valid', 'ge_se_spi_tgrp_fifo_stall', + 'ge_spi_gsgrp_valid', 'ge_spi_hsgrp_spi_stall', + 'ge_spi_hswave_fifo_full_stall', 'ge_spi_lswave_fifo_full_stall', + 'ge_te11_compactor_starved', 'ge_te11_con_stall', + 'ge_te11_stall_prim_funnel', 'ge_te11_stall_vert_funnel', + 'ge_tf_ret_data_stalling_hs_done'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/soc24.py b/tinygrad_repo/tinygrad/runtime/autogen/am/soc24.py new file mode 100644 index 0000000000..42e5a60365 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/soc24.py @@ -0,0 +1,37140 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + + + +_soc24_ENUM_HEADER = True # macro +CSDATA_TYPE_WIDTH = 0x00000002 # macro +CSDATA_ADDR_WIDTH = 0x00000007 # macro +CSDATA_DATA_WIDTH = 0x00000020 # macro +CSCNTL_TYPE_WIDTH = 0x00000002 # macro +CSCNTL_ADDR_WIDTH = 0x00000007 # macro +CSCNTL_DATA_WIDTH = 0x00000020 # macro +GSTHREADID_SIZE = 0x00000002 # macro +IQ_QUEUE_SLEEP = 0x00000000 # macro +IQ_OFFLOAD_RETRY = 0x00000001 # macro +IQ_SCH_WAVE_MSG = 0x00000002 # macro +IQ_DEQUEUE_RETRY = 0x00000004 # macro +IQ_INTR_TYPE_PQ = 0x00000000 # macro +IQ_INTR_TYPE_IB = 0x00000001 # macro +IQ_INTR_TYPE_MQD = 0x00000002 # macro +VMID_SZ = 0x00000004 # macro +CONFIG_SPACE_START = 0x00002000 # macro +CONFIG_SPACE_END = 0x00009fff # macro +CONFIG_SPACE1_START = 0x00002000 # macro +CONFIG_SPACE1_END = 0x00002bff # macro +CONFIG_SPACE2_START = 0x00003000 # macro +CONFIG_SPACE2_END = 0x00009fff # macro +UCONFIG_SPACE_START = 0x0000c000 # macro +UCONFIG_SPACE_END = 0x0000ffff # macro +PERSISTENT_SPACE_START = 0x00002c00 # macro +PERSISTENT_SPACE_END = 0x00002fff # macro +CONTEXT_SPACE_START = 0x0000a000 # macro +CONTEXT_SPACE_END = 0x0000a3ff # macro +SQ_WAVE_TYPE_PS0 = 0x00000000 # macro +SQ_FLAT = 0x00000000 # macro +SQ_SCRATCH = 0x00000001 # macro +SQ_GLOBAL = 0x00000002 # macro +SQIND_GLOBAL_REGS_OFFSET = 0x00000000 # macro +SQIND_GLOBAL_REGS_SIZE = 0x00000008 # macro +SQIND_LOCAL_REGS_OFFSET = 0x00000008 # macro +SQIND_LOCAL_REGS_SIZE = 0x00000008 # macro +SQIND_WAVE_HW_REGS_OFFSET = 0x00000100 # macro +SQIND_WAVE_HW_REGS_SIZE = 0x00000040 # macro +SQIND_WAVE_HOST_REGS_OFFSET = 0x00000140 # macro +SQIND_WAVE_HOST_REGS_SIZE = 0x000000c0 # macro +SQIND_WAVE_SGPRS_OFFSET = 0x00000200 # macro +SQIND_WAVE_SGPRS_SIZE = 0x00000200 # macro +SQIND_WAVE_VGPRS_OFFSET = 0x00000400 # macro +SQIND_WAVE_VGPRS_SIZE = 0x00000400 # macro +SQ_GFXDEC_BEGIN = 0x0000a000 # macro +SQ_GFXDEC_END = 0x0000c000 # macro +SQ_GFXDEC_STATE_ID_SHIFT = 0x0000000a # macro +SQDEC_BEGIN = 0x00002300 # macro +SQDEC_END = 0x000023ff # macro +PFVF_SQDEC_BEGIN = 0x0000a9e0 # macro +PFVF_SQDEC_END = 0x0000a9ff # macro +SQPERFSDEC_BEGIN = 0x0000d9c0 # macro +SQPERFSDEC_END = 0x0000da40 # macro +SQPERFDDEC_BEGIN = 0x0000d1c0 # macro +SQPERFDDEC_END = 0x0000d240 # macro +SQGFXUDEC_BEGIN = 0x0000c330 # macro +SQGFXUDEC_END = 0x0000c380 # macro +SQPWRDEC_BEGIN = 0x0000f08c # macro +SQPWRDEC_END = 0x0000f094 # macro +SQ_DISPATCHER_GFX_MIN = 0x00000010 # macro +SQ_DISPATCHER_GFX_CNT_PER_RING = 0x00000008 # macro +SQ_MAX_PGM_SGPRS = 0x00000068 # macro +SQ_MAX_PGM_VGPRS = 0x00000100 # macro +SQ_EX_EXCP_VALU_BASE = 0x00000000 # macro +SQ_EX_EXCP_VALU_SIZE = 0x00000007 # macro +SQ_EX_EXCP_ALU_INVALID = 0x00000000 # macro +SQ_EX_EXCP_ALU_INPUT_DENORM = 0x00000001 # macro +SQ_EX_EXCP_ALU_FLOAT_DIV0 = 0x00000002 # macro +SQ_EX_EXCP_ALU_OVERFLOW = 0x00000003 # macro +SQ_EX_EXCP_ALU_UNDERFLOW = 0x00000004 # macro +SQ_EX_EXCP_ALU_INEXACT = 0x00000005 # macro +SQ_EX_EXCP_ALU_INT_DIV0 = 0x00000006 # macro +SQ_EX_EXCP_ADDR_WATCH = 0x00000007 # macro +INST_ID_PRIV_START = 0x80000000 # macro +INST_ID_ECC_INTERRUPT_MSG = 0xfffffff0 # macro +INST_ID_TTRACE_NEW_PC_MSG = 0xfffffff1 # macro +INST_ID_HW_TRAP = 0xfffffff2 # macro +INST_ID_KILL_SEQ = 0xfffffff3 # macro +INST_ID_SPI_WREXEC = 0xfffffff4 # macro +INST_ID_HW_TRAP_GET_TBA = 0xfffffff5 # macro +INST_ID_HOST_REG_TRAP_MSG = 0xfffffffe # macro +SIMM16_WAITCNT_EXP_CNT_START = 0x00000000 # macro +SIMM16_WAITCNT_EXP_CNT_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_LGKM_CNT_START = 0x00000004 # macro +SIMM16_WAITCNT_LGKM_CNT_SIZE = 0x00000006 # macro +SIMM16_WAITCNT_VM_CNT_START = 0x0000000a # macro +SIMM16_WAITCNT_VM_CNT_SIZE = 0x00000006 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_START = 0x00000000 # macro +SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_START = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_START = 0x00000002 # macro +SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_HOLD_CNT_START = 0x00000007 # macro +SIMM16_WAITCNT_DEPCTR_HOLD_CNT_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_START = 0x00000008 # macro +SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE = 0x00000001 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_START = 0x00000009 # macro +SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_START = 0x0000000c # macro +SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE = 0x00000004 # macro +SIMM16_WAIT_EVENT_EXP_RDY_START = 0x00000000 # macro +SIMM16_WAIT_EVENT_EXP_RDY_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_SA_SDST_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_SA_EXEC_SIZE = 0x00000002 # macro +SQ_WAVE_IB_DEP_SA_M0_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_VM_VSRC_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_HOLD_CNT_SIZE = 0x00000001 # macro +SQ_WAVE_IB_DEP_VA_SSRC_SIZE = 0x00000003 # macro +SQ_WAVE_IB_DEP_VA_SDST_SIZE = 0x00000004 # macro +SQ_WAVE_IB_DEP_VA_VCC_SIZE = 0x00000003 # macro +SQ_WAVE_IB_DEP_VA_EXEC_SIZE = 0x00000002 # macro +SQ_WAVE_IB_DEP_VA_VDST_SIZE = 0x00000005 # macro +SQ_WAVE_IB_DEP_LDS_DIR_SIZE = 0x00000003 # macro +SQ_ARB_STATE_ISSUED_BRMSG = 0x00000000 # macro +SQ_ARB_STATE_ISSUED_EXPORT = 0x00000001 # macro +SQ_ARB_STATE_ISSUED_LDS_DIRECT = 0x00000002 # macro +SQ_ARB_STATE_ISSUED_LDS = 0x00000003 # macro +SQ_ARB_STATE_ISSUED_TEX = 0x00000004 # macro +SQ_ARB_STATE_ISSUED_SCALAR = 0x00000005 # macro +SQ_ARB_STATE_ISSUED_VALU = 0x00000006 # macro +SQ_ARB_STATE_STALLED_BRMSG = 0x00000008 # macro +SQ_ARB_STATE_STALLED_EXPORT = 0x00000009 # macro +SQ_ARB_STATE_STALLED_LDS_DIRECT = 0x0000000a # macro +SQ_ARB_STATE_STALLED_LDS = 0x0000000b # macro +SQ_ARB_STATE_STALLED_TEX = 0x0000000c # macro +SQ_ARB_STATE_STALLED_SCALAR = 0x0000000d # macro +SQ_ARB_STATE_STALLED_VALU = 0x0000000e # macro +ROM_SIGNATURE = 0x0000aa55 # macro + +# values for enumeration 'CP_PERFMON_ENABLE_MODE' +CP_PERFMON_ENABLE_MODE__enumvalues = { + 0: 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 1: 'CP_PERFMON_ENABLE_MODE_RESERVED_1', + 2: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 3: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', +} +CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT = 0 +CP_PERFMON_ENABLE_MODE_RESERVED_1 = 1 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE = 2 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE = 3 +CP_PERFMON_ENABLE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_STATE' +CP_PERFMON_STATE__enumvalues = { + 0: 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'CP_PERFMON_STATE_START_COUNTING', + 2: 'CP_PERFMON_STATE_STOP_COUNTING', + 3: 'CP_PERFMON_STATE_RESERVED_3', + 4: 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +CP_PERFMON_STATE_DISABLE_AND_RESET = 0 +CP_PERFMON_STATE_START_COUNTING = 1 +CP_PERFMON_STATE_STOP_COUNTING = 2 +CP_PERFMON_STATE_RESERVED_3 = 3 +CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +CP_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_NUM_SIMD_PER_CU' +ENUM_NUM_SIMD_PER_CU__enumvalues = { + 2: 'NUM_SIMD_PER_CU', +} +NUM_SIMD_PER_CU = 2 +ENUM_NUM_SIMD_PER_CU = ctypes.c_uint32 # enum + +# values for enumeration 'GATCL1RequestType' +GATCL1RequestType__enumvalues = { + 0: 'GATCL1_TYPE_NORMAL', + 1: 'GATCL1_TYPE_SHOOTDOWN', + 2: 'GATCL1_TYPE_BYPASS', +} +GATCL1_TYPE_NORMAL = 0 +GATCL1_TYPE_SHOOTDOWN = 1 +GATCL1_TYPE_BYPASS = 2 +GATCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'GL0V_CACHE_POLICIES' +GL0V_CACHE_POLICIES__enumvalues = { + 0: 'GL0V_CACHE_POLICY_MISS_LRU', + 1: 'GL0V_CACHE_POLICY_MISS_EVICT', + 2: 'GL0V_CACHE_POLICY_HIT_LRU', + 3: 'GL0V_CACHE_POLICY_HIT_EVICT', + 4: 'GL0V_CACHE_POLICY_MISS_INVAL', +} +GL0V_CACHE_POLICY_MISS_LRU = 0 +GL0V_CACHE_POLICY_MISS_EVICT = 1 +GL0V_CACHE_POLICY_HIT_LRU = 2 +GL0V_CACHE_POLICY_HIT_EVICT = 3 +GL0V_CACHE_POLICY_MISS_INVAL = 4 +GL0V_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_POLICIES' +GL1_CACHE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_POLICY_MISS_LRU', + 1: 'GL1_CACHE_POLICY_MISS_EVICT', + 2: 'GL1_CACHE_POLICY_HIT_LRU', + 3: 'GL1_CACHE_POLICY_HIT_EVICT', +} +GL1_CACHE_POLICY_MISS_LRU = 0 +GL1_CACHE_POLICY_MISS_EVICT = 1 +GL1_CACHE_POLICY_HIT_LRU = 2 +GL1_CACHE_POLICY_HIT_EVICT = 3 +GL1_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL1_CACHE_STORE_POLICIES' +GL1_CACHE_STORE_POLICIES__enumvalues = { + 0: 'GL1_CACHE_STORE_POLICY_BYPASS', +} +GL1_CACHE_STORE_POLICY_BYPASS = 0 +GL1_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_CACHE_POLICIES' +GL2_CACHE_POLICIES__enumvalues = { + 0: 'GL2_CACHE_POLICY_LRU', + 1: 'GL2_CACHE_POLICY_STREAM', + 2: 'GL2_CACHE_POLICY_NOA', + 3: 'GL2_CACHE_POLICY_BYPASS', +} +GL2_CACHE_POLICY_LRU = 0 +GL2_CACHE_POLICY_STREAM = 1 +GL2_CACHE_POLICY_NOA = 2 +GL2_CACHE_POLICY_BYPASS = 3 +GL2_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_NACKS' +GL2_NACKS__enumvalues = { + 0: 'GL2_NACK_NO_FAULT', + 1: 'GL2_NACK_PAGE_FAULT', + 2: 'GL2_NACK_PROTECTION_FAULT', + 3: 'GL2_NACK_DATA_ERROR', +} +GL2_NACK_NO_FAULT = 0 +GL2_NACK_PAGE_FAULT = 1 +GL2_NACK_PROTECTION_FAULT = 2 +GL2_NACK_DATA_ERROR = 3 +GL2_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP' +GL2_OP__enumvalues = { + 0: 'GL2_OP_READ', + 1: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'GL2_OP_ATOMIC_FMIN_RTN_32', + 3: 'GL2_OP_ATOMIC_FMAX_RTN_32', + 4: 'GL2_OP_ATOMIC_PK_ADD_FP16_RTN', + 5: 'GL2_OP_ATOMIC_FADD_RTN_32', + 6: 'GL2_OP_ATOMIC_PK_ADD_BF16_RTN', + 7: 'GL2_OP_ATOMIC_SWAP_RTN_32', + 8: 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'GL2_OP_PROBE_FILTER', + 13: 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 14: 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'GL2_OP_ATOMIC_ADD_RTN_32', + 16: 'GL2_OP_ATOMIC_SUB_RTN_32', + 17: 'GL2_OP_ATOMIC_SMIN_RTN_32', + 18: 'GL2_OP_ATOMIC_UMIN_RTN_32', + 19: 'GL2_OP_ATOMIC_SMAX_RTN_32', + 20: 'GL2_OP_ATOMIC_UMAX_RTN_32', + 21: 'GL2_OP_ATOMIC_AND_RTN_32', + 22: 'GL2_OP_ATOMIC_OR_RTN_32', + 23: 'GL2_OP_ATOMIC_XOR_RTN_32', + 24: 'GL2_OP_ATOMIC_INC_RTN_32', + 25: 'GL2_OP_ATOMIC_DEC_RTN_32', + 26: 'GL2_OP_ATOMIC_CLAMP_SUB_RTN_32', + 27: 'GL2_OP_ATOMIC_COND_SUB_RTN_32', + 29: 'GL2_OP_UTC_PROBE', + 30: 'GL2_OP_LOAD_RESERVE', + 32: 'GL2_OP_WRITE', + 33: 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'GL2_OP_ATOMIC_FMIN_RTN_64', + 35: 'GL2_OP_ATOMIC_FMAX_RTN_64', + 39: 'GL2_OP_ATOMIC_SWAP_RTN_64', + 40: 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 47: 'GL2_OP_ATOMIC_ADD_RTN_64', + 48: 'GL2_OP_ATOMIC_SUB_RTN_64', + 49: 'GL2_OP_ATOMIC_SMIN_RTN_64', + 50: 'GL2_OP_ATOMIC_UMIN_RTN_64', + 51: 'GL2_OP_ATOMIC_SMAX_RTN_64', + 52: 'GL2_OP_ATOMIC_UMAX_RTN_64', + 53: 'GL2_OP_ATOMIC_AND_RTN_64', + 54: 'GL2_OP_ATOMIC_OR_RTN_64', + 55: 'GL2_OP_ATOMIC_XOR_RTN_64', + 56: 'GL2_OP_ATOMIC_INC_RTN_64', + 57: 'GL2_OP_ATOMIC_DEC_RTN_64', + 59: 'GL2_OP_WRITE_ZERO_SIZE', + 61: 'GL2_OP_GL2_INV', + 62: 'GL2_OP_ATOMIC_STORE_COND_RTN', + 64: 'GL2_OP_GL1_INV', + 65: 'GL2_OP_ATOMIC_FCMPSWAP_32', + 66: 'GL2_OP_ATOMIC_FMIN_32', + 67: 'GL2_OP_ATOMIC_FMAX_32', + 68: 'GL2_OP_ATOMIC_PK_ADD_FP16', + 69: 'GL2_OP_ATOMIC_FADD_32', + 70: 'GL2_OP_ATOMIC_PK_ADD_BF16', + 71: 'GL2_OP_ATOMIC_SWAP_32', + 72: 'GL2_OP_ATOMIC_CMPSWAP_32', + 73: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'GL2_OP_ATOMIC_UMIN_8', + 77: 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 79: 'GL2_OP_ATOMIC_ADD_32', + 80: 'GL2_OP_ATOMIC_SUB_32', + 81: 'GL2_OP_ATOMIC_SMIN_32', + 82: 'GL2_OP_ATOMIC_UMIN_32', + 83: 'GL2_OP_ATOMIC_SMAX_32', + 84: 'GL2_OP_ATOMIC_UMAX_32', + 85: 'GL2_OP_ATOMIC_AND_32', + 86: 'GL2_OP_ATOMIC_OR_32', + 87: 'GL2_OP_ATOMIC_XOR_32', + 88: 'GL2_OP_ATOMIC_INC_32', + 89: 'GL2_OP_ATOMIC_DEC_32', + 91: 'GL2_OP_NOP_RTN0', + 93: 'GL2_OP_GL2_WB', + 94: 'GL2_OP_FORCE_EXISTING_DATA_TO_DECOMPRESS', + 97: 'GL2_OP_ATOMIC_FCMPSWAP_64', + 98: 'GL2_OP_ATOMIC_FMIN_64', + 99: 'GL2_OP_ATOMIC_FMAX_64', + 103: 'GL2_OP_ATOMIC_SWAP_64', + 104: 'GL2_OP_ATOMIC_CMPSWAP_64', + 105: 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 111: 'GL2_OP_ATOMIC_ADD_64', + 112: 'GL2_OP_ATOMIC_SUB_64', + 113: 'GL2_OP_ATOMIC_SMIN_64', + 114: 'GL2_OP_ATOMIC_UMIN_64', + 115: 'GL2_OP_ATOMIC_SMAX_64', + 116: 'GL2_OP_ATOMIC_UMAX_64', + 117: 'GL2_OP_ATOMIC_AND_64', + 118: 'GL2_OP_ATOMIC_OR_64', + 119: 'GL2_OP_ATOMIC_XOR_64', + 120: 'GL2_OP_ATOMIC_INC_64', + 121: 'GL2_OP_ATOMIC_DEC_64', + 122: 'GL2_OP_ATOMIC_UMAX_8', + 123: 'GL2_OP_NOP_ACK', + 125: 'GL2_OP_GL2_WBINV', + 126: 'GL2_OP_READ_COMPRESSION_KEY', +} +GL2_OP_READ = 0 +GL2_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +GL2_OP_ATOMIC_FMIN_RTN_32 = 2 +GL2_OP_ATOMIC_FMAX_RTN_32 = 3 +GL2_OP_ATOMIC_PK_ADD_FP16_RTN = 4 +GL2_OP_ATOMIC_FADD_RTN_32 = 5 +GL2_OP_ATOMIC_PK_ADD_BF16_RTN = 6 +GL2_OP_ATOMIC_SWAP_RTN_32 = 7 +GL2_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +GL2_OP_PROBE_FILTER = 12 +GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32 = 13 +GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +GL2_OP_ATOMIC_ADD_RTN_32 = 15 +GL2_OP_ATOMIC_SUB_RTN_32 = 16 +GL2_OP_ATOMIC_SMIN_RTN_32 = 17 +GL2_OP_ATOMIC_UMIN_RTN_32 = 18 +GL2_OP_ATOMIC_SMAX_RTN_32 = 19 +GL2_OP_ATOMIC_UMAX_RTN_32 = 20 +GL2_OP_ATOMIC_AND_RTN_32 = 21 +GL2_OP_ATOMIC_OR_RTN_32 = 22 +GL2_OP_ATOMIC_XOR_RTN_32 = 23 +GL2_OP_ATOMIC_INC_RTN_32 = 24 +GL2_OP_ATOMIC_DEC_RTN_32 = 25 +GL2_OP_ATOMIC_CLAMP_SUB_RTN_32 = 26 +GL2_OP_ATOMIC_COND_SUB_RTN_32 = 27 +GL2_OP_UTC_PROBE = 29 +GL2_OP_LOAD_RESERVE = 30 +GL2_OP_WRITE = 32 +GL2_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +GL2_OP_ATOMIC_FMIN_RTN_64 = 34 +GL2_OP_ATOMIC_FMAX_RTN_64 = 35 +GL2_OP_ATOMIC_SWAP_RTN_64 = 39 +GL2_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +GL2_OP_ATOMIC_ADD_RTN_64 = 47 +GL2_OP_ATOMIC_SUB_RTN_64 = 48 +GL2_OP_ATOMIC_SMIN_RTN_64 = 49 +GL2_OP_ATOMIC_UMIN_RTN_64 = 50 +GL2_OP_ATOMIC_SMAX_RTN_64 = 51 +GL2_OP_ATOMIC_UMAX_RTN_64 = 52 +GL2_OP_ATOMIC_AND_RTN_64 = 53 +GL2_OP_ATOMIC_OR_RTN_64 = 54 +GL2_OP_ATOMIC_XOR_RTN_64 = 55 +GL2_OP_ATOMIC_INC_RTN_64 = 56 +GL2_OP_ATOMIC_DEC_RTN_64 = 57 +GL2_OP_WRITE_ZERO_SIZE = 59 +GL2_OP_GL2_INV = 61 +GL2_OP_ATOMIC_STORE_COND_RTN = 62 +GL2_OP_GL1_INV = 64 +GL2_OP_ATOMIC_FCMPSWAP_32 = 65 +GL2_OP_ATOMIC_FMIN_32 = 66 +GL2_OP_ATOMIC_FMAX_32 = 67 +GL2_OP_ATOMIC_PK_ADD_FP16 = 68 +GL2_OP_ATOMIC_FADD_32 = 69 +GL2_OP_ATOMIC_PK_ADD_BF16 = 70 +GL2_OP_ATOMIC_SWAP_32 = 71 +GL2_OP_ATOMIC_CMPSWAP_32 = 72 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +GL2_OP_ATOMIC_UMIN_8 = 76 +GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32 = 77 +GL2_OP_ATOMIC_ADD_32 = 79 +GL2_OP_ATOMIC_SUB_32 = 80 +GL2_OP_ATOMIC_SMIN_32 = 81 +GL2_OP_ATOMIC_UMIN_32 = 82 +GL2_OP_ATOMIC_SMAX_32 = 83 +GL2_OP_ATOMIC_UMAX_32 = 84 +GL2_OP_ATOMIC_AND_32 = 85 +GL2_OP_ATOMIC_OR_32 = 86 +GL2_OP_ATOMIC_XOR_32 = 87 +GL2_OP_ATOMIC_INC_32 = 88 +GL2_OP_ATOMIC_DEC_32 = 89 +GL2_OP_NOP_RTN0 = 91 +GL2_OP_GL2_WB = 93 +GL2_OP_FORCE_EXISTING_DATA_TO_DECOMPRESS = 94 +GL2_OP_ATOMIC_FCMPSWAP_64 = 97 +GL2_OP_ATOMIC_FMIN_64 = 98 +GL2_OP_ATOMIC_FMAX_64 = 99 +GL2_OP_ATOMIC_SWAP_64 = 103 +GL2_OP_ATOMIC_CMPSWAP_64 = 104 +GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +GL2_OP_ATOMIC_ADD_64 = 111 +GL2_OP_ATOMIC_SUB_64 = 112 +GL2_OP_ATOMIC_SMIN_64 = 113 +GL2_OP_ATOMIC_UMIN_64 = 114 +GL2_OP_ATOMIC_SMAX_64 = 115 +GL2_OP_ATOMIC_UMAX_64 = 116 +GL2_OP_ATOMIC_AND_64 = 117 +GL2_OP_ATOMIC_OR_64 = 118 +GL2_OP_ATOMIC_XOR_64 = 119 +GL2_OP_ATOMIC_INC_64 = 120 +GL2_OP_ATOMIC_DEC_64 = 121 +GL2_OP_ATOMIC_UMAX_8 = 122 +GL2_OP_NOP_ACK = 123 +GL2_OP_GL2_WBINV = 125 +GL2_OP_READ_COMPRESSION_KEY = 126 +GL2_OP = ctypes.c_uint32 # enum + +# values for enumeration 'GL2_OP_MASKS' +GL2_OP_MASKS__enumvalues = { + 8: 'GL2_OP_MASK_FLUSH_DENROM', + 32: 'GL2_OP_MASK_64', + 64: 'GL2_OP_MASK_NO_RTN', +} +GL2_OP_MASK_FLUSH_DENROM = 8 +GL2_OP_MASK_64 = 32 +GL2_OP_MASK_NO_RTN = 64 +GL2_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'Hdp_SurfaceEndian' +Hdp_SurfaceEndian__enumvalues = { + 0: 'HDP_ENDIAN_NONE', + 1: 'HDP_ENDIAN_8IN16', + 2: 'HDP_ENDIAN_8IN32', + 3: 'HDP_ENDIAN_8IN64', +} +HDP_ENDIAN_NONE = 0 +HDP_ENDIAN_8IN16 = 1 +HDP_ENDIAN_8IN32 = 2 +HDP_ENDIAN_8IN64 = 3 +Hdp_SurfaceEndian = ctypes.c_uint32 # enum + +# values for enumeration 'MTYPE' +MTYPE__enumvalues = { + 0: 'MTYPE_C_RW_US', + 1: 'MTYPE_RESERVED_1', + 2: 'MTYPE_C_RO_S', + 3: 'MTYPE_UC', + 4: 'MTYPE_C_RW_S', + 5: 'MTYPE_RESERVED_5', + 6: 'MTYPE_C_RO_US', + 7: 'MTYPE_RESERVED_7', +} +MTYPE_C_RW_US = 0 +MTYPE_RESERVED_1 = 1 +MTYPE_C_RO_S = 2 +MTYPE_UC = 3 +MTYPE_C_RW_S = 4 +MTYPE_RESERVED_5 = 5 +MTYPE_C_RO_US = 6 +MTYPE_RESERVED_7 = 7 +MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_COUNTER_MODE' +PERFMON_COUNTER_MODE__enumvalues = { + 0: 'PERFMON_COUNTER_MODE_ACCUM', + 1: 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 2: 'PERFMON_COUNTER_MODE_MAX', + 3: 'PERFMON_COUNTER_MODE_DIRTY', + 4: 'PERFMON_COUNTER_MODE_SAMPLE', + 5: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 6: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 7: 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 8: 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 9: 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 15: 'PERFMON_COUNTER_MODE_RESERVED', +} +PERFMON_COUNTER_MODE_ACCUM = 0 +PERFMON_COUNTER_MODE_ACTIVE_CYCLES = 1 +PERFMON_COUNTER_MODE_MAX = 2 +PERFMON_COUNTER_MODE_DIRTY = 3 +PERFMON_COUNTER_MODE_SAMPLE = 4 +PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT = 5 +PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT = 6 +PERFMON_COUNTER_MODE_CYCLES_GE_HI = 7 +PERFMON_COUNTER_MODE_CYCLES_EQ_HI = 8 +PERFMON_COUNTER_MODE_INACTIVE_CYCLES = 9 +PERFMON_COUNTER_MODE_RESERVED = 15 +PERFMON_COUNTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_SPM_MODE' +PERFMON_SPM_MODE__enumvalues = { + 0: 'PERFMON_SPM_MODE_OFF', + 1: 'PERFMON_SPM_MODE_16BIT_CLAMP', + 2: 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 3: 'PERFMON_SPM_MODE_32BIT_CLAMP', + 4: 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 5: 'PERFMON_SPM_MODE_RESERVED_5', + 6: 'PERFMON_SPM_MODE_RESERVED_6', + 7: 'PERFMON_SPM_MODE_RESERVED_7', + 8: 'PERFMON_SPM_MODE_TEST_MODE_0', + 9: 'PERFMON_SPM_MODE_TEST_MODE_1', + 10: 'PERFMON_SPM_MODE_TEST_MODE_2', +} +PERFMON_SPM_MODE_OFF = 0 +PERFMON_SPM_MODE_16BIT_CLAMP = 1 +PERFMON_SPM_MODE_16BIT_NO_CLAMP = 2 +PERFMON_SPM_MODE_32BIT_CLAMP = 3 +PERFMON_SPM_MODE_32BIT_NO_CLAMP = 4 +PERFMON_SPM_MODE_RESERVED_5 = 5 +PERFMON_SPM_MODE_RESERVED_6 = 6 +PERFMON_SPM_MODE_RESERVED_7 = 7 +PERFMON_SPM_MODE_TEST_MODE_0 = 8 +PERFMON_SPM_MODE_TEST_MODE_1 = 9 +PERFMON_SPM_MODE_TEST_MODE_2 = 10 +PERFMON_SPM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'READ_COMPRESSION_MODE' +READ_COMPRESSION_MODE__enumvalues = { + 0: 'COMPRESSION_MODE_BYPASS_COMPRESSION', + 1: 'COMPRESSION_MODE_READ_RAW_COMPRESSED_DATA', + 2: 'COMPRESSION_MODE_READ_DECOMPRESSED', +} +COMPRESSION_MODE_BYPASS_COMPRESSION = 0 +COMPRESSION_MODE_READ_RAW_COMPRESSED_DATA = 1 +COMPRESSION_MODE_READ_DECOMPRESSED = 2 +READ_COMPRESSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ReadPolicy' +ReadPolicy__enumvalues = { + 0: 'CACHE_LRU_RD', + 1: 'CACHE_STREAM_RD', + 2: 'CACHE_NOA', + 3: 'RESERVED_RDPOLICY', +} +CACHE_LRU_RD = 0 +CACHE_STREAM_RD = 1 +CACHE_NOA = 2 +RESERVED_RDPOLICY = 3 +ReadPolicy = ctypes.c_uint32 # enum + +# values for enumeration 'SCOPE' +SCOPE__enumvalues = { + 0: 'SCOPE_CU', + 1: 'SCOPE_SE', + 2: 'SCOPE_DEV', + 3: 'SCOPE_SYS', +} +SCOPE_CU = 0 +SCOPE_SE = 1 +SCOPE_DEV = 2 +SCOPE_SYS = 3 +SCOPE = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERFMON_SEL' +SDMA_PERFMON_SEL__enumvalues = { + 0: 'SDMA_PERFMON_SEL_CYCLE', + 1: 'SDMA_PERFMON_SEL_IDLE', + 2: 'SDMA_PERFMON_SEL_REG_IDLE', + 3: 'SDMA_PERFMON_SEL_RB_EMPTY', + 4: 'SDMA_PERFMON_SEL_RB_FULL', + 5: 'SDMA_PERFMON_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERFMON_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERFMON_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERFMON_SEL_RB_RPTR_WB', + 9: 'SDMA_PERFMON_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERFMON_SEL_RB_CMD_FULL', + 11: 'SDMA_PERFMON_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERFMON_SEL_IB_CMD_FULL', + 13: 'SDMA_PERFMON_SEL_EX_IDLE', + 14: 'SDMA_PERFMON_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERFMON_SEL_WR_BA_RTR', + 17: 'SDMA_PERFMON_SEL_MC_WR_IDLE', + 18: 'SDMA_PERFMON_SEL_MC_WR_COUNT', + 19: 'SDMA_PERFMON_SEL_RD_BA_RTR', + 20: 'SDMA_PERFMON_SEL_MC_RD_IDLE', + 21: 'SDMA_PERFMON_SEL_MC_RD_COUNT', + 22: 'SDMA_PERFMON_SEL_MC_RD_RET_STALL', + 23: 'SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE', + 26: 'SDMA_PERFMON_SEL_SEM_IDLE', + 27: 'SDMA_PERFMON_SEL_SEM_REQ_STALL', + 28: 'SDMA_PERFMON_SEL_SEM_REQ_COUNT', + 29: 'SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE', + 30: 'SDMA_PERFMON_SEL_SEM_RESP_FAIL', + 31: 'SDMA_PERFMON_SEL_SEM_RESP_PASS', + 32: 'SDMA_PERFMON_SEL_INT_IDLE', + 33: 'SDMA_PERFMON_SEL_INT_REQ_STALL', + 34: 'SDMA_PERFMON_SEL_INT_REQ_COUNT', + 35: 'SDMA_PERFMON_SEL_INT_RESP_ACCEPTED', + 36: 'SDMA_PERFMON_SEL_INT_RESP_RETRY', + 37: 'SDMA_PERFMON_SEL_NUM_PACKET', + 39: 'SDMA_PERFMON_SEL_CE_WREQ_IDLE', + 40: 'SDMA_PERFMON_SEL_CE_WR_IDLE', + 41: 'SDMA_PERFMON_SEL_CE_SPLIT_IDLE', + 42: 'SDMA_PERFMON_SEL_CE_RREQ_IDLE', + 43: 'SDMA_PERFMON_SEL_CE_OUT_IDLE', + 44: 'SDMA_PERFMON_SEL_CE_IN_IDLE', + 45: 'SDMA_PERFMON_SEL_CE_DST_IDLE', + 48: 'SDMA_PERFMON_SEL_CE_AFIFO_FULL', + 49: 'SDMA_PERFMON_SEL_DUMMY_0', + 50: 'SDMA_PERFMON_SEL_DUMMY_1', + 51: 'SDMA_PERFMON_SEL_CE_INFO_FULL', + 52: 'SDMA_PERFMON_SEL_CE_INFO1_FULL', + 53: 'SDMA_PERFMON_SEL_CE_RD_STALL', + 54: 'SDMA_PERFMON_SEL_CE_WR_STALL', + 55: 'SDMA_PERFMON_SEL_QUEUE0_SELECT', + 56: 'SDMA_PERFMON_SEL_QUEUE1_SELECT', + 57: 'SDMA_PERFMON_SEL_QUEUE2_SELECT', + 58: 'SDMA_PERFMON_SEL_QUEUE3_SELECT', + 59: 'SDMA_PERFMON_SEL_CTX_CHANGE', + 60: 'SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED', + 61: 'SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION', + 62: 'SDMA_PERFMON_SEL_DOORBELL', + 63: 'SDMA_PERFMON_SEL_MCU_L1_WR_VLD', + 64: 'SDMA_PERFMON_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERFMON_SEL_CPF_SDMA_INVREQ', + 66: 'SDMA_PERFMON_SEL_SDMA_CPF_INVACK', + 67: 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ', + 68: 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK', + 69: 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL', + 70: 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL', + 71: 'SDMA_PERFMON_SEL_UTCL2_RET_XNACK', + 72: 'SDMA_PERFMON_SEL_UTCL2_RET_ACK', + 73: 'SDMA_PERFMON_SEL_UTCL2_FREE', + 74: 'SDMA_PERFMON_SEL_SDMA_UTCL2_SEND', + 75: 'SDMA_PERFMON_SEL_DMA_L1_WR_SEND', + 76: 'SDMA_PERFMON_SEL_DMA_L1_RD_SEND', + 77: 'SDMA_PERFMON_SEL_DMA_MC_WR_SEND', + 78: 'SDMA_PERFMON_SEL_DMA_MC_RD_SEND', + 79: 'SDMA_PERFMON_SEL_GPUVM_INV_HIGH', + 80: 'SDMA_PERFMON_SEL_GPUVM_INV_LOW', + 81: 'SDMA_PERFMON_SEL_L1_WRL2_IDLE', + 82: 'SDMA_PERFMON_SEL_L1_RDL2_IDLE', + 83: 'SDMA_PERFMON_SEL_L1_WRMC_IDLE', + 84: 'SDMA_PERFMON_SEL_L1_RDMC_IDLE', + 85: 'SDMA_PERFMON_SEL_L1_WR_INV_IDLE', + 86: 'SDMA_PERFMON_SEL_L1_RD_INV_IDLE', + 87: 'SDMA_PERFMON_SEL_META_L2_REQ_SEND', + 88: 'SDMA_PERFMON_SEL_L2_META_RET_VLD', + 89: 'SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND', + 90: 'SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN', + 91: 'SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND', + 92: 'SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN', + 93: 'SDMA_PERFMON_SEL_META_REQ_SEND', + 94: 'SDMA_PERFMON_SEL_META_RTN_VLD', + 95: 'SDMA_PERFMON_SEL_TLBI_SEND', + 96: 'SDMA_PERFMON_SEL_TLBI_RTN', + 97: 'SDMA_PERFMON_SEL_GCR_SEND', + 98: 'SDMA_PERFMON_SEL_GCR_RTN', + 99: 'SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER', + 100: 'SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER', +} +SDMA_PERFMON_SEL_CYCLE = 0 +SDMA_PERFMON_SEL_IDLE = 1 +SDMA_PERFMON_SEL_REG_IDLE = 2 +SDMA_PERFMON_SEL_RB_EMPTY = 3 +SDMA_PERFMON_SEL_RB_FULL = 4 +SDMA_PERFMON_SEL_RB_WPTR_WRAP = 5 +SDMA_PERFMON_SEL_RB_RPTR_WRAP = 6 +SDMA_PERFMON_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERFMON_SEL_RB_RPTR_WB = 8 +SDMA_PERFMON_SEL_RB_CMD_IDLE = 9 +SDMA_PERFMON_SEL_RB_CMD_FULL = 10 +SDMA_PERFMON_SEL_IB_CMD_IDLE = 11 +SDMA_PERFMON_SEL_IB_CMD_FULL = 12 +SDMA_PERFMON_SEL_EX_IDLE = 13 +SDMA_PERFMON_SEL_SRBM_REG_SEND = 14 +SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERFMON_SEL_WR_BA_RTR = 16 +SDMA_PERFMON_SEL_MC_WR_IDLE = 17 +SDMA_PERFMON_SEL_MC_WR_COUNT = 18 +SDMA_PERFMON_SEL_RD_BA_RTR = 19 +SDMA_PERFMON_SEL_MC_RD_IDLE = 20 +SDMA_PERFMON_SEL_MC_RD_COUNT = 21 +SDMA_PERFMON_SEL_MC_RD_RET_STALL = 22 +SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE = 23 +SDMA_PERFMON_SEL_SEM_IDLE = 26 +SDMA_PERFMON_SEL_SEM_REQ_STALL = 27 +SDMA_PERFMON_SEL_SEM_REQ_COUNT = 28 +SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE = 29 +SDMA_PERFMON_SEL_SEM_RESP_FAIL = 30 +SDMA_PERFMON_SEL_SEM_RESP_PASS = 31 +SDMA_PERFMON_SEL_INT_IDLE = 32 +SDMA_PERFMON_SEL_INT_REQ_STALL = 33 +SDMA_PERFMON_SEL_INT_REQ_COUNT = 34 +SDMA_PERFMON_SEL_INT_RESP_ACCEPTED = 35 +SDMA_PERFMON_SEL_INT_RESP_RETRY = 36 +SDMA_PERFMON_SEL_NUM_PACKET = 37 +SDMA_PERFMON_SEL_CE_WREQ_IDLE = 39 +SDMA_PERFMON_SEL_CE_WR_IDLE = 40 +SDMA_PERFMON_SEL_CE_SPLIT_IDLE = 41 +SDMA_PERFMON_SEL_CE_RREQ_IDLE = 42 +SDMA_PERFMON_SEL_CE_OUT_IDLE = 43 +SDMA_PERFMON_SEL_CE_IN_IDLE = 44 +SDMA_PERFMON_SEL_CE_DST_IDLE = 45 +SDMA_PERFMON_SEL_CE_AFIFO_FULL = 48 +SDMA_PERFMON_SEL_DUMMY_0 = 49 +SDMA_PERFMON_SEL_DUMMY_1 = 50 +SDMA_PERFMON_SEL_CE_INFO_FULL = 51 +SDMA_PERFMON_SEL_CE_INFO1_FULL = 52 +SDMA_PERFMON_SEL_CE_RD_STALL = 53 +SDMA_PERFMON_SEL_CE_WR_STALL = 54 +SDMA_PERFMON_SEL_QUEUE0_SELECT = 55 +SDMA_PERFMON_SEL_QUEUE1_SELECT = 56 +SDMA_PERFMON_SEL_QUEUE2_SELECT = 57 +SDMA_PERFMON_SEL_QUEUE3_SELECT = 58 +SDMA_PERFMON_SEL_CTX_CHANGE = 59 +SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED = 60 +SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION = 61 +SDMA_PERFMON_SEL_DOORBELL = 62 +SDMA_PERFMON_SEL_MCU_L1_WR_VLD = 63 +SDMA_PERFMON_SEL_CE_L1_WR_VLD = 64 +SDMA_PERFMON_SEL_CPF_SDMA_INVREQ = 65 +SDMA_PERFMON_SEL_SDMA_CPF_INVACK = 66 +SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ = 67 +SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK = 68 +SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL = 69 +SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL = 70 +SDMA_PERFMON_SEL_UTCL2_RET_XNACK = 71 +SDMA_PERFMON_SEL_UTCL2_RET_ACK = 72 +SDMA_PERFMON_SEL_UTCL2_FREE = 73 +SDMA_PERFMON_SEL_SDMA_UTCL2_SEND = 74 +SDMA_PERFMON_SEL_DMA_L1_WR_SEND = 75 +SDMA_PERFMON_SEL_DMA_L1_RD_SEND = 76 +SDMA_PERFMON_SEL_DMA_MC_WR_SEND = 77 +SDMA_PERFMON_SEL_DMA_MC_RD_SEND = 78 +SDMA_PERFMON_SEL_GPUVM_INV_HIGH = 79 +SDMA_PERFMON_SEL_GPUVM_INV_LOW = 80 +SDMA_PERFMON_SEL_L1_WRL2_IDLE = 81 +SDMA_PERFMON_SEL_L1_RDL2_IDLE = 82 +SDMA_PERFMON_SEL_L1_WRMC_IDLE = 83 +SDMA_PERFMON_SEL_L1_RDMC_IDLE = 84 +SDMA_PERFMON_SEL_L1_WR_INV_IDLE = 85 +SDMA_PERFMON_SEL_L1_RD_INV_IDLE = 86 +SDMA_PERFMON_SEL_META_L2_REQ_SEND = 87 +SDMA_PERFMON_SEL_L2_META_RET_VLD = 88 +SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND = 89 +SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN = 90 +SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND = 91 +SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN = 92 +SDMA_PERFMON_SEL_META_REQ_SEND = 93 +SDMA_PERFMON_SEL_META_RTN_VLD = 94 +SDMA_PERFMON_SEL_TLBI_SEND = 95 +SDMA_PERFMON_SEL_TLBI_RTN = 96 +SDMA_PERFMON_SEL_GCR_SEND = 97 +SDMA_PERFMON_SEL_GCR_RTN = 98 +SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER = 99 +SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER = 100 +SDMA_PERFMON_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERF_SEL' +SDMA_PERF_SEL__enumvalues = { + 0: 'SDMA_PERF_SEL_CYCLE', + 1: 'SDMA_PERF_SEL_IDLE', + 2: 'SDMA_PERF_SEL_REG_IDLE', + 3: 'SDMA_PERF_SEL_RB_EMPTY', + 4: 'SDMA_PERF_SEL_RB_FULL', + 5: 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERF_SEL_RB_RPTR_WB', + 9: 'SDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERF_SEL_RB_CMD_FULL', + 11: 'SDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERF_SEL_IB_CMD_FULL', + 13: 'SDMA_PERF_SEL_EX_IDLE', + 14: 'SDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERF_SEL_MC_WR_IDLE', + 17: 'SDMA_PERF_SEL_MC_WR_COUNT', + 18: 'SDMA_PERF_SEL_MC_RD_IDLE', + 19: 'SDMA_PERF_SEL_MC_RD_COUNT', + 20: 'SDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'SDMA_PERF_SEL_SEM_IDLE', + 25: 'SDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'SDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'SDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'SDMA_PERF_SEL_INT_IDLE', + 31: 'SDMA_PERF_SEL_INT_REQ_STALL', + 32: 'SDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'SDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'SDMA_PERF_SEL_NUM_PACKET', + 37: 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'SDMA_PERF_SEL_CE_WR_IDLE', + 39: 'SDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'SDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'SDMA_PERF_SEL_CE_IN_IDLE', + 43: 'SDMA_PERF_SEL_CE_DST_IDLE', + 46: 'SDMA_PERF_SEL_CE_AFIFO_FULL', + 47: 'SDMA_PERF_SEL_DUMMY_0', + 48: 'SDMA_PERF_SEL_DUMMY_1', + 49: 'SDMA_PERF_SEL_CE_INFO_FULL', + 50: 'SDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'SDMA_PERF_SEL_CE_RD_STALL', + 52: 'SDMA_PERF_SEL_CE_WR_STALL', + 53: 'SDMA_PERF_SEL_QUEUE0_SELECT', + 54: 'SDMA_PERF_SEL_QUEUE1_SELECT', + 55: 'SDMA_PERF_SEL_QUEUE2_SELECT', + 56: 'SDMA_PERF_SEL_QUEUE3_SELECT', + 57: 'SDMA_PERF_SEL_CTX_CHANGE', + 58: 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'SDMA_PERF_SEL_DOORBELL', + 61: 'SDMA_PERF_SEL_RD_BA_RTR', + 62: 'SDMA_PERF_SEL_WR_BA_RTR', + 63: 'SDMA_PERF_SEL_MCU_L1_WR_VLD', + 64: 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', + 66: 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 67: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 68: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 69: 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 70: 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 71: 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 72: 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 73: 'SDMA_PERF_SEL_UTCL2_FREE', + 74: 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 75: 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 76: 'SDMA_PERF_SEL_DMA_L1_RD_SEND', + 77: 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 78: 'SDMA_PERF_SEL_DMA_MC_RD_SEND', + 79: 'SDMA_PERF_SEL_GPUVM_INV_HIGH', + 80: 'SDMA_PERF_SEL_GPUVM_INV_LOW', + 81: 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 82: 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 83: 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 84: 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 85: 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 86: 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 87: 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 88: 'SDMA_PERF_SEL_L2_META_RET_VLD', + 89: 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 90: 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 91: 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', + 92: 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', + 93: 'SDMA_PERF_SEL_META_REQ_SEND', + 94: 'SDMA_PERF_SEL_META_RTN_VLD', + 95: 'SDMA_PERF_SEL_TLBI_SEND', + 96: 'SDMA_PERF_SEL_TLBI_RTN', + 97: 'SDMA_PERF_SEL_GCR_SEND', + 98: 'SDMA_PERF_SEL_GCR_RTN', + 99: 'SDMA_PERF_SEL_CGCG_FENCE', + 100: 'SDMA_PERF_SEL_CE_CH_WR_REQ', + 101: 'SDMA_PERF_SEL_CE_CH_WR_RET', + 102: 'SDMA_PERF_SEL_MCU_CH_WR_REQ', + 103: 'SDMA_PERF_SEL_MCU_CH_WR_RET', + 104: 'SDMA_PERF_SEL_CE_OR_MCU_CH_RD_REQ', + 105: 'SDMA_PERF_SEL_CE_OR_MCU_CH_RD_RET', + 106: 'SDMA_PERF_SEL_RB_CH_RD_REQ', + 107: 'SDMA_PERF_SEL_RB_CH_RD_RET', + 108: 'SDMA_PERF_SEL_IB_CH_RD_REQ', + 109: 'SDMA_PERF_SEL_IB_CH_RD_RET', + 110: 'SDMA_PERF_SEL_WPTR_CH_RD_REQ', + 111: 'SDMA_PERF_SEL_WPTR_CH_RD_RET', + 112: 'SDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 113: 'SDMA_PERF_SEL_UTCL1_UTCL2_RET', + 114: 'SDMA_PERF_SEL_CMD_OP_MATCH', + 115: 'SDMA_PERF_SEL_CMD_OP_START', + 116: 'SDMA_PERF_SEL_CMD_OP_END', + 117: 'SDMA_PERF_SEL_CE_BUSY', + 118: 'SDMA_PERF_SEL_CE_BUSY_START', + 119: 'SDMA_PERF_SEL_CE_BUSY_END', + 120: 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER', + 121: 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_START', + 122: 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_END', + 123: 'SDMA_PERF_SEL_CE_CH_WRREQ_SEND', + 124: 'SDMA_PERF_SEL_CH_CE_WRRET_VALID', + 125: 'SDMA_PERF_SEL_CE_CH_RDREQ_SEND', + 126: 'SDMA_PERF_SEL_CH_CE_RDRET_VALID', + 127: 'SDMA_PERF_SEL_QUEUE4_SELECT', + 128: 'SDMA_PERF_SEL_QUEUE5_SELECT', + 129: 'SDMA_PERF_SEL_QUEUE6_SELECT', + 130: 'SDMA_PERF_SEL_QUEUE7_SELECT', +} +SDMA_PERF_SEL_CYCLE = 0 +SDMA_PERF_SEL_IDLE = 1 +SDMA_PERF_SEL_REG_IDLE = 2 +SDMA_PERF_SEL_RB_EMPTY = 3 +SDMA_PERF_SEL_RB_FULL = 4 +SDMA_PERF_SEL_RB_WPTR_WRAP = 5 +SDMA_PERF_SEL_RB_RPTR_WRAP = 6 +SDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERF_SEL_RB_RPTR_WB = 8 +SDMA_PERF_SEL_RB_CMD_IDLE = 9 +SDMA_PERF_SEL_RB_CMD_FULL = 10 +SDMA_PERF_SEL_IB_CMD_IDLE = 11 +SDMA_PERF_SEL_IB_CMD_FULL = 12 +SDMA_PERF_SEL_EX_IDLE = 13 +SDMA_PERF_SEL_SRBM_REG_SEND = 14 +SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERF_SEL_MC_WR_IDLE = 16 +SDMA_PERF_SEL_MC_WR_COUNT = 17 +SDMA_PERF_SEL_MC_RD_IDLE = 18 +SDMA_PERF_SEL_MC_RD_COUNT = 19 +SDMA_PERF_SEL_MC_RD_RET_STALL = 20 +SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +SDMA_PERF_SEL_SEM_IDLE = 24 +SDMA_PERF_SEL_SEM_REQ_STALL = 25 +SDMA_PERF_SEL_SEM_REQ_COUNT = 26 +SDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +SDMA_PERF_SEL_SEM_RESP_FAIL = 28 +SDMA_PERF_SEL_SEM_RESP_PASS = 29 +SDMA_PERF_SEL_INT_IDLE = 30 +SDMA_PERF_SEL_INT_REQ_STALL = 31 +SDMA_PERF_SEL_INT_REQ_COUNT = 32 +SDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +SDMA_PERF_SEL_INT_RESP_RETRY = 34 +SDMA_PERF_SEL_NUM_PACKET = 35 +SDMA_PERF_SEL_CE_WREQ_IDLE = 37 +SDMA_PERF_SEL_CE_WR_IDLE = 38 +SDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +SDMA_PERF_SEL_CE_RREQ_IDLE = 40 +SDMA_PERF_SEL_CE_OUT_IDLE = 41 +SDMA_PERF_SEL_CE_IN_IDLE = 42 +SDMA_PERF_SEL_CE_DST_IDLE = 43 +SDMA_PERF_SEL_CE_AFIFO_FULL = 46 +SDMA_PERF_SEL_DUMMY_0 = 47 +SDMA_PERF_SEL_DUMMY_1 = 48 +SDMA_PERF_SEL_CE_INFO_FULL = 49 +SDMA_PERF_SEL_CE_INFO1_FULL = 50 +SDMA_PERF_SEL_CE_RD_STALL = 51 +SDMA_PERF_SEL_CE_WR_STALL = 52 +SDMA_PERF_SEL_QUEUE0_SELECT = 53 +SDMA_PERF_SEL_QUEUE1_SELECT = 54 +SDMA_PERF_SEL_QUEUE2_SELECT = 55 +SDMA_PERF_SEL_QUEUE3_SELECT = 56 +SDMA_PERF_SEL_CTX_CHANGE = 57 +SDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +SDMA_PERF_SEL_DOORBELL = 60 +SDMA_PERF_SEL_RD_BA_RTR = 61 +SDMA_PERF_SEL_WR_BA_RTR = 62 +SDMA_PERF_SEL_MCU_L1_WR_VLD = 63 +SDMA_PERF_SEL_CE_L1_WR_VLD = 64 +SDMA_PERF_SEL_CPF_SDMA_INVREQ = 65 +SDMA_PERF_SEL_SDMA_CPF_INVACK = 66 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ = 67 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK = 68 +SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL = 69 +SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL = 70 +SDMA_PERF_SEL_UTCL2_RET_XNACK = 71 +SDMA_PERF_SEL_UTCL2_RET_ACK = 72 +SDMA_PERF_SEL_UTCL2_FREE = 73 +SDMA_PERF_SEL_SDMA_UTCL2_SEND = 74 +SDMA_PERF_SEL_DMA_L1_WR_SEND = 75 +SDMA_PERF_SEL_DMA_L1_RD_SEND = 76 +SDMA_PERF_SEL_DMA_MC_WR_SEND = 77 +SDMA_PERF_SEL_DMA_MC_RD_SEND = 78 +SDMA_PERF_SEL_GPUVM_INV_HIGH = 79 +SDMA_PERF_SEL_GPUVM_INV_LOW = 80 +SDMA_PERF_SEL_L1_WRL2_IDLE = 81 +SDMA_PERF_SEL_L1_RDL2_IDLE = 82 +SDMA_PERF_SEL_L1_WRMC_IDLE = 83 +SDMA_PERF_SEL_L1_RDMC_IDLE = 84 +SDMA_PERF_SEL_L1_WR_INV_IDLE = 85 +SDMA_PERF_SEL_L1_RD_INV_IDLE = 86 +SDMA_PERF_SEL_META_L2_REQ_SEND = 87 +SDMA_PERF_SEL_L2_META_RET_VLD = 88 +SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND = 89 +SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN = 90 +SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND = 91 +SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN = 92 +SDMA_PERF_SEL_META_REQ_SEND = 93 +SDMA_PERF_SEL_META_RTN_VLD = 94 +SDMA_PERF_SEL_TLBI_SEND = 95 +SDMA_PERF_SEL_TLBI_RTN = 96 +SDMA_PERF_SEL_GCR_SEND = 97 +SDMA_PERF_SEL_GCR_RTN = 98 +SDMA_PERF_SEL_CGCG_FENCE = 99 +SDMA_PERF_SEL_CE_CH_WR_REQ = 100 +SDMA_PERF_SEL_CE_CH_WR_RET = 101 +SDMA_PERF_SEL_MCU_CH_WR_REQ = 102 +SDMA_PERF_SEL_MCU_CH_WR_RET = 103 +SDMA_PERF_SEL_CE_OR_MCU_CH_RD_REQ = 104 +SDMA_PERF_SEL_CE_OR_MCU_CH_RD_RET = 105 +SDMA_PERF_SEL_RB_CH_RD_REQ = 106 +SDMA_PERF_SEL_RB_CH_RD_RET = 107 +SDMA_PERF_SEL_IB_CH_RD_REQ = 108 +SDMA_PERF_SEL_IB_CH_RD_RET = 109 +SDMA_PERF_SEL_WPTR_CH_RD_REQ = 110 +SDMA_PERF_SEL_WPTR_CH_RD_RET = 111 +SDMA_PERF_SEL_UTCL1_UTCL2_REQ = 112 +SDMA_PERF_SEL_UTCL1_UTCL2_RET = 113 +SDMA_PERF_SEL_CMD_OP_MATCH = 114 +SDMA_PERF_SEL_CMD_OP_START = 115 +SDMA_PERF_SEL_CMD_OP_END = 116 +SDMA_PERF_SEL_CE_BUSY = 117 +SDMA_PERF_SEL_CE_BUSY_START = 118 +SDMA_PERF_SEL_CE_BUSY_END = 119 +SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER = 120 +SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_START = 121 +SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_END = 122 +SDMA_PERF_SEL_CE_CH_WRREQ_SEND = 123 +SDMA_PERF_SEL_CH_CE_WRRET_VALID = 124 +SDMA_PERF_SEL_CE_CH_RDREQ_SEND = 125 +SDMA_PERF_SEL_CH_CE_RDRET_VALID = 126 +SDMA_PERF_SEL_QUEUE4_SELECT = 127 +SDMA_PERF_SEL_QUEUE5_SELECT = 128 +SDMA_PERF_SEL_QUEUE6_SELECT = 129 +SDMA_PERF_SEL_QUEUE7_SELECT = 130 +SDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPM_PERFMON_STATE' +SPM_PERFMON_STATE__enumvalues = { + 0: 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'STRM_PERFMON_STATE_START_COUNTING', + 2: 'STRM_PERFMON_STATE_STOP_COUNTING', + 3: 'STRM_PERFMON_STATE_RESERVED_3', + 4: 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +STRM_PERFMON_STATE_DISABLE_AND_RESET = 0 +STRM_PERFMON_STATE_START_COUNTING = 1 +STRM_PERFMON_STATE_STOP_COUNTING = 2 +STRM_PERFMON_STATE_RESERVED_3 = 3 +STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +SPM_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_MTYPE' +TCC_MTYPE__enumvalues = { + 0: 'MTYPE_NC', + 1: 'MTYPE_WC', + 2: 'MTYPE_CC', +} +MTYPE_NC = 0 +MTYPE_WC = 1 +MTYPE_CC = 2 +TCC_MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0FaultType' +UTCL0FaultType__enumvalues = { + 0: 'UTCL0_XNACK_SUCCESS', + 1: 'UTCL0_XNACK_RETRY', + 2: 'UTCL0_XNACK_PRT', + 3: 'UTCL0_XNACK_NO_RETRY', +} +UTCL0_XNACK_SUCCESS = 0 +UTCL0_XNACK_RETRY = 1 +UTCL0_XNACK_PRT = 2 +UTCL0_XNACK_NO_RETRY = 3 +UTCL0FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL0RequestType' +UTCL0RequestType__enumvalues = { + 0: 'UTCL0_TYPE_NORMAL', + 1: 'UTCL0_TYPE_SHOOTDOWN', + 2: 'UTCL0_TYPE_BYPASS', +} +UTCL0_TYPE_NORMAL = 0 +UTCL0_TYPE_SHOOTDOWN = 1 +UTCL0_TYPE_BYPASS = 2 +UTCL0RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1FaultType' +UTCL1FaultType__enumvalues = { + 0: 'UTCL1_XNACK_SUCCESS', + 1: 'UTCL1_XNACK_RETRY', + 2: 'UTCL1_XNACK_PRT', + 3: 'UTCL1_XNACK_NO_RETRY', +} +UTCL1_XNACK_SUCCESS = 0 +UTCL1_XNACK_RETRY = 1 +UTCL1_XNACK_PRT = 2 +UTCL1_XNACK_NO_RETRY = 3 +UTCL1FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1RequestType' +UTCL1RequestType__enumvalues = { + 0: 'UTCL1_TYPE_NORMAL', + 1: 'UTCL1_TYPE_SHOOTDOWN', + 2: 'UTCL1_TYPE_BYPASS', +} +UTCL1_TYPE_NORMAL = 0 +UTCL1_TYPE_SHOOTDOWN = 1 +UTCL1_TYPE_BYPASS = 2 +UTCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'WRITE_COMPRESSION_MODE' +WRITE_COMPRESSION_MODE__enumvalues = { + 0: 'COMPRESSION_MODE_BYPASS_METADATA_CACHE', + 1: 'COMPRESSION_MODE_COMPRESSION_ENABLED', + 2: 'COMPRESSION_MODE_WRITE_COMPRESSION_DISABLED', +} +COMPRESSION_MODE_BYPASS_METADATA_CACHE = 0 +COMPRESSION_MODE_COMPRESSION_ENABLED = 1 +COMPRESSION_MODE_WRITE_COMPRESSION_DISABLED = 2 +WRITE_COMPRESSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'WritePolicy' +WritePolicy__enumvalues = { + 0: 'CACHE_LRU_WR', + 1: 'CACHE_STREAM', + 2: 'CACHE_NOA_WR', + 3: 'CACHE_BYPASS', +} +CACHE_LRU_WR = 0 +CACHE_STREAM = 1 +CACHE_NOA_WR = 2 +CACHE_BYPASS = 3 +WritePolicy = ctypes.c_uint32 # enum + +# values for enumeration 'COLOR_KEYER_ENABLE' +COLOR_KEYER_ENABLE__enumvalues = { + 0: 'COLOR_KEY_EN', + 1: 'COLOR_KEY_DIS', +} +COLOR_KEY_EN = 0 +COLOR_KEY_DIS = 1 +COLOR_KEYER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'COLOR_KEYER_MODE' +COLOR_KEYER_MODE__enumvalues = { + 0: 'FORCE_00', + 1: 'FORCE_FF', + 2: 'RANGE_00', + 3: 'RANGE_FF', +} +FORCE_00 = 0 +FORCE_FF = 1 +RANGE_00 = 2 +RANGE_FF = 3 +COLOR_KEYER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DENORM_TRUNCATE' +DENORM_TRUNCATE__enumvalues = { + 0: 'CNVC_ROUND', + 1: 'CNVC_TRUNCATE', +} +CNVC_ROUND = 0 +CNVC_TRUNCATE = 1 +DENORM_TRUNCATE = ctypes.c_uint32 # enum + +# values for enumeration 'FORMAT_CROSSBAR' +FORMAT_CROSSBAR__enumvalues = { + 0: 'FORMAT_CROSSBAR_R', + 1: 'FORMAT_CROSSBAR_G', + 2: 'FORMAT_CROSSBAR_B', +} +FORMAT_CROSSBAR_R = 0 +FORMAT_CROSSBAR_G = 1 +FORMAT_CROSSBAR_B = 2 +FORMAT_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'LUMA_KEYER_ENABLE' +LUMA_KEYER_ENABLE__enumvalues = { + 0: 'LUMA_KEY_EN', + 1: 'LUMA_KEY_DIS', +} +LUMA_KEY_EN = 0 +LUMA_KEY_DIS = 1 +LUMA_KEYER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'PIX_EXPAND_MODE' +PIX_EXPAND_MODE__enumvalues = { + 0: 'PIX_DYNAMIC_EXPANSION', + 1: 'PIX_ZERO_EXPANSION', +} +PIX_DYNAMIC_EXPANSION = 0 +PIX_ZERO_EXPANSION = 1 +PIX_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_CSC_MODE_ENUM' +PRE_CSC_MODE_ENUM__enumvalues = { + 0: 'PRE_CSC_BYPASS', + 1: 'PRE_CSC_SET_A', + 2: 'PRE_CSC_SET_B', +} +PRE_CSC_BYPASS = 0 +PRE_CSC_SET_A = 1 +PRE_CSC_SET_B = 2 +PRE_CSC_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_DEGAM_MODE' +PRE_DEGAM_MODE__enumvalues = { + 0: 'PRE_DEGAM_BYPASS', + 1: 'PRE_DEGAM_ENABLE', +} +PRE_DEGAM_BYPASS = 0 +PRE_DEGAM_ENABLE = 1 +PRE_DEGAM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PRE_DEGAM_SELECT' +PRE_DEGAM_SELECT__enumvalues = { + 0: 'PRE_DEGAM_SRGB', + 1: 'PRE_DEGAM_GAMMA_22', + 2: 'PRE_DEGAM_GAMMA_24', + 3: 'PRE_DEGAM_GAMMA_26', + 4: 'PRE_DEGAM_BT2020', + 5: 'PRE_DEGAM_BT2100PQ', + 6: 'PRE_DEGAM_BT2100HLG', +} +PRE_DEGAM_SRGB = 0 +PRE_DEGAM_GAMMA_22 = 1 +PRE_DEGAM_GAMMA_24 = 2 +PRE_DEGAM_GAMMA_26 = 3 +PRE_DEGAM_BT2020 = 4 +PRE_DEGAM_BT2100PQ = 5 +PRE_DEGAM_BT2100HLG = 6 +PRE_DEGAM_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_PIXEL_FORMAT' +SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'ARGB1555', + 2: 'RGBA5551', + 3: 'RGB565', + 4: 'BGR565', + 5: 'ARGB4444', + 6: 'RGBA4444', + 8: 'ARGB8888', + 9: 'RGBA8888', + 10: 'ARGB2101010', + 11: 'RGBA1010102', + 12: 'AYCrCb8888', + 13: 'YCrCbA8888', + 14: 'ACrYCb8888', + 15: 'CrYCbA8888', + 16: 'ARGB16161616_10MSB', + 17: 'RGBA16161616_10MSB', + 18: 'ARGB16161616_10LSB', + 19: 'RGBA16161616_10LSB', + 20: 'ARGB16161616_12MSB', + 21: 'RGBA16161616_12MSB', + 22: 'ARGB16161616_12LSB', + 23: 'RGBA16161616_12LSB', + 24: 'ARGB16161616_FLOAT', + 25: 'RGBA16161616_FLOAT', + 26: 'ARGB16161616_UNORM', + 27: 'RGBA16161616_UNORM', + 28: 'ARGB16161616_SNORM', + 29: 'RGBA16161616_SNORM', + 32: 'AYCrCb16161616_10MSB', + 33: 'AYCrCb16161616_10LSB', + 34: 'YCrCbA16161616_10MSB', + 35: 'YCrCbA16161616_10LSB', + 36: 'ACrYCb16161616_10MSB', + 37: 'ACrYCb16161616_10LSB', + 38: 'CrYCbA16161616_10MSB', + 39: 'CrYCbA16161616_10LSB', + 40: 'AYCrCb16161616_12MSB', + 41: 'AYCrCb16161616_12LSB', + 42: 'YCrCbA16161616_12MSB', + 43: 'YCrCbA16161616_12LSB', + 44: 'ACrYCb16161616_12MSB', + 45: 'ACrYCb16161616_12LSB', + 46: 'CrYCbA16161616_12MSB', + 47: 'CrYCbA16161616_12LSB', + 64: 'Y8_CrCb88_420_PLANAR', + 65: 'Y8_CbCr88_420_PLANAR', + 66: 'Y10_CrCb1010_420_PLANAR', + 67: 'Y10_CbCr1010_420_PLANAR', + 68: 'Y12_CrCb1212_420_PLANAR', + 69: 'Y12_CbCr1212_420_PLANAR', + 72: 'YCrYCb8888_422_PACKED', + 73: 'YCbYCr8888_422_PACKED', + 74: 'CrYCbY8888_422_PACKED', + 75: 'CbYCrY8888_422_PACKED', + 76: 'YCrYCb10101010_422_PACKED', + 77: 'YCbYCr10101010_422_PACKED', + 78: 'CrYCbY10101010_422_PACKED', + 79: 'CbYCrY10101010_422_PACKED', + 80: 'YCrYCb12121212_422_PACKED', + 81: 'YCbYCr12121212_422_PACKED', + 82: 'CrYCbY12121212_422_PACKED', + 83: 'CbYCrY12121212_422_PACKED', + 112: 'RGB111110_FIX', + 113: 'BGR101111_FIX', + 114: 'ACrYCb2101010', + 115: 'CrYCbA1010102', + 116: 'RGBE', + 118: 'RGB111110_FLOAT', + 119: 'BGR101111_FLOAT', + 120: 'MONO_8', + 121: 'MONO_10MSB', + 122: 'MONO_10LSB', + 123: 'MONO_12MSB', + 124: 'MONO_12LSB', + 125: 'MONO_16', +} +ARGB1555 = 1 +RGBA5551 = 2 +RGB565 = 3 +BGR565 = 4 +ARGB4444 = 5 +RGBA4444 = 6 +ARGB8888 = 8 +RGBA8888 = 9 +ARGB2101010 = 10 +RGBA1010102 = 11 +AYCrCb8888 = 12 +YCrCbA8888 = 13 +ACrYCb8888 = 14 +CrYCbA8888 = 15 +ARGB16161616_10MSB = 16 +RGBA16161616_10MSB = 17 +ARGB16161616_10LSB = 18 +RGBA16161616_10LSB = 19 +ARGB16161616_12MSB = 20 +RGBA16161616_12MSB = 21 +ARGB16161616_12LSB = 22 +RGBA16161616_12LSB = 23 +ARGB16161616_FLOAT = 24 +RGBA16161616_FLOAT = 25 +ARGB16161616_UNORM = 26 +RGBA16161616_UNORM = 27 +ARGB16161616_SNORM = 28 +RGBA16161616_SNORM = 29 +AYCrCb16161616_10MSB = 32 +AYCrCb16161616_10LSB = 33 +YCrCbA16161616_10MSB = 34 +YCrCbA16161616_10LSB = 35 +ACrYCb16161616_10MSB = 36 +ACrYCb16161616_10LSB = 37 +CrYCbA16161616_10MSB = 38 +CrYCbA16161616_10LSB = 39 +AYCrCb16161616_12MSB = 40 +AYCrCb16161616_12LSB = 41 +YCrCbA16161616_12MSB = 42 +YCrCbA16161616_12LSB = 43 +ACrYCb16161616_12MSB = 44 +ACrYCb16161616_12LSB = 45 +CrYCbA16161616_12MSB = 46 +CrYCbA16161616_12LSB = 47 +Y8_CrCb88_420_PLANAR = 64 +Y8_CbCr88_420_PLANAR = 65 +Y10_CrCb1010_420_PLANAR = 66 +Y10_CbCr1010_420_PLANAR = 67 +Y12_CrCb1212_420_PLANAR = 68 +Y12_CbCr1212_420_PLANAR = 69 +YCrYCb8888_422_PACKED = 72 +YCbYCr8888_422_PACKED = 73 +CrYCbY8888_422_PACKED = 74 +CbYCrY8888_422_PACKED = 75 +YCrYCb10101010_422_PACKED = 76 +YCbYCr10101010_422_PACKED = 77 +CrYCbY10101010_422_PACKED = 78 +CbYCrY10101010_422_PACKED = 79 +YCrYCb12121212_422_PACKED = 80 +YCbYCr12121212_422_PACKED = 81 +CrYCbY12121212_422_PACKED = 82 +CbYCrY12121212_422_PACKED = 83 +RGB111110_FIX = 112 +BGR101111_FIX = 113 +ACrYCb2101010 = 114 +CrYCbA1010102 = 115 +RGBE = 116 +RGB111110_FLOAT = 118 +BGR101111_FLOAT = 119 +MONO_8 = 120 +MONO_10MSB = 121 +MONO_10LSB = 122 +MONO_12MSB = 123 +MONO_12LSB = 124 +MONO_16 = 125 +SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'XNORM' +XNORM__enumvalues = { + 0: 'XNORM_A', + 1: 'XNORM_B', +} +XNORM_A = 0 +XNORM_B = 1 +XNORM = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ENABLE' +CUR_ENABLE__enumvalues = { + 0: 'CUR_DIS', + 1: 'CUR_EN', +} +CUR_DIS = 0 +CUR_EN = 1 +CUR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_EXPAND_MODE' +CUR_EXPAND_MODE__enumvalues = { + 0: 'CUR_DYNAMIC_EXPANSION', + 1: 'CUR_ZERO_EXPANSION', +} +CUR_DYNAMIC_EXPANSION = 0 +CUR_ZERO_EXPANSION = 1 +CUR_EXPAND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_INV_CLAMP' +CUR_INV_CLAMP__enumvalues = { + 0: 'CUR_CLAMP_DIS', + 1: 'CUR_CLAMP_EN', +} +CUR_CLAMP_DIS = 0 +CUR_CLAMP_EN = 1 +CUR_INV_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_MATRIX_COEF_FORMAT_ENUM' +CUR_MATRIX_COEF_FORMAT_ENUM__enumvalues = { + 0: 'CUR_MATRIX_FIX_S2_13', + 1: 'CUR_MATRIX_FIX_S3_12', +} +CUR_MATRIX_FIX_S2_13 = 0 +CUR_MATRIX_FIX_S3_12 = 1 +CUR_MATRIX_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_MODE' +CUR_MODE__enumvalues = { + 0: 'MONO_2BIT', + 1: 'COLOR_24BIT_1BIT_AND', + 2: 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'COLOR_64BIT_FP_PREMULT', + 5: 'COLOR_64BIT_FP_UNPREMULT', +} +MONO_2BIT = 0 +COLOR_24BIT_1BIT_AND = 1 +COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +COLOR_64BIT_FP_PREMULT = 4 +COLOR_64BIT_FP_UNPREMULT = 5 +CUR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_PENDING' +CUR_PENDING__enumvalues = { + 0: 'CUR_NOT_PENDING', + 1: 'CUR_YES_PENDING', +} +CUR_NOT_PENDING = 0 +CUR_YES_PENDING = 1 +CUR_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CUR_ROM_EN' +CUR_ROM_EN__enumvalues = { + 0: 'CUR_FP_NO_ROM', + 1: 'CUR_FP_USE_ROM', +} +CUR_FP_NO_ROM = 0 +CUR_FP_USE_ROM = 1 +CUR_ROM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'COEF_RAM_SELECT_RD' +COEF_RAM_SELECT_RD__enumvalues = { + 0: 'COEF_RAM_SELECT_BACK', + 1: 'COEF_RAM_SELECT_CURRENT', +} +COEF_RAM_SELECT_BACK = 0 +COEF_RAM_SELECT_CURRENT = 1 +COEF_RAM_SELECT_RD = ctypes.c_uint32 # enum + +# values for enumeration 'DSCL_MODE_SEL' +DSCL_MODE_SEL__enumvalues = { + 0: 'DSCL_MODE_SCALING_444_BYPASS', + 1: 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 2: 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 3: 'DSCL_MODE_SCALING_YCBCR_ENABLE', + 4: 'DSCL_MODE_LUMA_SCALING_BYPASS', + 5: 'DSCL_MODE_CHROMA_SCALING_BYPASS', + 6: 'DSCL_MODE_DSCL_BYPASS', +} +DSCL_MODE_SCALING_444_BYPASS = 0 +DSCL_MODE_SCALING_444_RGB_ENABLE = 1 +DSCL_MODE_SCALING_444_YCBCR_ENABLE = 2 +DSCL_MODE_SCALING_YCBCR_ENABLE = 3 +DSCL_MODE_LUMA_SCALING_BYPASS = 4 +DSCL_MODE_CHROMA_SCALING_BYPASS = 5 +DSCL_MODE_DSCL_BYPASS = 6 +DSCL_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ISHARP_FMT_MODE_ENUM' +ISHARP_FMT_MODE_ENUM__enumvalues = { + 0: 'ISHARP_FMT_MODE_0', + 1: 'ISHARP_FMT_MODE_1', +} +ISHARP_FMT_MODE_0 = 0 +ISHARP_FMT_MODE_1 = 1 +ISHARP_FMT_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ISHARP_LBA_MODE_ENUM' +ISHARP_LBA_MODE_ENUM__enumvalues = { + 0: 'ISHARP_LBA_MODE_0', + 1: 'ISHARP_LBA_MODE_1', +} +ISHARP_LBA_MODE_0 = 0 +ISHARP_LBA_MODE_1 = 1 +ISHARP_LBA_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ISHARP_NOISEDET_MODE_ENUM' +ISHARP_NOISEDET_MODE_ENUM__enumvalues = { + 0: 'ISHARP_NOISEDET_MODE_0', + 1: 'ISHARP_NOISEDET_MODE_1', + 2: 'ISHARP_NOISEDET_MODE_2', + 3: 'ISHARP_NOISEDET_MODE_3', +} +ISHARP_NOISEDET_MODE_0 = 0 +ISHARP_NOISEDET_MODE_1 = 1 +ISHARP_NOISEDET_MODE_2 = 2 +ISHARP_NOISEDET_MODE_3 = 3 +ISHARP_NOISEDET_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'LB_ALPHA_EN' +LB_ALPHA_EN__enumvalues = { + 0: 'LB_ALPHA_DISABLE', + 1: 'LB_ALPHA_ENABLE', +} +LB_ALPHA_DISABLE = 0 +LB_ALPHA_ENABLE = 1 +LB_ALPHA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERLEAVE_EN' +LB_INTERLEAVE_EN__enumvalues = { + 0: 'LB_INTERLEAVE_DISABLE', + 1: 'LB_INTERLEAVE_ENABLE', +} +LB_INTERLEAVE_DISABLE = 0 +LB_INTERLEAVE_ENABLE = 1 +LB_INTERLEAVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MEMORY_CONFIG' +LB_MEMORY_CONFIG__enumvalues = { + 0: 'LB_MEMORY_CONFIG_0', + 1: 'LB_MEMORY_CONFIG_1', + 2: 'LB_MEMORY_CONFIG_2', + 3: 'LB_MEMORY_CONFIG_3', +} +LB_MEMORY_CONFIG_0 = 0 +LB_MEMORY_CONFIG_1 = 1 +LB_MEMORY_CONFIG_2 = 2 +LB_MEMORY_CONFIG_3 = 3 +LB_MEMORY_CONFIG = ctypes.c_uint32 # enum + +# values for enumeration 'MATRIX_MODE_ENUM' +MATRIX_MODE_ENUM__enumvalues = { + 0: 'MATRIX_MODE_0', + 1: 'MATRIX_MODE_1', +} +MATRIX_MODE_0 = 0 +MATRIX_MODE_1 = 1 +MATRIX_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_BYPASS_SEL' +OBUF_BYPASS_SEL__enumvalues = { + 0: 'OBUF_BYPASS_DIS', + 1: 'OBUF_BYPASS_EN', +} +OBUF_BYPASS_DIS = 0 +OBUF_BYPASS_EN = 1 +OBUF_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_IS_HALF_RECOUT_WIDTH_SEL' +OBUF_IS_HALF_RECOUT_WIDTH_SEL__enumvalues = { + 0: 'OBUF_FULL_RECOUT', + 1: 'OBUF_HALF_RECOUT', +} +OBUF_FULL_RECOUT = 0 +OBUF_HALF_RECOUT = 1 +OBUF_IS_HALF_RECOUT_WIDTH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OBUF_USE_FULL_BUFFER_SEL' +OBUF_USE_FULL_BUFFER_SEL__enumvalues = { + 0: 'OBUF_RECOUT', + 1: 'OBUF_FULL', +} +OBUF_RECOUT = 0 +OBUF_FULL = 1 +OBUF_USE_FULL_BUFFER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_2TAP_HARDCODE' +SCL_2TAP_HARDCODE__enumvalues = { + 0: 'SCL_COEF_2TAP_HARDCODE_OFF', + 1: 'SCL_COEF_2TAP_HARDCODE_ON', +} +SCL_COEF_2TAP_HARDCODE_OFF = 0 +SCL_COEF_2TAP_HARDCODE_ON = 1 +SCL_2TAP_HARDCODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_ALPHA_COEF' +SCL_ALPHA_COEF__enumvalues = { + 0: 'SCL_ALPHA_COEF_FIRST', + 1: 'SCL_ALPHA_COEF_SECOND', +} +SCL_ALPHA_COEF_FIRST = 0 +SCL_ALPHA_COEF_SECOND = 1 +SCL_ALPHA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_AUTOCAL_MODE' +SCL_AUTOCAL_MODE__enumvalues = { + 0: 'AUTOCAL_MODE_OFF', + 1: 'AUTOCAL_MODE_AUTOSCALE', + 2: 'AUTOCAL_MODE_AUTOCENTER', + 3: 'AUTOCAL_MODE_AUTOREPLICATE', +} +AUTOCAL_MODE_OFF = 0 +AUTOCAL_MODE_AUTOSCALE = 1 +AUTOCAL_MODE_AUTOCENTER = 2 +AUTOCAL_MODE_AUTOREPLICATE = 3 +SCL_AUTOCAL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_BOUNDARY' +SCL_BOUNDARY__enumvalues = { + 0: 'SCL_BOUNDARY_EDGE', + 1: 'SCL_BOUNDARY_BLACK', +} +SCL_BOUNDARY_EDGE = 0 +SCL_BOUNDARY_BLACK = 1 +SCL_BOUNDARY = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_CHROMA_COEF' +SCL_CHROMA_COEF__enumvalues = { + 0: 'SCL_CHROMA_COEF_FIRST', + 1: 'SCL_CHROMA_COEF_SECOND', +} +SCL_CHROMA_COEF_FIRST = 0 +SCL_CHROMA_COEF_SECOND = 1 +SCL_CHROMA_COEF = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_FILTER_TYPE_SEL' +SCL_COEF_FILTER_TYPE_SEL__enumvalues = { + 0: 'SCL_COEF_LUMA_VERT_FILTER', + 1: 'SCL_COEF_LUMA_HORZ_FILTER', + 2: 'SCL_COEF_CHROMA_VERT_FILTER', + 3: 'SCL_COEF_CHROMA_HORZ_FILTER', + 4: 'SCL_COEF_SC_VERT_FILTER', + 5: 'SCL_COEF_SC_HORZ_FILTER', +} +SCL_COEF_LUMA_VERT_FILTER = 0 +SCL_COEF_LUMA_HORZ_FILTER = 1 +SCL_COEF_CHROMA_VERT_FILTER = 2 +SCL_COEF_CHROMA_HORZ_FILTER = 3 +SCL_COEF_SC_VERT_FILTER = 4 +SCL_COEF_SC_HORZ_FILTER = 5 +SCL_COEF_FILTER_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_RAM_SEL' +SCL_COEF_RAM_SEL__enumvalues = { + 0: 'SCL_COEF_RAM_SEL_0', + 1: 'SCL_COEF_RAM_SEL_1', +} +SCL_COEF_RAM_SEL_0 = 0 +SCL_COEF_RAM_SEL_1 = 1 +SCL_COEF_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_SHARP_EN' +SCL_SHARP_EN__enumvalues = { + 0: 'SCL_SHARP_DISABLE', + 1: 'SCL_SHARP_ENABLE', +} +SCL_SHARP_DISABLE = 0 +SCL_SHARP_ENABLE = 1 +SCL_SHARP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_30BIT_ENUM' +CMC_3DLUT_30BIT_ENUM__enumvalues = { + 0: 'CMC_3DLUT_36BIT', + 1: 'CMC_3DLUT_30BIT', +} +CMC_3DLUT_36BIT = 0 +CMC_3DLUT_30BIT = 1 +CMC_3DLUT_30BIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_RAM_SEL' +CMC_3DLUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAM0_ACCESS', + 1: 'CMC_RAM1_ACCESS', + 2: 'CMC_RAM2_ACCESS', + 3: 'CMC_RAM3_ACCESS', +} +CMC_RAM0_ACCESS = 0 +CMC_RAM1_ACCESS = 1 +CMC_RAM2_ACCESS = 2 +CMC_RAM3_ACCESS = 3 +CMC_3DLUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_3DLUT_SIZE_ENUM' +CMC_3DLUT_SIZE_ENUM__enumvalues = { + 0: 'CMC_3DLUT_17CUBE', + 1: 'CMC_3DLUT_9CUBE', +} +CMC_3DLUT_17CUBE = 0 +CMC_3DLUT_9CUBE = 1 +CMC_3DLUT_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_CONFIG_ENUM' +CMC_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'CMC_LUT_2CFG_NO_MEMORY', + 1: 'CMC_LUT_2CFG_MEMORY_A', + 2: 'CMC_LUT_2CFG_MEMORY_B', +} +CMC_LUT_2CFG_NO_MEMORY = 0 +CMC_LUT_2CFG_MEMORY_A = 1 +CMC_LUT_2CFG_MEMORY_B = 2 +CMC_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_2_MODE_ENUM' +CMC_LUT_2_MODE_ENUM__enumvalues = { + 0: 'CMC_LUT_2_MODE_BYPASS', + 1: 'CMC_LUT_2_MODE_RAMA_LUT', + 2: 'CMC_LUT_2_MODE_RAMB_LUT', +} +CMC_LUT_2_MODE_BYPASS = 0 +CMC_LUT_2_MODE_RAMA_LUT = 1 +CMC_LUT_2_MODE_RAMB_LUT = 2 +CMC_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_NUM_SEG' +CMC_LUT_NUM_SEG__enumvalues = { + 0: 'CMC_SEGMENTS_1', + 1: 'CMC_SEGMENTS_2', + 2: 'CMC_SEGMENTS_4', + 3: 'CMC_SEGMENTS_8', + 4: 'CMC_SEGMENTS_16', + 5: 'CMC_SEGMENTS_32', + 6: 'CMC_SEGMENTS_64', + 7: 'CMC_SEGMENTS_128', +} +CMC_SEGMENTS_1 = 0 +CMC_SEGMENTS_2 = 1 +CMC_SEGMENTS_4 = 2 +CMC_SEGMENTS_8 = 3 +CMC_SEGMENTS_16 = 4 +CMC_SEGMENTS_32 = 5 +CMC_SEGMENTS_64 = 6 +CMC_SEGMENTS_128 = 7 +CMC_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CMC_LUT_RAM_SEL' +CMC_LUT_RAM_SEL__enumvalues = { + 0: 'CMC_RAMA_ACCESS', + 1: 'CMC_RAMB_ACCESS', +} +CMC_RAMA_ACCESS = 0 +CMC_RAMB_ACCESS = 1 +CMC_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_BYPASS' +CM_BYPASS__enumvalues = { + 0: 'NON_BYPASS', + 1: 'BYPASS_EN', +} +NON_BYPASS = 0 +BYPASS_EN = 1 +CM_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'CM_COEF_FORMAT_ENUM' +CM_COEF_FORMAT_ENUM__enumvalues = { + 0: 'FIX_S2_13', + 1: 'FIX_S3_12', +} +FIX_S2_13 = 0 +FIX_S3_12 = 1 +CM_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_DATA_SIGNED' +CM_DATA_SIGNED__enumvalues = { + 0: 'UNSIGNED', + 1: 'SIGNED', +} +UNSIGNED = 0 +SIGNED = 1 +CM_DATA_SIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'CM_EN' +CM_EN__enumvalues = { + 0: 'CM_DISABLE', + 1: 'CM_ENABLE', +} +CM_DISABLE = 0 +CM_ENABLE = 1 +CM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_MODE_ENUM' +CM_GAMMA_LUT_MODE_ENUM__enumvalues = { + 0: 'BYPASS', + 1: 'RESERVED_1', + 2: 'RAM_LUT', + 3: 'RESERVED_3', +} +BYPASS = 0 +RESERVED_1 = 1 +RAM_LUT = 2 +RESERVED_3 = 3 +CM_GAMMA_LUT_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_PWL_DISABLE_ENUM' +CM_GAMMA_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'ENABLE_PWL', + 1: 'DISABLE_PWL', +} +ENABLE_PWL = 0 +DISABLE_PWL = 1 +CM_GAMMA_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_GAMMA_LUT_SEL_ENUM' +CM_GAMMA_LUT_SEL_ENUM__enumvalues = { + 0: 'RAMA', + 1: 'RAMB', +} +RAMA = 0 +RAMB = 1 +CM_GAMMA_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_CONFIG_ENUM' +CM_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'LUT_2CFG_NO_MEMORY', + 1: 'LUT_2CFG_MEMORY_A', + 2: 'LUT_2CFG_MEMORY_B', +} +LUT_2CFG_NO_MEMORY = 0 +LUT_2CFG_MEMORY_A = 1 +LUT_2CFG_MEMORY_B = 2 +CM_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_2_MODE_ENUM' +CM_LUT_2_MODE_ENUM__enumvalues = { + 0: 'LUT_2_MODE_BYPASS', + 1: 'LUT_2_MODE_RAMA_LUT', + 2: 'LUT_2_MODE_RAMB_LUT', +} +LUT_2_MODE_BYPASS = 0 +LUT_2_MODE_RAMA_LUT = 1 +LUT_2_MODE_RAMB_LUT = 2 +CM_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_CONFIG_ENUM' +CM_LUT_4_CONFIG_ENUM__enumvalues = { + 0: 'LUT_4CFG_NO_MEMORY', + 1: 'LUT_4CFG_ROM_A', + 2: 'LUT_4CFG_ROM_B', + 3: 'LUT_4CFG_MEMORY_A', + 4: 'LUT_4CFG_MEMORY_B', +} +LUT_4CFG_NO_MEMORY = 0 +LUT_4CFG_ROM_A = 1 +LUT_4CFG_ROM_B = 2 +LUT_4CFG_MEMORY_A = 3 +LUT_4CFG_MEMORY_B = 4 +CM_LUT_4_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_4_MODE_ENUM' +CM_LUT_4_MODE_ENUM__enumvalues = { + 0: 'LUT_4_MODE_BYPASS', + 1: 'LUT_4_MODE_ROMA_LUT', + 2: 'LUT_4_MODE_ROMB_LUT', + 3: 'LUT_4_MODE_RAMA_LUT', + 4: 'LUT_4_MODE_RAMB_LUT', +} +LUT_4_MODE_BYPASS = 0 +LUT_4_MODE_ROMA_LUT = 1 +LUT_4_MODE_ROMB_LUT = 2 +LUT_4_MODE_RAMA_LUT = 3 +LUT_4_MODE_RAMB_LUT = 4 +CM_LUT_4_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_CONFIG_MODE' +CM_LUT_CONFIG_MODE__enumvalues = { + 0: 'DIFFERENT_RGB', + 1: 'ALL_USE_R', +} +DIFFERENT_RGB = 0 +ALL_USE_R = 1 +CM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_NUM_SEG' +CM_LUT_NUM_SEG__enumvalues = { + 0: 'SEGMENTS_1', + 1: 'SEGMENTS_2', + 2: 'SEGMENTS_4', + 3: 'SEGMENTS_8', + 4: 'SEGMENTS_16', + 5: 'SEGMENTS_32', + 6: 'SEGMENTS_64', + 7: 'SEGMENTS_128', +} +SEGMENTS_1 = 0 +SEGMENTS_2 = 1 +SEGMENTS_4 = 2 +SEGMENTS_8 = 3 +SEGMENTS_16 = 4 +SEGMENTS_32 = 5 +SEGMENTS_64 = 6 +SEGMENTS_128 = 7 +CM_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_RAM_SEL' +CM_LUT_RAM_SEL__enumvalues = { + 0: 'RAMA_ACCESS', + 1: 'RAMB_ACCESS', +} +RAMA_ACCESS = 0 +RAMB_ACCESS = 1 +CM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_READ_COLOR_SEL' +CM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'BLUE_LUT', + 1: 'GREEN_LUT', + 2: 'RED_LUT', +} +BLUE_LUT = 0 +GREEN_LUT = 1 +RED_LUT = 2 +CM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CM_LUT_READ_DBG' +CM_LUT_READ_DBG__enumvalues = { + 0: 'DISABLE_DEBUG', + 1: 'ENABLE_DEBUG', +} +DISABLE_DEBUG = 0 +ENABLE_DEBUG = 1 +CM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'CM_PENDING' +CM_PENDING__enumvalues = { + 0: 'CM_NOT_PENDING', + 1: 'CM_YES_PENDING', +} +CM_NOT_PENDING = 0 +CM_YES_PENDING = 1 +CM_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'CM_POST_CSC_MODE_ENUM' +CM_POST_CSC_MODE_ENUM__enumvalues = { + 0: 'BYPASS_POST_CSC', + 1: 'COEF_POST_CSC', + 2: 'COEF_POST_CSC_B', +} +BYPASS_POST_CSC = 0 +COEF_POST_CSC = 1 +COEF_POST_CSC_B = 2 +CM_POST_CSC_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CM_WRITE_BASE_ONLY' +CM_WRITE_BASE_ONLY__enumvalues = { + 0: 'WRITE_BOTH', + 1: 'WRITE_BASE_ONLY', +} +WRITE_BOTH = 0 +WRITE_BASE_ONLY = 1 +CM_WRITE_BASE_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_CUR_SEL' +CRC_CUR_SEL__enumvalues = { + 0: 'CRC_CUR_0', + 1: 'CRC_CUR_1', +} +CRC_CUR_0 = 0 +CRC_CUR_1 = 1 +CRC_CUR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_INTERLACE_SEL' +CRC_INTERLACE_SEL__enumvalues = { + 0: 'CRC_INTERLACE_0', + 1: 'CRC_INTERLACE_1', + 2: 'CRC_INTERLACE_2', + 3: 'CRC_INTERLACE_3', +} +CRC_INTERLACE_0 = 0 +CRC_INTERLACE_1 = 1 +CRC_INTERLACE_2 = 2 +CRC_INTERLACE_3 = 3 +CRC_INTERLACE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_IN_PIX_SEL' +CRC_IN_PIX_SEL__enumvalues = { + 0: 'CRC_IN_PIX_0', + 1: 'CRC_IN_PIX_1', + 2: 'CRC_IN_PIX_2', + 3: 'CRC_IN_PIX_3', + 4: 'CRC_IN_PIX_4', + 5: 'CRC_IN_PIX_5', + 6: 'CRC_IN_PIX_6', + 7: 'CRC_IN_PIX_7', +} +CRC_IN_PIX_0 = 0 +CRC_IN_PIX_1 = 1 +CRC_IN_PIX_2 = 2 +CRC_IN_PIX_3 = 3 +CRC_IN_PIX_4 = 4 +CRC_IN_PIX_5 = 5 +CRC_IN_PIX_6 = 6 +CRC_IN_PIX_7 = 7 +CRC_IN_PIX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_SRC_SEL' +CRC_SRC_SEL__enumvalues = { + 0: 'CRC_SRC_0', + 1: 'CRC_SRC_1', + 2: 'CRC_SRC_2', + 3: 'CRC_SRC_3', +} +CRC_SRC_0 = 0 +CRC_SRC_1 = 1 +CRC_SRC_2 = 2 +CRC_SRC_3 = 3 +CRC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRC_STEREO_SEL' +CRC_STEREO_SEL__enumvalues = { + 0: 'CRC_STEREO_0', + 1: 'CRC_STEREO_1', + 2: 'CRC_STEREO_2', + 3: 'CRC_STEREO_3', +} +CRC_STEREO_0 = 0 +CRC_STEREO_1 = 1 +CRC_STEREO_2 = 2 +CRC_STEREO_3 = 3 +CRC_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_SEL' +TEST_CLK_SEL__enumvalues = { + 0: 'TEST_CLK_SEL_0', + 1: 'TEST_CLK_SEL_1', + 2: 'TEST_CLK_SEL_2', + 3: 'TEST_CLK_SEL_3', + 4: 'TEST_CLK_SEL_4', + 5: 'TEST_CLK_SEL_5', + 6: 'TEST_CLK_SEL_6', + 7: 'TEST_CLK_SEL_7', +} +TEST_CLK_SEL_0 = 0 +TEST_CLK_SEL_1 = 1 +TEST_CLK_SEL_2 = 2 +TEST_CLK_SEL_3 = 3 +TEST_CLK_SEL_4 = 4 +TEST_CLK_SEL_5 = 5 +TEST_CLK_SEL_6 = 6 +TEST_CLK_SEL_7 = 7 +TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_ACTIVE' +PERFCOUNTER_ACTIVE__enumvalues = { + 0: 'PERFCOUNTER_IS_IDLE', + 1: 'PERFCOUNTER_IS_ACTIVE', +} +PERFCOUNTER_IS_IDLE = 0 +PERFCOUNTER_IS_ACTIVE = 1 +PERFCOUNTER_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT0_STATE' +PERFCOUNTER_CNT0_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT0_STATE_RESET', + 1: 'PERFCOUNTER_CNT0_STATE_START', + 2: 'PERFCOUNTER_CNT0_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT0_STATE_HW', +} +PERFCOUNTER_CNT0_STATE_RESET = 0 +PERFCOUNTER_CNT0_STATE_START = 1 +PERFCOUNTER_CNT0_STATE_FREEZE = 2 +PERFCOUNTER_CNT0_STATE_HW = 3 +PERFCOUNTER_CNT0_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT1_STATE' +PERFCOUNTER_CNT1_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT1_STATE_RESET', + 1: 'PERFCOUNTER_CNT1_STATE_START', + 2: 'PERFCOUNTER_CNT1_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT1_STATE_HW', +} +PERFCOUNTER_CNT1_STATE_RESET = 0 +PERFCOUNTER_CNT1_STATE_START = 1 +PERFCOUNTER_CNT1_STATE_FREEZE = 2 +PERFCOUNTER_CNT1_STATE_HW = 3 +PERFCOUNTER_CNT1_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT2_STATE' +PERFCOUNTER_CNT2_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT2_STATE_RESET', + 1: 'PERFCOUNTER_CNT2_STATE_START', + 2: 'PERFCOUNTER_CNT2_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT2_STATE_HW', +} +PERFCOUNTER_CNT2_STATE_RESET = 0 +PERFCOUNTER_CNT2_STATE_START = 1 +PERFCOUNTER_CNT2_STATE_FREEZE = 2 +PERFCOUNTER_CNT2_STATE_HW = 3 +PERFCOUNTER_CNT2_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT3_STATE' +PERFCOUNTER_CNT3_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT3_STATE_RESET', + 1: 'PERFCOUNTER_CNT3_STATE_START', + 2: 'PERFCOUNTER_CNT3_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT3_STATE_HW', +} +PERFCOUNTER_CNT3_STATE_RESET = 0 +PERFCOUNTER_CNT3_STATE_START = 1 +PERFCOUNTER_CNT3_STATE_FREEZE = 2 +PERFCOUNTER_CNT3_STATE_HW = 3 +PERFCOUNTER_CNT3_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT4_STATE' +PERFCOUNTER_CNT4_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT4_STATE_RESET', + 1: 'PERFCOUNTER_CNT4_STATE_START', + 2: 'PERFCOUNTER_CNT4_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT4_STATE_HW', +} +PERFCOUNTER_CNT4_STATE_RESET = 0 +PERFCOUNTER_CNT4_STATE_START = 1 +PERFCOUNTER_CNT4_STATE_FREEZE = 2 +PERFCOUNTER_CNT4_STATE_HW = 3 +PERFCOUNTER_CNT4_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT5_STATE' +PERFCOUNTER_CNT5_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT5_STATE_RESET', + 1: 'PERFCOUNTER_CNT5_STATE_START', + 2: 'PERFCOUNTER_CNT5_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT5_STATE_HW', +} +PERFCOUNTER_CNT5_STATE_RESET = 0 +PERFCOUNTER_CNT5_STATE_START = 1 +PERFCOUNTER_CNT5_STATE_FREEZE = 2 +PERFCOUNTER_CNT5_STATE_HW = 3 +PERFCOUNTER_CNT5_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT6_STATE' +PERFCOUNTER_CNT6_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT6_STATE_RESET', + 1: 'PERFCOUNTER_CNT6_STATE_START', + 2: 'PERFCOUNTER_CNT6_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT6_STATE_HW', +} +PERFCOUNTER_CNT6_STATE_RESET = 0 +PERFCOUNTER_CNT6_STATE_START = 1 +PERFCOUNTER_CNT6_STATE_FREEZE = 2 +PERFCOUNTER_CNT6_STATE_HW = 3 +PERFCOUNTER_CNT6_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT7_STATE' +PERFCOUNTER_CNT7_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT7_STATE_RESET', + 1: 'PERFCOUNTER_CNT7_STATE_START', + 2: 'PERFCOUNTER_CNT7_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT7_STATE_HW', +} +PERFCOUNTER_CNT7_STATE_RESET = 0 +PERFCOUNTER_CNT7_STATE_START = 1 +PERFCOUNTER_CNT7_STATE_FREEZE = 2 +PERFCOUNTER_CNT7_STATE_HW = 3 +PERFCOUNTER_CNT7_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTL_SEL' +PERFCOUNTER_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_CNTL_SEL_0', + 1: 'PERFCOUNTER_CNTL_SEL_1', + 2: 'PERFCOUNTER_CNTL_SEL_2', + 3: 'PERFCOUNTER_CNTL_SEL_3', + 4: 'PERFCOUNTER_CNTL_SEL_4', + 5: 'PERFCOUNTER_CNTL_SEL_5', + 6: 'PERFCOUNTER_CNTL_SEL_6', + 7: 'PERFCOUNTER_CNTL_SEL_7', +} +PERFCOUNTER_CNTL_SEL_0 = 0 +PERFCOUNTER_CNTL_SEL_1 = 1 +PERFCOUNTER_CNTL_SEL_2 = 2 +PERFCOUNTER_CNTL_SEL_3 = 3 +PERFCOUNTER_CNTL_SEL_4 = 4 +PERFCOUNTER_CNTL_SEL_5 = 5 +PERFCOUNTER_CNTL_SEL_6 = 6 +PERFCOUNTER_CNTL_SEL_7 = 7 +PERFCOUNTER_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTOFF_START_DIS' +PERFCOUNTER_CNTOFF_START_DIS__enumvalues = { + 0: 'PERFCOUNTER_CNTOFF_START_ENABLE', + 1: 'PERFCOUNTER_CNTOFF_START_DISABLE', +} +PERFCOUNTER_CNTOFF_START_ENABLE = 0 +PERFCOUNTER_CNTOFF_START_DISABLE = 1 +PERFCOUNTER_CNTOFF_START_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_COUNTED_VALUE_TYPE' +PERFCOUNTER_COUNTED_VALUE_TYPE__enumvalues = { + 0: 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 1: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 2: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', +} +PERFCOUNTER_COUNTED_VALUE_TYPE_ACC = 0 +PERFCOUNTER_COUNTED_VALUE_TYPE_MAX = 1 +PERFCOUNTER_COUNTED_VALUE_TYPE_MIN = 2 +PERFCOUNTER_COUNTED_VALUE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CVALUE_SEL' +PERFCOUNTER_CVALUE_SEL__enumvalues = { + 0: 'PERFCOUNTER_CVALUE_SEL_47_0', + 1: 'PERFCOUNTER_CVALUE_SEL_15_0', + 2: 'PERFCOUNTER_CVALUE_SEL_31_16', + 3: 'PERFCOUNTER_CVALUE_SEL_47_32', + 4: 'PERFCOUNTER_CVALUE_SEL_11_0', + 5: 'PERFCOUNTER_CVALUE_SEL_23_12', + 6: 'PERFCOUNTER_CVALUE_SEL_35_24', + 7: 'PERFCOUNTER_CVALUE_SEL_47_36', +} +PERFCOUNTER_CVALUE_SEL_47_0 = 0 +PERFCOUNTER_CVALUE_SEL_15_0 = 1 +PERFCOUNTER_CVALUE_SEL_31_16 = 2 +PERFCOUNTER_CVALUE_SEL_47_32 = 3 +PERFCOUNTER_CVALUE_SEL_11_0 = 4 +PERFCOUNTER_CVALUE_SEL_23_12 = 5 +PERFCOUNTER_CVALUE_SEL_35_24 = 6 +PERFCOUNTER_CVALUE_SEL_47_36 = 7 +PERFCOUNTER_CVALUE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_CNTL_SEL' +PERFCOUNTER_HW_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', + 1: 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', +} +PERFCOUNTER_HW_CNTL_SEL_RUNEN = 0 +PERFCOUNTER_HW_CNTL_SEL_CNTOFF = 1 +PERFCOUNTER_HW_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP1_SEL' +PERFCOUNTER_HW_STOP1_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP1_0', + 1: 'PERFCOUNTER_HW_STOP1_1', +} +PERFCOUNTER_HW_STOP1_0 = 0 +PERFCOUNTER_HW_STOP1_1 = 1 +PERFCOUNTER_HW_STOP1_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_STOP2_SEL' +PERFCOUNTER_HW_STOP2_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_STOP2_0', + 1: 'PERFCOUNTER_HW_STOP2_1', +} +PERFCOUNTER_HW_STOP2_0 = 0 +PERFCOUNTER_HW_STOP2_1 = 1 +PERFCOUNTER_HW_STOP2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INC_MODE' +PERFCOUNTER_INC_MODE__enumvalues = { + 0: 'PERFCOUNTER_INC_MODE_MULTI_BIT', + 1: 'PERFCOUNTER_INC_MODE_BOTH_EDGE', + 2: 'PERFCOUNTER_INC_MODE_LSB', + 3: 'PERFCOUNTER_INC_MODE_POS_EDGE', + 4: 'PERFCOUNTER_INC_MODE_NEG_EDGE', +} +PERFCOUNTER_INC_MODE_MULTI_BIT = 0 +PERFCOUNTER_INC_MODE_BOTH_EDGE = 1 +PERFCOUNTER_INC_MODE_LSB = 2 +PERFCOUNTER_INC_MODE_POS_EDGE = 3 +PERFCOUNTER_INC_MODE_NEG_EDGE = 4 +PERFCOUNTER_INC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_EN' +PERFCOUNTER_INT_EN__enumvalues = { + 0: 'PERFCOUNTER_INT_DISABLE', + 1: 'PERFCOUNTER_INT_ENABLE', +} +PERFCOUNTER_INT_DISABLE = 0 +PERFCOUNTER_INT_ENABLE = 1 +PERFCOUNTER_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_TYPE' +PERFCOUNTER_INT_TYPE__enumvalues = { + 0: 'PERFCOUNTER_INT_TYPE_LEVEL', + 1: 'PERFCOUNTER_INT_TYPE_PULSE', +} +PERFCOUNTER_INT_TYPE_LEVEL = 0 +PERFCOUNTER_INT_TYPE_PULSE = 1 +PERFCOUNTER_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_OFF_MASK' +PERFCOUNTER_OFF_MASK__enumvalues = { + 0: 'PERFCOUNTER_OFF_MASK_DISABLE', + 1: 'PERFCOUNTER_OFF_MASK_ENABLE', +} +PERFCOUNTER_OFF_MASK_DISABLE = 0 +PERFCOUNTER_OFF_MASK_ENABLE = 1 +PERFCOUNTER_OFF_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RESTART_EN' +PERFCOUNTER_RESTART_EN__enumvalues = { + 0: 'PERFCOUNTER_RESTART_DISABLE', + 1: 'PERFCOUNTER_RESTART_ENABLE', +} +PERFCOUNTER_RESTART_DISABLE = 0 +PERFCOUNTER_RESTART_ENABLE = 1 +PERFCOUNTER_RESTART_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RUNEN_MODE' +PERFCOUNTER_RUNEN_MODE__enumvalues = { + 0: 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 1: 'PERFCOUNTER_RUNEN_MODE_EDGE', +} +PERFCOUNTER_RUNEN_MODE_LEVEL = 0 +PERFCOUNTER_RUNEN_MODE_EDGE = 1 +PERFCOUNTER_RUNEN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL0' +PERFCOUNTER_STATE_SEL0__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL0_LOCAL', +} +PERFCOUNTER_STATE_SEL0_GLOBAL = 0 +PERFCOUNTER_STATE_SEL0_LOCAL = 1 +PERFCOUNTER_STATE_SEL0 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL1' +PERFCOUNTER_STATE_SEL1__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL1_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL1_LOCAL', +} +PERFCOUNTER_STATE_SEL1_GLOBAL = 0 +PERFCOUNTER_STATE_SEL1_LOCAL = 1 +PERFCOUNTER_STATE_SEL1 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL2' +PERFCOUNTER_STATE_SEL2__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL2_LOCAL', +} +PERFCOUNTER_STATE_SEL2_GLOBAL = 0 +PERFCOUNTER_STATE_SEL2_LOCAL = 1 +PERFCOUNTER_STATE_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL3' +PERFCOUNTER_STATE_SEL3__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL3_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL3_LOCAL', +} +PERFCOUNTER_STATE_SEL3_GLOBAL = 0 +PERFCOUNTER_STATE_SEL3_LOCAL = 1 +PERFCOUNTER_STATE_SEL3 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL4' +PERFCOUNTER_STATE_SEL4__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL4_LOCAL', +} +PERFCOUNTER_STATE_SEL4_GLOBAL = 0 +PERFCOUNTER_STATE_SEL4_LOCAL = 1 +PERFCOUNTER_STATE_SEL4 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL5' +PERFCOUNTER_STATE_SEL5__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL5_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL5_LOCAL', +} +PERFCOUNTER_STATE_SEL5_GLOBAL = 0 +PERFCOUNTER_STATE_SEL5_LOCAL = 1 +PERFCOUNTER_STATE_SEL5 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL6' +PERFCOUNTER_STATE_SEL6__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL6_LOCAL', +} +PERFCOUNTER_STATE_SEL6_GLOBAL = 0 +PERFCOUNTER_STATE_SEL6_LOCAL = 1 +PERFCOUNTER_STATE_SEL6 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL7' +PERFCOUNTER_STATE_SEL7__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL7_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL7_LOCAL', +} +PERFCOUNTER_STATE_SEL7_GLOBAL = 0 +PERFCOUNTER_STATE_SEL7_LOCAL = 1 +PERFCOUNTER_STATE_SEL7 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_AND_OR' +PERFMON_CNTOFF_AND_OR__enumvalues = { + 0: 'PERFMON_CNTOFF_OR', + 1: 'PERFMON_CNTOFF_AND', +} +PERFMON_CNTOFF_OR = 0 +PERFMON_CNTOFF_AND = 1 +PERFMON_CNTOFF_AND_OR = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_EN' +PERFMON_CNTOFF_INT_EN__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_DISABLE', + 1: 'PERFMON_CNTOFF_INT_ENABLE', +} +PERFMON_CNTOFF_INT_DISABLE = 0 +PERFMON_CNTOFF_INT_ENABLE = 1 +PERFMON_CNTOFF_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_TYPE' +PERFMON_CNTOFF_INT_TYPE__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_TYPE_LEVEL', + 1: 'PERFMON_CNTOFF_INT_TYPE_PULSE', +} +PERFMON_CNTOFF_INT_TYPE_LEVEL = 0 +PERFMON_CNTOFF_INT_TYPE_PULSE = 1 +PERFMON_CNTOFF_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_STATE' +PERFMON_STATE__enumvalues = { + 0: 'PERFMON_STATE_RESET', + 1: 'PERFMON_STATE_START', + 2: 'PERFMON_STATE_FREEZE', + 3: 'PERFMON_STATE_HW', +} +PERFMON_STATE_RESET = 0 +PERFMON_STATE_START = 1 +PERFMON_STATE_FREEZE = 2 +PERFMON_STATE_HW = 3 +PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'BIGK_FRAGMENT_SIZE' +BIGK_FRAGMENT_SIZE__enumvalues = { + 0: 'VM_PG_SIZE_4KB', + 1: 'VM_PG_SIZE_8KB', + 2: 'VM_PG_SIZE_16KB', + 3: 'VM_PG_SIZE_32KB', + 4: 'VM_PG_SIZE_64KB', + 5: 'VM_PG_SIZE_128KB', + 6: 'VM_PG_SIZE_256KB', + 7: 'VM_PG_SIZE_512KB', + 8: 'VM_PG_SIZE_1MB', + 9: 'VM_PG_SIZE_2MB', + 10: 'VM_PG_SIZE_4MB', + 11: 'VM_PG_SIZE_8MB', + 12: 'VM_PG_SIZE_16MB', + 13: 'VM_PG_SIZE_32MB', + 14: 'VM_PG_SIZE_64MB', + 15: 'VM_PG_SIZE_128MB', +} +VM_PG_SIZE_4KB = 0 +VM_PG_SIZE_8KB = 1 +VM_PG_SIZE_16KB = 2 +VM_PG_SIZE_32KB = 3 +VM_PG_SIZE_64KB = 4 +VM_PG_SIZE_128KB = 5 +VM_PG_SIZE_256KB = 6 +VM_PG_SIZE_512KB = 7 +VM_PG_SIZE_1MB = 8 +VM_PG_SIZE_2MB = 9 +VM_PG_SIZE_4MB = 10 +VM_PG_SIZE_8MB = 11 +VM_PG_SIZE_16MB = 12 +VM_PG_SIZE_32MB = 13 +VM_PG_SIZE_64MB = 14 +VM_PG_SIZE_128MB = 15 +BIGK_FRAGMENT_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'CHUNK_SIZE' +CHUNK_SIZE__enumvalues = { + 0: 'CHUNK_SIZE_1KB', + 1: 'CHUNK_SIZE_2KB', + 2: 'CHUNK_SIZE_4KB', + 3: 'CHUNK_SIZE_8KB', + 4: 'CHUNK_SIZE_16KB', + 5: 'CHUNK_SIZE_32KB', + 6: 'CHUNK_SIZE_64KB', +} +CHUNK_SIZE_1KB = 0 +CHUNK_SIZE_2KB = 1 +CHUNK_SIZE_4KB = 2 +CHUNK_SIZE_8KB = 3 +CHUNK_SIZE_16KB = 4 +CHUNK_SIZE_32KB = 5 +CHUNK_SIZE_64KB = 6 +CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DPTE_GROUP_SIZE' +DPTE_GROUP_SIZE__enumvalues = { + 0: 'DPTE_GROUP_SIZE_64B', + 1: 'DPTE_GROUP_SIZE_128B', + 2: 'DPTE_GROUP_SIZE_256B', + 3: 'DPTE_GROUP_SIZE_512B', + 4: 'DPTE_GROUP_SIZE_1024B', + 5: 'DPTE_GROUP_SIZE_2048B', +} +DPTE_GROUP_SIZE_64B = 0 +DPTE_GROUP_SIZE_128B = 1 +DPTE_GROUP_SIZE_256B = 2 +DPTE_GROUP_SIZE_512B = 3 +DPTE_GROUP_SIZE_1024B = 4 +DPTE_GROUP_SIZE_2048B = 5 +DPTE_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'FORCE_ONE_ROW_FOR_FRAME' +FORCE_ONE_ROW_FOR_FRAME__enumvalues = { + 0: 'FORCE_ONE_ROW_FOR_FRAME_0', + 1: 'FORCE_ONE_ROW_FOR_FRAME_1', +} +FORCE_ONE_ROW_FOR_FRAME_0 = 0 +FORCE_ONE_ROW_FOR_FRAME_1 = 1 +FORCE_ONE_ROW_FOR_FRAME = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_BLANK_EN' +HUBP_BLANK_EN__enumvalues = { + 0: 'HUBP_BLANK_SW_DEASSERT', + 1: 'HUBP_BLANK_SW_ASSERT', +} +HUBP_BLANK_SW_DEASSERT = 0 +HUBP_BLANK_SW_ASSERT = 1 +HUBP_BLANK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_IN_BLANK' +HUBP_IN_BLANK__enumvalues = { + 0: 'HUBP_IN_ACTIVE', + 1: 'HUBP_IN_VBLANK', +} +HUBP_IN_ACTIVE = 0 +HUBP_IN_VBLANK = 1 +HUBP_IN_BLANK = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_MEASURE_WIN_MODE_DCFCLK' +HUBP_MEASURE_WIN_MODE_DCFCLK__enumvalues = { + 0: 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 1: 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 2: 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 3: 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', +} +HUBP_MEASURE_WIN_MODE_DCFCLK_0 = 0 +HUBP_MEASURE_WIN_MODE_DCFCLK_1 = 1 +HUBP_MEASURE_WIN_MODE_DCFCLK_2 = 2 +HUBP_MEASURE_WIN_MODE_DCFCLK_3 = 3 +HUBP_MEASURE_WIN_MODE_DCFCLK = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_NO_OUTSTANDING_REQ' +HUBP_NO_OUTSTANDING_REQ__enumvalues = { + 0: 'OUTSTANDING_REQ', + 1: 'NO_OUTSTANDING_REQ', +} +OUTSTANDING_REQ = 0 +NO_OUTSTANDING_REQ = 1 +HUBP_NO_OUTSTANDING_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_SOFT_RESET' +HUBP_SOFT_RESET__enumvalues = { + 0: 'HUBP_SOFT_RESET_ON', + 1: 'HUBP_SOFT_RESET_OFF', +} +HUBP_SOFT_RESET_ON = 0 +HUBP_SOFT_RESET_OFF = 1 +HUBP_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_TTU_DISABLE' +HUBP_TTU_DISABLE__enumvalues = { + 0: 'HUBP_TTU_ENABLED', + 1: 'HUBP_TTU_DISABLED', +} +HUBP_TTU_ENABLED = 0 +HUBP_TTU_DISABLED = 1 +HUBP_TTU_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VREADY_AT_OR_AFTER_VSYNC' +HUBP_VREADY_AT_OR_AFTER_VSYNC__enumvalues = { + 0: 'VREADY_BEFORE_VSYNC', + 1: 'VREADY_AT_OR_AFTER_VSYNC', +} +VREADY_BEFORE_VSYNC = 0 +VREADY_AT_OR_AFTER_VSYNC = 1 +HUBP_VREADY_AT_OR_AFTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_VTG_SEL' +HUBP_VTG_SEL__enumvalues = { + 0: 'VTG_SEL_0', + 1: 'VTG_SEL_1', + 2: 'VTG_SEL_2', + 3: 'VTG_SEL_3', + 4: 'VTG_SEL_4', + 5: 'VTG_SEL_5', +} +VTG_SEL_0 = 0 +VTG_SEL_1 = 1 +VTG_SEL_2 = 2 +VTG_SEL_3 = 3 +VTG_SEL_4 = 4 +VTG_SEL_5 = 5 +HUBP_VTG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'H_MIRROR_EN' +H_MIRROR_EN__enumvalues = { + 0: 'HW_MIRRORING_DISABLE', + 1: 'HW_MIRRORING_ENABLE', +} +HW_MIRRORING_DISABLE = 0 +HW_MIRRORING_ENABLE = 1 +H_MIRROR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LEGACY_PIPE_INTERLEAVE' +LEGACY_PIPE_INTERLEAVE__enumvalues = { + 0: 'LEGACY_PIPE_INTERLEAVE_256B', + 1: 'LEGACY_PIPE_INTERLEAVE_512B', +} +LEGACY_PIPE_INTERLEAVE_256B = 0 +LEGACY_PIPE_INTERLEAVE_512B = 1 +LEGACY_PIPE_INTERLEAVE = ctypes.c_uint32 # enum + +# values for enumeration 'META_CHUNK_SIZE' +META_CHUNK_SIZE__enumvalues = { + 0: 'META_CHUNK_SIZE_1KB', + 1: 'META_CHUNK_SIZE_2KB', + 2: 'META_CHUNK_SIZE_4KB', + 3: 'META_CHUNK_SIZE_8KB', +} +META_CHUNK_SIZE_1KB = 0 +META_CHUNK_SIZE_2KB = 1 +META_CHUNK_SIZE_4KB = 2 +META_CHUNK_SIZE_8KB = 3 +META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'META_LINEAR' +META_LINEAR__enumvalues = { + 0: 'META_SURF_TILED', + 1: 'META_SURF_LINEAR', +} +META_SURF_TILED = 0 +META_SURF_LINEAR = 1 +META_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_CHUNK_SIZE' +MIN_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_CHUNK_SIZE', + 1: 'MIN_CHUNK_SIZE_256B', + 2: 'MIN_CHUNK_SIZE_512B', + 3: 'MIN_CHUNK_SIZE_1024B', +} +NO_MIN_CHUNK_SIZE = 0 +MIN_CHUNK_SIZE_256B = 1 +MIN_CHUNK_SIZE_512B = 2 +MIN_CHUNK_SIZE_1024B = 3 +MIN_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'MIN_META_CHUNK_SIZE' +MIN_META_CHUNK_SIZE__enumvalues = { + 0: 'NO_MIN_META_CHUNK_SIZE', + 1: 'MIN_META_CHUNK_SIZE_64B', + 2: 'MIN_META_CHUNK_SIZE_128B', + 3: 'MIN_META_CHUNK_SIZE_256B', +} +NO_MIN_META_CHUNK_SIZE = 0 +MIN_META_CHUNK_SIZE_64B = 1 +MIN_META_CHUNK_SIZE_128B = 2 +MIN_META_CHUNK_SIZE_256B = 3 +MIN_META_CHUNK_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_ALIGNED' +PIPE_ALIGNED__enumvalues = { + 0: 'PIPE_UNALIGNED_SURF', + 1: 'PIPE_ALIGNED_SURF', +} +PIPE_UNALIGNED_SURF = 0 +PIPE_ALIGNED_SURF = 1 +PIPE_ALIGNED = ctypes.c_uint32 # enum + +# values for enumeration 'PTE_BUFFER_MODE' +PTE_BUFFER_MODE__enumvalues = { + 0: 'PTE_BUFFER_MODE_0', + 1: 'PTE_BUFFER_MODE_1', +} +PTE_BUFFER_MODE_0 = 0 +PTE_BUFFER_MODE_1 = 1 +PTE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PTE_ROW_HEIGHT_LINEAR' +PTE_ROW_HEIGHT_LINEAR__enumvalues = { + 0: 'PTE_ROW_HEIGHT_LINEAR_8L', + 1: 'PTE_ROW_HEIGHT_LINEAR_16L', + 2: 'PTE_ROW_HEIGHT_LINEAR_32L', + 3: 'PTE_ROW_HEIGHT_LINEAR_64L', + 4: 'PTE_ROW_HEIGHT_LINEAR_128L', + 5: 'PTE_ROW_HEIGHT_LINEAR_256L', + 6: 'PTE_ROW_HEIGHT_LINEAR_512L', + 7: 'PTE_ROW_HEIGHT_LINEAR_1024L', +} +PTE_ROW_HEIGHT_LINEAR_8L = 0 +PTE_ROW_HEIGHT_LINEAR_16L = 1 +PTE_ROW_HEIGHT_LINEAR_32L = 2 +PTE_ROW_HEIGHT_LINEAR_64L = 3 +PTE_ROW_HEIGHT_LINEAR_128L = 4 +PTE_ROW_HEIGHT_LINEAR_256L = 5 +PTE_ROW_HEIGHT_LINEAR_512L = 6 +PTE_ROW_HEIGHT_LINEAR_1024L = 7 +PTE_ROW_HEIGHT_LINEAR = ctypes.c_uint32 # enum + +# values for enumeration 'ROTATION_ANGLE' +ROTATION_ANGLE__enumvalues = { + 0: 'ROTATE_0_DEGREES', + 1: 'ROTATE_90_DEGREES', + 2: 'ROTATE_180_DEGREES', + 3: 'ROTATE_270_DEGREES', +} +ROTATE_0_DEGREES = 0 +ROTATE_90_DEGREES = 1 +ROTATE_180_DEGREES = 2 +ROTATE_270_DEGREES = 3 +ROTATION_ANGLE = ctypes.c_uint32 # enum + +# values for enumeration 'SWATH_HEIGHT' +SWATH_HEIGHT__enumvalues = { + 0: 'SWATH_HEIGHT_1L', + 1: 'SWATH_HEIGHT_2L', + 2: 'SWATH_HEIGHT_4L', + 3: 'SWATH_HEIGHT_8L', + 4: 'SWATH_HEIGHT_16L', +} +SWATH_HEIGHT_1L = 0 +SWATH_HEIGHT_2L = 1 +SWATH_HEIGHT_4L = 2 +SWATH_HEIGHT_8L = 3 +SWATH_HEIGHT_16L = 4 +SWATH_HEIGHT = ctypes.c_uint32 # enum + +# values for enumeration 'VMPG_SIZE' +VMPG_SIZE__enumvalues = { + 0: 'VMPG_SIZE_4KB', + 1: 'VMPG_SIZE_64KB', +} +VMPG_SIZE_4KB = 0 +VMPG_SIZE_64KB = 1 +VMPG_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VM_GROUP_SIZE' +VM_GROUP_SIZE__enumvalues = { + 0: 'VM_GROUP_SIZE_64B', + 1: 'VM_GROUP_SIZE_128B', + 2: 'VM_GROUP_SIZE_256B', + 3: 'VM_GROUP_SIZE_512B', + 4: 'VM_GROUP_SIZE_1024B', + 5: 'VM_GROUP_SIZE_2048B', +} +VM_GROUP_SIZE_64B = 0 +VM_GROUP_SIZE_128B = 1 +VM_GROUP_SIZE_256B = 2 +VM_GROUP_SIZE_512B = 3 +VM_GROUP_SIZE_1024B = 4 +VM_GROUP_SIZE_2048B = 5 +VM_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_MIN_FREE_ENTRIES' +DFQ_MIN_FREE_ENTRIES__enumvalues = { + 0: 'DFQ_MIN_FREE_ENTRIES_0', + 1: 'DFQ_MIN_FREE_ENTRIES_1', + 2: 'DFQ_MIN_FREE_ENTRIES_2', + 3: 'DFQ_MIN_FREE_ENTRIES_3', + 4: 'DFQ_MIN_FREE_ENTRIES_4', + 5: 'DFQ_MIN_FREE_ENTRIES_5', + 6: 'DFQ_MIN_FREE_ENTRIES_6', + 7: 'DFQ_MIN_FREE_ENTRIES_7', +} +DFQ_MIN_FREE_ENTRIES_0 = 0 +DFQ_MIN_FREE_ENTRIES_1 = 1 +DFQ_MIN_FREE_ENTRIES_2 = 2 +DFQ_MIN_FREE_ENTRIES_3 = 3 +DFQ_MIN_FREE_ENTRIES_4 = 4 +DFQ_MIN_FREE_ENTRIES_5 = 5 +DFQ_MIN_FREE_ENTRIES_6 = 6 +DFQ_MIN_FREE_ENTRIES_7 = 7 +DFQ_MIN_FREE_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_NUM_ENTRIES' +DFQ_NUM_ENTRIES__enumvalues = { + 0: 'DFQ_NUM_ENTRIES_0', + 1: 'DFQ_NUM_ENTRIES_1', + 2: 'DFQ_NUM_ENTRIES_2', + 3: 'DFQ_NUM_ENTRIES_3', + 4: 'DFQ_NUM_ENTRIES_4', + 5: 'DFQ_NUM_ENTRIES_5', + 6: 'DFQ_NUM_ENTRIES_6', + 7: 'DFQ_NUM_ENTRIES_7', + 8: 'DFQ_NUM_ENTRIES_8', +} +DFQ_NUM_ENTRIES_0 = 0 +DFQ_NUM_ENTRIES_1 = 1 +DFQ_NUM_ENTRIES_2 = 2 +DFQ_NUM_ENTRIES_3 = 3 +DFQ_NUM_ENTRIES_4 = 4 +DFQ_NUM_ENTRIES_5 = 5 +DFQ_NUM_ENTRIES_6 = 6 +DFQ_NUM_ENTRIES_7 = 7 +DFQ_NUM_ENTRIES_8 = 8 +DFQ_NUM_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DFQ_SIZE' +DFQ_SIZE__enumvalues = { + 0: 'DFQ_SIZE_0', + 1: 'DFQ_SIZE_1', + 2: 'DFQ_SIZE_2', + 3: 'DFQ_SIZE_3', + 4: 'DFQ_SIZE_4', + 5: 'DFQ_SIZE_5', + 6: 'DFQ_SIZE_6', + 7: 'DFQ_SIZE_7', +} +DFQ_SIZE_0 = 0 +DFQ_SIZE_1 = 1 +DFQ_SIZE_2 = 2 +DFQ_SIZE_3 = 3 +DFQ_SIZE_4 = 4 +DFQ_SIZE_5 = 5 +DFQ_SIZE_6 = 6 +DFQ_SIZE_7 = 7 +DFQ_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_VM_DONE' +DMDATA_VM_DONE__enumvalues = { + 0: 'DMDATA_VM_IS_NOT_DONE', + 1: 'DMDATA_VM_IS_DONE', +} +DMDATA_VM_IS_NOT_DONE = 0 +DMDATA_VM_IS_DONE = 1 +DMDATA_VM_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'EXPANSION_MODE' +EXPANSION_MODE__enumvalues = { + 0: 'EXPANSION_MODE_ZERO', + 1: 'EXPANSION_MODE_CONSERVATIVE', + 2: 'EXPANSION_MODE_OPTIMAL', +} +EXPANSION_MODE_ZERO = 0 +EXPANSION_MODE_CONSERVATIVE = 1 +EXPANSION_MODE_OPTIMAL = 2 +EXPANSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FLIP_RATE' +FLIP_RATE__enumvalues = { + 0: 'FLIP_RATE_0', + 1: 'FLIP_RATE_1', + 2: 'FLIP_RATE_2', + 3: 'FLIP_RATE_3', + 4: 'FLIP_RATE_4', + 5: 'FLIP_RATE_5', + 6: 'FLIP_RATE_6', + 7: 'FLIP_RATE_7', +} +FLIP_RATE_0 = 0 +FLIP_RATE_1 = 1 +FLIP_RATE_2 = 2 +FLIP_RATE_3 = 3 +FLIP_RATE_4 = 4 +FLIP_RATE_5 = 5 +FLIP_RATE_6 = 6 +FLIP_RATE_7 = 7 +FLIP_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'INT_MASK' +INT_MASK__enumvalues = { + 0: 'INT_DISABLED', + 1: 'INT_ENABLED', +} +INT_DISABLED = 0 +INT_ENABLED = 1 +INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_IN_FLUSH_URGENT' +PIPE_IN_FLUSH_URGENT__enumvalues = { + 0: 'PIPE_IN_FLUSH_URGENT_ENABLE', + 1: 'PIPE_IN_FLUSH_URGENT_DISABLE', +} +PIPE_IN_FLUSH_URGENT_ENABLE = 0 +PIPE_IN_FLUSH_URGENT_DISABLE = 1 +PIPE_IN_FLUSH_URGENT = ctypes.c_uint32 # enum + +# values for enumeration 'PRQ_MRQ_FLUSH_URGENT' +PRQ_MRQ_FLUSH_URGENT__enumvalues = { + 0: 'PRQ_MRQ_FLUSH_URGENT_ENABLE', + 1: 'PRQ_MRQ_FLUSH_URGENT_DISABLE', +} +PRQ_MRQ_FLUSH_URGENT_ENABLE = 0 +PRQ_MRQ_FLUSH_URGENT_DISABLE = 1 +PRQ_MRQ_FLUSH_URGENT = ctypes.c_uint32 # enum + +# values for enumeration 'ROW_TTU_MODE' +ROW_TTU_MODE__enumvalues = { + 0: 'END_OF_ROW_MODE', + 1: 'WATERMARK_MODE', +} +END_OF_ROW_MODE = 0 +WATERMARK_MODE = 1 +ROW_TTU_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC' +SURFACE_DCC__enumvalues = { + 0: 'SURFACE_IS_NOT_DCC', + 1: 'SURFACE_IS_DCC', +} +SURFACE_IS_NOT_DCC = 0 +SURFACE_IS_DCC = 1 +SURFACE_DCC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_128B' +SURFACE_DCC_IND_128B__enumvalues = { + 0: 'SURFACE_DCC_IS_NOT_IND_128B', + 1: 'SURFACE_DCC_IS_IND_128B', +} +SURFACE_DCC_IS_NOT_IND_128B = 0 +SURFACE_DCC_IS_IND_128B = 1 +SURFACE_DCC_IND_128B = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_64B' +SURFACE_DCC_IND_64B__enumvalues = { + 0: 'SURFACE_DCC_IS_NOT_IND_64B', + 1: 'SURFACE_DCC_IS_IND_64B', +} +SURFACE_DCC_IS_NOT_IND_64B = 0 +SURFACE_DCC_IS_IND_64B = 1 +SURFACE_DCC_IND_64B = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_DCC_IND_BLK' +SURFACE_DCC_IND_BLK__enumvalues = { + 0: 'SURFACE_DCC_BLOCK_IS_UNCONSTRAINED', + 1: 'SURFACE_DCC_BLOCK_IS_IND_64B', + 2: 'SURFACE_DCC_BLOCK_IS_IND_128B', + 3: 'SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL', +} +SURFACE_DCC_BLOCK_IS_UNCONSTRAINED = 0 +SURFACE_DCC_BLOCK_IS_IND_64B = 1 +SURFACE_DCC_BLOCK_IS_IND_128B = 2 +SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL = 3 +SURFACE_DCC_IND_BLK = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_AWAY_INT_TYPE' +SURFACE_FLIP_AWAY_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_AWAY_INT_LEVEL', + 1: 'SURFACE_FLIP_AWAY_INT_PULSE', +} +SURFACE_FLIP_AWAY_INT_LEVEL = 0 +SURFACE_FLIP_AWAY_INT_PULSE = 1 +SURFACE_FLIP_AWAY_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_EXEC_DEBUG_MODE' +SURFACE_FLIP_EXEC_DEBUG_MODE__enumvalues = { + 0: 'SURFACE_FLIP_EXEC_NORMAL_MODE', + 1: 'SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE', +} +SURFACE_FLIP_EXEC_NORMAL_MODE = 0 +SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE = 1 +SURFACE_FLIP_EXEC_DEBUG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_INT_TYPE' +SURFACE_FLIP_INT_TYPE__enumvalues = { + 0: 'SURFACE_FLIP_INT_LEVEL', + 1: 'SURFACE_FLIP_INT_PULSE', +} +SURFACE_FLIP_INT_LEVEL = 0 +SURFACE_FLIP_INT_PULSE = 1 +SURFACE_FLIP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_IN_STEREOSYNC' +SURFACE_FLIP_IN_STEREOSYNC__enumvalues = { + 0: 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 1: 'SURFACE_FLIP_IN_STEREOSYNC_MODE', +} +SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE = 0 +SURFACE_FLIP_IN_STEREOSYNC_MODE = 1 +SURFACE_FLIP_IN_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_MODE_FOR_STEREOSYNC' +SURFACE_FLIP_MODE_FOR_STEREOSYNC__enumvalues = { + 0: 'FLIP_ANY_FRAME', + 1: 'FLIP_LEFT_EYE', + 2: 'FLIP_RIGHT_EYE', + 3: 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', +} +FLIP_ANY_FRAME = 0 +FLIP_LEFT_EYE = 1 +FLIP_RIGHT_EYE = 2 +SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED = 3 +SURFACE_FLIP_MODE_FOR_STEREOSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_DISABLE' +SURFACE_FLIP_STEREO_SELECT_DISABLE__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 1: 'SURFACE_FLIP_STEREO_SELECT_DISABLED', +} +SURFACE_FLIP_STEREO_SELECT_ENABLED = 0 +SURFACE_FLIP_STEREO_SELECT_DISABLED = 1 +SURFACE_FLIP_STEREO_SELECT_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_STEREO_SELECT_POLARITY' +SURFACE_FLIP_STEREO_SELECT_POLARITY__enumvalues = { + 0: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 1: 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', +} +SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT = 0 +SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT = 1 +SURFACE_FLIP_STEREO_SELECT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_TYPE' +SURFACE_FLIP_TYPE__enumvalues = { + 0: 'SURFACE_V_FLIP', + 1: 'SURFACE_I_FLIP', +} +SURFACE_V_FLIP = 0 +SURFACE_I_FLIP = 1 +SURFACE_FLIP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_FLIP_VUPDATE_SKIP_NUM' +SURFACE_FLIP_VUPDATE_SKIP_NUM__enumvalues = { + 0: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 1: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 2: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 3: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 4: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 5: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 6: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 7: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 8: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 9: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', + 10: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 11: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 12: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 13: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 14: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 15: 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', +} +SURFACE_FLIP_VUPDATE_SKIP_NUM_0 = 0 +SURFACE_FLIP_VUPDATE_SKIP_NUM_1 = 1 +SURFACE_FLIP_VUPDATE_SKIP_NUM_2 = 2 +SURFACE_FLIP_VUPDATE_SKIP_NUM_3 = 3 +SURFACE_FLIP_VUPDATE_SKIP_NUM_4 = 4 +SURFACE_FLIP_VUPDATE_SKIP_NUM_5 = 5 +SURFACE_FLIP_VUPDATE_SKIP_NUM_6 = 6 +SURFACE_FLIP_VUPDATE_SKIP_NUM_7 = 7 +SURFACE_FLIP_VUPDATE_SKIP_NUM_8 = 8 +SURFACE_FLIP_VUPDATE_SKIP_NUM_9 = 9 +SURFACE_FLIP_VUPDATE_SKIP_NUM_10 = 10 +SURFACE_FLIP_VUPDATE_SKIP_NUM_11 = 11 +SURFACE_FLIP_VUPDATE_SKIP_NUM_12 = 12 +SURFACE_FLIP_VUPDATE_SKIP_NUM_13 = 13 +SURFACE_FLIP_VUPDATE_SKIP_NUM_14 = 14 +SURFACE_FLIP_VUPDATE_SKIP_NUM_15 = 15 +SURFACE_FLIP_VUPDATE_SKIP_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_INUSE_RAED_NO_LATCH' +SURFACE_INUSE_RAED_NO_LATCH__enumvalues = { + 0: 'SURFACE_INUSE_IS_LATCHED', + 1: 'SURFACE_INUSE_IS_NOT_LATCHED', +} +SURFACE_INUSE_IS_LATCHED = 0 +SURFACE_INUSE_IS_NOT_LATCHED = 1 +SURFACE_INUSE_RAED_NO_LATCH = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_TMZ' +SURFACE_TMZ__enumvalues = { + 0: 'SURFACE_IS_NOT_TMZ', + 1: 'SURFACE_IS_TMZ', +} +SURFACE_IS_NOT_TMZ = 0 +SURFACE_IS_TMZ = 1 +SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'SURFACE_UPDATE_LOCK' +SURFACE_UPDATE_LOCK__enumvalues = { + 0: 'SURFACE_UPDATE_IS_UNLOCKED', + 1: 'SURFACE_UPDATE_IS_LOCKED', +} +SURFACE_UPDATE_IS_UNLOCKED = 0 +SURFACE_UPDATE_IS_LOCKED = 1 +SURFACE_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_ALPHA' +CROSSBAR_FOR_ALPHA__enumvalues = { + 0: 'ALPHA_DATA_ONTO_ALPHA_PORT', + 1: 'Y_G_DATA_ONTO_ALPHA_PORT', + 2: 'CB_B_DATA_ONTO_ALPHA_PORT', + 3: 'CR_R_DATA_ONTO_ALPHA_PORT', +} +ALPHA_DATA_ONTO_ALPHA_PORT = 0 +Y_G_DATA_ONTO_ALPHA_PORT = 1 +CB_B_DATA_ONTO_ALPHA_PORT = 2 +CR_R_DATA_ONTO_ALPHA_PORT = 3 +CROSSBAR_FOR_ALPHA = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CB_B' +CROSSBAR_FOR_CB_B__enumvalues = { + 0: 'ALPHA_DATA_ONTO_CB_B_PORT', + 1: 'Y_G_DATA_ONTO_CB_B_PORT', + 2: 'CB_B_DATA_ONTO_CB_B_PORT', + 3: 'CR_R_DATA_ONTO_CB_B_PORT', +} +ALPHA_DATA_ONTO_CB_B_PORT = 0 +Y_G_DATA_ONTO_CB_B_PORT = 1 +CB_B_DATA_ONTO_CB_B_PORT = 2 +CR_R_DATA_ONTO_CB_B_PORT = 3 +CROSSBAR_FOR_CB_B = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_CR_R' +CROSSBAR_FOR_CR_R__enumvalues = { + 0: 'ALPHA_DATA_ONTO_CR_R_PORT', + 1: 'Y_G_DATA_ONTO_CR_R_PORT', + 2: 'CB_B_DATA_ONTO_CR_R_PORT', + 3: 'CR_R_DATA_ONTO_CR_R_PORT', +} +ALPHA_DATA_ONTO_CR_R_PORT = 0 +Y_G_DATA_ONTO_CR_R_PORT = 1 +CB_B_DATA_ONTO_CR_R_PORT = 2 +CR_R_DATA_ONTO_CR_R_PORT = 3 +CROSSBAR_FOR_CR_R = ctypes.c_uint32 # enum + +# values for enumeration 'CROSSBAR_FOR_Y_G' +CROSSBAR_FOR_Y_G__enumvalues = { + 0: 'ALPHA_DATA_ONTO_Y_G_PORT', + 1: 'Y_G_DATA_ONTO_Y_G_PORT', + 2: 'CB_B_DATA_ONTO_Y_G_PORT', + 3: 'CR_R_DATA_ONTO_Y_G_PORT', +} +ALPHA_DATA_ONTO_Y_G_PORT = 0 +Y_G_DATA_ONTO_Y_G_PORT = 1 +CB_B_DATA_ONTO_Y_G_PORT = 2 +CR_R_DATA_ONTO_Y_G_PORT = 3 +CROSSBAR_FOR_Y_G = ctypes.c_uint32 # enum + +# values for enumeration 'DETILE_BUFFER_PACKER_ENABLE' +DETILE_BUFFER_PACKER_ENABLE__enumvalues = { + 0: 'DETILE_BUFFER_PACKER_IS_DISABLE', + 1: 'DETILE_BUFFER_PACKER_IS_ENABLE', +} +DETILE_BUFFER_PACKER_IS_DISABLE = 0 +DETILE_BUFFER_PACKER_IS_ENABLE = 1 +DETILE_BUFFER_PACKER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_MODE' +MEM_PWR_DIS_MODE__enumvalues = { + 0: 'MEM_POWER_DIS_MODE_ENABLE', + 1: 'MEM_POWER_DIS_MODE_DISABLE', +} +MEM_POWER_DIS_MODE_ENABLE = 0 +MEM_POWER_DIS_MODE_DISABLE = 1 +MEM_PWR_DIS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_MODE' +MEM_PWR_FORCE_MODE__enumvalues = { + 0: 'MEM_POWER_FORCE_MODE_OFF', + 1: 'MEM_POWER_FORCE_MODE_LIGHT_SLEEP', + 2: 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', + 3: 'MEM_POWER_FORCE_MODE_SHUT_DOWN', +} +MEM_POWER_FORCE_MODE_OFF = 0 +MEM_POWER_FORCE_MODE_LIGHT_SLEEP = 1 +MEM_POWER_FORCE_MODE_DEEP_SLEEP = 2 +MEM_POWER_FORCE_MODE_SHUT_DOWN = 3 +MEM_PWR_FORCE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_STATUS' +MEM_PWR_STATUS__enumvalues = { + 0: 'MEM_POWER_STATUS_ON', + 1: 'MEM_POWER_STATUS_LIGHT_SLEEP', + 2: 'MEM_POWER_STATUS_DEEP_SLEEP', + 3: 'MEM_POWER_STATUS_SHUT_DOWN', +} +MEM_POWER_STATUS_ON = 0 +MEM_POWER_STATUS_LIGHT_SLEEP = 1 +MEM_POWER_STATUS_DEEP_SLEEP = 2 +MEM_POWER_STATUS_SHUT_DOWN = 3 +MEM_PWR_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_INT_MASK_MODE' +PIPE_INT_MASK_MODE__enumvalues = { + 0: 'PIPE_INT_MASK_MODE_DISABLE', + 1: 'PIPE_INT_MASK_MODE_ENABLE', +} +PIPE_INT_MASK_MODE_DISABLE = 0 +PIPE_INT_MASK_MODE_ENABLE = 1 +PIPE_INT_MASK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_INT_TYPE_MODE' +PIPE_INT_TYPE_MODE__enumvalues = { + 0: 'PIPE_INT_TYPE_MODE_DISABLE', + 1: 'PIPE_INT_TYPE_MODE_ENABLE', +} +PIPE_INT_TYPE_MODE_DISABLE = 0 +PIPE_INT_TYPE_MODE_ENABLE = 1 +PIPE_INT_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE' +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', +} +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CROB_MEM_PWR_LIGHT_SLEEP_MODE' +CROB_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +CROB_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +CROB_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_2X_MAGNIFY' +CURSOR_2X_MAGNIFY__enumvalues = { + 0: 'CURSOR_2X_MAGNIFY_IS_DISABLE', + 1: 'CURSOR_2X_MAGNIFY_IS_ENABLE', +} +CURSOR_2X_MAGNIFY_IS_DISABLE = 0 +CURSOR_2X_MAGNIFY_IS_ENABLE = 1 +CURSOR_2X_MAGNIFY = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_ENABLE' +CURSOR_ENABLE__enumvalues = { + 0: 'CURSOR_IS_DISABLE', + 1: 'CURSOR_IS_ENABLE', +} +CURSOR_IS_DISABLE = 0 +CURSOR_IS_ENABLE = 1 +CURSOR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_LINES_PER_CHUNK' +CURSOR_LINES_PER_CHUNK__enumvalues = { + 0: 'CURSOR_LINE_PER_CHUNK_1', + 1: 'CURSOR_LINE_PER_CHUNK_2', + 2: 'CURSOR_LINE_PER_CHUNK_4', + 3: 'CURSOR_LINE_PER_CHUNK_8', + 4: 'CURSOR_LINE_PER_CHUNK_16', +} +CURSOR_LINE_PER_CHUNK_1 = 0 +CURSOR_LINE_PER_CHUNK_2 = 1 +CURSOR_LINE_PER_CHUNK_4 = 2 +CURSOR_LINE_PER_CHUNK_8 = 3 +CURSOR_LINE_PER_CHUNK_16 = 4 +CURSOR_LINES_PER_CHUNK = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_MODE' +CURSOR_MODE__enumvalues = { + 0: 'CURSOR_MONO_2BIT', + 1: 'CURSOR_COLOR_24BIT_1BIT_AND', + 2: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 3: 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 4: 'CURSOR_COLOR_64BIT_FP_PREMULT', + 5: 'CURSOR_COLOR_64BIT_FP_UNPREMULT', +} +CURSOR_MONO_2BIT = 0 +CURSOR_COLOR_24BIT_1BIT_AND = 1 +CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT = 2 +CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT = 3 +CURSOR_COLOR_64BIT_FP_PREMULT = 4 +CURSOR_COLOR_64BIT_FP_UNPREMULT = 5 +CURSOR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_EN' +CURSOR_PERFMON_LATENCY_MEASURE_EN__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', +} +CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED = 0 +CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED = 1 +CURSOR_PERFMON_LATENCY_MEASURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PERFMON_LATENCY_MEASURE_SEL' +CURSOR_PERFMON_LATENCY_MEASURE_SEL__enumvalues = { + 0: 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 1: 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', +} +CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY = 0 +CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY = 1 +CURSOR_PERFMON_LATENCY_MEASURE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_PITCH' +CURSOR_PITCH__enumvalues = { + 0: 'CURSOR_PITCH_64_PIXELS', + 1: 'CURSOR_PITCH_128_PIXELS', + 2: 'CURSOR_PITCH_256_PIXELS', +} +CURSOR_PITCH_64_PIXELS = 0 +CURSOR_PITCH_128_PIXELS = 1 +CURSOR_PITCH_256_PIXELS = 2 +CURSOR_PITCH = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_REQ_MODE' +CURSOR_REQ_MODE__enumvalues = { + 0: 'CURSOR_REQUEST_NORMALLY', + 1: 'CURSOR_REQUEST_EARLY', +} +CURSOR_REQUEST_NORMALLY = 0 +CURSOR_REQUEST_EARLY = 1 +CURSOR_REQ_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SNOOP' +CURSOR_SNOOP__enumvalues = { + 0: 'CURSOR_IS_NOT_SNOOP', + 1: 'CURSOR_IS_SNOOP', +} +CURSOR_IS_NOT_SNOOP = 0 +CURSOR_IS_SNOOP = 1 +CURSOR_SNOOP = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_STEREO_EN' +CURSOR_STEREO_EN__enumvalues = { + 0: 'CURSOR_STEREO_IS_DISABLED', + 1: 'CURSOR_STEREO_IS_ENABLED', +} +CURSOR_STEREO_IS_DISABLED = 0 +CURSOR_STEREO_IS_ENABLED = 1 +CURSOR_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SURFACE_TMZ' +CURSOR_SURFACE_TMZ__enumvalues = { + 0: 'CURSOR_SURFACE_IS_NOT_TMZ', + 1: 'CURSOR_SURFACE_IS_TMZ', +} +CURSOR_SURFACE_IS_NOT_TMZ = 0 +CURSOR_SURFACE_IS_TMZ = 1 +CURSOR_SURFACE_TMZ = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_SYSTEM' +CURSOR_SYSTEM__enumvalues = { + 0: 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', + 1: 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', +} +CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS = 0 +CURSOR_IN_GUEST_PHYSICAL_ADDRESS = 1 +CURSOR_SYSTEM = ctypes.c_uint32 # enum + +# values for enumeration 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS' +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS__enumvalues = { + 0: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 1: 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', +} +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0 = 0 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1 = 1 +CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_DONE' +DMDATA_DONE__enumvalues = { + 0: 'DMDATA_NOT_SENT_TO_DIG', + 1: 'DMDATA_SENT_TO_DIG', +} +DMDATA_NOT_SENT_TO_DIG = 0 +DMDATA_SENT_TO_DIG = 1 +DMDATA_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_MODE' +DMDATA_MODE__enumvalues = { + 0: 'DMDATA_SOFTWARE_UPDATE_MODE', + 1: 'DMDATA_HARDWARE_UPDATE_MODE', +} +DMDATA_SOFTWARE_UPDATE_MODE = 0 +DMDATA_HARDWARE_UPDATE_MODE = 1 +DMDATA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_QOS_MODE' +DMDATA_QOS_MODE__enumvalues = { + 0: 'DMDATA_QOS_LEVEL_FROM_TTU', + 1: 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', +} +DMDATA_QOS_LEVEL_FROM_TTU = 0 +DMDATA_QOS_LEVEL_FROM_SOFTWARE = 1 +DMDATA_QOS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_REPEAT' +DMDATA_REPEAT__enumvalues = { + 0: 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', + 1: 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', +} +DMDATA_USE_FOR_CURRENT_FRAME_ONLY = 0 +DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES = 1 +DMDATA_REPEAT = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW' +DMDATA_UNDERFLOW__enumvalues = { + 0: 'DMDATA_NOT_UNDERFLOW', + 1: 'DMDATA_UNDERFLOWED', +} +DMDATA_NOT_UNDERFLOW = 0 +DMDATA_UNDERFLOWED = 1 +DMDATA_UNDERFLOW = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UNDERFLOW_CLEAR' +DMDATA_UNDERFLOW_CLEAR__enumvalues = { + 0: 'DMDATA_DONT_CLEAR', + 1: 'DMDATA_CLEAR_UNDERFLOW_STATUS', +} +DMDATA_DONT_CLEAR = 0 +DMDATA_CLEAR_UNDERFLOW_STATUS = 1 +DMDATA_UNDERFLOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'DMDATA_UPDATED' +DMDATA_UPDATED__enumvalues = { + 0: 'DMDATA_NOT_UPDATED', + 1: 'DMDATA_WAS_UPDATED', +} +DMDATA_NOT_UPDATED = 0 +DMDATA_WAS_UPDATED = 1 +DMDATA_UPDATED = ctypes.c_uint32 # enum + +# values for enumeration 'HUBP_3DLUT_ADDRESSING_MODE' +HUBP_3DLUT_ADDRESSING_MODE__enumvalues = { + 0: 'HUBP_3DLUT_SW_LINEAR', + 1: 'HUBP_3DLUT_SIMPLE_LINEAR', +} +HUBP_3DLUT_SW_LINEAR = 0 +HUBP_3DLUT_SIMPLE_LINEAR = 1 +HUBP_3DLUT_ADDRESSING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RESPONSE_STATUS' +RESPONSE_STATUS__enumvalues = { + 0: 'OKAY', + 1: 'EXOKAY', + 2: 'SLVERR', + 3: 'DECERR', + 4: 'EARLY', + 5: 'OKAY_NODATA', + 6: 'PROTVIOL', + 7: 'TRANSERR', + 8: 'CMPTO', + 12: 'CRS', +} +OKAY = 0 +EXOKAY = 1 +SLVERR = 2 +DECERR = 3 +EARLY = 4 +OKAY_NODATA = 5 +PROTVIOL = 6 +TRANSERR = 7 +CMPTO = 8 +CRS = 12 +RESPONSE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE' +DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE__enumvalues = { + 0: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 1: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 2: 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2', +} +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF = 0 +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1 = 1 +DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2 = 2 +DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_MEM_PWR_DIS_MODE' +DCHUBBUB_MEM_PWR_DIS_MODE__enumvalues = { + 0: 'DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE', + 1: 'DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE', +} +DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE = 0 +DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE = 1 +DCHUBBUB_MEM_PWR_DIS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCHUBBUB_MEM_PWR_MODE' +DCHUBBUB_MEM_PWR_MODE__enumvalues = { + 0: 'DCHUBBUB_MEM_POWER_MODE_OFF', + 1: 'DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP', + 2: 'DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP', + 3: 'DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN', +} +DCHUBBUB_MEM_POWER_MODE_OFF = 0 +DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP = 1 +DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP = 2 +DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN = 3 +DCHUBBUB_MEM_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_3DLUT_FL_FORMAT' +MPC_CFG_3DLUT_FL_FORMAT__enumvalues = { + 0: 'MPC_CFG_3DLUT_FL_FORMAT_0', + 1: 'MPC_CFG_3DLUT_FL_FORMAT_1', + 2: 'MPC_CFG_3DLUT_FL_FORMAT_2', +} +MPC_CFG_3DLUT_FL_FORMAT_0 = 0 +MPC_CFG_3DLUT_FL_FORMAT_1 = 1 +MPC_CFG_3DLUT_FL_FORMAT_2 = 2 +MPC_CFG_3DLUT_FL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_3DLUT_FL_MODE' +MPC_CFG_3DLUT_FL_MODE__enumvalues = { + 0: 'MPC_CFG_3DLUT_FL_MODE_0', + 1: 'MPC_CFG_3DLUT_FL_MODE_1', + 2: 'MPC_CFG_3DLUT_FL_MODE_2', + 3: 'MPC_CFG_3DLUT_FL_MODE_3', +} +MPC_CFG_3DLUT_FL_MODE_0 = 0 +MPC_CFG_3DLUT_FL_MODE_1 = 1 +MPC_CFG_3DLUT_FL_MODE_2 = 2 +MPC_CFG_3DLUT_FL_MODE_3 = 3 +MPC_CFG_3DLUT_FL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET' +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_ADR_VUPDATE_LOCK_SET' +MPC_CFG_ADR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_ADR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CFG_VUPDATE_LOCK_SET' +MPC_CFG_CFG_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CFG_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_CUR_VUPDATE_LOCK_SET' +MPC_CFG_CUR_VUPDATE_LOCK_SET__enumvalues = { + 0: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 1: 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', +} +MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE = 0 +MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE = 1 +MPC_CFG_CUR_VUPDATE_LOCK_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_MPC_TEST_CLK_SEL' +MPC_CFG_MPC_TEST_CLK_SEL__enumvalues = { + 0: 'MPC_CFG_MPC_TEST_CLK_SEL_0', + 1: 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 2: 'MPC_CFG_MPC_TEST_CLK_SEL_2', + 3: 'MPC_CFG_MPC_TEST_CLK_SEL_3', +} +MPC_CFG_MPC_TEST_CLK_SEL_0 = 0 +MPC_CFG_MPC_TEST_CLK_SEL_1 = 1 +MPC_CFG_MPC_TEST_CLK_SEL_2 = 2 +MPC_CFG_MPC_TEST_CLK_SEL_3 = 3 +MPC_CFG_MPC_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN' +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE', +} +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_INTERLACE_MODE' +MPC_CRC_CALC_INTERLACE_MODE__enumvalues = { + 0: 'MPC_CRC_INTERLACE_MODE_TOP', + 1: 'MPC_CRC_INTERLACE_MODE_BOTTOM', + 2: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 3: 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', +} +MPC_CRC_INTERLACE_MODE_TOP = 0 +MPC_CRC_INTERLACE_MODE_BOTTOM = 1 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM = 2 +MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_MODE' +MPC_CRC_CALC_MODE__enumvalues = { + 0: 'MPC_CRC_ONE_SHOT_MODE', + 1: 'MPC_CRC_CONTINUOUS_MODE', +} +MPC_CRC_ONE_SHOT_MODE = 0 +MPC_CRC_CONTINUOUS_MODE = 1 +MPC_CRC_CALC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_CALC_STEREO_MODE' +MPC_CRC_CALC_STEREO_MODE__enumvalues = { + 0: 'MPC_CRC_STEREO_MODE_LEFT', + 1: 'MPC_CRC_STEREO_MODE_RIGHT', + 2: 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 3: 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', +} +MPC_CRC_STEREO_MODE_LEFT = 0 +MPC_CRC_STEREO_MODE_RIGHT = 1 +MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT = 2 +MPC_CRC_STEREO_MODE_BOTH_RESET_EACH = 3 +MPC_CRC_CALC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_CRC_SOURCE_SELECT' +MPC_CRC_SOURCE_SELECT__enumvalues = { + 0: 'MPC_CRC_SOURCE_SEL_DPP', + 1: 'MPC_CRC_SOURCE_SEL_OPP', + 2: 'MPC_CRC_SOURCE_SEL_DWB', + 3: 'MPC_CRC_SOURCE_SEL_OTHER', +} +MPC_CRC_SOURCE_SEL_DPP = 0 +MPC_CRC_SOURCE_SEL_OPP = 1 +MPC_CRC_SOURCE_SEL_DWB = 2 +MPC_CRC_SOURCE_SEL_OTHER = 3 +MPC_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OCSC_COEF_FORMAT' +MPC_OCSC_COEF_FORMAT__enumvalues = { + 0: 'MPC_OCSC_COEF_FORMAT_S2_13', + 1: 'MPC_OCSC_COEF_FORMAT_S3_12', +} +MPC_OCSC_COEF_FORMAT_S2_13 = 0 +MPC_OCSC_COEF_FORMAT_S3_12 = 1 +MPC_OCSC_COEF_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN' +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE', +} +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_CSC_MODE' +MPC_OUT_CSC_MODE__enumvalues = { + 0: 'MPC_OUT_CSC_MODE_0', + 1: 'MPC_OUT_CSC_MODE_1', + 2: 'MPC_OUT_CSC_MODE_2', + 3: 'MPC_OUT_CSC_MODE_RSV', +} +MPC_OUT_CSC_MODE_0 = 0 +MPC_OUT_CSC_MODE_1 = 1 +MPC_OUT_CSC_MODE_2 = 2 +MPC_OUT_CSC_MODE_RSV = 3 +MPC_OUT_CSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE' +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE__enumvalues = { + 0: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 1: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 2: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 3: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 4: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 5: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 6: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 7: 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', +} +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS = 0 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS = 1 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS = 2 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS = 3 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS = 4 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS = 5 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS = 6 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH = 7 +MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPC_OUT_RATE_CONTROL_DISABLE_SET' +MPC_OUT_RATE_CONTROL_DISABLE_SET__enumvalues = { + 0: 'MPC_OUT_RATE_CONTROL_SET_ENABLE', + 1: 'MPC_OUT_RATE_CONTROL_SET_DISABLE', +} +MPC_OUT_RATE_CONTROL_SET_ENABLE = 0 +MPC_OUT_RATE_CONTROL_SET_DISABLE = 1 +MPC_OUT_RATE_CONTROL_DISABLE_SET = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_BG_COLOR_BPC' +MPCC_BG_COLOR_BPC__enumvalues = { + 0: 'MPCC_BG_COLOR_BPC_8bit', + 1: 'MPCC_BG_COLOR_BPC_9bit', + 2: 'MPCC_BG_COLOR_BPC_10bit', + 3: 'MPCC_BG_COLOR_BPC_11bit', + 4: 'MPCC_BG_COLOR_BPC_12bit', +} +MPCC_BG_COLOR_BPC_8bit = 0 +MPCC_BG_COLOR_BPC_9bit = 1 +MPCC_BG_COLOR_BPC_10bit = 2 +MPCC_BG_COLOR_BPC_11bit = 3 +MPCC_BG_COLOR_BPC_12bit = 4 +MPCC_BG_COLOR_BPC = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY' +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 1: 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', +} +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE = 0 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE = 1 +MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE' +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 1: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 2: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 3: 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', +} +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA = 0 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN = 1 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA = 2 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED = 3 +MPCC_CONTROL_MPCC_ALPHA_BLND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE' +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 1: 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', +} +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE = 0 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE = 1 +MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE' +MPCC_CONTROL_MPCC_BOT_GAIN_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 1: 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', +} +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0 = 0 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1 = 1 +MPCC_CONTROL_MPCC_BOT_GAIN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_CONTROL_MPCC_MODE' +MPCC_CONTROL_MPCC_MODE__enumvalues = { + 0: 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 1: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 2: 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 3: 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', +} +MPCC_CONTROL_MPCC_MODE_BYPASS = 0 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH = 1 +MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY = 2 +MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING = 3 +MPCC_CONTROL_MPCC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_EN' +MPCC_SM_CONTROL_MPCC_SM_EN__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_EN_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_EN_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT' +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL' +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 2: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 3: 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', +} +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE = 0 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED = 1 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW = 2 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH = 3 +MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT' +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 1: 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', +} +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE = 0 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE = 1 +MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_SM_CONTROL_MPCC_SM_MODE' +MPCC_SM_CONTROL_MPCC_SM_MODE__enumvalues = { + 0: 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 2: 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 4: 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 6: 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', +} +MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE = 0 +MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING = 2 +MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING = 4 +MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING = 6 +MPCC_SM_CONTROL_MPCC_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM' +MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM__enumvalues = { + 0: 'MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13', + 1: 'MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12', +} +MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13 = 0 +MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12 = 1 +MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_GAMUT_REMAP_MODE_ENUM' +MPCC_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'MPCC_GAMUT_REMAP_MODE_0', + 1: 'MPCC_GAMUT_REMAP_MODE_1', + 2: 'MPCC_GAMUT_REMAP_MODE_2', + 3: 'MPCC_GAMUT_REMAP_MODE_RSV', +} +MPCC_GAMUT_REMAP_MODE_0 = 0 +MPCC_GAMUT_REMAP_MODE_1 = 1 +MPCC_GAMUT_REMAP_MODE_2 = 2 +MPCC_GAMUT_REMAP_MODE_RSV = 3 +MPCC_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_2_CONFIG_ENUM' +MPCC_OGAM_LUT_2_CONFIG_ENUM__enumvalues = { + 0: 'MPCC_OGAM_LUT_2CFG_NO_MEMORY', + 1: 'MPCC_OGAM_LUT_2CFG_MEMORY_A', + 2: 'MPCC_OGAM_LUT_2CFG_MEMORY_B', +} +MPCC_OGAM_LUT_2CFG_NO_MEMORY = 0 +MPCC_OGAM_LUT_2CFG_MEMORY_A = 1 +MPCC_OGAM_LUT_2CFG_MEMORY_B = 2 +MPCC_OGAM_LUT_2_CONFIG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_CONFIG_MODE' +MPCC_OGAM_LUT_CONFIG_MODE__enumvalues = { + 0: 'MPCC_OGAM_DIFFERENT_RGB', + 1: 'MPCC_OGAM_ALL_USE_R', +} +MPCC_OGAM_DIFFERENT_RGB = 0 +MPCC_OGAM_ALL_USE_R = 1 +MPCC_OGAM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_PWL_DISABLE_ENUM' +MPCC_OGAM_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'MPCC_OGAM_ENABLE_PWL', + 1: 'MPCC_OGAM_DISABLE_PWL', +} +MPCC_OGAM_ENABLE_PWL = 0 +MPCC_OGAM_DISABLE_PWL = 1 +MPCC_OGAM_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL' +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 1: 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', +} +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA = 0 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB = 1 +MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_RAM_SEL' +MPCC_OGAM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_OGAM_RAMA_ACCESS', + 1: 'MPCC_OGAM_RAMB_ACCESS', +} +MPCC_OGAM_RAMA_ACCESS = 0 +MPCC_OGAM_RAMB_ACCESS = 1 +MPCC_OGAM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_READ_COLOR_SEL' +MPCC_OGAM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'MPCC_OGAM_BLUE_LUT', + 1: 'MPCC_OGAM_GREEN_LUT', + 2: 'MPCC_OGAM_RED_LUT', +} +MPCC_OGAM_BLUE_LUT = 0 +MPCC_OGAM_GREEN_LUT = 1 +MPCC_OGAM_RED_LUT = 2 +MPCC_OGAM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_READ_DBG' +MPCC_OGAM_LUT_READ_DBG__enumvalues = { + 0: 'MPCC_OGAM_DISABLE_DEBUG', + 1: 'MPCC_OGAM_ENABLE_DEBUG', +} +MPCC_OGAM_DISABLE_DEBUG = 0 +MPCC_OGAM_ENABLE_DEBUG = 1 +MPCC_OGAM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_LUT_SEL_ENUM' +MPCC_OGAM_LUT_SEL_ENUM__enumvalues = { + 0: 'MPCC_OGAM_RAMA', + 1: 'MPCC_OGAM_RAMB', +} +MPCC_OGAM_RAMA = 0 +MPCC_OGAM_RAMB = 1 +MPCC_OGAM_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM' +MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM__enumvalues = { + 0: 'MPCC_OGAM_MODE_0', + 1: 'MPCC_OGAM_MODE_RSV1', + 2: 'MPCC_OGAM_MODE_2', + 3: 'MPCC_OGAM_MODE_RSV', +} +MPCC_OGAM_MODE_0 = 0 +MPCC_OGAM_MODE_RSV1 = 1 +MPCC_OGAM_MODE_2 = 2 +MPCC_OGAM_MODE_RSV = 3 +MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_NUM_SEG' +MPCC_OGAM_NUM_SEG__enumvalues = { + 0: 'MPCC_OGAM_SEGMENTS_1', + 1: 'MPCC_OGAM_SEGMENTS_2', + 2: 'MPCC_OGAM_SEGMENTS_4', + 3: 'MPCC_OGAM_SEGMENTS_8', + 4: 'MPCC_OGAM_SEGMENTS_16', + 5: 'MPCC_OGAM_SEGMENTS_32', + 6: 'MPCC_OGAM_SEGMENTS_64', + 7: 'MPCC_OGAM_SEGMENTS_128', +} +MPCC_OGAM_SEGMENTS_1 = 0 +MPCC_OGAM_SEGMENTS_2 = 1 +MPCC_OGAM_SEGMENTS_4 = 2 +MPCC_OGAM_SEGMENTS_8 = 3 +MPCC_OGAM_SEGMENTS_16 = 4 +MPCC_OGAM_SEGMENTS_32 = 5 +MPCC_OGAM_SEGMENTS_64 = 6 +MPCC_OGAM_SEGMENTS_128 = 7 +MPCC_OGAM_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN' +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE', +} +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE = 0 +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE = 1 +MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_30BIT_ENUM' +MPCC_MCM_3DLUT_30BIT_ENUM__enumvalues = { + 0: 'MPCC_MCM_3DLUT_36BIT', + 1: 'MPCC_MCM_3DLUT_30BIT', +} +MPCC_MCM_3DLUT_36BIT = 0 +MPCC_MCM_3DLUT_30BIT = 1 +MPCC_MCM_3DLUT_30BIT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_RAM_SEL' +MPCC_MCM_3DLUT_RAM_SEL__enumvalues = { + 0: 'MPCC_MCM_RAM0_ACCESS', + 1: 'MPCC_MCM_RAM1_ACCESS', + 2: 'MPCC_MCM_RAM2_ACCESS', + 3: 'MPCC_MCM_RAM3_ACCESS', +} +MPCC_MCM_RAM0_ACCESS = 0 +MPCC_MCM_RAM1_ACCESS = 1 +MPCC_MCM_RAM2_ACCESS = 2 +MPCC_MCM_RAM3_ACCESS = 3 +MPCC_MCM_3DLUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_3DLUT_SIZE_ENUM' +MPCC_MCM_3DLUT_SIZE_ENUM__enumvalues = { + 0: 'MPCC_MCM_3DLUT_17CUBE', + 1: 'MPCC_MCM_3DLUT_9CUBE', +} +MPCC_MCM_3DLUT_17CUBE = 0 +MPCC_MCM_3DLUT_9CUBE = 1 +MPCC_MCM_3DLUT_SIZE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_MODE_ENUM' +MPCC_MCM_GAMMA_LUT_MODE_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_BYPASS', + 1: 'MPCC_MCM_GAMMA_LUT_RESERVED_1', + 2: 'MPCC_MCM_GAMMA_LUT_RAM_LUT', + 3: 'MPCC_MCM_GAMMA_LUT_RESERVED_3', +} +MPCC_MCM_GAMMA_LUT_BYPASS = 0 +MPCC_MCM_GAMMA_LUT_RESERVED_1 = 1 +MPCC_MCM_GAMMA_LUT_RAM_LUT = 2 +MPCC_MCM_GAMMA_LUT_RESERVED_3 = 3 +MPCC_MCM_GAMMA_LUT_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM' +MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_ENABLE_PWL', + 1: 'MPCC_MCM_GAMMA_LUT_DISABLE_PWL', +} +MPCC_MCM_GAMMA_LUT_ENABLE_PWL = 0 +MPCC_MCM_GAMMA_LUT_DISABLE_PWL = 1 +MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMMA_LUT_SEL_ENUM' +MPCC_MCM_GAMMA_LUT_SEL_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMMA_LUT_RAMA', + 1: 'MPCC_MCM_GAMMA_LUT_RAMB', +} +MPCC_MCM_GAMMA_LUT_RAMA = 0 +MPCC_MCM_GAMMA_LUT_RAMB = 1 +MPCC_MCM_GAMMA_LUT_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_ENUM' +MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S2_13', + 1: 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S3_12', +} +MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S2_13 = 0 +MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S3_12 = 1 +MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_GAMUT_REMAP_MODE_ENUM' +MPCC_MCM_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'MPCC_MCM_GAMUT_REMAP_MODE_0', + 1: 'MPCC_MCM_GAMUT_REMAP_MODE_1', + 2: 'MPCC_MCM_GAMUT_REMAP_MODE_2', + 3: 'MPCC_MCM_GAMUT_REMAP_MODE_RSV', +} +MPCC_MCM_GAMUT_REMAP_MODE_0 = 0 +MPCC_MCM_GAMUT_REMAP_MODE_1 = 1 +MPCC_MCM_GAMUT_REMAP_MODE_2 = 2 +MPCC_MCM_GAMUT_REMAP_MODE_RSV = 3 +MPCC_MCM_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_2_MODE_ENUM' +MPCC_MCM_LUT_2_MODE_ENUM__enumvalues = { + 0: 'MPCC_MCM_LUT_2_MODE_BYPASS', + 1: 'MPCC_MCM_LUT_2_MODE_RAMA_LUT', + 2: 'MPCC_MCM_LUT_2_MODE_RAMB_LUT', +} +MPCC_MCM_LUT_2_MODE_BYPASS = 0 +MPCC_MCM_LUT_2_MODE_RAMA_LUT = 1 +MPCC_MCM_LUT_2_MODE_RAMB_LUT = 2 +MPCC_MCM_LUT_2_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_CONFIG_MODE' +MPCC_MCM_LUT_CONFIG_MODE__enumvalues = { + 0: 'MPCC_MCM_LUT_DIFFERENT_RGB', + 1: 'MPCC_MCM_LUT_ALL_USE_R', +} +MPCC_MCM_LUT_DIFFERENT_RGB = 0 +MPCC_MCM_LUT_ALL_USE_R = 1 +MPCC_MCM_LUT_CONFIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_NUM_SEG' +MPCC_MCM_LUT_NUM_SEG__enumvalues = { + 0: 'MPCC_MCM_LUT_SEGMENTS_1', + 1: 'MPCC_MCM_LUT_SEGMENTS_2', + 2: 'MPCC_MCM_LUT_SEGMENTS_4', + 3: 'MPCC_MCM_LUT_SEGMENTS_8', + 4: 'MPCC_MCM_LUT_SEGMENTS_16', + 5: 'MPCC_MCM_LUT_SEGMENTS_32', + 6: 'MPCC_MCM_LUT_SEGMENTS_64', + 7: 'MPCC_MCM_LUT_SEGMENTS_128', +} +MPCC_MCM_LUT_SEGMENTS_1 = 0 +MPCC_MCM_LUT_SEGMENTS_2 = 1 +MPCC_MCM_LUT_SEGMENTS_4 = 2 +MPCC_MCM_LUT_SEGMENTS_8 = 3 +MPCC_MCM_LUT_SEGMENTS_16 = 4 +MPCC_MCM_LUT_SEGMENTS_32 = 5 +MPCC_MCM_LUT_SEGMENTS_64 = 6 +MPCC_MCM_LUT_SEGMENTS_128 = 7 +MPCC_MCM_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_RAM_SEL' +MPCC_MCM_LUT_RAM_SEL__enumvalues = { + 0: 'MPCC_MCM_LUT_RAMA_ACCESS', + 1: 'MPCC_MCM_LUT_RAMB_ACCESS', +} +MPCC_MCM_LUT_RAMA_ACCESS = 0 +MPCC_MCM_LUT_RAMB_ACCESS = 1 +MPCC_MCM_LUT_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_READ_COLOR_SEL' +MPCC_MCM_LUT_READ_COLOR_SEL__enumvalues = { + 0: 'MPCC_MCM_LUT_BLUE_LUT', + 1: 'MPCC_MCM_LUT_GREEN_LUT', + 2: 'MPCC_MCM_LUT_RED_LUT', +} +MPCC_MCM_LUT_BLUE_LUT = 0 +MPCC_MCM_LUT_GREEN_LUT = 1 +MPCC_MCM_LUT_RED_LUT = 2 +MPCC_MCM_LUT_READ_COLOR_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_LUT_READ_DBG' +MPCC_MCM_LUT_READ_DBG__enumvalues = { + 0: 'MPCC_MCM_LUT_DISABLE_DEBUG', + 1: 'MPCC_MCM_LUT_ENABLE_DEBUG', +} +MPCC_MCM_LUT_DISABLE_DEBUG = 0 +MPCC_MCM_LUT_ENABLE_DEBUG = 1 +MPCC_MCM_LUT_READ_DBG = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_MEM_PWR_FORCE_ENUM' +MPCC_MCM_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'MPCC_MCM_MEM_PWR_FORCE_DIS', + 1: 'MPCC_MCM_MEM_PWR_FORCE_LS', + 2: 'MPCC_MCM_MEM_PWR_FORCE_DS', + 3: 'MPCC_MCM_MEM_PWR_FORCE_SD', +} +MPCC_MCM_MEM_PWR_FORCE_DIS = 0 +MPCC_MCM_MEM_PWR_FORCE_LS = 1 +MPCC_MCM_MEM_PWR_FORCE_DS = 2 +MPCC_MCM_MEM_PWR_FORCE_SD = 3 +MPCC_MCM_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'MPCC_MCM_MEM_PWR_STATE_ENUM' +MPCC_MCM_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'MPCC_MCM_MEM_PWR_STATE_ON', + 1: 'MPCC_MCM_MEM_PWR_STATE_LS', + 2: 'MPCC_MCM_MEM_PWR_STATE_DS', + 3: 'MPCC_MCM_MEM_PWR_STATE_SD', +} +MPCC_MCM_MEM_PWR_STATE_ON = 0 +MPCC_MCM_MEM_PWR_STATE_LS = 1 +MPCC_MCM_MEM_PWR_STATE_DS = 2 +MPCC_MCM_MEM_PWR_STATE_SD = 3 +MPCC_MCM_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_BIT_DEPTH' +ENUM_DPG_BIT_DEPTH__enumvalues = { + 0: 'ENUM_DPG_BIT_DEPTH_6BPC', + 1: 'ENUM_DPG_BIT_DEPTH_8BPC', + 2: 'ENUM_DPG_BIT_DEPTH_10BPC', + 3: 'ENUM_DPG_BIT_DEPTH_12BPC', +} +ENUM_DPG_BIT_DEPTH_6BPC = 0 +ENUM_DPG_BIT_DEPTH_8BPC = 1 +ENUM_DPG_BIT_DEPTH_10BPC = 2 +ENUM_DPG_BIT_DEPTH_12BPC = 3 +ENUM_DPG_BIT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_DYNAMIC_RANGE' +ENUM_DPG_DYNAMIC_RANGE__enumvalues = { + 0: 'ENUM_DPG_DYNAMIC_RANGE_VESA', + 1: 'ENUM_DPG_DYNAMIC_RANGE_CEA', +} +ENUM_DPG_DYNAMIC_RANGE_VESA = 0 +ENUM_DPG_DYNAMIC_RANGE_CEA = 1 +ENUM_DPG_DYNAMIC_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_EN' +ENUM_DPG_EN__enumvalues = { + 0: 'ENUM_DPG_DISABLE', + 1: 'ENUM_DPG_ENABLE', +} +ENUM_DPG_DISABLE = 0 +ENUM_DPG_ENABLE = 1 +ENUM_DPG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_FIELD_POLARITY' +ENUM_DPG_FIELD_POLARITY__enumvalues = { + 0: 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 1: 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', +} +ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD = 0 +ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN = 1 +ENUM_DPG_FIELD_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DPG_MODE' +ENUM_DPG_MODE__enumvalues = { + 0: 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 1: 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 2: 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 3: 'ENUM_DPG_MODE_VERTICAL_BAR', + 4: 'ENUM_DPG_MODE_HORIZONTAL_BAR', + 5: 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 6: 'ENUM_DPG_MODE_RGB_DUAL_RAMP', + 7: 'ENUM_DPG_MODE_RGB_XR_BIAS', +} +ENUM_DPG_MODE_RGB_COLOUR_BLOCK = 0 +ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK = 1 +ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK = 2 +ENUM_DPG_MODE_VERTICAL_BAR = 3 +ENUM_DPG_MODE_HORIZONTAL_BAR = 4 +ENUM_DPG_MODE_RGB_SINGLE_RAMP = 5 +ENUM_DPG_MODE_RGB_DUAL_RAMP = 6 +ENUM_DPG_MODE_RGB_XR_BIAS = 7 +ENUM_DPG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_DIS_CTRL' +FMTMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 1: 'FMTMEM_DISABLE_MEM_PWR_CTRL', +} +FMTMEM_ENABLE_MEM_PWR_CTRL = 0 +FMTMEM_DISABLE_MEM_PWR_CTRL = 1 +FMTMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMTMEM_PWR_FORCE_CTRL' +FMTMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'FMTMEM_NO_FORCE_REQUEST', + 1: 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', +} +FMTMEM_NO_FORCE_REQUEST = 0 +FMTMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +FMTMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +FMTMEM_FORCE_SHUT_DOWN_REQUEST = 3 +FMTMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL' +FMT_BIT_DEPTH_CONTROL_25FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 1: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 2: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 3: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei = 0 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi = 1 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi = 2 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL' +FMT_BIT_DEPTH_CONTROL_50FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 1: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 2: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 3: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', +} +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A = 0 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B = 1 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C = 2 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D = 3 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL' +FMT_BIT_DEPTH_CONTROL_75FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 1: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 2: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 3: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E = 0 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F = 1 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G = 2 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2 = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4 = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CLAMP_CNTL_COLOR_FORMAT' +FMT_CLAMP_CNTL_COLOR_FORMAT__enumvalues = { + 0: 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 1: 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 2: 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 3: 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 4: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 5: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 6: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 7: 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', +} +FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC = 0 +FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC = 1 +FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC = 2 +FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC = 3 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1 = 4 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2 = 5 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3 = 6 +FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE = 7 +FMT_CLAMP_CNTL_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS' +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS__enumvalues = { + 0: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 1: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', +} +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE = 0 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE = 1 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_PIXEL_ENCODING' +FMT_CONTROL_PIXEL_ENCODING__enumvalues = { + 0: 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 1: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 2: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 3: 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', +} +FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444 = 0 +FMT_CONTROL_PIXEL_ENCODING_YCBCR422 = 1 +FMT_CONTROL_PIXEL_ENCODING_YCBCR420 = 2 +FMT_CONTROL_PIXEL_ENCODING_RESERVED = 3 +FMT_CONTROL_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_MODE' +FMT_CONTROL_SUBSAMPLING_MODE__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 1: 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 2: 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 3: 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', +} +FMT_CONTROL_SUBSAMPLING_MODE_DROP = 0 +FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE = 1 +FMT_CONTROL_SUBSAMPLING_MOME_3_TAP = 2 +FMT_CONTROL_SUBSAMPLING_MOME_RESERVED = 3 +FMT_CONTROL_SUBSAMPLING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_ORDER' +FMT_CONTROL_SUBSAMPLING_ORDER__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 1: 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', +} +FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR = 0 +FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB = 1 +FMT_CONTROL_SUBSAMPLING_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DEBUG_CNTL_COLOR_SELECT' +FMT_DEBUG_CNTL_COLOR_SELECT__enumvalues = { + 0: 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 1: 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 2: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 3: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', +} +FMT_DEBUG_CNTL_COLOR_SELECT_BLUE = 0 +FMT_DEBUG_CNTL_COLOR_SELECT_GREEN = 1 +FMT_DEBUG_CNTL_COLOR_SELECT_RED1 = 2 +FMT_DEBUG_CNTL_COLOR_SELECT_RED2 = 3 +FMT_DEBUG_CNTL_COLOR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DYNAMIC_EXP_MODE' +FMT_DYNAMIC_EXP_MODE__enumvalues = { + 0: 'FMT_DYNAMIC_EXP_MODE_10to12', + 1: 'FMT_DYNAMIC_EXP_MODE_8to12', +} +FMT_DYNAMIC_EXP_MODE_10to12 = 0 +FMT_DYNAMIC_EXP_MODE_8to12 = 1 +FMT_DYNAMIC_EXP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_FRAME_RANDOM_ENABLE_CONTROL' +FMT_FRAME_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 1: 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', +} +FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME = 0 +FMT_FRAME_RANDOM_ENABLE_RESET_ONCE = 1 +FMT_FRAME_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_POWER_STATE_ENUM' +FMT_POWER_STATE_ENUM__enumvalues = { + 0: 'FMT_POWER_STATE_ENUM_ON', + 1: 'FMT_POWER_STATE_ENUM_LS', + 2: 'FMT_POWER_STATE_ENUM_DS', + 3: 'FMT_POWER_STATE_ENUM_SD', +} +FMT_POWER_STATE_ENUM_ON = 0 +FMT_POWER_STATE_ENUM_LS = 1 +FMT_POWER_STATE_ENUM_DS = 2 +FMT_POWER_STATE_ENUM_SD = 3 +FMT_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_RGB_RANDOM_ENABLE_CONTROL' +FMT_RGB_RANDOM_ENABLE_CONTROL__enumvalues = { + 0: 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 1: 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', +} +FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE = 0 +FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE = 1 +FMT_RGB_RANDOM_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL' +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 1: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 2: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 3: 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', +} +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP = 0 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1 = 1 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2 = 2 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED = 3 +FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_MODE' +FMT_SPATIAL_DITHER_MODE__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_MODE_0', + 1: 'FMT_SPATIAL_DITHER_MODE_1', + 2: 'FMT_SPATIAL_DITHER_MODE_2', + 3: 'FMT_SPATIAL_DITHER_MODE_3', +} +FMT_SPATIAL_DITHER_MODE_0 = 0 +FMT_SPATIAL_DITHER_MODE_1 = 1 +FMT_SPATIAL_DITHER_MODE_2 = 2 +FMT_SPATIAL_DITHER_MODE_3 = 3 +FMT_SPATIAL_DITHER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_STEREOSYNC_OVERRIDE_CONTROL' +FMT_STEREOSYNC_OVERRIDE_CONTROL__enumvalues = { + 0: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 1: 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', +} +FMT_STEREOSYNC_OVERRIDE_CONTROL_0 = 0 +FMT_STEREOSYNC_OVERRIDE_CONTROL_1 = 1 +FMT_STEREOSYNC_OVERRIDE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0' +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0__enumvalues = { + 0: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 1: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', +} +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR = 0 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB = 1 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0 = ctypes.c_uint32 # enum + +# values for enumeration 'OPPBUF_DISPLAY_SEGMENTATION' +OPPBUF_DISPLAY_SEGMENTATION__enumvalues = { + 0: 'OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT', + 1: 'OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT', + 2: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT', + 3: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT', + 4: 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT', +} +OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT = 0 +OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT = 1 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT = 2 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT = 3 +OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT = 4 +OPPBUF_DISPLAY_SEGMENTATION = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CLOCK_ENABLE_CONTROL' +OPP_PIPE_CLOCK_ENABLE_CONTROL__enumvalues = { + 0: 'OPP_PIPE_CLOCK_DISABLE', + 1: 'OPP_PIPE_CLOCK_ENABLE', +} +OPP_PIPE_CLOCK_DISABLE = 0 +OPP_PIPE_CLOCK_ENABLE = 1 +OPP_PIPE_CLOCK_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL' +OPP_PIPE_DIGTIAL_BYPASS_CONTROL__enumvalues = { + 0: 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 1: 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', +} +OPP_PIPE_DIGTIAL_BYPASS_DISABLE = 0 +OPP_PIPE_DIGTIAL_BYPASS_ENABLE = 1 +OPP_PIPE_DIGTIAL_BYPASS_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_CONT_EN' +OPP_PIPE_CRC_CONT_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_MODE_ONE_SHOT', + 1: 'OPP_PIPE_CRC_MODE_CONTINUOUS', +} +OPP_PIPE_CRC_MODE_ONE_SHOT = 0 +OPP_PIPE_CRC_MODE_CONTINUOUS = 1 +OPP_PIPE_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_EN' +OPP_PIPE_CRC_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_DISABLE', + 1: 'OPP_PIPE_CRC_ENABLE', +} +OPP_PIPE_CRC_DISABLE = 0 +OPP_PIPE_CRC_ENABLE = 1 +OPP_PIPE_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_EN' +OPP_PIPE_CRC_INTERLACE_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 1: 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', +} +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE = 0 +OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED = 1 +OPP_PIPE_CRC_INTERLACE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_INTERLACE_MODE' +OPP_PIPE_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', + 1: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 3: 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', +} +OPP_PIPE_CRC_INTERLACE_MODE_TOP = 0 +OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM = 1 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD = 2 +OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD = 3 +OPP_PIPE_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_ONE_SHOT_PENDING' +OPP_PIPE_CRC_ONE_SHOT_PENDING__enumvalues = { + 0: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 1: 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', +} +OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING = 0 +OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING = 1 +OPP_PIPE_CRC_ONE_SHOT_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_PIXEL_SELECT' +OPP_PIPE_CRC_PIXEL_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 1: 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 2: 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 3: 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', +} +OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS = 0 +OPP_PIPE_CRC_PIXEL_SELECT_RESERVED = 1 +OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS = 2 +OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS = 3 +OPP_PIPE_CRC_PIXEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_SOURCE_SELECT' +OPP_PIPE_CRC_SOURCE_SELECT__enumvalues = { + 0: 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 1: 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', +} +OPP_PIPE_CRC_SOURCE_SELECT_FMT = 0 +OPP_PIPE_CRC_SOURCE_SELECT_SFT = 1 +OPP_PIPE_CRC_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_EN' +OPP_PIPE_CRC_STEREO_EN__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 1: 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', +} +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO = 0 +OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO = 1 +OPP_PIPE_CRC_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_PIPE_CRC_STEREO_MODE' +OPP_PIPE_CRC_STEREO_MODE__enumvalues = { + 0: 'OPP_PIPE_CRC_STEREO_MODE_LEFT', + 1: 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 2: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 3: 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', +} +OPP_PIPE_CRC_STEREO_MODE_LEFT = 0 +OPP_PIPE_CRC_STEREO_MODE_RIGHT = 1 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE = 2 +OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE = 3 +OPP_PIPE_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TEST_CLK_SEL_CONTROL' +OPP_TEST_CLK_SEL_CONTROL__enumvalues = { + 0: 'OPP_TEST_CLK_SEL_DISPCLK_P', + 1: 'OPP_TEST_CLK_SEL_DISPCLK_R', + 2: 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', + 3: 'OPP_TEST_CLK_SEL_DISPCLK_ABM1', + 4: 'OPP_TEST_CLK_SEL_DISPCLK_ABM2', + 5: 'OPP_TEST_CLK_SEL_DISPCLK_ABM3', + 6: 'OPP_TEST_CLK_SEL_RESERVED0', + 7: 'OPP_TEST_CLK_SEL_RESERVED1', + 8: 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', + 9: 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', + 10: 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', + 11: 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', + 12: 'OPP_TEST_CLK_SEL_RESERVED2', + 13: 'OPP_TEST_CLK_SEL_RESERVED3', +} +OPP_TEST_CLK_SEL_DISPCLK_P = 0 +OPP_TEST_CLK_SEL_DISPCLK_R = 1 +OPP_TEST_CLK_SEL_DISPCLK_ABM0 = 2 +OPP_TEST_CLK_SEL_DISPCLK_ABM1 = 3 +OPP_TEST_CLK_SEL_DISPCLK_ABM2 = 4 +OPP_TEST_CLK_SEL_DISPCLK_ABM3 = 5 +OPP_TEST_CLK_SEL_RESERVED0 = 6 +OPP_TEST_CLK_SEL_RESERVED1 = 7 +OPP_TEST_CLK_SEL_DISPCLK_OPP0 = 8 +OPP_TEST_CLK_SEL_DISPCLK_OPP1 = 9 +OPP_TEST_CLK_SEL_DISPCLK_OPP2 = 10 +OPP_TEST_CLK_SEL_DISPCLK_OPP3 = 11 +OPP_TEST_CLK_SEL_RESERVED2 = 12 +OPP_TEST_CLK_SEL_RESERVED3 = 13 +OPP_TEST_CLK_SEL_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_ENABLE_STATUS' +OPP_TOP_CLOCK_ENABLE_STATUS__enumvalues = { + 0: 'OPP_TOP_CLOCK_DISABLED_STATUS', + 1: 'OPP_TOP_CLOCK_ENABLED_STATUS', +} +OPP_TOP_CLOCK_DISABLED_STATUS = 0 +OPP_TOP_CLOCK_ENABLED_STATUS = 1 +OPP_TOP_CLOCK_ENABLE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OPP_TOP_CLOCK_GATING_CONTROL' +OPP_TOP_CLOCK_GATING_CONTROL__enumvalues = { + 0: 'OPP_TOP_CLOCK_GATING_ENABLED', + 1: 'OPP_TOP_CLOCK_GATING_DISABLED', +} +OPP_TOP_CLOCK_GATING_ENABLED = 0 +OPP_TOP_CLOCK_GATING_DISABLED = 1 +OPP_TOP_CLOCK_GATING_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK' +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_SEL' +MASTER_UPDATE_LOCK_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_SEL_0', + 1: 'MASTER_UPDATE_LOCK_SEL_1', + 2: 'MASTER_UPDATE_LOCK_SEL_2', + 3: 'MASTER_UPDATE_LOCK_SEL_3', + 4: 'MASTER_UPDATE_LOCK_SEL_RESERVED4', + 5: 'MASTER_UPDATE_LOCK_SEL_RESERVED5', +} +MASTER_UPDATE_LOCK_SEL_0 = 0 +MASTER_UPDATE_LOCK_SEL_1 = 1 +MASTER_UPDATE_LOCK_SEL_2 = 2 +MASTER_UPDATE_LOCK_SEL_3 = 3 +MASTER_UPDATE_LOCK_SEL_RESERVED4 = 4 +MASTER_UPDATE_LOCK_SEL_RESERVED5 = 5 +MASTER_UPDATE_LOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE' +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE__enumvalues = { + 0: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 1: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 2: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 3: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', +} +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH = 0 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP = 1 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM = 2 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED = 3 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE' +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE__enumvalues = { + 0: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 1: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 2: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 3: 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', +} +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH = 0 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE = 1 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE = 2 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED = 3 +OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL' +OTG_CONTROL_OTG_DISABLE_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 1: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 2: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE', + 3: 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', +} +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE = 0 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT = 1 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE = 2 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST = 3 +OTG_CONTROL_OTG_DISABLE_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL' +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', +} +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY' +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY__enumvalues = { + 0: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 1: 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', +} +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE = 0 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE = 1 +OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_MASTER_EN' +OTG_CONTROL_OTG_MASTER_EN__enumvalues = { + 0: 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 1: 'OTG_CONTROL_OTG_MASTER_EN_TRUE', +} +OTG_CONTROL_OTG_MASTER_EN_FALSE = 0 +OTG_CONTROL_OTG_MASTER_EN_TRUE = 1 +OTG_CONTROL_OTG_MASTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_OUT_MUX' +OTG_CONTROL_OTG_OUT_MUX__enumvalues = { + 0: 'OTG_CONTROL_OTG_OUT_MUX_0', + 1: 'OTG_CONTROL_OTG_OUT_MUX_1', + 2: 'OTG_CONTROL_OTG_OUT_MUX_2', +} +OTG_CONTROL_OTG_OUT_MUX_0 = 0 +OTG_CONTROL_OTG_OUT_MUX_1 = 1 +OTG_CONTROL_OTG_OUT_MUX_2 = 2 +OTG_CONTROL_OTG_OUT_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CONTROL_OTG_START_POINT_CNTL' +OTG_CONTROL_OTG_START_POINT_CNTL__enumvalues = { + 0: 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 1: 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', +} +OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL = 0 +OTG_CONTROL_OTG_START_POINT_CNTL_DP = 1 +OTG_CONTROL_OTG_START_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN' +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN__enumvalues = { + 0: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 1: 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', +} +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE = 0 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE = 1 +OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC1_EN' +OTG_CRC_CNTL_OTG_CRC1_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC1_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC1_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC1_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC1_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC1_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_CONT_EN' +OTG_CRC_CNTL_OTG_CRC_CONT_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE' +OTG_CRC_CNTL_OTG_CRC_CONT_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET', + 1: 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET', +} +OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET = 0 +OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET = 1 +OTG_CRC_CNTL_OTG_CRC_CONT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_EN' +OTG_CRC_CNTL_OTG_CRC_EN__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_EN_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_EN_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE' +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 1: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 2: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 3: 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', +} +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP = 0 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM = 1 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM = 2 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD = 3 +OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE' +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 1: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 2: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 3: 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', +} +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT = 0 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT = 1 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES = 2 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS = 3 +OTG_CRC_CNTL_OTG_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS' +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 1: 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', +} +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE = 0 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE = 1 +OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT' +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT__enumvalues = { + 0: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 1: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 2: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 3: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 4: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 5: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 6: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 7: 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', +} +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB = 0 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B = 1 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB = 2 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B = 3 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB = 4 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B = 5 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB = 6 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B = 7 +OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DIG_UPDATE_VCOUNT_MODE' +OTG_DIG_UPDATE_VCOUNT_MODE__enumvalues = { + 0: 'OTG_DIG_UPDATE_VCOUNT_0', + 1: 'OTG_DIG_UPDATE_VCOUNT_1', +} +OTG_DIG_UPDATE_VCOUNT_0 = 0 +OTG_DIG_UPDATE_VCOUNT_1 = 1 +OTG_DIG_UPDATE_VCOUNT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE' +OTG_DLPC_CONTROL_OTG_RESYNC_MODE__enumvalues = { + 0: 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE_0', + 1: 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE_1', +} +OTG_DLPC_CONTROL_OTG_RESYNC_MODE_0 = 0 +OTG_DLPC_CONTROL_OTG_RESYNC_MODE_1 = 1 +OTG_DLPC_CONTROL_OTG_RESYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE' +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1', + 2: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2', + 3: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0 = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1 = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2 = 2 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3 = 3 +OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY' +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY__enumvalues = { + 0: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 1: 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', +} +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE = 0 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE = 1 +OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME' +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME__enumvalues = { + 0: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 1: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 2: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 3: 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', +} +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME = 0 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME = 1 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME = 2 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME = 3 +OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN' +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN__enumvalues = { + 0: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 1: 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', +} +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE = 0 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE = 1 +OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT' +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT__enumvalues = { + 0: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 1: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 2: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 3: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 4: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 5: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 6: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 7: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 8: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 9: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 10: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 11: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 12: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 13: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 14: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 15: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED', + 16: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 17: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 18: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 19: 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', +} +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0 = 0 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1 = 1 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA = 2 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB = 3 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC = 4 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD = 5 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE = 6 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF = 7 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1 = 8 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2 = 9 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA = 10 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK = 11 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA = 12 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK = 13 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 14 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED = 15 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK = 16 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC = 17 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA = 18 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB = 19 +OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 2: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 3: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT = 2 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED = 3 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL' +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL__enumvalues = { + 0: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 1: 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', +} +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE = 0 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE = 1 +OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL' +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL__enumvalues = { + 0: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 1: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 2: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 3: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 4: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4', + 5: 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5', +} +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0 = 0 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1 = 1 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2 = 2 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3 = 3 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4 = 4 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5 = 5 +OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL' +OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL__enumvalues = { + 0: 'DIG_UPDATE_EYE_SEL_BOTH', + 1: 'DIG_UPDATE_EYE_SEL_LEFT', + 2: 'DIG_UPDATE_EYE_SEL_RIGHT', +} +DIG_UPDATE_EYE_SEL_BOTH = 0 +DIG_UPDATE_EYE_SEL_LEFT = 1 +DIG_UPDATE_EYE_SEL_RIGHT = 2 +OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL' +OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL__enumvalues = { + 0: 'DIG_UPDATE_FIELD_SEL_BOTH', + 1: 'DIG_UPDATE_FIELD_SEL_TOP', + 2: 'DIG_UPDATE_FIELD_SEL_BOTTOM', + 3: 'DIG_UPDATE_FIELD_SEL_RESERVED', +} +DIG_UPDATE_FIELD_SEL_BOTH = 0 +DIG_UPDATE_FIELD_SEL_TOP = 1 +DIG_UPDATE_FIELD_SEL_BOTTOM = 2 +DIG_UPDATE_FIELD_SEL_RESERVED = 3 +OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 2: 'MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM', + 3: 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', +} +MASTER_UPDATE_LOCK_DB_FIELD_BOTH = 0 +MASTER_UPDATE_LOCK_DB_FIELD_TOP = 1 +MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM = 2 +MASTER_UPDATE_LOCK_DB_FIELD_RESERVED = 3 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL' +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 1: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 2: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 3: 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', +} +MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH = 0 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT = 1 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT = 2 +MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED = 3 +OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GLOBAL_UPDATE_LOCK_EN' +OTG_GLOBAL_UPDATE_LOCK_EN__enumvalues = { + 0: 'OTG_GLOBAL_UPDATE_LOCK_DISABLE', + 1: 'OTG_GLOBAL_UPDATE_LOCK_ENABLE', +} +OTG_GLOBAL_UPDATE_LOCK_DISABLE = 0 +OTG_GLOBAL_UPDATE_LOCK_ENABLE = 1 +OTG_GLOBAL_UPDATE_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_GSL_MASTER_MODE' +OTG_GSL_MASTER_MODE__enumvalues = { + 0: 'OTG_GSL_MASTER_MODE_0', + 1: 'OTG_GSL_MASTER_MODE_1', + 2: 'OTG_GSL_MASTER_MODE_2', + 3: 'OTG_GSL_MASTER_MODE_3', +} +OTG_GSL_MASTER_MODE_0 = 0 +OTG_GSL_MASTER_MODE_1 = 1 +OTG_GSL_MASTER_MODE_2 = 2 +OTG_GSL_MASTER_MODE_3 = 3 +OTG_GSL_MASTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_HORZ_REPETITION_COUNT' +OTG_HORZ_REPETITION_COUNT__enumvalues = { + 0: 'OTG_HORZ_REPETITION_COUNT_0', + 1: 'OTG_HORZ_REPETITION_COUNT_1', + 2: 'OTG_HORZ_REPETITION_COUNT_2', + 3: 'OTG_HORZ_REPETITION_COUNT_3', + 4: 'OTG_HORZ_REPETITION_COUNT_4', + 5: 'OTG_HORZ_REPETITION_COUNT_5', + 6: 'OTG_HORZ_REPETITION_COUNT_6', + 7: 'OTG_HORZ_REPETITION_COUNT_7', + 8: 'OTG_HORZ_REPETITION_COUNT_8', + 9: 'OTG_HORZ_REPETITION_COUNT_9', + 10: 'OTG_HORZ_REPETITION_COUNT_10', + 11: 'OTG_HORZ_REPETITION_COUNT_11', + 12: 'OTG_HORZ_REPETITION_COUNT_12', + 13: 'OTG_HORZ_REPETITION_COUNT_13', + 14: 'OTG_HORZ_REPETITION_COUNT_14', + 15: 'OTG_HORZ_REPETITION_COUNT_15', +} +OTG_HORZ_REPETITION_COUNT_0 = 0 +OTG_HORZ_REPETITION_COUNT_1 = 1 +OTG_HORZ_REPETITION_COUNT_2 = 2 +OTG_HORZ_REPETITION_COUNT_3 = 3 +OTG_HORZ_REPETITION_COUNT_4 = 4 +OTG_HORZ_REPETITION_COUNT_5 = 5 +OTG_HORZ_REPETITION_COUNT_6 = 6 +OTG_HORZ_REPETITION_COUNT_7 = 7 +OTG_HORZ_REPETITION_COUNT_8 = 8 +OTG_HORZ_REPETITION_COUNT_9 = 9 +OTG_HORZ_REPETITION_COUNT_10 = 10 +OTG_HORZ_REPETITION_COUNT_11 = 11 +OTG_HORZ_REPETITION_COUNT_12 = 12 +OTG_HORZ_REPETITION_COUNT_13 = 13 +OTG_HORZ_REPETITION_COUNT_14 = 14 +OTG_HORZ_REPETITION_COUNT_15 = 15 +OTG_HORZ_REPETITION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_SYNC_A_POL' +OTG_H_SYNC_A_POL__enumvalues = { + 0: 'OTG_H_SYNC_A_POL_HIGH', + 1: 'OTG_H_SYNC_A_POL_LOW', +} +OTG_H_SYNC_A_POL_HIGH = 0 +OTG_H_SYNC_A_POL_LOW = 1 +OTG_H_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_MODE' +OTG_H_TIMING_DIV_MODE__enumvalues = { + 0: 'OTG_H_TIMING_DIV_MODE_NO_DIV', + 1: 'OTG_H_TIMING_DIV_MODE_DIV_BY2', + 2: 'OTG_H_TIMING_DIV_MODE_RESERVED', + 3: 'OTG_H_TIMING_DIV_MODE_DIV_BY4', +} +OTG_H_TIMING_DIV_MODE_NO_DIV = 0 +OTG_H_TIMING_DIV_MODE_DIV_BY2 = 1 +OTG_H_TIMING_DIV_MODE_RESERVED = 2 +OTG_H_TIMING_DIV_MODE_DIV_BY4 = 3 +OTG_H_TIMING_DIV_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_H_TIMING_DIV_MODE_MANUAL' +OTG_H_TIMING_DIV_MODE_MANUAL__enumvalues = { + 0: 'OTG_H_TIMING_DIV_MODE_AUTO', + 1: 'OTG_H_TIMING_DIV_MODE_NOAUTO', +} +OTG_H_TIMING_DIV_MODE_AUTO = 0 +OTG_H_TIMING_DIV_MODE_NOAUTO = 1 +OTG_H_TIMING_DIV_MODE_MANUAL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD' +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD__enumvalues = { + 0: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 1: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 2: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 3: 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', +} +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT = 0 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM = 1 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP = 2 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2 = 3 +OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE' +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE__enumvalues = { + 0: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 1: 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', +} +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE = 0 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE = 1 +OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE' +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE__enumvalues = { + 0: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 1: 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', +} +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE = 0 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE = 1 +OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_DB_EN' +OTG_MASTER_UPDATE_LOCK_DB_EN__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_DISABLE', + 1: 'OTG_MASTER_UPDATE_LOCK_ENABLE', +} +OTG_MASTER_UPDATE_LOCK_DISABLE = 0 +OTG_MASTER_UPDATE_LOCK_ENABLE = 1 +OTG_MASTER_UPDATE_LOCK_DB_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_GSL_EN' +OTG_MASTER_UPDATE_LOCK_GSL_EN__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 1: 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', +} +OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE = 0 +OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE = 1 +OTG_MASTER_UPDATE_LOCK_GSL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE' +OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE__enumvalues = { + 0: 'OTG_MASTER_UPDATE_LOCK_VCOUNT_0', + 1: 'OTG_MASTER_UPDATE_LOCK_VCOUNT_1', +} +OTG_MASTER_UPDATE_LOCK_VCOUNT_0 = 0 +OTG_MASTER_UPDATE_LOCK_VCOUNT_1 = 1 +OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL' +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL__enumvalues = { + 0: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 1: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 2: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 3: 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', +} +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE = 0 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA = 1 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB = 2 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED = 3 +OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR' +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR__enumvalues = { + 0: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 1: 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', +} +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE = 0 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE = 1 +OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE' +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE' +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE__enumvalues = { + 0: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 1: 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', +} +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF = 0 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON = 1 +OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL' +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE', +} +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE = 0 +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE = 1 +OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EN' +OTG_STEREO_CONTROL_OTG_STEREO_EN__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY' +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 1: 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', +} +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE = 0 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE = 1 +OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE' +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE__enumvalues = { + 0: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 1: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 2: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 3: 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', +} +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO = 0 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT = 1 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT = 2 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED = 3 +OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR' +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', +} +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN' +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4 = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5 = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT' +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14', + 15: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14 = 14 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_FREQUENCY_SELECT' +OTG_TRIGA_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGA_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGA_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGA_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGA_FREQUENCY_SELECT_3', +} +OTG_TRIGA_FREQUENCY_SELECT_0 = 0 +OTG_TRIGA_FREQUENCY_SELECT_1 = 1 +OTG_TRIGA_FREQUENCY_SELECT_2 = 2 +OTG_TRIGA_FREQUENCY_SELECT_3 = 3 +OTG_TRIGA_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL' +OTG_TRIGA_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGA_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR' +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', +} +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN' +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', +} +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1 = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2 = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3 = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4 = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5 = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT' +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT__enumvalues = { + 0: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 1: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 2: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 3: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 4: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 5: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 6: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 7: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 8: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 9: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 10: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 11: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 12: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 13: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 14: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14', + 15: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 16: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 17: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 18: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 19: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 20: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 21: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 22: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 23: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 24: 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', +} +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0 = 0 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN = 1 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN = 2 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN = 3 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN = 4 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN = 5 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN = 6 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN = 7 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN = 8 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN = 9 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN = 10 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1 = 11 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2 = 12 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN = 13 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14 = 14 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK = 15 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP = 16 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING = 17 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF = 18 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC = 19 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC = 20 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL = 21 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL = 22 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1 = 23 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING = 24 +OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL' +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_FALLING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_FREQUENCY_SELECT' +OTG_TRIGB_FREQUENCY_SELECT__enumvalues = { + 0: 'OTG_TRIGB_FREQUENCY_SELECT_0', + 1: 'OTG_TRIGB_FREQUENCY_SELECT_1', + 2: 'OTG_TRIGB_FREQUENCY_SELECT_2', + 3: 'OTG_TRIGB_FREQUENCY_SELECT_3', +} +OTG_TRIGB_FREQUENCY_SELECT_0 = 0 +OTG_TRIGB_FREQUENCY_SELECT_1 = 1 +OTG_TRIGB_FREQUENCY_SELECT_2 = 2 +OTG_TRIGB_FREQUENCY_SELECT_3 = 3 +OTG_TRIGB_FREQUENCY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL' +OTG_TRIGB_RISING_EDGE_DETECT_CNTL__enumvalues = { + 0: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 1: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 2: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 3: 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', +} +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0 = 0 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1 = 1 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2 = 2 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3 = 3 +OTG_TRIGB_RISING_EDGE_DETECT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK' +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK__enumvalues = { + 0: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 1: 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', +} +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE = 0 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE = 1 +OTG_UPDATE_LOCK_OTG_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY' +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', +} +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE = 0 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE = 1 +OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE' +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE' +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE__enumvalues = { + 0: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 1: 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', +} +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE = 0 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE = 1 +OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE' +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 2: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 3: 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', +} +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE = 0 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA = 1 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB = 2 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED = 3 +OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR' +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR__enumvalues = { + 0: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 1: 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', +} +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE = 0 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE = 1 +OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR' +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR__enumvalues = { + 0: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 1: 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', +} +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE = 0 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE = 1 +OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_VUPDATE_BLOCK_DISABLE' +OTG_VUPDATE_BLOCK_DISABLE__enumvalues = { + 0: 'OTG_VUPDATE_BLOCK_DISABLE_OFF', + 1: 'OTG_VUPDATE_BLOCK_DISABLE_ON', +} +OTG_VUPDATE_BLOCK_DISABLE_OFF = 0 +OTG_VUPDATE_BLOCK_DISABLE_ON = 1 +OTG_VUPDATE_BLOCK_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_SYNC_A_POL' +OTG_V_SYNC_A_POL__enumvalues = { + 0: 'OTG_V_SYNC_A_POL_HIGH', + 1: 'OTG_V_SYNC_A_POL_LOW', +} +OTG_V_SYNC_A_POL_HIGH = 0 +OTG_V_SYNC_A_POL_LOW = 1 +OTG_V_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_SYNC_MODE' +OTG_V_SYNC_MODE__enumvalues = { + 0: 'OTG_V_SYNC_MODE_HSYNC', + 1: 'OTG_V_SYNC_MODE_HBLANK', +} +OTG_V_SYNC_MODE_HSYNC = 0 +OTG_V_SYNC_MODE_HBLANK = 1 +OTG_V_SYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD' +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 1: 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', +} +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0 = 0 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1 = 1 +OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC' +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', +} +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE = 0 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE = 1 +OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL' +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL__enumvalues = { + 0: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 1: 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', +} +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE = 0 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE = 1 +OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK' +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK__enumvalues = { + 0: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE', + 1: 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE', +} +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE = 0 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE = 1 +OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL' +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL__enumvalues = { + 0: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0', + 1: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1', + 2: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2', + 3: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3', + 4: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4', + 5: 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5', +} +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0 = 0 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1 = 1 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2 = 2 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3 = 3 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4 = 4 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5 = 5 +OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_INT_TYPE' +DC_DMCUB_INT_TYPE__enumvalues = { + 0: 'INT_LEVEL', + 1: 'INT_PULSE', +} +INT_LEVEL = 0 +INT_PULSE = 1 +DC_DMCUB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DC_DMCUB_TIMER_WINDOW' +DC_DMCUB_TIMER_WINDOW__enumvalues = { + 0: 'BITS_31_0', + 1: 'BITS_32_1', + 2: 'BITS_33_2', + 3: 'BITS_34_3', + 4: 'BITS_35_4', + 5: 'BITS_36_5', + 6: 'BITS_37_6', + 7: 'BITS_38_7', +} +BITS_31_0 = 0 +BITS_32_1 = 1 +BITS_33_2 = 2 +BITS_34_3 = 3 +BITS_35_4 = 4 +BITS_36_5 = 5 +BITS_37_6 = 6 +BITS_38_7 = 7 +DC_DMCUB_TIMER_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'INVALID_REG_ACCESS_TYPE' +INVALID_REG_ACCESS_TYPE__enumvalues = { + 0: 'REG_UNALLOCATED_ADDR_WRITE', + 1: 'REG_UNALLOCATED_ADDR_READ', + 2: 'REG_VIRTUAL_WRITE', + 3: 'REG_VIRTUAL_READ', + 4: 'REG_SECURE_VIOLATE_WRITE', + 5: 'REG_SECURE_VIOLATE_READ', +} +REG_UNALLOCATED_ADDR_WRITE = 0 +REG_UNALLOCATED_ADDR_READ = 1 +REG_VIRTUAL_WRITE = 2 +REG_VIRTUAL_READ = 3 +REG_SECURE_VIOLATE_WRITE = 4 +REG_SECURE_VIOLATE_READ = 5 +INVALID_REG_ACCESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_READ_SELECT' +DMU_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 1: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 2: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 3: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 4: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 5: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 6: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 7: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 8: 'RESERVED_8', + 9: 'RESERVED_9', + 10: 'RESERVED_10', + 11: 'RESERVED_11', + 12: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 13: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 14: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 15: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 16: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 17: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 18: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 19: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 20: 'RESERVED_20', + 21: 'RESERVED_21', + 22: 'RESERVED_22', + 23: 'RESERVED_23', + 24: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 25: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 26: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 27: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 28: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 29: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 30: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 31: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 32: 'RESERVED_32', + 33: 'RESERVED_33', + 34: 'RESERVED_34', + 35: 'RESERVED_35', + 36: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 37: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 38: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 39: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 40: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 41: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 42: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 43: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 44: 'RESERVED_44', + 45: 'RESERVED_45', + 46: 'RESERVED_46', + 47: 'RESERVED_47', + 48: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 49: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 50: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 51: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 52: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 53: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 54: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 55: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 56: 'RESERVED_56', + 57: 'RESERVED_57', + 58: 'RESERVED_58', + 59: 'RESERVED_59', + 60: 'RESERVED_60', + 61: 'RESERVED_61', + 62: 'RESERVED_62', + 63: 'RESERVED_63', + 64: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 65: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 66: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 67: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 68: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 69: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 70: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 71: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 72: 'RESERVED_72', + 73: 'RESERVED_73', + 74: 'RESERVED_74', + 75: 'RESERVED_75', + 76: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 77: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 78: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 79: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 80: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 81: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 82: 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 83: 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 84: 'RESERVED_84', + 85: 'RESERVED_85', + 86: 'RESERVED_86', + 87: 'RESERVED_87', + 88: 'RESERVED_88', + 89: 'RESERVED_89', + 90: 'RESERVED_90', + 91: 'RESERVED_91', +} +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0 = 0 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1 = 1 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2 = 2 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3 = 3 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4 = 4 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5 = 5 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6 = 6 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7 = 7 +RESERVED_8 = 8 +RESERVED_9 = 9 +RESERVED_10 = 10 +RESERVED_11 = 11 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12 = 12 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13 = 13 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14 = 14 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15 = 15 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16 = 16 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17 = 17 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18 = 18 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19 = 19 +RESERVED_20 = 20 +RESERVED_21 = 21 +RESERVED_22 = 22 +RESERVED_23 = 23 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24 = 24 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25 = 25 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26 = 26 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27 = 27 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28 = 28 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29 = 29 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30 = 30 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31 = 31 +RESERVED_32 = 32 +RESERVED_33 = 33 +RESERVED_34 = 34 +RESERVED_35 = 35 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36 = 36 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37 = 37 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38 = 38 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39 = 39 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40 = 40 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41 = 41 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42 = 42 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43 = 43 +RESERVED_44 = 44 +RESERVED_45 = 45 +RESERVED_46 = 46 +RESERVED_47 = 47 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48 = 48 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49 = 49 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50 = 50 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51 = 51 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52 = 52 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53 = 53 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54 = 54 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55 = 55 +RESERVED_56 = 56 +RESERVED_57 = 57 +RESERVED_58 = 58 +RESERVED_59 = 59 +RESERVED_60 = 60 +RESERVED_61 = 61 +RESERVED_62 = 62 +RESERVED_63 = 63 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64 = 64 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65 = 65 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66 = 66 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67 = 67 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68 = 68 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69 = 69 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70 = 70 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71 = 71 +RESERVED_72 = 72 +RESERVED_73 = 73 +RESERVED_74 = 74 +RESERVED_75 = 75 +DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76 = 76 +DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77 = 77 +DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78 = 78 +DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79 = 79 +DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80 = 80 +DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81 = 81 +DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82 = 82 +DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83 = 83 +RESERVED_84 = 84 +RESERVED_85 = 85 +RESERVED_86 = 86 +RESERVED_87 = 87 +RESERVED_88 = 88 +RESERVED_89 = 89 +RESERVED_90 = 90 +RESERVED_91 = 91 +DMU_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_DC_GPU_TIMER_START_POSITION' +DMU_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DMU_GPU_TIMER_START_0_END_27', + 1: 'DMU_GPU_TIMER_START_1_END_28', + 2: 'DMU_GPU_TIMER_START_2_END_29', + 3: 'DMU_GPU_TIMER_START_3_END_30', + 4: 'DMU_GPU_TIMER_START_4_END_31', + 5: 'DMU_GPU_TIMER_START_6_END_33', + 6: 'DMU_GPU_TIMER_START_8_END_35', + 7: 'DMU_GPU_TIMER_START_10_END_37', +} +DMU_GPU_TIMER_START_0_END_27 = 0 +DMU_GPU_TIMER_START_1_END_28 = 1 +DMU_GPU_TIMER_START_2_END_29 = 2 +DMU_GPU_TIMER_START_3_END_30 = 3 +DMU_GPU_TIMER_START_4_END_31 = 4 +DMU_GPU_TIMER_START_6_END_33 = 5 +DMU_GPU_TIMER_START_8_END_35 = 6 +DMU_GPU_TIMER_START_10_END_37 = 7 +DMU_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'IHC_INTERRUPT_DEST' +IHC_INTERRUPT_DEST__enumvalues = { + 0: 'INTERRUPT_SENT_TO_IH', + 1: 'INTERRUPT_SENT_TO_DMCUB', +} +INTERRUPT_SENT_TO_IH = 0 +INTERRUPT_SENT_TO_DMCUB = 1 +IHC_INTERRUPT_DEST = ctypes.c_uint32 # enum + +# values for enumeration 'IHC_INTERRUPT_LINE_STATUS' +IHC_INTERRUPT_LINE_STATUS__enumvalues = { + 0: 'INTERRUPT_LINE_NOT_ASSERTED', + 1: 'INTERRUPT_LINE_ASSERTED', +} +INTERRUPT_LINE_NOT_ASSERTED = 0 +INTERRUPT_LINE_ASSERTED = 1 +IHC_INTERRUPT_LINE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DC_SMU_INTERRUPT_ENABLE' +DC_SMU_INTERRUPT_ENABLE__enumvalues = { + 0: 'DISABLE_THE_INTERRUPT', + 1: 'ENABLE_THE_INTERRUPT', +} +DISABLE_THE_INTERRUPT = 0 +ENABLE_THE_INTERRUPT = 1 +DC_SMU_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DMU_CLOCK_ON' +DMU_CLOCK_ON__enumvalues = { + 0: 'DMU_CLOCK_STATUS_ON', + 1: 'DMU_CLOCK_STATUS_OFF', +} +DMU_CLOCK_STATUS_ON = 0 +DMU_CLOCK_STATUS_OFF = 1 +DMU_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'SMU_INTR' +SMU_INTR__enumvalues = { + 0: 'SMU_MSG_INTR_NOOP', + 1: 'SET_SMU_MSG_INTR', +} +SMU_MSG_INTR_NOOP = 0 +SET_SMU_MSG_INTR = 1 +SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'ALLOW_SR_ON_TRANS_REQ' +ALLOW_SR_ON_TRANS_REQ__enumvalues = { + 0: 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 1: 'ALLOW_SR_ON_TRANS_REQ_DISABLE', +} +ALLOW_SR_ON_TRANS_REQ_ENABLE = 0 +ALLOW_SR_ON_TRANS_REQ_DISABLE = 1 +ALLOW_SR_ON_TRANS_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'AMCLOCK_ENABLE' +AMCLOCK_ENABLE__enumvalues = { + 0: 'ENABLE_AMCLK0', + 1: 'ENABLE_AMCLK1', +} +ENABLE_AMCLK0 = 0 +ENABLE_AMCLK1 = 1 +AMCLOCK_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CLEAR_SMU_INTR' +CLEAR_SMU_INTR__enumvalues = { + 0: 'SMU_INTR_STATUS_NOOP', + 1: 'SMU_INTR_STATUS_CLEAR', +} +SMU_INTR_STATUS_NOOP = 0 +SMU_INTR_STATUS_CLEAR = 1 +CLEAR_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_BRANCH_SOFT_RESET' +CLOCK_BRANCH_SOFT_RESET__enumvalues = { + 0: 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 1: 'CLOCK_BRANCH_SOFT_RESET_FORCE', +} +CLOCK_BRANCH_SOFT_RESET_NOOP = 0 +CLOCK_BRANCH_SOFT_RESET_FORCE = 1 +CLOCK_BRANCH_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO0_SOURCE_SEL' +DCCG_AUDIO_DTO0_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 1: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 2: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 3: 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 4: 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', +} +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0 = 0 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1 = 1 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2 = 2 +DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3 = 3 +DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED = 4 +DCCG_AUDIO_DTO0_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO2_SOURCE_SEL' +DCCG_AUDIO_DTO2_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 1: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2', +} +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0 = 0 +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2 = 1 +DCCG_AUDIO_DTO2_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_SEL' +DCCG_AUDIO_DTO_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', + 1: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 2: 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', +} +DCCG_AUDIO_DTO_SEL_AUDIO_DTO0 = 0 +DCCG_AUDIO_DTO_SEL_AUDIO_DTO1 = 1 +DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO = 2 +DCCG_AUDIO_DTO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_USE_512FBR_DTO' +DCCG_AUDIO_DTO_USE_512FBR_DTO__enumvalues = { + 0: 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 1: 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', +} +DCCG_AUDIO_DTO_USE_128FBR_FOR_DP = 0 +DCCG_AUDIO_DTO_USE_512FBR_FOR_DP = 1 +DCCG_AUDIO_DTO_USE_512FBR_DTO = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_BLOCK_SEL' +DCCG_DBG_BLOCK_SEL__enumvalues = { + 0: 'DCCG_DBG_BLOCK_SEL_DCCG', + 1: 'DCCG_DBG_BLOCK_SEL_PMON', + 2: 'DCCG_DBG_BLOCK_SEL_PMON2', +} +DCCG_DBG_BLOCK_SEL_DCCG = 0 +DCCG_DBG_BLOCK_SEL_PMON = 1 +DCCG_DBG_BLOCK_SEL_PMON2 = 2 +DCCG_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_EN' +DCCG_DBG_EN__enumvalues = { + 0: 'DCCG_DBG_EN_DISABLE', + 1: 'DCCG_DBG_EN_ENABLE', +} +DCCG_DBG_EN_DISABLE = 0 +DCCG_DBG_EN_ENABLE = 1 +DCCG_DBG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DEEP_COLOR_CNTL' +DCCG_DEEP_COLOR_CNTL__enumvalues = { + 0: 'DCCG_DEEP_COLOR_DTO_DISABLE', + 1: 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', + 2: 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 3: 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', +} +DCCG_DEEP_COLOR_DTO_DISABLE = 0 +DCCG_DEEP_COLOR_DTO_5_4_RATIO = 1 +DCCG_DEEP_COLOR_DTO_3_2_RATIO = 2 +DCCG_DEEP_COLOR_DTO_2_1_RATIO = 3 +DCCG_DEEP_COLOR_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_OVR_EN' +DCCG_FIFO_ERRDET_OVR_EN__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_OVR_DISABLE', + 1: 'DCCG_FIFO_ERRDET_OVR_ENABLE', +} +DCCG_FIFO_ERRDET_OVR_DISABLE = 0 +DCCG_FIFO_ERRDET_OVR_ENABLE = 1 +DCCG_FIFO_ERRDET_OVR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_RESET' +DCCG_FIFO_ERRDET_RESET__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_RESET_NOOP', + 1: 'DCCG_FIFO_ERRDET_RESET_FORCE', +} +DCCG_FIFO_ERRDET_RESET_NOOP = 0 +DCCG_FIFO_ERRDET_RESET_FORCE = 1 +DCCG_FIFO_ERRDET_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_STATE' +DCCG_FIFO_ERRDET_STATE__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 1: 'DCCG_FIFO_ERRDET_STATE_DETECTION', +} +DCCG_FIFO_ERRDET_STATE_CALIBRATION = 0 +DCCG_FIFO_ERRDET_STATE_DETECTION = 1 +DCCG_FIFO_ERRDET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_HSYNC' +DCCG_PERF_MODE_HSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_HSYNC_NOOP', + 1: 'DCCG_PERF_MODE_HSYNC_START', +} +DCCG_PERF_MODE_HSYNC_NOOP = 0 +DCCG_PERF_MODE_HSYNC_START = 1 +DCCG_PERF_MODE_HSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_VSYNC' +DCCG_PERF_MODE_VSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_VSYNC_NOOP', + 1: 'DCCG_PERF_MODE_VSYNC_START', +} +DCCG_PERF_MODE_VSYNC_NOOP = 0 +DCCG_PERF_MODE_VSYNC_START = 1 +DCCG_PERF_MODE_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_OTG_SELECT' +DCCG_PERF_OTG_SELECT__enumvalues = { + 0: 'DCCG_PERF_SEL_OTG0', + 1: 'DCCG_PERF_SEL_OTG1', + 2: 'DCCG_PERF_SEL_OTG2', + 3: 'DCCG_PERF_SEL_OTG3', + 4: 'DCCG_PERF_SEL_RESERVED', +} +DCCG_PERF_SEL_OTG0 = 0 +DCCG_PERF_SEL_OTG1 = 1 +DCCG_PERF_SEL_OTG2 = 2 +DCCG_PERF_SEL_OTG3 = 3 +DCCG_PERF_SEL_RESERVED = 4 +DCCG_PERF_OTG_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_RUN' +DCCG_PERF_RUN__enumvalues = { + 0: 'DCCG_PERF_RUN_NOOP', + 1: 'DCCG_PERF_RUN_START', +} +DCCG_PERF_RUN_NOOP = 0 +DCCG_PERF_RUN_START = 1 +DCCG_PERF_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'DC_MEM_GLOBAL_PWR_REQ_DIS' +DC_MEM_GLOBAL_PWR_REQ_DIS__enumvalues = { + 0: 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 1: 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', +} +DC_MEM_GLOBAL_PWR_REQ_ENABLE = 0 +DC_MEM_GLOBAL_PWR_REQ_DISABLE = 1 +DC_MEM_GLOBAL_PWR_REQ_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_FIFO_ERROR' +DIO_FIFO_ERROR__enumvalues = { + 0: 'DIO_FIFO_ERROR_00', + 1: 'DIO_FIFO_ERROR_01', + 2: 'DIO_FIFO_ERROR_10', + 3: 'DIO_FIFO_ERROR_11', +} +DIO_FIFO_ERROR_00 = 0 +DIO_FIFO_ERROR_01 = 1 +DIO_FIFO_ERROR_10 = 2 +DIO_FIFO_ERROR_11 = 3 +DIO_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING' +DISABLE_CLOCK_GATING__enumvalues = { + 0: 'CLOCK_GATING_ENABLED', + 1: 'CLOCK_GATING_DISABLED', +} +CLOCK_GATING_ENABLED = 0 +CLOCK_GATING_DISABLED = 1 +DISABLE_CLOCK_GATING = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING_IN_DCO' +DISABLE_CLOCK_GATING_IN_DCO__enumvalues = { + 0: 'CLOCK_GATING_ENABLED_IN_DCO', + 1: 'CLOCK_GATING_DISABLED_IN_DCO', +} +CLOCK_GATING_ENABLED_IN_DCO = 0 +CLOCK_GATING_DISABLED_IN_DCO = 1 +DISABLE_CLOCK_GATING_IN_DCO = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_CHG_FWD_CORR_DISABLE' +DISPCLK_CHG_FWD_CORR_DISABLE__enumvalues = { + 0: 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 1: 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', +} +DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING = 0 +DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING = 1 +DISPCLK_CHG_FWD_CORR_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_FREQ_RAMP_DONE' +DISPCLK_FREQ_RAMP_DONE__enumvalues = { + 0: 'DISPCLK_FREQ_RAMP_IN_PROGRESS', + 1: 'DISPCLK_FREQ_RAMP_COMPLETED', +} +DISPCLK_FREQ_RAMP_IN_PROGRESS = 0 +DISPCLK_FREQ_RAMP_COMPLETED = 1 +DISPCLK_FREQ_RAMP_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DPREFCLK_SRC_SEL' +DPREFCLK_SRC_SEL__enumvalues = { + 0: 'DPREFCLK_SRC_SEL_CK', + 1: 'DPREFCLK_SRC_SEL_P0PLL', + 2: 'DPREFCLK_SRC_SEL_P1PLL', + 3: 'DPREFCLK_SRC_SEL_P2PLL', +} +DPREFCLK_SRC_SEL_CK = 0 +DPREFCLK_SRC_SEL_P0PLL = 1 +DPREFCLK_SRC_SEL_P1PLL = 2 +DPREFCLK_SRC_SEL_P2PLL = 3 +DPREFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DTO_DS_DISABLE' +DP_DTO_DS_DISABLE__enumvalues = { + 0: 'DP_DTO_DESPREAD_DISABLE', + 1: 'DP_DTO_DESPREAD_ENABLE', +} +DP_DTO_DESPREAD_DISABLE = 0 +DP_DTO_DESPREAD_ENABLE = 1 +DP_DTO_DS_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_HW_CAL_ENABLE' +DS_HW_CAL_ENABLE__enumvalues = { + 0: 'DS_HW_CAL_DIS', + 1: 'DS_HW_CAL_EN', +} +DS_HW_CAL_DIS = 0 +DS_HW_CAL_EN = 1 +DS_HW_CAL_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_REF_SRC' +DS_REF_SRC__enumvalues = { + 0: 'DS_REF_IS_XTALIN', + 1: 'DS_REF_IS_EXT_GENLOCK', + 2: 'DS_REF_IS_PCIE', +} +DS_REF_IS_XTALIN = 0 +DS_REF_IS_EXT_GENLOCK = 1 +DS_REF_IS_PCIE = 2 +DS_REF_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DVO_ENABLE_RST' +DVO_ENABLE_RST__enumvalues = { + 0: 'DVO_ENABLE_RST_DISABLE', + 1: 'DVO_ENABLE_RST_ENABLE', +} +DVO_ENABLE_RST_DISABLE = 0 +DVO_ENABLE_RST_ENABLE = 1 +DVO_ENABLE_RST = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE' +ENABLE__enumvalues = { + 0: 'DISABLE_THE_FEATURE', + 1: 'ENABLE_THE_FEATURE', +} +DISABLE_THE_FEATURE = 0 +ENABLE_THE_FEATURE = 1 +ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_CLOCK' +ENABLE_CLOCK__enumvalues = { + 0: 'ENABLE_THE_REFCLK', + 1: 'ENABLE_THE_FUNC_CLOCK', +} +ENABLE_THE_REFCLK = 0 +ENABLE_THE_FUNC_CLOCK = 1 +ENABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'FORCE_DISABLE_CLOCK' +FORCE_DISABLE_CLOCK__enumvalues = { + 0: 'NOT_FORCE_THE_CLOCK_DISABLED', + 1: 'FORCE_THE_CLOCK_DISABLED', +} +NOT_FORCE_THE_CLOCK_DISABLED = 0 +FORCE_THE_CLOCK_DISABLED = 1 +FORCE_DISABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMICHARCLK_SRC_SEL' +HDMICHARCLK_SRC_SEL__enumvalues = { + 0: 'HDMICHARCLK_SRC_SEL_UNIPHYA', + 1: 'HDMICHARCLK_SRC_SEL_UNIPHYB', + 2: 'HDMICHARCLK_SRC_SEL_UNIPHYC', + 3: 'HDMICHARCLK_SRC_SEL_UNIPHYD', + 4: 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', +} +HDMICHARCLK_SRC_SEL_UNIPHYA = 0 +HDMICHARCLK_SRC_SEL_UNIPHYB = 1 +HDMICHARCLK_SRC_SEL_UNIPHYC = 2 +HDMICHARCLK_SRC_SEL_UNIPHYD = 3 +HDMICHARCLK_SRC_SEL_SRC_RESERVED = 4 +HDMICHARCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'HDMISTREAMCLK_SRC_SEL' +HDMISTREAMCLK_SRC_SEL__enumvalues = { + 0: 'SEL_DTBCLK_P0', + 1: 'SEL_DTBCLK_P1', + 2: 'SEL_DTBCLK_P2', + 3: 'SEL_DTBCLK_P3', +} +SEL_DTBCLK_P0 = 0 +SEL_DTBCLK_P1 = 1 +SEL_DTBCLK_P2 = 2 +SEL_DTBCLK_P3 = 3 +HDMISTREAMCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'JITTER_REMOVE_DISABLE' +JITTER_REMOVE_DISABLE__enumvalues = { + 0: 'ENABLE_JITTER_REMOVAL', + 1: 'DISABLE_JITTER_REMOVAL', +} +ENABLE_JITTER_REMOVAL = 0 +DISABLE_JITTER_REMOVAL = 1 +JITTER_REMOVE_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', +} +MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK = 1 +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_ADD_PIXEL' +OTG_ADD_PIXEL__enumvalues = { + 0: 'OTG_ADD_PIXEL_NOOP', + 1: 'OTG_ADD_PIXEL_FORCE', +} +OTG_ADD_PIXEL_NOOP = 0 +OTG_ADD_PIXEL_FORCE = 1 +OTG_ADD_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'OTG_DROP_PIXEL' +OTG_DROP_PIXEL__enumvalues = { + 0: 'OTG_DROP_PIXEL_NOOP', + 1: 'OTG_DROP_PIXEL_FORCE', +} +OTG_DROP_PIXEL_NOOP = 0 +OTG_DROP_PIXEL_FORCE = 1 +OTG_DROP_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'PHYSYMCLK_FORCE_EN' +PHYSYMCLK_FORCE_EN__enumvalues = { + 0: 'PHYSYMCLK_FORCE_EN_DISABLE', + 1: 'PHYSYMCLK_FORCE_EN_ENABLE', +} +PHYSYMCLK_FORCE_EN_DISABLE = 0 +PHYSYMCLK_FORCE_EN_ENABLE = 1 +PHYSYMCLK_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PHYSYMCLK_FORCE_SRC_SEL' +PHYSYMCLK_FORCE_SRC_SEL__enumvalues = { + 0: 'PHYSYMCLK_FORCE_SRC_SYMCLK', + 1: 'PHYSYMCLK_FORCE_SRC_PHYD18CLK', + 2: 'PHYSYMCLK_FORCE_SRC_PHYD32CLK', +} +PHYSYMCLK_FORCE_SRC_SYMCLK = 0 +PHYSYMCLK_FORCE_SRC_PHYD18CLK = 1 +PHYSYMCLK_FORCE_SRC_PHYD32CLK = 2 +PHYSYMCLK_FORCE_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PHYPLL_PIXEL_RATE_SOURCE' +PIPE_PHYPLL_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 1: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 2: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 3: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 4: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', +} +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA = 0 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB = 1 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC = 2 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD = 3 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED = 4 +PIPE_PHYPLL_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_PLL_SOURCE' +PIPE_PIXEL_RATE_PLL_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', + 1: 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', +} +PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL = 0 +PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL = 1 +PIPE_PIXEL_RATE_PLL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_SOURCE' +PIPE_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_SOURCE_P0PLL', + 1: 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 2: 'PIPE_PIXEL_RATE_SOURCE_P2PLL', +} +PIPE_PIXEL_RATE_SOURCE_P0PLL = 0 +PIPE_PIXEL_RATE_SOURCE_P1PLL = 1 +PIPE_PIXEL_RATE_SOURCE_P2PLL = 2 +PIPE_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PLL_CFG_IF_SOFT_RESET' +PLL_CFG_IF_SOFT_RESET__enumvalues = { + 0: 'PLL_CFG_IF_SOFT_RESET_NOOP', + 1: 'PLL_CFG_IF_SOFT_RESET_FORCE', +} +PLL_CFG_IF_SOFT_RESET_NOOP = 0 +PLL_CFG_IF_SOFT_RESET_FORCE = 1 +PLL_CFG_IF_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_SRC' +SYMCLK_FE_SRC__enumvalues = { + 0: 'SYMCLK_FE_SRC_UNIPHYA', + 1: 'SYMCLK_FE_SRC_UNIPHYB', + 2: 'SYMCLK_FE_SRC_UNIPHYC', + 3: 'SYMCLK_FE_SRC_UNIPHYD', + 4: 'SYMCLK_FE_SRC_RESERVED', +} +SYMCLK_FE_SRC_UNIPHYA = 0 +SYMCLK_FE_SRC_UNIPHYB = 1 +SYMCLK_FE_SRC_UNIPHYC = 2 +SYMCLK_FE_SRC_UNIPHYD = 3 +SYMCLK_FE_SRC_RESERVED = 4 +SYMCLK_FE_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLK_DIV_SEL' +TEST_CLK_DIV_SEL__enumvalues = { + 0: 'NO_DIV', + 1: 'DIV_2', + 2: 'DIV_4', + 3: 'DIV_8', +} +NO_DIV = 0 +DIV_2 = 1 +DIV_4 = 2 +DIV_8 = 3 +TEST_CLK_DIV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_LATCH_MASK' +VSYNC_CNT_LATCH_MASK__enumvalues = { + 0: 'VSYNC_CNT_LATCH_MASK_0', + 1: 'VSYNC_CNT_LATCH_MASK_1', +} +VSYNC_CNT_LATCH_MASK_0 = 0 +VSYNC_CNT_LATCH_MASK_1 = 1 +VSYNC_CNT_LATCH_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'VSYNC_CNT_RESET_SEL' +VSYNC_CNT_RESET_SEL__enumvalues = { + 0: 'VSYNC_CNT_RESET_SEL_0', + 1: 'VSYNC_CNT_RESET_SEL_1', +} +VSYNC_CNT_RESET_SEL_0 = 0 +VSYNC_CNT_RESET_SEL_1 = 1 +VSYNC_CNT_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_CLOCK_SOURCE_SEL' +XTAL_REF_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', + 1: 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', +} +XTAL_REF_CLOCK_SOURCE_SEL_XTALIN = 0 +XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK = 1 +XTAL_REF_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_SEL' +XTAL_REF_SEL__enumvalues = { + 0: 'XTAL_REF_SEL_1X', + 1: 'XTAL_REF_SEL_2X', +} +XTAL_REF_SEL_1X = 0 +XTAL_REF_SEL_2X = 1 +XTAL_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_CUR_DISP' +DPHY_8B10B_CUR_DISP__enumvalues = { + 0: 'DPHY_8B10B_CUR_DISP_ZERO', + 1: 'DPHY_8B10B_CUR_DISP_ONE', +} +DPHY_8B10B_CUR_DISP_ZERO = 0 +DPHY_8B10B_CUR_DISP_ONE = 1 +DPHY_8B10B_CUR_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_RESET' +DPHY_8B10B_RESET__enumvalues = { + 0: 'DPHY_8B10B_NOT_RESET', + 1: 'DPHY_8B10B_RESETET', +} +DPHY_8B10B_NOT_RESET = 0 +DPHY_8B10B_RESETET = 1 +DPHY_8B10B_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE0' +DPHY_ATEST_SEL_LANE0__enumvalues = { + 0: 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE0_REG_PATTERN', +} +DPHY_ATEST_LANE0_PRBS_PATTERN = 0 +DPHY_ATEST_LANE0_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE0 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE1' +DPHY_ATEST_SEL_LANE1__enumvalues = { + 0: 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE1_REG_PATTERN', +} +DPHY_ATEST_LANE1_PRBS_PATTERN = 0 +DPHY_ATEST_LANE1_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE1 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE2' +DPHY_ATEST_SEL_LANE2__enumvalues = { + 0: 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE2_REG_PATTERN', +} +DPHY_ATEST_LANE2_PRBS_PATTERN = 0 +DPHY_ATEST_LANE2_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE2 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE3' +DPHY_ATEST_SEL_LANE3__enumvalues = { + 0: 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE3_REG_PATTERN', +} +DPHY_ATEST_LANE3_PRBS_PATTERN = 0 +DPHY_ATEST_LANE3_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE3 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_BYPASS' +DPHY_BYPASS__enumvalues = { + 0: 'DPHY_8B10B_OUTPUT', + 1: 'DPHY_DBG_OUTPUT', +} +DPHY_8B10B_OUTPUT = 0 +DPHY_DBG_OUTPUT = 1 +DPHY_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_CONT_EN' +DPHY_CRC_CONT_EN__enumvalues = { + 0: 'DPHY_CRC_ONE_SHOT', + 1: 'DPHY_CRC_CONTINUOUS', +} +DPHY_CRC_ONE_SHOT = 0 +DPHY_CRC_CONTINUOUS = 1 +DPHY_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_EN' +DPHY_CRC_EN__enumvalues = { + 0: 'DPHY_CRC_DISABLED', + 1: 'DPHY_CRC_ENABLED', +} +DPHY_CRC_DISABLED = 0 +DPHY_CRC_ENABLED = 1 +DPHY_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_FIELD' +DPHY_CRC_FIELD__enumvalues = { + 0: 'DPHY_CRC_START_FROM_TOP_FIELD', + 1: 'DPHY_CRC_START_FROM_BOTTOM_FIELD', +} +DPHY_CRC_START_FROM_TOP_FIELD = 0 +DPHY_CRC_START_FROM_BOTTOM_FIELD = 1 +DPHY_CRC_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_MST_PHASE_ERROR_ACK' +DPHY_CRC_MST_PHASE_ERROR_ACK__enumvalues = { + 0: 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', + 1: 'DPHY_CRC_MST_PHASE_ERROR_ACKED', +} +DPHY_CRC_MST_PHASE_ERROR_NO_ACK = 0 +DPHY_CRC_MST_PHASE_ERROR_ACKED = 1 +DPHY_CRC_MST_PHASE_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_SEL' +DPHY_CRC_SEL__enumvalues = { + 0: 'DPHY_CRC_LANE0_SELECTED', + 1: 'DPHY_CRC_LANE1_SELECTED', + 2: 'DPHY_CRC_LANE2_SELECTED', + 3: 'DPHY_CRC_LANE3_SELECTED', +} +DPHY_CRC_LANE0_SELECTED = 0 +DPHY_CRC_LANE1_SELECTED = 1 +DPHY_CRC_LANE2_SELECTED = 2 +DPHY_CRC_LANE3_SELECTED = 3 +DPHY_CRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_ENABLE' +DPHY_FEC_ENABLE__enumvalues = { + 0: 'DPHY_FEC_DISABLED', + 1: 'DPHY_FEC_ENABLED', +} +DPHY_FEC_DISABLED = 0 +DPHY_FEC_ENABLED = 1 +DPHY_FEC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_FEC_READY' +DPHY_FEC_READY__enumvalues = { + 0: 'DPHY_FEC_READY_EN', + 1: 'DPHY_FEC_READY_DIS', +} +DPHY_FEC_READY_EN = 0 +DPHY_FEC_READY_DIS = 1 +DPHY_FEC_READY = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_LOAD_BS_COUNT_START' +DPHY_LOAD_BS_COUNT_START__enumvalues = { + 0: 'DPHY_LOAD_BS_COUNT_STARTED', + 1: 'DPHY_LOAD_BS_COUNT_NOT_STARTED', +} +DPHY_LOAD_BS_COUNT_STARTED = 0 +DPHY_LOAD_BS_COUNT_NOT_STARTED = 1 +DPHY_LOAD_BS_COUNT_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_EN' +DPHY_PRBS_EN__enumvalues = { + 0: 'DPHY_PRBS_DISABLE', + 1: 'DPHY_PRBS_ENABLE', +} +DPHY_PRBS_DISABLE = 0 +DPHY_PRBS_ENABLE = 1 +DPHY_PRBS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_SEL' +DPHY_PRBS_SEL__enumvalues = { + 0: 'DPHY_PRBS7_SELECTED', + 1: 'DPHY_PRBS23_SELECTED', + 2: 'DPHY_PRBS11_SELECTED', +} +DPHY_PRBS7_SELECTED = 0 +DPHY_PRBS23_SELECTED = 1 +DPHY_PRBS11_SELECTED = 2 +DPHY_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_RX_FAST_TRAINING_CAPABLE' +DPHY_RX_FAST_TRAINING_CAPABLE__enumvalues = { + 0: 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 1: 'DPHY_FAST_TRAINING_CAPABLE', +} +DPHY_FAST_TRAINING_NOT_CAPABLE_0 = 0 +DPHY_FAST_TRAINING_CAPABLE = 1 +DPHY_RX_FAST_TRAINING_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SKEW_BYPASS' +DPHY_SKEW_BYPASS__enumvalues = { + 0: 'DPHY_WITH_SKEW', + 1: 'DPHY_NO_SKEW', +} +DPHY_WITH_SKEW = 0 +DPHY_NO_SKEW = 1 +DPHY_SKEW_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM' +DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM__enumvalues = { + 0: 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET', + 1: 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET', +} +DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET = 0 +DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET = 1 +DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SW_FAST_TRAINING_START' +DPHY_SW_FAST_TRAINING_START__enumvalues = { + 0: 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 1: 'DPHY_SW_FAST_TRAINING_STARTED', +} +DPHY_SW_FAST_TRAINING_NOT_STARTED = 0 +DPHY_SW_FAST_TRAINING_STARTED = 1 +DPHY_SW_FAST_TRAINING_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_TRAINING_PATTERN_SEL' +DPHY_TRAINING_PATTERN_SEL__enumvalues = { + 0: 'DPHY_TRAINING_PATTERN_1', + 1: 'DPHY_TRAINING_PATTERN_2', + 2: 'DPHY_TRAINING_PATTERN_3', + 3: 'DPHY_TRAINING_PATTERN_4', +} +DPHY_TRAINING_PATTERN_1 = 0 +DPHY_TRAINING_PATTERN_2 = 1 +DPHY_TRAINING_PATTERN_3 = 2 +DPHY_TRAINING_PATTERN_4 = 3 +DPHY_TRAINING_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMPONENT_DEPTH' +DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_COMPONENT_DEPTH_6BPC', + 1: 'DP_COMPONENT_DEPTH_8BPC', + 2: 'DP_COMPONENT_DEPTH_10BPC', + 3: 'DP_COMPONENT_DEPTH_12BPC', + 4: 'DP_COMPONENT_DEPTH_16BPC', +} +DP_COMPONENT_DEPTH_6BPC = 0 +DP_COMPONENT_DEPTH_8BPC = 1 +DP_COMPONENT_DEPTH_10BPC = 2 +DP_COMPONENT_DEPTH_12BPC = 3 +DP_COMPONENT_DEPTH_16BPC = 4 +DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMPRESSED_PIXEL_FORMAT' +DP_COMPRESSED_PIXEL_FORMAT__enumvalues = { + 0: 'DP_DSC_444_S422', + 1: 'DP_DSC_N422_N420', +} +DP_DSC_444_S422 = 0 +DP_DSC_N422_N420 = 1 +DP_COMPRESSED_PIXEL_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_8B10B_EXT_DISP' +DP_DPHY_8B10B_EXT_DISP__enumvalues = { + 0: 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 1: 'DP_DPHY_8B10B_EXT_DISP_ONE', +} +DP_DPHY_8B10B_EXT_DISP_ZERO = 0 +DP_DPHY_8B10B_EXT_DISP_ONE = 1 +DP_DPHY_8B10B_EXT_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK' +DP_DPHY_FAST_TRAINING_COMPLETE_ACK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_ACKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK' +DP_DPHY_FAST_TRAINING_COMPLETE_MASK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_MASKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN' +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 1: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', +} +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED = 0 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED = 1 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE' +DP_DPHY_HBR2_PATTERN_CONTROL_MODE__enumvalues = { + 0: 'DP_DPHY_HBR2_PASS_THROUGH', + 1: 'DP_DPHY_HBR2_PATTERN_1', + 2: 'DP_DPHY_HBR2_PATTERN_2_NEG', + 3: 'DP_DPHY_HBR2_PATTERN_3', + 6: 'DP_DPHY_HBR2_PATTERN_2_POS', +} +DP_DPHY_HBR2_PASS_THROUGH = 0 +DP_DPHY_HBR2_PATTERN_1 = 1 +DP_DPHY_HBR2_PATTERN_2_NEG = 2 +DP_DPHY_HBR2_PATTERN_3 = 3 +DP_DPHY_HBR2_PATTERN_2_POS = 6 +DP_DPHY_HBR2_PATTERN_CONTROL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_COMPLETE' +DP_LINK_TRAINING_COMPLETE__enumvalues = { + 0: 'DP_LINK_TRAINING_NOT_COMPLETE', + 1: 'DP_LINK_TRAINING_ALREADY_COMPLETE', +} +DP_LINK_TRAINING_NOT_COMPLETE = 0 +DP_LINK_TRAINING_ALREADY_COMPLETE = 1 +DP_LINK_TRAINING_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_SWITCH_MODE' +DP_LINK_TRAINING_SWITCH_MODE__enumvalues = { + 0: 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 1: 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', +} +DP_LINK_TRAINING_SWITCH_TO_IDLE = 0 +DP_LINK_TRAINING_SWITCH_TO_VIDEO = 1 +DP_LINK_TRAINING_SWITCH_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_ML_PHY_SEQ_MODE' +DP_ML_PHY_SEQ_MODE__enumvalues = { + 0: 'DP_ML_PHY_SEQ_LINE_NUM', + 1: 'DP_ML_PHY_SEQ_IMMEDIATE', +} +DP_ML_PHY_SEQ_LINE_NUM = 0 +DP_ML_PHY_SEQ_IMMEDIATE = 1 +DP_ML_PHY_SEQ_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_V_TIMING_OVERRIDE_EN' +DP_MSA_V_TIMING_OVERRIDE_EN__enumvalues = { + 0: 'MSA_V_TIMING_OVERRIDE_DISABLED', + 1: 'MSA_V_TIMING_OVERRIDE_ENABLED', +} +MSA_V_TIMING_OVERRIDE_DISABLED = 0 +MSA_V_TIMING_OVERRIDE_ENABLED = 1 +DP_MSA_V_TIMING_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_BLANK_CODE' +DP_MSE_BLANK_CODE__enumvalues = { + 0: 'DP_MSE_BLANK_CODE_SF_FILLED', + 1: 'DP_MSE_BLANK_CODE_ZERO_FILLED', +} +DP_MSE_BLANK_CODE_SF_FILLED = 0 +DP_MSE_BLANK_CODE_ZERO_FILLED = 1 +DP_MSE_BLANK_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_LINK_LINE' +DP_MSE_LINK_LINE__enumvalues = { + 0: 'DP_MSE_LINK_LINE_32_MTP_LONG', + 1: 'DP_MSE_LINK_LINE_64_MTP_LONG', + 2: 'DP_MSE_LINK_LINE_128_MTP_LONG', + 3: 'DP_MSE_LINK_LINE_256_MTP_LONG', +} +DP_MSE_LINK_LINE_32_MTP_LONG = 0 +DP_MSE_LINK_LINE_64_MTP_LONG = 1 +DP_MSE_LINK_LINE_128_MTP_LONG = 2 +DP_MSE_LINK_LINE_256_MTP_LONG = 3 +DP_MSE_LINK_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_TIMESTAMP_MODE' +DP_MSE_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 1: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', +} +DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE = 0 +DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE = 1 +DP_MSE_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_ZERO_ENCODER' +DP_MSE_ZERO_ENCODER__enumvalues = { + 0: 'DP_MSE_NOT_ZERO_FE_ENCODER', + 1: 'DP_MSE_ZERO_FE_ENCODER', +} +DP_MSE_NOT_ZERO_FE_ENCODER = 0 +DP_MSE_ZERO_FE_ENCODER = 1 +DP_MSE_ZERO_ENCODER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSO_NUM_OF_SST_LINKS' +DP_MSO_NUM_OF_SST_LINKS__enumvalues = { + 0: 'DP_MSO_ONE_SSTLINK', + 1: 'DP_MSO_TWO_SSTLINK', + 2: 'DP_MSO_FOUR_SSTLINK', +} +DP_MSO_ONE_SSTLINK = 0 +DP_MSO_TWO_SSTLINK = 1 +DP_MSO_FOUR_SSTLINK = 2 +DP_MSO_NUM_OF_SST_LINKS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_ENCODING' +DP_PIXEL_ENCODING__enumvalues = { + 0: 'DP_PIXEL_ENCODING_RGB_YCBCR444', + 1: 'DP_PIXEL_ENCODING_YCBCR422', + 2: 'DP_PIXEL_ENCODING_YCBCR420', + 3: 'DP_PIXEL_ENCODING_Y_ONLY', +} +DP_PIXEL_ENCODING_RGB_YCBCR444 = 0 +DP_PIXEL_ENCODING_YCBCR422 = 1 +DP_PIXEL_ENCODING_YCBCR420 = 2 +DP_PIXEL_ENCODING_Y_ONLY = 3 +DP_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_ENCODING_TYPE' +DP_PIXEL_ENCODING_TYPE__enumvalues = { + 0: 'DP_PIXEL_ENCODING_UNCOMPRESSED', + 1: 'DP_PIXEL_ENCODING_COMPRESSED', +} +DP_PIXEL_ENCODING_UNCOMPRESSED = 0 +DP_PIXEL_ENCODING_COMPRESSED = 1 +DP_PIXEL_ENCODING_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE' +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ = 0 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_PRIORITY' +DP_SEC_ASP_PRIORITY__enumvalues = { + 0: 'DP_SEC_ASP_LOW_PRIORITY', + 1: 'DP_SEC_ASP_HIGH_PRIORITY', +} +DP_SEC_ASP_LOW_PRIORITY = 0 +DP_SEC_ASP_HIGH_PRIORITY = 1 +DP_SEC_ASP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_AUDIO_MUTE' +DP_SEC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SEC_AUDIO_MUTE_HW_CTRL', + 1: 'DP_SEC_AUDIO_MUTE_SW_CTRL', +} +DP_SEC_AUDIO_MUTE_HW_CTRL = 0 +DP_SEC_AUDIO_MUTE_SW_CTRL = 1 +DP_SEC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_COLLISION_ACK' +DP_SEC_COLLISION_ACK__enumvalues = { + 0: 'DP_SEC_COLLISION_ACK_NO_EFFECT', + 1: 'DP_SEC_COLLISION_ACK_CLR_FLAG', +} +DP_SEC_COLLISION_ACK_NO_EFFECT = 0 +DP_SEC_COLLISION_ACK_CLR_FLAG = 1 +DP_SEC_COLLISION_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP0_PRIORITY' +DP_SEC_GSP0_PRIORITY__enumvalues = { + 0: 'SEC_GSP0_PRIORITY_LOW', + 1: 'SEC_GSP0_PRIORITY_HIGH', +} +SEC_GSP0_PRIORITY_LOW = 0 +SEC_GSP0_PRIORITY_HIGH = 1 +DP_SEC_GSP0_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND' +DP_SEC_GSP_SEND__enumvalues = { + 0: 'NOT_SENT', + 1: 'FORCE_SENT', +} +NOT_SENT = 0 +FORCE_SENT = 1 +DP_SEC_GSP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_ANY_LINE' +DP_SEC_GSP_SEND_ANY_LINE__enumvalues = { + 0: 'SEND_AT_LINK_NUMBER', + 1: 'SEND_AT_EARLIEST_TIME', +} +SEND_AT_LINK_NUMBER = 0 +SEND_AT_EARLIEST_TIME = 1 +DP_SEC_GSP_SEND_ANY_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP_SEND_PPS' +DP_SEC_GSP_SEND_PPS__enumvalues = { + 0: 'SEND_NORMAL_PACKET', + 1: 'SEND_PPS_PACKET', +} +SEND_NORMAL_PACKET = 0 +SEND_PPS_PACKET = 1 +DP_SEC_GSP_SEND_PPS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_LINE_REFERENCE' +DP_SEC_LINE_REFERENCE__enumvalues = { + 0: 'REFER_TO_DP_SOF', + 1: 'REFER_TO_OTG_SOF', +} +REFER_TO_DP_SOF = 0 +REFER_TO_OTG_SOF = 1 +DP_SEC_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_TIMESTAMP_MODE' +DP_SEC_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', + 1: 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', +} +DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE = 0 +DP_SEC_TIMESTAMP_AUTO_CALC_MODE = 1 +DP_SEC_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OUTPUT_PIXEL_PER_CYCLE' +DP_STEER_OUTPUT_PIXEL_PER_CYCLE__enumvalues = { + 0: 'DP_STEER_1_PIX_PER_CYCLE', + 1: 'DP_STEER_2_PIX_PER_CYCLE', + 2: 'DP_STEER_4_PIX_PER_CYCLE', + 3: 'DP_STEER_8_PIX_PER_CYCLE', +} +DP_STEER_1_PIX_PER_CYCLE = 0 +DP_STEER_2_PIX_PER_CYCLE = 1 +DP_STEER_4_PIX_PER_CYCLE = 2 +DP_STEER_8_PIX_PER_CYCLE = 3 +DP_STEER_OUTPUT_PIXEL_PER_CYCLE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_ACK' +DP_STEER_OVERFLOW_ACK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_STEER_OVERFLOW_ACK_NO_EFFECT = 0 +DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_STEER_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_MASK' +DP_STEER_OVERFLOW_MASK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_MASKED', + 1: 'DP_STEER_OVERFLOW_UNMASK', +} +DP_STEER_OVERFLOW_MASKED = 0 +DP_STEER_OVERFLOW_UNMASK = 1 +DP_STEER_OVERFLOW_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SYNC_POLARITY' +DP_SYNC_POLARITY__enumvalues = { + 0: 'DP_SYNC_POLARITY_ACTIVE_HIGH', + 1: 'DP_SYNC_POLARITY_ACTIVE_LOW', +} +DP_SYNC_POLARITY_ACTIVE_HIGH = 0 +DP_SYNC_POLARITY_ACTIVE_LOW = 1 +DP_SYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_TU_OVERFLOW_ACK' +DP_TU_OVERFLOW_ACK__enumvalues = { + 0: 'DP_TU_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_TU_OVERFLOW_ACK_NO_EFFECT = 0 +DP_TU_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_TU_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_UDI_LANES' +DP_UDI_LANES__enumvalues = { + 0: 'DP_UDI_1_LANE', + 1: 'DP_UDI_2_LANES', + 2: 'DP_UDI_LANES_RESERVED', + 3: 'DP_UDI_4_LANES', +} +DP_UDI_1_LANE = 0 +DP_UDI_2_LANES = 1 +DP_UDI_LANES_RESERVED = 2 +DP_UDI_4_LANES = 3 +DP_UDI_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_ENHANCED_FRAME_MODE' +DP_VID_ENHANCED_FRAME_MODE__enumvalues = { + 0: 'VID_NORMAL_FRAME_MODE', + 1: 'VID_ENHANCED_MODE', +} +VID_NORMAL_FRAME_MODE = 0 +VID_ENHANCED_MODE = 1 +DP_VID_ENHANCED_FRAME_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_DOUBLE_BUFFER_MODE' +DP_VID_M_N_DOUBLE_BUFFER_MODE__enumvalues = { + 0: 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 1: 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', +} +DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE = 0 +DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START = 1 +DP_VID_M_N_DOUBLE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_GEN_EN' +DP_VID_M_N_GEN_EN__enumvalues = { + 0: 'DP_VID_M_N_PROGRAMMED_VIA_REG', + 1: 'DP_VID_M_N_CALC_AUTO', +} +DP_VID_M_N_PROGRAMMED_VIA_REG = 0 +DP_VID_M_N_CALC_AUTO = 1 +DP_VID_M_N_GEN_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_N_INTERVAL' +DP_VID_N_INTERVAL__enumvalues = { + 0: 'DP_VID_1X_Nvid', + 1: 'DP_VID_2X_Nvid', + 2: 'DP_VID_4X_Nvid', + 3: 'DP_VID_8X_Nvid', +} +DP_VID_1X_Nvid = 0 +DP_VID_2X_Nvid = 1 +DP_VID_4X_Nvid = 2 +DP_VID_8X_Nvid = 3 +DP_VID_N_INTERVAL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_ACK' +DP_VID_STREAM_DISABLE_ACK__enumvalues = { + 0: 'ID_STREAM_DISABLE_NO_ACK', + 1: 'ID_STREAM_DISABLE_ACKED', +} +ID_STREAM_DISABLE_NO_ACK = 0 +ID_STREAM_DISABLE_ACKED = 1 +DP_VID_STREAM_DISABLE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_MASK' +DP_VID_STREAM_DISABLE_MASK__enumvalues = { + 0: 'VID_STREAM_DISABLE_MASKED', + 1: 'VID_STREAM_DISABLE_UNMASK', +} +VID_STREAM_DISABLE_MASKED = 0 +VID_STREAM_DISABLE_UNMASK = 1 +DP_VID_STREAM_DISABLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DIS_DEFER' +DP_VID_STREAM_DIS_DEFER__enumvalues = { + 0: 'DP_VID_STREAM_DIS_NO_DEFER', + 1: 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 2: 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', +} +DP_VID_STREAM_DIS_NO_DEFER = 0 +DP_VID_STREAM_DIS_DEFER_TO_HBLANK = 1 +DP_VID_STREAM_DIS_DEFER_TO_VBLANK = 2 +DP_VID_STREAM_DIS_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_VBID_FIELD_POL' +DP_VID_VBID_FIELD_POL__enumvalues = { + 0: 'DP_VID_VBID_FIELD_POL_NORMAL', + 1: 'DP_VID_VBID_FIELD_POL_INV', +} +DP_VID_VBID_FIELD_POL_NORMAL = 0 +DP_VID_VBID_FIELD_POL_INV = 1 +DP_VID_VBID_FIELD_POL = ctypes.c_uint32 # enum + +# values for enumeration 'FEC_ACTIVE_STATUS' +FEC_ACTIVE_STATUS__enumvalues = { + 0: 'DPHY_FEC_NOT_ACTIVE', + 1: 'DPHY_FEC_ACTIVE', +} +DPHY_FEC_NOT_ACTIVE = 0 +DPHY_FEC_ACTIVE = 1 +FEC_ACTIVE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_HPD_SELECT' +DIG_BE_CNTL_HPD_SELECT__enumvalues = { + 0: 'DIG_BE_CNTL_HPD1', + 1: 'DIG_BE_CNTL_HPD2', + 2: 'DIG_BE_CNTL_HPD3', + 3: 'DIG_BE_CNTL_HPD4', + 4: 'DIG_BE_CNTL_NO_HPD', +} +DIG_BE_CNTL_HPD1 = 0 +DIG_BE_CNTL_HPD2 = 1 +DIG_BE_CNTL_HPD3 = 2 +DIG_BE_CNTL_HPD4 = 3 +DIG_BE_CNTL_NO_HPD = 4 +DIG_BE_CNTL_HPD_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_MODE' +DIG_BE_CNTL_MODE__enumvalues = { + 0: 'DIG_BE_DP_SST_MODE', + 1: 'DIG_BE_RESERVED1', + 2: 'DIG_BE_TMDS_DVI_MODE', + 3: 'DIG_BE_TMDS_HDMI_MODE', + 4: 'DIG_BE_RESERVED4', + 5: 'DIG_BE_DP_MST_MODE', + 6: 'DIG_BE_RESERVED2', + 7: 'DIG_BE_RESERVED3', +} +DIG_BE_DP_SST_MODE = 0 +DIG_BE_RESERVED1 = 1 +DIG_BE_TMDS_DVI_MODE = 2 +DIG_BE_TMDS_HDMI_MODE = 3 +DIG_BE_RESERVED4 = 4 +DIG_BE_DP_MST_MODE = 5 +DIG_BE_RESERVED2 = 6 +DIG_BE_RESERVED3 = 7 +DIG_BE_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_DIGITAL_BYPASS_ENABLE' +DIG_DIGITAL_BYPASS_ENABLE__enumvalues = { + 0: 'DIG_DIGITAL_BYPASS_OFF', + 1: 'DIG_DIGITAL_BYPASS_ON', +} +DIG_DIGITAL_BYPASS_OFF = 0 +DIG_DIGITAL_BYPASS_ON = 1 +DIG_DIGITAL_BYPASS_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_DIGITAL_BYPASS_SEL' +DIG_DIGITAL_BYPASS_SEL__enumvalues = { + 0: 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 1: 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 2: 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 3: 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 4: 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 5: 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 6: 'DIG_DIGITAL_BYPASS_SEL_ALPHA', +} +DIG_DIGITAL_BYPASS_SEL_BYPASS = 0 +DIG_DIGITAL_BYPASS_SEL_36BPP = 1 +DIG_DIGITAL_BYPASS_SEL_48BPP_LSB = 2 +DIG_DIGITAL_BYPASS_SEL_48BPP_MSB = 3 +DIG_DIGITAL_BYPASS_SEL_10BPP_LSB = 4 +DIG_DIGITAL_BYPASS_SEL_12BPC_LSB = 5 +DIG_DIGITAL_BYPASS_SEL_ALPHA = 6 +DIG_DIGITAL_BYPASS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_SOURCE_SELECT' +DIG_FE_CNTL_SOURCE_SELECT__enumvalues = { + 0: 'DIG_FE_SOURCE_FROM_OTG0', + 1: 'DIG_FE_SOURCE_FROM_OTG1', + 2: 'DIG_FE_SOURCE_FROM_OTG2', + 3: 'DIG_FE_SOURCE_FROM_OTG3', + 4: 'DIG_FE_SOURCE_RESERVED', +} +DIG_FE_SOURCE_FROM_OTG0 = 0 +DIG_FE_SOURCE_FROM_OTG1 = 1 +DIG_FE_SOURCE_FROM_OTG2 = 2 +DIG_FE_SOURCE_FROM_OTG3 = 3 +DIG_FE_SOURCE_RESERVED = 4 +DIG_FE_CNTL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_STEREOSYNC_SELECT' +DIG_FE_CNTL_STEREOSYNC_SELECT__enumvalues = { + 0: 'DIG_FE_STEREOSYNC_FROM_OTG0', + 1: 'DIG_FE_STEREOSYNC_FROM_OTG1', + 2: 'DIG_FE_STEREOSYNC_FROM_OTG2', + 3: 'DIG_FE_STEREOSYNC_FROM_OTG3', + 4: 'DIG_FE_STEREOSYNC_RESERVED', +} +DIG_FE_STEREOSYNC_FROM_OTG0 = 0 +DIG_FE_STEREOSYNC_FROM_OTG1 = 1 +DIG_FE_STEREOSYNC_FROM_OTG2 = 2 +DIG_FE_STEREOSYNC_FROM_OTG3 = 3 +DIG_FE_STEREOSYNC_RESERVED = 4 +DIG_FE_CNTL_STEREOSYNC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX' +DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', + 1: 'DIG_FIFO_FORCE_RECOMP_MINMAX', +} +DIG_FIFO_NOT_FORCE_RECOMP_MINMAX = 0 +DIG_FIFO_FORCE_RECOMP_MINMAX = 1 +DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL' +DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL__enumvalues = { + 0: 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 1: 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', +} +DIG_FIFO_USE_OVERWRITE_LEVEL = 0 +DIG_FIFO_USE_CAL_AVERAGE_LEVEL = 1 +DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_FORCE_RECAL_AVERAGE' +DIG_FIFO_FORCE_RECAL_AVERAGE__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 1: 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', +} +DIG_FIFO_NOT_FORCE_RECAL_AVERAGE = 0 +DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL = 1 +DIG_FIFO_FORCE_RECAL_AVERAGE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_OUTPUT_PIXEL_PER_CYCLE' +DIG_FIFO_OUTPUT_PIXEL_PER_CYCLE__enumvalues = { + 0: 'DIG_FIFO_1_PIX_PER_CYCLE', + 1: 'DIG_FIFO_2_PIX_PER_CYCLE', + 2: 'DIG_FIFO_4_PIX_PER_CYCLE', + 3: 'DIG_FIFO_8_PIX_PER_CYCLE', +} +DIG_FIFO_1_PIX_PER_CYCLE = 0 +DIG_FIFO_2_PIX_PER_CYCLE = 1 +DIG_FIFO_4_PIX_PER_CYCLE = 2 +DIG_FIFO_8_PIX_PER_CYCLE = 3 +DIG_FIFO_OUTPUT_PIXEL_PER_CYCLE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR' +DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR__enumvalues = { + 0: 'DIG_FIFO_NO_ERROR_OCCURRED', + 1: 'DIG_FIFO_UNDERFLOW_OCCURRED', + 2: 'DIG_FIFO_OVERFLOW_OCCURRED', +} +DIG_FIFO_NO_ERROR_OCCURRED = 0 +DIG_FIFO_UNDERFLOW_OCCURRED = 1 +DIG_FIFO_OVERFLOW_OCCURRED = 2 +DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_READ_CLOCK_SRC' +DIG_FIFO_READ_CLOCK_SRC__enumvalues = { + 0: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 1: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', +} +DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG = 0 +DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE = 1 +DIG_FIFO_READ_CLOCK_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_MODE' +DIG_MODE__enumvalues = { + 0: 'DP_SST_MODE', + 1: 'RESERVED1', + 2: 'TMDS_DVI_MODE', + 3: 'TMDS_HDMI_MODE', + 4: 'RESERVED4', + 5: 'DP_MST_MODE', + 6: 'RESERVED2', + 7: 'RESERVED3', +} +DP_SST_MODE = 0 +RESERVED1 = 1 +TMDS_DVI_MODE = 2 +TMDS_HDMI_MODE = 3 +RESERVED4 = 4 +DP_MST_MODE = 5 +RESERVED2 = 6 +RESERVED3 = 7 +DIG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_CNTL_LINK_SEL' +DIG_OUTPUT_CRC_CNTL_LINK_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_ON_LINK0', + 1: 'DIG_OUTPUT_CRC_ON_LINK1', +} +DIG_OUTPUT_CRC_ON_LINK0 = 0 +DIG_OUTPUT_CRC_ON_LINK1 = 1 +DIG_OUTPUT_CRC_CNTL_LINK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_DATA_SEL' +DIG_OUTPUT_CRC_DATA_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_FOR_FULLFRAME', + 1: 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', + 2: 'DIG_OUTPUT_CRC_FOR_VBI', + 3: 'DIG_OUTPUT_CRC_FOR_AUDIO', +} +DIG_OUTPUT_CRC_FOR_FULLFRAME = 0 +DIG_OUTPUT_CRC_FOR_ACTIVEONLY = 1 +DIG_OUTPUT_CRC_FOR_VBI = 2 +DIG_OUTPUT_CRC_FOR_AUDIO = 3 +DIG_OUTPUT_CRC_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_RANDOM_PATTERN_SEED_RAN_PAT' +DIG_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 1: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', +} +DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS = 0 +DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH = 1 +DIG_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN' +DIG_TEST_PATTERN_EXTERNAL_RESET_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 1: 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', +} +DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE = 0 +DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG = 1 +DIG_TEST_PATTERN_EXTERNAL_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL' +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL__enumvalues = { + 0: 'DIG_10BIT_TEST_PATTERN', + 1: 'DIG_ALTERNATING_TEST_PATTERN', +} +DIG_10BIT_TEST_PATTERN = 0 +DIG_ALTERNATING_TEST_PATTERN = 1 +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN' +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_NORMAL', + 1: 'DIG_TEST_PATTERN_RANDOM', +} +DIG_TEST_PATTERN_NORMAL = 0 +DIG_TEST_PATTERN_RANDOM = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET' +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_ENABLED', + 1: 'DIG_RANDOM_PATTERN_RESETED', +} +DIG_RANDOM_PATTERN_ENABLED = 0 +DIG_RANDOM_PATTERN_RESETED = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN' +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_IN_NORMAL_OPERATION', + 1: 'DIG_IN_DEBUG_MODE', +} +DIG_IN_NORMAL_OPERATION = 0 +DIG_IN_DEBUG_MODE = 1 +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACP_SEND' +HDMI_ACP_SEND__enumvalues = { + 0: 'HDMI_ACP_NOT_SEND', + 1: 'HDMI_ACP_PKT_SEND', +} +HDMI_ACP_NOT_SEND = 0 +HDMI_ACP_PKT_SEND = 1 +HDMI_ACP_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_AUDIO_PRIORITY' +HDMI_ACR_AUDIO_PRIORITY__enumvalues = { + 0: 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 1: 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', +} +HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE = 0 +HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT = 1 +HDMI_ACR_AUDIO_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_CONT' +HDMI_ACR_CONT__enumvalues = { + 0: 'HDMI_ACR_CONT_DISABLE', + 1: 'HDMI_ACR_CONT_ENABLE', +} +HDMI_ACR_CONT_DISABLE = 0 +HDMI_ACR_CONT_ENABLE = 1 +HDMI_ACR_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_N_MULTIPLE' +HDMI_ACR_N_MULTIPLE__enumvalues = { + 0: 'HDMI_ACR_0_MULTIPLE_RESERVED', + 1: 'HDMI_ACR_1_MULTIPLE', + 2: 'HDMI_ACR_2_MULTIPLE', + 3: 'HDMI_ACR_3_MULTIPLE_RESERVED', + 4: 'HDMI_ACR_4_MULTIPLE', + 5: 'HDMI_ACR_5_MULTIPLE_RESERVED', + 6: 'HDMI_ACR_6_MULTIPLE_RESERVED', + 7: 'HDMI_ACR_7_MULTIPLE_RESERVED', +} +HDMI_ACR_0_MULTIPLE_RESERVED = 0 +HDMI_ACR_1_MULTIPLE = 1 +HDMI_ACR_2_MULTIPLE = 2 +HDMI_ACR_3_MULTIPLE_RESERVED = 3 +HDMI_ACR_4_MULTIPLE = 4 +HDMI_ACR_5_MULTIPLE_RESERVED = 5 +HDMI_ACR_6_MULTIPLE_RESERVED = 6 +HDMI_ACR_7_MULTIPLE_RESERVED = 7 +HDMI_ACR_N_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SELECT' +HDMI_ACR_SELECT__enumvalues = { + 0: 'HDMI_ACR_SELECT_HW', + 1: 'HDMI_ACR_SELECT_32K', + 2: 'HDMI_ACR_SELECT_44K', + 3: 'HDMI_ACR_SELECT_48K', +} +HDMI_ACR_SELECT_HW = 0 +HDMI_ACR_SELECT_32K = 1 +HDMI_ACR_SELECT_44K = 2 +HDMI_ACR_SELECT_48K = 3 +HDMI_ACR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SEND' +HDMI_ACR_SEND__enumvalues = { + 0: 'HDMI_ACR_NOT_SEND', + 1: 'HDMI_ACR_PKT_SEND', +} +HDMI_ACR_NOT_SEND = 0 +HDMI_ACR_PKT_SEND = 1 +HDMI_ACR_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SOURCE' +HDMI_ACR_SOURCE__enumvalues = { + 0: 'HDMI_ACR_SOURCE_HW', + 1: 'HDMI_ACR_SOURCE_SW', +} +HDMI_ACR_SOURCE_HW = 0 +HDMI_ACR_SOURCE_SW = 1 +HDMI_ACR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_DELAY_EN' +HDMI_AUDIO_DELAY_EN__enumvalues = { + 0: 'HDMI_AUDIO_DELAY_DISABLE', + 1: 'HDMI_AUDIO_DELAY_58CLK', + 2: 'HDMI_AUDIO_DELAY_56CLK', + 3: 'HDMI_AUDIO_DELAY_RESERVED', +} +HDMI_AUDIO_DELAY_DISABLE = 0 +HDMI_AUDIO_DELAY_58CLK = 1 +HDMI_AUDIO_DELAY_56CLK = 2 +HDMI_AUDIO_DELAY_RESERVED = 3 +HDMI_AUDIO_DELAY_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_CONT' +HDMI_AUDIO_INFO_CONT__enumvalues = { + 0: 'HDMI_AUDIO_INFO_CONT_DISABLE', + 1: 'HDMI_AUDIO_INFO_CONT_ENABLE', +} +HDMI_AUDIO_INFO_CONT_DISABLE = 0 +HDMI_AUDIO_INFO_CONT_ENABLE = 1 +HDMI_AUDIO_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_SEND' +HDMI_AUDIO_INFO_SEND__enumvalues = { + 0: 'HDMI_AUDIO_INFO_NOT_SEND', + 1: 'HDMI_AUDIO_INFO_PKT_SEND', +} +HDMI_AUDIO_INFO_NOT_SEND = 0 +HDMI_AUDIO_INFO_PKT_SEND = 1 +HDMI_AUDIO_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_CLOCK_CHANNEL_RATE' +HDMI_CLOCK_CHANNEL_RATE__enumvalues = { + 0: 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 1: 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', +} +HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE = 0 +HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE = 1 +HDMI_CLOCK_CHANNEL_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DATA_SCRAMBLE_EN' +HDMI_DATA_SCRAMBLE_EN__enumvalues = { + 0: 'HDMI_DATA_SCRAMBLE_DISABLE', + 1: 'HDMI_DATA_SCRAMBLE_ENABLE', +} +HDMI_DATA_SCRAMBLE_DISABLE = 0 +HDMI_DATA_SCRAMBLE_ENABLE = 1 +HDMI_DATA_SCRAMBLE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEEP_COLOR_DEPTH' +HDMI_DEEP_COLOR_DEPTH__enumvalues = { + 0: 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 1: 'HDMI_DEEP_COLOR_DEPTH_30BPP', + 2: 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 3: 'HDMI_DEEP_COLOR_DEPTH_48BPP', +} +HDMI_DEEP_COLOR_DEPTH_24BPP = 0 +HDMI_DEEP_COLOR_DEPTH_30BPP = 1 +HDMI_DEEP_COLOR_DEPTH_36BPP = 2 +HDMI_DEEP_COLOR_DEPTH_48BPP = 3 +HDMI_DEEP_COLOR_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEFAULT_PAHSE' +HDMI_DEFAULT_PAHSE__enumvalues = { + 0: 'HDMI_DEFAULT_PHASE_IS_0', + 1: 'HDMI_DEFAULT_PHASE_IS_1', +} +HDMI_DEFAULT_PHASE_IS_0 = 0 +HDMI_DEFAULT_PHASE_IS_1 = 1 +HDMI_DEFAULT_PAHSE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_ACK' +HDMI_ERROR_ACK__enumvalues = { + 0: 'HDMI_ERROR_ACK_INT', + 1: 'HDMI_ERROR_NOT_ACK', +} +HDMI_ERROR_ACK_INT = 0 +HDMI_ERROR_NOT_ACK = 1 +HDMI_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_MASK' +HDMI_ERROR_MASK__enumvalues = { + 0: 'HDMI_ERROR_MASK_INT', + 1: 'HDMI_ERROR_NOT_MASK', +} +HDMI_ERROR_MASK_INT = 0 +HDMI_ERROR_NOT_MASK = 1 +HDMI_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE' +HDMI_GC_AVMUTE__enumvalues = { + 0: 'HDMI_GC_AVMUTE_SET', + 1: 'HDMI_GC_AVMUTE_UNSET', +} +HDMI_GC_AVMUTE_SET = 0 +HDMI_GC_AVMUTE_UNSET = 1 +HDMI_GC_AVMUTE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE_CONT' +HDMI_GC_AVMUTE_CONT__enumvalues = { + 0: 'HDMI_GC_AVMUTE_CONT_DISABLE', + 1: 'HDMI_GC_AVMUTE_CONT_ENABLE', +} +HDMI_GC_AVMUTE_CONT_DISABLE = 0 +HDMI_GC_AVMUTE_CONT_ENABLE = 1 +HDMI_GC_AVMUTE_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_CONT' +HDMI_GC_CONT__enumvalues = { + 0: 'HDMI_GC_CONT_DISABLE', + 1: 'HDMI_GC_CONT_ENABLE', +} +HDMI_GC_CONT_DISABLE = 0 +HDMI_GC_CONT_ENABLE = 1 +HDMI_GC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_SEND' +HDMI_GC_SEND__enumvalues = { + 0: 'HDMI_GC_NOT_SEND', + 1: 'HDMI_GC_PKT_SEND', +} +HDMI_GC_NOT_SEND = 0 +HDMI_GC_PKT_SEND = 1 +HDMI_GC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_CONT' +HDMI_GENERIC_CONT__enumvalues = { + 0: 'HDMI_GENERIC_CONT_DISABLE', + 1: 'HDMI_GENERIC_CONT_ENABLE', +} +HDMI_GENERIC_CONT_DISABLE = 0 +HDMI_GENERIC_CONT_ENABLE = 1 +HDMI_GENERIC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC_SEND' +HDMI_GENERIC_SEND__enumvalues = { + 0: 'HDMI_GENERIC_NOT_SEND', + 1: 'HDMI_GENERIC_PKT_SEND', +} +HDMI_GENERIC_NOT_SEND = 0 +HDMI_GENERIC_PKT_SEND = 1 +HDMI_GENERIC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_CONT' +HDMI_ISRC_CONT__enumvalues = { + 0: 'HDMI_ISRC_CONT_DISABLE', + 1: 'HDMI_ISRC_CONT_ENABLE', +} +HDMI_ISRC_CONT_DISABLE = 0 +HDMI_ISRC_CONT_ENABLE = 1 +HDMI_ISRC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_SEND' +HDMI_ISRC_SEND__enumvalues = { + 0: 'HDMI_ISRC_NOT_SEND', + 1: 'HDMI_ISRC_PKT_SEND', +} +HDMI_ISRC_NOT_SEND = 0 +HDMI_ISRC_PKT_SEND = 1 +HDMI_ISRC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_KEEPOUT_MODE' +HDMI_KEEPOUT_MODE__enumvalues = { + 0: 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 1: 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', +} +HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC = 0 +HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC = 1 +HDMI_KEEPOUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_METADATA_ENABLE' +HDMI_METADATA_ENABLE__enumvalues = { + 0: 'HDMI_METADATA_NOT_SEND', + 1: 'HDMI_METADATA_PKT_SEND', +} +HDMI_METADATA_NOT_SEND = 0 +HDMI_METADATA_PKT_SEND = 1 +HDMI_METADATA_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_CONT' +HDMI_MPEG_INFO_CONT__enumvalues = { + 0: 'HDMI_MPEG_INFO_CONT_DISABLE', + 1: 'HDMI_MPEG_INFO_CONT_ENABLE', +} +HDMI_MPEG_INFO_CONT_DISABLE = 0 +HDMI_MPEG_INFO_CONT_ENABLE = 1 +HDMI_MPEG_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_SEND' +HDMI_MPEG_INFO_SEND__enumvalues = { + 0: 'HDMI_MPEG_INFO_NOT_SEND', + 1: 'HDMI_MPEG_INFO_PKT_SEND', +} +HDMI_MPEG_INFO_NOT_SEND = 0 +HDMI_MPEG_INFO_PKT_SEND = 1 +HDMI_MPEG_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NO_EXTRA_NULL_PACKET_FILLED' +HDMI_NO_EXTRA_NULL_PACKET_FILLED__enumvalues = { + 0: 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', + 1: 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', +} +HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE = 0 +HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE = 1 +HDMI_NO_EXTRA_NULL_PACKET_FILLED = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NULL_SEND' +HDMI_NULL_SEND__enumvalues = { + 0: 'HDMI_NULL_NOT_SEND', + 1: 'HDMI_NULL_PKT_SEND', +} +HDMI_NULL_NOT_SEND = 0 +HDMI_NULL_PKT_SEND = 1 +HDMI_NULL_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_GEN_VERSION' +HDMI_PACKET_GEN_VERSION__enumvalues = { + 0: 'HDMI_PACKET_GEN_VERSION_OLD', + 1: 'HDMI_PACKET_GEN_VERSION_NEW', +} +HDMI_PACKET_GEN_VERSION_OLD = 0 +HDMI_PACKET_GEN_VERSION_NEW = 1 +HDMI_PACKET_GEN_VERSION = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_LINE_REFERENCE' +HDMI_PACKET_LINE_REFERENCE__enumvalues = { + 0: 'HDMI_PKT_LINE_REF_VSYNC', + 1: 'HDMI_PKT_LINE_REF_OTGSOF', +} +HDMI_PKT_LINE_REF_VSYNC = 0 +HDMI_PKT_LINE_REF_OTGSOF = 1 +HDMI_PACKET_LINE_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKING_PHASE_OVERRIDE' +HDMI_PACKING_PHASE_OVERRIDE__enumvalues = { + 0: 'HDMI_PACKING_PHASE_SET_BY_HW', + 1: 'HDMI_PACKING_PHASE_SET_BY_SW', +} +HDMI_PACKING_PHASE_SET_BY_HW = 0 +HDMI_PACKING_PHASE_SET_BY_SW = 1 +HDMI_PACKING_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT' +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 1: 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', +} +LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS = 0 +LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH = 1 +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_COLOR_FORMAT' +TMDS_COLOR_FORMAT__enumvalues = { + 0: 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 1: 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 2: 'TMDS_COLOR_FORMAT_DUAL30BPP', + 3: 'TMDS_COLOR_FORMAT_RESERVED', +} +TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP = 0 +TMDS_COLOR_FORMAT_TWIN30BPP_LSB = 1 +TMDS_COLOR_FORMAT_DUAL30BPP = 2 +TMDS_COLOR_FORMAT_RESERVED = 3 +TMDS_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_INVERT' +TMDS_CTL0_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL0_DATA_NORMAL', + 1: 'TMDS_CTL0_DATA_INVERT_EN', +} +TMDS_CTL0_DATA_NORMAL = 0 +TMDS_CTL0_DATA_INVERT_EN = 1 +TMDS_CTL0_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_MODULATION' +TMDS_CTL0_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL0_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL0_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL0_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL0_DATA_MODULATION_BIT2', +} +TMDS_CTL0_DATA_MODULATION_DISABLE = 0 +TMDS_CTL0_DATA_MODULATION_BIT0 = 1 +TMDS_CTL0_DATA_MODULATION_BIT1 = 2 +TMDS_CTL0_DATA_MODULATION_BIT2 = 3 +TMDS_CTL0_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_SEL' +TMDS_CTL0_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL0_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL0_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL0_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL0_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 7: 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', +} +TMDS_CTL0_DATA_SEL0_RESERVED = 0 +TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL0_DATA_SEL2_VSYNC = 2 +TMDS_CTL0_DATA_SEL3_RESERVED = 3 +TMDS_CTL0_DATA_SEL4_HSYNC = 4 +TMDS_CTL0_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL0_DATA_SEL8_RANDOM_DATA = 6 +TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA = 7 +TMDS_CTL0_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_PATTERN_OUT_EN' +TMDS_CTL0_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL0_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL0_PATTERN_OUT_ENABLE', +} +TMDS_CTL0_PATTERN_OUT_DISABLE = 0 +TMDS_CTL0_PATTERN_OUT_ENABLE = 1 +TMDS_CTL0_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_INVERT' +TMDS_CTL1_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL1_DATA_NORMAL', + 1: 'TMDS_CTL1_DATA_INVERT_EN', +} +TMDS_CTL1_DATA_NORMAL = 0 +TMDS_CTL1_DATA_INVERT_EN = 1 +TMDS_CTL1_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_MODULATION' +TMDS_CTL1_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL1_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL1_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL1_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL1_DATA_MODULATION_BIT2', +} +TMDS_CTL1_DATA_MODULATION_DISABLE = 0 +TMDS_CTL1_DATA_MODULATION_BIT0 = 1 +TMDS_CTL1_DATA_MODULATION_BIT1 = 2 +TMDS_CTL1_DATA_MODULATION_BIT2 = 3 +TMDS_CTL1_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_SEL' +TMDS_CTL1_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL1_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL1_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL1_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL1_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL1_DATA_SEL0_RESERVED = 0 +TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL1_DATA_SEL2_VSYNC = 2 +TMDS_CTL1_DATA_SEL3_RESERVED = 3 +TMDS_CTL1_DATA_SEL4_HSYNC = 4 +TMDS_CTL1_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL1_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL1_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL1_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_PATTERN_OUT_EN' +TMDS_CTL1_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL1_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL1_PATTERN_OUT_ENABLE', +} +TMDS_CTL1_PATTERN_OUT_DISABLE = 0 +TMDS_CTL1_PATTERN_OUT_ENABLE = 1 +TMDS_CTL1_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_INVERT' +TMDS_CTL2_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL2_DATA_NORMAL', + 1: 'TMDS_CTL2_DATA_INVERT_EN', +} +TMDS_CTL2_DATA_NORMAL = 0 +TMDS_CTL2_DATA_INVERT_EN = 1 +TMDS_CTL2_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_MODULATION' +TMDS_CTL2_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL2_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL2_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL2_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL2_DATA_MODULATION_BIT2', +} +TMDS_CTL2_DATA_MODULATION_DISABLE = 0 +TMDS_CTL2_DATA_MODULATION_BIT0 = 1 +TMDS_CTL2_DATA_MODULATION_BIT1 = 2 +TMDS_CTL2_DATA_MODULATION_BIT2 = 3 +TMDS_CTL2_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_SEL' +TMDS_CTL2_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL2_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL2_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL2_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL2_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL2_DATA_SEL0_RESERVED = 0 +TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL2_DATA_SEL2_VSYNC = 2 +TMDS_CTL2_DATA_SEL3_RESERVED = 3 +TMDS_CTL2_DATA_SEL4_HSYNC = 4 +TMDS_CTL2_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL2_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL2_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL2_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_PATTERN_OUT_EN' +TMDS_CTL2_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL2_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL2_PATTERN_OUT_ENABLE', +} +TMDS_CTL2_PATTERN_OUT_DISABLE = 0 +TMDS_CTL2_PATTERN_OUT_ENABLE = 1 +TMDS_CTL2_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_INVERT' +TMDS_CTL3_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL3_DATA_NORMAL', + 1: 'TMDS_CTL3_DATA_INVERT_EN', +} +TMDS_CTL3_DATA_NORMAL = 0 +TMDS_CTL3_DATA_INVERT_EN = 1 +TMDS_CTL3_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_MODULATION' +TMDS_CTL3_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL3_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL3_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL3_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL3_DATA_MODULATION_BIT2', +} +TMDS_CTL3_DATA_MODULATION_DISABLE = 0 +TMDS_CTL3_DATA_MODULATION_BIT0 = 1 +TMDS_CTL3_DATA_MODULATION_BIT1 = 2 +TMDS_CTL3_DATA_MODULATION_BIT2 = 3 +TMDS_CTL3_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_SEL' +TMDS_CTL3_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL3_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL3_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL3_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL3_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL3_DATA_SEL0_RESERVED = 0 +TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL3_DATA_SEL2_VSYNC = 2 +TMDS_CTL3_DATA_SEL3_RESERVED = 3 +TMDS_CTL3_DATA_SEL4_HSYNC = 4 +TMDS_CTL3_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL3_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL3_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL3_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_PATTERN_OUT_EN' +TMDS_CTL3_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL3_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL3_PATTERN_OUT_ENABLE', +} +TMDS_CTL3_PATTERN_OUT_DISABLE = 0 +TMDS_CTL3_PATTERN_OUT_ENABLE = 1 +TMDS_CTL3_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL' +TMDS_DATA_SYNCHRONIZATION_DSINTSEL__enumvalues = { + 0: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 1: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', +} +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS = 0 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL = 1 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_PIXEL_ENCODING' +TMDS_PIXEL_ENCODING__enumvalues = { + 0: 'TMDS_PIXEL_ENCODING_444_OR_420', + 1: 'TMDS_PIXEL_ENCODING_422', +} +TMDS_PIXEL_ENCODING_444_OR_420 = 0 +TMDS_PIXEL_ENCODING_422 = 1 +TMDS_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTA_CNTLA' +TMDS_REG_TEST_OUTPUTA_CNTLA__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 1: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 2: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 3: 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', +} +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0 = 0 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1 = 1 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2 = 2 +TMDS_REG_TEST_OUTPUTA_CNTLA_NA = 3 +TMDS_REG_TEST_OUTPUTA_CNTLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTB_CNTLB' +TMDS_REG_TEST_OUTPUTB_CNTLB__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 1: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 2: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', + 3: 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', +} +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0 = 0 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1 = 1 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2 = 2 +TMDS_REG_TEST_OUTPUTB_CNTLB_NA = 3 +TMDS_REG_TEST_OUTPUTB_CNTLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_STEREOSYNC_CTL_SEL_REG' +TMDS_STEREOSYNC_CTL_SEL_REG__enumvalues = { + 0: 'TMDS_STEREOSYNC_CTL0', + 1: 'TMDS_STEREOSYNC_CTL1', + 2: 'TMDS_STEREOSYNC_CTL2', + 3: 'TMDS_STEREOSYNC_CTL3', +} +TMDS_STEREOSYNC_CTL0 = 0 +TMDS_STEREOSYNC_CTL1 = 1 +TMDS_STEREOSYNC_CTL2 = 2 +TMDS_STEREOSYNC_CTL3 = 3 +TMDS_STEREOSYNC_CTL_SEL_REG = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_SYNC_PHASE' +TMDS_SYNC_PHASE__enumvalues = { + 0: 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 1: 'TMDS_SYNC_PHASE_ON_FRAME_START', +} +TMDS_NOT_SYNC_PHASE_ON_FRAME_START = 0 +TMDS_SYNC_PHASE_ON_FRAME_START = 1 +TMDS_SYNC_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA' +TMDS_TRANSMITTER_CONTROL_IDSCKSELA__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB' +TMDS_TRANSMITTER_CONTROL_IDSCKSELB__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN' +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 1: 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', +} +TMDS_TRANSMITTER_PLLSEL_BY_HW = 0 +TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW = 1 +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 1: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 2: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 3: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', +} +TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE = 0 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON = 1 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON = 2 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE = 3 +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN' +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 1: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', +} +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE = 0 +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE = 1 +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 1: 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', +} +TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD = 0 +TMDS_TRANSMITTER_PLL_RST_ON_HPD = 1 +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 1: 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK = 0 +TMDS_TRANSMITTER_TDCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 1: 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK = 0 +TMDS_TRANSMITTER_TMCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ACK' +DOUT_I2C_ACK__enumvalues = { + 0: 'DOUT_I2C_NO_ACK', + 1: 'DOUT_I2C_ACK_TO_CLEAN', +} +DOUT_I2C_NO_ACK = 0 +DOUT_I2C_ACK_TO_CLEAN = 1 +DOUT_I2C_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_ABORT_XFER' +DOUT_I2C_ARBITRATION_ABORT_XFER__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 1: 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', +} +DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER = 0 +DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER = 1 +DOUT_I2C_ARBITRATION_ABORT_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG' +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 1: 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', +} +DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG = 0 +DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG = 1 +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO' +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 1: 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', +} +DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED = 0 +DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED = 1 +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_SW_PRIORITY' +DOUT_I2C_ARBITRATION_SW_PRIORITY__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 1: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 2: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 3: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', +} +DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL = 0 +DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH = 1 +DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED = 2 +DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED = 3 +DOUT_I2C_ARBITRATION_SW_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ' +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 1: 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', +} +DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ = 0 +DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ = 1 +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DBG_REF_SEL' +DOUT_I2C_CONTROL_DBG_REF_SEL__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 1: 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', +} +DOUT_I2C_CONTROL_NORMAL_DEBUG = 0 +DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG = 1 +DOUT_I2C_CONTROL_DBG_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DDC_SELECT' +DOUT_I2C_CONTROL_DDC_SELECT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_SELECT_DDC1', + 1: 'DOUT_I2C_CONTROL_SELECT_DDC2', + 2: 'DOUT_I2C_CONTROL_SELECT_DDC3', + 3: 'DOUT_I2C_CONTROL_SELECT_DDC4', + 4: 'DOUT_I2C_CONTROL_SELECT_DDCVGA', +} +DOUT_I2C_CONTROL_SELECT_DDC1 = 0 +DOUT_I2C_CONTROL_SELECT_DDC2 = 1 +DOUT_I2C_CONTROL_SELECT_DDC3 = 2 +DOUT_I2C_CONTROL_SELECT_DDC4 = 3 +DOUT_I2C_CONTROL_SELECT_DDCVGA = 4 +DOUT_I2C_CONTROL_DDC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_GO' +DOUT_I2C_CONTROL_GO__enumvalues = { + 0: 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 1: 'DOUT_I2C_CONTROL_START_TRANSFER', +} +DOUT_I2C_CONTROL_STOP_TRANSFER = 0 +DOUT_I2C_CONTROL_START_TRANSFER = 1 +DOUT_I2C_CONTROL_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET' +DOUT_I2C_CONTROL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 1: 'DOUT_I2C_CONTROL__SEND_RESET', +} +DOUT_I2C_CONTROL__NOT_SEND_RESET = 0 +DOUT_I2C_CONTROL__SEND_RESET = 1 +DOUT_I2C_CONTROL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH' +DOUT_I2C_CONTROL_SEND_RESET_LENGTH__enumvalues = { + 0: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 1: 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', +} +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9 = 0 +DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10 = 1 +DOUT_I2C_CONTROL_SEND_RESET_LENGTH = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SOFT_RESET' +DOUT_I2C_CONTROL_SOFT_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 1: 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', +} +DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER = 0 +DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER = 1 +DOUT_I2C_CONTROL_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SW_STATUS_RESET' +DOUT_I2C_CONTROL_SW_STATUS_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 1: 'DOUT_I2C_CONTROL_RESET_SW_STATUS', +} +DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS = 0 +DOUT_I2C_CONTROL_RESET_SW_STATUS = 1 +DOUT_I2C_CONTROL_SW_STATUS_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_TRANSACTION_COUNT' +DOUT_I2C_CONTROL_TRANSACTION_COUNT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_TRANS0', + 1: 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 2: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 3: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', +} +DOUT_I2C_CONTROL_TRANS0 = 0 +DOUT_I2C_CONTROL_TRANS0_TRANS1 = 1 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2 = 2 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3 = 3 +DOUT_I2C_CONTROL_TRANSACTION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DATA_INDEX_WRITE' +DOUT_I2C_DATA_INDEX_WRITE__enumvalues = { + 0: 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 1: 'DOUT_I2C_DATA__INDEX_WRITE', +} +DOUT_I2C_DATA__NOT_INDEX_WRITE = 0 +DOUT_I2C_DATA__INDEX_WRITE = 1 +DOUT_I2C_DATA_INDEX_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN' +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', +} +DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL = 1 +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 1: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS = 0 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE' +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 1: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', +} +DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT = 0 +DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT = 1 +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SPEED_THRESHOLD' +DOUT_I2C_DDC_SPEED_THRESHOLD__enumvalues = { + 0: 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 1: 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 2: 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 3: 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', +} +DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO = 0 +DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE = 1 +DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE = 2 +DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE = 3 +DOUT_I2C_DDC_SPEED_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET' +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 1: 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', +} +DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION = 0 +DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION = 1 +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE' +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__enumvalues = { + 0: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 1: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', +} +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL = 0 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE = 1 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_TRANSACTION_STOP_ON_NACK' +DOUT_I2C_TRANSACTION_STOP_ON_NACK__enumvalues = { + 0: 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 1: 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', +} +DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS = 0 +DOUT_I2C_TRANSACTION_STOP_ALL_TRANS = 1 +DOUT_I2C_TRANSACTION_STOP_ON_NACK = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_EN' +CLOCK_GATING_EN__enumvalues = { + 0: 'CLOCK_GATING_ENABLE', + 1: 'CLOCK_GATING_DISABLE', +} +CLOCK_GATING_ENABLE = 0 +CLOCK_GATING_DISABLE = 1 +CLOCK_GATING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DAC_MUX_SELECT' +DAC_MUX_SELECT__enumvalues = { + 0: 'DAC_MUX_SELECT_DACA', + 1: 'DAC_MUX_SELECT_DACB', +} +DAC_MUX_SELECT_DACA = 0 +DAC_MUX_SELECT_DACB = 1 +DAC_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_DIS_CTRL' +DIOMEM_PWR_DIS_CTRL__enumvalues = { + 0: 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 1: 'DIOMEM_DISABLE_MEM_PWR_CTRL', +} +DIOMEM_ENABLE_MEM_PWR_CTRL = 0 +DIOMEM_DISABLE_MEM_PWR_CTRL = 1 +DIOMEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL' +DIOMEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQUEST', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', +} +DIOMEM_NO_FORCE_REQUEST = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DIOMEM_FORCE_DEEP_SLEEP_REQUEST = 2 +DIOMEM_FORCE_SHUT_DOWN_REQUEST = 3 +DIOMEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_FORCE_CTRL2' +DIOMEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'DIOMEM_NO_FORCE_REQ', + 1: 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', +} +DIOMEM_NO_FORCE_REQ = 0 +DIOMEM_FORCE_LIGHT_SLEEP_REQ = 1 +DIOMEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL' +DIOMEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE = 0 +DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +DIOMEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DIOMEM_PWR_SEL_CTRL2' +DIOMEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 1: 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', +} +DIOMEM_DYNAMIC_DEEP_SLEEP_EN = 0 +DIOMEM_DYNAMIC_LIGHT_SLEEP_EN = 1 +DIOMEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_CLOCK_GATING_DISABLE' +DIO_CLOCK_GATING_DISABLE__enumvalues = { + 0: 'DIO_CLOCK_GATING_EN', + 1: 'DIO_CLOCK_GATING_DIS', +} +DIO_CLOCK_GATING_EN = 0 +DIO_CLOCK_GATING_DIS = 1 +DIO_CLOCK_GATING_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_DBG_BLOCK_SEL' +DIO_DBG_BLOCK_SEL__enumvalues = { + 0: 'DIO_DBG_BLOCK_SEL_DIO', + 11: 'DIO_DBG_BLOCK_SEL_DIGFE_A', + 12: 'DIO_DBG_BLOCK_SEL_DIGFE_B', + 13: 'DIO_DBG_BLOCK_SEL_DIGFE_C', + 14: 'DIO_DBG_BLOCK_SEL_DIGFE_D', + 18: 'DIO_DBG_BLOCK_SEL_DIGA', + 19: 'DIO_DBG_BLOCK_SEL_DIGB', + 20: 'DIO_DBG_BLOCK_SEL_DIGC', + 21: 'DIO_DBG_BLOCK_SEL_DIGD', + 25: 'DIO_DBG_BLOCK_SEL_DPFE_A', + 26: 'DIO_DBG_BLOCK_SEL_DPFE_B', + 27: 'DIO_DBG_BLOCK_SEL_DPFE_C', + 28: 'DIO_DBG_BLOCK_SEL_DPFE_D', + 32: 'DIO_DBG_BLOCK_SEL_DPA', + 33: 'DIO_DBG_BLOCK_SEL_DPB', + 34: 'DIO_DBG_BLOCK_SEL_DPC', + 35: 'DIO_DBG_BLOCK_SEL_DPD', + 39: 'DIO_DBG_BLOCK_SEL_AUX0', + 40: 'DIO_DBG_BLOCK_SEL_AUX1', + 41: 'DIO_DBG_BLOCK_SEL_AUX2', + 42: 'DIO_DBG_BLOCK_SEL_AUX3', + 45: 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', + 46: 'DIO_DBG_BLOCK_SEL_RESERVED', +} +DIO_DBG_BLOCK_SEL_DIO = 0 +DIO_DBG_BLOCK_SEL_DIGFE_A = 11 +DIO_DBG_BLOCK_SEL_DIGFE_B = 12 +DIO_DBG_BLOCK_SEL_DIGFE_C = 13 +DIO_DBG_BLOCK_SEL_DIGFE_D = 14 +DIO_DBG_BLOCK_SEL_DIGA = 18 +DIO_DBG_BLOCK_SEL_DIGB = 19 +DIO_DBG_BLOCK_SEL_DIGC = 20 +DIO_DBG_BLOCK_SEL_DIGD = 21 +DIO_DBG_BLOCK_SEL_DPFE_A = 25 +DIO_DBG_BLOCK_SEL_DPFE_B = 26 +DIO_DBG_BLOCK_SEL_DPFE_C = 27 +DIO_DBG_BLOCK_SEL_DPFE_D = 28 +DIO_DBG_BLOCK_SEL_DPA = 32 +DIO_DBG_BLOCK_SEL_DPB = 33 +DIO_DBG_BLOCK_SEL_DPC = 34 +DIO_DBG_BLOCK_SEL_DPD = 35 +DIO_DBG_BLOCK_SEL_AUX0 = 39 +DIO_DBG_BLOCK_SEL_AUX1 = 40 +DIO_DBG_BLOCK_SEL_AUX2 = 41 +DIO_DBG_BLOCK_SEL_AUX3 = 42 +DIO_DBG_BLOCK_SEL_PERFMON_DIO = 45 +DIO_DBG_BLOCK_SEL_RESERVED = 46 +DIO_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE' +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE__enumvalues = { + 0: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 1: 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', +} +DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL = 0 +DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE = 1 +DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DIO_DCN_ACTIVE_STATUS' +ENUM_DIO_DCN_ACTIVE_STATUS__enumvalues = { + 0: 'ENUM_DCN_NOT_ACTIVE', + 1: 'ENUM_DCN_ACTIVE', +} +ENUM_DCN_NOT_ACTIVE = 0 +ENUM_DCN_ACTIVE = 1 +ENUM_DIO_DCN_ACTIVE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_STEREOSYNC_SEL' +GENERIC_STEREOSYNC_SEL__enumvalues = { + 0: 'GENERIC_STEREOSYNC_SEL_D1', + 1: 'GENERIC_STEREOSYNC_SEL_D2', + 2: 'GENERIC_STEREOSYNC_SEL_D3', + 3: 'GENERIC_STEREOSYNC_SEL_D4', + 4: 'GENERIC_STEREOSYNC_SEL_RESERVED', +} +GENERIC_STEREOSYNC_SEL_D1 = 0 +GENERIC_STEREOSYNC_SEL_D2 = 1 +GENERIC_STEREOSYNC_SEL_D3 = 2 +GENERIC_STEREOSYNC_SEL_D4 = 3 +GENERIC_STEREOSYNC_SEL_RESERVED = 4 +GENERIC_STEREOSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PM_ASSERT_RESET' +PM_ASSERT_RESET__enumvalues = { + 0: 'PM_ASSERT_RESET_0', + 1: 'PM_ASSERT_RESET_1', +} +PM_ASSERT_RESET_0 = 0 +PM_ASSERT_RESET_1 = 1 +PM_ASSERT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'SOFT_RESET' +SOFT_RESET__enumvalues = { + 0: 'SOFT_RESET_0', + 1: 'SOFT_RESET_1', +} +SOFT_RESET_0 = 0 +SOFT_RESET_1 = 1 +SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_MUX_SELECT' +TMDS_MUX_SELECT__enumvalues = { + 0: 'TMDS_MUX_SELECT_B', + 1: 'TMDS_MUX_SELECT_G', + 2: 'TMDS_MUX_SELECT_R', + 3: 'TMDS_MUX_SELECT_RESERVED', +} +TMDS_MUX_SELECT_B = 0 +TMDS_MUX_SELECT_G = 1 +TMDS_MUX_SELECT_R = 2 +TMDS_MUX_SELECT_RESERVED = 3 +TMDS_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_STREAM_MAPPER_DIG_STREAM_LINK_TARGET' +DIG_STREAM_MAPPER_DIG_STREAM_LINK_TARGET__enumvalues = { + 0: 'DIG_STREAM_MAPPER_LINK0', + 1: 'DIG_STREAM_MAPPER_LINK1', + 2: 'DIG_STREAM_MAPPER_LINK2', + 3: 'DIG_STREAM_MAPPER_LINK3', + 4: 'DIG_STREAM_MAPPER_LINK6', +} +DIG_STREAM_MAPPER_LINK0 = 0 +DIG_STREAM_MAPPER_LINK1 = 1 +DIG_STREAM_MAPPER_LINK2 = 2 +DIG_STREAM_MAPPER_LINK3 = 3 +DIG_STREAM_MAPPER_LINK6 = 4 +DIG_STREAM_MAPPER_DIG_STREAM_LINK_TARGET = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_POWER_STATE_ENUM' +DME_MEM_POWER_STATE_ENUM__enumvalues = { + 0: 'DME_MEM_POWER_STATE_ENUM_ON', + 1: 'DME_MEM_POWER_STATE_ENUM_LS', + 2: 'DME_MEM_POWER_STATE_ENUM_DS', + 3: 'DME_MEM_POWER_STATE_ENUM_SD', +} +DME_MEM_POWER_STATE_ENUM_ON = 0 +DME_MEM_POWER_STATE_ENUM_LS = 1 +DME_MEM_POWER_STATE_ENUM_DS = 2 +DME_MEM_POWER_STATE_ENUM_SD = 3 +DME_MEM_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_PWR_DIS_CTRL' +DME_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'DME_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'DME_MEM_DISABLE_MEM_PWR_CTRL', +} +DME_MEM_ENABLE_MEM_PWR_CTRL = 0 +DME_MEM_DISABLE_MEM_PWR_CTRL = 1 +DME_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'DME_MEM_PWR_FORCE_CTRL' +DME_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'DME_MEM_NO_FORCE_REQUEST', + 1: 'DME_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DME_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DME_MEM_FORCE_SHUT_DOWN_REQUEST', +} +DME_MEM_NO_FORCE_REQUEST = 0 +DME_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DME_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +DME_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +DME_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_HUBP_SEL' +METADATA_HUBP_SEL__enumvalues = { + 0: 'METADATA_HUBP_SEL_0', + 1: 'METADATA_HUBP_SEL_1', + 2: 'METADATA_HUBP_SEL_2', + 3: 'METADATA_HUBP_SEL_3', + 4: 'METADATA_HUBP_SEL_RESERVED', +} +METADATA_HUBP_SEL_0 = 0 +METADATA_HUBP_SEL_1 = 1 +METADATA_HUBP_SEL_2 = 2 +METADATA_HUBP_SEL_3 = 3 +METADATA_HUBP_SEL_RESERVED = 4 +METADATA_HUBP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'METADATA_STREAM_TYPE_SEL' +METADATA_STREAM_TYPE_SEL__enumvalues = { + 0: 'METADATA_STREAM_DP', + 1: 'METADATA_STREAM_DVE', +} +METADATA_STREAM_DP = 0 +METADATA_STREAM_DVE = 1 +METADATA_STREAM_TYPE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VPG_MEM_PWR_DIS_CTRL' +VPG_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'VPG_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'VPG_MEM_DISABLE_MEM_PWR_CTRL', +} +VPG_MEM_ENABLE_MEM_PWR_CTRL = 0 +VPG_MEM_DISABLE_MEM_PWR_CTRL = 1 +VPG_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'VPG_MEM_PWR_FORCE_CTRL' +VPG_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'VPG_MEM_NO_FORCE_REQ', + 1: 'VPG_MEM_FORCE_LIGHT_SLEEP_REQ', +} +VPG_MEM_NO_FORCE_REQ = 0 +VPG_MEM_FORCE_LIGHT_SLEEP_REQ = 1 +VPG_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_ACP_TYPE' +AFMT_ACP_TYPE__enumvalues = { + 0: 'ACP_TYPE_GENERIC_AUDIO', + 1: 'ACP_TYPE_ICE60958_AUDIO', + 2: 'ACP_TYPE_DVD_AUDIO', + 3: 'ACP_TYPE_SUPER_AUDIO_CD', +} +ACP_TYPE_GENERIC_AUDIO = 0 +ACP_TYPE_ICE60958_AUDIO = 1 +ACP_TYPE_DVD_AUDIO = 2 +ACP_TYPE_SUPER_AUDIO_CD = 3 +AFMT_ACP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CH_SEL' +AFMT_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'AFMT_AUDIO_CRC_CH0_SIG', + 1: 'AFMT_AUDIO_CRC_CH1_SIG', + 2: 'AFMT_AUDIO_CRC_CH2_SIG', + 3: 'AFMT_AUDIO_CRC_CH3_SIG', + 4: 'AFMT_AUDIO_CRC_CH4_SIG', + 5: 'AFMT_AUDIO_CRC_CH5_SIG', + 6: 'AFMT_AUDIO_CRC_CH6_SIG', + 7: 'AFMT_AUDIO_CRC_CH7_SIG', + 8: 'AFMT_AUDIO_CRC_RESERVED_8', + 9: 'AFMT_AUDIO_CRC_RESERVED_9', + 10: 'AFMT_AUDIO_CRC_RESERVED_10', + 11: 'AFMT_AUDIO_CRC_RESERVED_11', + 12: 'AFMT_AUDIO_CRC_RESERVED_12', + 13: 'AFMT_AUDIO_CRC_RESERVED_13', + 14: 'AFMT_AUDIO_CRC_RESERVED_14', + 15: 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', +} +AFMT_AUDIO_CRC_CH0_SIG = 0 +AFMT_AUDIO_CRC_CH1_SIG = 1 +AFMT_AUDIO_CRC_CH2_SIG = 2 +AFMT_AUDIO_CRC_CH3_SIG = 3 +AFMT_AUDIO_CRC_CH4_SIG = 4 +AFMT_AUDIO_CRC_CH5_SIG = 5 +AFMT_AUDIO_CRC_CH6_SIG = 6 +AFMT_AUDIO_CRC_CH7_SIG = 7 +AFMT_AUDIO_CRC_RESERVED_8 = 8 +AFMT_AUDIO_CRC_RESERVED_9 = 9 +AFMT_AUDIO_CRC_RESERVED_10 = 10 +AFMT_AUDIO_CRC_RESERVED_11 = 11 +AFMT_AUDIO_CRC_RESERVED_12 = 12 +AFMT_AUDIO_CRC_RESERVED_13 = 13 +AFMT_AUDIO_CRC_RESERVED_14 = 14 +AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT = 15 +AFMT_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CONT' +AFMT_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'AFMT_AUDIO_CRC_ONESHOT', + 1: 'AFMT_AUDIO_CRC_AUTO_RESTART', +} +AFMT_AUDIO_CRC_ONESHOT = 0 +AFMT_AUDIO_CRC_AUTO_RESTART = 1 +AFMT_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_SOURCE' +AFMT_AUDIO_CRC_CONTROL_SOURCE__enumvalues = { + 0: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 1: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', +} +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT = 0 +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT = 1 +AFMT_AUDIO_CRC_CONTROL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD' +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD__enumvalues = { + 0: 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 1: 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', +} +AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS = 0 +AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER = 1 +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND' +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND__enumvalues = { + 0: 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 1: 'AFMT_AUDIO_PACKET_SENT_ENABLED', +} +AFMT_AUDIO_PACKET_SENT_DISABLED = 0 +AFMT_AUDIO_PACKET_SENT_ENABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS' +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS__enumvalues = { + 0: 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 1: 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', +} +AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED = 0 +AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_SRC_CONTROL_SELECT' +AFMT_AUDIO_SRC_CONTROL_SELECT__enumvalues = { + 0: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 1: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 2: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 3: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 4: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 5: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', +} +AFMT_AUDIO_SRC_FROM_AZ_STREAM0 = 0 +AFMT_AUDIO_SRC_FROM_AZ_STREAM1 = 1 +AFMT_AUDIO_SRC_FROM_AZ_STREAM2 = 2 +AFMT_AUDIO_SRC_FROM_AZ_STREAM3 = 3 +AFMT_AUDIO_SRC_FROM_AZ_STREAM4 = 4 +AFMT_AUDIO_SRC_FROM_AZ_STREAM5 = 5 +AFMT_AUDIO_SRC_CONTROL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_HDMI_AUDIO_SEND_MAX_PACKETS' +AFMT_HDMI_AUDIO_SEND_MAX_PACKETS__enumvalues = { + 0: 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 1: 'HDMI_SEND_MAX_AUDIO_PACKETS', +} +HDMI_NOT_SEND_MAX_AUDIO_PACKETS = 0 +HDMI_SEND_MAX_AUDIO_PACKETS = 1 +AFMT_HDMI_AUDIO_SEND_MAX_PACKETS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE' +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 1: 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK = 0 +AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INTERRUPT_STATUS_CHG_MASK' +AFMT_INTERRUPT_STATUS_CHG_MASK__enumvalues = { + 0: 'AFMT_INTERRUPT_DISABLE', + 1: 'AFMT_INTERRUPT_ENABLE', +} +AFMT_INTERRUPT_DISABLE = 0 +AFMT_INTERRUPT_ENABLE = 1 +AFMT_INTERRUPT_STATUS_CHG_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_MEM_PWR_DIS_CTRL' +AFMT_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'AFMT_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'AFMT_MEM_DISABLE_MEM_PWR_CTRL', +} +AFMT_MEM_ENABLE_MEM_PWR_CTRL = 0 +AFMT_MEM_DISABLE_MEM_PWR_CTRL = 1 +AFMT_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_MEM_PWR_FORCE_CTRL' +AFMT_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'AFMT_MEM_NO_FORCE_REQUEST', + 1: 'AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'AFMT_MEM_FORCE_SHUT_DOWN_REQUEST', +} +AFMT_MEM_NO_FORCE_REQUEST = 0 +AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +AFMT_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +AFMT_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_RAMP_CONTROL0_SIGN' +AFMT_RAMP_CONTROL0_SIGN__enumvalues = { + 0: 'AFMT_RAMP_SIGNED', + 1: 'AFMT_RAMP_UNSIGNED', +} +AFMT_RAMP_SIGNED = 0 +AFMT_RAMP_UNSIGNED = 1 +AFMT_RAMP_CONTROL0_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_VBI_PACKET_CONTROL_ACP_SOURCE' +AFMT_VBI_PACKET_CONTROL_ACP_SOURCE__enumvalues = { + 0: 'AFMT_ACP_SOURCE_FROM_AZALIA', + 1: 'AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_ACP_SOURCE_FROM_AZALIA = 0 +AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_VBI_PACKET_CONTROL_ACP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AUDIO_LAYOUT_SELECT' +AUDIO_LAYOUT_SELECT__enumvalues = { + 0: 'AUDIO_LAYOUT_0', + 1: 'AUDIO_LAYOUT_1', +} +AUDIO_LAYOUT_0 = 0 +AUDIO_LAYOUT_1 = 1 +AUDIO_LAYOUT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCOH_TEST_CLOCK_MUX_SELECT_ENUM' +DCOH_TEST_CLOCK_MUX_SELECT_ENUM__enumvalues = { + 0: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 1: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 2: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX1', + 3: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX2', + 4: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX3', + 5: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX4', + 6: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX5', + 7: 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX6', + 8: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_P', + 9: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_R', + 10: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX1', + 11: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX2', + 12: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX3', + 13: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX4', + 14: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX5', + 15: 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX6', + 16: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK0', + 17: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK1', + 18: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK2', + 19: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK3', + 20: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK4', + 21: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK5', + 22: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK6', + 23: 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK7', + 24: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYASYMCLK', + 25: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYBSYMCLK', + 26: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYCSYMCLK', + 27: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYDSYMCLK', + 28: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYESYMCLK', + 29: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYFSYMCLK', + 30: 'DCOH_TEST_CLOCK_MUX_SELECT_PHYGSYMCLK', +} +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_P = 0 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_R = 1 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX1 = 2 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX2 = 3 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX3 = 4 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX4 = 5 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX5 = 6 +DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX6 = 7 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_P = 8 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_R = 9 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX1 = 10 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX2 = 11 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX3 = 12 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX4 = 13 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX5 = 14 +DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX6 = 15 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK0 = 16 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK1 = 17 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK2 = 18 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK3 = 19 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK4 = 20 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK5 = 21 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK6 = 22 +DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK7 = 23 +DCOH_TEST_CLOCK_MUX_SELECT_PHYASYMCLK = 24 +DCOH_TEST_CLOCK_MUX_SELECT_PHYBSYMCLK = 25 +DCOH_TEST_CLOCK_MUX_SELECT_PHYCSYMCLK = 26 +DCOH_TEST_CLOCK_MUX_SELECT_PHYDSYMCLK = 27 +DCOH_TEST_CLOCK_MUX_SELECT_PHYESYMCLK = 28 +DCOH_TEST_CLOCK_MUX_SELECT_PHYFSYMCLK = 29 +DCOH_TEST_CLOCK_MUX_SELECT_PHYGSYMCLK = 30 +DCOH_TEST_CLOCK_MUX_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM' +DCOH_TOP_CLOCK_GATING_DISABLE_ENUM__enumvalues = { + 0: 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_ENABLED', + 1: 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_DISABLED', +} +DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_ENABLED = 0 +DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_DISABLED = 1 +DCOH_TOP_CLOCK_GATING_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DCOH_TOP_ENABLE_ENUM' +DCOH_TOP_ENABLE_ENUM__enumvalues = { + 0: 'DCOH_TOP_ENABLE_ENUM_DISABLED', + 1: 'DCOH_TOP_ENABLE_ENUM_ENABLED', +} +DCOH_TOP_ENABLE_ENUM_DISABLED = 0 +DCOH_TOP_ENABLE_ENUM_ENABLED = 1 +DCOH_TOP_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'PHY_MUX_ENABLE_ENUM' +PHY_MUX_ENABLE_ENUM__enumvalues = { + 0: 'PHY_MUX_ENABLE_ENUM_DISABLED', + 1: 'PHY_MUX_ENABLE_ENUM_ENABLED', +} +PHY_MUX_ENABLE_ENUM_DISABLED = 0 +PHY_MUX_ENABLE_ENUM_ENABLED = 1 +PHY_MUX_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_ARB_PRIORITY' +DP_AUX_ARB_CONTROL_ARB_PRIORITY__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 1: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 2: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 3: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', +} +DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW = 0 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW = 1 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC = 2 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS = 3 +DP_AUX_ARB_CONTROL_ARB_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG' +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 1: 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', +} +DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG = 0 +DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG = 1 +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ' +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 1: 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', +} +DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ = 0 +DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ = 1 +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_STATUS' +DP_AUX_ARB_STATUS__enumvalues = { + 0: 'DP_AUX_IDLE', + 1: 'DP_AUX_IN_USE_LS', + 2: 'DP_AUX_IN_USE_GTC', + 3: 'DP_AUX_IN_USE_SW', + 4: 'DP_AUX_IN_USE_PHYWAKE', +} +DP_AUX_IDLE = 0 +DP_AUX_IN_USE_LS = 1 +DP_AUX_IN_USE_GTC = 2 +DP_AUX_IN_USE_SW = 3 +DP_AUX_IN_USE_PHYWAKE = 4 +DP_AUX_ARB_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_HPD_SEL' +DP_AUX_CONTROL_HPD_SEL__enumvalues = { + 0: 'DP_AUX_CONTROL_HPD1_SELECTED', + 1: 'DP_AUX_CONTROL_HPD2_SELECTED', + 2: 'DP_AUX_CONTROL_HPD3_SELECTED', + 3: 'DP_AUX_CONTROL_HPD4_SELECTED', + 4: 'DP_AUX_CONTROL_NO_HPD_SELECTED', +} +DP_AUX_CONTROL_HPD1_SELECTED = 0 +DP_AUX_CONTROL_HPD2_SELECTED = 1 +DP_AUX_CONTROL_HPD3_SELECTED = 2 +DP_AUX_CONTROL_HPD4_SELECTED = 3 +DP_AUX_CONTROL_NO_HPD_SELECTED = 4 +DP_AUX_CONTROL_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_TEST_MODE' +DP_AUX_CONTROL_TEST_MODE__enumvalues = { + 0: 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 1: 'DP_AUX_CONTROL_TEST_MODE_ENABLE', +} +DP_AUX_CONTROL_TEST_MODE_DISABLE = 0 +DP_AUX_CONTROL_TEST_MODE_ENABLE = 1 +DP_AUX_CONTROL_TEST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DEFINITE_ERR_REACHED_ACK' +DP_AUX_DEFINITE_ERR_REACHED_ACK__enumvalues = { + 0: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', + 1: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', +} +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK = 0 +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK = 1 +DP_AUX_DEFINITE_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 1: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 2: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 3: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', +} +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES = 0 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES = 1 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES = 2 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED = 3 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 1: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 2: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 3: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', +} +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS = 0 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS = 1 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS = 2 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS = 3 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW' +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW' +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD' +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__enumvalues = { + 0: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 1: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 2: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 3: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 4: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 5: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 6: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 7: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', +} +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2 = 0 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4 = 1 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8 = 2 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16 = 3 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32 = 4 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64 = 5 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128 = 6 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256 = 7 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY' +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__enumvalues = { + 0: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 1: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 2: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 3: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 4: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 5: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', +} +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0 = 0 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US = 1 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US = 2 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US = 3 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US = 4 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US = 5 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE' +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 2: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 3: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ = 2 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ = 3 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL' +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ERR_OCCURRED_ACK' +DP_AUX_ERR_OCCURRED_ACK__enumvalues = { + 0: 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 1: 'DP_AUX_ERR_OCCURRED__ACK', +} +DP_AUX_ERR_OCCURRED__NOT_ACK = 0 +DP_AUX_ERR_OCCURRED__ACK = 1 +DP_AUX_ERR_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ' +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 1: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', +} +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX = 0 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX = 1 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW' +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 1: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 2: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 3: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', +} +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US = 0 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US = 1 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US = 2 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US = 3 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT' +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 1: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 2: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 3: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', +} +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS = 0 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS = 1 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS = 2 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED = 3 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN' +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 1: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 2: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 3: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', +} +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0 = 0 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64 = 1 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128 = 2 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256 = 3 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_INT_ACK' +DP_AUX_INT_ACK__enumvalues = { + 0: 'DP_AUX_INT__NOT_ACK', + 1: 'DP_AUX_INT__ACK', +} +DP_AUX_INT__NOT_ACK = 0 +DP_AUX_INT__ACK = 1 +DP_AUX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_LS_UPDATE_ACK' +DP_AUX_LS_UPDATE_ACK__enumvalues = { + 0: 'DP_AUX_INT_LS_UPDATE_NOT_ACK', + 1: 'DP_AUX_INT_LS_UPDATE_ACK', +} +DP_AUX_INT_LS_UPDATE_NOT_ACK = 0 +DP_AUX_INT_LS_UPDATE_ACK = 1 +DP_AUX_LS_UPDATE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_PHY_WAKE_PRIORITY' +DP_AUX_PHY_WAKE_PRIORITY__enumvalues = { + 0: 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', + 1: 'DP_AUX_PHY_WAKE_LOW_PRIORITY', +} +DP_AUX_PHY_WAKE_HIGH_PRIORITY = 0 +DP_AUX_PHY_WAKE_LOW_PRIORITY = 1 +DP_AUX_PHY_WAKE_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_POTENTIAL_ERR_REACHED_ACK' +DP_AUX_POTENTIAL_ERR_REACHED_ACK__enumvalues = { + 0: 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', + 1: 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', +} +DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK = 0 +DP_AUX_POTENTIAL_ERR_REACHED__ACK = 1 +DP_AUX_POTENTIAL_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET' +DP_AUX_RESET__enumvalues = { + 0: 'DP_AUX_RESET_DEASSERTED', + 1: 'DP_AUX_RESET_ASSERTED', +} +DP_AUX_RESET_DEASSERTED = 0 +DP_AUX_RESET_ASSERTED = 1 +DP_AUX_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET_DONE' +DP_AUX_RESET_DONE__enumvalues = { + 0: 'DP_AUX_RESET_SEQUENCE_NOT_DONE', + 1: 'DP_AUX_RESET_SEQUENCE_DONE', +} +DP_AUX_RESET_SEQUENCE_NOT_DONE = 0 +DP_AUX_RESET_SEQUENCE_DONE = 1 +DP_AUX_RESET_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RX_TIMEOUT_LEN_MUL' +DP_AUX_RX_TIMEOUT_LEN_MUL__enumvalues = { + 0: 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 1: 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', + 2: 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 3: 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', +} +DP_AUX_RX_TIMEOUT_LEN_NO_MUL = 0 +DP_AUX_RX_TIMEOUT_LEN_MUL_2 = 1 +DP_AUX_RX_TIMEOUT_LEN_MUL_4 = 2 +DP_AUX_RX_TIMEOUT_LEN_MUL_8 = 3 +DP_AUX_RX_TIMEOUT_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_LS_READ_TRIG' +DP_AUX_SW_CONTROL_LS_READ_TRIG__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 1: 'DP_AUX_SW_CONTROL_LS_READ__TRIG', +} +DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG = 0 +DP_AUX_SW_CONTROL_LS_READ__TRIG = 1 +DP_AUX_SW_CONTROL_LS_READ_TRIG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_SW_GO' +DP_AUX_SW_CONTROL_SW_GO__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 1: 'DP_AUX_SW_CONTROL_SW__GO', +} +DP_AUX_SW_CONTROL_SW__NOT_GO = 0 +DP_AUX_SW_CONTROL_SW__GO = 1 +DP_AUX_SW_CONTROL_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_TX_PRECHARGE_LEN_MUL' +DP_AUX_TX_PRECHARGE_LEN_MUL__enumvalues = { + 0: 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', + 1: 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 2: 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', + 3: 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', +} +DP_AUX_TX_PRECHARGE_LEN_NO_MUL = 0 +DP_AUX_TX_PRECHARGE_LEN_MUL_2 = 1 +DP_AUX_TX_PRECHARGE_LEN_MUL_4 = 2 +DP_AUX_TX_PRECHARGE_LEN_MUL_8 = 3 +DP_AUX_TX_PRECHARGE_LEN_MUL = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_ACK' +HPD_INT_CONTROL_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_ACK_0', + 1: 'HPD_INT_CONTROL_ACK_1', +} +HPD_INT_CONTROL_ACK_0 = 0 +HPD_INT_CONTROL_ACK_1 = 1 +HPD_INT_CONTROL_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_POLARITY' +HPD_INT_CONTROL_POLARITY__enumvalues = { + 0: 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', + 1: 'HPD_INT_CONTROL_GEN_INT_ON_CON', +} +HPD_INT_CONTROL_GEN_INT_ON_DISCON = 0 +HPD_INT_CONTROL_GEN_INT_ON_CON = 1 +HPD_INT_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_RX_INT_ACK' +HPD_INT_CONTROL_RX_INT_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_RX_INT_ACK_0', + 1: 'HPD_INT_CONTROL_RX_INT_ACK_1', +} +HPD_INT_CONTROL_RX_INT_ACK_0 = 0 +HPD_INT_CONTROL_RX_INT_ACK_1 = 1 +HPD_INT_CONTROL_RX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HPO_TOP_CLOCK_GATING_DISABLE' +HPO_TOP_CLOCK_GATING_DISABLE__enumvalues = { + 0: 'HPO_TOP_CLOCK_GATING_EN', + 1: 'HPO_TOP_CLOCK_GATING_DIS', +} +HPO_TOP_CLOCK_GATING_EN = 0 +HPO_TOP_CLOCK_GATING_DIS = 1 +HPO_TOP_CLOCK_GATING_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'HPO_TOP_TEST_CLK_SEL' +HPO_TOP_TEST_CLK_SEL__enumvalues = { + 0: 'HPO_TOP_PERMANENT_DISPCLK', + 1: 'HPO_TOP_REGISTER_GATED_DISPCLK', + 2: 'HPO_TOP_PERMANENT_SOCCLK', + 3: 'HPO_TOP_TEST_CLOCK_RESERVED', + 4: 'HPO_TOP_PERMANENT_HDMISTREAMCLK0', + 5: 'HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0', + 6: 'HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0', + 7: 'HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0', + 8: 'HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0', + 9: 'HPO_TOP_PERMANENT_HDMICHARCLK0', + 10: 'HPO_TOP_FEATURE_GATED_HDMICHARCLK0', + 11: 'HPO_TOP_REGISTER_GATED_HDMICHARCLK0', +} +HPO_TOP_PERMANENT_DISPCLK = 0 +HPO_TOP_REGISTER_GATED_DISPCLK = 1 +HPO_TOP_PERMANENT_SOCCLK = 2 +HPO_TOP_TEST_CLOCK_RESERVED = 3 +HPO_TOP_PERMANENT_HDMISTREAMCLK0 = 4 +HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0 = 5 +HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0 = 6 +HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0 = 7 +HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0 = 8 +HPO_TOP_PERMANENT_HDMICHARCLK0 = 9 +HPO_TOP_FEATURE_GATED_HDMICHARCLK0 = 10 +HPO_TOP_REGISTER_GATED_HDMICHARCLK0 = 11 +HPO_TOP_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET' +DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET__enumvalues = { + 0: 'DP_STREAM_MAPPER_LINK0', + 1: 'DP_STREAM_MAPPER_LINK1', + 2: 'DP_STREAM_MAPPER_LINK2', + 3: 'DP_STREAM_MAPPER_LINK3', + 4: 'DP_STREAM_MAPPER_RESERVED', +} +DP_STREAM_MAPPER_LINK0 = 0 +DP_STREAM_MAPPER_LINK1 = 1 +DP_STREAM_MAPPER_LINK2 = 2 +DP_STREAM_MAPPER_LINK3 = 3 +DP_STREAM_MAPPER_RESERVED = 4 +DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR' +DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR__enumvalues = { + 0: 'DP_STREAM_ENC_NO_ERROR_OCCURRED', + 1: 'DP_STREAM_ENC_UNDERFLOW_OCCURRED', + 2: 'DP_STREAM_ENC_OVERFLOW_OCCURRED', +} +DP_STREAM_ENC_NO_ERROR_OCCURRED = 0 +DP_STREAM_ENC_UNDERFLOW_OCCURRED = 1 +DP_STREAM_ENC_OVERFLOW_OCCURRED = 2 +DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT' +DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT__enumvalues = { + 0: 'DP_STREAM_ENC_HARDWARE', + 1: 'DP_STREAM_ENC_PROGRAMMABLE', +} +DP_STREAM_ENC_HARDWARE = 0 +DP_STREAM_ENC_PROGRAMMABLE = 1 +DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_READ_CLOCK_CONTROL' +DP_STREAM_ENC_READ_CLOCK_CONTROL__enumvalues = { + 0: 'DP_STREAM_ENC_DCCG', + 1: 'DP_STREAM_ENC_DISPLAY_PIPE', +} +DP_STREAM_ENC_DCCG = 0 +DP_STREAM_ENC_DISPLAY_PIPE = 1 +DP_STREAM_ENC_READ_CLOCK_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_RESET_CONTROL' +DP_STREAM_ENC_RESET_CONTROL__enumvalues = { + 0: 'DP_STREAM_ENC_NOT_RESET', + 1: 'DP_STREAM_ENC_RESET', +} +DP_STREAM_ENC_NOT_RESET = 0 +DP_STREAM_ENC_RESET = 1 +DP_STREAM_ENC_RESET_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STREAM_ENC_STREAM_ACTIVE' +DP_STREAM_ENC_STREAM_ACTIVE__enumvalues = { + 0: 'DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', + 1: 'DP_STREAM_ENC_VIDEO_STREAM_ACTIVE', +} +DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE = 0 +DP_STREAM_ENC_VIDEO_STREAM_ACTIVE = 1 +DP_STREAM_ENC_STREAM_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_AUDIO_MUTE' +ENUM_DP_SYM32_ENC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED', + 1: 'DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED', +} +DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED = 0 +DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED = 1 +ENUM_DP_SYM32_ENC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_CONTINUOUS_MODE' +ENUM_DP_SYM32_ENC_CONTINUOUS_MODE__enumvalues = { + 0: 'DP_SYM32_ENC_ONE_SHOT_MODE', + 1: 'DP_SYM32_ENC_CONTINUOUS_MODE', +} +DP_SYM32_ENC_ONE_SHOT_MODE = 0 +DP_SYM32_ENC_CONTINUOUS_MODE = 1 +ENUM_DP_SYM32_ENC_CONTINUOUS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_CRC_VALID' +ENUM_DP_SYM32_ENC_CRC_VALID__enumvalues = { + 0: 'DP_SYM32_ENC_CRC_NOT_VALID', + 1: 'DP_SYM32_ENC_CRC_VALID', +} +DP_SYM32_ENC_CRC_NOT_VALID = 0 +DP_SYM32_ENC_CRC_VALID = 1 +ENUM_DP_SYM32_ENC_CRC_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH' +ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_SYM32_ENC_COMPONENT_DEPTH_6BPC', + 1: 'DP_SYM32_ENC_COMPONENT_DEPTH_8BPC', + 2: 'DP_SYM32_ENC_COMPONENT_DEPTH_10BPC', + 3: 'DP_SYM32_ENC_COMPONENT_DEPTH_12BPC', +} +DP_SYM32_ENC_COMPONENT_DEPTH_6BPC = 0 +DP_SYM32_ENC_COMPONENT_DEPTH_8BPC = 1 +DP_SYM32_ENC_COMPONENT_DEPTH_10BPC = 2 +DP_SYM32_ENC_COMPONENT_DEPTH_12BPC = 3 +ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_ENABLE' +ENUM_DP_SYM32_ENC_ENABLE__enumvalues = { + 0: 'DP_SYM32_ENC_DISABLE', + 1: 'DP_SYM32_ENC_ENABLE', +} +DP_SYM32_ENC_DISABLE = 0 +DP_SYM32_ENC_ENABLE = 1 +ENUM_DP_SYM32_ENC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED' +ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED', + 1: 'DP_SYM32_ENC_GSP_DEADLINE_MISSED', +} +DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED = 0 +DP_SYM32_ENC_GSP_DEADLINE_MISSED = 1 +ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION' +ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER', + 1: 'DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME', +} +DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER = 0 +DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME = 1 +ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE' +ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32', + 1: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0', + 2: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1', + 3: 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128', +} +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32 = 0 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0 = 1 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1 = 2 +DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128 = 3 +ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING' +ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING__enumvalues = { + 0: 'DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING', + 1: 'DP_SYM32_ENC_GSP_TRIGGER_PENDING', +} +DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING = 0 +DP_SYM32_ENC_GSP_TRIGGER_PENDING = 1 +ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM' +ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST', + 1: 'DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST', +} +DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST = 0 +DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST = 1 +DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST = 2 +DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST = 3 +ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_OVERFLOW_STATUS' +ENUM_DP_SYM32_ENC_OVERFLOW_STATUS__enumvalues = { + 0: 'DP_SYM32_ENC_NO_OVERFLOW_OCCURRED', + 1: 'DP_SYM32_ENC_OVERFLOW_OCCURRED', +} +DP_SYM32_ENC_NO_OVERFLOW_OCCURRED = 0 +DP_SYM32_ENC_OVERFLOW_OCCURRED = 1 +ENUM_DP_SYM32_ENC_OVERFLOW_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PENDING' +ENUM_DP_SYM32_ENC_PENDING__enumvalues = { + 0: 'DP_SYM32_ENC_NOT_PENDING', + 1: 'DP_SYM32_ENC_PENDING', +} +DP_SYM32_ENC_NOT_PENDING = 0 +DP_SYM32_ENC_PENDING = 1 +ENUM_DP_SYM32_ENC_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING' +ENUM_DP_SYM32_ENC_PIXEL_ENCODING__enumvalues = { + 0: 'DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444', + 1: 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422', + 2: 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420', + 3: 'DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY', +} +DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444 = 0 +DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422 = 1 +DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420 = 2 +DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY = 3 +ENUM_DP_SYM32_ENC_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE' +ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE__enumvalues = { + 0: 'DP_SYM32_ENC_UNCOMPRESSED_FORMAT', + 1: 'DP_SYM32_ENC_COMPRESSED_FORMAT', +} +DP_SYM32_ENC_UNCOMPRESSED_FORMAT = 0 +DP_SYM32_ENC_COMPRESSED_FORMAT = 1 +ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_POWER_STATE_ENUM' +ENUM_DP_SYM32_ENC_POWER_STATE_ENUM__enumvalues = { + 0: 'DP_SYM32_ENC_POWER_STATE_ENUM_ON', + 1: 'DP_SYM32_ENC_POWER_STATE_ENUM_LS', + 2: 'DP_SYM32_ENC_POWER_STATE_ENUM_DS', + 3: 'DP_SYM32_ENC_POWER_STATE_ENUM_SD', +} +DP_SYM32_ENC_POWER_STATE_ENUM_ON = 0 +DP_SYM32_ENC_POWER_STATE_ENUM_LS = 1 +DP_SYM32_ENC_POWER_STATE_ENUM_DS = 2 +DP_SYM32_ENC_POWER_STATE_ENUM_SD = 3 +ENUM_DP_SYM32_ENC_POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_RESET' +ENUM_DP_SYM32_ENC_RESET__enumvalues = { + 0: 'DP_SYM32_ENC_NOT_RESET', + 1: 'DP_SYM32_ENC_RESET', +} +DP_SYM32_ENC_NOT_RESET = 0 +DP_SYM32_ENC_RESET = 1 +ENUM_DP_SYM32_ENC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_SDP_PRIORITY' +ENUM_DP_SYM32_ENC_SDP_PRIORITY__enumvalues = { + 0: 'DP_SYM32_ENC_SDP_LOW_PRIORITY', + 1: 'DP_SYM32_ENC_SDP_HIGH_PRIORITY', +} +DP_SYM32_ENC_SDP_LOW_PRIORITY = 0 +DP_SYM32_ENC_SDP_HIGH_PRIORITY = 1 +ENUM_DP_SYM32_ENC_SDP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_SOF_REFERENCE' +ENUM_DP_SYM32_ENC_SOF_REFERENCE__enumvalues = { + 0: 'DP_SYM32_ENC_DP_SOF', + 1: 'DP_SYM32_ENC_OTG_SOF', +} +DP_SYM32_ENC_DP_SOF = 0 +DP_SYM32_ENC_OTG_SOF = 1 +ENUM_DP_SYM32_ENC_SOF_REFERENCE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_SYM32_ENC_VID_STREAM_DEFER' +ENUM_DP_SYM32_ENC_VID_STREAM_DEFER__enumvalues = { + 0: 'DP_SYM32_ENC_VID_STREAM_NO_DEFER', + 1: 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK', + 2: 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK', +} +DP_SYM32_ENC_VID_STREAM_NO_DEFER = 0 +DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK = 1 +DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK = 2 +ENUM_DP_SYM32_ENC_VID_STREAM_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_END_EVENT' +ENUM_DP_DPHY_SYM32_CRC_END_EVENT__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_END_LLCP', + 1: 'DP_DPHY_SYM32_CRC_END_PS_ONLY', + 2: 'DP_DPHY_SYM32_CRC_END_PS_LT_SR', + 3: 'DP_DPHY_SYM32_CRC_END_PS_ANY', +} +DP_DPHY_SYM32_CRC_END_LLCP = 0 +DP_DPHY_SYM32_CRC_END_PS_ONLY = 1 +DP_DPHY_SYM32_CRC_END_PS_LT_SR = 2 +DP_DPHY_SYM32_CRC_END_PS_ANY = 3 +ENUM_DP_DPHY_SYM32_CRC_END_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_START_EVENT' +ENUM_DP_DPHY_SYM32_CRC_START_EVENT__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_START_LLCP', + 1: 'DP_DPHY_SYM32_CRC_START_PS_ONLY', + 2: 'DP_DPHY_SYM32_CRC_START_PS_LT_SR', + 3: 'DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR', + 4: 'DP_DPHY_SYM32_CRC_START_TP_START', +} +DP_DPHY_SYM32_CRC_START_LLCP = 0 +DP_DPHY_SYM32_CRC_START_PS_ONLY = 1 +DP_DPHY_SYM32_CRC_START_PS_LT_SR = 2 +DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR = 3 +DP_DPHY_SYM32_CRC_START_TP_START = 4 +ENUM_DP_DPHY_SYM32_CRC_START_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE' +ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER', + 1: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER', + 2: 'DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX', +} +DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER = 0 +DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER = 1 +DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX = 2 +ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS' +ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS__enumvalues = { + 0: 'DP_DPHY_SYM32_CRC_USE_END_EVENT', + 1: 'DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', +} +DP_DPHY_SYM32_CRC_USE_END_EVENT = 0 +DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS = 1 +ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_ENABLE' +ENUM_DP_DPHY_SYM32_ENABLE__enumvalues = { + 0: 'DP_DPHY_SYM32_DISABLE', + 1: 'DP_DPHY_SYM32_ENABLE', +} +DP_DPHY_SYM32_DISABLE = 0 +DP_DPHY_SYM32_ENABLE = 1 +ENUM_DP_DPHY_SYM32_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_MODE' +ENUM_DP_DPHY_SYM32_MODE__enumvalues = { + 0: 'DP_DPHY_SYM32_LT_TPS1', + 1: 'DP_DPHY_SYM32_LT_TPS2', + 2: 'DP_DPHY_SYM32_ACTIVE', + 3: 'DP_DPHY_SYM32_TEST', +} +DP_DPHY_SYM32_LT_TPS1 = 0 +DP_DPHY_SYM32_LT_TPS2 = 1 +DP_DPHY_SYM32_ACTIVE = 2 +DP_DPHY_SYM32_TEST = 3 +ENUM_DP_DPHY_SYM32_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_NUM_LANES' +ENUM_DP_DPHY_SYM32_NUM_LANES__enumvalues = { + 0: 'DP_DPHY_SYM32_1LANE', + 1: 'DP_DPHY_SYM32_2LANE', + 2: 'DP_DPHY_SYM32_RESERVED', + 3: 'DP_DPHY_SYM32_4LANE', +} +DP_DPHY_SYM32_1LANE = 0 +DP_DPHY_SYM32_2LANE = 1 +DP_DPHY_SYM32_RESERVED = 2 +DP_DPHY_SYM32_4LANE = 3 +ENUM_DP_DPHY_SYM32_NUM_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_OUTPUT_MODE' +ENUM_DP_DPHY_SYM32_OUTPUT_MODE__enumvalues = { + 0: 'DP_DPHY_SYM32_OUTPUT_PHY', + 1: 'DP_DPHY_SYM32_OUTPUT_DPIA', +} +DP_DPHY_SYM32_OUTPUT_PHY = 0 +DP_DPHY_SYM32_OUTPUT_DPIA = 1 +ENUM_DP_DPHY_SYM32_OUTPUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING' +ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING__enumvalues = { + 0: 'DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING', + 1: 'DP_DPHY_SYM32_RATE_UPDATE_PENDING', +} +DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING = 0 +DP_DPHY_SYM32_RATE_UPDATE_PENDING = 1 +ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RESET' +ENUM_DP_DPHY_SYM32_RESET__enumvalues = { + 0: 'DP_DPHY_SYM32_NOT_RESET', + 1: 'DP_DPHY_SYM32_RESET', +} +DP_DPHY_SYM32_NOT_RESET = 0 +DP_DPHY_SYM32_RESET = 1 +ENUM_DP_DPHY_SYM32_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_RESET_STATUS' +ENUM_DP_DPHY_SYM32_RESET_STATUS__enumvalues = { + 0: 'DP_DPHY_SYM32_RESET_STATUS_DEASSERTED', + 1: 'DP_DPHY_SYM32_RESET_STATUS_ASSERTED', +} +DP_DPHY_SYM32_RESET_STATUS_DEASSERTED = 0 +DP_DPHY_SYM32_RESET_STATUS_ASSERTED = 1 +ENUM_DP_DPHY_SYM32_RESET_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_SAT_UPDATE' +ENUM_DP_DPHY_SYM32_SAT_UPDATE__enumvalues = { + 0: 'DP_DPHY_SYM32_SAT_NO_UPDATE', + 1: 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE', + 2: 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE', +} +DP_DPHY_SYM32_SAT_NO_UPDATE = 0 +DP_DPHY_SYM32_SAT_TRIGGER_UPDATE = 1 +DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE = 2 +ENUM_DP_DPHY_SYM32_SAT_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING' +ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING__enumvalues = { + 0: 'DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING', + 1: 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING', + 2: 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING', +} +DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING = 0 +DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING = 1 +DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING = 2 +ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_SCHEDULER_STATUS' +ENUM_DP_DPHY_SYM32_SCHEDULER_STATUS__enumvalues = { + 0: 'DP_DPHY_SYM32_SCHEDULER_OFF', + 1: 'DP_DPHY_SYM32_SCHEDULER_ASLEEP', + 2: 'DP_DPHY_SYM32_SCHEDULER_AWAKE', +} +DP_DPHY_SYM32_SCHEDULER_OFF = 0 +DP_DPHY_SYM32_SCHEDULER_ASLEEP = 1 +DP_DPHY_SYM32_SCHEDULER_AWAKE = 2 +ENUM_DP_DPHY_SYM32_SCHEDULER_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STATUS' +ENUM_DP_DPHY_SYM32_STATUS__enumvalues = { + 0: 'DP_DPHY_SYM32_STATUS_IDLE', + 1: 'DP_DPHY_SYM32_STATUS_ENABLED', +} +DP_DPHY_SYM32_STATUS_IDLE = 0 +DP_DPHY_SYM32_STATUS_ENABLED = 1 +ENUM_DP_DPHY_SYM32_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE' +ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE__enumvalues = { + 0: 'DP_DPHY_SYM32_STREAM_OVR_NONE', + 1: 'DP_DPHY_SYM32_STREAM_OVR_REPLACE', + 2: 'DP_DPHY_SYM32_STREAM_OVR_ALWAYS', +} +DP_DPHY_SYM32_STREAM_OVR_NONE = 0 +DP_DPHY_SYM32_STREAM_OVR_REPLACE = 1 +DP_DPHY_SYM32_STREAM_OVR_ALWAYS = 2 +ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE' +ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE__enumvalues = { + 0: 'DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA', + 1: 'DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL', +} +DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA = 0 +DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL = 1 +ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_TP_PRBS_SEL' +ENUM_DP_DPHY_SYM32_TP_PRBS_SEL__enumvalues = { + 0: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7', + 1: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9', + 2: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11', + 3: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15', + 4: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23', + 5: 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31', +} +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7 = 0 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9 = 1 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11 = 2 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15 = 3 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23 = 4 +DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31 = 5 +ENUM_DP_DPHY_SYM32_TP_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_DP_DPHY_SYM32_TP_SELECT' +ENUM_DP_DPHY_SYM32_TP_SELECT__enumvalues = { + 0: 'DP_DPHY_SYM32_TP_SELECT_TPS1', + 1: 'DP_DPHY_SYM32_TP_SELECT_TPS2', + 2: 'DP_DPHY_SYM32_TP_SELECT_PRBS', + 3: 'DP_DPHY_SYM32_TP_SELECT_CUSTOM', + 4: 'DP_DPHY_SYM32_TP_SELECT_SQUARE', +} +DP_DPHY_SYM32_TP_SELECT_TPS1 = 0 +DP_DPHY_SYM32_TP_SELECT_TPS2 = 1 +DP_DPHY_SYM32_TP_SELECT_PRBS = 2 +DP_DPHY_SYM32_TP_SELECT_CUSTOM = 3 +DP_DPHY_SYM32_TP_SELECT_SQUARE = 4 +ENUM_DP_DPHY_SYM32_TP_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'APG_AUDIO_CRC_CONTROL_CH_SEL' +APG_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'APG_AUDIO_CRC_CH0_SIG', + 1: 'APG_AUDIO_CRC_CH1_SIG', + 2: 'APG_AUDIO_CRC_CH2_SIG', + 3: 'APG_AUDIO_CRC_CH3_SIG', + 4: 'APG_AUDIO_CRC_CH4_SIG', + 5: 'APG_AUDIO_CRC_CH5_SIG', + 6: 'APG_AUDIO_CRC_CH6_SIG', + 7: 'APG_AUDIO_CRC_CH7_SIG', + 8: 'APG_AUDIO_CRC_RESERVED_8', + 9: 'APG_AUDIO_CRC_RESERVED_9', + 10: 'APG_AUDIO_CRC_RESERVED_10', + 11: 'APG_AUDIO_CRC_RESERVED_11', + 12: 'APG_AUDIO_CRC_RESERVED_12', + 13: 'APG_AUDIO_CRC_RESERVED_13', + 14: 'APG_AUDIO_CRC_RESERVED_14', + 15: 'APG_AUDIO_CRC_RESERVED_15', +} +APG_AUDIO_CRC_CH0_SIG = 0 +APG_AUDIO_CRC_CH1_SIG = 1 +APG_AUDIO_CRC_CH2_SIG = 2 +APG_AUDIO_CRC_CH3_SIG = 3 +APG_AUDIO_CRC_CH4_SIG = 4 +APG_AUDIO_CRC_CH5_SIG = 5 +APG_AUDIO_CRC_CH6_SIG = 6 +APG_AUDIO_CRC_CH7_SIG = 7 +APG_AUDIO_CRC_RESERVED_8 = 8 +APG_AUDIO_CRC_RESERVED_9 = 9 +APG_AUDIO_CRC_RESERVED_10 = 10 +APG_AUDIO_CRC_RESERVED_11 = 11 +APG_AUDIO_CRC_RESERVED_12 = 12 +APG_AUDIO_CRC_RESERVED_13 = 13 +APG_AUDIO_CRC_RESERVED_14 = 14 +APG_AUDIO_CRC_RESERVED_15 = 15 +APG_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_AUDIO_CRC_CONTROL_CONT' +APG_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'APG_AUDIO_CRC_ONESHOT', + 1: 'APG_AUDIO_CRC_CONTINUOUS', +} +APG_AUDIO_CRC_ONESHOT = 0 +APG_AUDIO_CRC_CONTINUOUS = 1 +APG_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_ACP_TYPE' +APG_DBG_ACP_TYPE__enumvalues = { + 0: 'APG_ACP_TYPE_GENERIC_AUDIO', + 1: 'APG_ACP_TYPE_ICE60958_AUDIO', + 2: 'APG_ACP_TYPE_DVD_AUDIO', + 3: 'APG_ACP_TYPE_SUPER_AUDIO_CD', +} +APG_ACP_TYPE_GENERIC_AUDIO = 0 +APG_ACP_TYPE_ICE60958_AUDIO = 1 +APG_ACP_TYPE_DVD_AUDIO = 2 +APG_ACP_TYPE_SUPER_AUDIO_CD = 3 +APG_DBG_ACP_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_BASE' +APG_DBG_AUDIO_DTO_BASE__enumvalues = { + 0: 'BASE_RATE_48KHZ', + 1: 'BASE_RATE_44P1KHZ', +} +BASE_RATE_48KHZ = 0 +BASE_RATE_44P1KHZ = 1 +APG_DBG_AUDIO_DTO_BASE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_DIV' +APG_DBG_AUDIO_DTO_DIV__enumvalues = { + 0: 'DIVISOR_BY1', + 1: 'DIVISOR_BY2_RESERVED', + 2: 'DIVISOR_BY3', + 3: 'DIVISOR_BY4_RESERVED', + 4: 'DIVISOR_BY5_RESERVED', + 5: 'DIVISOR_BY6_RESERVED', + 6: 'DIVISOR_BY7_RESERVED', + 7: 'DIVISOR_BY8_RESERVED', +} +DIVISOR_BY1 = 0 +DIVISOR_BY2_RESERVED = 1 +DIVISOR_BY3 = 2 +DIVISOR_BY4_RESERVED = 3 +DIVISOR_BY5_RESERVED = 4 +DIVISOR_BY6_RESERVED = 5 +DIVISOR_BY7_RESERVED = 6 +DIVISOR_BY8_RESERVED = 7 +APG_DBG_AUDIO_DTO_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_AUDIO_DTO_MULTI' +APG_DBG_AUDIO_DTO_MULTI__enumvalues = { + 0: 'MULTIPLE_BY1', + 1: 'MULTIPLE_BY2', + 2: 'MULTIPLE_BY3_RESERVED', + 3: 'MULTIPLE_BY4', + 4: 'MULTIPLE_RESERVED', +} +MULTIPLE_BY1 = 0 +MULTIPLE_BY2 = 1 +MULTIPLE_BY3_RESERVED = 2 +MULTIPLE_BY4 = 3 +MULTIPLE_RESERVED = 4 +APG_DBG_AUDIO_DTO_MULTI = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DBG_MUX_SEL' +APG_DBG_MUX_SEL__enumvalues = { + 0: 'APG_FUNCTIONAL_MODE', + 1: 'APG_DEBUG_AUDIO_MODE', +} +APG_FUNCTIONAL_MODE = 0 +APG_DEBUG_AUDIO_MODE = 1 +APG_DBG_MUX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE' +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'APG_DP_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +APG_DP_ASP_CHANNEL_COUNT_FROM_AZ = 0 +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +APG_DP_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_POWER_STATE' +APG_MEM_POWER_STATE__enumvalues = { + 0: 'APG_MEM_POWER_STATE_ON', + 1: 'APG_MEM_POWER_STATE_LS', + 2: 'APG_MEM_POWER_STATE_DS', + 3: 'APG_MEM_POWER_STATE_SD', +} +APG_MEM_POWER_STATE_ON = 0 +APG_MEM_POWER_STATE_LS = 1 +APG_MEM_POWER_STATE_DS = 2 +APG_MEM_POWER_STATE_SD = 3 +APG_MEM_POWER_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_PWR_DIS_CTRL' +APG_MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'APG_MEM_ENABLE_MEM_PWR_CTRL', + 1: 'APG_MEM_DISABLE_MEM_PWR_CTRL', +} +APG_MEM_ENABLE_MEM_PWR_CTRL = 0 +APG_MEM_DISABLE_MEM_PWR_CTRL = 1 +APG_MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_MEM_PWR_FORCE_CTRL' +APG_MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'APG_MEM_NO_FORCE_REQUEST', + 1: 'APG_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'APG_MEM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'APG_MEM_FORCE_SHUT_DOWN_REQUEST', +} +APG_MEM_NO_FORCE_REQUEST = 0 +APG_MEM_FORCE_LIGHT_SLEEP_REQUEST = 1 +APG_MEM_FORCE_DEEP_SLEEP_REQUEST = 2 +APG_MEM_FORCE_SHUT_DOWN_REQUEST = 3 +APG_MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'APG_PACKET_CONTROL_ACP_SOURCE' +APG_PACKET_CONTROL_ACP_SOURCE__enumvalues = { + 0: 'APG_ACP_SOURCE_NO_OVERRIDE', + 1: 'APG_ACP_OVERRIDE', +} +APG_ACP_SOURCE_NO_OVERRIDE = 0 +APG_ACP_OVERRIDE = 1 +APG_PACKET_CONTROL_ACP_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_PACKET_CONTROL_AUDIO_INFO_SOURCE' +APG_PACKET_CONTROL_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'APG_INFOFRAME_SOURCE_NO_OVERRIDE', + 1: 'APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS', +} +APG_INFOFRAME_SOURCE_NO_OVERRIDE = 0 +APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS = 1 +APG_PACKET_CONTROL_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'APG_RAMP_CONTROL_SIGN' +APG_RAMP_CONTROL_SIGN__enumvalues = { + 0: 'APG_RAMP_SIGNED', + 1: 'APG_RAMP_UNSIGNED', +} +APG_RAMP_SIGNED = 0 +APG_RAMP_UNSIGNED = 1 +APG_RAMP_CONTROL_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL' +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 1: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 2: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 3: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 4: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 5: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', +} +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1 = 0 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2 = 1 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3 = 2 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4 = 3 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5 = 4 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6 = 5 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL' +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL__enumvalues = { + 0: 'DCIO_TEST_CLK_SEL_DISPCLK', + 1: 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', + 2: 'DCIO_TEST_CLK_SEL_SOCCLK', +} +DCIO_TEST_CLK_SEL_DISPCLK = 0 +DCIO_TEST_CLK_SEL_GATED_DISPCLK = 1 +DCIO_TEST_CLK_SEL_SOCCLK = 2 +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS' +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS__enumvalues = { + 0: 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 1: 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', +} +DCIO_DISPCLK_R_DCIO_GATE_DISABLE = 0 +DCIO_DISPCLK_R_DCIO_GATE_ENABLE = 1 +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_4BIT_SEL' +DCIO_DBG_ASYNC_4BIT_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 1: 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', + 2: 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 3: 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 4: 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 5: 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 6: 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 7: 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', +} +DCIO_DBG_ASYNC_4BIT_SEL_3TO0 = 0 +DCIO_DBG_ASYNC_4BIT_SEL_7TO4 = 1 +DCIO_DBG_ASYNC_4BIT_SEL_11TO8 = 2 +DCIO_DBG_ASYNC_4BIT_SEL_15TO12 = 3 +DCIO_DBG_ASYNC_4BIT_SEL_19TO16 = 4 +DCIO_DBG_ASYNC_4BIT_SEL_23TO20 = 5 +DCIO_DBG_ASYNC_4BIT_SEL_27TO24 = 6 +DCIO_DBG_ASYNC_4BIT_SEL_31TO28 = 7 +DCIO_DBG_ASYNC_4BIT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_BLOCK_SEL' +DCIO_DBG_ASYNC_BLOCK_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', + 1: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', + 2: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 3: 'DCIO_DBG_ASYNC_BLOCK_SEL_DIO', +} +DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE = 0 +DCIO_DBG_ASYNC_BLOCK_SEL_DCCG = 1 +DCIO_DBG_ASYNC_BLOCK_SEL_DCIO = 2 +DCIO_DBG_ASYNC_BLOCK_SEL_DIO = 3 +DCIO_DBG_ASYNC_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCRXPHY_SOFT_RESET' +DCIO_DCRXPHY_SOFT_RESET__enumvalues = { + 0: 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 1: 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', +} +DCIO_DCRXPHY_SOFT_RESET_DEASSERT = 0 +DCIO_DCRXPHY_SOFT_RESET_ASSERT = 1 +DCIO_DCRXPHY_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICA_SEL' +DCIO_DC_GENERICA_SEL__enumvalues = { + 1: 'DCIO_GENERICA_SEL_STEREOSYNC', + 10: 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 11: 'DCIO_GENERICA_SEL_SYNCEN', +} +DCIO_GENERICA_SEL_STEREOSYNC = 1 +DCIO_GENERICA_SEL_GENERICA_DCCG = 10 +DCIO_GENERICA_SEL_SYNCEN = 11 +DCIO_DC_GENERICA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICB_SEL' +DCIO_DC_GENERICB_SEL__enumvalues = { + 1: 'DCIO_GENERICB_SEL_STEREOSYNC', + 10: 'DCIO_GENERICB_SEL_GENERICB_DCCG', + 11: 'DCIO_GENERICB_SEL_SYNCEN', +} +DCIO_GENERICB_SEL_STEREOSYNC = 1 +DCIO_GENERICB_SEL_GENERICB_DCCG = 10 +DCIO_GENERICB_SEL_SYNCEN = 11 +DCIO_DC_GENERICB_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 1: 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 2: 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 3: 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 4: 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 5: 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 6: 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', +} +DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2 = 0 +DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2 = 1 +DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2 = 2 +DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2 = 3 +DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2 = 4 +DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2 = 5 +DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2 = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_CLK', +} +DCIO_UNIPHYA_FBDIV_CLK = 0 +DCIO_UNIPHYB_FBDIV_CLK = 1 +DCIO_UNIPHYC_FBDIV_CLK = 2 +DCIO_UNIPHYD_FBDIV_CLK = 3 +DCIO_UNIPHYE_FBDIV_CLK = 4 +DCIO_UNIPHYF_FBDIV_CLK = 5 +DCIO_UNIPHYG_FBDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_SSC_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_SSC_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_SSC_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_SSC_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_SSC_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_SSC_CLK', +} +DCIO_UNIPHYA_FBDIV_SSC_CLK = 0 +DCIO_UNIPHYB_FBDIV_SSC_CLK = 1 +DCIO_UNIPHYC_FBDIV_SSC_CLK = 2 +DCIO_UNIPHYD_FBDIV_SSC_CLK = 3 +DCIO_UNIPHYE_FBDIV_SSC_CLK = 4 +DCIO_UNIPHYF_FBDIV_SSC_CLK = 5 +DCIO_UNIPHYG_FBDIV_SSC_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_REFDIV_CLK', + 1: 'DCIO_UNIPHYB_TEST_REFDIV_CLK', + 2: 'DCIO_UNIPHYC_TEST_REFDIV_CLK', + 3: 'DCIO_UNIPHYD_TEST_REFDIV_CLK', + 4: 'DCIO_UNIPHYE_TEST_REFDIV_CLK', + 5: 'DCIO_UNIPHYF_TEST_REFDIV_CLK', + 6: 'DCIO_UNIPHYG_TEST_REFDIV_CLK', +} +DCIO_UNIPHYA_TEST_REFDIV_CLK = 0 +DCIO_UNIPHYB_TEST_REFDIV_CLK = 1 +DCIO_UNIPHYC_TEST_REFDIV_CLK = 2 +DCIO_UNIPHYD_TEST_REFDIV_CLK = 3 +DCIO_UNIPHYE_TEST_REFDIV_CLK = 4 +DCIO_UNIPHYF_TEST_REFDIV_CLK = 5 +DCIO_UNIPHYG_TEST_REFDIV_CLK = 6 +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE' +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE__enumvalues = { + 0: 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', + 1: 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', +} +DCIO_DPRX_LOOPBACK_ENABLE_NORMAL = 0 +DCIO_DPRX_LOOPBACK_ENABLE_LOOP = 1 +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_READ_SELECT' +DCIO_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 1: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 2: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 3: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 4: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 5: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', +} +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE = 0 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE = 1 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP = 2 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP = 3 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM = 4 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM = 5 +DCIO_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_START_POSITION' +DCIO_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DCIO_GPU_TIMER_START_0_END_27', + 1: 'DCIO_GPU_TIMER_START_1_END_28', + 2: 'DCIO_GPU_TIMER_START_2_END_29', + 3: 'DCIO_GPU_TIMER_START_3_END_30', + 4: 'DCIO_GPU_TIMER_START_4_END_31', + 5: 'DCIO_GPU_TIMER_START_6_END_33', + 6: 'DCIO_GPU_TIMER_START_8_END_35', + 7: 'DCIO_GPU_TIMER_START_10_END_37', +} +DCIO_GPU_TIMER_START_0_END_27 = 0 +DCIO_GPU_TIMER_START_1_END_28 = 1 +DCIO_GPU_TIMER_START_2_END_29 = 2 +DCIO_GPU_TIMER_START_3_END_30 = 3 +DCIO_GPU_TIMER_START_4_END_31 = 4 +DCIO_GPU_TIMER_START_6_END_33 = 5 +DCIO_GPU_TIMER_START_8_END_35 = 6 +DCIO_GPU_TIMER_START_10_END_37 = 7 +DCIO_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 1: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 2: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 3: 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', +} +DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE = 0 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1 = 1 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2 = 2 +DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3 = 3 +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_EXT_VSYNC_MASK' +DCIO_DIO_EXT_VSYNC_MASK__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MASK_NONE', + 1: 'DCIO_EXT_VSYNC_MASK_PIPE0', + 2: 'DCIO_EXT_VSYNC_MASK_PIPE1', + 3: 'DCIO_EXT_VSYNC_MASK_PIPE2', + 4: 'DCIO_EXT_VSYNC_MASK_PIPE3', + 5: 'DCIO_EXT_VSYNC_MASK_PIPE4', + 6: 'DCIO_EXT_VSYNC_MASK_PIPE5', + 7: 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', +} +DCIO_EXT_VSYNC_MASK_NONE = 0 +DCIO_EXT_VSYNC_MASK_PIPE0 = 1 +DCIO_EXT_VSYNC_MASK_PIPE1 = 2 +DCIO_EXT_VSYNC_MASK_PIPE2 = 3 +DCIO_EXT_VSYNC_MASK_PIPE3 = 4 +DCIO_EXT_VSYNC_MASK_PIPE4 = 5 +DCIO_EXT_VSYNC_MASK_PIPE5 = 6 +DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE = 7 +DCIO_DIO_EXT_VSYNC_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DIO_OTG_EXT_VSYNC_MUX' +DCIO_DIO_OTG_EXT_VSYNC_MUX__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 1: 'DCIO_EXT_VSYNC_MUX_OTG0', + 2: 'DCIO_EXT_VSYNC_MUX_OTG1', + 3: 'DCIO_EXT_VSYNC_MUX_OTG2', + 4: 'DCIO_EXT_VSYNC_MUX_OTG3', + 5: 'DCIO_EXT_VSYNC_MUX_OTG4', + 6: 'DCIO_EXT_VSYNC_MUX_OTG5', + 7: 'DCIO_EXT_VSYNC_MUX_GENERICB', +} +DCIO_EXT_VSYNC_MUX_SWAPLOCKB = 0 +DCIO_EXT_VSYNC_MUX_OTG0 = 1 +DCIO_EXT_VSYNC_MUX_OTG1 = 2 +DCIO_EXT_VSYNC_MUX_OTG2 = 3 +DCIO_EXT_VSYNC_MUX_OTG3 = 4 +DCIO_EXT_VSYNC_MUX_OTG4 = 5 +DCIO_EXT_VSYNC_MUX_OTG5 = 6 +DCIO_EXT_VSYNC_MUX_GENERICB = 7 +DCIO_DIO_OTG_EXT_VSYNC_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_MASK' +DCIO_DPCS_INTERRUPT_MASK__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_DISABLE', + 1: 'DCIO_DPCS_INTERRUPT_ENABLE', +} +DCIO_DPCS_INTERRUPT_DISABLE = 0 +DCIO_DPCS_INTERRUPT_ENABLE = 1 +DCIO_DPCS_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_TYPE' +DCIO_DPCS_INTERRUPT_TYPE__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', +} +DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED = 0 +DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED = 1 +DCIO_DPCS_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_CLK_GSL_MASK' +DCIO_GENLK_CLK_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_CLK_GSL_MASK_NO', + 1: 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_CLK_GSL_MASK_STEREO', +} +DCIO_GENLK_CLK_GSL_MASK_NO = 0 +DCIO_GENLK_CLK_GSL_MASK_TIMING = 1 +DCIO_GENLK_CLK_GSL_MASK_STEREO = 2 +DCIO_GENLK_CLK_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_VSYNC_GSL_MASK' +DCIO_GENLK_VSYNC_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 1: 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', +} +DCIO_GENLK_VSYNC_GSL_MASK_NO = 0 +DCIO_GENLK_VSYNC_GSL_MASK_TIMING = 1 +DCIO_GENLK_VSYNC_GSL_MASK_STEREO = 2 +DCIO_GENLK_VSYNC_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL_SEL' +DCIO_GSL_SEL__enumvalues = { + 0: 'DCIO_GSL_SEL_GROUP_0', + 1: 'DCIO_GSL_SEL_GROUP_1', + 2: 'DCIO_GSL_SEL_GROUP_2', +} +DCIO_GSL_SEL_GROUP_0 = 0 +DCIO_GSL_SEL_GROUP_1 = 1 +DCIO_GSL_SEL_GROUP_2 = 2 +DCIO_GSL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_PHY_HPO_ENC_SRC_SEL' +DCIO_PHY_HPO_ENC_SRC_SEL__enumvalues = { + 0: 'HPO_SRC0', + 1: 'HPO_SRC_RESERVED', +} +HPO_SRC0 = 0 +HPO_SRC_RESERVED = 1 +DCIO_PHY_HPO_ENC_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_A_GSL_MASK' +DCIO_SWAPLOCK_A_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_A_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_A_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_A_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_A_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_B_GSL_MASK' +DCIO_SWAPLOCK_B_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_B_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_B_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_B_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_B_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_B_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE' +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 1: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 2: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 3: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', +} +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0 = 0 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1 = 1 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2 = 2 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3 = 3 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_IMPCAL_SEL' +DCIO_UNIPHY_IMPCAL_SEL__enumvalues = { + 0: 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 1: 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', +} +DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE = 0 +DCIO_UNIPHY_IMPCAL_SEL_BINARY = 1 +DCIO_UNIPHY_IMPCAL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT' +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 1: 'DCIO_UNIPHY_CHANNEL_INVERTED', +} +DCIO_UNIPHY_CHANNEL_NO_INVERSION = 0 +DCIO_UNIPHY_CHANNEL_INVERTED = 1 +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK' +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK__enumvalues = { + 0: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 1: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 2: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 3: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', +} +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW = 0 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW = 1 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED = 2 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED = 3 +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_ALL_PWR_OK' +DCIOCHIP_AUX_ALL_PWR_OK__enumvalues = { + 0: 'DCIOCHIP_AUX_ALL_PWR_OK_0', + 1: 'DCIOCHIP_AUX_ALL_PWR_OK_1', +} +DCIOCHIP_AUX_ALL_PWR_OK_0 = 0 +DCIOCHIP_AUX_ALL_PWR_OK_1 = 1 +DCIOCHIP_AUX_ALL_PWR_OK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL0P9' +DCIOCHIP_AUX_CSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_CSEL_DEC0P9', +} +DCIOCHIP_AUX_CSEL_DEC1P0 = 0 +DCIOCHIP_AUX_CSEL_DEC0P9 = 1 +DCIOCHIP_AUX_CSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL1P1' +DCIOCHIP_AUX_CSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_INC1P0', + 1: 'DCIOCHIP_AUX_CSEL_INC1P1', +} +DCIOCHIP_AUX_CSEL_INC1P0 = 0 +DCIOCHIP_AUX_CSEL_INC1P1 = 1 +DCIOCHIP_AUX_CSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_FALLSLEWSEL' +DCIOCHIP_AUX_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 1: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 2: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', + 3: 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', +} +DCIOCHIP_AUX_FALLSLEWSEL_LOW = 0 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH0 = 1 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH1 = 2 +DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH = 3 +DCIOCHIP_AUX_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_HYS_TUNE' +DCIOCHIP_AUX_HYS_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_HYS_TUNE_0', + 1: 'DCIOCHIP_AUX_HYS_TUNE_1', + 2: 'DCIOCHIP_AUX_HYS_TUNE_2', + 3: 'DCIOCHIP_AUX_HYS_TUNE_3', +} +DCIOCHIP_AUX_HYS_TUNE_0 = 0 +DCIOCHIP_AUX_HYS_TUNE_1 = 1 +DCIOCHIP_AUX_HYS_TUNE_2 = 2 +DCIOCHIP_AUX_HYS_TUNE_3 = 3 +DCIOCHIP_AUX_HYS_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RECEIVER_SEL' +DCIOCHIP_AUX_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 1: 'DCIOCHIP_AUX_RECEIVER_SEL_1', + 2: 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 3: 'DCIOCHIP_AUX_RECEIVER_SEL_3', +} +DCIOCHIP_AUX_RECEIVER_SEL_0 = 0 +DCIOCHIP_AUX_RECEIVER_SEL_1 = 1 +DCIOCHIP_AUX_RECEIVER_SEL_2 = 2 +DCIOCHIP_AUX_RECEIVER_SEL_3 = 3 +DCIOCHIP_AUX_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL0P9' +DCIOCHIP_AUX_RSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_RSEL_DEC0P9', +} +DCIOCHIP_AUX_RSEL_DEC1P0 = 0 +DCIOCHIP_AUX_RSEL_DEC0P9 = 1 +DCIOCHIP_AUX_RSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL1P1' +DCIOCHIP_AUX_RSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_INC1P0', + 1: 'DCIOCHIP_AUX_RSEL_INC1P1', +} +DCIOCHIP_AUX_RSEL_INC1P0 = 0 +DCIOCHIP_AUX_RSEL_INC1P1 = 1 +DCIOCHIP_AUX_RSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_SPIKESEL' +DCIOCHIP_AUX_SPIKESEL__enumvalues = { + 0: 'DCIOCHIP_AUX_SPIKESEL_50NS', + 1: 'DCIOCHIP_AUX_SPIKESEL_10NS', +} +DCIOCHIP_AUX_SPIKESEL_50NS = 0 +DCIOCHIP_AUX_SPIKESEL_10NS = 1 +DCIOCHIP_AUX_SPIKESEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_VOD_TUNE' +DCIOCHIP_AUX_VOD_TUNE__enumvalues = { + 0: 'DCIOCHIP_AUX_VOD_TUNE_0', + 1: 'DCIOCHIP_AUX_VOD_TUNE_1', + 2: 'DCIOCHIP_AUX_VOD_TUNE_2', + 3: 'DCIOCHIP_AUX_VOD_TUNE_3', +} +DCIOCHIP_AUX_VOD_TUNE_0 = 0 +DCIOCHIP_AUX_VOD_TUNE_1 = 1 +DCIOCHIP_AUX_VOD_TUNE_2 = 2 +DCIOCHIP_AUX_VOD_TUNE_3 = 3 +DCIOCHIP_AUX_VOD_TUNE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_MASK_EN' +DCIOCHIP_GPIO_MASK_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 1: 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', +} +DCIOCHIP_GPIO_MASK_EN_HARDWARE = 0 +DCIOCHIP_GPIO_MASK_EN_SOFTWARE = 1 +DCIOCHIP_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_HPD_SEL' +DCIOCHIP_HPD_SEL__enumvalues = { + 0: 'DCIOCHIP_HPD_SEL_ASYNC', + 1: 'DCIOCHIP_HPD_SEL_CLOCKED', +} +DCIOCHIP_HPD_SEL_ASYNC = 0 +DCIOCHIP_HPD_SEL_CLOCKED = 1 +DCIOCHIP_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_COMPSEL' +DCIOCHIP_I2C_COMPSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_REC_SCHMIT', + 1: 'DCIOCHIP_I2C_REC_COMPARATOR', +} +DCIOCHIP_I2C_REC_SCHMIT = 0 +DCIOCHIP_I2C_REC_COMPARATOR = 1 +DCIOCHIP_I2C_COMPSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_FALLSLEWSEL' +DCIOCHIP_I2C_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_I2C_FALLSLEWSEL_00', + 1: 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 2: 'DCIOCHIP_I2C_FALLSLEWSEL_10', + 3: 'DCIOCHIP_I2C_FALLSLEWSEL_11', +} +DCIOCHIP_I2C_FALLSLEWSEL_00 = 0 +DCIOCHIP_I2C_FALLSLEWSEL_01 = 1 +DCIOCHIP_I2C_FALLSLEWSEL_10 = 2 +DCIOCHIP_I2C_FALLSLEWSEL_11 = 3 +DCIOCHIP_I2C_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_RECEIVER_SEL' +DCIOCHIP_I2C_RECEIVER_SEL__enumvalues = { + 0: 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 1: 'DCIOCHIP_I2C_RECEIVER_SEL_1', + 2: 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 3: 'DCIOCHIP_I2C_RECEIVER_SEL_3', +} +DCIOCHIP_I2C_RECEIVER_SEL_0 = 0 +DCIOCHIP_I2C_RECEIVER_SEL_1 = 1 +DCIOCHIP_I2C_RECEIVER_SEL_2 = 2 +DCIOCHIP_I2C_RECEIVER_SEL_3 = 3 +DCIOCHIP_I2C_RECEIVER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_I2C_VPH_1V2_EN' +DCIOCHIP_I2C_VPH_1V2_EN__enumvalues = { + 0: 'DCIOCHIP_I2C_VPH_1V2_EN_0', + 1: 'DCIOCHIP_I2C_VPH_1V2_EN_1', +} +DCIOCHIP_I2C_VPH_1V2_EN_0 = 0 +DCIOCHIP_I2C_VPH_1V2_EN_1 = 1 +DCIOCHIP_I2C_VPH_1V2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_INVERT' +DCIOCHIP_INVERT__enumvalues = { + 0: 'DCIOCHIP_POL_NON_INVERT', + 1: 'DCIOCHIP_POL_INVERT', +} +DCIOCHIP_POL_NON_INVERT = 0 +DCIOCHIP_POL_INVERT = 1 +DCIOCHIP_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK' +DCIOCHIP_MASK__enumvalues = { + 0: 'DCIOCHIP_MASK_DISABLE', + 1: 'DCIOCHIP_MASK_ENABLE', +} +DCIOCHIP_MASK_DISABLE = 0 +DCIOCHIP_MASK_ENABLE = 1 +DCIOCHIP_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PAD_MODE' +DCIOCHIP_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_PAD_MODE_DDC', + 1: 'DCIOCHIP_PAD_MODE_DP', +} +DCIOCHIP_PAD_MODE_DDC = 0 +DCIOCHIP_PAD_MODE_DP = 1 +DCIOCHIP_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PD_EN' +DCIOCHIP_PD_EN__enumvalues = { + 0: 'DCIOCHIP_PD_EN_NOTALLOW', + 1: 'DCIOCHIP_PD_EN_ALLOW', +} +DCIOCHIP_PD_EN_NOTALLOW = 0 +DCIOCHIP_PD_EN_ALLOW = 1 +DCIOCHIP_PD_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_REF_27_SRC_SEL' +DCIOCHIP_REF_27_SRC_SEL__enumvalues = { + 0: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 1: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 2: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 3: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', +} +DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER = 0 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER = 1 +DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS = 2 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS = 3 +DCIOCHIP_REF_27_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE' +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE__enumvalues = { + 0: 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 1: 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE', +} +PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE = 0 +PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN' +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL', + 1: 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM', +} +PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL = 0 +PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM = 1 +PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT' +PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT__enumvalues = { + 0: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 1: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 2: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 3: 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', +} +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL = 0 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1 = 1 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2 = 2 +PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3 = 3 +PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL_BL_PWM_EN' +PWRSEQ_BL_PWM_CNTL_BL_PWM_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_DISABLE', + 1: 'PWRSEQ_BL_PWM_ENABLE', +} +PWRSEQ_BL_PWM_DISABLE = 0 +PWRSEQ_BL_PWM_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL_BL_PWM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN' +PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_FRACTIONAL_DISABLE', + 1: 'PWRSEQ_BL_PWM_FRACTIONAL_ENABLE', +} +PWRSEQ_BL_PWM_FRACTIONAL_DISABLE = 0 +PWRSEQ_BL_PWM_FRACTIONAL_ENABLE = 1 +PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN' +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', +} +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE = 0 +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE = 1 +PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN' +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 1: 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', +} +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM = 0 +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM = 1 +PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_REG_LOCK' +PWRSEQ_BL_PWM_GRP1_REG_LOCK__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE', +} +PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE = 0 +PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE = 1 +PWRSEQ_BL_PWM_GRP1_REG_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START' +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START__enumvalues = { + 0: 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 1: 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', +} +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE = 0 +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE = 1 +PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_GPIO_MASK_EN' +PWRSEQ_GPIO_MASK_EN__enumvalues = { + 0: 'PWRSEQ_GPIO_MASK_EN_HARDWARE', + 1: 'PWRSEQ_GPIO_MASK_EN_SOFTWARE', +} +PWRSEQ_GPIO_MASK_EN_HARDWARE = 0 +PWRSEQ_GPIO_MASK_EN_SOFTWARE = 1 +PWRSEQ_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON__enumvalues = { + 0: 'PWRSEQ_PANEL_BLON_OFF', + 1: 'PWRSEQ_PANEL_BLON_ON', +} +PWRSEQ_PANEL_BLON_OFF = 0 +PWRSEQ_PANEL_BLON_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_BLON_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_BLON_POL_INVERT', +} +PWRSEQ_PANEL_BLON_POL_NON_INVERT = 0 +PWRSEQ_PANEL_BLON_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON__enumvalues = { + 0: 'PWRSEQ_PANEL_DIGON_OFF', + 1: 'PWRSEQ_PANEL_DIGON_ON', +} +PWRSEQ_PANEL_DIGON_OFF = 0 +PWRSEQ_PANEL_DIGON_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_DIGON_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_DIGON_POL_INVERT', +} +PWRSEQ_PANEL_DIGON_POL_NON_INVERT = 0 +PWRSEQ_PANEL_DIGON_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL' +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL__enumvalues = { + 0: 'PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT', + 1: 'PWRSEQ_PANEL_SYNCEN_POL_INVERT', +} +PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT = 0 +PWRSEQ_PANEL_SYNCEN_POL_INVERT = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE' +PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE__enumvalues = { + 0: 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF', + 1: 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON', +} +PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF = 0 +PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON = 1 +PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN' +PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN__enumvalues = { + 0: 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON', + 1: 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE', +} +PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON = 0 +PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE = 1 +PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_CORB_SIZE' +AZ_CORB_SIZE__enumvalues = { + 0: 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_CORB_SIZE_256ENTRIES', + 3: 'AZ_CORB_SIZE_RESERVED', +} +AZ_CORB_SIZE_2ENTRIES_RESERVED = 0 +AZ_CORB_SIZE_16ENTRIES_RESERVED = 1 +AZ_CORB_SIZE_256ENTRIES = 2 +AZ_CORB_SIZE_RESERVED = 3 +AZ_CORB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_GLOBAL_CAPABILITIES' +AZ_GLOBAL_CAPABILITIES__enumvalues = { + 0: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 1: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', +} +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED = 0 +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED = 1 +AZ_GLOBAL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_SIZE' +AZ_RIRB_SIZE__enumvalues = { + 0: 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_RIRB_SIZE_256ENTRIES', + 3: 'AZ_RIRB_SIZE_UNDEFINED', +} +AZ_RIRB_SIZE_2ENTRIES_RESERVED = 0 +AZ_RIRB_SIZE_16ENTRIES_RESERVED = 1 +AZ_RIRB_SIZE_256ENTRIES = 2 +AZ_RIRB_SIZE_UNDEFINED = 3 +AZ_RIRB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_WRITE_POINTER_RESET' +AZ_RIRB_WRITE_POINTER_RESET__enumvalues = { + 0: 'AZ_RIRB_WRITE_POINTER_NOT_RESET', + 1: 'AZ_RIRB_WRITE_POINTER_DO_RESET', +} +AZ_RIRB_WRITE_POINTER_NOT_RESET = 0 +AZ_RIRB_WRITE_POINTER_DO_RESET = 1 +AZ_RIRB_WRITE_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_STATE_CHANGE_STATUS' +AZ_STATE_CHANGE_STATUS__enumvalues = { + 0: 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 1: 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', +} +AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT = 0 +AZ_STATE_CHANGE_STATUS_CODEC_PRESENT = 1 +AZ_STATE_CHANGE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'CORB_READ_POINTER_RESET' +CORB_READ_POINTER_RESET__enumvalues = { + 0: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 1: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', +} +CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET = 0 +CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET = 1 +CORB_READ_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE' +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE__enumvalues = { + 0: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 1: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', +} +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE = 0 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE = 1 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE' +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE__enumvalues = { + 0: 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', + 1: 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', +} +ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE = 0 +ACCEPT_UNSOLICITED_RESPONSE_ENABLE = 1 +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_CONTROLLER_RESET' +GLOBAL_CONTROL_CONTROLLER_RESET__enumvalues = { + 0: 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 1: 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', +} +CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET = 0 +CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET = 1 +GLOBAL_CONTROL_CONTROLLER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_FLUSH_CONTROL' +GLOBAL_CONTROL_FLUSH_CONTROL__enumvalues = { + 0: 'FLUSH_CONTROL_FLUSH_NOT_STARTED', + 1: 'FLUSH_CONTROL_FLUSH_STARTED', +} +FLUSH_CONTROL_FLUSH_NOT_STARTED = 0 +FLUSH_CONTROL_FLUSH_STARTED = 1 +GLOBAL_CONTROL_FLUSH_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_STATUS_FLUSH_STATUS' +GLOBAL_STATUS_FLUSH_STATUS__enumvalues = { + 0: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 1: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', +} +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED = 0 +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED = 1 +GLOBAL_STATUS_FLUSH_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_0_SYNCHRONIZATION' +STREAM_0_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_0_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_0_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_10_SYNCHRONIZATION' +STREAM_10_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_10_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_11_SYNCHRONIZATION' +STREAM_11_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_11_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_12_SYNCHRONIZATION' +STREAM_12_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_12_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_13_SYNCHRONIZATION' +STREAM_13_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_13_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_14_SYNCHRONIZATION' +STREAM_14_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_14_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_15_SYNCHRONIZATION' +STREAM_15_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_15_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_1_SYNCHRONIZATION' +STREAM_1_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_1_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_1_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_2_SYNCHRONIZATION' +STREAM_2_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_2_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_2_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_3_SYNCHRONIZATION' +STREAM_3_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_3_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_3_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_4_SYNCHRONIZATION' +STREAM_4_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_4_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_5_SYNCHRONIZATION' +STREAM_5_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_5_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_6_SYNCHRONIZATION' +STREAM_6_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_6_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_7_SYNCHRONIZATION' +STREAM_7_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_7_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_8_SYNCHRONIZATION' +STREAM_8_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_8_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_9_SYNCHRONIZATION' +STREAM_9_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_9_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE' +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 2: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 3: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 4: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 5: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 6: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 7: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 8: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 9: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 10: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 11: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 12: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 13: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 14: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 15: 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', +} +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0 = 0 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1 = 1 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2 = 2 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3 = 3 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4 = 4 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5 = 5 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6 = 6 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7 = 7 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8 = 8 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9 = 9 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10 = 10 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11 = 11 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12 = 12 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13 = 13 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14 = 14 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15 = 15 +AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT' +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET' +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET__enumvalues = { + 0: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 1: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', +} +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET = 0 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC = 1 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_CTRL' +MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'ENABLE_MEM_PWR_CTRL', + 1: 'DISABLE_MEM_PWR_CTRL', +} +ENABLE_MEM_PWR_CTRL = 0 +DISABLE_MEM_PWR_CTRL = 1 +MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL' +MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'NO_FORCE_REQUEST', + 1: 'FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FORCE_DEEP_SLEEP_REQUEST', + 3: 'FORCE_SHUT_DOWN_REQUEST', +} +NO_FORCE_REQUEST = 0 +FORCE_LIGHT_SLEEP_REQUEST = 1 +FORCE_DEEP_SLEEP_REQUEST = 2 +FORCE_SHUT_DOWN_REQUEST = 3 +MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL2' +MEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'NO_FORCE_REQ', + 1: 'FORCE_LIGHT_SLEEP_REQ', +} +NO_FORCE_REQ = 0 +FORCE_LIGHT_SLEEP_REQ = 1 +MEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL' +MEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DYNAMIC_SHUT_DOWN_ENABLE = 0 +DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +MEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL2' +MEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DYNAMIC_DEEP_SLEEP_EN', + 1: 'DYNAMIC_LIGHT_SLEEP_EN', +} +DYNAMIC_DEEP_SLEEP_EN = 0 +DYNAMIC_LIGHT_SLEEP_EN = 1 +MEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET' +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET__enumvalues = { + 0: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 1: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', +} +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET = 0 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET = 1 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_LATENCY_COUNTER_CONTROL' +AZ_LATENCY_COUNTER_CONTROL__enumvalues = { + 0: 'AZ_LATENCY_COUNTER_NO_RESET', + 1: 'AZ_LATENCY_COUNTER_RESET_DONE', +} +AZ_LATENCY_COUNTER_NO_RESET = 0 +AZ_LATENCY_COUNTER_RESET_DONE = 1 +AZ_LATENCY_COUNTER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 9: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 10: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 11: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 12: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 13: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 14: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 15: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED = 8 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED = 9 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED = 10 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED = 11 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED = 12 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED = 13 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED = 14 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED = 15 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', +} +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY = 0 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY = 1 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_BITS_PER_COMPONENT_ENUM' +DSCC_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCC_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MAJOR_ENUM' +DSCC_DSC_VERSION_MAJOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', +} +DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION = 1 +DSCC_DSC_VERSION_MAJOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_DSC_VERSION_MINOR_ENUM' +DSCC_DSC_VERSION_MINOR_ENUM__enumvalues = { + 1: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 2: 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', +} +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION = 1 +DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION = 2 +DSCC_DSC_VERSION_MINOR_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ENABLE_ENUM' +DSCC_ENABLE_ENUM__enumvalues = { + 0: 'DSCC_ENABLE_ENUM_DISABLED', + 1: 'DSCC_ENABLE_ENUM_ENABLED', +} +DSCC_ENABLE_ENUM_DISABLED = 0 +DSCC_ENABLE_ENUM_ENABLED = 1 +DSCC_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_ICH_RESET_ENUM' +DSCC_ICH_RESET_ENUM__enumvalues = { + 1: 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 2: 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 4: 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 8: 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', +} +DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET = 1 +DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET = 2 +DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET = 4 +DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET = 8 +DSCC_ICH_RESET_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_LINEBUF_DEPTH_ENUM' +DSCC_LINEBUF_DEPTH_ENUM__enumvalues = { + 8: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 9: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 10: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 11: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 12: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 13: 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', +} +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT = 8 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT = 9 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT = 10 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT = 11 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT = 12 +DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT = 13 +DSCC_LINEBUF_DEPTH_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_DIS_ENUM' +DSCC_MEM_PWR_DIS_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', + 1: 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', +} +DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN = 0 +DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS = 1 +DSCC_MEM_PWR_DIS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCC_MEM_PWR_FORCE_ENUM' +DSCC_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 1: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 2: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 3: 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', +} +DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST = 0 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST = 1 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST = 2 +DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST = 3 +DSCC_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'POWER_STATE_ENUM' +POWER_STATE_ENUM__enumvalues = { + 0: 'POWER_STATE_ENUM_ON', + 1: 'POWER_STATE_ENUM_LS', + 2: 'POWER_STATE_ENUM_DS', + 3: 'POWER_STATE_ENUM_SD', +} +POWER_STATE_ENUM_ON = 0 +POWER_STATE_ENUM_LS = 1 +POWER_STATE_ENUM_DS = 2 +POWER_STATE_ENUM_SD = 3 +POWER_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_BITS_PER_COMPONENT_ENUM' +DSCCIF_BITS_PER_COMPONENT_ENUM__enumvalues = { + 8: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 10: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 12: 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', +} +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT = 8 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT = 10 +DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT = 12 +DSCCIF_BITS_PER_COMPONENT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_ENABLE_ENUM' +DSCCIF_ENABLE_ENUM__enumvalues = { + 0: 'DSCCIF_ENABLE_ENUM_DISABLED', + 1: 'DSCCIF_ENABLE_ENUM_ENABLED', +} +DSCCIF_ENABLE_ENUM_DISABLED = 0 +DSCCIF_ENABLE_ENUM_ENABLED = 1 +DSCCIF_ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM' +DSCCIF_INPUT_PIXEL_FORMAT_ENUM__enumvalues = { + 0: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 1: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 2: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 3: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 4: 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', +} +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB = 0 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444 = 1 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422 = 2 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422 = 3 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420 = 4 +DSCCIF_INPUT_PIXEL_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_GATING_DISABLE_ENUM' +CLOCK_GATING_DISABLE_ENUM__enumvalues = { + 0: 'CLOCK_GATING_DISABLE_ENUM_ENABLED', + 1: 'CLOCK_GATING_DISABLE_ENUM_DISABLED', +} +CLOCK_GATING_DISABLE_ENUM_ENABLED = 0 +CLOCK_GATING_DISABLE_ENUM_DISABLED = 1 +CLOCK_GATING_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_ENUM' +ENABLE_ENUM__enumvalues = { + 0: 'ENABLE_ENUM_DISABLED', + 1: 'ENABLE_ENUM_ENABLED', +} +ENABLE_ENUM_DISABLED = 0 +ENABLE_ENUM_ENABLED = 1 +ENABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TEST_CLOCK_MUX_SELECT_ENUM' +TEST_CLOCK_MUX_SELECT_ENUM__enumvalues = { + 0: 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 1: 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 2: 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 3: 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 4: 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 5: 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', + 6: 'TEST_CLOCK_MUX_SELECT_DSCCLK_D', +} +TEST_CLOCK_MUX_SELECT_DISPCLK_P = 0 +TEST_CLOCK_MUX_SELECT_DISPCLK_G = 1 +TEST_CLOCK_MUX_SELECT_DISPCLK_R = 2 +TEST_CLOCK_MUX_SELECT_DSCCLK_P = 3 +TEST_CLOCK_MUX_SELECT_DSCCLK_G = 4 +TEST_CLOCK_MUX_SELECT_DSCCLK_R = 5 +TEST_CLOCK_MUX_SELECT_DSCCLK_D = 6 +TEST_CLOCK_MUX_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_CRC_CONT_EN_ENUM' +DWB_CRC_CONT_EN_ENUM__enumvalues = { + 0: 'DWB_CRC_CONT_EN_ONE_SHOT', + 1: 'DWB_CRC_CONT_EN_CONT', +} +DWB_CRC_CONT_EN_ONE_SHOT = 0 +DWB_CRC_CONT_EN_CONT = 1 +DWB_CRC_CONT_EN_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_CRC_SRC_SEL_ENUM' +DWB_CRC_SRC_SEL_ENUM__enumvalues = { + 0: 'DWB_CRC_SRC_SEL_DWB_IN', + 1: 'DWB_CRC_SRC_SEL_OGAM_OUT', + 2: 'DWB_CRC_SRC_SEL_DWB_OUT', +} +DWB_CRC_SRC_SEL_DWB_IN = 0 +DWB_CRC_SRC_SEL_OGAM_OUT = 1 +DWB_CRC_SRC_SEL_DWB_OUT = 2 +DWB_CRC_SRC_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DATA_OVERFLOW_INT_TYPE_ENUM' +DWB_DATA_OVERFLOW_INT_TYPE_ENUM__enumvalues = { + 0: 'DWB_DATA_OVERFLOW_INT_TYPE_0', + 1: 'DWB_DATA_OVERFLOW_INT_TYPE_1', +} +DWB_DATA_OVERFLOW_INT_TYPE_0 = 0 +DWB_DATA_OVERFLOW_INT_TYPE_1 = 1 +DWB_DATA_OVERFLOW_INT_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DATA_OVERFLOW_TYPE_ENUM' +DWB_DATA_OVERFLOW_TYPE_ENUM__enumvalues = { + 0: 'DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW', + 1: 'DWB_DATA_OVERFLOW_TYPE_BUFFER', + 2: 'DWB_DATA_OVERFLOW_TYPE_VUPDATE', + 3: 'DWB_DATA_OVERFLOW_TYPE_VREADY', +} +DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW = 0 +DWB_DATA_OVERFLOW_TYPE_BUFFER = 1 +DWB_DATA_OVERFLOW_TYPE_VUPDATE = 2 +DWB_DATA_OVERFLOW_TYPE_VREADY = 3 +DWB_DATA_OVERFLOW_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_DEBUG_SEL_ENUM' +DWB_DEBUG_SEL_ENUM__enumvalues = { + 0: 'DWB_DEBUG_SEL_FC', + 1: 'DWB_DEBUG_SEL_RESERVED', + 2: 'DWB_DEBUG_SEL_DWBCP', + 3: 'DWB_DEBUG_SEL_PERFMON', +} +DWB_DEBUG_SEL_FC = 0 +DWB_DEBUG_SEL_RESERVED = 1 +DWB_DEBUG_SEL_DWBCP = 2 +DWB_DEBUG_SEL_PERFMON = 3 +DWB_DEBUG_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_MEM_PWR_FORCE_ENUM' +DWB_MEM_PWR_FORCE_ENUM__enumvalues = { + 0: 'DWB_MEM_PWR_FORCE_DIS', + 1: 'DWB_MEM_PWR_FORCE_LS', + 2: 'DWB_MEM_PWR_FORCE_DS', + 3: 'DWB_MEM_PWR_FORCE_SD', +} +DWB_MEM_PWR_FORCE_DIS = 0 +DWB_MEM_PWR_FORCE_LS = 1 +DWB_MEM_PWR_FORCE_DS = 2 +DWB_MEM_PWR_FORCE_SD = 3 +DWB_MEM_PWR_FORCE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_MEM_PWR_STATE_ENUM' +DWB_MEM_PWR_STATE_ENUM__enumvalues = { + 0: 'DWB_MEM_PWR_STATE_ON', + 1: 'DWB_MEM_PWR_STATE_LS', + 2: 'DWB_MEM_PWR_STATE_DS', + 3: 'DWB_MEM_PWR_STATE_SD', +} +DWB_MEM_PWR_STATE_ON = 0 +DWB_MEM_PWR_STATE_LS = 1 +DWB_MEM_PWR_STATE_DS = 2 +DWB_MEM_PWR_STATE_SD = 3 +DWB_MEM_PWR_STATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_TEST_CLK_SEL_ENUM' +DWB_TEST_CLK_SEL_ENUM__enumvalues = { + 0: 'DWB_TEST_CLK_SEL_R', + 1: 'DWB_TEST_CLK_SEL_G', + 2: 'DWB_TEST_CLK_SEL_P', +} +DWB_TEST_CLK_SEL_R = 0 +DWB_TEST_CLK_SEL_G = 1 +DWB_TEST_CLK_SEL_P = 2 +DWB_TEST_CLK_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_EYE_SELECTION_ENUM' +FC_EYE_SELECTION_ENUM__enumvalues = { + 0: 'FC_EYE_SELECTION_STEREO_DIS', + 1: 'FC_EYE_SELECTION_LEFT_EYE', + 2: 'FC_EYE_SELECTION_RIGHT_EYE', +} +FC_EYE_SELECTION_STEREO_DIS = 0 +FC_EYE_SELECTION_LEFT_EYE = 1 +FC_EYE_SELECTION_RIGHT_EYE = 2 +FC_EYE_SELECTION_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_FRAME_CAPTURE_RATE_ENUM' +FC_FRAME_CAPTURE_RATE_ENUM__enumvalues = { + 0: 'FC_FRAME_CAPTURE_RATE_FULL', + 1: 'FC_FRAME_CAPTURE_RATE_HALF', + 2: 'FC_FRAME_CAPTURE_RATE_THIRD', + 3: 'FC_FRAME_CAPTURE_RATE_QUARTER', +} +FC_FRAME_CAPTURE_RATE_FULL = 0 +FC_FRAME_CAPTURE_RATE_HALF = 1 +FC_FRAME_CAPTURE_RATE_THIRD = 2 +FC_FRAME_CAPTURE_RATE_QUARTER = 3 +FC_FRAME_CAPTURE_RATE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'FC_STEREO_EYE_POLARITY_ENUM' +FC_STEREO_EYE_POLARITY_ENUM__enumvalues = { + 0: 'FC_STEREO_EYE_POLARITY_LEFT', + 1: 'FC_STEREO_EYE_POLARITY_RIGHT', +} +FC_STEREO_EYE_POLARITY_LEFT = 0 +FC_STEREO_EYE_POLARITY_RIGHT = 1 +FC_STEREO_EYE_POLARITY_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_GAMUT_REMAP_COEF_FORMAT_ENUM' +DWB_GAMUT_REMAP_COEF_FORMAT_ENUM__enumvalues = { + 0: 'DWB_GAMUT_REMAP_COEF_FORMAT_S2_13', + 1: 'DWB_GAMUT_REMAP_COEF_FORMAT_S3_12', +} +DWB_GAMUT_REMAP_COEF_FORMAT_S2_13 = 0 +DWB_GAMUT_REMAP_COEF_FORMAT_S3_12 = 1 +DWB_GAMUT_REMAP_COEF_FORMAT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_GAMUT_REMAP_MODE_ENUM' +DWB_GAMUT_REMAP_MODE_ENUM__enumvalues = { + 0: 'DWB_GAMUT_REMAP_MODE_BYPASS', + 1: 'DWB_GAMUT_REMAP_MODE_COEF_A', + 2: 'DWB_GAMUT_REMAP_MODE_COEF_B', + 3: 'DWB_GAMUT_REMAP_MODE_RESERVED', +} +DWB_GAMUT_REMAP_MODE_BYPASS = 0 +DWB_GAMUT_REMAP_MODE_COEF_A = 1 +DWB_GAMUT_REMAP_MODE_COEF_B = 2 +DWB_GAMUT_REMAP_MODE_RESERVED = 3 +DWB_GAMUT_REMAP_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_LUT_NUM_SEG' +DWB_LUT_NUM_SEG__enumvalues = { + 0: 'DWB_SEGMENTS_1', + 1: 'DWB_SEGMENTS_2', + 2: 'DWB_SEGMENTS_4', + 3: 'DWB_SEGMENTS_8', + 4: 'DWB_SEGMENTS_16', + 5: 'DWB_SEGMENTS_32', + 6: 'DWB_SEGMENTS_64', + 7: 'DWB_SEGMENTS_128', +} +DWB_SEGMENTS_1 = 0 +DWB_SEGMENTS_2 = 1 +DWB_SEGMENTS_4 = 2 +DWB_SEGMENTS_8 = 3 +DWB_SEGMENTS_16 = 4 +DWB_SEGMENTS_32 = 5 +DWB_SEGMENTS_64 = 6 +DWB_SEGMENTS_128 = 7 +DWB_LUT_NUM_SEG = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_CONFIG_MODE_ENUM' +DWB_OGAM_LUT_CONFIG_MODE_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_CONFIG_MODE_DIFF', + 1: 'DWB_OGAM_LUT_CONFIG_MODE_SAME', +} +DWB_OGAM_LUT_CONFIG_MODE_DIFF = 0 +DWB_OGAM_LUT_CONFIG_MODE_SAME = 1 +DWB_OGAM_LUT_CONFIG_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_HOST_SEL_ENUM' +DWB_OGAM_LUT_HOST_SEL_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_HOST_SEL_RAMA', + 1: 'DWB_OGAM_LUT_HOST_SEL_RAMB', +} +DWB_OGAM_LUT_HOST_SEL_RAMA = 0 +DWB_OGAM_LUT_HOST_SEL_RAMB = 1 +DWB_OGAM_LUT_HOST_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_READ_COLOR_SEL_ENUM' +DWB_OGAM_LUT_READ_COLOR_SEL_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_READ_COLOR_SEL_B', + 1: 'DWB_OGAM_LUT_READ_COLOR_SEL_G', + 2: 'DWB_OGAM_LUT_READ_COLOR_SEL_R', + 3: 'DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED', +} +DWB_OGAM_LUT_READ_COLOR_SEL_B = 0 +DWB_OGAM_LUT_READ_COLOR_SEL_G = 1 +DWB_OGAM_LUT_READ_COLOR_SEL_R = 2 +DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED = 3 +DWB_OGAM_LUT_READ_COLOR_SEL_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_LUT_READ_DBG_ENUM' +DWB_OGAM_LUT_READ_DBG_ENUM__enumvalues = { + 0: 'DWB_OGAM_LUT_READ_DBG_DISABLE', + 1: 'DWB_OGAM_LUT_READ_DBG_ENABLE', +} +DWB_OGAM_LUT_READ_DBG_DISABLE = 0 +DWB_OGAM_LUT_READ_DBG_ENABLE = 1 +DWB_OGAM_LUT_READ_DBG_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_MODE_ENUM' +DWB_OGAM_MODE_ENUM__enumvalues = { + 0: 'DWB_OGAM_MODE_BYPASS', + 1: 'DWB_OGAM_MODE_RESERVED', + 2: 'DWB_OGAM_MODE_RAM_LUT_ENABLED', +} +DWB_OGAM_MODE_BYPASS = 0 +DWB_OGAM_MODE_RESERVED = 1 +DWB_OGAM_MODE_RAM_LUT_ENABLED = 2 +DWB_OGAM_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_PWL_DISABLE_ENUM' +DWB_OGAM_PWL_DISABLE_ENUM__enumvalues = { + 0: 'DWB_OGAM_PWL_DISABLE_FALSE', + 1: 'DWB_OGAM_PWL_DISABLE_TRUE', +} +DWB_OGAM_PWL_DISABLE_FALSE = 0 +DWB_OGAM_PWL_DISABLE_TRUE = 1 +DWB_OGAM_PWL_DISABLE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'DWB_OGAM_SELECT_ENUM' +DWB_OGAM_SELECT_ENUM__enumvalues = { + 0: 'DWB_OGAM_SELECT_A', + 1: 'DWB_OGAM_SELECT_B', +} +DWB_OGAM_SELECT_A = 0 +DWB_OGAM_SELECT_B = 1 +DWB_OGAM_SELECT_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN__enumvalues = { + 0: 'RDPCS_EXT_REFCLK_DISABLE', + 1: 'RDPCS_EXT_REFCLK_ENABLE', +} +RDPCS_EXT_REFCLK_DISABLE = 0 +RDPCS_EXT_REFCLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_CLOCK_ON' +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_OCLACLK_CLOCK_OFF', + 1: 'RDPCS_OCLACLK_CLOCK_ON', +} +RDPCS_OCLACLK_CLOCK_OFF = 0 +RDPCS_OCLACLK_CLOCK_ON = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_EN__enumvalues = { + 0: 'RDPCS_OCLACLK_DISABLE', + 1: 'RDPCS_OCLACLK_ENABLE', +} +RDPCS_OCLACLK_DISABLE = 0 +RDPCS_OCLACLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_GATE_DIS' +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_GATE_DIS__enumvalues = { + 0: 'RDPCS_OCLACLK_GATE_ENABLE', + 1: 'RDPCS_OCLACLK_GATE_DISABLE', +} +RDPCS_OCLACLK_GATE_ENABLE = 0 +RDPCS_OCLACLK_GATE_DISABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF', + 1: 'RDPCS_SYMCLK_SRAMCLK_CLOCK_ON', +} +RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF = 0 +RDPCS_SYMCLK_SRAMCLK_CLOCK_ON = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN__enumvalues = { + 0: 'RDPCS_SRAMCLK_DISABLE', + 1: 'RDPCS_SRAMCLK_ENABLE', +} +RDPCS_SRAMCLK_DISABLE = 0 +RDPCS_SRAMCLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS__enumvalues = { + 0: 'RDPCS_SRAMCLK_GATE_ENABLE', + 1: 'RDPCS_SRAMCLK_GATE_DISABLE', +} +RDPCS_SRAMCLK_GATE_ENABLE = 0 +RDPCS_SRAMCLK_GATE_DISABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_PASS' +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_PASS__enumvalues = { + 0: 'RDPCS_SRAMCLK_NOT_PASS', + 1: 'RDPCS_SRAMCLK_PASS', +} +RDPCS_SRAMCLK_NOT_PASS = 0 +RDPCS_SRAMCLK_PASS = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_PASS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_CLOCK_ON' +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_CLOCK_ON__enumvalues = { + 0: 'RDPCS_TX_CLK_CLOCK_OFF', + 1: 'RDPCS_TX_CLK_CLOCK_ON', +} +RDPCS_TX_CLK_CLOCK_OFF = 0 +RDPCS_TX_CLK_CLOCK_ON = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_CLOCK_ON = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_EN' +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_EN__enumvalues = { + 0: 'RDPCS_TX_CLK_DISABLE', + 1: 'RDPCS_TX_CLK_ENABLE', +} +RDPCS_TX_CLK_DISABLE = 0 +RDPCS_TX_CLK_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_GATE_DIS' +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_GATE_DIS__enumvalues = { + 0: 'RDPCS_TX_CLK_GATE_ENABLE', + 1: 'RDPCS_TX_CLK_GATE_DISABLE', +} +RDPCS_TX_CLK_GATE_ENABLE = 0 +RDPCS_TX_CLK_GATE_DISABLE = 1 +RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CLOCK_CNTL_TX_CLK_EN' +RDPCSTX_CLOCK_CNTL_TX_CLK_EN__enumvalues = { + 0: 'RDPCS_EXT_REFCLK_EN_DISABLE', + 1: 'RDPCS_EXT_REFCLK_EN_ENABLE', +} +RDPCS_EXT_REFCLK_EN_DISABLE = 0 +RDPCS_EXT_REFCLK_EN_ENABLE = 1 +RDPCSTX_CLOCK_CNTL_TX_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET__enumvalues = { + 0: 'RDPCS_CBUS_SOFT_RESET_DISABLE', + 1: 'RDPCS_CBUS_SOFT_RESET_ENABLE', +} +RDPCS_CBUS_SOFT_RESET_DISABLE = 0 +RDPCS_CBUS_SOFT_RESET_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET__enumvalues = { + 0: 'RDPCS_SRAM_SRAM_RESET_DISABLE', + 1: 'RDPCS_SRAM_SRAM_RESET_ENABLE', +} +RDPCS_SRAM_SRAM_RESET_DISABLE = 0 +RDPCS_SRAM_SRAM_RESET_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_FIFO_EN' +RDPCSTX_CNTL_RDPCS_TX_FIFO_EN__enumvalues = { + 0: 'RDPCS_TX_FIFO_DISABLE', + 1: 'RDPCS_TX_FIFO_ENABLE', +} +RDPCS_TX_FIFO_DISABLE = 0 +RDPCS_TX_FIFO_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_FIFO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN' +RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN__enumvalues = { + 0: 'RDPCS_TX_FIFO_LANE_DISABLE', + 1: 'RDPCS_TX_FIFO_LANE_ENABLE', +} +RDPCS_TX_FIFO_LANE_DISABLE = 0 +RDPCS_TX_FIFO_LANE_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET' +RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET__enumvalues = { + 0: 'RDPCS_TX_SOFT_RESET_DISABLE', + 1: 'RDPCS_TX_SOFT_RESET_ENABLE', +} +RDPCS_TX_SOFT_RESET_DISABLE = 0 +RDPCS_TX_SOFT_RESET_ENABLE = 1 +RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_FIFO_EMPTY' +RDPCSTX_FIFO_EMPTY__enumvalues = { + 0: 'RDPCSTX_FIFO_NOT_EMPTY', + 1: 'RDPCSTX_FIFO_IS_EMPTY', +} +RDPCSTX_FIFO_NOT_EMPTY = 0 +RDPCSTX_FIFO_IS_EMPTY = 1 +RDPCSTX_FIFO_EMPTY = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_FIFO_FULL' +RDPCSTX_FIFO_FULL__enumvalues = { + 0: 'RDPCSTX_FIFO_NOT_FULL', + 1: 'RDPCSTX_FIFO_IS_FULL', +} +RDPCSTX_FIFO_NOT_FULL = 0 +RDPCSTX_FIFO_IS_FULL = 1 +RDPCSTX_FIFO_FULL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE__enumvalues = { + 0: 'RDPCS_DPALT_4LANE_TOGGLE_2LANE', + 1: 'RDPCS_DPALT_4LANE_TOGGLE_4LANE', +} +RDPCS_DPALT_4LANE_TOGGLE_2LANE = 0 +RDPCS_DPALT_4LANE_TOGGLE_4LANE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 1: 'RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE', +} +RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE = 0 +RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE__enumvalues = { + 0: 'RDPCS_DPALT_DISABLE_TOGGLE_ENABLE', + 1: 'RDPCS_DPALT_DISABLE_TOGGLE_DISABLE', +} +RDPCS_DPALT_DISABLE_TOGGLE_ENABLE = 0 +RDPCS_DPALT_DISABLE_TOGGLE_DISABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK__enumvalues = { + 0: 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 1: 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE', +} +RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE = 0 +RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCS_REG_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCS_REG_FIFO_ERROR_MASK_ENABLE', +} +RDPCS_REG_FIFO_ERROR_MASK_DISABLE = 0 +RDPCS_REG_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK' +RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK__enumvalues = { + 0: 'RDPCS_TX_FIFO_ERROR_MASK_DISABLE', + 1: 'RDPCS_TX_FIFO_ERROR_MASK_ENABLE', +} +RDPCS_TX_FIFO_ERROR_MASK_DISABLE = 0 +RDPCS_TX_FIFO_ERROR_MASK_ENABLE = 1 +RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL__enumvalues = { + 0: 'RDPCS_PHY_CR_MUX_SEL_FOR_USB', + 1: 'RDPCS_PHY_CR_MUX_SEL_FOR_DC', +} +RDPCS_PHY_CR_MUX_SEL_FOR_USB = 0 +RDPCS_PHY_CR_MUX_SEL_FOR_DC = 1 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL__enumvalues = { + 0: 'RDPCS_PHY_CR_PARA_SEL_JTAG', + 1: 'RDPCS_PHY_CR_PARA_SEL_CR', +} +RDPCS_PHY_CR_PARA_SEL_JTAG = 0 +RDPCS_PHY_CR_PARA_SEL_CR = 1 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE' +RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE__enumvalues = { + 0: 'RDPCS_PHY_REF_RANGE_0', + 1: 'RDPCS_PHY_REF_RANGE_1', + 2: 'RDPCS_PHY_REF_RANGE_2', + 3: 'RDPCS_PHY_REF_RANGE_3', + 4: 'RDPCS_PHY_REF_RANGE_4', + 5: 'RDPCS_PHY_REF_RANGE_5', + 6: 'RDPCS_PHY_REF_RANGE_6', + 7: 'RDPCS_PHY_REF_RANGE_7', +} +RDPCS_PHY_REF_RANGE_0 = 0 +RDPCS_PHY_REF_RANGE_1 = 1 +RDPCS_PHY_REF_RANGE_2 = 2 +RDPCS_PHY_REF_RANGE_3 = 3 +RDPCS_PHY_REF_RANGE_4 = 4 +RDPCS_PHY_REF_RANGE_5 = 5 +RDPCS_PHY_REF_RANGE_6 = 6 +RDPCS_PHY_REF_RANGE_7 = 7 +RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE' +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE__enumvalues = { + 0: 'RDPCS_SRAM_EXT_LD_NOT_DONE', + 1: 'RDPCS_SRAM_EXT_LD_DONE', +} +RDPCS_SRAM_EXT_LD_NOT_DONE = 0 +RDPCS_SRAM_EXT_LD_DONE = 1 +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE' +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE__enumvalues = { + 0: 'RDPCS_SRAM_INIT_NOT_DONE', + 1: 'RDPCS_SRAM_INIT_DONE', +} +RDPCS_SRAM_INIT_NOT_DONE = 0 +RDPCS_SRAM_INIT_DONE = 1 +RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV' +RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV__enumvalues = { + 0: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1', + 1: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2', + 2: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3', + 3: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8', + 4: 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16', +} +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1 = 0 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2 = 1 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3 = 2 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8 = 3 +RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16 = 4 +RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV' +RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV__enumvalues = { + 0: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 1: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 2: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 3: 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', +} +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0 = 0 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1 = 1 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2 = 2 +RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3 = 3 +RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV' +RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV__enumvalues = { + 0: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 1: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2', + 2: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4', + 3: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8', + 4: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3', + 5: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5', + 6: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6', + 7: 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10', +} +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV = 0 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2 = 1 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4 = 2 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8 = 3 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3 = 4 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5 = 5 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6 = 6 +RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10 = 7 +RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL' +RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_TERM_CTRL_54', + 1: 'RDPCS_PHY_DP_TX_TERM_CTRL_52', + 2: 'RDPCS_PHY_DP_TX_TERM_CTRL_50', + 3: 'RDPCS_PHY_DP_TX_TERM_CTRL_48', + 4: 'RDPCS_PHY_DP_TX_TERM_CTRL_46', + 5: 'RDPCS_PHY_DP_TX_TERM_CTRL_44', + 6: 'RDPCS_PHY_DP_TX_TERM_CTRL_42', + 7: 'RDPCS_PHY_DP_TX_TERM_CTRL_40', +} +RDPCS_PHY_DP_TX_TERM_CTRL_54 = 0 +RDPCS_PHY_DP_TX_TERM_CTRL_52 = 1 +RDPCS_PHY_DP_TX_TERM_CTRL_50 = 2 +RDPCS_PHY_DP_TX_TERM_CTRL_48 = 3 +RDPCS_PHY_DP_TX_TERM_CTRL_46 = 4 +RDPCS_PHY_DP_TX_TERM_CTRL_44 = 5 +RDPCS_PHY_DP_TX_TERM_CTRL_42 = 6 +RDPCS_PHY_DP_TX_TERM_CTRL_40 = 7 +RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT', + 1: 'RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT', +} +RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT = 0 +RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT = 1 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_RATE', + 1: 'RDPCS_PHY_DP_TX_RATE_DIV2', + 2: 'RDPCS_PHY_DP_TX_RATE_DIV4', +} +RDPCS_PHY_DP_TX_RATE = 0 +RDPCS_PHY_DP_TX_RATE_DIV2 = 1 +RDPCS_PHY_DP_TX_RATE_DIV4 = 2 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH' +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH__enumvalues = { + 0: 'RDPCS_PHY_DP_TX_WIDTH_8', + 1: 'RDPCS_PHY_DP_TX_WIDTH_10', + 2: 'RDPCS_PHY_DP_TX_WIDTH_16', + 3: 'RDPCS_PHY_DP_TX_WIDTH_20', +} +RDPCS_PHY_DP_TX_WIDTH_8 = 0 +RDPCS_PHY_DP_TX_WIDTH_10 = 1 +RDPCS_PHY_DP_TX_WIDTH_16 = 2 +RDPCS_PHY_DP_TX_WIDTH_20 = 3 +RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE' +RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE__enumvalues = { + 0: 'RRDPCS_PHY_DP_TX_PSTATE_POWER_UP', + 1: 'RRDPCS_PHY_DP_TX_PSTATE_HOLD', + 2: 'RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF', + 3: 'RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN', +} +RRDPCS_PHY_DP_TX_PSTATE_POWER_UP = 0 +RRDPCS_PHY_DP_TX_PSTATE_HOLD = 1 +RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF = 2 +RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN = 3 +RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_PHY_REF_ALT_CLK_EN' +RDPCSTX_PHY_REF_ALT_CLK_EN__enumvalues = { + 0: 'RDPCS_PHY_REF_ALT_CLK_DISABLE', + 1: 'RDPCS_PHY_REF_ALT_CLK_ENABLE', +} +RDPCS_PHY_REF_ALT_CLK_DISABLE = 0 +RDPCS_PHY_REF_ALT_CLK_ENABLE = 1 +RDPCSTX_PHY_REF_ALT_CLK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCSTX_TX_FIFO_DISABLED_MASK' +RDPCSTX_TX_FIFO_DISABLED_MASK__enumvalues = { + 0: 'RDPCSTX_TX_FIFO_DISABLED_MASK_DISABLE', + 1: 'RDPCSTX_TX_FIFO_DISABLED_MASK_ENABLE', +} +RDPCSTX_TX_FIFO_DISABLED_MASK_DISABLE = 0 +RDPCSTX_TX_FIFO_DISABLED_MASK_ENABLE = 1 +RDPCSTX_TX_FIFO_DISABLED_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_DBG_OCLA_SEL' +RDPCS_DBG_OCLA_SEL__enumvalues = { + 0: 'RDPCS_DBG_OCLA_SEL_MON_OUT_7_0', + 1: 'RDPCS_DBG_OCLA_SEL_MON_OUT_15_8', + 2: 'RDPCS_DBG_OCLA_SEL_MON_OUT_23_16', + 3: 'RDPCS_DBG_OCLA_SEL_MON_OUT_31_24', + 4: 'RDPCS_DBG_OCLA_SEL_MON_OUT_39_32', + 5: 'RDPCS_DBG_OCLA_SEL_MON_OUT_47_40', + 6: 'RDPCS_DBG_OCLA_SEL_MON_OUT_55_48', + 7: 'RDPCS_DBG_OCLA_SEL_MON_OUT_63_56', +} +RDPCS_DBG_OCLA_SEL_MON_OUT_7_0 = 0 +RDPCS_DBG_OCLA_SEL_MON_OUT_15_8 = 1 +RDPCS_DBG_OCLA_SEL_MON_OUT_23_16 = 2 +RDPCS_DBG_OCLA_SEL_MON_OUT_31_24 = 3 +RDPCS_DBG_OCLA_SEL_MON_OUT_39_32 = 4 +RDPCS_DBG_OCLA_SEL_MON_OUT_47_40 = 5 +RDPCS_DBG_OCLA_SEL_MON_OUT_55_48 = 6 +RDPCS_DBG_OCLA_SEL_MON_OUT_63_56 = 7 +RDPCS_DBG_OCLA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TEST_CLK_SEL' +RDPCS_TEST_CLK_SEL__enumvalues = { + 0: 'RDPCS_TEST_CLK_SEL_NONE', + 1: 'RDPCS_TEST_CLK_SEL_CFGCLK', + 2: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 3: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 4: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 5: 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 6: 'RDPCS_TEST_CLK_SEL_SRAMCLK', + 7: 'RDPCS_TEST_CLK_SEL_EXT_CR_CLK', + 8: 'RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 9: 'RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 10: 'RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 11: 'RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 12: 'RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 13: 'RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 14: 'RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 15: 'RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk', + 16: 'RDPCS_TEST_CLK_SEL_dtb_out0', + 17: 'RDPCS_TEST_CLK_SEL_dtb_out1', +} +RDPCS_TEST_CLK_SEL_NONE = 0 +RDPCS_TEST_CLK_SEL_CFGCLK = 1 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS = 2 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS = 3 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4 = 4 +RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4 = 5 +RDPCS_TEST_CLK_SEL_SRAMCLK = 6 +RDPCS_TEST_CLK_SEL_EXT_CR_CLK = 7 +RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK = 8 +RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK = 9 +RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK = 10 +RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK = 11 +RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK = 12 +RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK = 13 +RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK = 14 +RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk = 15 +RDPCS_TEST_CLK_SEL_dtb_out0 = 16 +RDPCS_TEST_CLK_SEL_dtb_out1 = 17 +RDPCS_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TX_CNTL_TX_LANE_PACK_FROM_MSB' +RDPCS_TX_CNTL_TX_LANE_PACK_FROM_MSB__enumvalues = { + 0: 'RDPCS_LANE_PACK_FROM_MSB_DISABLE', + 1: 'RDPCS_LANE_PACK_FROM_MSB_ENABLE', +} +RDPCS_LANE_PACK_FROM_MSB_DISABLE = 0 +RDPCS_LANE_PACK_FROM_MSB_ENABLE = 1 +RDPCS_TX_CNTL_TX_LANE_PACK_FROM_MSB = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE' +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE__enumvalues = { + 0: 'RDPCS_MEM_PWR_NO_FORCE', + 1: 'RDPCS_MEM_PWR_LIGHT_SLEEP', + 2: 'RDPCS_MEM_PWR_DEEP_SLEEP', + 3: 'RDPCS_MEM_PWR_SHUT_DOWN', +} +RDPCS_MEM_PWR_NO_FORCE = 0 +RDPCS_MEM_PWR_LIGHT_SLEEP = 1 +RDPCS_MEM_PWR_DEEP_SLEEP = 2 +RDPCS_MEM_PWR_SHUT_DOWN = 3 +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE = ctypes.c_uint32 # enum + +# values for enumeration 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE' +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE__enumvalues = { + 0: 'RDPCS_MEM_PWR_PWR_STATE_ON', + 1: 'RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 2: 'RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 3: 'RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN', +} +RDPCS_MEM_PWR_PWR_STATE_ON = 0 +RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP = 1 +RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP = 2 +RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN = 3 +RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'RPDCSTX_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK' +RPDCSTX_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK__enumvalues = { + 0: 'RDPCS_LANE_BIT_ORDER_REVERSE_DISABLE', + 1: 'RDPCS_LANE_BIT_ORDER_REVERSE_ENABLE', +} +RDPCS_LANE_BIT_ORDER_REVERSE_DISABLE = 0 +RDPCS_LANE_BIT_ORDER_REVERSE_ENABLE = 1 +RPDCSTX_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_DOORBELL_MODE' +RLC_DOORBELL_MODE__enumvalues = { + 0: 'RLC_DOORBELL_MODE_DISABLE', + 1: 'RLC_DOORBELL_MODE_ENABLE', + 2: 'RLC_DOORBELL_MODE_ENABLE_PF', + 3: 'RLC_DOORBELL_MODE_ENABLE_PF_VF', +} +RLC_DOORBELL_MODE_DISABLE = 0 +RLC_DOORBELL_MODE_ENABLE = 1 +RLC_DOORBELL_MODE_ENABLE_PF = 2 +RLC_DOORBELL_MODE_ENABLE_PF_VF = 3 +RLC_DOORBELL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_PERFCOUNTER_SEL' +RLC_PERFCOUNTER_SEL__enumvalues = { + 0: 'RLC_PERF_SEL_POWER_FEATURE_0', + 1: 'RLC_PERF_SEL_POWER_FEATURE_1', + 2: 'RLC_PERF_SEL_CP_INTERRUPT', + 3: 'RLC_PERF_SEL_GRBM_INTERRUPT', + 4: 'RLC_PERF_SEL_SPM_INTERRUPT', + 5: 'RLC_PERF_SEL_IH_INTERRUPT', + 6: 'RLC_PERF_SEL_SERDES_COMMAND_WRITE', +} +RLC_PERF_SEL_POWER_FEATURE_0 = 0 +RLC_PERF_SEL_POWER_FEATURE_1 = 1 +RLC_PERF_SEL_CP_INTERRUPT = 2 +RLC_PERF_SEL_GRBM_INTERRUPT = 3 +RLC_PERF_SEL_SPM_INTERRUPT = 4 +RLC_PERF_SEL_IH_INTERRUPT = 5 +RLC_PERF_SEL_SERDES_COMMAND_WRITE = 6 +RLC_PERFCOUNTER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RLC_PERFMON_STATE' +RLC_PERFMON_STATE__enumvalues = { + 0: 'RLC_PERFMON_STATE_RESET', + 1: 'RLC_PERFMON_STATE_ENABLE', + 2: 'RLC_PERFMON_STATE_DISABLE', + 3: 'RLC_PERFMON_STATE_RESERVED_3', + 4: 'RLC_PERFMON_STATE_RESERVED_4', + 5: 'RLC_PERFMON_STATE_RESERVED_5', + 6: 'RLC_PERFMON_STATE_RESERVED_6', + 7: 'RLC_PERFMON_STATE_ROLLOVER', +} +RLC_PERFMON_STATE_RESET = 0 +RLC_PERFMON_STATE_ENABLE = 1 +RLC_PERFMON_STATE_DISABLE = 2 +RLC_PERFMON_STATE_RESERVED_3 = 3 +RLC_PERFMON_STATE_RESERVED_4 = 4 +RLC_PERFMON_STATE_RESERVED_5 = 5 +RLC_PERFMON_STATE_RESERVED_6 = 6 +RLC_PERFMON_STATE_ROLLOVER = 7 +RLC_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'RSPM_CMD' +RSPM_CMD__enumvalues = { + 0: 'RSPM_CMD_INVALID', + 1: 'RSPM_CMD_IDLE', + 2: 'RSPM_CMD_CALIBRATE', + 3: 'RSPM_CMD_SPM_RESET', + 4: 'RSPM_CMD_SPM_START', + 5: 'RSPM_CMD_SPM_STOP', + 6: 'RSPM_CMD_PERF_RESET', + 7: 'RSPM_CMD_PERF_SAMPLE', + 8: 'RSPM_CMD_PROF_START', + 9: 'RSPM_CMD_PROF_STOP', + 10: 'RSPM_CMD_FORCE_SAMPLE', +} +RSPM_CMD_INVALID = 0 +RSPM_CMD_IDLE = 1 +RSPM_CMD_CALIBRATE = 2 +RSPM_CMD_SPM_RESET = 3 +RSPM_CMD_SPM_START = 4 +RSPM_CMD_SPM_STOP = 5 +RSPM_CMD_PERF_RESET = 6 +RSPM_CMD_PERF_SAMPLE = 7 +RSPM_CMD_PROF_START = 8 +RSPM_CMD_PROF_STOP = 9 +RSPM_CMD_FORCE_SAMPLE = 10 +RSPM_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'CSCNTL_TYPE' +CSCNTL_TYPE__enumvalues = { + 0: 'CSCNTL_TYPE_TG', + 1: 'CSCNTL_TYPE_STATE', + 2: 'CSCNTL_TYPE_EVENT', + 3: 'CSCNTL_TYPE_PRIVATE', +} +CSCNTL_TYPE_TG = 0 +CSCNTL_TYPE_STATE = 1 +CSCNTL_TYPE_EVENT = 2 +CSCNTL_TYPE_PRIVATE = 3 +CSCNTL_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CSDATA_TYPE' +CSDATA_TYPE__enumvalues = { + 0: 'CSDATA_TYPE_TG', + 1: 'CSDATA_TYPE_STATE', + 2: 'CSDATA_TYPE_EVENT', + 3: 'CSDATA_TYPE_PRIVATE', +} +CSDATA_TYPE_TG = 0 +CSDATA_TYPE_STATE = 1 +CSDATA_TYPE_EVENT = 2 +CSDATA_TYPE_PRIVATE = 3 +CSDATA_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GE1_PERFCOUNT_SELECT' +GE1_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge1_assembler_busy', + 1: 'ge1_assembler_stalled', + 2: 'ge1_dma_busy', + 3: 'ge1_dma_lat_bin_0', + 4: 'ge1_dma_lat_bin_1', + 5: 'ge1_dma_lat_bin_2', + 6: 'ge1_dma_lat_bin_3', + 7: 'ge1_dma_lat_bin_4', + 8: 'ge1_dma_lat_bin_5', + 9: 'ge1_dma_lat_bin_6', + 10: 'ge1_dma_lat_bin_7', + 11: 'ge1_dma_return_cl0', + 12: 'ge1_dma_return_cl1', + 13: 'ge1_dma_utcl1_consecutive_retry_event', + 14: 'ge1_dma_utcl1_request_event', + 15: 'ge1_dma_utcl1_retry_event', + 16: 'ge1_dma_utcl1_stall_event', + 17: 'ge1_dma_utcl1_stall_utcl2_event', + 18: 'ge1_dma_utcl1_translation_hit_event', + 19: 'ge1_dma_utcl1_translation_miss_event', + 20: 'ge1_assembler_dma_starved', + 21: 'ge1_rbiu_di_fifo_stalled_p0', + 22: 'ge1_rbiu_di_fifo_starved_p0', + 23: 'ge1_rbiu_dr_fifo_stalled_p0', + 24: 'ge1_rbiu_dr_fifo_starved_p0', + 25: 'ge1_sclk_reg_vld', + 26: 'ge1_stat_busy', + 27: 'ge1_stat_no_dma_busy', + 28: 'ge1_pipe0_to_pipe1', + 29: 'ge1_pipe1_to_pipe0', + 30: 'ge1_dma_return_size_cl0', + 31: 'ge1_dma_return_size_cl1', + 32: 'ge1_small_draws_one_instance', + 33: 'ge1_sclk_input_vld', + 34: 'ge1_prim_group_limit_hit', + 35: 'ge1_unopt_multi_instance_draws', + 36: 'ge1_rbiu_di_fifo_stalled_p1', + 37: 'ge1_rbiu_di_fifo_starved_p1', + 38: 'ge1_rbiu_dr_fifo_stalled_p1', + 39: 'ge1_rbiu_dr_fifo_starved_p1', +} +ge1_assembler_busy = 0 +ge1_assembler_stalled = 1 +ge1_dma_busy = 2 +ge1_dma_lat_bin_0 = 3 +ge1_dma_lat_bin_1 = 4 +ge1_dma_lat_bin_2 = 5 +ge1_dma_lat_bin_3 = 6 +ge1_dma_lat_bin_4 = 7 +ge1_dma_lat_bin_5 = 8 +ge1_dma_lat_bin_6 = 9 +ge1_dma_lat_bin_7 = 10 +ge1_dma_return_cl0 = 11 +ge1_dma_return_cl1 = 12 +ge1_dma_utcl1_consecutive_retry_event = 13 +ge1_dma_utcl1_request_event = 14 +ge1_dma_utcl1_retry_event = 15 +ge1_dma_utcl1_stall_event = 16 +ge1_dma_utcl1_stall_utcl2_event = 17 +ge1_dma_utcl1_translation_hit_event = 18 +ge1_dma_utcl1_translation_miss_event = 19 +ge1_assembler_dma_starved = 20 +ge1_rbiu_di_fifo_stalled_p0 = 21 +ge1_rbiu_di_fifo_starved_p0 = 22 +ge1_rbiu_dr_fifo_stalled_p0 = 23 +ge1_rbiu_dr_fifo_starved_p0 = 24 +ge1_sclk_reg_vld = 25 +ge1_stat_busy = 26 +ge1_stat_no_dma_busy = 27 +ge1_pipe0_to_pipe1 = 28 +ge1_pipe1_to_pipe0 = 29 +ge1_dma_return_size_cl0 = 30 +ge1_dma_return_size_cl1 = 31 +ge1_small_draws_one_instance = 32 +ge1_sclk_input_vld = 33 +ge1_prim_group_limit_hit = 34 +ge1_unopt_multi_instance_draws = 35 +ge1_rbiu_di_fifo_stalled_p1 = 36 +ge1_rbiu_di_fifo_starved_p1 = 37 +ge1_rbiu_dr_fifo_stalled_p1 = 38 +ge1_rbiu_dr_fifo_starved_p1 = 39 +GE1_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'GE2_DIST_PERFCOUNT_SELECT' +GE2_DIST_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge_dist_hs_done', + 1: 'ge_dist_hs_done_latency_se0', + 2: 'ge_dist_hs_done_latency_se1', + 3: 'ge_dist_hs_done_latency_se2', + 4: 'ge_dist_hs_done_latency_se3', + 5: 'ge_dist_hs_done_latency_se4', + 6: 'ge_dist_hs_done_latency_se5', + 7: 'ge_dist_hs_done_latency_se6', + 8: 'ge_dist_hs_done_latency_se7', + 9: 'ge_dist_inside_tf_bin_0', + 10: 'ge_dist_inside_tf_bin_1', + 11: 'ge_dist_inside_tf_bin_2', + 12: 'ge_dist_inside_tf_bin_3', + 13: 'ge_dist_inside_tf_bin_4', + 14: 'ge_dist_inside_tf_bin_5', + 15: 'ge_dist_inside_tf_bin_6', + 16: 'ge_dist_inside_tf_bin_7', + 17: 'ge_dist_inside_tf_bin_8', + 18: 'ge_dist_null_patch', + 19: 'ge_dist_sclk_core_vld', + 20: 'ge_dist_sclk_wd_te11_vld', + 21: 'ge_dist_tfreq_lat_bin_0', + 22: 'ge_dist_tfreq_lat_bin_1', + 23: 'ge_dist_tfreq_lat_bin_2', + 24: 'ge_dist_tfreq_lat_bin_3', + 25: 'ge_dist_tfreq_lat_bin_4', + 26: 'ge_dist_tfreq_lat_bin_5', + 27: 'ge_dist_tfreq_lat_bin_6', + 28: 'ge_dist_tfreq_lat_bin_7', + 29: 'ge_dist_tfreq_utcl1_consecutive_retry_event', + 30: 'ge_dist_tfreq_utcl1_request_event', + 31: 'ge_dist_tfreq_utcl1_retry_event', + 32: 'ge_dist_tfreq_utcl1_stall_event', + 33: 'ge_dist_tfreq_utcl1_stall_utcl2_event', + 34: 'ge_dist_tfreq_utcl1_translation_hit_event', + 35: 'ge_dist_tfreq_utcl1_translation_miss_event', + 36: 'ge_dist_pc_feorder_fifo_full', + 37: 'ge_dist_pc_ge_manager_busy', + 38: 'ge_dist_sclk_input_vld', + 39: 'ge_dist_wd_te11_busy', + 40: 'ge_dist_te11_starved', + 41: 'ge_dist_switch_mode_stall', + 42: 'ge_all_tf_eq', + 43: 'ge_all_tf2', + 44: 'ge_all_tf3', + 45: 'ge_all_tf4', + 46: 'ge_all_tf5', + 47: 'ge_all_tf6', + 48: 'ge_se0_te11_starved_on_hs_done', + 49: 'ge_se1_te11_starved_on_hs_done', + 50: 'ge_se2_te11_starved_on_hs_done', + 51: 'ge_se3_te11_starved_on_hs_done', + 52: 'ge_se4_te11_starved_on_hs_done', + 53: 'ge_se5_te11_starved_on_hs_done', + 54: 'ge_se6_te11_starved_on_hs_done', + 55: 'ge_se7_te11_starved_on_hs_done', + 56: 'ge_dist_op_fifo_full_starve', + 57: 'ge_dist_hs_done_se0', + 58: 'ge_dist_hs_done_se1', + 59: 'ge_dist_hs_done_se2', + 60: 'ge_dist_hs_done_se3', + 61: 'ge_dist_hs_done_se4', + 62: 'ge_dist_hs_done_se5', + 63: 'ge_dist_hs_done_se6', + 64: 'ge_dist_hs_done_se7', + 65: 'ge_dist_hs_done_latency', + 66: 'ge_dist_distributer_busy', + 67: 'ge_tf_ret_data_stalling_hs_done', + 68: 'ge_num_of_no_dist_patches', + 69: 'ge_num_of_donut_dist_patches', + 70: 'ge_num_of_patch_dist_patches', + 71: 'ge_num_of_se_switches_due_to_patch_accum', + 72: 'ge_num_of_se_switches_due_to_donut', + 73: 'ge_num_of_se_switches_due_to_trap', + 74: 'ge_num_of_hs_dealloc_events', + 75: 'ge_agm_gcr_req', + 76: 'ge_agm_gcr_tag_stall', + 77: 'ge_agm_gcr_crd_stall', + 78: 'ge_agm_gcr_stall', + 79: 'ge_agm_gcr_latency', + 80: 'ge_distclk_vld', + 81: 'ge_dist_indx_fifos_full_and_empty', + 82: 'ge_hs_done_all_tf0_se0', + 83: 'ge_hs_done_all_tf0_se1', + 84: 'ge_hs_done_all_tf0_se2', + 85: 'ge_hs_done_all_tf0_se3', + 86: 'ge_hs_done_all_tf0_se4', + 87: 'ge_hs_done_all_tf0_se5', + 88: 'ge_hs_done_all_tf0_se6', + 89: 'ge_hs_done_all_tf0_se7', + 90: 'ge_hs_done_all_tf1_se0', + 91: 'ge_hs_done_all_tf1_se1', + 92: 'ge_hs_done_all_tf1_se2', + 93: 'ge_hs_done_all_tf1_se3', + 94: 'ge_hs_done_all_tf1_se4', + 95: 'ge_hs_done_all_tf1_se5', + 96: 'ge_hs_done_all_tf1_se6', + 97: 'ge_hs_done_all_tf1_se7', + 98: 'ge_agm_gcr_req_outstanding', + 99: 'ge_agm_gcr_req_amount', + 100: 'ge_agm_gcr_combine', +} +ge_dist_hs_done = 0 +ge_dist_hs_done_latency_se0 = 1 +ge_dist_hs_done_latency_se1 = 2 +ge_dist_hs_done_latency_se2 = 3 +ge_dist_hs_done_latency_se3 = 4 +ge_dist_hs_done_latency_se4 = 5 +ge_dist_hs_done_latency_se5 = 6 +ge_dist_hs_done_latency_se6 = 7 +ge_dist_hs_done_latency_se7 = 8 +ge_dist_inside_tf_bin_0 = 9 +ge_dist_inside_tf_bin_1 = 10 +ge_dist_inside_tf_bin_2 = 11 +ge_dist_inside_tf_bin_3 = 12 +ge_dist_inside_tf_bin_4 = 13 +ge_dist_inside_tf_bin_5 = 14 +ge_dist_inside_tf_bin_6 = 15 +ge_dist_inside_tf_bin_7 = 16 +ge_dist_inside_tf_bin_8 = 17 +ge_dist_null_patch = 18 +ge_dist_sclk_core_vld = 19 +ge_dist_sclk_wd_te11_vld = 20 +ge_dist_tfreq_lat_bin_0 = 21 +ge_dist_tfreq_lat_bin_1 = 22 +ge_dist_tfreq_lat_bin_2 = 23 +ge_dist_tfreq_lat_bin_3 = 24 +ge_dist_tfreq_lat_bin_4 = 25 +ge_dist_tfreq_lat_bin_5 = 26 +ge_dist_tfreq_lat_bin_6 = 27 +ge_dist_tfreq_lat_bin_7 = 28 +ge_dist_tfreq_utcl1_consecutive_retry_event = 29 +ge_dist_tfreq_utcl1_request_event = 30 +ge_dist_tfreq_utcl1_retry_event = 31 +ge_dist_tfreq_utcl1_stall_event = 32 +ge_dist_tfreq_utcl1_stall_utcl2_event = 33 +ge_dist_tfreq_utcl1_translation_hit_event = 34 +ge_dist_tfreq_utcl1_translation_miss_event = 35 +ge_dist_pc_feorder_fifo_full = 36 +ge_dist_pc_ge_manager_busy = 37 +ge_dist_sclk_input_vld = 38 +ge_dist_wd_te11_busy = 39 +ge_dist_te11_starved = 40 +ge_dist_switch_mode_stall = 41 +ge_all_tf_eq = 42 +ge_all_tf2 = 43 +ge_all_tf3 = 44 +ge_all_tf4 = 45 +ge_all_tf5 = 46 +ge_all_tf6 = 47 +ge_se0_te11_starved_on_hs_done = 48 +ge_se1_te11_starved_on_hs_done = 49 +ge_se2_te11_starved_on_hs_done = 50 +ge_se3_te11_starved_on_hs_done = 51 +ge_se4_te11_starved_on_hs_done = 52 +ge_se5_te11_starved_on_hs_done = 53 +ge_se6_te11_starved_on_hs_done = 54 +ge_se7_te11_starved_on_hs_done = 55 +ge_dist_op_fifo_full_starve = 56 +ge_dist_hs_done_se0 = 57 +ge_dist_hs_done_se1 = 58 +ge_dist_hs_done_se2 = 59 +ge_dist_hs_done_se3 = 60 +ge_dist_hs_done_se4 = 61 +ge_dist_hs_done_se5 = 62 +ge_dist_hs_done_se6 = 63 +ge_dist_hs_done_se7 = 64 +ge_dist_hs_done_latency = 65 +ge_dist_distributer_busy = 66 +ge_tf_ret_data_stalling_hs_done = 67 +ge_num_of_no_dist_patches = 68 +ge_num_of_donut_dist_patches = 69 +ge_num_of_patch_dist_patches = 70 +ge_num_of_se_switches_due_to_patch_accum = 71 +ge_num_of_se_switches_due_to_donut = 72 +ge_num_of_se_switches_due_to_trap = 73 +ge_num_of_hs_dealloc_events = 74 +ge_agm_gcr_req = 75 +ge_agm_gcr_tag_stall = 76 +ge_agm_gcr_crd_stall = 77 +ge_agm_gcr_stall = 78 +ge_agm_gcr_latency = 79 +ge_distclk_vld = 80 +ge_dist_indx_fifos_full_and_empty = 81 +ge_hs_done_all_tf0_se0 = 82 +ge_hs_done_all_tf0_se1 = 83 +ge_hs_done_all_tf0_se2 = 84 +ge_hs_done_all_tf0_se3 = 85 +ge_hs_done_all_tf0_se4 = 86 +ge_hs_done_all_tf0_se5 = 87 +ge_hs_done_all_tf0_se6 = 88 +ge_hs_done_all_tf0_se7 = 89 +ge_hs_done_all_tf1_se0 = 90 +ge_hs_done_all_tf1_se1 = 91 +ge_hs_done_all_tf1_se2 = 92 +ge_hs_done_all_tf1_se3 = 93 +ge_hs_done_all_tf1_se4 = 94 +ge_hs_done_all_tf1_se5 = 95 +ge_hs_done_all_tf1_se6 = 96 +ge_hs_done_all_tf1_se7 = 97 +ge_agm_gcr_req_outstanding = 98 +ge_agm_gcr_req_amount = 99 +ge_agm_gcr_combine = 100 +GE2_DIST_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'GE2_SE_PERFCOUNT_SELECT' +GE2_SE_PERFCOUNT_SELECT__enumvalues = { + 0: 'ge_se_ds_prims', + 1: 'ge_se_es_thread_groups', + 2: 'ge_se_esvert_stalled_gsprim', + 3: 'ge_se_hs_tfm_stall', + 4: 'ge_se_hs_tgs_active_high_water_mark', + 5: 'ge_se_hs_thread_groups', + 6: 'ge_se_reused_es_indices', + 7: 'ge_se_sclk_ngg_vld', + 8: 'ge_se_sclk_te11_vld', + 9: 'ge_se_spi_esvert_eov', + 10: 'ge_se_spi_esvert_stalled', + 11: 'ge_se_spi_esvert_starved_busy', + 12: 'ge_se_spi_esvert_valid', + 13: 'ge_se_spi_gsprim_cont', + 14: 'ge_se_spi_gsprim_eov', + 15: 'ge_se_spi_gsprim_stalled', + 16: 'ge_se_spi_gsprim_starved_busy', + 17: 'ge_se_spi_gsprim_valid', + 18: 'ge_se_spi_gssubgrp_is_event', + 19: 'ge_se_spi_gssubgrp_send', + 20: 'ge_se_spi_hsvert_eov', + 21: 'ge_se_spi_hsvert_stalled', + 22: 'ge_se_spi_hsvert_starved_busy', + 23: 'ge_se_spi_hsvert_valid', + 24: 'ge_se_spi_hsgrp_is_event', + 25: 'ge_se_spi_hsgrp_send', + 26: 'ge_se_spi_lsvert_eov', + 27: 'ge_se_spi_lsvert_stalled', + 28: 'ge_se_spi_lsvert_starved_busy', + 29: 'ge_se_spi_lsvert_valid', + 30: 'ge_se_spi_hsvert_fifo_full_stall', + 31: 'ge_se_spi_tgrp_fifo_stall', + 32: 'ge_spi_hsgrp_spi_stall', + 33: 'ge_se_spi_gssubgrp_event_window_active', + 34: 'ge_se_hs_input_stall', + 35: 'ge_se_sending_vert_or_prim', + 36: 'ge_se_sclk_input_vld', + 37: 'ge_spi_lswave_fifo_full_stall', + 38: 'ge_spi_hswave_fifo_full_stall', + 39: 'ge_hs_tif_stall', + 40: 'ge_csb_spi_bp', + 41: 'ge_ngg_starving_for_wave_id', + 42: 'ge_pa0_csb_eop', + 43: 'ge_ngg_starved_idle', + 44: 'ge_gsprim_send', + 45: 'ge_esvert_send', + 46: 'ge_ngg_starved_after_work', + 47: 'ge_ngg_subgrp_fifo_stall', + 48: 'ge_ngg_ord_id_req_stall', + 49: 'ge_ngg_indx_bus_stall', + 50: 'ge_hs_stall_tfmm_fifo_full', + 51: 'ge_gs_issue_rtr_stalled', + 52: 'ge_gsprim_stalled_esvert', + 53: 'ge_gsthread_stalled', + 54: 'ge_ngg_attr_grp_alloc', + 55: 'ge_ngg_attr_discard_alloc', + 56: 'ge_ngg_pc_space_not_avail', + 57: 'ge_ngg_agm_req_stall', + 58: 'ge_ngg_spi_esvert_partial_eov', + 59: 'ge_ngg_spi_gsprim_partial_eov', + 60: 'ge_spi_gsgrp_valid', + 61: 'ge_ngg_attr_grp_latency', + 62: 'ge_ngg_reuse_prim_limit_hit', + 63: 'ge_ngg_reuse_vert_limit_hit', + 64: 'ge_te11_con_stall', + 65: 'ge_te11_compactor_starved', + 66: 'ge_ngg_stall_tess_off_tess_on', + 67: 'ge_ngg_stall_tess_on_tess_off', + 68: 'ge_merged_lses_vert_stalled', + 69: 'ge_merged_hsgs_vert_stalled', + 70: 'ge_merged_hsgs_grp_stalled', + 71: 'ge_merge_lses_fifo_blocked', + 72: 'ge_merge_hsgs_fifo_blocked', + 73: 'ge_merge_lses_vert_switch', + 74: 'ge_merge_hsgs_vert_switch', + 75: 'ge_merge_hsgs_grp_switch', + 76: 'ge_merge_gsgrp_rdy_pending_verts', + 77: 'ge_merge_hsgrp_rdy_pending_verts', + 78: 'ge_se_ds_cache_hits', + 79: 'ge_se_api_vs_verts', + 80: 'ge_se_api_ds_verts', + 81: 'ge_se_combined_busy', + 82: 'ge_spi_lsvert_send', + 83: 'ge_spi_hsvert_send', + 84: 'ge_ngg_attr_grp_wasted', + 85: 'ge_spi_gssubgrp_stalled', + 86: 'ge_ngg_attr_null_dealloc', + 87: 'ge_ngg_busy_base', +} +ge_se_ds_prims = 0 +ge_se_es_thread_groups = 1 +ge_se_esvert_stalled_gsprim = 2 +ge_se_hs_tfm_stall = 3 +ge_se_hs_tgs_active_high_water_mark = 4 +ge_se_hs_thread_groups = 5 +ge_se_reused_es_indices = 6 +ge_se_sclk_ngg_vld = 7 +ge_se_sclk_te11_vld = 8 +ge_se_spi_esvert_eov = 9 +ge_se_spi_esvert_stalled = 10 +ge_se_spi_esvert_starved_busy = 11 +ge_se_spi_esvert_valid = 12 +ge_se_spi_gsprim_cont = 13 +ge_se_spi_gsprim_eov = 14 +ge_se_spi_gsprim_stalled = 15 +ge_se_spi_gsprim_starved_busy = 16 +ge_se_spi_gsprim_valid = 17 +ge_se_spi_gssubgrp_is_event = 18 +ge_se_spi_gssubgrp_send = 19 +ge_se_spi_hsvert_eov = 20 +ge_se_spi_hsvert_stalled = 21 +ge_se_spi_hsvert_starved_busy = 22 +ge_se_spi_hsvert_valid = 23 +ge_se_spi_hsgrp_is_event = 24 +ge_se_spi_hsgrp_send = 25 +ge_se_spi_lsvert_eov = 26 +ge_se_spi_lsvert_stalled = 27 +ge_se_spi_lsvert_starved_busy = 28 +ge_se_spi_lsvert_valid = 29 +ge_se_spi_hsvert_fifo_full_stall = 30 +ge_se_spi_tgrp_fifo_stall = 31 +ge_spi_hsgrp_spi_stall = 32 +ge_se_spi_gssubgrp_event_window_active = 33 +ge_se_hs_input_stall = 34 +ge_se_sending_vert_or_prim = 35 +ge_se_sclk_input_vld = 36 +ge_spi_lswave_fifo_full_stall = 37 +ge_spi_hswave_fifo_full_stall = 38 +ge_hs_tif_stall = 39 +ge_csb_spi_bp = 40 +ge_ngg_starving_for_wave_id = 41 +ge_pa0_csb_eop = 42 +ge_ngg_starved_idle = 43 +ge_gsprim_send = 44 +ge_esvert_send = 45 +ge_ngg_starved_after_work = 46 +ge_ngg_subgrp_fifo_stall = 47 +ge_ngg_ord_id_req_stall = 48 +ge_ngg_indx_bus_stall = 49 +ge_hs_stall_tfmm_fifo_full = 50 +ge_gs_issue_rtr_stalled = 51 +ge_gsprim_stalled_esvert = 52 +ge_gsthread_stalled = 53 +ge_ngg_attr_grp_alloc = 54 +ge_ngg_attr_discard_alloc = 55 +ge_ngg_pc_space_not_avail = 56 +ge_ngg_agm_req_stall = 57 +ge_ngg_spi_esvert_partial_eov = 58 +ge_ngg_spi_gsprim_partial_eov = 59 +ge_spi_gsgrp_valid = 60 +ge_ngg_attr_grp_latency = 61 +ge_ngg_reuse_prim_limit_hit = 62 +ge_ngg_reuse_vert_limit_hit = 63 +ge_te11_con_stall = 64 +ge_te11_compactor_starved = 65 +ge_ngg_stall_tess_off_tess_on = 66 +ge_ngg_stall_tess_on_tess_off = 67 +ge_merged_lses_vert_stalled = 68 +ge_merged_hsgs_vert_stalled = 69 +ge_merged_hsgs_grp_stalled = 70 +ge_merge_lses_fifo_blocked = 71 +ge_merge_hsgs_fifo_blocked = 72 +ge_merge_lses_vert_switch = 73 +ge_merge_hsgs_vert_switch = 74 +ge_merge_hsgs_grp_switch = 75 +ge_merge_gsgrp_rdy_pending_verts = 76 +ge_merge_hsgrp_rdy_pending_verts = 77 +ge_se_ds_cache_hits = 78 +ge_se_api_vs_verts = 79 +ge_se_api_ds_verts = 80 +ge_se_combined_busy = 81 +ge_spi_lsvert_send = 82 +ge_spi_hsvert_send = 83 +ge_ngg_attr_grp_wasted = 84 +ge_spi_gssubgrp_stalled = 85 +ge_ngg_attr_null_dealloc = 86 +ge_ngg_busy_base = 87 +GE2_SE_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ONE' +VGT_DETECT_ONE__enumvalues = { + 0: 'ENABLE_TF1_OPT', + 1: 'DISABLE_TF1_OPT', +} +ENABLE_TF1_OPT = 0 +DISABLE_TF1_OPT = 1 +VGT_DETECT_ONE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DETECT_ZERO' +VGT_DETECT_ZERO__enumvalues = { + 0: 'ENABLE_TF0_OPT', + 1: 'DISABLE_TF0_OPT', +} +ENABLE_TF0_OPT = 0 +DISABLE_TF0_OPT = 1 +VGT_DETECT_ZERO = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DIST_MODE' +VGT_DIST_MODE__enumvalues = { + 0: 'NO_DIST', + 1: 'PATCHES', + 2: 'DONUTS', + 3: 'TRAPEZOIDS', +} +NO_DIST = 0 +PATCHES = 1 +DONUTS = 2 +TRAPEZOIDS = 3 +VGT_DIST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_INDEX_SIZE' +VGT_DI_INDEX_SIZE__enumvalues = { + 0: 'DI_INDEX_SIZE_16_BIT', + 1: 'DI_INDEX_SIZE_32_BIT', + 2: 'DI_INDEX_SIZE_8_BIT', +} +DI_INDEX_SIZE_16_BIT = 0 +DI_INDEX_SIZE_32_BIT = 1 +DI_INDEX_SIZE_8_BIT = 2 +VGT_DI_INDEX_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_PRIM_TYPE' +VGT_DI_PRIM_TYPE__enumvalues = { + 0: 'DI_PT_NONE', + 1: 'DI_PT_POINTLIST', + 2: 'DI_PT_LINELIST', + 3: 'DI_PT_LINESTRIP', + 4: 'DI_PT_TRILIST', + 5: 'DI_PT_TRIFAN', + 6: 'DI_PT_TRISTRIP', + 7: 'DI_PT_2D_RECTANGLE', + 8: 'DI_PT_UNUSED_1', + 9: 'DI_PT_PATCH', + 10: 'DI_PT_LINELIST_ADJ', + 11: 'DI_PT_LINESTRIP_ADJ', + 12: 'DI_PT_TRILIST_ADJ', + 13: 'DI_PT_TRISTRIP_ADJ', + 14: 'DI_PT_UNUSED_3', + 15: 'DI_PT_UNUSED_4', + 16: 'DI_PT_UNUSED_5', + 17: 'DI_PT_RECTLIST', + 18: 'DI_PT_LINELOOP', + 19: 'DI_PT_QUADLIST', + 20: 'DI_PT_QUADSTRIP', + 21: 'DI_PT_POLYGON', +} +DI_PT_NONE = 0 +DI_PT_POINTLIST = 1 +DI_PT_LINELIST = 2 +DI_PT_LINESTRIP = 3 +DI_PT_TRILIST = 4 +DI_PT_TRIFAN = 5 +DI_PT_TRISTRIP = 6 +DI_PT_2D_RECTANGLE = 7 +DI_PT_UNUSED_1 = 8 +DI_PT_PATCH = 9 +DI_PT_LINELIST_ADJ = 10 +DI_PT_LINESTRIP_ADJ = 11 +DI_PT_TRILIST_ADJ = 12 +DI_PT_TRISTRIP_ADJ = 13 +DI_PT_UNUSED_3 = 14 +DI_PT_UNUSED_4 = 15 +DI_PT_UNUSED_5 = 16 +DI_PT_RECTLIST = 17 +DI_PT_LINELOOP = 18 +DI_PT_QUADLIST = 19 +DI_PT_QUADSTRIP = 20 +DI_PT_POLYGON = 21 +VGT_DI_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_SOURCE_SELECT' +VGT_DI_SOURCE_SELECT__enumvalues = { + 0: 'DI_SRC_SEL_DMA', + 1: 'DI_SRC_SEL_IMMEDIATE', + 2: 'DI_SRC_SEL_AUTO_INDEX', + 3: 'DI_SRC_SEL_RESERVED', +} +DI_SRC_SEL_DMA = 0 +DI_SRC_SEL_IMMEDIATE = 1 +DI_SRC_SEL_AUTO_INDEX = 2 +DI_SRC_SEL_RESERVED = 3 +VGT_DI_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_BUF_TYPE' +VGT_DMA_BUF_TYPE__enumvalues = { + 0: 'VGT_DMA_BUF_MEM', + 1: 'VGT_DMA_BUF_RING', + 2: 'VGT_DMA_BUF_SETUP', + 3: 'VGT_DMA_PTR_UPDATE', +} +VGT_DMA_BUF_MEM = 0 +VGT_DMA_BUF_RING = 1 +VGT_DMA_BUF_SETUP = 2 +VGT_DMA_PTR_UPDATE = 3 +VGT_DMA_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_SWAP_MODE' +VGT_DMA_SWAP_MODE__enumvalues = { + 0: 'VGT_DMA_SWAP_NONE', + 1: 'VGT_DMA_SWAP_16_BIT', + 2: 'VGT_DMA_SWAP_32_BIT', + 3: 'VGT_DMA_SWAP_WORD', +} +VGT_DMA_SWAP_NONE = 0 +VGT_DMA_SWAP_16_BIT = 1 +VGT_DMA_SWAP_32_BIT = 2 +VGT_DMA_SWAP_WORD = 3 +VGT_DMA_SWAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_EVENT_TYPE' +VGT_EVENT_TYPE__enumvalues = { + 0: 'Reserved_0x00', + 1: 'SAMPLE_STREAMOUTSTATS1', + 2: 'SAMPLE_STREAMOUTSTATS2', + 3: 'SAMPLE_STREAMOUTSTATS3', + 4: 'CACHE_FLUSH_TS', + 5: 'CONTEXT_DONE', + 6: 'CACHE_FLUSH', + 7: 'CS_PARTIAL_FLUSH', + 8: 'VGT_STREAMOUT_SYNC', + 9: 'EVENT_STATE_CHANGE', + 10: 'VGT_STREAMOUT_RESET', + 11: 'END_OF_PIPE_INCR_DE', + 12: 'END_OF_PIPE_IB_END', + 13: 'RST_PIX_CNT', + 14: 'BREAK_BATCH', + 15: 'VS_PARTIAL_FLUSH', + 16: 'PS_PARTIAL_FLUSH', + 17: 'FLUSH_HS_OUTPUT', + 18: 'FLUSH_DFSM', + 19: 'RESET_TO_LOWEST_VGT', + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', + 21: 'WAIT_SYNC', + 22: 'CACHE_FLUSH_AND_INV_EVENT', + 23: 'PERFCOUNTER_START', + 24: 'PERFCOUNTER_STOP', + 25: 'PIPELINESTAT_START', + 26: 'PIPELINESTAT_STOP', + 27: 'PERFCOUNTER_SAMPLE', + 28: 'FLUSH_ES_OUTPUT', + 29: 'BIN_CONF_OVERRIDE_CHECK', + 30: 'SAMPLE_PIPELINESTAT', + 31: 'SO_VGTSTREAMOUT_FLUSH', + 32: 'SAMPLE_STREAMOUTSTATS', + 33: 'RESET_VTX_CNT', + 34: 'BLOCK_CONTEXT_DONE', + 35: 'CS_CONTEXT_DONE', + 36: 'VGT_FLUSH', + 37: 'TGID_ROLLOVER', + 38: 'SQ_NON_EVENT', + 39: 'SC_SEND_DB_VPZ', + 40: 'BOTTOM_OF_PIPE_TS', + 41: 'FLUSH_SX_TS', + 42: 'DB_CACHE_FLUSH_AND_INV', + 43: 'FLUSH_AND_INV_DB_DATA_TS', + 44: 'FLUSH_AND_INV_DB_META', + 45: 'FLUSH_AND_INV_CB_DATA_TS', + 46: 'FLUSH_AND_INV_CB_META', + 47: 'CS_DONE', + 48: 'PS_DONE', + 49: 'FLUSH_AND_INV_CB_PIXEL_DATA', + 50: 'SX_CB_RAT_ACK_REQUEST', + 51: 'THREAD_TRACE_START', + 52: 'THREAD_TRACE_STOP', + 53: 'THREAD_TRACE_MARKER', + 54: 'THREAD_TRACE_DRAW', + 55: 'THREAD_TRACE_FINISH', + 56: 'PIXEL_PIPE_STAT_CONTROL', + 57: 'PIXEL_PIPE_STAT_DUMP', + 58: 'PIXEL_PIPE_STAT_RESET', + 59: 'CONTEXT_SUSPEND', + 60: 'OFFCHIP_HS_DEALLOC', + 61: 'ENABLE_NGG_PIPELINE', + 62: 'ENABLE_PIPELINE_NOT_USED', + 63: 'DRAW_DONE', +} +Reserved_0x00 = 0 +SAMPLE_STREAMOUTSTATS1 = 1 +SAMPLE_STREAMOUTSTATS2 = 2 +SAMPLE_STREAMOUTSTATS3 = 3 +CACHE_FLUSH_TS = 4 +CONTEXT_DONE = 5 +CACHE_FLUSH = 6 +CS_PARTIAL_FLUSH = 7 +VGT_STREAMOUT_SYNC = 8 +EVENT_STATE_CHANGE = 9 +VGT_STREAMOUT_RESET = 10 +END_OF_PIPE_INCR_DE = 11 +END_OF_PIPE_IB_END = 12 +RST_PIX_CNT = 13 +BREAK_BATCH = 14 +VS_PARTIAL_FLUSH = 15 +PS_PARTIAL_FLUSH = 16 +FLUSH_HS_OUTPUT = 17 +FLUSH_DFSM = 18 +RESET_TO_LOWEST_VGT = 19 +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +WAIT_SYNC = 21 +CACHE_FLUSH_AND_INV_EVENT = 22 +PERFCOUNTER_START = 23 +PERFCOUNTER_STOP = 24 +PIPELINESTAT_START = 25 +PIPELINESTAT_STOP = 26 +PERFCOUNTER_SAMPLE = 27 +FLUSH_ES_OUTPUT = 28 +BIN_CONF_OVERRIDE_CHECK = 29 +SAMPLE_PIPELINESTAT = 30 +SO_VGTSTREAMOUT_FLUSH = 31 +SAMPLE_STREAMOUTSTATS = 32 +RESET_VTX_CNT = 33 +BLOCK_CONTEXT_DONE = 34 +CS_CONTEXT_DONE = 35 +VGT_FLUSH = 36 +TGID_ROLLOVER = 37 +SQ_NON_EVENT = 38 +SC_SEND_DB_VPZ = 39 +BOTTOM_OF_PIPE_TS = 40 +FLUSH_SX_TS = 41 +DB_CACHE_FLUSH_AND_INV = 42 +FLUSH_AND_INV_DB_DATA_TS = 43 +FLUSH_AND_INV_DB_META = 44 +FLUSH_AND_INV_CB_DATA_TS = 45 +FLUSH_AND_INV_CB_META = 46 +CS_DONE = 47 +PS_DONE = 48 +FLUSH_AND_INV_CB_PIXEL_DATA = 49 +SX_CB_RAT_ACK_REQUEST = 50 +THREAD_TRACE_START = 51 +THREAD_TRACE_STOP = 52 +THREAD_TRACE_MARKER = 53 +THREAD_TRACE_DRAW = 54 +THREAD_TRACE_FINISH = 55 +PIXEL_PIPE_STAT_CONTROL = 56 +PIXEL_PIPE_STAT_DUMP = 57 +PIXEL_PIPE_STAT_RESET = 58 +CONTEXT_SUSPEND = 59 +OFFCHIP_HS_DEALLOC = 60 +ENABLE_NGG_PIPELINE = 61 +ENABLE_PIPELINE_NOT_USED = 62 +DRAW_DONE = 63 +VGT_EVENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GROUP_CONV_SEL' +VGT_GROUP_CONV_SEL__enumvalues = { + 0: 'VGT_GRP_INDEX_16', + 1: 'VGT_GRP_INDEX_32', + 2: 'VGT_GRP_UINT_16', + 3: 'VGT_GRP_UINT_32', + 4: 'VGT_GRP_SINT_16', + 5: 'VGT_GRP_SINT_32', + 6: 'VGT_GRP_FLOAT_32', + 7: 'VGT_GRP_AUTO_PRIM', + 8: 'VGT_GRP_FIX_1_23_TO_FLOAT', +} +VGT_GRP_INDEX_16 = 0 +VGT_GRP_INDEX_32 = 1 +VGT_GRP_UINT_16 = 2 +VGT_GRP_UINT_32 = 3 +VGT_GRP_SINT_16 = 4 +VGT_GRP_SINT_32 = 5 +VGT_GRP_FLOAT_32 = 6 +VGT_GRP_AUTO_PRIM = 7 +VGT_GRP_FIX_1_23_TO_FLOAT = 8 +VGT_GROUP_CONV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_MODE_TYPE' +VGT_GS_MODE_TYPE__enumvalues = { + 0: 'GS_OFF', + 1: 'GS_SCENARIO_A', + 2: 'GS_SCENARIO_B', + 3: 'GS_SCENARIO_G', + 4: 'GS_SCENARIO_C', + 5: 'SPRITE_EN', +} +GS_OFF = 0 +GS_SCENARIO_A = 1 +GS_SCENARIO_B = 2 +GS_SCENARIO_G = 3 +GS_SCENARIO_C = 4 +SPRITE_EN = 5 +VGT_GS_MODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_OUTPRIM_TYPE' +VGT_GS_OUTPRIM_TYPE__enumvalues = { + 0: 'POINTLIST', + 1: 'LINESTRIP', + 2: 'TRISTRIP', + 3: 'RECT_2D', + 4: 'RECTLIST', +} +POINTLIST = 0 +LINESTRIP = 1 +TRISTRIP = 2 +RECT_2D = 3 +RECTLIST = 4 +VGT_GS_OUTPRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_INDEX_TYPE_MODE' +VGT_INDEX_TYPE_MODE__enumvalues = { + 0: 'VGT_INDEX_16', + 1: 'VGT_INDEX_32', + 2: 'VGT_INDEX_8', +} +VGT_INDEX_16 = 0 +VGT_INDEX_32 = 1 +VGT_INDEX_8 = 2 +VGT_INDEX_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUTPATH_SELECT' +VGT_OUTPATH_SELECT__enumvalues = { + 0: 'VGT_OUTPATH_VTX_REUSE', + 1: 'VGT_OUTPATH_GS_BLOCK', + 2: 'VGT_OUTPATH_HS_BLOCK', + 3: 'VGT_OUTPATH_PRIM_GEN', + 4: 'VGT_OUTPATH_TE_PRIM_GEN', + 5: 'VGT_OUTPATH_TE_GS_BLOCK', + 6: 'VGT_OUTPATH_TE_OUTPUT', +} +VGT_OUTPATH_VTX_REUSE = 0 +VGT_OUTPATH_GS_BLOCK = 1 +VGT_OUTPATH_HS_BLOCK = 2 +VGT_OUTPATH_PRIM_GEN = 3 +VGT_OUTPATH_TE_PRIM_GEN = 4 +VGT_OUTPATH_TE_GS_BLOCK = 5 +VGT_OUTPATH_TE_OUTPUT = 6 +VGT_OUTPATH_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUT_PRIM_TYPE' +VGT_OUT_PRIM_TYPE__enumvalues = { + 0: 'VGT_OUT_POINT', + 1: 'VGT_OUT_LINE', + 2: 'VGT_OUT_TRI', + 3: 'VGT_OUT_2D_RECT', + 4: 'VGT_OUT_RECT_V0', + 5: 'VGT_OUT_DUMMY_1', + 6: 'VGT_OUT_DUMMY_2', + 7: 'VGT_OUT_DUMMY_3', + 8: 'VGT_OUT_PATCH', + 9: 'VGT_OUT_LINE_ADJ', + 10: 'VGT_OUT_TRI_ADJ', +} +VGT_OUT_POINT = 0 +VGT_OUT_LINE = 1 +VGT_OUT_TRI = 2 +VGT_OUT_2D_RECT = 3 +VGT_OUT_RECT_V0 = 4 +VGT_OUT_DUMMY_1 = 5 +VGT_OUT_DUMMY_2 = 6 +VGT_OUT_DUMMY_3 = 7 +VGT_OUT_PATCH = 8 +VGT_OUT_LINE_ADJ = 9 +VGT_OUT_TRI_ADJ = 10 +VGT_OUT_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_RDREQ_POLICY' +VGT_RDREQ_POLICY__enumvalues = { + 0: 'VGT_POLICY_LRU', + 1: 'VGT_POLICY_STREAM', + 2: 'VGT_POLICY_BYPASS', +} +VGT_POLICY_LRU = 0 +VGT_POLICY_STREAM = 1 +VGT_POLICY_BYPASS = 2 +VGT_RDREQ_POLICY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_SPEC_DATA_READ' +VGT_SPEC_DATA_READ__enumvalues = { + 0: 'VGT_SPEC_DATA_READ_AUTO', + 1: 'VGT_SPEC_DATA_READ_FORCE_ON', + 2: 'VGT_SPEC_DATA_READ_FORCE_OFF', +} +VGT_SPEC_DATA_READ_AUTO = 0 +VGT_SPEC_DATA_READ_FORCE_ON = 1 +VGT_SPEC_DATA_READ_FORCE_OFF = 2 +VGT_SPEC_DATA_READ = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_GS_EN' +VGT_STAGES_GS_EN__enumvalues = { + 0: 'GS_STAGE_OFF', + 1: 'GS_STAGE_ON', +} +GS_STAGE_OFF = 0 +GS_STAGE_ON = 1 +VGT_STAGES_GS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_HS_EN' +VGT_STAGES_HS_EN__enumvalues = { + 0: 'HS_STAGE_OFF', + 1: 'HS_STAGE_ON', +} +HS_STAGE_OFF = 0 +HS_STAGE_ON = 1 +VGT_STAGES_HS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TEMPORAL' +VGT_TEMPORAL__enumvalues = { + 0: 'VGT_TEMPORAL_NORMAL', + 1: 'VGT_TEMPORAL_HIGH_PRIORITY', + 2: 'VGT_TEMPORAL_STREAM', + 3: 'VGT_TEMPORAL_DISCARD', +} +VGT_TEMPORAL_NORMAL = 0 +VGT_TEMPORAL_HIGH_PRIORITY = 1 +VGT_TEMPORAL_STREAM = 2 +VGT_TEMPORAL_DISCARD = 3 +VGT_TEMPORAL = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_PARTITION' +VGT_TESS_PARTITION__enumvalues = { + 0: 'PART_INTEGER', + 1: 'PART_POW2', + 2: 'PART_FRAC_ODD', + 3: 'PART_FRAC_EVEN', +} +PART_INTEGER = 0 +PART_POW2 = 1 +PART_FRAC_ODD = 2 +PART_FRAC_EVEN = 3 +VGT_TESS_PARTITION = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TOPOLOGY' +VGT_TESS_TOPOLOGY__enumvalues = { + 0: 'OUTPUT_POINT', + 1: 'OUTPUT_LINE', + 2: 'OUTPUT_TRIANGLE_CW', + 3: 'OUTPUT_TRIANGLE_CCW', +} +OUTPUT_POINT = 0 +OUTPUT_LINE = 1 +OUTPUT_TRIANGLE_CW = 2 +OUTPUT_TRIANGLE_CCW = 3 +VGT_TESS_TOPOLOGY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TYPE' +VGT_TESS_TYPE__enumvalues = { + 0: 'TESS_ISOLINE', + 1: 'TESS_TRIANGLE', + 2: 'TESS_QUAD', +} +TESS_ISOLINE = 0 +TESS_TRIANGLE = 1 +TESS_QUAD = 2 +VGT_TESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_REG_XFER' +WD_IA_DRAW_REG_XFER__enumvalues = { + 0: 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 1: 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 2: 'WD_IA_DRAW_REG_XFER_VGT_GS_OUT_PRIM_TYPE', + 3: 'WD_IA_DRAW_REG_XFER_GE_CNTL', + 4: 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVE_TYPE', + 5: 'WD_IA_DRAW_REG_XFER_GFX_PIPE_CONTROL', + 6: 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN', + 7: 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM', + 8: 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1', + 9: 'WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC', + 10: 'WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE', + 11: 'WD_IA_DRAW_REG_XFER_VGT_DRAW_PAYLOAD_CNTL', + 12: 'WD_IA_DRAW_REG_XFER_GE_STEREO_CNTL', + 13: 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_RESET', + 14: 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_EN', + 15: 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR1', + 16: 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR2', + 17: 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR3', + 18: 'WD_IA_DRAW_REG_XFER_GE_VRS_RATE', + 19: 'WD_IA_DRAW_REG_XFER_GE_PC_ALLOC', + 20: 'WD_IA_DRAW_REG_XFER_SPI_SHADER_GS_OUT_CONFIG_PS', + 21: 'WD_IA_DRAW_REG_XFER_GE_GS_THROTTLE', +} +WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID = 0 +WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN = 1 +WD_IA_DRAW_REG_XFER_VGT_GS_OUT_PRIM_TYPE = 2 +WD_IA_DRAW_REG_XFER_GE_CNTL = 3 +WD_IA_DRAW_REG_XFER_VGT_PRIMITIVE_TYPE = 4 +WD_IA_DRAW_REG_XFER_GFX_PIPE_CONTROL = 5 +WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN = 6 +WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM = 7 +WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1 = 8 +WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC = 9 +WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE = 10 +WD_IA_DRAW_REG_XFER_VGT_DRAW_PAYLOAD_CNTL = 11 +WD_IA_DRAW_REG_XFER_GE_STEREO_CNTL = 12 +WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_RESET = 13 +WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_EN = 14 +WD_IA_DRAW_REG_XFER_GE_USER_VGPR1 = 15 +WD_IA_DRAW_REG_XFER_GE_USER_VGPR2 = 16 +WD_IA_DRAW_REG_XFER_GE_USER_VGPR3 = 17 +WD_IA_DRAW_REG_XFER_GE_VRS_RATE = 18 +WD_IA_DRAW_REG_XFER_GE_PC_ALLOC = 19 +WD_IA_DRAW_REG_XFER_SPI_SHADER_GS_OUT_CONFIG_PS = 20 +WD_IA_DRAW_REG_XFER_GE_GS_THROTTLE = 21 +WD_IA_DRAW_REG_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_SOURCE' +WD_IA_DRAW_SOURCE__enumvalues = { + 0: 'WD_IA_DRAW_SOURCE_DMA', + 1: 'WD_IA_DRAW_SOURCE_IMMD', + 2: 'WD_IA_DRAW_SOURCE_AUTO', + 3: 'WD_IA_DRAW_SOURCE_OPAQ', +} +WD_IA_DRAW_SOURCE_DMA = 0 +WD_IA_DRAW_SOURCE_IMMD = 1 +WD_IA_DRAW_SOURCE_AUTO = 2 +WD_IA_DRAW_SOURCE_OPAQ = 3 +WD_IA_DRAW_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_TYPE' +WD_IA_DRAW_TYPE__enumvalues = { + 0: 'WD_IA_DRAW_TYPE_DI_MM0', + 1: 'WD_IA_DRAW_TYPE_INDX_OFF', + 2: 'WD_IA_DRAW_TYPE_EVENT_INIT', + 3: 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 4: 'WD_IA_DRAW_TYPE_REG_XFER', + 5: 'WD_IA_DRAW_TYPE_MIN_INDX', + 6: 'WD_IA_DRAW_TYPE_MAX_INDX', + 7: 'WD_IA_DRAW_TYPE_IMM_DATA', +} +WD_IA_DRAW_TYPE_DI_MM0 = 0 +WD_IA_DRAW_TYPE_INDX_OFF = 1 +WD_IA_DRAW_TYPE_EVENT_INIT = 2 +WD_IA_DRAW_TYPE_EVENT_ADDR = 3 +WD_IA_DRAW_TYPE_REG_XFER = 4 +WD_IA_DRAW_TYPE_MIN_INDX = 5 +WD_IA_DRAW_TYPE_MAX_INDX = 6 +WD_IA_DRAW_TYPE_IMM_DATA = 7 +WD_IA_DRAW_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CHA_PERF_SEL' +CHA_PERF_SEL__enumvalues = { + 0: 'CHA_PERF_SEL_BUSY', + 1: 'CHA_PERF_SEL_STALL_CHC0', + 2: 'CHA_PERF_SEL_STALL_CHC1', + 3: 'CHA_PERF_SEL_STALL_CHC2', + 4: 'CHA_PERF_SEL_STALL_CHC3', + 5: 'CHA_PERF_SEL_REQUEST_CHC0', + 6: 'CHA_PERF_SEL_REQUEST_CHC1', + 7: 'CHA_PERF_SEL_REQUEST_CHC2', + 8: 'CHA_PERF_SEL_REQUEST_CHC3', + 9: 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', + 10: 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 11: 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', + 12: 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 13: 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 14: 'CHA_PERF_SEL_IO_32B_WDS_CHC1', + 15: 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 16: 'CHA_PERF_SEL_IO_32B_WDS_CHC3', + 17: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 18: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 19: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 20: 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', + 21: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 22: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 23: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 24: 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 25: 'CHA_PERF_SEL_ARB_REQUESTS', + 26: 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 27: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 28: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 29: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 30: 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', + 31: 'CHA_PERF_SEL_CYCLE', +} +CHA_PERF_SEL_BUSY = 0 +CHA_PERF_SEL_STALL_CHC0 = 1 +CHA_PERF_SEL_STALL_CHC1 = 2 +CHA_PERF_SEL_STALL_CHC2 = 3 +CHA_PERF_SEL_STALL_CHC3 = 4 +CHA_PERF_SEL_REQUEST_CHC0 = 5 +CHA_PERF_SEL_REQUEST_CHC1 = 6 +CHA_PERF_SEL_REQUEST_CHC2 = 7 +CHA_PERF_SEL_REQUEST_CHC3 = 8 +CHA_PERF_SEL_MEM_32B_WDS_CHC0 = 9 +CHA_PERF_SEL_MEM_32B_WDS_CHC1 = 10 +CHA_PERF_SEL_MEM_32B_WDS_CHC2 = 11 +CHA_PERF_SEL_MEM_32B_WDS_CHC3 = 12 +CHA_PERF_SEL_IO_32B_WDS_CHC0 = 13 +CHA_PERF_SEL_IO_32B_WDS_CHC1 = 14 +CHA_PERF_SEL_IO_32B_WDS_CHC2 = 15 +CHA_PERF_SEL_IO_32B_WDS_CHC3 = 16 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC0 = 17 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC1 = 18 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC2 = 19 +CHA_PERF_SEL_MEM_BURST_COUNT_CHC3 = 20 +CHA_PERF_SEL_IO_BURST_COUNT_CHC0 = 21 +CHA_PERF_SEL_IO_BURST_COUNT_CHC1 = 22 +CHA_PERF_SEL_IO_BURST_COUNT_CHC2 = 23 +CHA_PERF_SEL_IO_BURST_COUNT_CHC3 = 24 +CHA_PERF_SEL_ARB_REQUESTS = 25 +CHA_PERF_SEL_REQ_INFLIGHT_LEVEL = 26 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0 = 27 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1 = 28 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2 = 29 +CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3 = 30 +CHA_PERF_SEL_CYCLE = 31 +CHA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CHC_PERF_SEL' +CHC_PERF_SEL__enumvalues = { + 0: 'CHC_PERF_SEL_CYCLE', + 1: 'CHC_PERF_SEL_BUSY', + 2: 'CHC_PERF_SEL_STARVE', + 3: 'CHC_PERF_SEL_ARB_RET_LEVEL', + 4: 'CHC_PERF_SEL_GL2_REQ_READ_LATENCY', + 5: 'CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 6: 'CHC_PERF_SEL_REQ', + 7: 'CHC_PERF_SEL_REQ_ATOMIC_WITH_RET', + 8: 'CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 9: 'CHC_PERF_SEL_REQ_NOP_ACK', + 10: 'CHC_PERF_SEL_REQ_NOP_RTN0', + 11: 'CHC_PERF_SEL_REQ_READ', + 12: 'CHC_PERF_SEL_REQ_READ_128B', + 13: 'CHC_PERF_SEL_REQ_READ_32B', + 14: 'CHC_PERF_SEL_REQ_READ_64B', + 15: 'CHC_PERF_SEL_REQ_WRITE', + 16: 'CHC_PERF_SEL_REQ_WRITE_32B', + 17: 'CHC_PERF_SEL_REQ_WRITE_64B', + 18: 'CHC_PERF_SEL_STALL_GL2_GL1', + 19: 'CHC_PERF_SEL_STALL_BUFFER_FULL', + 20: 'CHC_PERF_SEL_REQ_CLIENT0', + 21: 'CHC_PERF_SEL_REQ_CLIENT1', + 22: 'CHC_PERF_SEL_REQ_CLIENT2', + 23: 'CHC_PERF_SEL_REQ_CLIENT3', + 24: 'CHC_PERF_SEL_REQ_CLIENT4', + 25: 'CHC_PERF_SEL_REQ_CLIENT5', + 26: 'CHC_PERF_SEL_REQ_CLIENT6', + 27: 'CHC_PERF_SEL_REQ_CLIENT7', + 28: 'CHC_PERF_SEL_REQ_CLIENT8', + 29: 'CHC_PERF_SEL_REQ_CLIENT9', + 30: 'CHC_PERF_SEL_REQ_CLIENT10', + 31: 'CHC_PERF_SEL_REQ_CLIENT11', + 32: 'CHC_PERF_SEL_REQ_CLIENT12', + 33: 'CHC_PERF_SEL_REQ_CLIENT13', + 34: 'CHC_PERF_SEL_REQ_CLIENT14', + 35: 'CHC_PERF_SEL_REQ_CLIENT15', + 36: 'CHC_PERF_SEL_REQ_CLIENT16', + 37: 'CHC_PERF_SEL_REQ_CLIENT17', + 38: 'CHC_PERF_SEL_REQ_CLIENT18', + 39: 'CHC_PERF_SEL_REQ_CLIENT19', + 40: 'CHC_PERF_SEL_REQ_CLIENT20', + 41: 'CHC_PERF_SEL_REQ_CLIENT21', + 42: 'CHC_PERF_SEL_REQ_CLIENT22', + 43: 'CHC_PERF_SEL_REQ_CLIENT23', +} +CHC_PERF_SEL_CYCLE = 0 +CHC_PERF_SEL_BUSY = 1 +CHC_PERF_SEL_STARVE = 2 +CHC_PERF_SEL_ARB_RET_LEVEL = 3 +CHC_PERF_SEL_GL2_REQ_READ_LATENCY = 4 +CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY = 5 +CHC_PERF_SEL_REQ = 6 +CHC_PERF_SEL_REQ_ATOMIC_WITH_RET = 7 +CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 8 +CHC_PERF_SEL_REQ_NOP_ACK = 9 +CHC_PERF_SEL_REQ_NOP_RTN0 = 10 +CHC_PERF_SEL_REQ_READ = 11 +CHC_PERF_SEL_REQ_READ_128B = 12 +CHC_PERF_SEL_REQ_READ_32B = 13 +CHC_PERF_SEL_REQ_READ_64B = 14 +CHC_PERF_SEL_REQ_WRITE = 15 +CHC_PERF_SEL_REQ_WRITE_32B = 16 +CHC_PERF_SEL_REQ_WRITE_64B = 17 +CHC_PERF_SEL_STALL_GL2_GL1 = 18 +CHC_PERF_SEL_STALL_BUFFER_FULL = 19 +CHC_PERF_SEL_REQ_CLIENT0 = 20 +CHC_PERF_SEL_REQ_CLIENT1 = 21 +CHC_PERF_SEL_REQ_CLIENT2 = 22 +CHC_PERF_SEL_REQ_CLIENT3 = 23 +CHC_PERF_SEL_REQ_CLIENT4 = 24 +CHC_PERF_SEL_REQ_CLIENT5 = 25 +CHC_PERF_SEL_REQ_CLIENT6 = 26 +CHC_PERF_SEL_REQ_CLIENT7 = 27 +CHC_PERF_SEL_REQ_CLIENT8 = 28 +CHC_PERF_SEL_REQ_CLIENT9 = 29 +CHC_PERF_SEL_REQ_CLIENT10 = 30 +CHC_PERF_SEL_REQ_CLIENT11 = 31 +CHC_PERF_SEL_REQ_CLIENT12 = 32 +CHC_PERF_SEL_REQ_CLIENT13 = 33 +CHC_PERF_SEL_REQ_CLIENT14 = 34 +CHC_PERF_SEL_REQ_CLIENT15 = 35 +CHC_PERF_SEL_REQ_CLIENT16 = 36 +CHC_PERF_SEL_REQ_CLIENT17 = 37 +CHC_PERF_SEL_REQ_CLIENT18 = 38 +CHC_PERF_SEL_REQ_CLIENT19 = 39 +CHC_PERF_SEL_REQ_CLIENT20 = 40 +CHC_PERF_SEL_REQ_CLIENT21 = 41 +CHC_PERF_SEL_REQ_CLIENT22 = 42 +CHC_PERF_SEL_REQ_CLIENT23 = 43 +CHC_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_PERF_SEL' +GRBM_PERF_SEL__enumvalues = { + 0: 'GRBM_PERF_SEL_COUNT', + 1: 'GRBM_PERF_SEL_USER_DEFINED', + 2: 'GRBM_PERF_SEL_GUI_ACTIVE', + 3: 'GRBM_PERF_SEL_CP_BUSY', + 4: 'GRBM_PERF_SEL_CP_COHER_BUSY', + 5: 'GRBM_PERF_SEL_CP_DMA_BUSY', + 6: 'GRBM_PERF_SEL_CB_BUSY', + 7: 'GRBM_PERF_SEL_DB_BUSY', + 8: 'GRBM_PERF_SEL_PA_BUSY', + 9: 'GRBM_PERF_SEL_SC_BUSY', + 11: 'GRBM_PERF_SEL_SPI_BUSY', + 12: 'GRBM_PERF_SEL_SX_BUSY', + 13: 'GRBM_PERF_SEL_TA_BUSY', + 14: 'GRBM_PERF_SEL_CB_CLEAN', + 15: 'GRBM_PERF_SEL_DB_CLEAN', + 26: 'GRBM_PERF_SEL_BCI_BUSY', + 27: 'GRBM_PERF_SEL_RLC_BUSY', + 28: 'GRBM_PERF_SEL_TCP_BUSY', + 29: 'GRBM_PERF_SEL_CPG_BUSY', + 30: 'GRBM_PERF_SEL_CPC_BUSY', + 31: 'GRBM_PERF_SEL_CPF_BUSY', + 32: 'GRBM_PERF_SEL_GE_BUSY', + 33: 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', + 34: 'GRBM_PERF_SEL_UTCL2_BUSY', + 35: 'GRBM_PERF_SEL_EA_BUSY', + 39: 'GRBM_PERF_SEL_UTCL1_BUSY', + 40: 'GRBM_PERF_SEL_GL2CC_BUSY', + 41: 'GRBM_PERF_SEL_SDMA_BUSY', + 42: 'GRBM_PERF_SEL_CH_BUSY', + 44: 'GRBM_PERF_SEL_PMM_BUSY', + 45: 'GRBM_PERF_SEL_GUS_BUSY', + 46: 'GRBM_PERF_SEL_GL1CC_BUSY', + 47: 'GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY', + 48: 'GRBM_PERF_SEL_GL1XCC_BUSY', + 49: 'GRBM_PERF_SEL_PC_BUSY', +} +GRBM_PERF_SEL_COUNT = 0 +GRBM_PERF_SEL_USER_DEFINED = 1 +GRBM_PERF_SEL_GUI_ACTIVE = 2 +GRBM_PERF_SEL_CP_BUSY = 3 +GRBM_PERF_SEL_CP_COHER_BUSY = 4 +GRBM_PERF_SEL_CP_DMA_BUSY = 5 +GRBM_PERF_SEL_CB_BUSY = 6 +GRBM_PERF_SEL_DB_BUSY = 7 +GRBM_PERF_SEL_PA_BUSY = 8 +GRBM_PERF_SEL_SC_BUSY = 9 +GRBM_PERF_SEL_SPI_BUSY = 11 +GRBM_PERF_SEL_SX_BUSY = 12 +GRBM_PERF_SEL_TA_BUSY = 13 +GRBM_PERF_SEL_CB_CLEAN = 14 +GRBM_PERF_SEL_DB_CLEAN = 15 +GRBM_PERF_SEL_BCI_BUSY = 26 +GRBM_PERF_SEL_RLC_BUSY = 27 +GRBM_PERF_SEL_TCP_BUSY = 28 +GRBM_PERF_SEL_CPG_BUSY = 29 +GRBM_PERF_SEL_CPC_BUSY = 30 +GRBM_PERF_SEL_CPF_BUSY = 31 +GRBM_PERF_SEL_GE_BUSY = 32 +GRBM_PERF_SEL_GE_NO_DMA_BUSY = 33 +GRBM_PERF_SEL_UTCL2_BUSY = 34 +GRBM_PERF_SEL_EA_BUSY = 35 +GRBM_PERF_SEL_UTCL1_BUSY = 39 +GRBM_PERF_SEL_GL2CC_BUSY = 40 +GRBM_PERF_SEL_SDMA_BUSY = 41 +GRBM_PERF_SEL_CH_BUSY = 42 +GRBM_PERF_SEL_PMM_BUSY = 44 +GRBM_PERF_SEL_GUS_BUSY = 45 +GRBM_PERF_SEL_GL1CC_BUSY = 46 +GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY = 47 +GRBM_PERF_SEL_GL1XCC_BUSY = 48 +GRBM_PERF_SEL_PC_BUSY = 49 +GRBM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_LATENCY_STATS_SEL' +CPC_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPC_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 7: 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 8: 'CPC_LATENCY_STATS_SEL_INVAL_LAST', +} +CPC_LATENCY_STATS_SEL_XACK_MAX = 0 +CPC_LATENCY_STATS_SEL_XACK_MIN = 1 +CPC_LATENCY_STATS_SEL_XACK_LAST = 2 +CPC_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPC_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPC_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPC_LATENCY_STATS_SEL_INVAL_MAX = 6 +CPC_LATENCY_STATS_SEL_INVAL_MIN = 7 +CPC_LATENCY_STATS_SEL_INVAL_LAST = 8 +CPC_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_PERFCOUNT_SEL' +CPC_PERFCOUNT_SEL__enumvalues = { + 0: 'CPC_PERF_SEL_ALWAYS_COUNT', + 1: 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 2: 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 5: 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 6: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 7: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 8: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 9: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_READ', + 10: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_WRITE', + 11: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 12: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 13: 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 14: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 15: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 16: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 17: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_READ', + 18: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_WRITE', + 19: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 20: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 21: 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 22: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 23: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 24: 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 25: 'CPC_PERF_SEL_CPC_STAT_BUSY', + 26: 'CPC_PERF_SEL_CPC_STAT_IDLE', + 27: 'CPC_PERF_SEL_CPC_STAT_STALL', + 28: 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 29: 'CPC_PERF_SEL_CPC_TCIU_IDLE', + 30: 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 31: 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', + 32: 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 33: 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 34: 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 35: 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 36: 'CPC_PERF_SEL_CPC_GCRIU_IDLE', + 37: 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 38: 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 39: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 40: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 41: 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', + 42: 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 43: 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 44: 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', + 45: 'CPC_PERF_SEL_MES_THREAD0', + 46: 'CPC_PERF_SEL_MES_THREAD1', + 47: 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 48: 'CPC_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 49: 'CPC_PERF_SEL_TCIU_READ_REQUEST_SENT', + 50: 'CPC_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 51: 'CPC_PERF_SEL_GUS_READ_REQUEST_SENT', + 52: 'CPC_PERF_SEL_MEC_THREAD0', + 53: 'CPC_PERF_SEL_MEC_THREAD1', + 54: 'CPC_PERF_SEL_MEC_THREAD2', + 55: 'CPC_PERF_SEL_MEC_THREAD3', +} +CPC_PERF_SEL_ALWAYS_COUNT = 0 +CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 1 +CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION = 2 +CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 5 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY = 6 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF = 7 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ = 8 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_READ = 9 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_WRITE = 10 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ = 11 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF = 12 +CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE = 13 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY = 14 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF = 15 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ = 16 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_READ = 17 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_WRITE = 18 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ = 19 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF = 20 +CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE = 21 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 22 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 23 +CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 24 +CPC_PERF_SEL_CPC_STAT_BUSY = 25 +CPC_PERF_SEL_CPC_STAT_IDLE = 26 +CPC_PERF_SEL_CPC_STAT_STALL = 27 +CPC_PERF_SEL_CPC_TCIU_BUSY = 28 +CPC_PERF_SEL_CPC_TCIU_IDLE = 29 +CPC_PERF_SEL_CPC_UTCL2IU_BUSY = 30 +CPC_PERF_SEL_CPC_UTCL2IU_IDLE = 31 +CPC_PERF_SEL_CPC_UTCL2IU_STALL = 32 +CPC_PERF_SEL_ME1_DC0_SPI_BUSY = 33 +CPC_PERF_SEL_ME2_DC1_SPI_BUSY = 34 +CPC_PERF_SEL_CPC_GCRIU_BUSY = 35 +CPC_PERF_SEL_CPC_GCRIU_IDLE = 36 +CPC_PERF_SEL_CPC_GCRIU_STALL = 37 +CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 38 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ = 39 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ = 40 +CPC_PERF_SEL_CPC_UTCL2IU_XACK = 41 +CPC_PERF_SEL_CPC_UTCL2IU_XNACK = 42 +CPC_PERF_SEL_MEC_INSTR_CACHE_HIT = 43 +CPC_PERF_SEL_MEC_INSTR_CACHE_MISS = 44 +CPC_PERF_SEL_MES_THREAD0 = 45 +CPC_PERF_SEL_MES_THREAD1 = 46 +CPC_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS = 47 +CPC_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 48 +CPC_PERF_SEL_TCIU_READ_REQUEST_SENT = 49 +CPC_PERF_SEL_GUS_WRITE_REQUEST_SENT = 50 +CPC_PERF_SEL_GUS_READ_REQUEST_SENT = 51 +CPC_PERF_SEL_MEC_THREAD0 = 52 +CPC_PERF_SEL_MEC_THREAD1 = 53 +CPC_PERF_SEL_MEC_THREAD2 = 54 +CPC_PERF_SEL_MEC_THREAD3 = 55 +CPC_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_LATENCY_STATS_SEL' +CPF_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPF_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPF_LATENCY_STATS_SEL_READ_MAX', + 7: 'CPF_LATENCY_STATS_SEL_READ_MIN', + 8: 'CPF_LATENCY_STATS_SEL_READ_LAST', + 9: 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 10: 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 11: 'CPF_LATENCY_STATS_SEL_INVAL_LAST', +} +CPF_LATENCY_STATS_SEL_XACK_MAX = 0 +CPF_LATENCY_STATS_SEL_XACK_MIN = 1 +CPF_LATENCY_STATS_SEL_XACK_LAST = 2 +CPF_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPF_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPF_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPF_LATENCY_STATS_SEL_READ_MAX = 6 +CPF_LATENCY_STATS_SEL_READ_MIN = 7 +CPF_LATENCY_STATS_SEL_READ_LAST = 8 +CPF_LATENCY_STATS_SEL_INVAL_MAX = 9 +CPF_LATENCY_STATS_SEL_INVAL_MIN = 10 +CPF_LATENCY_STATS_SEL_INVAL_LAST = 11 +CPF_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNTWINDOW_SEL' +CPF_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPF_PERFWINDOW_SEL_CSF', + 1: 'CPF_PERFWINDOW_SEL_HQD1', + 2: 'CPF_PERFWINDOW_SEL_HQD2', + 3: 'CPF_PERFWINDOW_SEL_RDMA', + 4: 'CPF_PERFWINDOW_SEL_RWPP', +} +CPF_PERFWINDOW_SEL_CSF = 0 +CPF_PERFWINDOW_SEL_HQD1 = 1 +CPF_PERFWINDOW_SEL_HQD2 = 2 +CPF_PERFWINDOW_SEL_RDMA = 3 +CPF_PERFWINDOW_SEL_RWPP = 4 +CPF_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNT_SEL' +CPF_PERFCOUNT_SEL__enumvalues = { + 0: 'CPF_PERF_SEL_ALWAYS_COUNT', + 2: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 3: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 4: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 5: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 6: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 7: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE', + 10: 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 11: 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 12: 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 13: 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 14: 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 15: 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 16: 'CPF_PERF_SEL_GUS_READ_REQUEST_SENT', + 17: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 18: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 19: 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 20: 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 21: 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 22: 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 23: 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 24: 'CPF_PERF_SEL_CPF_STAT_BUSY', + 25: 'CPF_PERF_SEL_CPF_STAT_IDLE', + 26: 'CPF_PERF_SEL_CPF_STAT_STALL', + 27: 'CPF_PERF_SEL_CPF_TCIU_BUSY', + 28: 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 29: 'CPF_PERF_SEL_CPF_TCIU_STALL', + 30: 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 31: 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', + 32: 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 33: 'CPF_PERF_SEL_CPF_GCRIU_BUSY', + 34: 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 35: 'CPF_PERF_SEL_CPF_GCRIU_STALL', + 36: 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 37: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 38: 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', + 39: 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', + 40: 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ', + 41: 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE', + 42: 'CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY', + 43: 'CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY', +} +CPF_PERF_SEL_ALWAYS_COUNT = 0 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE = 2 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS = 3 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING = 4 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1 = 5 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2 = 6 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE = 7 +CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR = 10 +CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 11 +CPF_PERF_SEL_GRBM_DWORDS_SENT = 12 +CPF_PERF_SEL_DYNAMIC_CLOCK_VALID = 13 +CPF_PERF_SEL_REGISTER_CLOCK_VALID = 14 +CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT = 15 +CPF_PERF_SEL_GUS_READ_REQUEST_SENT = 16 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 17 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 18 +CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION = 19 +CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION = 20 +CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 21 +CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 22 +CPF_PERF_SEL_TCIU_READ_REQUEST_SENT = 23 +CPF_PERF_SEL_CPF_STAT_BUSY = 24 +CPF_PERF_SEL_CPF_STAT_IDLE = 25 +CPF_PERF_SEL_CPF_STAT_STALL = 26 +CPF_PERF_SEL_CPF_TCIU_BUSY = 27 +CPF_PERF_SEL_CPF_TCIU_IDLE = 28 +CPF_PERF_SEL_CPF_TCIU_STALL = 29 +CPF_PERF_SEL_CPF_UTCL2IU_BUSY = 30 +CPF_PERF_SEL_CPF_UTCL2IU_IDLE = 31 +CPF_PERF_SEL_CPF_UTCL2IU_STALL = 32 +CPF_PERF_SEL_CPF_GCRIU_BUSY = 33 +CPF_PERF_SEL_CPF_GCRIU_IDLE = 34 +CPF_PERF_SEL_CPF_GCRIU_STALL = 35 +CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 36 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB = 37 +CPF_PERF_SEL_CPF_UTCL2IU_XACK = 38 +CPF_PERF_SEL_CPF_UTCL2IU_XNACK = 39 +CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ = 40 +CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE = 41 +CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY = 42 +CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY = 43 +CPF_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_SCRATCH_REG_ATOMIC_OP' +CPF_SCRATCH_REG_ATOMIC_OP__enumvalues = { + 0: 'CPF_SCRATCH_REG_ATOMIC_ADD', + 1: 'CPF_SCRATCH_REG_ATOMIC_SUB', + 2: 'CPF_SCRATCH_REG_ATOMIC_OR', + 3: 'CPF_SCRATCH_REG_ATOMIC_AND', + 4: 'CPF_SCRATCH_REG_ATOMIC_NOT', + 5: 'CPF_SCRATCH_REG_ATOMIC_MIN', + 6: 'CPF_SCRATCH_REG_ATOMIC_MAX', + 7: 'CPF_SCRATCH_REG_ATOMIC_CMPSWAP', +} +CPF_SCRATCH_REG_ATOMIC_ADD = 0 +CPF_SCRATCH_REG_ATOMIC_SUB = 1 +CPF_SCRATCH_REG_ATOMIC_OR = 2 +CPF_SCRATCH_REG_ATOMIC_AND = 3 +CPF_SCRATCH_REG_ATOMIC_NOT = 4 +CPF_SCRATCH_REG_ATOMIC_MIN = 5 +CPF_SCRATCH_REG_ATOMIC_MAX = 6 +CPF_SCRATCH_REG_ATOMIC_CMPSWAP = 7 +CPF_SCRATCH_REG_ATOMIC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_LATENCY_STATS_SEL' +CPG_LATENCY_STATS_SEL__enumvalues = { + 0: 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 1: 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 2: 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 3: 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 4: 'CPG_LATENCY_STATS_SEL_XNACK_MIN', + 5: 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 6: 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 7: 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 8: 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 9: 'CPG_LATENCY_STATS_SEL_READ_MAX', + 10: 'CPG_LATENCY_STATS_SEL_READ_MIN', + 11: 'CPG_LATENCY_STATS_SEL_READ_LAST', + 12: 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 13: 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 14: 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 15: 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 16: 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 17: 'CPG_LATENCY_STATS_SEL_INVAL_LAST', +} +CPG_LATENCY_STATS_SEL_XACK_MAX = 0 +CPG_LATENCY_STATS_SEL_XACK_MIN = 1 +CPG_LATENCY_STATS_SEL_XACK_LAST = 2 +CPG_LATENCY_STATS_SEL_XNACK_MAX = 3 +CPG_LATENCY_STATS_SEL_XNACK_MIN = 4 +CPG_LATENCY_STATS_SEL_XNACK_LAST = 5 +CPG_LATENCY_STATS_SEL_WRITE_MAX = 6 +CPG_LATENCY_STATS_SEL_WRITE_MIN = 7 +CPG_LATENCY_STATS_SEL_WRITE_LAST = 8 +CPG_LATENCY_STATS_SEL_READ_MAX = 9 +CPG_LATENCY_STATS_SEL_READ_MIN = 10 +CPG_LATENCY_STATS_SEL_READ_LAST = 11 +CPG_LATENCY_STATS_SEL_ATOMIC_MAX = 12 +CPG_LATENCY_STATS_SEL_ATOMIC_MIN = 13 +CPG_LATENCY_STATS_SEL_ATOMIC_LAST = 14 +CPG_LATENCY_STATS_SEL_INVAL_MAX = 15 +CPG_LATENCY_STATS_SEL_INVAL_MIN = 16 +CPG_LATENCY_STATS_SEL_INVAL_LAST = 17 +CPG_LATENCY_STATS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNTWINDOW_SEL' +CPG_PERFCOUNTWINDOW_SEL__enumvalues = { + 0: 'CPG_PERFWINDOW_SEL_PFP', + 1: 'CPG_PERFWINDOW_SEL_ME', + 2: 'CPG_PERFWINDOW_SEL_CE', + 3: 'CPG_PERFWINDOW_SEL_MES', + 4: 'CPG_PERFWINDOW_SEL_MEC1', + 5: 'CPG_PERFWINDOW_SEL_MEC2', + 6: 'CPG_PERFWINDOW_SEL_DFY', + 7: 'CPG_PERFWINDOW_SEL_DMA', + 8: 'CPG_PERFWINDOW_SEL_SHADOW', + 9: 'CPG_PERFWINDOW_SEL_RB', + 10: 'CPG_PERFWINDOW_SEL_CEDMA', + 11: 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 12: 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', + 13: 'CPG_PERFWINDOW_SEL_PQ1', + 14: 'CPG_PERFWINDOW_SEL_PQ2', + 15: 'CPG_PERFWINDOW_SEL_PQ3', + 16: 'CPG_PERFWINDOW_SEL_MEMWR', + 17: 'CPG_PERFWINDOW_SEL_MEMRD', + 18: 'CPG_PERFWINDOW_SEL_VGT0', + 19: 'CPG_PERFWINDOW_SEL_VGT1', + 20: 'CPG_PERFWINDOW_SEL_APPEND', + 21: 'CPG_PERFWINDOW_SEL_QURD', + 22: 'CPG_PERFWINDOW_SEL_DDID', + 23: 'CPG_PERFWINDOW_SEL_SR', + 24: 'CPG_PERFWINDOW_SEL_QU_EOP', + 25: 'CPG_PERFWINDOW_SEL_QU_STRM', + 26: 'CPG_PERFWINDOW_SEL_QU_PIPE', + 27: 'CPG_PERFWINDOW_SEL_RESERVED1', + 28: 'CPG_PERFWINDOW_SEL_CPC_IC', + 29: 'CPG_PERFWINDOW_SEL_RESERVED2', + 30: 'CPG_PERFWINDOW_SEL_CPG_IC', +} +CPG_PERFWINDOW_SEL_PFP = 0 +CPG_PERFWINDOW_SEL_ME = 1 +CPG_PERFWINDOW_SEL_CE = 2 +CPG_PERFWINDOW_SEL_MES = 3 +CPG_PERFWINDOW_SEL_MEC1 = 4 +CPG_PERFWINDOW_SEL_MEC2 = 5 +CPG_PERFWINDOW_SEL_DFY = 6 +CPG_PERFWINDOW_SEL_DMA = 7 +CPG_PERFWINDOW_SEL_SHADOW = 8 +CPG_PERFWINDOW_SEL_RB = 9 +CPG_PERFWINDOW_SEL_CEDMA = 10 +CPG_PERFWINDOW_SEL_PRT_HDR_RPTR = 11 +CPG_PERFWINDOW_SEL_PRT_SMP_RPTR = 12 +CPG_PERFWINDOW_SEL_PQ1 = 13 +CPG_PERFWINDOW_SEL_PQ2 = 14 +CPG_PERFWINDOW_SEL_PQ3 = 15 +CPG_PERFWINDOW_SEL_MEMWR = 16 +CPG_PERFWINDOW_SEL_MEMRD = 17 +CPG_PERFWINDOW_SEL_VGT0 = 18 +CPG_PERFWINDOW_SEL_VGT1 = 19 +CPG_PERFWINDOW_SEL_APPEND = 20 +CPG_PERFWINDOW_SEL_QURD = 21 +CPG_PERFWINDOW_SEL_DDID = 22 +CPG_PERFWINDOW_SEL_SR = 23 +CPG_PERFWINDOW_SEL_QU_EOP = 24 +CPG_PERFWINDOW_SEL_QU_STRM = 25 +CPG_PERFWINDOW_SEL_QU_PIPE = 26 +CPG_PERFWINDOW_SEL_RESERVED1 = 27 +CPG_PERFWINDOW_SEL_CPC_IC = 28 +CPG_PERFWINDOW_SEL_RESERVED2 = 29 +CPG_PERFWINDOW_SEL_CPG_IC = 30 +CPG_PERFCOUNTWINDOW_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNT_SEL' +CPG_PERFCOUNT_SEL__enumvalues = { + 0: 'CPG_PERF_SEL_ALWAYS_COUNT', + 1: 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 4: 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 5: 'CPG_PERF_SEL_ME_PARSER_BUSY', + 6: 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 7: 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', + 9: 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 10: 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 11: 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 12: 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 13: 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 14: 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 15: 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 16: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 17: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 18: 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 19: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 20: 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 21: 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 22: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 23: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 24: 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 25: 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 26: 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 27: 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 28: 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 29: 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 31: 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 32: 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 33: 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 34: 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 35: 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 36: 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 37: 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 38: 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 39: 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 41: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 42: 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 43: 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 44: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 45: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 46: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 47: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 48: 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 49: 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 50: 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 51: 'CPG_PERF_SEL_CPG_STAT_BUSY', + 52: 'CPG_PERF_SEL_CPG_STAT_IDLE', + 53: 'CPG_PERF_SEL_CPG_STAT_STALL', + 54: 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 55: 'CPG_PERF_SEL_CPG_TCIU_IDLE', + 56: 'CPG_PERF_SEL_CPG_TCIU_STALL', + 57: 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', + 58: 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', + 59: 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', + 60: 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 61: 'CPG_PERF_SEL_CPG_GCRIU_IDLE', + 62: 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 63: 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 64: 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', + 65: 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', + 66: 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 67: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 68: 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 69: 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 70: 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 71: 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 72: 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 73: 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', + 74: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 75: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 76: 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 77: 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', + 78: 'CPG_PERF_SEL_DMA_BUSY', + 79: 'CPG_PERF_SEL_DMA_STARVED', + 80: 'CPG_PERF_SEL_DMA_STALLED', + 81: 'CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL', + 82: 'CPG_PERF_SEL_PFP_PWS_STALLED0', + 83: 'CPG_PERF_SEL_ME_PWS_STALLED0', + 84: 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS0', + 85: 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS0', + 86: 'CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL0', + 87: 'CPG_PERF_SEL_PFP_PWS_STALLED1', + 88: 'CPG_PERF_SEL_ME_PWS_STALLED1', + 89: 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS1', + 90: 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS1', + 91: 'CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL1', +} +CPG_PERF_SEL_ALWAYS_COUNT = 0 +CPG_PERF_SEL_RBIU_FIFO_FULL = 1 +CPG_PERF_SEL_CP_GRBM_DWORDS_SENT = 4 +CPG_PERF_SEL_ME_PARSER_BUSY = 5 +CPG_PERF_SEL_COUNT_TYPE0_PACKETS = 6 +CPG_PERF_SEL_COUNT_TYPE3_PACKETS = 7 +CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS = 9 +CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS = 10 +CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS = 11 +CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ = 12 +CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ = 13 +CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX = 14 +CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS = 15 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE = 16 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM = 17 +CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY = 18 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY = 19 +CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY = 20 +CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ = 21 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP = 22 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ = 23 +CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX = 24 +CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU = 25 +CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS = 26 +CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH = 27 +CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER = 28 +CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER = 29 +CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY = 31 +CPG_PERF_SEL_DYNAMIC_CLK_VALID = 32 +CPG_PERF_SEL_REGISTER_CLK_VALID = 33 +CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT = 34 +CPG_PERF_SEL_GUS_READ_REQUEST_SENT = 35 +CPG_PERF_SEL_CE_STALL_RAM_DUMP = 36 +CPG_PERF_SEL_CE_STALL_RAM_WRITE = 37 +CPG_PERF_SEL_CE_STALL_ON_INC_FIFO = 38 +CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO = 39 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ = 41 +CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG = 42 +CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER = 43 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 44 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS = 45 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 46 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 47 +CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 48 +CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT = 49 +CPG_PERF_SEL_TCIU_READ_REQUEST_SENT = 50 +CPG_PERF_SEL_CPG_STAT_BUSY = 51 +CPG_PERF_SEL_CPG_STAT_IDLE = 52 +CPG_PERF_SEL_CPG_STAT_STALL = 53 +CPG_PERF_SEL_CPG_TCIU_BUSY = 54 +CPG_PERF_SEL_CPG_TCIU_IDLE = 55 +CPG_PERF_SEL_CPG_TCIU_STALL = 56 +CPG_PERF_SEL_CPG_UTCL2IU_BUSY = 57 +CPG_PERF_SEL_CPG_UTCL2IU_IDLE = 58 +CPG_PERF_SEL_CPG_UTCL2IU_STALL = 59 +CPG_PERF_SEL_CPG_GCRIU_BUSY = 60 +CPG_PERF_SEL_CPG_GCRIU_IDLE = 61 +CPG_PERF_SEL_CPG_GCRIU_STALL = 62 +CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE = 63 +CPG_PERF_SEL_ALL_GFX_PIPES_BUSY = 64 +CPG_PERF_SEL_CPG_UTCL2IU_XACK = 65 +CPG_PERF_SEL_CPG_UTCL2IU_XNACK = 66 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY = 67 +CPG_PERF_SEL_PFP_INSTR_CACHE_HIT = 68 +CPG_PERF_SEL_PFP_INSTR_CACHE_MISS = 69 +CPG_PERF_SEL_CE_INSTR_CACHE_HIT = 70 +CPG_PERF_SEL_CE_INSTR_CACHE_MISS = 71 +CPG_PERF_SEL_ME_INSTR_CACHE_HIT = 72 +CPG_PERF_SEL_ME_INSTR_CACHE_MISS = 73 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1 = 74 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1 = 75 +CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2 = 76 +CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2 = 77 +CPG_PERF_SEL_DMA_BUSY = 78 +CPG_PERF_SEL_DMA_STARVED = 79 +CPG_PERF_SEL_DMA_STALLED = 80 +CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL = 81 +CPG_PERF_SEL_PFP_PWS_STALLED0 = 82 +CPG_PERF_SEL_ME_PWS_STALLED0 = 83 +CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS0 = 84 +CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS0 = 85 +CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL0 = 86 +CPG_PERF_SEL_PFP_PWS_STALLED1 = 87 +CPG_PERF_SEL_ME_PWS_STALLED1 = 88 +CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS1 = 89 +CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS1 = 90 +CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL1 = 91 +CPG_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ALPHA_TAG_RAM_SEL' +CP_ALPHA_TAG_RAM_SEL__enumvalues = { + 0: 'CPG_TAG_RAM', + 1: 'CPC_TAG_RAM', + 2: 'CPF_TAG_RAM', + 3: 'RSV_TAG_RAM', +} +CPG_TAG_RAM = 0 +CPC_TAG_RAM = 1 +CPF_TAG_RAM = 2 +RSV_TAG_RAM = 3 +CP_ALPHA_TAG_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_MODE' +CP_DDID_CNTL_MODE__enumvalues = { + 0: 'STALL', + 1: 'OVERRUN', +} +STALL = 0 +OVERRUN = 1 +CP_DDID_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_SIZE' +CP_DDID_CNTL_SIZE__enumvalues = { + 0: 'SIZE_8K', + 1: 'SIZE_16K', +} +SIZE_8K = 0 +SIZE_16K = 1 +CP_DDID_CNTL_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_DDID_CNTL_VMID_SEL' +CP_DDID_CNTL_VMID_SEL__enumvalues = { + 0: 'DDID_VMID_PIPE', + 1: 'DDID_VMID_CNTL', +} +DDID_VMID_PIPE = 0 +DDID_VMID_CNTL = 1 +CP_DDID_CNTL_VMID_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ME_ID' +CP_ME_ID__enumvalues = { + 0: 'ME_ID0', + 1: 'ME_ID1', + 2: 'ME_ID2', + 3: 'ME_ID3', +} +ME_ID0 = 0 +ME_ID1 = 1 +ME_ID2 = 2 +ME_ID3 = 3 +CP_ME_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PIPE_ID' +CP_PIPE_ID__enumvalues = { + 0: 'PIPE_ID0', + 1: 'PIPE_ID1', + 2: 'PIPE_ID2', + 3: 'PIPE_ID3', +} +PIPE_ID0 = 0 +PIPE_ID1 = 1 +PIPE_ID2 = 2 +PIPE_ID3 = 3 +CP_PIPE_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_RING_ID' +CP_RING_ID__enumvalues = { + 0: 'RINGID0', + 1: 'RINGID1', + 2: 'RINGID2', + 3: 'RINGID3', +} +RINGID0 = 0 +RINGID1 = 1 +RINGID2 = 2 +RINGID3 = 3 +CP_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'GCRPerfSel' +GCRPerfSel__enumvalues = { + 0: 'GCR_PERF_SEL_NONE', + 1: 'GCR_PERF_SEL_SDMA0_ALL_REQ', + 2: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 3: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 4: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 5: 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 6: 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 7: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 8: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 9: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 10: 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 11: 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 12: 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 13: 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 14: 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', + 15: 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 16: 'GCR_PERF_SEL_SDMA0_GL1_TLB_SHOOTDOWN_REQ', + 17: 'GCR_PERF_SEL_SDMA1_ALL_REQ', + 18: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 19: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 20: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 21: 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 22: 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 23: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 24: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 25: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 26: 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 27: 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 28: 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 29: 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 30: 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', + 31: 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 32: 'GCR_PERF_SEL_SDMA1_GL1_TLB_SHOOTDOWN_REQ', + 33: 'GCR_PERF_SEL_CPC_ALL_REQ', + 34: 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', + 35: 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 36: 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 37: 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 38: 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 39: 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', + 40: 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 41: 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 42: 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 43: 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 44: 'GCR_PERF_SEL_CPC_METADATA_REQ', + 45: 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', + 46: 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 47: 'GCR_PERF_SEL_CPC_TCP_REQ', + 48: 'GCR_PERF_SEL_CPC_GL1_TLB_SHOOTDOWN_REQ', + 49: 'GCR_PERF_SEL_CPG_ALL_REQ', + 50: 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', + 51: 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 52: 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 53: 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 54: 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 55: 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', + 56: 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 57: 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 58: 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 59: 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 60: 'GCR_PERF_SEL_CPG_METADATA_REQ', + 61: 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', + 62: 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 63: 'GCR_PERF_SEL_CPG_TCP_REQ', + 64: 'GCR_PERF_SEL_CPG_GL1_TLB_SHOOTDOWN_REQ', + 65: 'GCR_PERF_SEL_CPF_ALL_REQ', + 66: 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', + 67: 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 68: 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 69: 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 70: 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 71: 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', + 72: 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 73: 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 74: 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 75: 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 76: 'GCR_PERF_SEL_CPF_METADATA_REQ', + 77: 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', + 78: 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 79: 'GCR_PERF_SEL_CPF_TCP_REQ', + 80: 'GCR_PERF_SEL_CPF_GL1_TLB_SHOOTDOWN_REQ', + 81: 'GCR_PERF_SEL_VIRT_REQ', + 82: 'GCR_PERF_SEL_PHY_REQ', + 83: 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 84: 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 85: 'GCR_PERF_SEL_ALL_REQ', + 86: 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 87: 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 88: 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 89: 'GCR_PERF_SEL_UTCL2_REQ', + 90: 'GCR_PERF_SEL_UTCL2_RET', + 91: 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 92: 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 93: 'GCR_PERF_SEL_UTCL2_FILTERED_RET', + 94: 'GCR_PERF_SEL_PMM_ABIT_NUM_FLUSH', + 95: 'GCR_PERF_SEL_PMM_ABIT_FLUSH_ONGOING', + 96: 'GCR_PERF_SEL_PMM_NUM_INTERRUPT', + 97: 'GCR_PERF_SEL_PMM_STALL_PMM_IH_CREDITS', + 98: 'GCR_PERF_SEL_PMM_INTERRUPT_READY_TO_SEND', + 99: 'GCR_PERF_SEL_PMM_ABIT_TIMER_FLUSH', + 100: 'GCR_PERF_SEL_PMM_ABIT_FORCE_FLUSH', + 101: 'GCR_PERF_SEL_PMM_ABIT_FLUSH_INTERRUPT', + 102: 'GCR_PERF_SEL_PMM_ALOG_INTERRUPT', + 103: 'GCR_PERF_SEL_PMM_MAM_FLUSH_REQ', + 104: 'GCR_PERF_SEL_PMM_MAM_FLUSH_RESP', + 105: 'GCR_PERF_SEL_PMM_RLC_CGCG_REQ', + 106: 'GCR_PERF_SEL_PMM_RLC_CGCG_RESP', + 107: 'GCR_PERF_SEL_RLC_ALL_REQ', + 108: 'GCR_PERF_SEL_RLC_GL2_RANGE_REQ', + 109: 'GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ', + 110: 'GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ', + 111: 'GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ', + 112: 'GCR_PERF_SEL_RLC_GL2_ALL_REQ', + 113: 'GCR_PERF_SEL_RLC_GL1_RANGE_REQ', + 114: 'GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ', + 115: 'GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ', + 116: 'GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ', + 117: 'GCR_PERF_SEL_RLC_GL1_ALL_REQ', + 118: 'GCR_PERF_SEL_RLC_METADATA_REQ', + 119: 'GCR_PERF_SEL_RLC_SQC_DATA_REQ', + 120: 'GCR_PERF_SEL_RLC_SQC_INST_REQ', + 121: 'GCR_PERF_SEL_RLC_TCP_REQ', + 122: 'GCR_PERF_SEL_RLC_GL1_TLB_SHOOTDOWN_REQ', + 123: 'GCR_PERF_SEL_PM_ALL_REQ', + 124: 'GCR_PERF_SEL_PM_GL2_RANGE_REQ', + 125: 'GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ', + 126: 'GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ', + 127: 'GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ', + 128: 'GCR_PERF_SEL_PM_GL2_ALL_REQ', + 129: 'GCR_PERF_SEL_PM_GL1_RANGE_REQ', + 130: 'GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ', + 131: 'GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ', + 132: 'GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ', + 133: 'GCR_PERF_SEL_PM_GL1_ALL_REQ', + 134: 'GCR_PERF_SEL_PM_METADATA_REQ', + 135: 'GCR_PERF_SEL_PM_SQC_DATA_REQ', + 136: 'GCR_PERF_SEL_PM_SQC_INST_REQ', + 137: 'GCR_PERF_SEL_PM_TCP_REQ', + 138: 'GCR_PERF_SEL_PM_GL1_TLB_SHOOTDOWN_REQ', + 139: 'GCR_PERF_SEL_PIO_ALL_REQ', + 140: 'GCR_PERF_SEL_PIO_GL2_RANGE_REQ', + 141: 'GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ', + 142: 'GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ', + 143: 'GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ', + 144: 'GCR_PERF_SEL_PIO_GL2_ALL_REQ', + 145: 'GCR_PERF_SEL_PIO_GL1_RANGE_REQ', + 146: 'GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ', + 147: 'GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ', + 148: 'GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ', + 149: 'GCR_PERF_SEL_PIO_GL1_ALL_REQ', + 150: 'GCR_PERF_SEL_PIO_METADATA_REQ', + 151: 'GCR_PERF_SEL_PIO_SQC_DATA_REQ', + 152: 'GCR_PERF_SEL_PIO_SQC_INST_REQ', + 153: 'GCR_PERF_SEL_PIO_TCP_REQ', + 154: 'GCR_PERF_SEL_PIO_GL1_TLB_SHOOTDOWN_REQ', +} +GCR_PERF_SEL_NONE = 0 +GCR_PERF_SEL_SDMA0_ALL_REQ = 1 +GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ = 2 +GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ = 3 +GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ = 4 +GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ = 5 +GCR_PERF_SEL_SDMA0_GL2_ALL_REQ = 6 +GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ = 7 +GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ = 8 +GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ = 9 +GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ = 10 +GCR_PERF_SEL_SDMA0_GL1_ALL_REQ = 11 +GCR_PERF_SEL_SDMA0_METADATA_REQ = 12 +GCR_PERF_SEL_SDMA0_SQC_DATA_REQ = 13 +GCR_PERF_SEL_SDMA0_SQC_INST_REQ = 14 +GCR_PERF_SEL_SDMA0_TCP_REQ = 15 +GCR_PERF_SEL_SDMA0_GL1_TLB_SHOOTDOWN_REQ = 16 +GCR_PERF_SEL_SDMA1_ALL_REQ = 17 +GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ = 18 +GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ = 19 +GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ = 20 +GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ = 21 +GCR_PERF_SEL_SDMA1_GL2_ALL_REQ = 22 +GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ = 23 +GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ = 24 +GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ = 25 +GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ = 26 +GCR_PERF_SEL_SDMA1_GL1_ALL_REQ = 27 +GCR_PERF_SEL_SDMA1_METADATA_REQ = 28 +GCR_PERF_SEL_SDMA1_SQC_DATA_REQ = 29 +GCR_PERF_SEL_SDMA1_SQC_INST_REQ = 30 +GCR_PERF_SEL_SDMA1_TCP_REQ = 31 +GCR_PERF_SEL_SDMA1_GL1_TLB_SHOOTDOWN_REQ = 32 +GCR_PERF_SEL_CPC_ALL_REQ = 33 +GCR_PERF_SEL_CPC_GL2_RANGE_REQ = 34 +GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ = 35 +GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ = 36 +GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ = 37 +GCR_PERF_SEL_CPC_GL2_ALL_REQ = 38 +GCR_PERF_SEL_CPC_GL1_RANGE_REQ = 39 +GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ = 40 +GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ = 41 +GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ = 42 +GCR_PERF_SEL_CPC_GL1_ALL_REQ = 43 +GCR_PERF_SEL_CPC_METADATA_REQ = 44 +GCR_PERF_SEL_CPC_SQC_DATA_REQ = 45 +GCR_PERF_SEL_CPC_SQC_INST_REQ = 46 +GCR_PERF_SEL_CPC_TCP_REQ = 47 +GCR_PERF_SEL_CPC_GL1_TLB_SHOOTDOWN_REQ = 48 +GCR_PERF_SEL_CPG_ALL_REQ = 49 +GCR_PERF_SEL_CPG_GL2_RANGE_REQ = 50 +GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ = 51 +GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ = 52 +GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ = 53 +GCR_PERF_SEL_CPG_GL2_ALL_REQ = 54 +GCR_PERF_SEL_CPG_GL1_RANGE_REQ = 55 +GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ = 56 +GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ = 57 +GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ = 58 +GCR_PERF_SEL_CPG_GL1_ALL_REQ = 59 +GCR_PERF_SEL_CPG_METADATA_REQ = 60 +GCR_PERF_SEL_CPG_SQC_DATA_REQ = 61 +GCR_PERF_SEL_CPG_SQC_INST_REQ = 62 +GCR_PERF_SEL_CPG_TCP_REQ = 63 +GCR_PERF_SEL_CPG_GL1_TLB_SHOOTDOWN_REQ = 64 +GCR_PERF_SEL_CPF_ALL_REQ = 65 +GCR_PERF_SEL_CPF_GL2_RANGE_REQ = 66 +GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ = 67 +GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ = 68 +GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ = 69 +GCR_PERF_SEL_CPF_GL2_ALL_REQ = 70 +GCR_PERF_SEL_CPF_GL1_RANGE_REQ = 71 +GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ = 72 +GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ = 73 +GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ = 74 +GCR_PERF_SEL_CPF_GL1_ALL_REQ = 75 +GCR_PERF_SEL_CPF_METADATA_REQ = 76 +GCR_PERF_SEL_CPF_SQC_DATA_REQ = 77 +GCR_PERF_SEL_CPF_SQC_INST_REQ = 78 +GCR_PERF_SEL_CPF_TCP_REQ = 79 +GCR_PERF_SEL_CPF_GL1_TLB_SHOOTDOWN_REQ = 80 +GCR_PERF_SEL_VIRT_REQ = 81 +GCR_PERF_SEL_PHY_REQ = 82 +GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ = 83 +GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ = 84 +GCR_PERF_SEL_ALL_REQ = 85 +GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ = 86 +GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ = 87 +GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ = 88 +GCR_PERF_SEL_UTCL2_REQ = 89 +GCR_PERF_SEL_UTCL2_RET = 90 +GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT = 91 +GCR_PERF_SEL_UTCL2_INFLIGHT_REQ = 92 +GCR_PERF_SEL_UTCL2_FILTERED_RET = 93 +GCR_PERF_SEL_PMM_ABIT_NUM_FLUSH = 94 +GCR_PERF_SEL_PMM_ABIT_FLUSH_ONGOING = 95 +GCR_PERF_SEL_PMM_NUM_INTERRUPT = 96 +GCR_PERF_SEL_PMM_STALL_PMM_IH_CREDITS = 97 +GCR_PERF_SEL_PMM_INTERRUPT_READY_TO_SEND = 98 +GCR_PERF_SEL_PMM_ABIT_TIMER_FLUSH = 99 +GCR_PERF_SEL_PMM_ABIT_FORCE_FLUSH = 100 +GCR_PERF_SEL_PMM_ABIT_FLUSH_INTERRUPT = 101 +GCR_PERF_SEL_PMM_ALOG_INTERRUPT = 102 +GCR_PERF_SEL_PMM_MAM_FLUSH_REQ = 103 +GCR_PERF_SEL_PMM_MAM_FLUSH_RESP = 104 +GCR_PERF_SEL_PMM_RLC_CGCG_REQ = 105 +GCR_PERF_SEL_PMM_RLC_CGCG_RESP = 106 +GCR_PERF_SEL_RLC_ALL_REQ = 107 +GCR_PERF_SEL_RLC_GL2_RANGE_REQ = 108 +GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ = 109 +GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ = 110 +GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ = 111 +GCR_PERF_SEL_RLC_GL2_ALL_REQ = 112 +GCR_PERF_SEL_RLC_GL1_RANGE_REQ = 113 +GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ = 114 +GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ = 115 +GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ = 116 +GCR_PERF_SEL_RLC_GL1_ALL_REQ = 117 +GCR_PERF_SEL_RLC_METADATA_REQ = 118 +GCR_PERF_SEL_RLC_SQC_DATA_REQ = 119 +GCR_PERF_SEL_RLC_SQC_INST_REQ = 120 +GCR_PERF_SEL_RLC_TCP_REQ = 121 +GCR_PERF_SEL_RLC_GL1_TLB_SHOOTDOWN_REQ = 122 +GCR_PERF_SEL_PM_ALL_REQ = 123 +GCR_PERF_SEL_PM_GL2_RANGE_REQ = 124 +GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ = 125 +GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ = 126 +GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ = 127 +GCR_PERF_SEL_PM_GL2_ALL_REQ = 128 +GCR_PERF_SEL_PM_GL1_RANGE_REQ = 129 +GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ = 130 +GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ = 131 +GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ = 132 +GCR_PERF_SEL_PM_GL1_ALL_REQ = 133 +GCR_PERF_SEL_PM_METADATA_REQ = 134 +GCR_PERF_SEL_PM_SQC_DATA_REQ = 135 +GCR_PERF_SEL_PM_SQC_INST_REQ = 136 +GCR_PERF_SEL_PM_TCP_REQ = 137 +GCR_PERF_SEL_PM_GL1_TLB_SHOOTDOWN_REQ = 138 +GCR_PERF_SEL_PIO_ALL_REQ = 139 +GCR_PERF_SEL_PIO_GL2_RANGE_REQ = 140 +GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ = 141 +GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ = 142 +GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ = 143 +GCR_PERF_SEL_PIO_GL2_ALL_REQ = 144 +GCR_PERF_SEL_PIO_GL1_RANGE_REQ = 145 +GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ = 146 +GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ = 147 +GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ = 148 +GCR_PERF_SEL_PIO_GL1_ALL_REQ = 149 +GCR_PERF_SEL_PIO_METADATA_REQ = 150 +GCR_PERF_SEL_PIO_SQC_DATA_REQ = 151 +GCR_PERF_SEL_PIO_SQC_INST_REQ = 152 +GCR_PERF_SEL_PIO_TCP_REQ = 153 +GCR_PERF_SEL_PIO_GL1_TLB_SHOOTDOWN_REQ = 154 +GCRPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'GC_EA_CPWD_PERFCOUNT_SEL' +GC_EA_CPWD_PERFCOUNT_SEL__enumvalues = { + 0: 'GC_EA_CPWD_PERF_SEL_ALWAYS_COUNT', + 1: 'GC_EA_CPWD_PERF_SEL_RDRAM_NUM_BANKS_VLD', + 2: 'GC_EA_CPWD_PERF_SEL_RDRAM_REQ_PER_CLIGRP', + 3: 'GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP', + 4: 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START0', + 5: 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END0', + 6: 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START1', + 7: 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END1', + 8: 'GC_EA_CPWD_PERF_SEL_WDRAM_NUM_BANKS_VLD', + 9: 'GC_EA_CPWD_PERF_SEL_WDRAM_REQ_PER_CLIGRP', + 10: 'GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP', + 11: 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START0', + 12: 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END0', + 13: 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START1', + 14: 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END1', + 15: 'GC_EA_CPWD_PERF_SEL_RGMI_NUM_BANKS_VLD', + 16: 'GC_EA_CPWD_PERF_SEL_RGMI_REQ_PER_CLIGRP', + 17: 'GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR', + 18: 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START0', + 19: 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END0', + 20: 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START1', + 21: 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END1', + 22: 'GC_EA_CPWD_PERF_SEL_WGMI_NUM_BANKS_VLD', + 23: 'GC_EA_CPWD_PERF_SEL_WGMI_REQ_PER_CLIGRP', + 24: 'GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP', + 25: 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START0', + 26: 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END0', + 27: 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START1', + 28: 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END1', + 29: 'GC_EA_CPWD_PERF_SEL_RIO_REQ_PER_CLIGRP', + 30: 'GC_EA_CPWD_PERF_SEL_RIO_SIZE_REQ', + 31: 'GC_EA_CPWD_PERF_SEL_RIO_GRP0_SIZE_REQ', + 32: 'GC_EA_CPWD_PERF_SEL_RIO_GRP1_SIZE_REQ', + 33: 'GC_EA_CPWD_PERF_SEL_RIO_GRP2_SIZE_REQ', + 34: 'GC_EA_CPWD_PERF_SEL_RIO_GRP3_SIZE_REQ', + 35: 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START0', + 36: 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END0', + 37: 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START1', + 38: 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END1', + 39: 'GC_EA_CPWD_PERF_SEL_WIO_REQ_PER_CLIGRP', + 40: 'GC_EA_CPWD_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP', + 41: 'GC_EA_CPWD_PERF_SEL_WIO_SIZE_REQ', + 42: 'GC_EA_CPWD_PERF_SEL_WIO_GRP0_SIZE_REQ', + 43: 'GC_EA_CPWD_PERF_SEL_WIO_GRP1_SIZE_REQ', + 44: 'GC_EA_CPWD_PERF_SEL_WIO_GRP2_SIZE_REQ', + 45: 'GC_EA_CPWD_PERF_SEL_WIO_GRP3_SIZE_REQ', + 46: 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START0', + 47: 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END0', + 48: 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START1', + 49: 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END1', + 50: 'GC_EA_CPWD_PERF_SEL_SARB_REQ_PER_VC', + 51: 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_REQ_PER_VC', + 52: 'GC_EA_CPWD_PERF_SEL_SARB_GMI_REQ_PER_VC', + 53: 'GC_EA_CPWD_PERF_SEL_SARB_IO_REQ_PER_VC', + 54: 'GC_EA_CPWD_PERF_SEL_SARB_SIZE_REQ', + 55: 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_SIZE_REQ', + 56: 'GC_EA_CPWD_PERF_SEL_SARB_GMI_SIZE_REQ', + 57: 'GC_EA_CPWD_PERF_SEL_SARB_IO_SIZE_REQ', + 58: 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START0', + 59: 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END0', + 60: 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START1', + 61: 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END1', + 62: 'GC_EA_CPWD_PERF_SEL_SARB_BUSY', + 63: 'GC_EA_CPWD_PERF_SEL_SARB_STALLED', + 64: 'GC_EA_CPWD_PERF_SEL_SARB_STARVING', + 65: 'GC_EA_CPWD_PERF_SEL_SARB_IDLE', + 66: 'GC_EA_CPWD_PERF_SEL_RRET_VLD', + 67: 'GC_EA_CPWD_PERF_SEL_WRET_VLD', + 68: 'GC_EA_CPWD_PERF_SEL_PRB_REQ', + 69: 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_EVICT', + 70: 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_REQ_VLD', + 71: 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT', + 72: 'GC_EA_CPWD_PERF_SEL_MAM_NUM_DQRY', + 73: 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT', + 74: 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED', + 75: 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_COMPLETED', + 76: 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_ONGOING', + 77: 'GC_EA_CPWD_PERF_SEL_RDRAM_SIZE_REQ', + 78: 'GC_EA_CPWD_PERF_SEL_WDRAM_SIZE_REQ', + 79: 'GC_EA_CPWD_PERF_SEL_RGMI_SIZE_REQ', + 80: 'GC_EA_CPWD_PERF_SEL_WGMI_SIZE_REQ', + 81: 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_RW_TURN_AROUND', + 82: 'GC_EA_CPWD_PERF_SEL_SARB_GMI_RW_TURN_AROUND', + 83: 'GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 84: 'GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 85: 'GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 86: 'GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 87: 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_EVICT', + 88: 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_REQ_VLD', + 89: 'GC_EA_CPWD_PERF_SEL_SARB_COHERENT_SIZE_REQ', + 90: 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT_EVICT', + 91: 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_LRU_EVICT', + 92: 'GC_EA_CPWD_PERF_SEL_MAM_FLUSH_REQ', + 93: 'GC_EA_CPWD_PERF_SEL_MAM_FLUSH_RESP', + 94: 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT_EVICT', + 95: 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_LRU_EVICT', + 96: 'GC_EA_CPWD_PERF_SEL_MAM_DQRY_ONGOING', + 97: 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT', +} +GC_EA_CPWD_PERF_SEL_ALWAYS_COUNT = 0 +GC_EA_CPWD_PERF_SEL_RDRAM_NUM_BANKS_VLD = 1 +GC_EA_CPWD_PERF_SEL_RDRAM_REQ_PER_CLIGRP = 2 +GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP = 3 +GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START0 = 4 +GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END0 = 5 +GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START1 = 6 +GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END1 = 7 +GC_EA_CPWD_PERF_SEL_WDRAM_NUM_BANKS_VLD = 8 +GC_EA_CPWD_PERF_SEL_WDRAM_REQ_PER_CLIGRP = 9 +GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP = 10 +GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START0 = 11 +GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END0 = 12 +GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START1 = 13 +GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END1 = 14 +GC_EA_CPWD_PERF_SEL_RGMI_NUM_BANKS_VLD = 15 +GC_EA_CPWD_PERF_SEL_RGMI_REQ_PER_CLIGRP = 16 +GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR = 17 +GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START0 = 18 +GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END0 = 19 +GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START1 = 20 +GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END1 = 21 +GC_EA_CPWD_PERF_SEL_WGMI_NUM_BANKS_VLD = 22 +GC_EA_CPWD_PERF_SEL_WGMI_REQ_PER_CLIGRP = 23 +GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP = 24 +GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START0 = 25 +GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END0 = 26 +GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START1 = 27 +GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END1 = 28 +GC_EA_CPWD_PERF_SEL_RIO_REQ_PER_CLIGRP = 29 +GC_EA_CPWD_PERF_SEL_RIO_SIZE_REQ = 30 +GC_EA_CPWD_PERF_SEL_RIO_GRP0_SIZE_REQ = 31 +GC_EA_CPWD_PERF_SEL_RIO_GRP1_SIZE_REQ = 32 +GC_EA_CPWD_PERF_SEL_RIO_GRP2_SIZE_REQ = 33 +GC_EA_CPWD_PERF_SEL_RIO_GRP3_SIZE_REQ = 34 +GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START0 = 35 +GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END0 = 36 +GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START1 = 37 +GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END1 = 38 +GC_EA_CPWD_PERF_SEL_WIO_REQ_PER_CLIGRP = 39 +GC_EA_CPWD_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP = 40 +GC_EA_CPWD_PERF_SEL_WIO_SIZE_REQ = 41 +GC_EA_CPWD_PERF_SEL_WIO_GRP0_SIZE_REQ = 42 +GC_EA_CPWD_PERF_SEL_WIO_GRP1_SIZE_REQ = 43 +GC_EA_CPWD_PERF_SEL_WIO_GRP2_SIZE_REQ = 44 +GC_EA_CPWD_PERF_SEL_WIO_GRP3_SIZE_REQ = 45 +GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START0 = 46 +GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END0 = 47 +GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START1 = 48 +GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END1 = 49 +GC_EA_CPWD_PERF_SEL_SARB_REQ_PER_VC = 50 +GC_EA_CPWD_PERF_SEL_SARB_DRAM_REQ_PER_VC = 51 +GC_EA_CPWD_PERF_SEL_SARB_GMI_REQ_PER_VC = 52 +GC_EA_CPWD_PERF_SEL_SARB_IO_REQ_PER_VC = 53 +GC_EA_CPWD_PERF_SEL_SARB_SIZE_REQ = 54 +GC_EA_CPWD_PERF_SEL_SARB_DRAM_SIZE_REQ = 55 +GC_EA_CPWD_PERF_SEL_SARB_GMI_SIZE_REQ = 56 +GC_EA_CPWD_PERF_SEL_SARB_IO_SIZE_REQ = 57 +GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START0 = 58 +GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END0 = 59 +GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START1 = 60 +GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END1 = 61 +GC_EA_CPWD_PERF_SEL_SARB_BUSY = 62 +GC_EA_CPWD_PERF_SEL_SARB_STALLED = 63 +GC_EA_CPWD_PERF_SEL_SARB_STARVING = 64 +GC_EA_CPWD_PERF_SEL_SARB_IDLE = 65 +GC_EA_CPWD_PERF_SEL_RRET_VLD = 66 +GC_EA_CPWD_PERF_SEL_WRET_VLD = 67 +GC_EA_CPWD_PERF_SEL_PRB_REQ = 68 +GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_EVICT = 69 +GC_EA_CPWD_PERF_SEL_MAM_ARAM_REQ_VLD = 70 +GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT = 71 +GC_EA_CPWD_PERF_SEL_MAM_NUM_DQRY = 72 +GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT = 73 +GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED = 74 +GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_COMPLETED = 75 +GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_ONGOING = 76 +GC_EA_CPWD_PERF_SEL_RDRAM_SIZE_REQ = 77 +GC_EA_CPWD_PERF_SEL_WDRAM_SIZE_REQ = 78 +GC_EA_CPWD_PERF_SEL_RGMI_SIZE_REQ = 79 +GC_EA_CPWD_PERF_SEL_WGMI_SIZE_REQ = 80 +GC_EA_CPWD_PERF_SEL_SARB_DRAM_RW_TURN_AROUND = 81 +GC_EA_CPWD_PERF_SEL_SARB_GMI_RW_TURN_AROUND = 82 +GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH = 83 +GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH = 84 +GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH = 85 +GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH = 86 +GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_EVICT = 87 +GC_EA_CPWD_PERF_SEL_MAM_DBIT_REQ_VLD = 88 +GC_EA_CPWD_PERF_SEL_SARB_COHERENT_SIZE_REQ = 89 +GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT_EVICT = 90 +GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_LRU_EVICT = 91 +GC_EA_CPWD_PERF_SEL_MAM_FLUSH_REQ = 92 +GC_EA_CPWD_PERF_SEL_MAM_FLUSH_RESP = 93 +GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT_EVICT = 94 +GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_LRU_EVICT = 95 +GC_EA_CPWD_PERF_SEL_MAM_DQRY_ONGOING = 96 +GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT = 97 +GC_EA_CPWD_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GCVML2_SPM_PERF_SEL' +GCVML2_SPM_PERF_SEL__enumvalues = { + 0: 'GCVML2_SPM_PERF_SEL_EVENT_0', + 1: 'GCVML2_SPM_PERF_SEL_EVENT_1', + 2: 'GCVML2_SPM_PERF_SEL_EVENT_2', + 3: 'GCVML2_SPM_PERF_SEL_EVENT_3', + 4: 'GCVML2_SPM_PERF_SEL_EVENT_4', + 5: 'GCVML2_SPM_PERF_SEL_EVENT_5', + 6: 'GCVML2_SPM_PERF_SEL_EVENT_6', + 7: 'GCVML2_SPM_PERF_SEL_EVENT_7', + 8: 'GCVML2_SPM_PERF_SEL_EVENT_8', + 9: 'GCVML2_SPM_PERF_SEL_EVENT_9', + 10: 'GCVML2_SPM_PERF_SEL_EVENT_10', + 11: 'GCVML2_SPM_PERF_SEL_EVENT_11', + 12: 'GCVML2_SPM_PERF_SEL_EVENT_12', + 13: 'GCVML2_SPM_PERF_SEL_EVENT_13', + 14: 'GCVML2_SPM_PERF_SEL_EVENT_14', + 15: 'GCVML2_SPM_PERF_SEL_EVENT_15', + 16: 'GCVML2_SPM_PERF_SEL_EVENT_16', + 17: 'GCVML2_SPM_PERF_SEL_EVENT_17', + 18: 'GCVML2_SPM_PERF_SEL_EVENT_18', + 19: 'GCVML2_SPM_PERF_SEL_EVENT_19', + 20: 'GCVML2_SPM_PERF_SEL_EVENT_20', + 21: 'GCVML2_SPM_PERF_SEL_EVENT_21', + 22: 'GCVML2_SPM_PERF_SEL_EVENT_22', + 23: 'GCVML2_SPM_PERF_SEL_EVENT_23', + 24: 'GCVML2_SPM_PERF_SEL_EVENT_24', + 25: 'GCVML2_SPM_PERF_SEL_EVENT_25', + 26: 'GCVML2_SPM_PERF_SEL_EVENT_26', + 27: 'GCVML2_SPM_PERF_SEL_EVENT_27', + 28: 'GCVML2_SPM_PERF_SEL_EVENT_28', + 29: 'GCVML2_SPM_PERF_SEL_EVENT_29', + 30: 'GCVML2_SPM_PERF_SEL_EVENT_30', + 31: 'GCVML2_SPM_PERF_SEL_EVENT_31', + 32: 'GCVML2_SPM_PERF_SEL_EVENT_32', + 33: 'GCVML2_SPM_PERF_SEL_EVENT_33', + 34: 'GCVML2_SPM_PERF_SEL_EVENT_34', + 35: 'GCVML2_SPM_PERF_SEL_EVENT_35', + 36: 'GCVML2_SPM_PERF_SEL_EVENT_36', + 37: 'GCVML2_SPM_PERF_SEL_EVENT_37', + 38: 'GCVML2_SPM_PERF_SEL_EVENT_38', + 39: 'GCVML2_SPM_PERF_SEL_EVENT_39', + 40: 'GCVML2_SPM_PERF_SEL_EVENT_40', + 41: 'GCVML2_SPM_PERF_SEL_EVENT_41', + 42: 'GCVML2_SPM_PERF_SEL_EVENT_42', + 43: 'GCVML2_SPM_PERF_SEL_EVENT_43', + 44: 'GCVML2_SPM_PERF_SEL_EVENT_44', + 45: 'GCVML2_SPM_PERF_SEL_EVENT_45', + 46: 'GCVML2_SPM_PERF_SEL_EVENT_46', + 47: 'GCVML2_SPM_PERF_SEL_EVENT_47', + 48: 'GCVML2_SPM_PERF_SEL_EVENT_48', + 49: 'GCVML2_SPM_PERF_SEL_EVENT_49', + 50: 'GCVML2_SPM_PERF_SEL_EVENT_50', + 51: 'GCVML2_SPM_PERF_SEL_EVENT_51', + 52: 'GCVML2_SPM_PERF_SEL_EVENT_52', + 53: 'GCVML2_SPM_PERF_SEL_EVENT_53', + 54: 'GCVML2_SPM_PERF_SEL_EVENT_54', + 55: 'GCVML2_SPM_PERF_SEL_EVENT_55', + 56: 'GCVML2_SPM_PERF_SEL_EVENT_56', + 57: 'GCVML2_SPM_PERF_SEL_EVENT_57', + 58: 'GCVML2_SPM_PERF_SEL_EVENT_58', + 59: 'GCVML2_SPM_PERF_SEL_EVENT_59', + 60: 'GCVML2_SPM_PERF_SEL_EVENT_60', + 61: 'GCVML2_SPM_PERF_SEL_EVENT_61', + 62: 'GCVML2_SPM_PERF_SEL_EVENT_62', + 63: 'GCVML2_SPM_PERF_SEL_EVENT_63', + 64: 'GCVML2_SPM_PERF_SEL_EVENT_64', + 65: 'GCVML2_SPM_PERF_SEL_EVENT_65', + 66: 'GCVML2_SPM_PERF_SEL_EVENT_66', + 67: 'GCVML2_SPM_PERF_SEL_EVENT_67', + 68: 'GCVML2_SPM_PERF_SEL_EVENT_68', + 69: 'GCVML2_SPM_PERF_SEL_EVENT_69', + 70: 'GCVML2_SPM_PERF_SEL_EVENT_70', + 71: 'GCVML2_SPM_PERF_SEL_EVENT_71', + 72: 'GCVML2_SPM_PERF_SEL_EVENT_72', + 73: 'GCVML2_SPM_PERF_SEL_EVENT_73', + 74: 'GCVML2_SPM_PERF_SEL_EVENT_74', + 75: 'GCVML2_SPM_PERF_SEL_EVENT_75', + 76: 'GCVML2_SPM_PERF_SEL_EVENT_76', + 77: 'GCVML2_SPM_PERF_SEL_EVENT_77', + 78: 'GCVML2_SPM_PERF_SEL_EVENT_78', + 79: 'GCVML2_SPM_PERF_SEL_EVENT_79', + 80: 'GCVML2_SPM_PERF_SEL_EVENT_80', + 81: 'GCVML2_SPM_PERF_SEL_EVENT_81', + 82: 'GCVML2_SPM_PERF_SEL_EVENT_82', + 83: 'GCVML2_SPM_PERF_SEL_EVENT_83', + 84: 'GCVML2_SPM_PERF_SEL_EVENT_84', + 85: 'GCVML2_SPM_PERF_SEL_EVENT_85', + 86: 'GCVML2_SPM_PERF_SEL_EVENT_86', + 87: 'GCVML2_SPM_PERF_SEL_EVENT_87', + 88: 'GCVML2_SPM_PERF_SEL_EVENT_88', + 89: 'GCVML2_SPM_PERF_SEL_EVENT_89', + 90: 'GCVML2_SPM_PERF_SEL_EVENT_90', +} +GCVML2_SPM_PERF_SEL_EVENT_0 = 0 +GCVML2_SPM_PERF_SEL_EVENT_1 = 1 +GCVML2_SPM_PERF_SEL_EVENT_2 = 2 +GCVML2_SPM_PERF_SEL_EVENT_3 = 3 +GCVML2_SPM_PERF_SEL_EVENT_4 = 4 +GCVML2_SPM_PERF_SEL_EVENT_5 = 5 +GCVML2_SPM_PERF_SEL_EVENT_6 = 6 +GCVML2_SPM_PERF_SEL_EVENT_7 = 7 +GCVML2_SPM_PERF_SEL_EVENT_8 = 8 +GCVML2_SPM_PERF_SEL_EVENT_9 = 9 +GCVML2_SPM_PERF_SEL_EVENT_10 = 10 +GCVML2_SPM_PERF_SEL_EVENT_11 = 11 +GCVML2_SPM_PERF_SEL_EVENT_12 = 12 +GCVML2_SPM_PERF_SEL_EVENT_13 = 13 +GCVML2_SPM_PERF_SEL_EVENT_14 = 14 +GCVML2_SPM_PERF_SEL_EVENT_15 = 15 +GCVML2_SPM_PERF_SEL_EVENT_16 = 16 +GCVML2_SPM_PERF_SEL_EVENT_17 = 17 +GCVML2_SPM_PERF_SEL_EVENT_18 = 18 +GCVML2_SPM_PERF_SEL_EVENT_19 = 19 +GCVML2_SPM_PERF_SEL_EVENT_20 = 20 +GCVML2_SPM_PERF_SEL_EVENT_21 = 21 +GCVML2_SPM_PERF_SEL_EVENT_22 = 22 +GCVML2_SPM_PERF_SEL_EVENT_23 = 23 +GCVML2_SPM_PERF_SEL_EVENT_24 = 24 +GCVML2_SPM_PERF_SEL_EVENT_25 = 25 +GCVML2_SPM_PERF_SEL_EVENT_26 = 26 +GCVML2_SPM_PERF_SEL_EVENT_27 = 27 +GCVML2_SPM_PERF_SEL_EVENT_28 = 28 +GCVML2_SPM_PERF_SEL_EVENT_29 = 29 +GCVML2_SPM_PERF_SEL_EVENT_30 = 30 +GCVML2_SPM_PERF_SEL_EVENT_31 = 31 +GCVML2_SPM_PERF_SEL_EVENT_32 = 32 +GCVML2_SPM_PERF_SEL_EVENT_33 = 33 +GCVML2_SPM_PERF_SEL_EVENT_34 = 34 +GCVML2_SPM_PERF_SEL_EVENT_35 = 35 +GCVML2_SPM_PERF_SEL_EVENT_36 = 36 +GCVML2_SPM_PERF_SEL_EVENT_37 = 37 +GCVML2_SPM_PERF_SEL_EVENT_38 = 38 +GCVML2_SPM_PERF_SEL_EVENT_39 = 39 +GCVML2_SPM_PERF_SEL_EVENT_40 = 40 +GCVML2_SPM_PERF_SEL_EVENT_41 = 41 +GCVML2_SPM_PERF_SEL_EVENT_42 = 42 +GCVML2_SPM_PERF_SEL_EVENT_43 = 43 +GCVML2_SPM_PERF_SEL_EVENT_44 = 44 +GCVML2_SPM_PERF_SEL_EVENT_45 = 45 +GCVML2_SPM_PERF_SEL_EVENT_46 = 46 +GCVML2_SPM_PERF_SEL_EVENT_47 = 47 +GCVML2_SPM_PERF_SEL_EVENT_48 = 48 +GCVML2_SPM_PERF_SEL_EVENT_49 = 49 +GCVML2_SPM_PERF_SEL_EVENT_50 = 50 +GCVML2_SPM_PERF_SEL_EVENT_51 = 51 +GCVML2_SPM_PERF_SEL_EVENT_52 = 52 +GCVML2_SPM_PERF_SEL_EVENT_53 = 53 +GCVML2_SPM_PERF_SEL_EVENT_54 = 54 +GCVML2_SPM_PERF_SEL_EVENT_55 = 55 +GCVML2_SPM_PERF_SEL_EVENT_56 = 56 +GCVML2_SPM_PERF_SEL_EVENT_57 = 57 +GCVML2_SPM_PERF_SEL_EVENT_58 = 58 +GCVML2_SPM_PERF_SEL_EVENT_59 = 59 +GCVML2_SPM_PERF_SEL_EVENT_60 = 60 +GCVML2_SPM_PERF_SEL_EVENT_61 = 61 +GCVML2_SPM_PERF_SEL_EVENT_62 = 62 +GCVML2_SPM_PERF_SEL_EVENT_63 = 63 +GCVML2_SPM_PERF_SEL_EVENT_64 = 64 +GCVML2_SPM_PERF_SEL_EVENT_65 = 65 +GCVML2_SPM_PERF_SEL_EVENT_66 = 66 +GCVML2_SPM_PERF_SEL_EVENT_67 = 67 +GCVML2_SPM_PERF_SEL_EVENT_68 = 68 +GCVML2_SPM_PERF_SEL_EVENT_69 = 69 +GCVML2_SPM_PERF_SEL_EVENT_70 = 70 +GCVML2_SPM_PERF_SEL_EVENT_71 = 71 +GCVML2_SPM_PERF_SEL_EVENT_72 = 72 +GCVML2_SPM_PERF_SEL_EVENT_73 = 73 +GCVML2_SPM_PERF_SEL_EVENT_74 = 74 +GCVML2_SPM_PERF_SEL_EVENT_75 = 75 +GCVML2_SPM_PERF_SEL_EVENT_76 = 76 +GCVML2_SPM_PERF_SEL_EVENT_77 = 77 +GCVML2_SPM_PERF_SEL_EVENT_78 = 78 +GCVML2_SPM_PERF_SEL_EVENT_79 = 79 +GCVML2_SPM_PERF_SEL_EVENT_80 = 80 +GCVML2_SPM_PERF_SEL_EVENT_81 = 81 +GCVML2_SPM_PERF_SEL_EVENT_82 = 82 +GCVML2_SPM_PERF_SEL_EVENT_83 = 83 +GCVML2_SPM_PERF_SEL_EVENT_84 = 84 +GCVML2_SPM_PERF_SEL_EVENT_85 = 85 +GCVML2_SPM_PERF_SEL_EVENT_86 = 86 +GCVML2_SPM_PERF_SEL_EVENT_87 = 87 +GCVML2_SPM_PERF_SEL_EVENT_88 = 88 +GCVML2_SPM_PERF_SEL_EVENT_89 = 89 +GCVML2_SPM_PERF_SEL_EVENT_90 = 90 +GCVML2_SPM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GCUTCL2_PERF_SEL' +GCUTCL2_PERF_SEL__enumvalues = { + 0: 'GCUTCL2_PERF_SEL_EVENT_0', + 1: 'GCUTCL2_PERF_SEL_EVENT_1', + 2: 'GCUTCL2_PERF_SEL_EVENT_2', + 3: 'GCUTCL2_PERF_SEL_EVENT_3', + 4: 'GCUTCL2_PERF_SEL_EVENT_4', + 5: 'GCUTCL2_PERF_SEL_EVENT_5', + 6: 'GCUTCL2_PERF_SEL_EVENT_6', + 7: 'GCUTCL2_PERF_SEL_EVENT_7', + 8: 'GCUTCL2_PERF_SEL_EVENT_8', + 9: 'GCUTCL2_PERF_SEL_EVENT_9', + 10: 'GCUTCL2_PERF_SEL_EVENT_10', + 11: 'GCUTCL2_PERF_SEL_EVENT_11', + 12: 'GCUTCL2_PERF_SEL_EVENT_12', + 13: 'GCUTCL2_PERF_SEL_EVENT_13', + 14: 'GCUTCL2_PERF_SEL_EVENT_14', + 15: 'GCUTCL2_PERF_SEL_EVENT_15', + 16: 'GCUTCL2_PERF_SEL_EVENT_16', + 17: 'GCUTCL2_PERF_SEL_EVENT_17', + 18: 'GCUTCL2_PERF_SEL_EVENT_18', + 19: 'GCUTCL2_PERF_SEL_EVENT_19', + 20: 'GCUTCL2_PERF_SEL_EVENT_20', + 21: 'GCUTCL2_PERF_SEL_EVENT_21', + 22: 'GCUTCL2_PERF_SEL_EVENT_22', + 23: 'GCUTCL2_PERF_SEL_EVENT_23', + 24: 'GCUTCL2_PERF_SEL_EVENT_24', + 25: 'GCUTCL2_PERF_SEL_EVENT_25', + 26: 'GCUTCL2_PERF_SEL_EVENT_26', + 27: 'GCUTCL2_PERF_SEL_EVENT_27', + 28: 'GCUTCL2_PERF_SEL_EVENT_28', + 29: 'GCUTCL2_PERF_SEL_EVENT_29', + 30: 'GCUTCL2_PERF_SEL_EVENT_30', + 31: 'GCUTCL2_PERF_SEL_EVENT_31', + 32: 'GCUTCL2_PERF_SEL_EVENT_32', + 33: 'GCUTCL2_PERF_SEL_EVENT_33', + 34: 'GCUTCL2_PERF_SEL_EVENT_34', + 35: 'GCUTCL2_PERF_SEL_EVENT_35', + 36: 'GCUTCL2_PERF_SEL_EVENT_36', +} +GCUTCL2_PERF_SEL_EVENT_0 = 0 +GCUTCL2_PERF_SEL_EVENT_1 = 1 +GCUTCL2_PERF_SEL_EVENT_2 = 2 +GCUTCL2_PERF_SEL_EVENT_3 = 3 +GCUTCL2_PERF_SEL_EVENT_4 = 4 +GCUTCL2_PERF_SEL_EVENT_5 = 5 +GCUTCL2_PERF_SEL_EVENT_6 = 6 +GCUTCL2_PERF_SEL_EVENT_7 = 7 +GCUTCL2_PERF_SEL_EVENT_8 = 8 +GCUTCL2_PERF_SEL_EVENT_9 = 9 +GCUTCL2_PERF_SEL_EVENT_10 = 10 +GCUTCL2_PERF_SEL_EVENT_11 = 11 +GCUTCL2_PERF_SEL_EVENT_12 = 12 +GCUTCL2_PERF_SEL_EVENT_13 = 13 +GCUTCL2_PERF_SEL_EVENT_14 = 14 +GCUTCL2_PERF_SEL_EVENT_15 = 15 +GCUTCL2_PERF_SEL_EVENT_16 = 16 +GCUTCL2_PERF_SEL_EVENT_17 = 17 +GCUTCL2_PERF_SEL_EVENT_18 = 18 +GCUTCL2_PERF_SEL_EVENT_19 = 19 +GCUTCL2_PERF_SEL_EVENT_20 = 20 +GCUTCL2_PERF_SEL_EVENT_21 = 21 +GCUTCL2_PERF_SEL_EVENT_22 = 22 +GCUTCL2_PERF_SEL_EVENT_23 = 23 +GCUTCL2_PERF_SEL_EVENT_24 = 24 +GCUTCL2_PERF_SEL_EVENT_25 = 25 +GCUTCL2_PERF_SEL_EVENT_26 = 26 +GCUTCL2_PERF_SEL_EVENT_27 = 27 +GCUTCL2_PERF_SEL_EVENT_28 = 28 +GCUTCL2_PERF_SEL_EVENT_29 = 29 +GCUTCL2_PERF_SEL_EVENT_30 = 30 +GCUTCL2_PERF_SEL_EVENT_31 = 31 +GCUTCL2_PERF_SEL_EVENT_32 = 32 +GCUTCL2_PERF_SEL_EVENT_33 = 33 +GCUTCL2_PERF_SEL_EVENT_34 = 34 +GCUTCL2_PERF_SEL_EVENT_35 = 35 +GCUTCL2_PERF_SEL_EVENT_36 = 36 +GCUTCL2_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GCVML2_PERF_SEL' +GCVML2_PERF_SEL__enumvalues = { + 0: 'GCVML2_PERF_SEL_EVENT_0', + 1: 'GCVML2_PERF_SEL_EVENT_1', + 2: 'GCVML2_PERF_SEL_EVENT_2', + 3: 'GCVML2_PERF_SEL_EVENT_3', + 4: 'GCVML2_PERF_SEL_EVENT_4', + 5: 'GCVML2_PERF_SEL_EVENT_5', + 6: 'GCVML2_PERF_SEL_EVENT_6', + 7: 'GCVML2_PERF_SEL_EVENT_7', + 8: 'GCVML2_PERF_SEL_EVENT_8', + 9: 'GCVML2_PERF_SEL_EVENT_9', + 10: 'GCVML2_PERF_SEL_EVENT_10', + 11: 'GCVML2_PERF_SEL_EVENT_11', + 12: 'GCVML2_PERF_SEL_EVENT_12', + 13: 'GCVML2_PERF_SEL_EVENT_13', + 14: 'GCVML2_PERF_SEL_EVENT_14', + 15: 'GCVML2_PERF_SEL_EVENT_15', + 16: 'GCVML2_PERF_SEL_EVENT_16', + 17: 'GCVML2_PERF_SEL_EVENT_17', + 18: 'GCVML2_PERF_SEL_EVENT_18', + 19: 'GCVML2_PERF_SEL_EVENT_19', + 20: 'GCVML2_PERF_SEL_EVENT_20', + 21: 'GCVML2_PERF_SEL_EVENT_21', + 22: 'GCVML2_PERF_SEL_EVENT_22', + 23: 'GCVML2_PERF_SEL_EVENT_23', + 24: 'GCVML2_PERF_SEL_EVENT_24', + 25: 'GCVML2_PERF_SEL_EVENT_25', + 26: 'GCVML2_PERF_SEL_EVENT_26', + 27: 'GCVML2_PERF_SEL_EVENT_27', + 28: 'GCVML2_PERF_SEL_EVENT_28', + 29: 'GCVML2_PERF_SEL_EVENT_29', + 30: 'GCVML2_PERF_SEL_EVENT_30', + 31: 'GCVML2_PERF_SEL_EVENT_31', + 32: 'GCVML2_PERF_SEL_EVENT_32', + 33: 'GCVML2_PERF_SEL_EVENT_33', + 34: 'GCVML2_PERF_SEL_EVENT_34', + 35: 'GCVML2_PERF_SEL_EVENT_35', + 36: 'GCVML2_PERF_SEL_EVENT_36', + 37: 'GCVML2_PERF_SEL_EVENT_37', + 38: 'GCVML2_PERF_SEL_EVENT_38', + 39: 'GCVML2_PERF_SEL_EVENT_39', + 40: 'GCVML2_PERF_SEL_EVENT_40', + 41: 'GCVML2_PERF_SEL_EVENT_41', + 42: 'GCVML2_PERF_SEL_EVENT_42', + 43: 'GCVML2_PERF_SEL_EVENT_43', + 44: 'GCVML2_PERF_SEL_EVENT_44', + 45: 'GCVML2_PERF_SEL_EVENT_45', + 46: 'GCVML2_PERF_SEL_EVENT_46', + 47: 'GCVML2_PERF_SEL_EVENT_47', + 48: 'GCVML2_PERF_SEL_EVENT_48', + 49: 'GCVML2_PERF_SEL_EVENT_49', + 50: 'GCVML2_PERF_SEL_EVENT_50', + 51: 'GCVML2_PERF_SEL_EVENT_51', + 52: 'GCVML2_PERF_SEL_EVENT_52', + 53: 'GCVML2_PERF_SEL_EVENT_53', + 54: 'GCVML2_PERF_SEL_EVENT_54', + 55: 'GCVML2_PERF_SEL_EVENT_55', + 56: 'GCVML2_PERF_SEL_EVENT_56', + 57: 'GCVML2_PERF_SEL_EVENT_57', + 58: 'GCVML2_PERF_SEL_EVENT_58', + 59: 'GCVML2_PERF_SEL_EVENT_59', + 60: 'GCVML2_PERF_SEL_EVENT_60', + 61: 'GCVML2_PERF_SEL_EVENT_61', + 62: 'GCVML2_PERF_SEL_EVENT_62', + 63: 'GCVML2_PERF_SEL_EVENT_63', + 64: 'GCVML2_PERF_SEL_EVENT_64', + 65: 'GCVML2_PERF_SEL_EVENT_65', + 66: 'GCVML2_PERF_SEL_EVENT_66', + 67: 'GCVML2_PERF_SEL_EVENT_67', + 68: 'GCVML2_PERF_SEL_EVENT_68', + 69: 'GCVML2_PERF_SEL_EVENT_69', + 70: 'GCVML2_PERF_SEL_EVENT_70', + 71: 'GCVML2_PERF_SEL_EVENT_71', + 72: 'GCVML2_PERF_SEL_EVENT_72', + 73: 'GCVML2_PERF_SEL_EVENT_73', + 74: 'GCVML2_PERF_SEL_EVENT_74', + 75: 'GCVML2_PERF_SEL_EVENT_75', + 76: 'GCVML2_PERF_SEL_EVENT_76', + 77: 'GCVML2_PERF_SEL_EVENT_77', + 78: 'GCVML2_PERF_SEL_EVENT_78', + 79: 'GCVML2_PERF_SEL_EVENT_79', + 80: 'GCVML2_PERF_SEL_EVENT_80', + 81: 'GCVML2_PERF_SEL_EVENT_81', + 82: 'GCVML2_PERF_SEL_EVENT_82', + 83: 'GCVML2_PERF_SEL_EVENT_83', + 84: 'GCVML2_PERF_SEL_EVENT_84', + 85: 'GCVML2_PERF_SEL_EVENT_85', + 86: 'GCVML2_PERF_SEL_EVENT_86', + 87: 'GCVML2_PERF_SEL_EVENT_87', + 88: 'GCVML2_PERF_SEL_EVENT_88', + 89: 'GCVML2_PERF_SEL_EVENT_89', + 90: 'GCVML2_PERF_SEL_EVENT_90', +} +GCVML2_PERF_SEL_EVENT_0 = 0 +GCVML2_PERF_SEL_EVENT_1 = 1 +GCVML2_PERF_SEL_EVENT_2 = 2 +GCVML2_PERF_SEL_EVENT_3 = 3 +GCVML2_PERF_SEL_EVENT_4 = 4 +GCVML2_PERF_SEL_EVENT_5 = 5 +GCVML2_PERF_SEL_EVENT_6 = 6 +GCVML2_PERF_SEL_EVENT_7 = 7 +GCVML2_PERF_SEL_EVENT_8 = 8 +GCVML2_PERF_SEL_EVENT_9 = 9 +GCVML2_PERF_SEL_EVENT_10 = 10 +GCVML2_PERF_SEL_EVENT_11 = 11 +GCVML2_PERF_SEL_EVENT_12 = 12 +GCVML2_PERF_SEL_EVENT_13 = 13 +GCVML2_PERF_SEL_EVENT_14 = 14 +GCVML2_PERF_SEL_EVENT_15 = 15 +GCVML2_PERF_SEL_EVENT_16 = 16 +GCVML2_PERF_SEL_EVENT_17 = 17 +GCVML2_PERF_SEL_EVENT_18 = 18 +GCVML2_PERF_SEL_EVENT_19 = 19 +GCVML2_PERF_SEL_EVENT_20 = 20 +GCVML2_PERF_SEL_EVENT_21 = 21 +GCVML2_PERF_SEL_EVENT_22 = 22 +GCVML2_PERF_SEL_EVENT_23 = 23 +GCVML2_PERF_SEL_EVENT_24 = 24 +GCVML2_PERF_SEL_EVENT_25 = 25 +GCVML2_PERF_SEL_EVENT_26 = 26 +GCVML2_PERF_SEL_EVENT_27 = 27 +GCVML2_PERF_SEL_EVENT_28 = 28 +GCVML2_PERF_SEL_EVENT_29 = 29 +GCVML2_PERF_SEL_EVENT_30 = 30 +GCVML2_PERF_SEL_EVENT_31 = 31 +GCVML2_PERF_SEL_EVENT_32 = 32 +GCVML2_PERF_SEL_EVENT_33 = 33 +GCVML2_PERF_SEL_EVENT_34 = 34 +GCVML2_PERF_SEL_EVENT_35 = 35 +GCVML2_PERF_SEL_EVENT_36 = 36 +GCVML2_PERF_SEL_EVENT_37 = 37 +GCVML2_PERF_SEL_EVENT_38 = 38 +GCVML2_PERF_SEL_EVENT_39 = 39 +GCVML2_PERF_SEL_EVENT_40 = 40 +GCVML2_PERF_SEL_EVENT_41 = 41 +GCVML2_PERF_SEL_EVENT_42 = 42 +GCVML2_PERF_SEL_EVENT_43 = 43 +GCVML2_PERF_SEL_EVENT_44 = 44 +GCVML2_PERF_SEL_EVENT_45 = 45 +GCVML2_PERF_SEL_EVENT_46 = 46 +GCVML2_PERF_SEL_EVENT_47 = 47 +GCVML2_PERF_SEL_EVENT_48 = 48 +GCVML2_PERF_SEL_EVENT_49 = 49 +GCVML2_PERF_SEL_EVENT_50 = 50 +GCVML2_PERF_SEL_EVENT_51 = 51 +GCVML2_PERF_SEL_EVENT_52 = 52 +GCVML2_PERF_SEL_EVENT_53 = 53 +GCVML2_PERF_SEL_EVENT_54 = 54 +GCVML2_PERF_SEL_EVENT_55 = 55 +GCVML2_PERF_SEL_EVENT_56 = 56 +GCVML2_PERF_SEL_EVENT_57 = 57 +GCVML2_PERF_SEL_EVENT_58 = 58 +GCVML2_PERF_SEL_EVENT_59 = 59 +GCVML2_PERF_SEL_EVENT_60 = 60 +GCVML2_PERF_SEL_EVENT_61 = 61 +GCVML2_PERF_SEL_EVENT_62 = 62 +GCVML2_PERF_SEL_EVENT_63 = 63 +GCVML2_PERF_SEL_EVENT_64 = 64 +GCVML2_PERF_SEL_EVENT_65 = 65 +GCVML2_PERF_SEL_EVENT_66 = 66 +GCVML2_PERF_SEL_EVENT_67 = 67 +GCVML2_PERF_SEL_EVENT_68 = 68 +GCVML2_PERF_SEL_EVENT_69 = 69 +GCVML2_PERF_SEL_EVENT_70 = 70 +GCVML2_PERF_SEL_EVENT_71 = 71 +GCVML2_PERF_SEL_EVENT_72 = 72 +GCVML2_PERF_SEL_EVENT_73 = 73 +GCVML2_PERF_SEL_EVENT_74 = 74 +GCVML2_PERF_SEL_EVENT_75 = 75 +GCVML2_PERF_SEL_EVENT_76 = 76 +GCVML2_PERF_SEL_EVENT_77 = 77 +GCVML2_PERF_SEL_EVENT_78 = 78 +GCVML2_PERF_SEL_EVENT_79 = 79 +GCVML2_PERF_SEL_EVENT_80 = 80 +GCVML2_PERF_SEL_EVENT_81 = 81 +GCVML2_PERF_SEL_EVENT_82 = 82 +GCVML2_PERF_SEL_EVENT_83 = 83 +GCVML2_PERF_SEL_EVENT_84 = 84 +GCVML2_PERF_SEL_EVENT_85 = 85 +GCVML2_PERF_SEL_EVENT_86 = 86 +GCVML2_PERF_SEL_EVENT_87 = 87 +GCVML2_PERF_SEL_EVENT_88 = 88 +GCVML2_PERF_SEL_EVENT_89 = 89 +GCVML2_PERF_SEL_EVENT_90 = 90 +GCVML2_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOp' +BlendOp__enumvalues = { + 0: 'BLEND_ZERO', + 1: 'BLEND_ONE', + 2: 'BLEND_SRC_COLOR', + 3: 'BLEND_ONE_MINUS_SRC_COLOR', + 4: 'BLEND_SRC_ALPHA', + 5: 'BLEND_ONE_MINUS_SRC_ALPHA', + 6: 'BLEND_DST_ALPHA', + 7: 'BLEND_ONE_MINUS_DST_ALPHA', + 8: 'BLEND_DST_COLOR', + 9: 'BLEND_ONE_MINUS_DST_COLOR', + 10: 'BLEND_SRC_ALPHA_SATURATE', + 11: 'BLEND_CONSTANT_COLOR', + 12: 'BLEND_ONE_MINUS_CONSTANT_COLOR', + 13: 'BLEND_SRC1_COLOR', + 14: 'BLEND_INV_SRC1_COLOR', + 15: 'BLEND_SRC1_ALPHA', + 16: 'BLEND_INV_SRC1_ALPHA', + 17: 'BLEND_CONSTANT_ALPHA', + 18: 'BLEND_ONE_MINUS_CONSTANT_ALPHA', +} +BLEND_ZERO = 0 +BLEND_ONE = 1 +BLEND_SRC_COLOR = 2 +BLEND_ONE_MINUS_SRC_COLOR = 3 +BLEND_SRC_ALPHA = 4 +BLEND_ONE_MINUS_SRC_ALPHA = 5 +BLEND_DST_ALPHA = 6 +BLEND_ONE_MINUS_DST_ALPHA = 7 +BLEND_DST_COLOR = 8 +BLEND_ONE_MINUS_DST_COLOR = 9 +BLEND_SRC_ALPHA_SATURATE = 10 +BLEND_CONSTANT_COLOR = 11 +BLEND_ONE_MINUS_CONSTANT_COLOR = 12 +BLEND_SRC1_COLOR = 13 +BLEND_INV_SRC1_COLOR = 14 +BLEND_SRC1_ALPHA = 15 +BLEND_INV_SRC1_ALPHA = 16 +BLEND_CONSTANT_ALPHA = 17 +BLEND_ONE_MINUS_CONSTANT_ALPHA = 18 +BlendOp = ctypes.c_uint32 # enum +GL__ZERO = BLEND_ZERO # macro +GL__ONE = BLEND_ONE # macro +GL__SRC_COLOR = BLEND_SRC_COLOR # macro +GL__ONE_MINUS_SRC_COLOR = BLEND_ONE_MINUS_SRC_COLOR # macro +GL__DST_COLOR = BLEND_DST_COLOR # macro +GL__ONE_MINUS_DST_COLOR = BLEND_ONE_MINUS_DST_COLOR # macro +GL__SRC_ALPHA = BLEND_SRC_ALPHA # macro +GL__ONE_MINUS_SRC_ALPHA = BLEND_ONE_MINUS_SRC_ALPHA # macro +GL__DST_ALPHA = BLEND_DST_ALPHA # macro +GL__ONE_MINUS_DST_ALPHA = BLEND_ONE_MINUS_DST_ALPHA # macro +GL__SRC_ALPHA_SATURATE = BLEND_SRC_ALPHA_SATURATE # macro +GL__CONSTANT_COLOR = BLEND_CONSTANT_COLOR # macro +GL__ONE_MINUS_CONSTANT_COLOR = BLEND_ONE_MINUS_CONSTANT_COLOR # macro +GL__CONSTANT_ALPHA = BLEND_CONSTANT_ALPHA # macro +GL__ONE_MINUS_CONSTANT_ALPHA = BLEND_ONE_MINUS_CONSTANT_ALPHA # macro + +# values for enumeration 'BlendOpt' +BlendOpt__enumvalues = { + 0: 'FORCE_OPT_AUTO', + 1: 'FORCE_OPT_DISABLE', + 2: 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 3: 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 4: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 5: 'FORCE_OPT_ENABLE_IF_SRC_A_1', + 6: 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', + 7: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', +} +FORCE_OPT_AUTO = 0 +FORCE_OPT_DISABLE = 1 +FORCE_OPT_ENABLE_IF_SRC_A_0 = 2 +FORCE_OPT_ENABLE_IF_SRC_RGB_0 = 3 +FORCE_OPT_ENABLE_IF_SRC_ARGB_0 = 4 +FORCE_OPT_ENABLE_IF_SRC_A_1 = 5 +FORCE_OPT_ENABLE_IF_SRC_RGB_1 = 6 +FORCE_OPT_ENABLE_IF_SRC_ARGB_1 = 7 +BlendOpt = ctypes.c_uint32 # enum + +# values for enumeration 'CBMode' +CBMode__enumvalues = { + 0: 'CB_DISABLE', + 1: 'CB_NORMAL', + 2: 'CB_ELIMINATE_FAST_CLEAR', + 3: 'CB_DCC_DECOMPRESS', + 4: 'CB_RESERVED', +} +CB_DISABLE = 0 +CB_NORMAL = 1 +CB_ELIMINATE_FAST_CLEAR = 2 +CB_DCC_DECOMPRESS = 3 +CB_RESERVED = 4 +CBMode = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfClearFilterSel' +CBPerfClearFilterSel__enumvalues = { + 0: 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 1: 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', +} +CB_PERF_CLEAR_FILTER_SEL_NONCLEAR = 0 +CB_PERF_CLEAR_FILTER_SEL_CLEAR = 1 +CBPerfClearFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfOpFilterSel' +CBPerfOpFilterSel__enumvalues = { + 0: 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 1: 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 2: 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 3: 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 4: 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 5: 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', +} +CB_PERF_OP_FILTER_SEL_WRITE_ONLY = 0 +CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION = 1 +CB_PERF_OP_FILTER_SEL_RESOLVE = 2 +CB_PERF_OP_FILTER_SEL_DECOMPRESS = 3 +CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS = 4 +CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR = 5 +CBPerfOpFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfSel' +CBPerfSel__enumvalues = { + 1: 'CB_PERF_SEL_BUSY', + 2: 'CB_PERF_SEL_DRAWN_BUSY', + 3: 'CB_PERF_SEL_DRAWN_PIXEL', + 4: 'CB_PERF_SEL_DRAWN_QUAD', + 5: 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', + 15: 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READY', + 16: 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB', + 17: 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY', + 18: 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB', + 21: 'CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST', + 22: 'CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST_IN_FLIGHT', + 23: 'CB_PERF_SEL_CC_CRW_GLX_REQ_WRITE_REQUEST', + 24: 'CB_PERF_SEL_CC_CRW_GLX_SRC_WRITE_CYCLES', + 25: 'CB_PERF_SEL_CC_FDCC_COMPRESS_FRAG_TIDS_IN', + 26: 'CB_PERF_SEL_CC_FDCC_DECOMPRESS_FRAG_TIDS_OUT', + 50: 'CB_PERF_SEL_EVENT', + 51: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 52: 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 53: 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 54: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 55: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 56: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 57: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 58: 'CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS', + 60: 'CB_PERF_SEL_STATIC_CLOCK_EN', + 61: 'CB_PERF_SEL_PERFMON_CLOCK_EN', + 62: 'CB_PERF_SEL_BLEND_CLOCK_EN', + 63: 'CB_PERF_SEL_COLOR_STORE_CLOCK_EN', + 64: 'CB_PERF_SEL_BACKEND_READ_CLOCK_EN', + 65: 'CB_PERF_SEL_GRBM_CLOCK_EN', + 66: 'CB_PERF_SEL_MEMARB_CLOCK_EN', + 67: 'CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN', + 68: 'CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN', + 69: 'CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN', + 70: 'CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN', + 71: 'CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN', + 72: 'CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN', + 73: 'CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN', + 74: 'CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN', + 75: 'CB_PERF_SEL_EVENTS_CLK_EN', + 80: 'CB_PERF_SEL_CC_TAG_HIT', + 81: 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 82: 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', + 83: 'CB_PERF_SEL_CC_CACHE_SECTOR_HIT', + 88: 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 89: 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 90: 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 91: 'CB_PERF_SEL_CC_CACHE_STALL', + 92: 'CB_PERF_SEL_CC_CACHE_FLUSH', + 93: 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 94: 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 95: 'CB_PERF_SEL_CC_CACHE_QBLOCKS_FLUSHED', + 96: 'CB_PERF_SEL_CC_CACHE_DIRTY_QBLOCKS_FLUSHED', + 97: 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 98: 'CB_PERF_SEL_CCC_IN_EVICT_HAZARD_STALL', + 99: 'CB_PERF_SEL_CCC_COLOR_RESOURCE_PANIC', + 100: 'CB_PERF_SEL_CCC_FMASK_RESOURCE_PANIC', + 101: 'CB_PERF_SEL_CCC_FREE_WAYS_PANIC', + 102: 'CB_PERF_SEL_CCC_SKID_FIFO_FULL', + 103: 'CB_PERF_SEL_CCC_SKID_FIFO_STALL', + 104: 'CB_PERF_SEL_CCC_COLOR_RESOURCE_STALL', + 105: 'CB_PERF_SEL_CCC_FMASK_RESOURCE_STALL', + 106: 'CB_PERF_SEL_CCC_FREE_WAYS_STALL', + 110: 'CB_PERF_SEL_BE_SRCFIFO_FULL', + 111: 'CB_PERF_SEL_BE_RDLATFIFO_FULL', + 112: 'CB_PERF_SEL_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 113: 'CB_PERF_SEL_CC_QUADFRAG_VALID_READY', + 114: 'CB_PERF_SEL_CC_QUADFRAG_VALID_READYB', + 115: 'CB_PERF_SEL_CC_QUADFRAG_VALIDB_READY', + 116: 'CB_PERF_SEL_CC_QUADFRAG_VALIDB_READYB', + 118: 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READY', + 119: 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READYB', + 120: 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READY', + 121: 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READYB', + 150: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 151: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 152: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 180: 'CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 181: 'CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 182: 'CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED', + 183: 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 184: 'CB_PERF_SEL_BLEND_STALL_AT_OUTPUT', + 185: 'CB_PERF_SEL_BLEND_STALL_ON_CACHE_ACCESS', + 186: 'CB_PERF_SEL_BLEND_COLLISION_DUE_TO_CACHE_WRITE', + 187: 'CB_PERF_SEL_BLEND_RAW_HAZARD_STALL', + 190: 'CB_PERF_SEL_BE_CS_FILLRATE_1X2', + 191: 'CB_PERF_SEL_BE_CS_FILLRATE_2X1', + 192: 'CB_PERF_SEL_BE_CS_FILLRATE_2X2', + 250: 'CB_PERF_SEL_FORMAT_IS_32_R', + 251: 'CB_PERF_SEL_FORMAT_IS_32_AR', + 252: 'CB_PERF_SEL_FORMAT_IS_32_GR', + 253: 'CB_PERF_SEL_FORMAT_IS_32_ABGR', + 254: 'CB_PERF_SEL_FORMAT_IS_FP16_ABGR', + 255: 'CB_PERF_SEL_FORMAT_IS_SIGNED16_ABGR', + 256: 'CB_PERF_SEL_FORMAT_IS_UNSIGNED16_ABGR', + 257: 'CB_PERF_SEL_FORMAT_IS_32BPP_8PIX', + 258: 'CB_PERF_SEL_FORMAT_IS_16_16_UNSIGNED_8PIX', + 259: 'CB_PERF_SEL_FORMAT_IS_16_16_SIGNED_8PIX', + 260: 'CB_PERF_SEL_FORMAT_IS_16_16_FLOAT_8PIX', + 261: 'CB_PERF_SEL_EXPORT_ADDED_1_FRAGMENT', + 262: 'CB_PERF_SEL_EXPORT_ADDED_2_FRAGMENTS', + 263: 'CB_PERF_SEL_EXPORT_ADDED_3_FRAGMENTS', + 264: 'CB_PERF_SEL_EXPORT_ADDED_4_FRAGMENTS', + 265: 'CB_PERF_SEL_EXPORT_ADDED_5_FRAGMENTS', + 266: 'CB_PERF_SEL_EXPORT_ADDED_6_FRAGMENTS', + 267: 'CB_PERF_SEL_EXPORT_ADDED_7_FRAGMENTS', + 268: 'CB_PERF_SEL_EXPORT_BLEND_OPT_DONT_READ_DST', + 269: 'CB_PERF_SEL_EXPORT_BLEND_OPT_BLEND_BYPASS', + 270: 'CB_PERF_SEL_EXPORT_BLEND_OPT_DISCARD_PIXELS', + 271: 'CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_BEFORE_UPDATE', + 272: 'CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_AFTER_UPDATE', + 273: 'CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 274: 'CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_AFTER_UPDATE', + 275: 'CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 276: 'CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_AFTER_UPDATE', + 277: 'CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 278: 'CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_AFTER_UPDATE', + 279: 'CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 280: 'CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_AFTER_UPDATE', + 281: 'CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 282: 'CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_AFTER_UPDATE', + 283: 'CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 284: 'CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_AFTER_UPDATE', + 285: 'CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 286: 'CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_AFTER_UPDATE', + 287: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_0', + 288: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_1', + 289: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_2', + 290: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_3', + 291: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_4', + 292: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_5', + 293: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_6', + 294: 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_7', + 295: 'CB_PERF_SEL_EXPORT_REMOVED_1_FRAGMENT', + 296: 'CB_PERF_SEL_EXPORT_REMOVED_2_FRAGMENTS', + 297: 'CB_PERF_SEL_EXPORT_REMOVED_3_FRAGMENTS', + 298: 'CB_PERF_SEL_EXPORT_REMOVED_4_FRAGMENTS', + 299: 'CB_PERF_SEL_EXPORT_REMOVED_5_FRAGMENTS', + 300: 'CB_PERF_SEL_EXPORT_REMOVED_6_FRAGMENTS', + 301: 'CB_PERF_SEL_EXPORT_REMOVED_7_FRAGMENTS', + 302: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_0', + 303: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_1', + 304: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_2', + 305: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_3', + 306: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_4', + 307: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_5', + 308: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_6', + 309: 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_7', + 310: 'CB_PERF_SEL_EXPORT_KILLED_BY_COLOR_INVALID', + 311: 'CB_PERF_SEL_EXPORT_KILLED_BY_DISCARD_PIXEL', + 312: 'CB_PERF_SEL_EXPORT_KILLED_BY_NULL_SAMPLE_MASK', + 313: 'CB_PERF_SEL_EXPORT_KILLED_BY_NULL_TARGET_SHADER_MASK', +} +CB_PERF_SEL_BUSY = 1 +CB_PERF_SEL_DRAWN_BUSY = 2 +CB_PERF_SEL_DRAWN_PIXEL = 3 +CB_PERF_SEL_DRAWN_QUAD = 4 +CB_PERF_SEL_DRAWN_QUAD_FRAGMENT = 5 +CB_PERF_SEL_DB_CB_EXPORT_VALID_READY = 15 +CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB = 16 +CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY = 17 +CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB = 18 +CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST = 21 +CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST_IN_FLIGHT = 22 +CB_PERF_SEL_CC_CRW_GLX_REQ_WRITE_REQUEST = 23 +CB_PERF_SEL_CC_CRW_GLX_SRC_WRITE_CYCLES = 24 +CB_PERF_SEL_CC_FDCC_COMPRESS_FRAG_TIDS_IN = 25 +CB_PERF_SEL_CC_FDCC_DECOMPRESS_FRAG_TIDS_OUT = 26 +CB_PERF_SEL_EVENT = 50 +CB_PERF_SEL_EVENT_CACHE_FLUSH_TS = 51 +CB_PERF_SEL_EVENT_CONTEXT_DONE = 52 +CB_PERF_SEL_EVENT_CACHE_FLUSH = 53 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT = 54 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT = 55 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS = 56 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META = 57 +CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS = 58 +CB_PERF_SEL_STATIC_CLOCK_EN = 60 +CB_PERF_SEL_PERFMON_CLOCK_EN = 61 +CB_PERF_SEL_BLEND_CLOCK_EN = 62 +CB_PERF_SEL_COLOR_STORE_CLOCK_EN = 63 +CB_PERF_SEL_BACKEND_READ_CLOCK_EN = 64 +CB_PERF_SEL_GRBM_CLOCK_EN = 65 +CB_PERF_SEL_MEMARB_CLOCK_EN = 66 +CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN = 67 +CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN = 68 +CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN = 69 +CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN = 70 +CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN = 71 +CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN = 72 +CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN = 73 +CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN = 74 +CB_PERF_SEL_EVENTS_CLK_EN = 75 +CB_PERF_SEL_CC_TAG_HIT = 80 +CB_PERF_SEL_CC_CACHE_TAG_MISS = 81 +CB_PERF_SEL_CC_CACHE_SECTOR_MISS = 82 +CB_PERF_SEL_CC_CACHE_SECTOR_HIT = 83 +CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL = 88 +CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL = 89 +CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL = 90 +CB_PERF_SEL_CC_CACHE_STALL = 91 +CB_PERF_SEL_CC_CACHE_FLUSH = 92 +CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED = 93 +CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION = 94 +CB_PERF_SEL_CC_CACHE_QBLOCKS_FLUSHED = 95 +CB_PERF_SEL_CC_CACHE_DIRTY_QBLOCKS_FLUSHED = 96 +CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC = 97 +CB_PERF_SEL_CCC_IN_EVICT_HAZARD_STALL = 98 +CB_PERF_SEL_CCC_COLOR_RESOURCE_PANIC = 99 +CB_PERF_SEL_CCC_FMASK_RESOURCE_PANIC = 100 +CB_PERF_SEL_CCC_FREE_WAYS_PANIC = 101 +CB_PERF_SEL_CCC_SKID_FIFO_FULL = 102 +CB_PERF_SEL_CCC_SKID_FIFO_STALL = 103 +CB_PERF_SEL_CCC_COLOR_RESOURCE_STALL = 104 +CB_PERF_SEL_CCC_FMASK_RESOURCE_STALL = 105 +CB_PERF_SEL_CCC_FREE_WAYS_STALL = 106 +CB_PERF_SEL_BE_SRCFIFO_FULL = 110 +CB_PERF_SEL_BE_RDLATFIFO_FULL = 111 +CB_PERF_SEL_RDLAT_FIFO_QUAD_RESIDENCY_STALL = 112 +CB_PERF_SEL_CC_QUADFRAG_VALID_READY = 113 +CB_PERF_SEL_CC_QUADFRAG_VALID_READYB = 114 +CB_PERF_SEL_CC_QUADFRAG_VALIDB_READY = 115 +CB_PERF_SEL_CC_QUADFRAG_VALIDB_READYB = 116 +CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READY = 118 +CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READYB = 119 +CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READY = 120 +CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READYB = 121 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH = 150 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT = 151 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT = 152 +CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED = 180 +CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED = 181 +CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED = 182 +CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST = 183 +CB_PERF_SEL_BLEND_STALL_AT_OUTPUT = 184 +CB_PERF_SEL_BLEND_STALL_ON_CACHE_ACCESS = 185 +CB_PERF_SEL_BLEND_COLLISION_DUE_TO_CACHE_WRITE = 186 +CB_PERF_SEL_BLEND_RAW_HAZARD_STALL = 187 +CB_PERF_SEL_BE_CS_FILLRATE_1X2 = 190 +CB_PERF_SEL_BE_CS_FILLRATE_2X1 = 191 +CB_PERF_SEL_BE_CS_FILLRATE_2X2 = 192 +CB_PERF_SEL_FORMAT_IS_32_R = 250 +CB_PERF_SEL_FORMAT_IS_32_AR = 251 +CB_PERF_SEL_FORMAT_IS_32_GR = 252 +CB_PERF_SEL_FORMAT_IS_32_ABGR = 253 +CB_PERF_SEL_FORMAT_IS_FP16_ABGR = 254 +CB_PERF_SEL_FORMAT_IS_SIGNED16_ABGR = 255 +CB_PERF_SEL_FORMAT_IS_UNSIGNED16_ABGR = 256 +CB_PERF_SEL_FORMAT_IS_32BPP_8PIX = 257 +CB_PERF_SEL_FORMAT_IS_16_16_UNSIGNED_8PIX = 258 +CB_PERF_SEL_FORMAT_IS_16_16_SIGNED_8PIX = 259 +CB_PERF_SEL_FORMAT_IS_16_16_FLOAT_8PIX = 260 +CB_PERF_SEL_EXPORT_ADDED_1_FRAGMENT = 261 +CB_PERF_SEL_EXPORT_ADDED_2_FRAGMENTS = 262 +CB_PERF_SEL_EXPORT_ADDED_3_FRAGMENTS = 263 +CB_PERF_SEL_EXPORT_ADDED_4_FRAGMENTS = 264 +CB_PERF_SEL_EXPORT_ADDED_5_FRAGMENTS = 265 +CB_PERF_SEL_EXPORT_ADDED_6_FRAGMENTS = 266 +CB_PERF_SEL_EXPORT_ADDED_7_FRAGMENTS = 267 +CB_PERF_SEL_EXPORT_BLEND_OPT_DONT_READ_DST = 268 +CB_PERF_SEL_EXPORT_BLEND_OPT_BLEND_BYPASS = 269 +CB_PERF_SEL_EXPORT_BLEND_OPT_DISCARD_PIXELS = 270 +CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_BEFORE_UPDATE = 271 +CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_AFTER_UPDATE = 272 +CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_BEFORE_UPDATE = 273 +CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_AFTER_UPDATE = 274 +CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_BEFORE_UPDATE = 275 +CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_AFTER_UPDATE = 276 +CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_BEFORE_UPDATE = 277 +CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_AFTER_UPDATE = 278 +CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_BEFORE_UPDATE = 279 +CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_AFTER_UPDATE = 280 +CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_BEFORE_UPDATE = 281 +CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_AFTER_UPDATE = 282 +CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_BEFORE_UPDATE = 283 +CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_AFTER_UPDATE = 284 +CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_BEFORE_UPDATE = 285 +CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_AFTER_UPDATE = 286 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_0 = 287 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_1 = 288 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_2 = 289 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_3 = 290 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_4 = 291 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_5 = 292 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_6 = 293 +CB_PERF_SEL_EXPORT_READS_FRAGMENT_7 = 294 +CB_PERF_SEL_EXPORT_REMOVED_1_FRAGMENT = 295 +CB_PERF_SEL_EXPORT_REMOVED_2_FRAGMENTS = 296 +CB_PERF_SEL_EXPORT_REMOVED_3_FRAGMENTS = 297 +CB_PERF_SEL_EXPORT_REMOVED_4_FRAGMENTS = 298 +CB_PERF_SEL_EXPORT_REMOVED_5_FRAGMENTS = 299 +CB_PERF_SEL_EXPORT_REMOVED_6_FRAGMENTS = 300 +CB_PERF_SEL_EXPORT_REMOVED_7_FRAGMENTS = 301 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_0 = 302 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_1 = 303 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_2 = 304 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_3 = 305 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_4 = 306 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_5 = 307 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_6 = 308 +CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_7 = 309 +CB_PERF_SEL_EXPORT_KILLED_BY_COLOR_INVALID = 310 +CB_PERF_SEL_EXPORT_KILLED_BY_DISCARD_PIXEL = 311 +CB_PERF_SEL_EXPORT_KILLED_BY_NULL_SAMPLE_MASK = 312 +CB_PERF_SEL_EXPORT_KILLED_BY_NULL_TARGET_SHADER_MASK = 313 +CBPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'CombFunc' +CombFunc__enumvalues = { + 0: 'COMB_DST_PLUS_SRC', + 1: 'COMB_SRC_MINUS_DST', + 2: 'COMB_MIN_DST_SRC', + 3: 'COMB_MAX_DST_SRC', + 4: 'COMB_DST_MINUS_SRC', +} +COMB_DST_PLUS_SRC = 0 +COMB_SRC_MINUS_DST = 1 +COMB_MIN_DST_SRC = 2 +COMB_MAX_DST_SRC = 3 +COMB_DST_MINUS_SRC = 4 +CombFunc = ctypes.c_uint32 # enum + +# values for enumeration 'MemArbMode' +MemArbMode__enumvalues = { + 0: 'MEM_ARB_MODE_FIXED', + 1: 'MEM_ARB_MODE_AGE', + 2: 'MEM_ARB_MODE_WEIGHT', + 3: 'MEM_ARB_MODE_BOTH', +} +MEM_ARB_MODE_FIXED = 0 +MEM_ARB_MODE_AGE = 1 +MEM_ARB_MODE_WEIGHT = 2 +MEM_ARB_MODE_BOTH = 3 +MemArbMode = ctypes.c_uint32 # enum + +# values for enumeration 'PH_PERFCNT_SEL' +PH_PERFCNT_SEL__enumvalues = { + 0: 'PH_PERF_SEL_SC0_SRPS_WINDOW_VALID', + 1: 'PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 2: 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES', + 3: 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 4: 'PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW', + 5: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE', + 6: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 7: 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 8: 'PH_PERF_SEL_SC0_ARB_BUSY', + 9: 'PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP', + 10: 'PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP', + 11: 'PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP', + 12: 'PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE', + 13: 'PH_PERF_SEL_SC0_EOP_SYNC_WINDOW', + 14: 'PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', + 15: 'PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO', + 16: 'PH_PERF_SEL_SC0_SEND', + 17: 'PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 18: 'PH_PERF_SEL_SC0_CREDIT_AT_MAX', + 19: 'PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 20: 'PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION', + 21: 'PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION', + 22: 'PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 23: 'PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 24: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD', + 25: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE', + 26: 'PH_PERF_SEL_SC0_PA0_FIFO_EMPTY', + 27: 'PH_PERF_SEL_SC0_PA0_FIFO_FULL', + 28: 'PH_PERF_SEL_SC0_PA0_NULL_WE', + 29: 'PH_PERF_SEL_SC0_PA0_EVENT_WE', + 30: 'PH_PERF_SEL_SC0_PA0_FPOV_WE', + 31: 'PH_PERF_SEL_SC0_PA0_FPOP_WE', + 32: 'PH_PERF_SEL_SC0_PA0_EOP_WE', + 33: 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD', + 34: 'PH_PERF_SEL_SC0_PA0_EOPG_WE', + 35: 'PH_PERF_SEL_SC0_PA0_DEALLOC_WE', + 36: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD', + 37: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE', + 38: 'PH_PERF_SEL_SC0_PA1_FIFO_EMPTY', + 39: 'PH_PERF_SEL_SC0_PA1_FIFO_FULL', + 40: 'PH_PERF_SEL_SC0_PA1_NULL_WE', + 41: 'PH_PERF_SEL_SC0_PA1_EVENT_WE', + 42: 'PH_PERF_SEL_SC0_PA1_FPOV_WE', + 43: 'PH_PERF_SEL_SC0_PA1_FPOP_WE', + 44: 'PH_PERF_SEL_SC0_PA1_EOP_WE', + 45: 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD', + 46: 'PH_PERF_SEL_SC0_PA1_EOPG_WE', + 47: 'PH_PERF_SEL_SC0_PA1_DEALLOC_WE', + 48: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD', + 49: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE', + 50: 'PH_PERF_SEL_SC0_PA2_FIFO_EMPTY', + 51: 'PH_PERF_SEL_SC0_PA2_FIFO_FULL', + 52: 'PH_PERF_SEL_SC0_PA2_NULL_WE', + 53: 'PH_PERF_SEL_SC0_PA2_EVENT_WE', + 54: 'PH_PERF_SEL_SC0_PA2_FPOV_WE', + 55: 'PH_PERF_SEL_SC0_PA2_FPOP_WE', + 56: 'PH_PERF_SEL_SC0_PA2_EOP_WE', + 57: 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD', + 58: 'PH_PERF_SEL_SC0_PA2_EOPG_WE', + 59: 'PH_PERF_SEL_SC0_PA2_DEALLOC_WE', + 60: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD', + 61: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE', + 62: 'PH_PERF_SEL_SC0_PA3_FIFO_EMPTY', + 63: 'PH_PERF_SEL_SC0_PA3_FIFO_FULL', + 64: 'PH_PERF_SEL_SC0_PA3_NULL_WE', + 65: 'PH_PERF_SEL_SC0_PA3_EVENT_WE', + 66: 'PH_PERF_SEL_SC0_PA3_FPOV_WE', + 67: 'PH_PERF_SEL_SC0_PA3_FPOP_WE', + 68: 'PH_PERF_SEL_SC0_PA3_EOP_WE', + 69: 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD', + 70: 'PH_PERF_SEL_SC0_PA3_EOPG_WE', + 71: 'PH_PERF_SEL_SC0_PA3_DEALLOC_WE', + 72: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD', + 73: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE', + 74: 'PH_PERF_SEL_SC0_PA4_FIFO_EMPTY', + 75: 'PH_PERF_SEL_SC0_PA4_FIFO_FULL', + 76: 'PH_PERF_SEL_SC0_PA4_NULL_WE', + 77: 'PH_PERF_SEL_SC0_PA4_EVENT_WE', + 78: 'PH_PERF_SEL_SC0_PA4_FPOV_WE', + 79: 'PH_PERF_SEL_SC0_PA4_FPOP_WE', + 80: 'PH_PERF_SEL_SC0_PA4_EOP_WE', + 81: 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD', + 82: 'PH_PERF_SEL_SC0_PA4_EOPG_WE', + 83: 'PH_PERF_SEL_SC0_PA4_DEALLOC_WE', + 84: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD', + 85: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE', + 86: 'PH_PERF_SEL_SC0_PA5_FIFO_EMPTY', + 87: 'PH_PERF_SEL_SC0_PA5_FIFO_FULL', + 88: 'PH_PERF_SEL_SC0_PA5_NULL_WE', + 89: 'PH_PERF_SEL_SC0_PA5_EVENT_WE', + 90: 'PH_PERF_SEL_SC0_PA5_FPOV_WE', + 91: 'PH_PERF_SEL_SC0_PA5_FPOP_WE', + 92: 'PH_PERF_SEL_SC0_PA5_EOP_WE', + 93: 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD', + 94: 'PH_PERF_SEL_SC0_PA5_EOPG_WE', + 95: 'PH_PERF_SEL_SC0_PA5_DEALLOC_WE', + 96: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD', + 97: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE', + 98: 'PH_PERF_SEL_SC0_PA6_FIFO_EMPTY', + 99: 'PH_PERF_SEL_SC0_PA6_FIFO_FULL', + 100: 'PH_PERF_SEL_SC0_PA6_NULL_WE', + 101: 'PH_PERF_SEL_SC0_PA6_EVENT_WE', + 102: 'PH_PERF_SEL_SC0_PA6_FPOV_WE', + 103: 'PH_PERF_SEL_SC0_PA6_FPOP_WE', + 104: 'PH_PERF_SEL_SC0_PA6_EOP_WE', + 105: 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD', + 106: 'PH_PERF_SEL_SC0_PA6_EOPG_WE', + 107: 'PH_PERF_SEL_SC0_PA6_DEALLOC_WE', + 108: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD', + 109: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE', + 110: 'PH_PERF_SEL_SC0_PA7_FIFO_EMPTY', + 111: 'PH_PERF_SEL_SC0_PA7_FIFO_FULL', + 112: 'PH_PERF_SEL_SC0_PA7_NULL_WE', + 113: 'PH_PERF_SEL_SC0_PA7_EVENT_WE', + 114: 'PH_PERF_SEL_SC0_PA7_FPOV_WE', + 115: 'PH_PERF_SEL_SC0_PA7_FPOP_WE', + 116: 'PH_PERF_SEL_SC0_PA7_EOP_WE', + 117: 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD', + 118: 'PH_PERF_SEL_SC0_PA7_EOPG_WE', + 119: 'PH_PERF_SEL_SC0_PA7_DEALLOC_WE', + 120: 'PH_PERF_SEL_SC1_SRPS_WINDOW_VALID', + 121: 'PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 122: 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES', + 123: 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 124: 'PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW', + 125: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE', + 126: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 127: 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 128: 'PH_PERF_SEL_SC1_ARB_BUSY', + 129: 'PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP', + 130: 'PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP', + 131: 'PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP', + 132: 'PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE', + 133: 'PH_PERF_SEL_SC1_EOP_SYNC_WINDOW', + 134: 'PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', + 135: 'PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO', + 136: 'PH_PERF_SEL_SC1_SEND', + 137: 'PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 138: 'PH_PERF_SEL_SC1_CREDIT_AT_MAX', + 139: 'PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 140: 'PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION', + 141: 'PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION', + 142: 'PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 143: 'PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 144: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD', + 145: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE', + 146: 'PH_PERF_SEL_SC1_PA0_FIFO_EMPTY', + 147: 'PH_PERF_SEL_SC1_PA0_FIFO_FULL', + 148: 'PH_PERF_SEL_SC1_PA0_NULL_WE', + 149: 'PH_PERF_SEL_SC1_PA0_EVENT_WE', + 150: 'PH_PERF_SEL_SC1_PA0_FPOV_WE', + 151: 'PH_PERF_SEL_SC1_PA0_FPOP_WE', + 152: 'PH_PERF_SEL_SC1_PA0_EOP_WE', + 153: 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD', + 154: 'PH_PERF_SEL_SC1_PA0_EOPG_WE', + 155: 'PH_PERF_SEL_SC1_PA0_DEALLOC_WE', + 156: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD', + 157: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE', + 158: 'PH_PERF_SEL_SC1_PA1_FIFO_EMPTY', + 159: 'PH_PERF_SEL_SC1_PA1_FIFO_FULL', + 160: 'PH_PERF_SEL_SC1_PA1_NULL_WE', + 161: 'PH_PERF_SEL_SC1_PA1_EVENT_WE', + 162: 'PH_PERF_SEL_SC1_PA1_FPOV_WE', + 163: 'PH_PERF_SEL_SC1_PA1_FPOP_WE', + 164: 'PH_PERF_SEL_SC1_PA1_EOP_WE', + 165: 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD', + 166: 'PH_PERF_SEL_SC1_PA1_EOPG_WE', + 167: 'PH_PERF_SEL_SC1_PA1_DEALLOC_WE', + 168: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD', + 169: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE', + 170: 'PH_PERF_SEL_SC1_PA2_FIFO_EMPTY', + 171: 'PH_PERF_SEL_SC1_PA2_FIFO_FULL', + 172: 'PH_PERF_SEL_SC1_PA2_NULL_WE', + 173: 'PH_PERF_SEL_SC1_PA2_EVENT_WE', + 174: 'PH_PERF_SEL_SC1_PA2_FPOV_WE', + 175: 'PH_PERF_SEL_SC1_PA2_FPOP_WE', + 176: 'PH_PERF_SEL_SC1_PA2_EOP_WE', + 177: 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD', + 178: 'PH_PERF_SEL_SC1_PA2_EOPG_WE', + 179: 'PH_PERF_SEL_SC1_PA2_DEALLOC_WE', + 180: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD', + 181: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE', + 182: 'PH_PERF_SEL_SC1_PA3_FIFO_EMPTY', + 183: 'PH_PERF_SEL_SC1_PA3_FIFO_FULL', + 184: 'PH_PERF_SEL_SC1_PA3_NULL_WE', + 185: 'PH_PERF_SEL_SC1_PA3_EVENT_WE', + 186: 'PH_PERF_SEL_SC1_PA3_FPOV_WE', + 187: 'PH_PERF_SEL_SC1_PA3_FPOP_WE', + 188: 'PH_PERF_SEL_SC1_PA3_EOP_WE', + 189: 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD', + 190: 'PH_PERF_SEL_SC1_PA3_EOPG_WE', + 191: 'PH_PERF_SEL_SC1_PA3_DEALLOC_WE', + 192: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD', + 193: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE', + 194: 'PH_PERF_SEL_SC1_PA4_FIFO_EMPTY', + 195: 'PH_PERF_SEL_SC1_PA4_FIFO_FULL', + 196: 'PH_PERF_SEL_SC1_PA4_NULL_WE', + 197: 'PH_PERF_SEL_SC1_PA4_EVENT_WE', + 198: 'PH_PERF_SEL_SC1_PA4_FPOV_WE', + 199: 'PH_PERF_SEL_SC1_PA4_FPOP_WE', + 200: 'PH_PERF_SEL_SC1_PA4_EOP_WE', + 201: 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD', + 202: 'PH_PERF_SEL_SC1_PA4_EOPG_WE', + 203: 'PH_PERF_SEL_SC1_PA4_DEALLOC_WE', + 204: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD', + 205: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE', + 206: 'PH_PERF_SEL_SC1_PA5_FIFO_EMPTY', + 207: 'PH_PERF_SEL_SC1_PA5_FIFO_FULL', + 208: 'PH_PERF_SEL_SC1_PA5_NULL_WE', + 209: 'PH_PERF_SEL_SC1_PA5_EVENT_WE', + 210: 'PH_PERF_SEL_SC1_PA5_FPOV_WE', + 211: 'PH_PERF_SEL_SC1_PA5_FPOP_WE', + 212: 'PH_PERF_SEL_SC1_PA5_EOP_WE', + 213: 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD', + 214: 'PH_PERF_SEL_SC1_PA5_EOPG_WE', + 215: 'PH_PERF_SEL_SC1_PA5_DEALLOC_WE', + 216: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD', + 217: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE', + 218: 'PH_PERF_SEL_SC1_PA6_FIFO_EMPTY', + 219: 'PH_PERF_SEL_SC1_PA6_FIFO_FULL', + 220: 'PH_PERF_SEL_SC1_PA6_NULL_WE', + 221: 'PH_PERF_SEL_SC1_PA6_EVENT_WE', + 222: 'PH_PERF_SEL_SC1_PA6_FPOV_WE', + 223: 'PH_PERF_SEL_SC1_PA6_FPOP_WE', + 224: 'PH_PERF_SEL_SC1_PA6_EOP_WE', + 225: 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD', + 226: 'PH_PERF_SEL_SC1_PA6_EOPG_WE', + 227: 'PH_PERF_SEL_SC1_PA6_DEALLOC_WE', + 228: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD', + 229: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE', + 230: 'PH_PERF_SEL_SC1_PA7_FIFO_EMPTY', + 231: 'PH_PERF_SEL_SC1_PA7_FIFO_FULL', + 232: 'PH_PERF_SEL_SC1_PA7_NULL_WE', + 233: 'PH_PERF_SEL_SC1_PA7_EVENT_WE', + 234: 'PH_PERF_SEL_SC1_PA7_FPOV_WE', + 235: 'PH_PERF_SEL_SC1_PA7_FPOP_WE', + 236: 'PH_PERF_SEL_SC1_PA7_EOP_WE', + 237: 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD', + 238: 'PH_PERF_SEL_SC1_PA7_EOPG_WE', + 239: 'PH_PERF_SEL_SC1_PA7_DEALLOC_WE', + 240: 'PH_PERF_SEL_SC2_SRPS_WINDOW_VALID', + 241: 'PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 242: 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES', + 243: 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 244: 'PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW', + 245: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE', + 246: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 247: 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 248: 'PH_PERF_SEL_SC2_ARB_BUSY', + 249: 'PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP', + 250: 'PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP', + 251: 'PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP', + 252: 'PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE', + 253: 'PH_PERF_SEL_SC2_EOP_SYNC_WINDOW', + 254: 'PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', + 255: 'PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO', + 256: 'PH_PERF_SEL_SC2_SEND', + 257: 'PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 258: 'PH_PERF_SEL_SC2_CREDIT_AT_MAX', + 259: 'PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 260: 'PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION', + 261: 'PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION', + 262: 'PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 263: 'PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 264: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD', + 265: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE', + 266: 'PH_PERF_SEL_SC2_PA0_FIFO_EMPTY', + 267: 'PH_PERF_SEL_SC2_PA0_FIFO_FULL', + 268: 'PH_PERF_SEL_SC2_PA0_NULL_WE', + 269: 'PH_PERF_SEL_SC2_PA0_EVENT_WE', + 270: 'PH_PERF_SEL_SC2_PA0_FPOV_WE', + 271: 'PH_PERF_SEL_SC2_PA0_FPOP_WE', + 272: 'PH_PERF_SEL_SC2_PA0_EOP_WE', + 273: 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD', + 274: 'PH_PERF_SEL_SC2_PA0_EOPG_WE', + 275: 'PH_PERF_SEL_SC2_PA0_DEALLOC_WE', + 276: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD', + 277: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE', + 278: 'PH_PERF_SEL_SC2_PA1_FIFO_EMPTY', + 279: 'PH_PERF_SEL_SC2_PA1_FIFO_FULL', + 280: 'PH_PERF_SEL_SC2_PA1_NULL_WE', + 281: 'PH_PERF_SEL_SC2_PA1_EVENT_WE', + 282: 'PH_PERF_SEL_SC2_PA1_FPOV_WE', + 283: 'PH_PERF_SEL_SC2_PA1_FPOP_WE', + 284: 'PH_PERF_SEL_SC2_PA1_EOP_WE', + 285: 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD', + 286: 'PH_PERF_SEL_SC2_PA1_EOPG_WE', + 287: 'PH_PERF_SEL_SC2_PA1_DEALLOC_WE', + 288: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD', + 289: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE', + 290: 'PH_PERF_SEL_SC2_PA2_FIFO_EMPTY', + 291: 'PH_PERF_SEL_SC2_PA2_FIFO_FULL', + 292: 'PH_PERF_SEL_SC2_PA2_NULL_WE', + 293: 'PH_PERF_SEL_SC2_PA2_EVENT_WE', + 294: 'PH_PERF_SEL_SC2_PA2_FPOV_WE', + 295: 'PH_PERF_SEL_SC2_PA2_FPOP_WE', + 296: 'PH_PERF_SEL_SC2_PA2_EOP_WE', + 297: 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD', + 298: 'PH_PERF_SEL_SC2_PA2_EOPG_WE', + 299: 'PH_PERF_SEL_SC2_PA2_DEALLOC_WE', + 300: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD', + 301: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE', + 302: 'PH_PERF_SEL_SC2_PA3_FIFO_EMPTY', + 303: 'PH_PERF_SEL_SC2_PA3_FIFO_FULL', + 304: 'PH_PERF_SEL_SC2_PA3_NULL_WE', + 305: 'PH_PERF_SEL_SC2_PA3_EVENT_WE', + 306: 'PH_PERF_SEL_SC2_PA3_FPOV_WE', + 307: 'PH_PERF_SEL_SC2_PA3_FPOP_WE', + 308: 'PH_PERF_SEL_SC2_PA3_EOP_WE', + 309: 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD', + 310: 'PH_PERF_SEL_SC2_PA3_EOPG_WE', + 311: 'PH_PERF_SEL_SC2_PA3_DEALLOC_WE', + 312: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD', + 313: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE', + 314: 'PH_PERF_SEL_SC2_PA4_FIFO_EMPTY', + 315: 'PH_PERF_SEL_SC2_PA4_FIFO_FULL', + 316: 'PH_PERF_SEL_SC2_PA4_NULL_WE', + 317: 'PH_PERF_SEL_SC2_PA4_EVENT_WE', + 318: 'PH_PERF_SEL_SC2_PA4_FPOV_WE', + 319: 'PH_PERF_SEL_SC2_PA4_FPOP_WE', + 320: 'PH_PERF_SEL_SC2_PA4_EOP_WE', + 321: 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD', + 322: 'PH_PERF_SEL_SC2_PA4_EOPG_WE', + 323: 'PH_PERF_SEL_SC2_PA4_DEALLOC_WE', + 324: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD', + 325: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE', + 326: 'PH_PERF_SEL_SC2_PA5_FIFO_EMPTY', + 327: 'PH_PERF_SEL_SC2_PA5_FIFO_FULL', + 328: 'PH_PERF_SEL_SC2_PA5_NULL_WE', + 329: 'PH_PERF_SEL_SC2_PA5_EVENT_WE', + 330: 'PH_PERF_SEL_SC2_PA5_FPOV_WE', + 331: 'PH_PERF_SEL_SC2_PA5_FPOP_WE', + 332: 'PH_PERF_SEL_SC2_PA5_EOP_WE', + 333: 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD', + 334: 'PH_PERF_SEL_SC2_PA5_EOPG_WE', + 335: 'PH_PERF_SEL_SC2_PA5_DEALLOC_WE', + 336: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD', + 337: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE', + 338: 'PH_PERF_SEL_SC2_PA6_FIFO_EMPTY', + 339: 'PH_PERF_SEL_SC2_PA6_FIFO_FULL', + 340: 'PH_PERF_SEL_SC2_PA6_NULL_WE', + 341: 'PH_PERF_SEL_SC2_PA6_EVENT_WE', + 342: 'PH_PERF_SEL_SC2_PA6_FPOV_WE', + 343: 'PH_PERF_SEL_SC2_PA6_FPOP_WE', + 344: 'PH_PERF_SEL_SC2_PA6_EOP_WE', + 345: 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD', + 346: 'PH_PERF_SEL_SC2_PA6_EOPG_WE', + 347: 'PH_PERF_SEL_SC2_PA6_DEALLOC_WE', + 348: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD', + 349: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE', + 350: 'PH_PERF_SEL_SC2_PA7_FIFO_EMPTY', + 351: 'PH_PERF_SEL_SC2_PA7_FIFO_FULL', + 352: 'PH_PERF_SEL_SC2_PA7_NULL_WE', + 353: 'PH_PERF_SEL_SC2_PA7_EVENT_WE', + 354: 'PH_PERF_SEL_SC2_PA7_FPOV_WE', + 355: 'PH_PERF_SEL_SC2_PA7_FPOP_WE', + 356: 'PH_PERF_SEL_SC2_PA7_EOP_WE', + 357: 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD', + 358: 'PH_PERF_SEL_SC2_PA7_EOPG_WE', + 359: 'PH_PERF_SEL_SC2_PA7_DEALLOC_WE', + 360: 'PH_PERF_SEL_SC3_SRPS_WINDOW_VALID', + 361: 'PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 362: 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES', + 363: 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 364: 'PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW', + 365: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE', + 366: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 367: 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 368: 'PH_PERF_SEL_SC3_ARB_BUSY', + 369: 'PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP', + 370: 'PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP', + 371: 'PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP', + 372: 'PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE', + 373: 'PH_PERF_SEL_SC3_EOP_SYNC_WINDOW', + 374: 'PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', + 375: 'PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO', + 376: 'PH_PERF_SEL_SC3_SEND', + 377: 'PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 378: 'PH_PERF_SEL_SC3_CREDIT_AT_MAX', + 379: 'PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 380: 'PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION', + 381: 'PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION', + 382: 'PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 383: 'PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 384: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD', + 385: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE', + 386: 'PH_PERF_SEL_SC3_PA0_FIFO_EMPTY', + 387: 'PH_PERF_SEL_SC3_PA0_FIFO_FULL', + 388: 'PH_PERF_SEL_SC3_PA0_NULL_WE', + 389: 'PH_PERF_SEL_SC3_PA0_EVENT_WE', + 390: 'PH_PERF_SEL_SC3_PA0_FPOV_WE', + 391: 'PH_PERF_SEL_SC3_PA0_FPOP_WE', + 392: 'PH_PERF_SEL_SC3_PA0_EOP_WE', + 393: 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD', + 394: 'PH_PERF_SEL_SC3_PA0_EOPG_WE', + 395: 'PH_PERF_SEL_SC3_PA0_DEALLOC_WE', + 396: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD', + 397: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE', + 398: 'PH_PERF_SEL_SC3_PA1_FIFO_EMPTY', + 399: 'PH_PERF_SEL_SC3_PA1_FIFO_FULL', + 400: 'PH_PERF_SEL_SC3_PA1_NULL_WE', + 401: 'PH_PERF_SEL_SC3_PA1_EVENT_WE', + 402: 'PH_PERF_SEL_SC3_PA1_FPOV_WE', + 403: 'PH_PERF_SEL_SC3_PA1_FPOP_WE', + 404: 'PH_PERF_SEL_SC3_PA1_EOP_WE', + 405: 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD', + 406: 'PH_PERF_SEL_SC3_PA1_EOPG_WE', + 407: 'PH_PERF_SEL_SC3_PA1_DEALLOC_WE', + 408: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD', + 409: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE', + 410: 'PH_PERF_SEL_SC3_PA2_FIFO_EMPTY', + 411: 'PH_PERF_SEL_SC3_PA2_FIFO_FULL', + 412: 'PH_PERF_SEL_SC3_PA2_NULL_WE', + 413: 'PH_PERF_SEL_SC3_PA2_EVENT_WE', + 414: 'PH_PERF_SEL_SC3_PA2_FPOV_WE', + 415: 'PH_PERF_SEL_SC3_PA2_FPOP_WE', + 416: 'PH_PERF_SEL_SC3_PA2_EOP_WE', + 417: 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD', + 418: 'PH_PERF_SEL_SC3_PA2_EOPG_WE', + 419: 'PH_PERF_SEL_SC3_PA2_DEALLOC_WE', + 420: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD', + 421: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE', + 422: 'PH_PERF_SEL_SC3_PA3_FIFO_EMPTY', + 423: 'PH_PERF_SEL_SC3_PA3_FIFO_FULL', + 424: 'PH_PERF_SEL_SC3_PA3_NULL_WE', + 425: 'PH_PERF_SEL_SC3_PA3_EVENT_WE', + 426: 'PH_PERF_SEL_SC3_PA3_FPOV_WE', + 427: 'PH_PERF_SEL_SC3_PA3_FPOP_WE', + 428: 'PH_PERF_SEL_SC3_PA3_EOP_WE', + 429: 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD', + 430: 'PH_PERF_SEL_SC3_PA3_EOPG_WE', + 431: 'PH_PERF_SEL_SC3_PA3_DEALLOC_WE', + 432: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD', + 433: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE', + 434: 'PH_PERF_SEL_SC3_PA4_FIFO_EMPTY', + 435: 'PH_PERF_SEL_SC3_PA4_FIFO_FULL', + 436: 'PH_PERF_SEL_SC3_PA4_NULL_WE', + 437: 'PH_PERF_SEL_SC3_PA4_EVENT_WE', + 438: 'PH_PERF_SEL_SC3_PA4_FPOV_WE', + 439: 'PH_PERF_SEL_SC3_PA4_FPOP_WE', + 440: 'PH_PERF_SEL_SC3_PA4_EOP_WE', + 441: 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD', + 442: 'PH_PERF_SEL_SC3_PA4_EOPG_WE', + 443: 'PH_PERF_SEL_SC3_PA4_DEALLOC_WE', + 444: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD', + 445: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE', + 446: 'PH_PERF_SEL_SC3_PA5_FIFO_EMPTY', + 447: 'PH_PERF_SEL_SC3_PA5_FIFO_FULL', + 448: 'PH_PERF_SEL_SC3_PA5_NULL_WE', + 449: 'PH_PERF_SEL_SC3_PA5_EVENT_WE', + 450: 'PH_PERF_SEL_SC3_PA5_FPOV_WE', + 451: 'PH_PERF_SEL_SC3_PA5_FPOP_WE', + 452: 'PH_PERF_SEL_SC3_PA5_EOP_WE', + 453: 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD', + 454: 'PH_PERF_SEL_SC3_PA5_EOPG_WE', + 455: 'PH_PERF_SEL_SC3_PA5_DEALLOC_WE', + 456: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD', + 457: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE', + 458: 'PH_PERF_SEL_SC3_PA6_FIFO_EMPTY', + 459: 'PH_PERF_SEL_SC3_PA6_FIFO_FULL', + 460: 'PH_PERF_SEL_SC3_PA6_NULL_WE', + 461: 'PH_PERF_SEL_SC3_PA6_EVENT_WE', + 462: 'PH_PERF_SEL_SC3_PA6_FPOV_WE', + 463: 'PH_PERF_SEL_SC3_PA6_FPOP_WE', + 464: 'PH_PERF_SEL_SC3_PA6_EOP_WE', + 465: 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD', + 466: 'PH_PERF_SEL_SC3_PA6_EOPG_WE', + 467: 'PH_PERF_SEL_SC3_PA6_DEALLOC_WE', + 468: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD', + 469: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE', + 470: 'PH_PERF_SEL_SC3_PA7_FIFO_EMPTY', + 471: 'PH_PERF_SEL_SC3_PA7_FIFO_FULL', + 472: 'PH_PERF_SEL_SC3_PA7_NULL_WE', + 473: 'PH_PERF_SEL_SC3_PA7_EVENT_WE', + 474: 'PH_PERF_SEL_SC3_PA7_FPOV_WE', + 475: 'PH_PERF_SEL_SC3_PA7_FPOP_WE', + 476: 'PH_PERF_SEL_SC3_PA7_EOP_WE', + 477: 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD', + 478: 'PH_PERF_SEL_SC3_PA7_EOPG_WE', + 479: 'PH_PERF_SEL_SC3_PA7_DEALLOC_WE', + 480: 'PH_PERF_SEL_SC4_SRPS_WINDOW_VALID', + 481: 'PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 482: 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES', + 483: 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 484: 'PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW', + 485: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE', + 486: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 487: 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 488: 'PH_PERF_SEL_SC4_ARB_BUSY', + 489: 'PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP', + 490: 'PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP', + 491: 'PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP', + 492: 'PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE', + 493: 'PH_PERF_SEL_SC4_EOP_SYNC_WINDOW', + 494: 'PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', + 495: 'PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO', + 496: 'PH_PERF_SEL_SC4_SEND', + 497: 'PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 498: 'PH_PERF_SEL_SC4_CREDIT_AT_MAX', + 499: 'PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 500: 'PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION', + 501: 'PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION', + 502: 'PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 503: 'PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 504: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD', + 505: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE', + 506: 'PH_PERF_SEL_SC4_PA0_FIFO_EMPTY', + 507: 'PH_PERF_SEL_SC4_PA0_FIFO_FULL', + 508: 'PH_PERF_SEL_SC4_PA0_NULL_WE', + 509: 'PH_PERF_SEL_SC4_PA0_EVENT_WE', + 510: 'PH_PERF_SEL_SC4_PA0_FPOV_WE', + 511: 'PH_PERF_SEL_SC4_PA0_FPOP_WE', + 512: 'PH_PERF_SEL_SC4_PA0_EOP_WE', + 513: 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD', + 514: 'PH_PERF_SEL_SC4_PA0_EOPG_WE', + 515: 'PH_PERF_SEL_SC4_PA0_DEALLOC_WE', + 516: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD', + 517: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE', + 518: 'PH_PERF_SEL_SC4_PA1_FIFO_EMPTY', + 519: 'PH_PERF_SEL_SC4_PA1_FIFO_FULL', + 520: 'PH_PERF_SEL_SC4_PA1_NULL_WE', + 521: 'PH_PERF_SEL_SC4_PA1_EVENT_WE', + 522: 'PH_PERF_SEL_SC4_PA1_FPOV_WE', + 523: 'PH_PERF_SEL_SC4_PA1_FPOP_WE', + 524: 'PH_PERF_SEL_SC4_PA1_EOP_WE', + 525: 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD', + 526: 'PH_PERF_SEL_SC4_PA1_EOPG_WE', + 527: 'PH_PERF_SEL_SC4_PA1_DEALLOC_WE', + 528: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD', + 529: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE', + 530: 'PH_PERF_SEL_SC4_PA2_FIFO_EMPTY', + 531: 'PH_PERF_SEL_SC4_PA2_FIFO_FULL', + 532: 'PH_PERF_SEL_SC4_PA2_NULL_WE', + 533: 'PH_PERF_SEL_SC4_PA2_EVENT_WE', + 534: 'PH_PERF_SEL_SC4_PA2_FPOV_WE', + 535: 'PH_PERF_SEL_SC4_PA2_FPOP_WE', + 536: 'PH_PERF_SEL_SC4_PA2_EOP_WE', + 537: 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD', + 538: 'PH_PERF_SEL_SC4_PA2_EOPG_WE', + 539: 'PH_PERF_SEL_SC4_PA2_DEALLOC_WE', + 540: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD', + 541: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE', + 542: 'PH_PERF_SEL_SC4_PA3_FIFO_EMPTY', + 543: 'PH_PERF_SEL_SC4_PA3_FIFO_FULL', + 544: 'PH_PERF_SEL_SC4_PA3_NULL_WE', + 545: 'PH_PERF_SEL_SC4_PA3_EVENT_WE', + 546: 'PH_PERF_SEL_SC4_PA3_FPOV_WE', + 547: 'PH_PERF_SEL_SC4_PA3_FPOP_WE', + 548: 'PH_PERF_SEL_SC4_PA3_EOP_WE', + 549: 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD', + 550: 'PH_PERF_SEL_SC4_PA3_EOPG_WE', + 551: 'PH_PERF_SEL_SC4_PA3_DEALLOC_WE', + 552: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD', + 553: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE', + 554: 'PH_PERF_SEL_SC4_PA4_FIFO_EMPTY', + 555: 'PH_PERF_SEL_SC4_PA4_FIFO_FULL', + 556: 'PH_PERF_SEL_SC4_PA4_NULL_WE', + 557: 'PH_PERF_SEL_SC4_PA4_EVENT_WE', + 558: 'PH_PERF_SEL_SC4_PA4_FPOV_WE', + 559: 'PH_PERF_SEL_SC4_PA4_FPOP_WE', + 560: 'PH_PERF_SEL_SC4_PA4_EOP_WE', + 561: 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD', + 562: 'PH_PERF_SEL_SC4_PA4_EOPG_WE', + 563: 'PH_PERF_SEL_SC4_PA4_DEALLOC_WE', + 564: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD', + 565: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE', + 566: 'PH_PERF_SEL_SC4_PA5_FIFO_EMPTY', + 567: 'PH_PERF_SEL_SC4_PA5_FIFO_FULL', + 568: 'PH_PERF_SEL_SC4_PA5_NULL_WE', + 569: 'PH_PERF_SEL_SC4_PA5_EVENT_WE', + 570: 'PH_PERF_SEL_SC4_PA5_FPOV_WE', + 571: 'PH_PERF_SEL_SC4_PA5_FPOP_WE', + 572: 'PH_PERF_SEL_SC4_PA5_EOP_WE', + 573: 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD', + 574: 'PH_PERF_SEL_SC4_PA5_EOPG_WE', + 575: 'PH_PERF_SEL_SC4_PA5_DEALLOC_WE', + 576: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD', + 577: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE', + 578: 'PH_PERF_SEL_SC4_PA6_FIFO_EMPTY', + 579: 'PH_PERF_SEL_SC4_PA6_FIFO_FULL', + 580: 'PH_PERF_SEL_SC4_PA6_NULL_WE', + 581: 'PH_PERF_SEL_SC4_PA6_EVENT_WE', + 582: 'PH_PERF_SEL_SC4_PA6_FPOV_WE', + 583: 'PH_PERF_SEL_SC4_PA6_FPOP_WE', + 584: 'PH_PERF_SEL_SC4_PA6_EOP_WE', + 585: 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD', + 586: 'PH_PERF_SEL_SC4_PA6_EOPG_WE', + 587: 'PH_PERF_SEL_SC4_PA6_DEALLOC_WE', + 588: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD', + 589: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE', + 590: 'PH_PERF_SEL_SC4_PA7_FIFO_EMPTY', + 591: 'PH_PERF_SEL_SC4_PA7_FIFO_FULL', + 592: 'PH_PERF_SEL_SC4_PA7_NULL_WE', + 593: 'PH_PERF_SEL_SC4_PA7_EVENT_WE', + 594: 'PH_PERF_SEL_SC4_PA7_FPOV_WE', + 595: 'PH_PERF_SEL_SC4_PA7_FPOP_WE', + 596: 'PH_PERF_SEL_SC4_PA7_EOP_WE', + 597: 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD', + 598: 'PH_PERF_SEL_SC4_PA7_EOPG_WE', + 599: 'PH_PERF_SEL_SC4_PA7_DEALLOC_WE', + 600: 'PH_PERF_SEL_SC5_SRPS_WINDOW_VALID', + 601: 'PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 602: 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES', + 603: 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 604: 'PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW', + 605: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE', + 606: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 607: 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 608: 'PH_PERF_SEL_SC5_ARB_BUSY', + 609: 'PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP', + 610: 'PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP', + 611: 'PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP', + 612: 'PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE', + 613: 'PH_PERF_SEL_SC5_EOP_SYNC_WINDOW', + 614: 'PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', + 615: 'PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO', + 616: 'PH_PERF_SEL_SC5_SEND', + 617: 'PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 618: 'PH_PERF_SEL_SC5_CREDIT_AT_MAX', + 619: 'PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 620: 'PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION', + 621: 'PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION', + 622: 'PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 623: 'PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 624: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD', + 625: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE', + 626: 'PH_PERF_SEL_SC5_PA0_FIFO_EMPTY', + 627: 'PH_PERF_SEL_SC5_PA0_FIFO_FULL', + 628: 'PH_PERF_SEL_SC5_PA0_NULL_WE', + 629: 'PH_PERF_SEL_SC5_PA0_EVENT_WE', + 630: 'PH_PERF_SEL_SC5_PA0_FPOV_WE', + 631: 'PH_PERF_SEL_SC5_PA0_FPOP_WE', + 632: 'PH_PERF_SEL_SC5_PA0_EOP_WE', + 633: 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD', + 634: 'PH_PERF_SEL_SC5_PA0_EOPG_WE', + 635: 'PH_PERF_SEL_SC5_PA0_DEALLOC_WE', + 636: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD', + 637: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE', + 638: 'PH_PERF_SEL_SC5_PA1_FIFO_EMPTY', + 639: 'PH_PERF_SEL_SC5_PA1_FIFO_FULL', + 640: 'PH_PERF_SEL_SC5_PA1_NULL_WE', + 641: 'PH_PERF_SEL_SC5_PA1_EVENT_WE', + 642: 'PH_PERF_SEL_SC5_PA1_FPOV_WE', + 643: 'PH_PERF_SEL_SC5_PA1_FPOP_WE', + 644: 'PH_PERF_SEL_SC5_PA1_EOP_WE', + 645: 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD', + 646: 'PH_PERF_SEL_SC5_PA1_EOPG_WE', + 647: 'PH_PERF_SEL_SC5_PA1_DEALLOC_WE', + 648: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD', + 649: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE', + 650: 'PH_PERF_SEL_SC5_PA2_FIFO_EMPTY', + 651: 'PH_PERF_SEL_SC5_PA2_FIFO_FULL', + 652: 'PH_PERF_SEL_SC5_PA2_NULL_WE', + 653: 'PH_PERF_SEL_SC5_PA2_EVENT_WE', + 654: 'PH_PERF_SEL_SC5_PA2_FPOV_WE', + 655: 'PH_PERF_SEL_SC5_PA2_FPOP_WE', + 656: 'PH_PERF_SEL_SC5_PA2_EOP_WE', + 657: 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD', + 658: 'PH_PERF_SEL_SC5_PA2_EOPG_WE', + 659: 'PH_PERF_SEL_SC5_PA2_DEALLOC_WE', + 660: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD', + 661: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE', + 662: 'PH_PERF_SEL_SC5_PA3_FIFO_EMPTY', + 663: 'PH_PERF_SEL_SC5_PA3_FIFO_FULL', + 664: 'PH_PERF_SEL_SC5_PA3_NULL_WE', + 665: 'PH_PERF_SEL_SC5_PA3_EVENT_WE', + 666: 'PH_PERF_SEL_SC5_PA3_FPOV_WE', + 667: 'PH_PERF_SEL_SC5_PA3_FPOP_WE', + 668: 'PH_PERF_SEL_SC5_PA3_EOP_WE', + 669: 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD', + 670: 'PH_PERF_SEL_SC5_PA3_EOPG_WE', + 671: 'PH_PERF_SEL_SC5_PA3_DEALLOC_WE', + 672: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD', + 673: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE', + 674: 'PH_PERF_SEL_SC5_PA4_FIFO_EMPTY', + 675: 'PH_PERF_SEL_SC5_PA4_FIFO_FULL', + 676: 'PH_PERF_SEL_SC5_PA4_NULL_WE', + 677: 'PH_PERF_SEL_SC5_PA4_EVENT_WE', + 678: 'PH_PERF_SEL_SC5_PA4_FPOV_WE', + 679: 'PH_PERF_SEL_SC5_PA4_FPOP_WE', + 680: 'PH_PERF_SEL_SC5_PA4_EOP_WE', + 681: 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD', + 682: 'PH_PERF_SEL_SC5_PA4_EOPG_WE', + 683: 'PH_PERF_SEL_SC5_PA4_DEALLOC_WE', + 684: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD', + 685: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE', + 686: 'PH_PERF_SEL_SC5_PA5_FIFO_EMPTY', + 687: 'PH_PERF_SEL_SC5_PA5_FIFO_FULL', + 688: 'PH_PERF_SEL_SC5_PA5_NULL_WE', + 689: 'PH_PERF_SEL_SC5_PA5_EVENT_WE', + 690: 'PH_PERF_SEL_SC5_PA5_FPOV_WE', + 691: 'PH_PERF_SEL_SC5_PA5_FPOP_WE', + 692: 'PH_PERF_SEL_SC5_PA5_EOP_WE', + 693: 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD', + 694: 'PH_PERF_SEL_SC5_PA5_EOPG_WE', + 695: 'PH_PERF_SEL_SC5_PA5_DEALLOC_WE', + 696: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD', + 697: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE', + 698: 'PH_PERF_SEL_SC5_PA6_FIFO_EMPTY', + 699: 'PH_PERF_SEL_SC5_PA6_FIFO_FULL', + 700: 'PH_PERF_SEL_SC5_PA6_NULL_WE', + 701: 'PH_PERF_SEL_SC5_PA6_EVENT_WE', + 702: 'PH_PERF_SEL_SC5_PA6_FPOV_WE', + 703: 'PH_PERF_SEL_SC5_PA6_FPOP_WE', + 704: 'PH_PERF_SEL_SC5_PA6_EOP_WE', + 705: 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD', + 706: 'PH_PERF_SEL_SC5_PA6_EOPG_WE', + 707: 'PH_PERF_SEL_SC5_PA6_DEALLOC_WE', + 708: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD', + 709: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE', + 710: 'PH_PERF_SEL_SC5_PA7_FIFO_EMPTY', + 711: 'PH_PERF_SEL_SC5_PA7_FIFO_FULL', + 712: 'PH_PERF_SEL_SC5_PA7_NULL_WE', + 713: 'PH_PERF_SEL_SC5_PA7_EVENT_WE', + 714: 'PH_PERF_SEL_SC5_PA7_FPOV_WE', + 715: 'PH_PERF_SEL_SC5_PA7_FPOP_WE', + 716: 'PH_PERF_SEL_SC5_PA7_EOP_WE', + 717: 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD', + 718: 'PH_PERF_SEL_SC5_PA7_EOPG_WE', + 719: 'PH_PERF_SEL_SC5_PA7_DEALLOC_WE', + 720: 'PH_PERF_SEL_SC6_SRPS_WINDOW_VALID', + 721: 'PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 722: 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES', + 723: 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 724: 'PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW', + 725: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE', + 726: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 727: 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 728: 'PH_PERF_SEL_SC6_ARB_BUSY', + 729: 'PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP', + 730: 'PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP', + 731: 'PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP', + 732: 'PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE', + 733: 'PH_PERF_SEL_SC6_EOP_SYNC_WINDOW', + 734: 'PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', + 735: 'PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO', + 736: 'PH_PERF_SEL_SC6_SEND', + 737: 'PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 738: 'PH_PERF_SEL_SC6_CREDIT_AT_MAX', + 739: 'PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 740: 'PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION', + 741: 'PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION', + 742: 'PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 743: 'PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 744: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD', + 745: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE', + 746: 'PH_PERF_SEL_SC6_PA0_FIFO_EMPTY', + 747: 'PH_PERF_SEL_SC6_PA0_FIFO_FULL', + 748: 'PH_PERF_SEL_SC6_PA0_NULL_WE', + 749: 'PH_PERF_SEL_SC6_PA0_EVENT_WE', + 750: 'PH_PERF_SEL_SC6_PA0_FPOV_WE', + 751: 'PH_PERF_SEL_SC6_PA0_FPOP_WE', + 752: 'PH_PERF_SEL_SC6_PA0_EOP_WE', + 753: 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD', + 754: 'PH_PERF_SEL_SC6_PA0_EOPG_WE', + 755: 'PH_PERF_SEL_SC6_PA0_DEALLOC_WE', + 756: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD', + 757: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE', + 758: 'PH_PERF_SEL_SC6_PA1_FIFO_EMPTY', + 759: 'PH_PERF_SEL_SC6_PA1_FIFO_FULL', + 760: 'PH_PERF_SEL_SC6_PA1_NULL_WE', + 761: 'PH_PERF_SEL_SC6_PA1_EVENT_WE', + 762: 'PH_PERF_SEL_SC6_PA1_FPOV_WE', + 763: 'PH_PERF_SEL_SC6_PA1_FPOP_WE', + 764: 'PH_PERF_SEL_SC6_PA1_EOP_WE', + 765: 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD', + 766: 'PH_PERF_SEL_SC6_PA1_EOPG_WE', + 767: 'PH_PERF_SEL_SC6_PA1_DEALLOC_WE', + 768: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD', + 769: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE', + 770: 'PH_PERF_SEL_SC6_PA2_FIFO_EMPTY', + 771: 'PH_PERF_SEL_SC6_PA2_FIFO_FULL', + 772: 'PH_PERF_SEL_SC6_PA2_NULL_WE', + 773: 'PH_PERF_SEL_SC6_PA2_EVENT_WE', + 774: 'PH_PERF_SEL_SC6_PA2_FPOV_WE', + 775: 'PH_PERF_SEL_SC6_PA2_FPOP_WE', + 776: 'PH_PERF_SEL_SC6_PA2_EOP_WE', + 777: 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD', + 778: 'PH_PERF_SEL_SC6_PA2_EOPG_WE', + 779: 'PH_PERF_SEL_SC6_PA2_DEALLOC_WE', + 780: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD', + 781: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE', + 782: 'PH_PERF_SEL_SC6_PA3_FIFO_EMPTY', + 783: 'PH_PERF_SEL_SC6_PA3_FIFO_FULL', + 784: 'PH_PERF_SEL_SC6_PA3_NULL_WE', + 785: 'PH_PERF_SEL_SC6_PA3_EVENT_WE', + 786: 'PH_PERF_SEL_SC6_PA3_FPOV_WE', + 787: 'PH_PERF_SEL_SC6_PA3_FPOP_WE', + 788: 'PH_PERF_SEL_SC6_PA3_EOP_WE', + 789: 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD', + 790: 'PH_PERF_SEL_SC6_PA3_EOPG_WE', + 791: 'PH_PERF_SEL_SC6_PA3_DEALLOC_WE', + 792: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD', + 793: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE', + 794: 'PH_PERF_SEL_SC6_PA4_FIFO_EMPTY', + 795: 'PH_PERF_SEL_SC6_PA4_FIFO_FULL', + 796: 'PH_PERF_SEL_SC6_PA4_NULL_WE', + 797: 'PH_PERF_SEL_SC6_PA4_EVENT_WE', + 798: 'PH_PERF_SEL_SC6_PA4_FPOV_WE', + 799: 'PH_PERF_SEL_SC6_PA4_FPOP_WE', + 800: 'PH_PERF_SEL_SC6_PA4_EOP_WE', + 801: 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD', + 802: 'PH_PERF_SEL_SC6_PA4_EOPG_WE', + 803: 'PH_PERF_SEL_SC6_PA4_DEALLOC_WE', + 804: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD', + 805: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE', + 806: 'PH_PERF_SEL_SC6_PA5_FIFO_EMPTY', + 807: 'PH_PERF_SEL_SC6_PA5_FIFO_FULL', + 808: 'PH_PERF_SEL_SC6_PA5_NULL_WE', + 809: 'PH_PERF_SEL_SC6_PA5_EVENT_WE', + 810: 'PH_PERF_SEL_SC6_PA5_FPOV_WE', + 811: 'PH_PERF_SEL_SC6_PA5_FPOP_WE', + 812: 'PH_PERF_SEL_SC6_PA5_EOP_WE', + 813: 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD', + 814: 'PH_PERF_SEL_SC6_PA5_EOPG_WE', + 815: 'PH_PERF_SEL_SC6_PA5_DEALLOC_WE', + 816: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD', + 817: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE', + 818: 'PH_PERF_SEL_SC6_PA6_FIFO_EMPTY', + 819: 'PH_PERF_SEL_SC6_PA6_FIFO_FULL', + 820: 'PH_PERF_SEL_SC6_PA6_NULL_WE', + 821: 'PH_PERF_SEL_SC6_PA6_EVENT_WE', + 822: 'PH_PERF_SEL_SC6_PA6_FPOV_WE', + 823: 'PH_PERF_SEL_SC6_PA6_FPOP_WE', + 824: 'PH_PERF_SEL_SC6_PA6_EOP_WE', + 825: 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD', + 826: 'PH_PERF_SEL_SC6_PA6_EOPG_WE', + 827: 'PH_PERF_SEL_SC6_PA6_DEALLOC_WE', + 828: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD', + 829: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE', + 830: 'PH_PERF_SEL_SC6_PA7_FIFO_EMPTY', + 831: 'PH_PERF_SEL_SC6_PA7_FIFO_FULL', + 832: 'PH_PERF_SEL_SC6_PA7_NULL_WE', + 833: 'PH_PERF_SEL_SC6_PA7_EVENT_WE', + 834: 'PH_PERF_SEL_SC6_PA7_FPOV_WE', + 835: 'PH_PERF_SEL_SC6_PA7_FPOP_WE', + 836: 'PH_PERF_SEL_SC6_PA7_EOP_WE', + 837: 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD', + 838: 'PH_PERF_SEL_SC6_PA7_EOPG_WE', + 839: 'PH_PERF_SEL_SC6_PA7_DEALLOC_WE', + 840: 'PH_PERF_SEL_SC7_SRPS_WINDOW_VALID', + 841: 'PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 842: 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES', + 843: 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 844: 'PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW', + 845: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE', + 846: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 847: 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 848: 'PH_PERF_SEL_SC7_ARB_BUSY', + 849: 'PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP', + 850: 'PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP', + 851: 'PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP', + 852: 'PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE', + 853: 'PH_PERF_SEL_SC7_EOP_SYNC_WINDOW', + 854: 'PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', + 855: 'PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO', + 856: 'PH_PERF_SEL_SC7_SEND', + 857: 'PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 858: 'PH_PERF_SEL_SC7_CREDIT_AT_MAX', + 859: 'PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 860: 'PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION', + 861: 'PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION', + 862: 'PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 863: 'PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 864: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD', + 865: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE', + 866: 'PH_PERF_SEL_SC7_PA0_FIFO_EMPTY', + 867: 'PH_PERF_SEL_SC7_PA0_FIFO_FULL', + 868: 'PH_PERF_SEL_SC7_PA0_NULL_WE', + 869: 'PH_PERF_SEL_SC7_PA0_EVENT_WE', + 870: 'PH_PERF_SEL_SC7_PA0_FPOV_WE', + 871: 'PH_PERF_SEL_SC7_PA0_FPOP_WE', + 872: 'PH_PERF_SEL_SC7_PA0_EOP_WE', + 873: 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD', + 874: 'PH_PERF_SEL_SC7_PA0_EOPG_WE', + 875: 'PH_PERF_SEL_SC7_PA0_DEALLOC_WE', + 876: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD', + 877: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE', + 878: 'PH_PERF_SEL_SC7_PA1_FIFO_EMPTY', + 879: 'PH_PERF_SEL_SC7_PA1_FIFO_FULL', + 880: 'PH_PERF_SEL_SC7_PA1_NULL_WE', + 881: 'PH_PERF_SEL_SC7_PA1_EVENT_WE', + 882: 'PH_PERF_SEL_SC7_PA1_FPOV_WE', + 883: 'PH_PERF_SEL_SC7_PA1_FPOP_WE', + 884: 'PH_PERF_SEL_SC7_PA1_EOP_WE', + 885: 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD', + 886: 'PH_PERF_SEL_SC7_PA1_EOPG_WE', + 887: 'PH_PERF_SEL_SC7_PA1_DEALLOC_WE', + 888: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD', + 889: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE', + 890: 'PH_PERF_SEL_SC7_PA2_FIFO_EMPTY', + 891: 'PH_PERF_SEL_SC7_PA2_FIFO_FULL', + 892: 'PH_PERF_SEL_SC7_PA2_NULL_WE', + 893: 'PH_PERF_SEL_SC7_PA2_EVENT_WE', + 894: 'PH_PERF_SEL_SC7_PA2_FPOV_WE', + 895: 'PH_PERF_SEL_SC7_PA2_FPOP_WE', + 896: 'PH_PERF_SEL_SC7_PA2_EOP_WE', + 897: 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD', + 898: 'PH_PERF_SEL_SC7_PA2_EOPG_WE', + 899: 'PH_PERF_SEL_SC7_PA2_DEALLOC_WE', + 900: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD', + 901: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE', + 902: 'PH_PERF_SEL_SC7_PA3_FIFO_EMPTY', + 903: 'PH_PERF_SEL_SC7_PA3_FIFO_FULL', + 904: 'PH_PERF_SEL_SC7_PA3_NULL_WE', + 905: 'PH_PERF_SEL_SC7_PA3_EVENT_WE', + 906: 'PH_PERF_SEL_SC7_PA3_FPOV_WE', + 907: 'PH_PERF_SEL_SC7_PA3_FPOP_WE', + 908: 'PH_PERF_SEL_SC7_PA3_EOP_WE', + 909: 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD', + 910: 'PH_PERF_SEL_SC7_PA3_EOPG_WE', + 911: 'PH_PERF_SEL_SC7_PA3_DEALLOC_WE', + 912: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD', + 913: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE', + 914: 'PH_PERF_SEL_SC7_PA4_FIFO_EMPTY', + 915: 'PH_PERF_SEL_SC7_PA4_FIFO_FULL', + 916: 'PH_PERF_SEL_SC7_PA4_NULL_WE', + 917: 'PH_PERF_SEL_SC7_PA4_EVENT_WE', + 918: 'PH_PERF_SEL_SC7_PA4_FPOV_WE', + 919: 'PH_PERF_SEL_SC7_PA4_FPOP_WE', + 920: 'PH_PERF_SEL_SC7_PA4_EOP_WE', + 921: 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD', + 922: 'PH_PERF_SEL_SC7_PA4_EOPG_WE', + 923: 'PH_PERF_SEL_SC7_PA4_DEALLOC_WE', + 924: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD', + 925: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE', + 926: 'PH_PERF_SEL_SC7_PA5_FIFO_EMPTY', + 927: 'PH_PERF_SEL_SC7_PA5_FIFO_FULL', + 928: 'PH_PERF_SEL_SC7_PA5_NULL_WE', + 929: 'PH_PERF_SEL_SC7_PA5_EVENT_WE', + 930: 'PH_PERF_SEL_SC7_PA5_FPOV_WE', + 931: 'PH_PERF_SEL_SC7_PA5_FPOP_WE', + 932: 'PH_PERF_SEL_SC7_PA5_EOP_WE', + 933: 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD', + 934: 'PH_PERF_SEL_SC7_PA5_EOPG_WE', + 935: 'PH_PERF_SEL_SC7_PA5_DEALLOC_WE', + 936: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD', + 937: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE', + 938: 'PH_PERF_SEL_SC7_PA6_FIFO_EMPTY', + 939: 'PH_PERF_SEL_SC7_PA6_FIFO_FULL', + 940: 'PH_PERF_SEL_SC7_PA6_NULL_WE', + 941: 'PH_PERF_SEL_SC7_PA6_EVENT_WE', + 942: 'PH_PERF_SEL_SC7_PA6_FPOV_WE', + 943: 'PH_PERF_SEL_SC7_PA6_FPOP_WE', + 944: 'PH_PERF_SEL_SC7_PA6_EOP_WE', + 945: 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD', + 946: 'PH_PERF_SEL_SC7_PA6_EOPG_WE', + 947: 'PH_PERF_SEL_SC7_PA6_DEALLOC_WE', + 948: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD', + 949: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE', + 950: 'PH_PERF_SEL_SC7_PA7_FIFO_EMPTY', + 951: 'PH_PERF_SEL_SC7_PA7_FIFO_FULL', + 952: 'PH_PERF_SEL_SC7_PA7_NULL_WE', + 953: 'PH_PERF_SEL_SC7_PA7_EVENT_WE', + 954: 'PH_PERF_SEL_SC7_PA7_FPOV_WE', + 955: 'PH_PERF_SEL_SC7_PA7_FPOP_WE', + 956: 'PH_PERF_SEL_SC7_PA7_EOP_WE', + 957: 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD', + 958: 'PH_PERF_SEL_SC7_PA7_EOPG_WE', + 959: 'PH_PERF_SEL_SC7_PA7_DEALLOC_WE', + 960: 'PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW', + 961: 'PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW', + 962: 'PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW', + 963: 'PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW', + 964: 'PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW', + 965: 'PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW', + 966: 'PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW', + 967: 'PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW', + 968: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE', + 969: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE', + 970: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE', + 971: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE', + 972: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE', + 973: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE', + 974: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE', + 975: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE', + 976: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 977: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 978: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 979: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 980: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 981: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 982: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 983: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 984: 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 985: 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 986: 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 987: 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 988: 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 989: 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 990: 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 991: 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 992: 'PH_PERF_SC0_FIFO_STATUS_0', + 993: 'PH_PERF_SC0_FIFO_STATUS_1', + 994: 'PH_PERF_SC0_FIFO_STATUS_2', + 995: 'PH_PERF_SC0_FIFO_STATUS_3', + 996: 'PH_PERF_SC1_FIFO_STATUS_0', + 997: 'PH_PERF_SC1_FIFO_STATUS_1', + 998: 'PH_PERF_SC1_FIFO_STATUS_2', + 999: 'PH_PERF_SC1_FIFO_STATUS_3', + 1000: 'PH_PERF_SC2_FIFO_STATUS_0', + 1001: 'PH_PERF_SC2_FIFO_STATUS_1', + 1002: 'PH_PERF_SC2_FIFO_STATUS_2', + 1003: 'PH_PERF_SC2_FIFO_STATUS_3', + 1004: 'PH_PERF_SC3_FIFO_STATUS_0', + 1005: 'PH_PERF_SC3_FIFO_STATUS_1', + 1006: 'PH_PERF_SC3_FIFO_STATUS_2', + 1007: 'PH_PERF_SC3_FIFO_STATUS_3', + 1008: 'PH_PERF_SC4_FIFO_STATUS_0', + 1009: 'PH_PERF_SC4_FIFO_STATUS_1', + 1010: 'PH_PERF_SC4_FIFO_STATUS_2', + 1011: 'PH_PERF_SC4_FIFO_STATUS_3', + 1012: 'PH_PERF_SC5_FIFO_STATUS_0', + 1013: 'PH_PERF_SC5_FIFO_STATUS_1', + 1014: 'PH_PERF_SC5_FIFO_STATUS_2', + 1015: 'PH_PERF_SC5_FIFO_STATUS_3', + 1016: 'PH_PERF_SC6_FIFO_STATUS_0', + 1017: 'PH_PERF_SC6_FIFO_STATUS_1', + 1018: 'PH_PERF_SC6_FIFO_STATUS_2', + 1019: 'PH_PERF_SC6_FIFO_STATUS_3', + 1020: 'PH_PERF_SC7_FIFO_STATUS_0', + 1021: 'PH_PERF_SC7_FIFO_STATUS_1', + 1022: 'PH_PERF_SC7_FIFO_STATUS_2', + 1023: 'PH_PERF_SC7_FIFO_STATUS_3', +} +PH_PERF_SEL_SC0_SRPS_WINDOW_VALID = 0 +PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 1 +PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES = 2 +PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 3 +PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW = 4 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE = 5 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 6 +PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 7 +PH_PERF_SEL_SC0_ARB_BUSY = 8 +PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP = 9 +PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP = 10 +PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP = 11 +PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE = 12 +PH_PERF_SEL_SC0_EOP_SYNC_WINDOW = 13 +PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM = 14 +PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO = 15 +PH_PERF_SEL_SC0_SEND = 16 +PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND = 17 +PH_PERF_SEL_SC0_CREDIT_AT_MAX = 18 +PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND = 19 +PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION = 20 +PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION = 21 +PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION = 22 +PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 23 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD = 24 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE = 25 +PH_PERF_SEL_SC0_PA0_FIFO_EMPTY = 26 +PH_PERF_SEL_SC0_PA0_FIFO_FULL = 27 +PH_PERF_SEL_SC0_PA0_NULL_WE = 28 +PH_PERF_SEL_SC0_PA0_EVENT_WE = 29 +PH_PERF_SEL_SC0_PA0_FPOV_WE = 30 +PH_PERF_SEL_SC0_PA0_FPOP_WE = 31 +PH_PERF_SEL_SC0_PA0_EOP_WE = 32 +PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD = 33 +PH_PERF_SEL_SC0_PA0_EOPG_WE = 34 +PH_PERF_SEL_SC0_PA0_DEALLOC_WE = 35 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD = 36 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE = 37 +PH_PERF_SEL_SC0_PA1_FIFO_EMPTY = 38 +PH_PERF_SEL_SC0_PA1_FIFO_FULL = 39 +PH_PERF_SEL_SC0_PA1_NULL_WE = 40 +PH_PERF_SEL_SC0_PA1_EVENT_WE = 41 +PH_PERF_SEL_SC0_PA1_FPOV_WE = 42 +PH_PERF_SEL_SC0_PA1_FPOP_WE = 43 +PH_PERF_SEL_SC0_PA1_EOP_WE = 44 +PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD = 45 +PH_PERF_SEL_SC0_PA1_EOPG_WE = 46 +PH_PERF_SEL_SC0_PA1_DEALLOC_WE = 47 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD = 48 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE = 49 +PH_PERF_SEL_SC0_PA2_FIFO_EMPTY = 50 +PH_PERF_SEL_SC0_PA2_FIFO_FULL = 51 +PH_PERF_SEL_SC0_PA2_NULL_WE = 52 +PH_PERF_SEL_SC0_PA2_EVENT_WE = 53 +PH_PERF_SEL_SC0_PA2_FPOV_WE = 54 +PH_PERF_SEL_SC0_PA2_FPOP_WE = 55 +PH_PERF_SEL_SC0_PA2_EOP_WE = 56 +PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD = 57 +PH_PERF_SEL_SC0_PA2_EOPG_WE = 58 +PH_PERF_SEL_SC0_PA2_DEALLOC_WE = 59 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD = 60 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE = 61 +PH_PERF_SEL_SC0_PA3_FIFO_EMPTY = 62 +PH_PERF_SEL_SC0_PA3_FIFO_FULL = 63 +PH_PERF_SEL_SC0_PA3_NULL_WE = 64 +PH_PERF_SEL_SC0_PA3_EVENT_WE = 65 +PH_PERF_SEL_SC0_PA3_FPOV_WE = 66 +PH_PERF_SEL_SC0_PA3_FPOP_WE = 67 +PH_PERF_SEL_SC0_PA3_EOP_WE = 68 +PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD = 69 +PH_PERF_SEL_SC0_PA3_EOPG_WE = 70 +PH_PERF_SEL_SC0_PA3_DEALLOC_WE = 71 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD = 72 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE = 73 +PH_PERF_SEL_SC0_PA4_FIFO_EMPTY = 74 +PH_PERF_SEL_SC0_PA4_FIFO_FULL = 75 +PH_PERF_SEL_SC0_PA4_NULL_WE = 76 +PH_PERF_SEL_SC0_PA4_EVENT_WE = 77 +PH_PERF_SEL_SC0_PA4_FPOV_WE = 78 +PH_PERF_SEL_SC0_PA4_FPOP_WE = 79 +PH_PERF_SEL_SC0_PA4_EOP_WE = 80 +PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD = 81 +PH_PERF_SEL_SC0_PA4_EOPG_WE = 82 +PH_PERF_SEL_SC0_PA4_DEALLOC_WE = 83 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD = 84 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE = 85 +PH_PERF_SEL_SC0_PA5_FIFO_EMPTY = 86 +PH_PERF_SEL_SC0_PA5_FIFO_FULL = 87 +PH_PERF_SEL_SC0_PA5_NULL_WE = 88 +PH_PERF_SEL_SC0_PA5_EVENT_WE = 89 +PH_PERF_SEL_SC0_PA5_FPOV_WE = 90 +PH_PERF_SEL_SC0_PA5_FPOP_WE = 91 +PH_PERF_SEL_SC0_PA5_EOP_WE = 92 +PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD = 93 +PH_PERF_SEL_SC0_PA5_EOPG_WE = 94 +PH_PERF_SEL_SC0_PA5_DEALLOC_WE = 95 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD = 96 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE = 97 +PH_PERF_SEL_SC0_PA6_FIFO_EMPTY = 98 +PH_PERF_SEL_SC0_PA6_FIFO_FULL = 99 +PH_PERF_SEL_SC0_PA6_NULL_WE = 100 +PH_PERF_SEL_SC0_PA6_EVENT_WE = 101 +PH_PERF_SEL_SC0_PA6_FPOV_WE = 102 +PH_PERF_SEL_SC0_PA6_FPOP_WE = 103 +PH_PERF_SEL_SC0_PA6_EOP_WE = 104 +PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD = 105 +PH_PERF_SEL_SC0_PA6_EOPG_WE = 106 +PH_PERF_SEL_SC0_PA6_DEALLOC_WE = 107 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD = 108 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE = 109 +PH_PERF_SEL_SC0_PA7_FIFO_EMPTY = 110 +PH_PERF_SEL_SC0_PA7_FIFO_FULL = 111 +PH_PERF_SEL_SC0_PA7_NULL_WE = 112 +PH_PERF_SEL_SC0_PA7_EVENT_WE = 113 +PH_PERF_SEL_SC0_PA7_FPOV_WE = 114 +PH_PERF_SEL_SC0_PA7_FPOP_WE = 115 +PH_PERF_SEL_SC0_PA7_EOP_WE = 116 +PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD = 117 +PH_PERF_SEL_SC0_PA7_EOPG_WE = 118 +PH_PERF_SEL_SC0_PA7_DEALLOC_WE = 119 +PH_PERF_SEL_SC1_SRPS_WINDOW_VALID = 120 +PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 121 +PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES = 122 +PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 123 +PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW = 124 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE = 125 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 126 +PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 127 +PH_PERF_SEL_SC1_ARB_BUSY = 128 +PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP = 129 +PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP = 130 +PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP = 131 +PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE = 132 +PH_PERF_SEL_SC1_EOP_SYNC_WINDOW = 133 +PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM = 134 +PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO = 135 +PH_PERF_SEL_SC1_SEND = 136 +PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND = 137 +PH_PERF_SEL_SC1_CREDIT_AT_MAX = 138 +PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND = 139 +PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION = 140 +PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION = 141 +PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 142 +PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 143 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD = 144 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE = 145 +PH_PERF_SEL_SC1_PA0_FIFO_EMPTY = 146 +PH_PERF_SEL_SC1_PA0_FIFO_FULL = 147 +PH_PERF_SEL_SC1_PA0_NULL_WE = 148 +PH_PERF_SEL_SC1_PA0_EVENT_WE = 149 +PH_PERF_SEL_SC1_PA0_FPOV_WE = 150 +PH_PERF_SEL_SC1_PA0_FPOP_WE = 151 +PH_PERF_SEL_SC1_PA0_EOP_WE = 152 +PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD = 153 +PH_PERF_SEL_SC1_PA0_EOPG_WE = 154 +PH_PERF_SEL_SC1_PA0_DEALLOC_WE = 155 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD = 156 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE = 157 +PH_PERF_SEL_SC1_PA1_FIFO_EMPTY = 158 +PH_PERF_SEL_SC1_PA1_FIFO_FULL = 159 +PH_PERF_SEL_SC1_PA1_NULL_WE = 160 +PH_PERF_SEL_SC1_PA1_EVENT_WE = 161 +PH_PERF_SEL_SC1_PA1_FPOV_WE = 162 +PH_PERF_SEL_SC1_PA1_FPOP_WE = 163 +PH_PERF_SEL_SC1_PA1_EOP_WE = 164 +PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD = 165 +PH_PERF_SEL_SC1_PA1_EOPG_WE = 166 +PH_PERF_SEL_SC1_PA1_DEALLOC_WE = 167 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD = 168 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE = 169 +PH_PERF_SEL_SC1_PA2_FIFO_EMPTY = 170 +PH_PERF_SEL_SC1_PA2_FIFO_FULL = 171 +PH_PERF_SEL_SC1_PA2_NULL_WE = 172 +PH_PERF_SEL_SC1_PA2_EVENT_WE = 173 +PH_PERF_SEL_SC1_PA2_FPOV_WE = 174 +PH_PERF_SEL_SC1_PA2_FPOP_WE = 175 +PH_PERF_SEL_SC1_PA2_EOP_WE = 176 +PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD = 177 +PH_PERF_SEL_SC1_PA2_EOPG_WE = 178 +PH_PERF_SEL_SC1_PA2_DEALLOC_WE = 179 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD = 180 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE = 181 +PH_PERF_SEL_SC1_PA3_FIFO_EMPTY = 182 +PH_PERF_SEL_SC1_PA3_FIFO_FULL = 183 +PH_PERF_SEL_SC1_PA3_NULL_WE = 184 +PH_PERF_SEL_SC1_PA3_EVENT_WE = 185 +PH_PERF_SEL_SC1_PA3_FPOV_WE = 186 +PH_PERF_SEL_SC1_PA3_FPOP_WE = 187 +PH_PERF_SEL_SC1_PA3_EOP_WE = 188 +PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD = 189 +PH_PERF_SEL_SC1_PA3_EOPG_WE = 190 +PH_PERF_SEL_SC1_PA3_DEALLOC_WE = 191 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD = 192 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE = 193 +PH_PERF_SEL_SC1_PA4_FIFO_EMPTY = 194 +PH_PERF_SEL_SC1_PA4_FIFO_FULL = 195 +PH_PERF_SEL_SC1_PA4_NULL_WE = 196 +PH_PERF_SEL_SC1_PA4_EVENT_WE = 197 +PH_PERF_SEL_SC1_PA4_FPOV_WE = 198 +PH_PERF_SEL_SC1_PA4_FPOP_WE = 199 +PH_PERF_SEL_SC1_PA4_EOP_WE = 200 +PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD = 201 +PH_PERF_SEL_SC1_PA4_EOPG_WE = 202 +PH_PERF_SEL_SC1_PA4_DEALLOC_WE = 203 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD = 204 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE = 205 +PH_PERF_SEL_SC1_PA5_FIFO_EMPTY = 206 +PH_PERF_SEL_SC1_PA5_FIFO_FULL = 207 +PH_PERF_SEL_SC1_PA5_NULL_WE = 208 +PH_PERF_SEL_SC1_PA5_EVENT_WE = 209 +PH_PERF_SEL_SC1_PA5_FPOV_WE = 210 +PH_PERF_SEL_SC1_PA5_FPOP_WE = 211 +PH_PERF_SEL_SC1_PA5_EOP_WE = 212 +PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD = 213 +PH_PERF_SEL_SC1_PA5_EOPG_WE = 214 +PH_PERF_SEL_SC1_PA5_DEALLOC_WE = 215 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD = 216 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE = 217 +PH_PERF_SEL_SC1_PA6_FIFO_EMPTY = 218 +PH_PERF_SEL_SC1_PA6_FIFO_FULL = 219 +PH_PERF_SEL_SC1_PA6_NULL_WE = 220 +PH_PERF_SEL_SC1_PA6_EVENT_WE = 221 +PH_PERF_SEL_SC1_PA6_FPOV_WE = 222 +PH_PERF_SEL_SC1_PA6_FPOP_WE = 223 +PH_PERF_SEL_SC1_PA6_EOP_WE = 224 +PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD = 225 +PH_PERF_SEL_SC1_PA6_EOPG_WE = 226 +PH_PERF_SEL_SC1_PA6_DEALLOC_WE = 227 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD = 228 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE = 229 +PH_PERF_SEL_SC1_PA7_FIFO_EMPTY = 230 +PH_PERF_SEL_SC1_PA7_FIFO_FULL = 231 +PH_PERF_SEL_SC1_PA7_NULL_WE = 232 +PH_PERF_SEL_SC1_PA7_EVENT_WE = 233 +PH_PERF_SEL_SC1_PA7_FPOV_WE = 234 +PH_PERF_SEL_SC1_PA7_FPOP_WE = 235 +PH_PERF_SEL_SC1_PA7_EOP_WE = 236 +PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD = 237 +PH_PERF_SEL_SC1_PA7_EOPG_WE = 238 +PH_PERF_SEL_SC1_PA7_DEALLOC_WE = 239 +PH_PERF_SEL_SC2_SRPS_WINDOW_VALID = 240 +PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 241 +PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES = 242 +PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 243 +PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW = 244 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE = 245 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 246 +PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 247 +PH_PERF_SEL_SC2_ARB_BUSY = 248 +PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP = 249 +PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP = 250 +PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP = 251 +PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE = 252 +PH_PERF_SEL_SC2_EOP_SYNC_WINDOW = 253 +PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM = 254 +PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO = 255 +PH_PERF_SEL_SC2_SEND = 256 +PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND = 257 +PH_PERF_SEL_SC2_CREDIT_AT_MAX = 258 +PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND = 259 +PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION = 260 +PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION = 261 +PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 262 +PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 263 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD = 264 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE = 265 +PH_PERF_SEL_SC2_PA0_FIFO_EMPTY = 266 +PH_PERF_SEL_SC2_PA0_FIFO_FULL = 267 +PH_PERF_SEL_SC2_PA0_NULL_WE = 268 +PH_PERF_SEL_SC2_PA0_EVENT_WE = 269 +PH_PERF_SEL_SC2_PA0_FPOV_WE = 270 +PH_PERF_SEL_SC2_PA0_FPOP_WE = 271 +PH_PERF_SEL_SC2_PA0_EOP_WE = 272 +PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD = 273 +PH_PERF_SEL_SC2_PA0_EOPG_WE = 274 +PH_PERF_SEL_SC2_PA0_DEALLOC_WE = 275 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD = 276 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE = 277 +PH_PERF_SEL_SC2_PA1_FIFO_EMPTY = 278 +PH_PERF_SEL_SC2_PA1_FIFO_FULL = 279 +PH_PERF_SEL_SC2_PA1_NULL_WE = 280 +PH_PERF_SEL_SC2_PA1_EVENT_WE = 281 +PH_PERF_SEL_SC2_PA1_FPOV_WE = 282 +PH_PERF_SEL_SC2_PA1_FPOP_WE = 283 +PH_PERF_SEL_SC2_PA1_EOP_WE = 284 +PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD = 285 +PH_PERF_SEL_SC2_PA1_EOPG_WE = 286 +PH_PERF_SEL_SC2_PA1_DEALLOC_WE = 287 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD = 288 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE = 289 +PH_PERF_SEL_SC2_PA2_FIFO_EMPTY = 290 +PH_PERF_SEL_SC2_PA2_FIFO_FULL = 291 +PH_PERF_SEL_SC2_PA2_NULL_WE = 292 +PH_PERF_SEL_SC2_PA2_EVENT_WE = 293 +PH_PERF_SEL_SC2_PA2_FPOV_WE = 294 +PH_PERF_SEL_SC2_PA2_FPOP_WE = 295 +PH_PERF_SEL_SC2_PA2_EOP_WE = 296 +PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD = 297 +PH_PERF_SEL_SC2_PA2_EOPG_WE = 298 +PH_PERF_SEL_SC2_PA2_DEALLOC_WE = 299 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD = 300 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE = 301 +PH_PERF_SEL_SC2_PA3_FIFO_EMPTY = 302 +PH_PERF_SEL_SC2_PA3_FIFO_FULL = 303 +PH_PERF_SEL_SC2_PA3_NULL_WE = 304 +PH_PERF_SEL_SC2_PA3_EVENT_WE = 305 +PH_PERF_SEL_SC2_PA3_FPOV_WE = 306 +PH_PERF_SEL_SC2_PA3_FPOP_WE = 307 +PH_PERF_SEL_SC2_PA3_EOP_WE = 308 +PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD = 309 +PH_PERF_SEL_SC2_PA3_EOPG_WE = 310 +PH_PERF_SEL_SC2_PA3_DEALLOC_WE = 311 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD = 312 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE = 313 +PH_PERF_SEL_SC2_PA4_FIFO_EMPTY = 314 +PH_PERF_SEL_SC2_PA4_FIFO_FULL = 315 +PH_PERF_SEL_SC2_PA4_NULL_WE = 316 +PH_PERF_SEL_SC2_PA4_EVENT_WE = 317 +PH_PERF_SEL_SC2_PA4_FPOV_WE = 318 +PH_PERF_SEL_SC2_PA4_FPOP_WE = 319 +PH_PERF_SEL_SC2_PA4_EOP_WE = 320 +PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD = 321 +PH_PERF_SEL_SC2_PA4_EOPG_WE = 322 +PH_PERF_SEL_SC2_PA4_DEALLOC_WE = 323 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD = 324 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE = 325 +PH_PERF_SEL_SC2_PA5_FIFO_EMPTY = 326 +PH_PERF_SEL_SC2_PA5_FIFO_FULL = 327 +PH_PERF_SEL_SC2_PA5_NULL_WE = 328 +PH_PERF_SEL_SC2_PA5_EVENT_WE = 329 +PH_PERF_SEL_SC2_PA5_FPOV_WE = 330 +PH_PERF_SEL_SC2_PA5_FPOP_WE = 331 +PH_PERF_SEL_SC2_PA5_EOP_WE = 332 +PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD = 333 +PH_PERF_SEL_SC2_PA5_EOPG_WE = 334 +PH_PERF_SEL_SC2_PA5_DEALLOC_WE = 335 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD = 336 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE = 337 +PH_PERF_SEL_SC2_PA6_FIFO_EMPTY = 338 +PH_PERF_SEL_SC2_PA6_FIFO_FULL = 339 +PH_PERF_SEL_SC2_PA6_NULL_WE = 340 +PH_PERF_SEL_SC2_PA6_EVENT_WE = 341 +PH_PERF_SEL_SC2_PA6_FPOV_WE = 342 +PH_PERF_SEL_SC2_PA6_FPOP_WE = 343 +PH_PERF_SEL_SC2_PA6_EOP_WE = 344 +PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD = 345 +PH_PERF_SEL_SC2_PA6_EOPG_WE = 346 +PH_PERF_SEL_SC2_PA6_DEALLOC_WE = 347 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD = 348 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE = 349 +PH_PERF_SEL_SC2_PA7_FIFO_EMPTY = 350 +PH_PERF_SEL_SC2_PA7_FIFO_FULL = 351 +PH_PERF_SEL_SC2_PA7_NULL_WE = 352 +PH_PERF_SEL_SC2_PA7_EVENT_WE = 353 +PH_PERF_SEL_SC2_PA7_FPOV_WE = 354 +PH_PERF_SEL_SC2_PA7_FPOP_WE = 355 +PH_PERF_SEL_SC2_PA7_EOP_WE = 356 +PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD = 357 +PH_PERF_SEL_SC2_PA7_EOPG_WE = 358 +PH_PERF_SEL_SC2_PA7_DEALLOC_WE = 359 +PH_PERF_SEL_SC3_SRPS_WINDOW_VALID = 360 +PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 361 +PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES = 362 +PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 363 +PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW = 364 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE = 365 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 366 +PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 367 +PH_PERF_SEL_SC3_ARB_BUSY = 368 +PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP = 369 +PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP = 370 +PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP = 371 +PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE = 372 +PH_PERF_SEL_SC3_EOP_SYNC_WINDOW = 373 +PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM = 374 +PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO = 375 +PH_PERF_SEL_SC3_SEND = 376 +PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND = 377 +PH_PERF_SEL_SC3_CREDIT_AT_MAX = 378 +PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND = 379 +PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION = 380 +PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION = 381 +PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 382 +PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 383 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD = 384 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE = 385 +PH_PERF_SEL_SC3_PA0_FIFO_EMPTY = 386 +PH_PERF_SEL_SC3_PA0_FIFO_FULL = 387 +PH_PERF_SEL_SC3_PA0_NULL_WE = 388 +PH_PERF_SEL_SC3_PA0_EVENT_WE = 389 +PH_PERF_SEL_SC3_PA0_FPOV_WE = 390 +PH_PERF_SEL_SC3_PA0_FPOP_WE = 391 +PH_PERF_SEL_SC3_PA0_EOP_WE = 392 +PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD = 393 +PH_PERF_SEL_SC3_PA0_EOPG_WE = 394 +PH_PERF_SEL_SC3_PA0_DEALLOC_WE = 395 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD = 396 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE = 397 +PH_PERF_SEL_SC3_PA1_FIFO_EMPTY = 398 +PH_PERF_SEL_SC3_PA1_FIFO_FULL = 399 +PH_PERF_SEL_SC3_PA1_NULL_WE = 400 +PH_PERF_SEL_SC3_PA1_EVENT_WE = 401 +PH_PERF_SEL_SC3_PA1_FPOV_WE = 402 +PH_PERF_SEL_SC3_PA1_FPOP_WE = 403 +PH_PERF_SEL_SC3_PA1_EOP_WE = 404 +PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD = 405 +PH_PERF_SEL_SC3_PA1_EOPG_WE = 406 +PH_PERF_SEL_SC3_PA1_DEALLOC_WE = 407 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD = 408 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE = 409 +PH_PERF_SEL_SC3_PA2_FIFO_EMPTY = 410 +PH_PERF_SEL_SC3_PA2_FIFO_FULL = 411 +PH_PERF_SEL_SC3_PA2_NULL_WE = 412 +PH_PERF_SEL_SC3_PA2_EVENT_WE = 413 +PH_PERF_SEL_SC3_PA2_FPOV_WE = 414 +PH_PERF_SEL_SC3_PA2_FPOP_WE = 415 +PH_PERF_SEL_SC3_PA2_EOP_WE = 416 +PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD = 417 +PH_PERF_SEL_SC3_PA2_EOPG_WE = 418 +PH_PERF_SEL_SC3_PA2_DEALLOC_WE = 419 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD = 420 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE = 421 +PH_PERF_SEL_SC3_PA3_FIFO_EMPTY = 422 +PH_PERF_SEL_SC3_PA3_FIFO_FULL = 423 +PH_PERF_SEL_SC3_PA3_NULL_WE = 424 +PH_PERF_SEL_SC3_PA3_EVENT_WE = 425 +PH_PERF_SEL_SC3_PA3_FPOV_WE = 426 +PH_PERF_SEL_SC3_PA3_FPOP_WE = 427 +PH_PERF_SEL_SC3_PA3_EOP_WE = 428 +PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD = 429 +PH_PERF_SEL_SC3_PA3_EOPG_WE = 430 +PH_PERF_SEL_SC3_PA3_DEALLOC_WE = 431 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD = 432 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE = 433 +PH_PERF_SEL_SC3_PA4_FIFO_EMPTY = 434 +PH_PERF_SEL_SC3_PA4_FIFO_FULL = 435 +PH_PERF_SEL_SC3_PA4_NULL_WE = 436 +PH_PERF_SEL_SC3_PA4_EVENT_WE = 437 +PH_PERF_SEL_SC3_PA4_FPOV_WE = 438 +PH_PERF_SEL_SC3_PA4_FPOP_WE = 439 +PH_PERF_SEL_SC3_PA4_EOP_WE = 440 +PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD = 441 +PH_PERF_SEL_SC3_PA4_EOPG_WE = 442 +PH_PERF_SEL_SC3_PA4_DEALLOC_WE = 443 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD = 444 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE = 445 +PH_PERF_SEL_SC3_PA5_FIFO_EMPTY = 446 +PH_PERF_SEL_SC3_PA5_FIFO_FULL = 447 +PH_PERF_SEL_SC3_PA5_NULL_WE = 448 +PH_PERF_SEL_SC3_PA5_EVENT_WE = 449 +PH_PERF_SEL_SC3_PA5_FPOV_WE = 450 +PH_PERF_SEL_SC3_PA5_FPOP_WE = 451 +PH_PERF_SEL_SC3_PA5_EOP_WE = 452 +PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD = 453 +PH_PERF_SEL_SC3_PA5_EOPG_WE = 454 +PH_PERF_SEL_SC3_PA5_DEALLOC_WE = 455 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD = 456 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE = 457 +PH_PERF_SEL_SC3_PA6_FIFO_EMPTY = 458 +PH_PERF_SEL_SC3_PA6_FIFO_FULL = 459 +PH_PERF_SEL_SC3_PA6_NULL_WE = 460 +PH_PERF_SEL_SC3_PA6_EVENT_WE = 461 +PH_PERF_SEL_SC3_PA6_FPOV_WE = 462 +PH_PERF_SEL_SC3_PA6_FPOP_WE = 463 +PH_PERF_SEL_SC3_PA6_EOP_WE = 464 +PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD = 465 +PH_PERF_SEL_SC3_PA6_EOPG_WE = 466 +PH_PERF_SEL_SC3_PA6_DEALLOC_WE = 467 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD = 468 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE = 469 +PH_PERF_SEL_SC3_PA7_FIFO_EMPTY = 470 +PH_PERF_SEL_SC3_PA7_FIFO_FULL = 471 +PH_PERF_SEL_SC3_PA7_NULL_WE = 472 +PH_PERF_SEL_SC3_PA7_EVENT_WE = 473 +PH_PERF_SEL_SC3_PA7_FPOV_WE = 474 +PH_PERF_SEL_SC3_PA7_FPOP_WE = 475 +PH_PERF_SEL_SC3_PA7_EOP_WE = 476 +PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD = 477 +PH_PERF_SEL_SC3_PA7_EOPG_WE = 478 +PH_PERF_SEL_SC3_PA7_DEALLOC_WE = 479 +PH_PERF_SEL_SC4_SRPS_WINDOW_VALID = 480 +PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 481 +PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES = 482 +PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 483 +PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW = 484 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE = 485 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 486 +PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 487 +PH_PERF_SEL_SC4_ARB_BUSY = 488 +PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP = 489 +PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP = 490 +PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP = 491 +PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE = 492 +PH_PERF_SEL_SC4_EOP_SYNC_WINDOW = 493 +PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM = 494 +PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO = 495 +PH_PERF_SEL_SC4_SEND = 496 +PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND = 497 +PH_PERF_SEL_SC4_CREDIT_AT_MAX = 498 +PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND = 499 +PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION = 500 +PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION = 501 +PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 502 +PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 503 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD = 504 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE = 505 +PH_PERF_SEL_SC4_PA0_FIFO_EMPTY = 506 +PH_PERF_SEL_SC4_PA0_FIFO_FULL = 507 +PH_PERF_SEL_SC4_PA0_NULL_WE = 508 +PH_PERF_SEL_SC4_PA0_EVENT_WE = 509 +PH_PERF_SEL_SC4_PA0_FPOV_WE = 510 +PH_PERF_SEL_SC4_PA0_FPOP_WE = 511 +PH_PERF_SEL_SC4_PA0_EOP_WE = 512 +PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD = 513 +PH_PERF_SEL_SC4_PA0_EOPG_WE = 514 +PH_PERF_SEL_SC4_PA0_DEALLOC_WE = 515 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD = 516 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE = 517 +PH_PERF_SEL_SC4_PA1_FIFO_EMPTY = 518 +PH_PERF_SEL_SC4_PA1_FIFO_FULL = 519 +PH_PERF_SEL_SC4_PA1_NULL_WE = 520 +PH_PERF_SEL_SC4_PA1_EVENT_WE = 521 +PH_PERF_SEL_SC4_PA1_FPOV_WE = 522 +PH_PERF_SEL_SC4_PA1_FPOP_WE = 523 +PH_PERF_SEL_SC4_PA1_EOP_WE = 524 +PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD = 525 +PH_PERF_SEL_SC4_PA1_EOPG_WE = 526 +PH_PERF_SEL_SC4_PA1_DEALLOC_WE = 527 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD = 528 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE = 529 +PH_PERF_SEL_SC4_PA2_FIFO_EMPTY = 530 +PH_PERF_SEL_SC4_PA2_FIFO_FULL = 531 +PH_PERF_SEL_SC4_PA2_NULL_WE = 532 +PH_PERF_SEL_SC4_PA2_EVENT_WE = 533 +PH_PERF_SEL_SC4_PA2_FPOV_WE = 534 +PH_PERF_SEL_SC4_PA2_FPOP_WE = 535 +PH_PERF_SEL_SC4_PA2_EOP_WE = 536 +PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD = 537 +PH_PERF_SEL_SC4_PA2_EOPG_WE = 538 +PH_PERF_SEL_SC4_PA2_DEALLOC_WE = 539 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD = 540 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE = 541 +PH_PERF_SEL_SC4_PA3_FIFO_EMPTY = 542 +PH_PERF_SEL_SC4_PA3_FIFO_FULL = 543 +PH_PERF_SEL_SC4_PA3_NULL_WE = 544 +PH_PERF_SEL_SC4_PA3_EVENT_WE = 545 +PH_PERF_SEL_SC4_PA3_FPOV_WE = 546 +PH_PERF_SEL_SC4_PA3_FPOP_WE = 547 +PH_PERF_SEL_SC4_PA3_EOP_WE = 548 +PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD = 549 +PH_PERF_SEL_SC4_PA3_EOPG_WE = 550 +PH_PERF_SEL_SC4_PA3_DEALLOC_WE = 551 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD = 552 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE = 553 +PH_PERF_SEL_SC4_PA4_FIFO_EMPTY = 554 +PH_PERF_SEL_SC4_PA4_FIFO_FULL = 555 +PH_PERF_SEL_SC4_PA4_NULL_WE = 556 +PH_PERF_SEL_SC4_PA4_EVENT_WE = 557 +PH_PERF_SEL_SC4_PA4_FPOV_WE = 558 +PH_PERF_SEL_SC4_PA4_FPOP_WE = 559 +PH_PERF_SEL_SC4_PA4_EOP_WE = 560 +PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD = 561 +PH_PERF_SEL_SC4_PA4_EOPG_WE = 562 +PH_PERF_SEL_SC4_PA4_DEALLOC_WE = 563 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD = 564 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE = 565 +PH_PERF_SEL_SC4_PA5_FIFO_EMPTY = 566 +PH_PERF_SEL_SC4_PA5_FIFO_FULL = 567 +PH_PERF_SEL_SC4_PA5_NULL_WE = 568 +PH_PERF_SEL_SC4_PA5_EVENT_WE = 569 +PH_PERF_SEL_SC4_PA5_FPOV_WE = 570 +PH_PERF_SEL_SC4_PA5_FPOP_WE = 571 +PH_PERF_SEL_SC4_PA5_EOP_WE = 572 +PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD = 573 +PH_PERF_SEL_SC4_PA5_EOPG_WE = 574 +PH_PERF_SEL_SC4_PA5_DEALLOC_WE = 575 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD = 576 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE = 577 +PH_PERF_SEL_SC4_PA6_FIFO_EMPTY = 578 +PH_PERF_SEL_SC4_PA6_FIFO_FULL = 579 +PH_PERF_SEL_SC4_PA6_NULL_WE = 580 +PH_PERF_SEL_SC4_PA6_EVENT_WE = 581 +PH_PERF_SEL_SC4_PA6_FPOV_WE = 582 +PH_PERF_SEL_SC4_PA6_FPOP_WE = 583 +PH_PERF_SEL_SC4_PA6_EOP_WE = 584 +PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD = 585 +PH_PERF_SEL_SC4_PA6_EOPG_WE = 586 +PH_PERF_SEL_SC4_PA6_DEALLOC_WE = 587 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD = 588 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE = 589 +PH_PERF_SEL_SC4_PA7_FIFO_EMPTY = 590 +PH_PERF_SEL_SC4_PA7_FIFO_FULL = 591 +PH_PERF_SEL_SC4_PA7_NULL_WE = 592 +PH_PERF_SEL_SC4_PA7_EVENT_WE = 593 +PH_PERF_SEL_SC4_PA7_FPOV_WE = 594 +PH_PERF_SEL_SC4_PA7_FPOP_WE = 595 +PH_PERF_SEL_SC4_PA7_EOP_WE = 596 +PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD = 597 +PH_PERF_SEL_SC4_PA7_EOPG_WE = 598 +PH_PERF_SEL_SC4_PA7_DEALLOC_WE = 599 +PH_PERF_SEL_SC5_SRPS_WINDOW_VALID = 600 +PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 601 +PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES = 602 +PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 603 +PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW = 604 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE = 605 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 606 +PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 607 +PH_PERF_SEL_SC5_ARB_BUSY = 608 +PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP = 609 +PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP = 610 +PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP = 611 +PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE = 612 +PH_PERF_SEL_SC5_EOP_SYNC_WINDOW = 613 +PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM = 614 +PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO = 615 +PH_PERF_SEL_SC5_SEND = 616 +PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND = 617 +PH_PERF_SEL_SC5_CREDIT_AT_MAX = 618 +PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND = 619 +PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION = 620 +PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION = 621 +PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 622 +PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 623 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD = 624 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE = 625 +PH_PERF_SEL_SC5_PA0_FIFO_EMPTY = 626 +PH_PERF_SEL_SC5_PA0_FIFO_FULL = 627 +PH_PERF_SEL_SC5_PA0_NULL_WE = 628 +PH_PERF_SEL_SC5_PA0_EVENT_WE = 629 +PH_PERF_SEL_SC5_PA0_FPOV_WE = 630 +PH_PERF_SEL_SC5_PA0_FPOP_WE = 631 +PH_PERF_SEL_SC5_PA0_EOP_WE = 632 +PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD = 633 +PH_PERF_SEL_SC5_PA0_EOPG_WE = 634 +PH_PERF_SEL_SC5_PA0_DEALLOC_WE = 635 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD = 636 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE = 637 +PH_PERF_SEL_SC5_PA1_FIFO_EMPTY = 638 +PH_PERF_SEL_SC5_PA1_FIFO_FULL = 639 +PH_PERF_SEL_SC5_PA1_NULL_WE = 640 +PH_PERF_SEL_SC5_PA1_EVENT_WE = 641 +PH_PERF_SEL_SC5_PA1_FPOV_WE = 642 +PH_PERF_SEL_SC5_PA1_FPOP_WE = 643 +PH_PERF_SEL_SC5_PA1_EOP_WE = 644 +PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD = 645 +PH_PERF_SEL_SC5_PA1_EOPG_WE = 646 +PH_PERF_SEL_SC5_PA1_DEALLOC_WE = 647 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD = 648 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE = 649 +PH_PERF_SEL_SC5_PA2_FIFO_EMPTY = 650 +PH_PERF_SEL_SC5_PA2_FIFO_FULL = 651 +PH_PERF_SEL_SC5_PA2_NULL_WE = 652 +PH_PERF_SEL_SC5_PA2_EVENT_WE = 653 +PH_PERF_SEL_SC5_PA2_FPOV_WE = 654 +PH_PERF_SEL_SC5_PA2_FPOP_WE = 655 +PH_PERF_SEL_SC5_PA2_EOP_WE = 656 +PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD = 657 +PH_PERF_SEL_SC5_PA2_EOPG_WE = 658 +PH_PERF_SEL_SC5_PA2_DEALLOC_WE = 659 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD = 660 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE = 661 +PH_PERF_SEL_SC5_PA3_FIFO_EMPTY = 662 +PH_PERF_SEL_SC5_PA3_FIFO_FULL = 663 +PH_PERF_SEL_SC5_PA3_NULL_WE = 664 +PH_PERF_SEL_SC5_PA3_EVENT_WE = 665 +PH_PERF_SEL_SC5_PA3_FPOV_WE = 666 +PH_PERF_SEL_SC5_PA3_FPOP_WE = 667 +PH_PERF_SEL_SC5_PA3_EOP_WE = 668 +PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD = 669 +PH_PERF_SEL_SC5_PA3_EOPG_WE = 670 +PH_PERF_SEL_SC5_PA3_DEALLOC_WE = 671 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD = 672 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE = 673 +PH_PERF_SEL_SC5_PA4_FIFO_EMPTY = 674 +PH_PERF_SEL_SC5_PA4_FIFO_FULL = 675 +PH_PERF_SEL_SC5_PA4_NULL_WE = 676 +PH_PERF_SEL_SC5_PA4_EVENT_WE = 677 +PH_PERF_SEL_SC5_PA4_FPOV_WE = 678 +PH_PERF_SEL_SC5_PA4_FPOP_WE = 679 +PH_PERF_SEL_SC5_PA4_EOP_WE = 680 +PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD = 681 +PH_PERF_SEL_SC5_PA4_EOPG_WE = 682 +PH_PERF_SEL_SC5_PA4_DEALLOC_WE = 683 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD = 684 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE = 685 +PH_PERF_SEL_SC5_PA5_FIFO_EMPTY = 686 +PH_PERF_SEL_SC5_PA5_FIFO_FULL = 687 +PH_PERF_SEL_SC5_PA5_NULL_WE = 688 +PH_PERF_SEL_SC5_PA5_EVENT_WE = 689 +PH_PERF_SEL_SC5_PA5_FPOV_WE = 690 +PH_PERF_SEL_SC5_PA5_FPOP_WE = 691 +PH_PERF_SEL_SC5_PA5_EOP_WE = 692 +PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD = 693 +PH_PERF_SEL_SC5_PA5_EOPG_WE = 694 +PH_PERF_SEL_SC5_PA5_DEALLOC_WE = 695 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD = 696 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE = 697 +PH_PERF_SEL_SC5_PA6_FIFO_EMPTY = 698 +PH_PERF_SEL_SC5_PA6_FIFO_FULL = 699 +PH_PERF_SEL_SC5_PA6_NULL_WE = 700 +PH_PERF_SEL_SC5_PA6_EVENT_WE = 701 +PH_PERF_SEL_SC5_PA6_FPOV_WE = 702 +PH_PERF_SEL_SC5_PA6_FPOP_WE = 703 +PH_PERF_SEL_SC5_PA6_EOP_WE = 704 +PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD = 705 +PH_PERF_SEL_SC5_PA6_EOPG_WE = 706 +PH_PERF_SEL_SC5_PA6_DEALLOC_WE = 707 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD = 708 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE = 709 +PH_PERF_SEL_SC5_PA7_FIFO_EMPTY = 710 +PH_PERF_SEL_SC5_PA7_FIFO_FULL = 711 +PH_PERF_SEL_SC5_PA7_NULL_WE = 712 +PH_PERF_SEL_SC5_PA7_EVENT_WE = 713 +PH_PERF_SEL_SC5_PA7_FPOV_WE = 714 +PH_PERF_SEL_SC5_PA7_FPOP_WE = 715 +PH_PERF_SEL_SC5_PA7_EOP_WE = 716 +PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD = 717 +PH_PERF_SEL_SC5_PA7_EOPG_WE = 718 +PH_PERF_SEL_SC5_PA7_DEALLOC_WE = 719 +PH_PERF_SEL_SC6_SRPS_WINDOW_VALID = 720 +PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 721 +PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES = 722 +PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 723 +PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW = 724 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE = 725 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 726 +PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 727 +PH_PERF_SEL_SC6_ARB_BUSY = 728 +PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP = 729 +PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP = 730 +PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP = 731 +PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE = 732 +PH_PERF_SEL_SC6_EOP_SYNC_WINDOW = 733 +PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM = 734 +PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO = 735 +PH_PERF_SEL_SC6_SEND = 736 +PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND = 737 +PH_PERF_SEL_SC6_CREDIT_AT_MAX = 738 +PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND = 739 +PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION = 740 +PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION = 741 +PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 742 +PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 743 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD = 744 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE = 745 +PH_PERF_SEL_SC6_PA0_FIFO_EMPTY = 746 +PH_PERF_SEL_SC6_PA0_FIFO_FULL = 747 +PH_PERF_SEL_SC6_PA0_NULL_WE = 748 +PH_PERF_SEL_SC6_PA0_EVENT_WE = 749 +PH_PERF_SEL_SC6_PA0_FPOV_WE = 750 +PH_PERF_SEL_SC6_PA0_FPOP_WE = 751 +PH_PERF_SEL_SC6_PA0_EOP_WE = 752 +PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD = 753 +PH_PERF_SEL_SC6_PA0_EOPG_WE = 754 +PH_PERF_SEL_SC6_PA0_DEALLOC_WE = 755 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD = 756 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE = 757 +PH_PERF_SEL_SC6_PA1_FIFO_EMPTY = 758 +PH_PERF_SEL_SC6_PA1_FIFO_FULL = 759 +PH_PERF_SEL_SC6_PA1_NULL_WE = 760 +PH_PERF_SEL_SC6_PA1_EVENT_WE = 761 +PH_PERF_SEL_SC6_PA1_FPOV_WE = 762 +PH_PERF_SEL_SC6_PA1_FPOP_WE = 763 +PH_PERF_SEL_SC6_PA1_EOP_WE = 764 +PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD = 765 +PH_PERF_SEL_SC6_PA1_EOPG_WE = 766 +PH_PERF_SEL_SC6_PA1_DEALLOC_WE = 767 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD = 768 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE = 769 +PH_PERF_SEL_SC6_PA2_FIFO_EMPTY = 770 +PH_PERF_SEL_SC6_PA2_FIFO_FULL = 771 +PH_PERF_SEL_SC6_PA2_NULL_WE = 772 +PH_PERF_SEL_SC6_PA2_EVENT_WE = 773 +PH_PERF_SEL_SC6_PA2_FPOV_WE = 774 +PH_PERF_SEL_SC6_PA2_FPOP_WE = 775 +PH_PERF_SEL_SC6_PA2_EOP_WE = 776 +PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD = 777 +PH_PERF_SEL_SC6_PA2_EOPG_WE = 778 +PH_PERF_SEL_SC6_PA2_DEALLOC_WE = 779 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD = 780 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE = 781 +PH_PERF_SEL_SC6_PA3_FIFO_EMPTY = 782 +PH_PERF_SEL_SC6_PA3_FIFO_FULL = 783 +PH_PERF_SEL_SC6_PA3_NULL_WE = 784 +PH_PERF_SEL_SC6_PA3_EVENT_WE = 785 +PH_PERF_SEL_SC6_PA3_FPOV_WE = 786 +PH_PERF_SEL_SC6_PA3_FPOP_WE = 787 +PH_PERF_SEL_SC6_PA3_EOP_WE = 788 +PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD = 789 +PH_PERF_SEL_SC6_PA3_EOPG_WE = 790 +PH_PERF_SEL_SC6_PA3_DEALLOC_WE = 791 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD = 792 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE = 793 +PH_PERF_SEL_SC6_PA4_FIFO_EMPTY = 794 +PH_PERF_SEL_SC6_PA4_FIFO_FULL = 795 +PH_PERF_SEL_SC6_PA4_NULL_WE = 796 +PH_PERF_SEL_SC6_PA4_EVENT_WE = 797 +PH_PERF_SEL_SC6_PA4_FPOV_WE = 798 +PH_PERF_SEL_SC6_PA4_FPOP_WE = 799 +PH_PERF_SEL_SC6_PA4_EOP_WE = 800 +PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD = 801 +PH_PERF_SEL_SC6_PA4_EOPG_WE = 802 +PH_PERF_SEL_SC6_PA4_DEALLOC_WE = 803 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD = 804 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE = 805 +PH_PERF_SEL_SC6_PA5_FIFO_EMPTY = 806 +PH_PERF_SEL_SC6_PA5_FIFO_FULL = 807 +PH_PERF_SEL_SC6_PA5_NULL_WE = 808 +PH_PERF_SEL_SC6_PA5_EVENT_WE = 809 +PH_PERF_SEL_SC6_PA5_FPOV_WE = 810 +PH_PERF_SEL_SC6_PA5_FPOP_WE = 811 +PH_PERF_SEL_SC6_PA5_EOP_WE = 812 +PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD = 813 +PH_PERF_SEL_SC6_PA5_EOPG_WE = 814 +PH_PERF_SEL_SC6_PA5_DEALLOC_WE = 815 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD = 816 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE = 817 +PH_PERF_SEL_SC6_PA6_FIFO_EMPTY = 818 +PH_PERF_SEL_SC6_PA6_FIFO_FULL = 819 +PH_PERF_SEL_SC6_PA6_NULL_WE = 820 +PH_PERF_SEL_SC6_PA6_EVENT_WE = 821 +PH_PERF_SEL_SC6_PA6_FPOV_WE = 822 +PH_PERF_SEL_SC6_PA6_FPOP_WE = 823 +PH_PERF_SEL_SC6_PA6_EOP_WE = 824 +PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD = 825 +PH_PERF_SEL_SC6_PA6_EOPG_WE = 826 +PH_PERF_SEL_SC6_PA6_DEALLOC_WE = 827 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD = 828 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE = 829 +PH_PERF_SEL_SC6_PA7_FIFO_EMPTY = 830 +PH_PERF_SEL_SC6_PA7_FIFO_FULL = 831 +PH_PERF_SEL_SC6_PA7_NULL_WE = 832 +PH_PERF_SEL_SC6_PA7_EVENT_WE = 833 +PH_PERF_SEL_SC6_PA7_FPOV_WE = 834 +PH_PERF_SEL_SC6_PA7_FPOP_WE = 835 +PH_PERF_SEL_SC6_PA7_EOP_WE = 836 +PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD = 837 +PH_PERF_SEL_SC6_PA7_EOPG_WE = 838 +PH_PERF_SEL_SC6_PA7_DEALLOC_WE = 839 +PH_PERF_SEL_SC7_SRPS_WINDOW_VALID = 840 +PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 841 +PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES = 842 +PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 843 +PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW = 844 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE = 845 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 846 +PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 847 +PH_PERF_SEL_SC7_ARB_BUSY = 848 +PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP = 849 +PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP = 850 +PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP = 851 +PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE = 852 +PH_PERF_SEL_SC7_EOP_SYNC_WINDOW = 853 +PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM = 854 +PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO = 855 +PH_PERF_SEL_SC7_SEND = 856 +PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND = 857 +PH_PERF_SEL_SC7_CREDIT_AT_MAX = 858 +PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND = 859 +PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION = 860 +PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION = 861 +PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION = 862 +PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION = 863 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD = 864 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE = 865 +PH_PERF_SEL_SC7_PA0_FIFO_EMPTY = 866 +PH_PERF_SEL_SC7_PA0_FIFO_FULL = 867 +PH_PERF_SEL_SC7_PA0_NULL_WE = 868 +PH_PERF_SEL_SC7_PA0_EVENT_WE = 869 +PH_PERF_SEL_SC7_PA0_FPOV_WE = 870 +PH_PERF_SEL_SC7_PA0_FPOP_WE = 871 +PH_PERF_SEL_SC7_PA0_EOP_WE = 872 +PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD = 873 +PH_PERF_SEL_SC7_PA0_EOPG_WE = 874 +PH_PERF_SEL_SC7_PA0_DEALLOC_WE = 875 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD = 876 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE = 877 +PH_PERF_SEL_SC7_PA1_FIFO_EMPTY = 878 +PH_PERF_SEL_SC7_PA1_FIFO_FULL = 879 +PH_PERF_SEL_SC7_PA1_NULL_WE = 880 +PH_PERF_SEL_SC7_PA1_EVENT_WE = 881 +PH_PERF_SEL_SC7_PA1_FPOV_WE = 882 +PH_PERF_SEL_SC7_PA1_FPOP_WE = 883 +PH_PERF_SEL_SC7_PA1_EOP_WE = 884 +PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD = 885 +PH_PERF_SEL_SC7_PA1_EOPG_WE = 886 +PH_PERF_SEL_SC7_PA1_DEALLOC_WE = 887 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD = 888 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE = 889 +PH_PERF_SEL_SC7_PA2_FIFO_EMPTY = 890 +PH_PERF_SEL_SC7_PA2_FIFO_FULL = 891 +PH_PERF_SEL_SC7_PA2_NULL_WE = 892 +PH_PERF_SEL_SC7_PA2_EVENT_WE = 893 +PH_PERF_SEL_SC7_PA2_FPOV_WE = 894 +PH_PERF_SEL_SC7_PA2_FPOP_WE = 895 +PH_PERF_SEL_SC7_PA2_EOP_WE = 896 +PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD = 897 +PH_PERF_SEL_SC7_PA2_EOPG_WE = 898 +PH_PERF_SEL_SC7_PA2_DEALLOC_WE = 899 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD = 900 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE = 901 +PH_PERF_SEL_SC7_PA3_FIFO_EMPTY = 902 +PH_PERF_SEL_SC7_PA3_FIFO_FULL = 903 +PH_PERF_SEL_SC7_PA3_NULL_WE = 904 +PH_PERF_SEL_SC7_PA3_EVENT_WE = 905 +PH_PERF_SEL_SC7_PA3_FPOV_WE = 906 +PH_PERF_SEL_SC7_PA3_FPOP_WE = 907 +PH_PERF_SEL_SC7_PA3_EOP_WE = 908 +PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD = 909 +PH_PERF_SEL_SC7_PA3_EOPG_WE = 910 +PH_PERF_SEL_SC7_PA3_DEALLOC_WE = 911 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD = 912 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE = 913 +PH_PERF_SEL_SC7_PA4_FIFO_EMPTY = 914 +PH_PERF_SEL_SC7_PA4_FIFO_FULL = 915 +PH_PERF_SEL_SC7_PA4_NULL_WE = 916 +PH_PERF_SEL_SC7_PA4_EVENT_WE = 917 +PH_PERF_SEL_SC7_PA4_FPOV_WE = 918 +PH_PERF_SEL_SC7_PA4_FPOP_WE = 919 +PH_PERF_SEL_SC7_PA4_EOP_WE = 920 +PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD = 921 +PH_PERF_SEL_SC7_PA4_EOPG_WE = 922 +PH_PERF_SEL_SC7_PA4_DEALLOC_WE = 923 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD = 924 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE = 925 +PH_PERF_SEL_SC7_PA5_FIFO_EMPTY = 926 +PH_PERF_SEL_SC7_PA5_FIFO_FULL = 927 +PH_PERF_SEL_SC7_PA5_NULL_WE = 928 +PH_PERF_SEL_SC7_PA5_EVENT_WE = 929 +PH_PERF_SEL_SC7_PA5_FPOV_WE = 930 +PH_PERF_SEL_SC7_PA5_FPOP_WE = 931 +PH_PERF_SEL_SC7_PA5_EOP_WE = 932 +PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD = 933 +PH_PERF_SEL_SC7_PA5_EOPG_WE = 934 +PH_PERF_SEL_SC7_PA5_DEALLOC_WE = 935 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD = 936 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE = 937 +PH_PERF_SEL_SC7_PA6_FIFO_EMPTY = 938 +PH_PERF_SEL_SC7_PA6_FIFO_FULL = 939 +PH_PERF_SEL_SC7_PA6_NULL_WE = 940 +PH_PERF_SEL_SC7_PA6_EVENT_WE = 941 +PH_PERF_SEL_SC7_PA6_FPOV_WE = 942 +PH_PERF_SEL_SC7_PA6_FPOP_WE = 943 +PH_PERF_SEL_SC7_PA6_EOP_WE = 944 +PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD = 945 +PH_PERF_SEL_SC7_PA6_EOPG_WE = 946 +PH_PERF_SEL_SC7_PA6_DEALLOC_WE = 947 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD = 948 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE = 949 +PH_PERF_SEL_SC7_PA7_FIFO_EMPTY = 950 +PH_PERF_SEL_SC7_PA7_FIFO_FULL = 951 +PH_PERF_SEL_SC7_PA7_NULL_WE = 952 +PH_PERF_SEL_SC7_PA7_EVENT_WE = 953 +PH_PERF_SEL_SC7_PA7_FPOV_WE = 954 +PH_PERF_SEL_SC7_PA7_FPOP_WE = 955 +PH_PERF_SEL_SC7_PA7_EOP_WE = 956 +PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD = 957 +PH_PERF_SEL_SC7_PA7_EOPG_WE = 958 +PH_PERF_SEL_SC7_PA7_DEALLOC_WE = 959 +PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW = 960 +PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW = 961 +PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW = 962 +PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW = 963 +PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW = 964 +PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW = 965 +PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW = 966 +PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW = 967 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE = 968 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE = 969 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE = 970 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE = 971 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE = 972 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE = 973 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE = 974 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE = 975 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 976 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 977 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 978 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 979 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 980 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 981 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 982 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY = 983 +PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 984 +PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 985 +PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 986 +PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 987 +PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 988 +PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 989 +PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 990 +PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL = 991 +PH_PERF_SC0_FIFO_STATUS_0 = 992 +PH_PERF_SC0_FIFO_STATUS_1 = 993 +PH_PERF_SC0_FIFO_STATUS_2 = 994 +PH_PERF_SC0_FIFO_STATUS_3 = 995 +PH_PERF_SC1_FIFO_STATUS_0 = 996 +PH_PERF_SC1_FIFO_STATUS_1 = 997 +PH_PERF_SC1_FIFO_STATUS_2 = 998 +PH_PERF_SC1_FIFO_STATUS_3 = 999 +PH_PERF_SC2_FIFO_STATUS_0 = 1000 +PH_PERF_SC2_FIFO_STATUS_1 = 1001 +PH_PERF_SC2_FIFO_STATUS_2 = 1002 +PH_PERF_SC2_FIFO_STATUS_3 = 1003 +PH_PERF_SC3_FIFO_STATUS_0 = 1004 +PH_PERF_SC3_FIFO_STATUS_1 = 1005 +PH_PERF_SC3_FIFO_STATUS_2 = 1006 +PH_PERF_SC3_FIFO_STATUS_3 = 1007 +PH_PERF_SC4_FIFO_STATUS_0 = 1008 +PH_PERF_SC4_FIFO_STATUS_1 = 1009 +PH_PERF_SC4_FIFO_STATUS_2 = 1010 +PH_PERF_SC4_FIFO_STATUS_3 = 1011 +PH_PERF_SC5_FIFO_STATUS_0 = 1012 +PH_PERF_SC5_FIFO_STATUS_1 = 1013 +PH_PERF_SC5_FIFO_STATUS_2 = 1014 +PH_PERF_SC5_FIFO_STATUS_3 = 1015 +PH_PERF_SC6_FIFO_STATUS_0 = 1016 +PH_PERF_SC6_FIFO_STATUS_1 = 1017 +PH_PERF_SC6_FIFO_STATUS_2 = 1018 +PH_PERF_SC6_FIFO_STATUS_3 = 1019 +PH_PERF_SC7_FIFO_STATUS_0 = 1020 +PH_PERF_SC7_FIFO_STATUS_1 = 1021 +PH_PERF_SC7_FIFO_STATUS_2 = 1022 +PH_PERF_SC7_FIFO_STATUS_3 = 1023 +PH_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PhSPIstatusMode' +PhSPIstatusMode__enumvalues = { + 0: 'PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT', + 1: 'PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT', + 2: 'PH_SPI_MODE_DISABLED', +} +PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT = 0 +PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT = 1 +PH_SPI_MODE_DISABLED = 2 +PhSPIstatusMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinEventCntl' +BinEventCntl__enumvalues = { + 0: 'BINNER_BREAK_BATCH', + 1: 'BINNER_PIPELINE', + 2: 'BINNER_DROP', + 3: 'BINNER_PIPELINE_BREAK', +} +BINNER_BREAK_BATCH = 0 +BINNER_PIPELINE = 1 +BINNER_DROP = 2 +BINNER_PIPELINE_BREAK = 3 +BinEventCntl = ctypes.c_uint32 # enum + +# values for enumeration 'BinMapMode' +BinMapMode__enumvalues = { + 0: 'BIN_MAP_MODE_NONE', + 1: 'BIN_MAP_MODE_RTA_INDEX', + 2: 'BIN_MAP_MODE_POPS', +} +BIN_MAP_MODE_NONE = 0 +BIN_MAP_MODE_RTA_INDEX = 1 +BIN_MAP_MODE_POPS = 2 +BinMapMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinSizeExtend' +BinSizeExtend__enumvalues = { + 0: 'BIN_SIZE_32_PIXELS', + 1: 'BIN_SIZE_64_PIXELS', + 2: 'BIN_SIZE_128_PIXELS', + 3: 'BIN_SIZE_256_PIXELS', + 4: 'BIN_SIZE_512_PIXELS', +} +BIN_SIZE_32_PIXELS = 0 +BIN_SIZE_64_PIXELS = 1 +BIN_SIZE_128_PIXELS = 2 +BIN_SIZE_256_PIXELS = 3 +BIN_SIZE_512_PIXELS = 4 +BinSizeExtend = ctypes.c_uint32 # enum + +# values for enumeration 'BinningMode' +BinningMode__enumvalues = { + 0: 'BINNING_ALLOWED', + 1: 'FORCE_BINNING_ON', + 2: 'BINNING_ONE_PRIM_PER_BATCH', + 3: 'BINNING_DISABLED', +} +BINNING_ALLOWED = 0 +FORCE_BINNING_ON = 1 +BINNING_ONE_PRIM_PER_BATCH = 2 +BINNING_DISABLED = 3 +BinningMode = ctypes.c_uint32 # enum + +# values for enumeration 'PkrMap' +PkrMap__enumvalues = { + 0: 'RASTER_CONFIG_PKR_MAP_0', + 1: 'RASTER_CONFIG_PKR_MAP_1', + 2: 'RASTER_CONFIG_PKR_MAP_2', + 3: 'RASTER_CONFIG_PKR_MAP_3', +} +RASTER_CONFIG_PKR_MAP_0 = 0 +RASTER_CONFIG_PKR_MAP_1 = 1 +RASTER_CONFIG_PKR_MAP_2 = 2 +RASTER_CONFIG_PKR_MAP_3 = 3 +PkrMap = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel' +PkrXsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL_0', + 1: 'RASTER_CONFIG_PKR_XSEL_1', + 2: 'RASTER_CONFIG_PKR_XSEL_2', + 3: 'RASTER_CONFIG_PKR_XSEL_3', +} +RASTER_CONFIG_PKR_XSEL_0 = 0 +RASTER_CONFIG_PKR_XSEL_1 = 1 +RASTER_CONFIG_PKR_XSEL_2 = 2 +RASTER_CONFIG_PKR_XSEL_3 = 3 +PkrXsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel2' +PkrXsel2__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL2_0', + 1: 'RASTER_CONFIG_PKR_XSEL2_1', + 2: 'RASTER_CONFIG_PKR_XSEL2_2', + 3: 'RASTER_CONFIG_PKR_XSEL2_3', +} +RASTER_CONFIG_PKR_XSEL2_0 = 0 +RASTER_CONFIG_PKR_XSEL2_1 = 1 +RASTER_CONFIG_PKR_XSEL2_2 = 2 +RASTER_CONFIG_PKR_XSEL2_3 = 3 +PkrXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'PkrYsel' +PkrYsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_YSEL_0', + 1: 'RASTER_CONFIG_PKR_YSEL_1', + 2: 'RASTER_CONFIG_PKR_YSEL_2', + 3: 'RASTER_CONFIG_PKR_YSEL_3', +} +RASTER_CONFIG_PKR_YSEL_0 = 0 +RASTER_CONFIG_PKR_YSEL_1 = 1 +RASTER_CONFIG_PKR_YSEL_2 = 2 +RASTER_CONFIG_PKR_YSEL_3 = 3 +PkrYsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbMap' +RbMap__enumvalues = { + 0: 'RASTER_CONFIG_RB_MAP_0', + 1: 'RASTER_CONFIG_RB_MAP_1', + 2: 'RASTER_CONFIG_RB_MAP_2', + 3: 'RASTER_CONFIG_RB_MAP_3', +} +RASTER_CONFIG_RB_MAP_0 = 0 +RASTER_CONFIG_RB_MAP_1 = 1 +RASTER_CONFIG_RB_MAP_2 = 2 +RASTER_CONFIG_RB_MAP_3 = 3 +RbMap = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel' +RbXsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL_0', + 1: 'RASTER_CONFIG_RB_XSEL_1', +} +RASTER_CONFIG_RB_XSEL_0 = 0 +RASTER_CONFIG_RB_XSEL_1 = 1 +RbXsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel2' +RbXsel2__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL2_0', + 1: 'RASTER_CONFIG_RB_XSEL2_1', + 2: 'RASTER_CONFIG_RB_XSEL2_2', + 3: 'RASTER_CONFIG_RB_XSEL2_3', +} +RASTER_CONFIG_RB_XSEL2_0 = 0 +RASTER_CONFIG_RB_XSEL2_1 = 1 +RASTER_CONFIG_RB_XSEL2_2 = 2 +RASTER_CONFIG_RB_XSEL2_3 = 3 +RbXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'RbYsel' +RbYsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_YSEL_0', + 1: 'RASTER_CONFIG_RB_YSEL_1', +} +RASTER_CONFIG_RB_YSEL_0 = 0 +RASTER_CONFIG_RB_YSEL_1 = 1 +RbYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SC_PERFCNT_SEL' +SC_PERFCNT_SEL__enumvalues = { + 0: 'SC_SRPS_WINDOW_VALID', + 1: 'SC_PSSW_WINDOW_VALID', + 2: 'SC_TPQZ_WINDOW_VALID', + 3: 'SC_QZQP_WINDOW_VALID', + 4: 'SC_TRPK_WINDOW_VALID', + 5: 'SC_SRPS_WINDOW_VALID_BUSY', + 6: 'SC_PSSW_WINDOW_VALID_BUSY', + 7: 'SC_TPQZ_WINDOW_VALID_BUSY', + 8: 'SC_QZQP_WINDOW_VALID_BUSY', + 9: 'SC_TRPK_WINDOW_VALID_BUSY', + 10: 'SC_STARVED_BY_PA', + 11: 'SC_STALLED_BY_PRIMFIFO', + 12: 'SC_STALLED_BY_DB_TILE', + 13: 'SC_STARVED_BY_DB_TILE', + 14: 'SC_STALLED_BY_TILEORDERFIFO', + 15: 'SC_STALLED_BY_TILEFIFO', + 16: 'SC_STALLED_BY_DB_QUAD', + 17: 'SC_STARVED_BY_DB_QUAD', + 18: 'SC_STALLED_BY_QUADFIFO', + 19: 'SC_STALLED_BY_BCI', + 20: 'SC_STALLED_BY_SPI', + 21: 'SC_SCISSOR_DISCARD', + 22: 'SC_BB_DISCARD', + 23: 'SC_SUPERTILE_COUNT', + 24: 'SC_SUPERTILE_PER_PRIM_H0', + 25: 'SC_SUPERTILE_PER_PRIM_H1', + 26: 'SC_SUPERTILE_PER_PRIM_H2', + 27: 'SC_SUPERTILE_PER_PRIM_H3', + 28: 'SC_SUPERTILE_PER_PRIM_H4', + 29: 'SC_SUPERTILE_PER_PRIM_H5', + 30: 'SC_SUPERTILE_PER_PRIM_H6', + 31: 'SC_SUPERTILE_PER_PRIM_H7', + 32: 'SC_SUPERTILE_PER_PRIM_H8', + 33: 'SC_SUPERTILE_PER_PRIM_H9', + 34: 'SC_SUPERTILE_PER_PRIM_H10', + 35: 'SC_SUPERTILE_PER_PRIM_H11', + 36: 'SC_SUPERTILE_PER_PRIM_H12', + 37: 'SC_SUPERTILE_PER_PRIM_H13', + 38: 'SC_SUPERTILE_PER_PRIM_H14', + 39: 'SC_SUPERTILE_PER_PRIM_H15', + 40: 'SC_SUPERTILE_PER_PRIM_H16', + 41: 'SC_TILE_PER_PRIM_H0', + 42: 'SC_TILE_PER_PRIM_H1', + 43: 'SC_TILE_PER_PRIM_H2', + 44: 'SC_TILE_PER_PRIM_H3', + 45: 'SC_TILE_PER_PRIM_H4', + 46: 'SC_TILE_PER_PRIM_H5', + 47: 'SC_TILE_PER_PRIM_H6', + 48: 'SC_TILE_PER_PRIM_H7', + 49: 'SC_TILE_PER_PRIM_H8', + 50: 'SC_TILE_PER_PRIM_H9', + 51: 'SC_TILE_PER_PRIM_H10', + 52: 'SC_TILE_PER_PRIM_H11', + 53: 'SC_TILE_PER_PRIM_H12', + 54: 'SC_TILE_PER_PRIM_H13', + 55: 'SC_TILE_PER_PRIM_H14', + 56: 'SC_TILE_PER_PRIM_H15', + 57: 'SC_TILE_PER_PRIM_H16', + 58: 'SC_TILE_PER_SUPERTILE_H0', + 59: 'SC_TILE_PER_SUPERTILE_H1', + 60: 'SC_TILE_PER_SUPERTILE_H2', + 61: 'SC_TILE_PER_SUPERTILE_H3', + 62: 'SC_TILE_PER_SUPERTILE_H4', + 63: 'SC_TILE_PER_SUPERTILE_H5', + 64: 'SC_TILE_PER_SUPERTILE_H6', + 65: 'SC_TILE_PER_SUPERTILE_H7', + 66: 'SC_TILE_PER_SUPERTILE_H8', + 67: 'SC_TILE_PER_SUPERTILE_H9', + 68: 'SC_TILE_PER_SUPERTILE_H10', + 69: 'SC_TILE_PER_SUPERTILE_H11', + 70: 'SC_TILE_PER_SUPERTILE_H12', + 71: 'SC_TILE_PER_SUPERTILE_H13', + 72: 'SC_TILE_PER_SUPERTILE_H14', + 73: 'SC_TILE_PER_SUPERTILE_H15', + 74: 'SC_TILE_PER_SUPERTILE_H16', + 75: 'SC_TILE_PICKED_H1', + 76: 'SC_PERF_SEL_RESERVED_76', + 77: 'SC_PERF_SEL_RESERVED_77', + 78: 'SC_PERF_SEL_RESERVED_78', + 79: 'SC_QZ0_TILE_COUNT', + 80: 'SC_PERF_SEL_RESERVED_80', + 81: 'SC_PERF_SEL_RESERVED_81', + 82: 'SC_PERF_SEL_RESERVED_82', + 83: 'SC_QZ0_TILE_COVERED_COUNT', + 84: 'SC_PERF_SEL_RESERVED_84', + 85: 'SC_PERF_SEL_RESERVED_85', + 86: 'SC_PERF_SEL_RESERVED_86', + 87: 'SC_QZ0_TILE_NOT_COVERED_COUNT', + 88: 'SC_PERF_SEL_RESERVED_88', + 89: 'SC_PERF_SEL_RESERVED_89', + 90: 'SC_PERF_SEL_RESERVED_90', + 91: 'SC_QZ0_QUAD_PER_TILE_H0', + 92: 'SC_QZ0_QUAD_PER_TILE_H1', + 93: 'SC_QZ0_QUAD_PER_TILE_H2', + 94: 'SC_QZ0_QUAD_PER_TILE_H3', + 95: 'SC_QZ0_QUAD_PER_TILE_H4', + 96: 'SC_QZ0_QUAD_PER_TILE_H5', + 97: 'SC_QZ0_QUAD_PER_TILE_H6', + 98: 'SC_QZ0_QUAD_PER_TILE_H7', + 99: 'SC_QZ0_QUAD_PER_TILE_H8', + 100: 'SC_QZ0_QUAD_PER_TILE_H9', + 101: 'SC_QZ0_QUAD_PER_TILE_H10', + 102: 'SC_QZ0_QUAD_PER_TILE_H11', + 103: 'SC_QZ0_QUAD_PER_TILE_H12', + 104: 'SC_QZ0_QUAD_PER_TILE_H13', + 105: 'SC_QZ0_QUAD_PER_TILE_H14', + 106: 'SC_QZ0_QUAD_PER_TILE_H15', + 107: 'SC_QZ0_QUAD_PER_TILE_H16', + 108: 'SC_PERF_SEL_RESERVED_108', + 109: 'SC_PERF_SEL_RESERVED_109', + 110: 'SC_PERF_SEL_RESERVED_110', + 111: 'SC_PERF_SEL_RESERVED_111', + 112: 'SC_PERF_SEL_RESERVED_112', + 113: 'SC_PERF_SEL_RESERVED_113', + 114: 'SC_PERF_SEL_RESERVED_114', + 115: 'SC_PERF_SEL_RESERVED_115', + 116: 'SC_PERF_SEL_RESERVED_116', + 117: 'SC_PERF_SEL_RESERVED_117', + 118: 'SC_PERF_SEL_RESERVED_118', + 119: 'SC_PERF_SEL_RESERVED_119', + 120: 'SC_PERF_SEL_RESERVED_120', + 121: 'SC_PERF_SEL_RESERVED_121', + 122: 'SC_PERF_SEL_RESERVED_122', + 123: 'SC_PERF_SEL_RESERVED_123', + 124: 'SC_PERF_SEL_RESERVED_124', + 125: 'SC_PERF_SEL_RESERVED_125', + 126: 'SC_PERF_SEL_RESERVED_126', + 127: 'SC_PERF_SEL_RESERVED_127', + 128: 'SC_PERF_SEL_RESERVED_128', + 129: 'SC_PERF_SEL_RESERVED_129', + 130: 'SC_PERF_SEL_RESERVED_130', + 131: 'SC_PERF_SEL_RESERVED_131', + 132: 'SC_PERF_SEL_RESERVED_132', + 133: 'SC_PERF_SEL_RESERVED_133', + 134: 'SC_PERF_SEL_RESERVED_134', + 135: 'SC_PERF_SEL_RESERVED_135', + 136: 'SC_PERF_SEL_RESERVED_136', + 137: 'SC_PERF_SEL_RESERVED_137', + 138: 'SC_PERF_SEL_RESERVED_138', + 139: 'SC_PERF_SEL_RESERVED_139', + 140: 'SC_PERF_SEL_RESERVED_140', + 141: 'SC_PERF_SEL_RESERVED_141', + 142: 'SC_PERF_SEL_RESERVED_142', + 143: 'SC_PERF_SEL_RESERVED_143', + 144: 'SC_PERF_SEL_RESERVED_144', + 145: 'SC_PERF_SEL_RESERVED_145', + 146: 'SC_PERF_SEL_RESERVED_146', + 147: 'SC_PERF_SEL_RESERVED_147', + 148: 'SC_PERF_SEL_RESERVED_148', + 149: 'SC_PERF_SEL_RESERVED_149', + 150: 'SC_PERF_SEL_RESERVED_150', + 151: 'SC_PERF_SEL_RESERVED_151', + 152: 'SC_PERF_SEL_RESERVED_152', + 153: 'SC_PERF_SEL_RESERVED_153', + 154: 'SC_PERF_SEL_RESERVED_154', + 155: 'SC_PERF_SEL_RESERVED_155', + 156: 'SC_PERF_SEL_RESERVED_156', + 157: 'SC_PERF_SEL_RESERVED_157', + 158: 'SC_PERF_SEL_RESERVED_158', + 159: 'SC_QZ0_QUAD_COUNT', + 160: 'SC_PERF_SEL_RESERVED_160', + 161: 'SC_PERF_SEL_RESERVED_161', + 162: 'SC_PERF_SEL_RESERVED_162', + 163: 'SC_P0_HIZ_TILE_COUNT', + 164: 'SC_PERF_SEL_RESERVED_164', + 165: 'SC_PERF_SEL_RESERVED_165', + 166: 'SC_PERF_SEL_RESERVED_166', + 167: 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 168: 'SC_P0_HIZ_QUAD_PER_TILE_H1', + 169: 'SC_P0_HIZ_QUAD_PER_TILE_H2', + 170: 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 171: 'SC_P0_HIZ_QUAD_PER_TILE_H4', + 172: 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 173: 'SC_P0_HIZ_QUAD_PER_TILE_H6', + 174: 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 175: 'SC_P0_HIZ_QUAD_PER_TILE_H8', + 176: 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 177: 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 178: 'SC_P0_HIZ_QUAD_PER_TILE_H11', + 179: 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 180: 'SC_P0_HIZ_QUAD_PER_TILE_H13', + 181: 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 182: 'SC_P0_HIZ_QUAD_PER_TILE_H15', + 183: 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 184: 'SC_PERF_SEL_RESERVED_184', + 185: 'SC_PERF_SEL_RESERVED_185', + 186: 'SC_PERF_SEL_RESERVED_186', + 187: 'SC_PERF_SEL_RESERVED_187', + 188: 'SC_PERF_SEL_RESERVED_188', + 189: 'SC_PERF_SEL_RESERVED_189', + 190: 'SC_PERF_SEL_RESERVED_190', + 191: 'SC_PERF_SEL_RESERVED_191', + 192: 'SC_PERF_SEL_RESERVED_192', + 193: 'SC_PERF_SEL_RESERVED_193', + 194: 'SC_PERF_SEL_RESERVED_194', + 195: 'SC_PERF_SEL_RESERVED_195', + 196: 'SC_PERF_SEL_RESERVED_196', + 197: 'SC_PERF_SEL_RESERVED_197', + 198: 'SC_PERF_SEL_RESERVED_198', + 199: 'SC_PERF_SEL_RESERVED_199', + 200: 'SC_PERF_SEL_RESERVED_200', + 201: 'SC_PERF_SEL_RESERVED_201', + 202: 'SC_PERF_SEL_RESERVED_202', + 203: 'SC_PERF_SEL_RESERVED_203', + 204: 'SC_PERF_SEL_RESERVED_204', + 205: 'SC_PERF_SEL_RESERVED_205', + 206: 'SC_PERF_SEL_RESERVED_206', + 207: 'SC_PERF_SEL_RESERVED_207', + 208: 'SC_PERF_SEL_RESERVED_208', + 209: 'SC_PERF_SEL_RESERVED_209', + 210: 'SC_PERF_SEL_RESERVED_210', + 211: 'SC_PERF_SEL_RESERVED_211', + 212: 'SC_PERF_SEL_RESERVED_212', + 213: 'SC_PERF_SEL_RESERVED_213', + 214: 'SC_PERF_SEL_RESERVED_214', + 215: 'SC_PERF_SEL_RESERVED_215', + 216: 'SC_PERF_SEL_RESERVED_216', + 217: 'SC_PERF_SEL_RESERVED_217', + 218: 'SC_PERF_SEL_RESERVED_218', + 219: 'SC_PERF_SEL_RESERVED_219', + 220: 'SC_PERF_SEL_RESERVED_220', + 221: 'SC_PERF_SEL_RESERVED_221', + 222: 'SC_PERF_SEL_RESERVED_222', + 223: 'SC_PERF_SEL_RESERVED_223', + 224: 'SC_PERF_SEL_RESERVED_224', + 225: 'SC_PERF_SEL_RESERVED_225', + 226: 'SC_PERF_SEL_RESERVED_226', + 227: 'SC_PERF_SEL_RESERVED_227', + 228: 'SC_PERF_SEL_RESERVED_228', + 229: 'SC_PERF_SEL_RESERVED_229', + 230: 'SC_PERF_SEL_RESERVED_230', + 231: 'SC_PERF_SEL_RESERVED_231', + 232: 'SC_PERF_SEL_RESERVED_232', + 233: 'SC_PERF_SEL_RESERVED_233', + 234: 'SC_PERF_SEL_RESERVED_234', + 235: 'SC_P0_HIZ_QUAD_COUNT', + 236: 'SC_PERF_SEL_RESERVED_236', + 237: 'SC_PERF_SEL_RESERVED_237', + 238: 'SC_PERF_SEL_RESERVED_238', + 239: 'SC_P0_DETAIL_QUAD_COUNT', + 240: 'SC_PERF_SEL_RESERVED_240', + 241: 'SC_PERF_SEL_RESERVED_241', + 242: 'SC_PERF_SEL_RESERVED_242', + 243: 'SC_P0_DETAIL_QUAD_WITH_1_PIX', + 244: 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 245: 'SC_P0_DETAIL_QUAD_WITH_3_PIX', + 246: 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 247: 'SC_PERF_SEL_RESERVED_247', + 248: 'SC_PERF_SEL_RESERVED_248', + 249: 'SC_PERF_SEL_RESERVED_249', + 250: 'SC_PERF_SEL_RESERVED_250', + 251: 'SC_PERF_SEL_RESERVED_251', + 252: 'SC_PERF_SEL_RESERVED_252', + 253: 'SC_PERF_SEL_RESERVED_253', + 254: 'SC_PERF_SEL_RESERVED_254', + 255: 'SC_PERF_SEL_RESERVED_255', + 256: 'SC_PERF_SEL_RESERVED_256', + 257: 'SC_PERF_SEL_RESERVED_257', + 258: 'SC_PERF_SEL_RESERVED_258', + 259: 'SC_EARLYZ_QUAD_COUNT', + 260: 'SC_EARLYZ_QUAD_WITH_1_PIX', + 261: 'SC_EARLYZ_QUAD_WITH_2_PIX', + 262: 'SC_EARLYZ_QUAD_WITH_3_PIX', + 263: 'SC_EARLYZ_QUAD_WITH_4_PIX', + 264: 'SC_PKR_QUAD_PER_ROW_H1', + 265: 'SC_PKR_QUAD_PER_ROW_H2', + 266: 'SC_PKR_4X2_QUAD_SPLIT', + 267: 'SC_PKR_4X2_FILL_QUAD', + 268: 'SC_PKR_END_OF_VECTOR', + 269: 'SC_PKR_CONTROL_XFER', + 270: 'SC_PKR_DBHANG_FORCE_EOV', + 271: 'SC_REG_SCLK_BUSY', + 272: 'SC_GRP0_DYN_SCLK_BUSY', + 273: 'SC_GRP1_DYN_SCLK_BUSY', + 274: 'SC_GRP2_DYN_SCLK_BUSY', + 275: 'SC_GRP3_DYN_SCLK_BUSY', + 276: 'SC_GRP4_DYN_SCLK_BUSY', + 277: 'SC_PA0_SC_DATA_FIFO_RD', + 278: 'SC_PA0_SC_DATA_FIFO_WE', + 279: 'SC_PERF_SEL_RESERVED_279', + 280: 'SC_PERF_SEL_RESERVED_280', + 281: 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 282: 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', + 283: 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 284: 'SC_PS_ARB_STALLED_FROM_BELOW', + 285: 'SC_PS_ARB_STARVED_FROM_ABOVE', + 286: 'SC_PS_ARB_SC_BUSY', + 287: 'SC_PS_ARB_PA_SC_BUSY', + 288: 'SC_PERF_SEL_RESERVED_288', + 289: 'SC_PERF_SEL_RESERVED_289', + 290: 'SC_PERF_SEL_RESERVED_290', + 291: 'SC_PERF_SEL_RESERVED_291', + 292: 'SC_PA_SC_DEALLOC_2_0_WE', + 293: 'SC_PERF_SEL_RESERVED_293', + 294: 'SC_PERF_SEL_RESERVED_294', + 295: 'SC_PERF_SEL_RESERVED_295', + 296: 'SC_PERF_SEL_RESERVED_296', + 297: 'SC_PERF_SEL_RESERVED_297', + 298: 'SC_PERF_SEL_RESERVED_298', + 299: 'SC_PERF_SEL_RESERVED_299', + 300: 'SC_PA0_SC_EOP_WE', + 301: 'SC_PERF_SEL_RESERVED_301', + 302: 'SC_PA0_SC_EVENT_WE', + 303: 'SC_PERF_SEL_RESERVED_303', + 304: 'SC_PERF_SEL_RESERVED_304', + 305: 'SC_PERF_SEL_RESERVED_305', + 306: 'SC_PERF_SEL_RESERVED_306', + 307: 'SC_PERF_SEL_RESERVED_307', + 308: 'SC_PERF_SEL_RESERVED_308', + 309: 'SC_PERF_SEL_RESERVED_309', + 310: 'SC_PERF_SEL_RESERVED_310', + 311: 'SC_PERF_SEL_RESERVED_311', + 312: 'SC_PERF_SEL_RESERVED_312', + 313: 'SC_PERF_SEL_RESERVED_313', + 314: 'SC_PERF_SEL_RESERVED_314', + 315: 'SC_PERF_SEL_RESERVED_315', + 316: 'SC_PERF_SEL_RESERVED_316', + 317: 'SC_PERF_SEL_RESERVED_317', + 318: 'SC_PA_SC_FPOV_WE', + 319: 'SC_PERF_SEL_RESERVED_319', + 320: 'SC_PERF_SEL_RESERVED_320', + 321: 'SC_PERF_SEL_RESERVED_321', + 322: 'SC_PERF_SEL_RESERVED_322', + 323: 'SC_PERF_SEL_RESERVED_323', + 324: 'SC_PERF_SEL_RESERVED_324', + 325: 'SC_PERF_SEL_RESERVED_325', + 326: 'SC_SPI_DEALLOC_4_0', + 327: 'SC_SPI_DEALLOC_7_5', + 328: 'SC_PERF_SEL_RESERVED_328', + 329: 'SC_PERF_SEL_RESERVED_329', + 330: 'SC_PERF_SEL_RESERVED_330', + 331: 'SC_PERF_SEL_RESERVED_331', + 332: 'SC_PERF_SEL_RESERVED_332', + 333: 'SC_PERF_SEL_RESERVED_333', + 334: 'SC_PERF_SEL_RESERVED_334', + 335: 'SC_PERF_SEL_RESERVED_335', + 336: 'SC_PERF_SEL_RESERVED_336', + 337: 'SC_PERF_SEL_RESERVED_337', + 338: 'SC_SPI_FPOV_4_0', + 339: 'SC_SPI_FPOV_7_5', + 340: 'SC_PERF_SEL_RESERVED_340', + 341: 'SC_PERF_SEL_RESERVED_341', + 342: 'SC_SPI_EVENT', + 343: 'SC_PS_TS_EVENT_FIFO_PUSH', + 344: 'SC_PS_TS_EVENT_FIFO_POP', + 345: 'SC_PS_CTX_DONE_FIFO_PUSH', + 346: 'SC_PS_CTX_DONE_FIFO_POP', + 347: 'SC_PERF_SEL_RESERVED_347', + 348: 'SC_PERF_SEL_RESERVED_348', + 349: 'SC_PA0_SC_NULL_WE', + 350: 'SC_PA0_SC_NULL_DEALLOC_WE', + 351: 'SC_PERF_SEL_RESERVED_351', + 352: 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 353: 'SC_PA0_SC_DEALLOC_2_0_RD', + 354: 'SC_PERF_SEL_RESERVED_354', + 355: 'SC_PERF_SEL_RESERVED_355', + 356: 'SC_PERF_SEL_RESERVED_356', + 357: 'SC_PERF_SEL_RESERVED_357', + 358: 'SC_PERF_SEL_RESERVED_358', + 359: 'SC_PERF_SEL_RESERVED_359', + 360: 'SC_PERF_SEL_RESERVED_360', + 361: 'SC_PERF_SEL_RESERVED_361', + 362: 'SC_PERF_SEL_RESERVED_362', + 363: 'SC_PERF_SEL_RESERVED_363', + 364: 'SC_PERF_SEL_RESERVED_364', + 365: 'SC_PERF_SEL_RESERVED_365', + 366: 'SC_PERF_SEL_RESERVED_366', + 367: 'SC_PERF_SEL_RESERVED_367', + 368: 'SC_PERF_SEL_RESERVED_368', + 369: 'SC_PERF_SEL_RESERVED_369', + 370: 'SC_PERF_SEL_RESERVED_370', + 371: 'SC_PERF_SEL_RESERVED_371', + 372: 'SC_PERF_SEL_RESERVED_372', + 373: 'SC_PS_PA0_SC_FIFO_EMPTY', + 374: 'SC_PS_PA0_SC_FIFO_FULL', + 375: 'SC_PERF_SEL_RESERVED_375', + 376: 'SC_PERF_SEL_RESERVED_376', + 377: 'SC_PERF_SEL_RESERVED_377', + 378: 'SC_PERF_SEL_RESERVED_378', + 379: 'SC_PERF_SEL_RESERVED_379', + 380: 'SC_PERF_SEL_RESERVED_380', + 381: 'SC_PERF_SEL_RESERVED_381', + 382: 'SC_PERF_SEL_RESERVED_382', + 383: 'SC_PERF_SEL_RESERVED_383', + 384: 'SC_PERF_SEL_RESERVED_384', + 385: 'SC_PERF_SEL_RESERVED_385', + 386: 'SC_BUSY_CNT_NOT_ZERO', + 387: 'SC_BM_BUSY', + 388: 'SC_BACKEND_BUSY', + 389: 'SC_SCF_SCB_INTERFACE_BUSY', + 390: 'SC_SCB_BUSY', + 391: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 392: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 393: 'SC_PBB_BIN_HIST_NUM_PRIMS', + 394: 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 395: 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 396: 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 397: 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 398: 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 399: 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 400: 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 401: 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 402: 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 403: 'SC_PBB_BUSY', + 404: 'SC_PBB_BUSY_AND_NO_SENDS', + 405: 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 406: 'SC_PBB_NUM_BINS', + 407: 'SC_PBB_END_OF_BIN', + 408: 'SC_PBB_END_OF_BATCH', + 409: 'SC_PBB_PRIMBIN_PROCESSED', + 410: 'SC_PBB_PRIM_ADDED_TO_BATCH', + 411: 'SC_PBB_NONBINNED_PRIM', + 412: 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', + 413: 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 414: 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 415: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 416: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 417: 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 418: 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 419: 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 420: 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 421: 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 422: 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 423: 'SC_PERF_SEL_RESERVED_423', + 424: 'SC_PERF_SEL_RESERVED_424', + 425: 'SC_PERF_SEL_RESERVED_425', + 426: 'SC_PERF_SEL_RESERVED_426', + 427: 'SC_PERF_SEL_RESERVED_427', + 428: 'SC_PERF_SEL_RESERVED_428', + 429: 'SC_PERF_SEL_RESERVED_429', + 430: 'SC_PERF_SEL_RESERVED_430', + 431: 'SC_PERF_SEL_RESERVED_431', + 432: 'SC_PERF_SEL_RESERVED_432', + 433: 'SC_PERF_SEL_RESERVED_433', + 434: 'SC_PERF_SEL_RESERVED_434', + 435: 'SC_PERF_SEL_RESERVED_435', + 436: 'SC_PERF_SEL_RESERVED_436', + 437: 'SC_GRP5_DYN_SCLK_BUSY', + 438: 'SC_GRP6_DYN_SCLK_BUSY', + 439: 'SC_GRP7_DYN_SCLK_BUSY', + 440: 'SC_GRP8_DYN_SCLK_BUSY', + 441: 'SC_GRP9_DYN_SCLK_BUSY', + 442: 'SC_PS_TO_BE_SCLK_GATE_STALL', + 443: 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 444: 'SC_PK_BUSY', + 445: 'SC_PK_MAX_DEALLOC_FORCE_EOV', + 446: 'SC_PK_DEALLOC_WAVE_BREAK', + 447: 'SC_SPI_SEND', + 448: 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 449: 'SC_SPI_CREDIT_AT_MAX', + 450: 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 451: 'SC_BCI_SEND', + 452: 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 453: 'SC_BCI_CREDIT_AT_MAX', + 454: 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 455: 'SC_SPIBC_FULL_FREEZE', + 456: 'SC_PW_BM_PASS_EMPTY_PRIM', + 457: 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 458: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 459: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 460: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 461: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 462: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 463: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 464: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 465: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 466: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 467: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 468: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 469: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 470: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 471: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 472: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 473: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 474: 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 475: 'SC_DB0_TILE_INTERFACE_BUSY', + 476: 'SC_DB0_TILE_INTERFACE_SEND', + 477: 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 478: 'SC_PERF_SEL_RESERVED_478', + 479: 'SC_PERF_SEL_RESERVED_479', + 480: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 481: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 482: 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 483: 'SC_PERF_SEL_RESERVED_483', + 484: 'SC_PERF_SEL_RESERVED_484', + 485: 'SC_PERF_SEL_RESERVED_485', + 486: 'SC_PERF_SEL_RESERVED_486', + 487: 'SC_PERF_SEL_RESERVED_487', + 488: 'SC_PERF_SEL_RESERVED_488', + 489: 'SC_PERF_SEL_RESERVED_489', + 490: 'SC_PERF_SEL_RESERVED_490', + 491: 'SC_BACKEND_PRIM_FIFO_FULL', + 492: 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 493: 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 494: 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 495: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 496: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 497: 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 498: 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 499: 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 500: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', + 501: 'SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET', + 502: 'SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE', + 503: 'SC_STALLED_BY_DB0_TILEFIFO', + 504: 'SC_DB0_QUAD_INTF_SEND', + 505: 'SC_DB0_QUAD_INTF_BUSY', + 506: 'SC_DB0_QUAD_INTF_STALLED_BY_DB', + 507: 'SC_DB0_QUAD_INTF_CREDIT_AT_MAX', + 508: 'SC_DB0_QUAD_INTF_IDLE', + 509: 'SC_PERF_SEL_RESERVED_509', + 510: 'SC_PERF_SEL_RESERVED_510', + 511: 'SC_PERF_SEL_RESERVED_511', + 512: 'SC_PERF_SEL_RESERVED_512', + 513: 'SC_PERF_SEL_RESERVED_513', + 514: 'SC_PERF_SEL_RESERVED_514', + 515: 'SC_PKR_WAVE_BREAK_OUTSIDE_REGION', + 516: 'SC_PKR_WAVE_BREAK_FULL_TILE', + 517: 'SC_RESERVED_60', + 518: 'SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN', + 519: 'SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT', + 520: 'SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL', + 521: 'SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 522: 'SC_DB0_TILE_MASK_FIFO_FULL', + 523: 'SC_PERF_SEL_RESERVED_523', + 524: 'SC_PERF_SEL_RESERVED_524', + 525: 'SC_PERF_SEL_RESERVED_525', + 526: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL', + 527: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL', + 528: 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL', + 529: 'SC_PS_PM_PFF_PW_FULL', + 530: 'SC_PS_PM_ZFF_PW_FULL', + 531: 'SC_PS_PM_PBB_TO_PSE_FIFO_FULL', + 532: 'SC_PERF_SEL_RESERVED_532', + 533: 'SC_PERF_SEL_RESERVED_533', + 534: 'SC_PERF_SEL_RESERVED_534', + 535: 'SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H', + 536: 'SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H', + 537: 'SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H', + 538: 'SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H', + 539: 'SC_PERF_SEL_RESERVED_539', + 540: 'SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H', + 541: 'SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 542: 'SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H', + 543: 'SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 544: 'SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H', + 545: 'SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H', + 546: 'SC_PK_PM_FULL_TILE_WAVE_BRK_1H', + 547: 'SC_PK_PM_OREO_CONFLICT_QUAD_FORCE_EOV_WAVE_BRK_1H', + 548: 'SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H', + 549: 'SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H', + 550: 'SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H', + 551: 'SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H', + 552: 'SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD', + 553: 'SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD', + 554: 'SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD', + 555: 'SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD', + 556: 'SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD', + 557: 'SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD', + 558: 'SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD', + 559: 'SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD', + 560: 'SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD', + 561: 'SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD', + 562: 'SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD', + 563: 'SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD', + 564: 'SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD', + 565: 'SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD', + 566: 'SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD', + 567: 'SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD', + 568: 'SC_PERF_SEL_RESERVED_568', + 569: 'SC_PBB_RESERVED', + 570: 'SC_BM_BE0_STALLED', + 571: 'SC_BM_BE1_STALLED', + 572: 'SC_BM_BE2_STALLED', + 573: 'SC_BM_BE3_STALLED', + 574: 'SC_BM_MULTI_ACCUM_1_BE_STALLED', + 575: 'SC_BM_MULTI_ACCUM_2_BE_STALLED', + 576: 'SC_BM_MULTI_ACCUM_3_BE_STALLED', + 577: 'SC_BM_MULTI_ACCUM_4_BE_STALLED', + 578: 'SC_PBB_READ_PH0', + 579: 'SC_PBB_READ_DEALLOC_4_0', + 580: 'SC_PBB_READ_DEALLOC_7_5', + 581: 'SC_PBB_READ_FPOG_4_0', + 582: 'SC_PBB_READ_FPOG_7_5', + 583: 'SC_VRC_SECTOR_HIT', + 584: 'SC_VRC_TAG_MISS', + 585: 'SC_VRC_SECTOR_MISS', + 586: 'SC_VRC_LRU_EVICT_STALL', + 587: 'SC_VRC_LRU_EVICT_SCHEDULED_EVICT_STALL', + 588: 'SC_VRC_LRU_EVICT_PENDING_EVICT_STALL', + 589: 'SC_VRC_REEVICTION_STALL', + 590: 'SC_VRC_EVICT_NONZERO_INFLIGHT_STALL', + 591: 'SC_VRC_REPLACE_SCHEDULED_EVICT_STALL', + 592: 'SC_VRC_REPLACE_PENDING_EVICT_STALL', + 593: 'SC_VRC_REPLACE_FLUSH_IN_PROGRESS_STALL', + 594: 'SC_VRC_INFLIGHT_COUNTER_MAXIMUM_STALL', + 595: 'SC_VRC_READ_OUTPUT_STALL', + 596: 'SC_VRC_WRITE_OUTPUT_STALL', + 597: 'SC_VRC_ACK_OUTPUT_STALL', + 598: 'SC_VRC_FLUSH_EVICT_STALL', + 599: 'SC_VRC_FLUSH_REFLUSH_STALL', + 600: 'SC_VRC_FLUSH_FIP_HIT_STALL', + 601: 'SC_VRC_FLUSH_WRREQ_DRAIN_STALL', + 602: 'SC_VRC_FLUSH_DONE_STALL', + 603: 'SC_VRC_FLUSH_STALL', + 604: 'SC_VRC_STALL', + 605: 'SC_VRC_FLUSH', + 606: 'SC_VRC_SECTORS_FLUSHED', + 607: 'SC_VRC_DIRTY_SECTORS_FLUSHED', + 608: 'SC_VRC_TAGS_FLUSHED', + 609: 'SC_VRC_HPF_REQ', + 610: 'SC_VRC_HPF_EVENT', + 611: 'SC_VRC_HPF_STALLED', + 612: 'SC_VRC_PROBE_ACK_TILES', + 613: 'SC_VRC_GL1X_RD_REQ', + 614: 'SC_VRC_GL1X_WR_REQ', + 615: 'SC_VRC_GL1X_SRC_XFR', + 616: 'SC_VRC_GL1X_RD_RET', + 617: 'SC_VRC_GL1X_WR_ACK', + 618: 'SC_VRC_GL1X_RD_XNACK', + 619: 'SC_VRC_GL1X_WR_XNACK', + 620: 'SC_VRC_GL1X_REQ_STALLED', + 621: 'SC_VRC_GL1X_SRC_STALLED', + 622: 'SC_VRC_RATEMEM_WE_CNT', + 623: 'SC_VRC_RATEMEM_RE_CNT', + 624: 'SC_VRC_HINTMEM_WE_CNT', + 625: 'SC_VRC_HINTMEM_RE_CNT', + 626: 'SC_VRC_BUSY', + 627: 'SC_GL1X_BUSY', + 628: 'SC_BE_VRS_RD_REQ', + 629: 'SC_BE_VRS_RD_REQ_STALLED', + 630: 'SC_BE_VRS_RD_REQ_HIT', + 631: 'SC_BE_VRS_RD_RET', + 632: 'SC_BE_VRS_RD_RET_STALLED', + 633: 'SC_BE_VRS_FB_RET', + 634: 'SC_BE_VRS_FB_RET_STALLED', + 635: 'SC_BE_VRS_FB_RET_HIT', + 636: 'SC_VRS_BE_BUSY', + 637: 'SC_PWS_CS_EVENTS_PWS_ENABLE', + 638: 'SC_PWS_PS_EVENTS_PWS_ENABLE', + 639: 'SC_PWS_TS_EVENTS_PWS_ENABLE', + 640: 'SC_PWS_STALLED', + 641: 'SC_PWS_P0_CS_SYNC_COMPLETE', + 642: 'SC_PWS_P0_PS_SYNC_COMPLETE', + 643: 'SC_PWS_P0_TS_SYNC_COMPLETE', + 644: 'SC_PWS_P1_CS_SYNC_COMPLETE', + 645: 'SC_PWS_P1_PS_SYNC_COMPLETE', + 646: 'SC_PWS_P1_TS_SYNC_COMPLETE', + 647: 'SC_PKR_PC_NO_CREDITS', + 648: 'SC_PKR_PC_STALLED', + 649: 'SC_PKR_PC_SEND', + 650: 'SC_PKR_PC_SEND_PRIM_VALID_1', + 651: 'SC_PKR_PC_SEND_PRIM_VALID_0', + 652: 'SC_PKR_PC_SEND_TRUE_PRIM', + 653: 'SC_PKR_PC_SEND_EOV', + 654: 'SC_PKR_PC_SEND_EVENT', + 655: 'SC_PKR_DB_WAVE_STALL', + 656: 'SC_PKR_PSINVOC_SEDC_FIFO_FULL', + 657: 'SC_PKR_OREO_STALLED_BY_NO_VALID_WAIVE_ID', + 658: 'SC_PKR_SPI_QUAD_COUNT', + 659: 'SC_PKR_DB_OREO_WAVE_QUAD_COUNT', + 660: 'SC_PKR_BCI_QUAD_NEW_PRIM', + 661: 'SC_SPI_WAVE_STALLED_BY_SPI', +} +SC_SRPS_WINDOW_VALID = 0 +SC_PSSW_WINDOW_VALID = 1 +SC_TPQZ_WINDOW_VALID = 2 +SC_QZQP_WINDOW_VALID = 3 +SC_TRPK_WINDOW_VALID = 4 +SC_SRPS_WINDOW_VALID_BUSY = 5 +SC_PSSW_WINDOW_VALID_BUSY = 6 +SC_TPQZ_WINDOW_VALID_BUSY = 7 +SC_QZQP_WINDOW_VALID_BUSY = 8 +SC_TRPK_WINDOW_VALID_BUSY = 9 +SC_STARVED_BY_PA = 10 +SC_STALLED_BY_PRIMFIFO = 11 +SC_STALLED_BY_DB_TILE = 12 +SC_STARVED_BY_DB_TILE = 13 +SC_STALLED_BY_TILEORDERFIFO = 14 +SC_STALLED_BY_TILEFIFO = 15 +SC_STALLED_BY_DB_QUAD = 16 +SC_STARVED_BY_DB_QUAD = 17 +SC_STALLED_BY_QUADFIFO = 18 +SC_STALLED_BY_BCI = 19 +SC_STALLED_BY_SPI = 20 +SC_SCISSOR_DISCARD = 21 +SC_BB_DISCARD = 22 +SC_SUPERTILE_COUNT = 23 +SC_SUPERTILE_PER_PRIM_H0 = 24 +SC_SUPERTILE_PER_PRIM_H1 = 25 +SC_SUPERTILE_PER_PRIM_H2 = 26 +SC_SUPERTILE_PER_PRIM_H3 = 27 +SC_SUPERTILE_PER_PRIM_H4 = 28 +SC_SUPERTILE_PER_PRIM_H5 = 29 +SC_SUPERTILE_PER_PRIM_H6 = 30 +SC_SUPERTILE_PER_PRIM_H7 = 31 +SC_SUPERTILE_PER_PRIM_H8 = 32 +SC_SUPERTILE_PER_PRIM_H9 = 33 +SC_SUPERTILE_PER_PRIM_H10 = 34 +SC_SUPERTILE_PER_PRIM_H11 = 35 +SC_SUPERTILE_PER_PRIM_H12 = 36 +SC_SUPERTILE_PER_PRIM_H13 = 37 +SC_SUPERTILE_PER_PRIM_H14 = 38 +SC_SUPERTILE_PER_PRIM_H15 = 39 +SC_SUPERTILE_PER_PRIM_H16 = 40 +SC_TILE_PER_PRIM_H0 = 41 +SC_TILE_PER_PRIM_H1 = 42 +SC_TILE_PER_PRIM_H2 = 43 +SC_TILE_PER_PRIM_H3 = 44 +SC_TILE_PER_PRIM_H4 = 45 +SC_TILE_PER_PRIM_H5 = 46 +SC_TILE_PER_PRIM_H6 = 47 +SC_TILE_PER_PRIM_H7 = 48 +SC_TILE_PER_PRIM_H8 = 49 +SC_TILE_PER_PRIM_H9 = 50 +SC_TILE_PER_PRIM_H10 = 51 +SC_TILE_PER_PRIM_H11 = 52 +SC_TILE_PER_PRIM_H12 = 53 +SC_TILE_PER_PRIM_H13 = 54 +SC_TILE_PER_PRIM_H14 = 55 +SC_TILE_PER_PRIM_H15 = 56 +SC_TILE_PER_PRIM_H16 = 57 +SC_TILE_PER_SUPERTILE_H0 = 58 +SC_TILE_PER_SUPERTILE_H1 = 59 +SC_TILE_PER_SUPERTILE_H2 = 60 +SC_TILE_PER_SUPERTILE_H3 = 61 +SC_TILE_PER_SUPERTILE_H4 = 62 +SC_TILE_PER_SUPERTILE_H5 = 63 +SC_TILE_PER_SUPERTILE_H6 = 64 +SC_TILE_PER_SUPERTILE_H7 = 65 +SC_TILE_PER_SUPERTILE_H8 = 66 +SC_TILE_PER_SUPERTILE_H9 = 67 +SC_TILE_PER_SUPERTILE_H10 = 68 +SC_TILE_PER_SUPERTILE_H11 = 69 +SC_TILE_PER_SUPERTILE_H12 = 70 +SC_TILE_PER_SUPERTILE_H13 = 71 +SC_TILE_PER_SUPERTILE_H14 = 72 +SC_TILE_PER_SUPERTILE_H15 = 73 +SC_TILE_PER_SUPERTILE_H16 = 74 +SC_TILE_PICKED_H1 = 75 +SC_PERF_SEL_RESERVED_76 = 76 +SC_PERF_SEL_RESERVED_77 = 77 +SC_PERF_SEL_RESERVED_78 = 78 +SC_QZ0_TILE_COUNT = 79 +SC_PERF_SEL_RESERVED_80 = 80 +SC_PERF_SEL_RESERVED_81 = 81 +SC_PERF_SEL_RESERVED_82 = 82 +SC_QZ0_TILE_COVERED_COUNT = 83 +SC_PERF_SEL_RESERVED_84 = 84 +SC_PERF_SEL_RESERVED_85 = 85 +SC_PERF_SEL_RESERVED_86 = 86 +SC_QZ0_TILE_NOT_COVERED_COUNT = 87 +SC_PERF_SEL_RESERVED_88 = 88 +SC_PERF_SEL_RESERVED_89 = 89 +SC_PERF_SEL_RESERVED_90 = 90 +SC_QZ0_QUAD_PER_TILE_H0 = 91 +SC_QZ0_QUAD_PER_TILE_H1 = 92 +SC_QZ0_QUAD_PER_TILE_H2 = 93 +SC_QZ0_QUAD_PER_TILE_H3 = 94 +SC_QZ0_QUAD_PER_TILE_H4 = 95 +SC_QZ0_QUAD_PER_TILE_H5 = 96 +SC_QZ0_QUAD_PER_TILE_H6 = 97 +SC_QZ0_QUAD_PER_TILE_H7 = 98 +SC_QZ0_QUAD_PER_TILE_H8 = 99 +SC_QZ0_QUAD_PER_TILE_H9 = 100 +SC_QZ0_QUAD_PER_TILE_H10 = 101 +SC_QZ0_QUAD_PER_TILE_H11 = 102 +SC_QZ0_QUAD_PER_TILE_H12 = 103 +SC_QZ0_QUAD_PER_TILE_H13 = 104 +SC_QZ0_QUAD_PER_TILE_H14 = 105 +SC_QZ0_QUAD_PER_TILE_H15 = 106 +SC_QZ0_QUAD_PER_TILE_H16 = 107 +SC_PERF_SEL_RESERVED_108 = 108 +SC_PERF_SEL_RESERVED_109 = 109 +SC_PERF_SEL_RESERVED_110 = 110 +SC_PERF_SEL_RESERVED_111 = 111 +SC_PERF_SEL_RESERVED_112 = 112 +SC_PERF_SEL_RESERVED_113 = 113 +SC_PERF_SEL_RESERVED_114 = 114 +SC_PERF_SEL_RESERVED_115 = 115 +SC_PERF_SEL_RESERVED_116 = 116 +SC_PERF_SEL_RESERVED_117 = 117 +SC_PERF_SEL_RESERVED_118 = 118 +SC_PERF_SEL_RESERVED_119 = 119 +SC_PERF_SEL_RESERVED_120 = 120 +SC_PERF_SEL_RESERVED_121 = 121 +SC_PERF_SEL_RESERVED_122 = 122 +SC_PERF_SEL_RESERVED_123 = 123 +SC_PERF_SEL_RESERVED_124 = 124 +SC_PERF_SEL_RESERVED_125 = 125 +SC_PERF_SEL_RESERVED_126 = 126 +SC_PERF_SEL_RESERVED_127 = 127 +SC_PERF_SEL_RESERVED_128 = 128 +SC_PERF_SEL_RESERVED_129 = 129 +SC_PERF_SEL_RESERVED_130 = 130 +SC_PERF_SEL_RESERVED_131 = 131 +SC_PERF_SEL_RESERVED_132 = 132 +SC_PERF_SEL_RESERVED_133 = 133 +SC_PERF_SEL_RESERVED_134 = 134 +SC_PERF_SEL_RESERVED_135 = 135 +SC_PERF_SEL_RESERVED_136 = 136 +SC_PERF_SEL_RESERVED_137 = 137 +SC_PERF_SEL_RESERVED_138 = 138 +SC_PERF_SEL_RESERVED_139 = 139 +SC_PERF_SEL_RESERVED_140 = 140 +SC_PERF_SEL_RESERVED_141 = 141 +SC_PERF_SEL_RESERVED_142 = 142 +SC_PERF_SEL_RESERVED_143 = 143 +SC_PERF_SEL_RESERVED_144 = 144 +SC_PERF_SEL_RESERVED_145 = 145 +SC_PERF_SEL_RESERVED_146 = 146 +SC_PERF_SEL_RESERVED_147 = 147 +SC_PERF_SEL_RESERVED_148 = 148 +SC_PERF_SEL_RESERVED_149 = 149 +SC_PERF_SEL_RESERVED_150 = 150 +SC_PERF_SEL_RESERVED_151 = 151 +SC_PERF_SEL_RESERVED_152 = 152 +SC_PERF_SEL_RESERVED_153 = 153 +SC_PERF_SEL_RESERVED_154 = 154 +SC_PERF_SEL_RESERVED_155 = 155 +SC_PERF_SEL_RESERVED_156 = 156 +SC_PERF_SEL_RESERVED_157 = 157 +SC_PERF_SEL_RESERVED_158 = 158 +SC_QZ0_QUAD_COUNT = 159 +SC_PERF_SEL_RESERVED_160 = 160 +SC_PERF_SEL_RESERVED_161 = 161 +SC_PERF_SEL_RESERVED_162 = 162 +SC_P0_HIZ_TILE_COUNT = 163 +SC_PERF_SEL_RESERVED_164 = 164 +SC_PERF_SEL_RESERVED_165 = 165 +SC_PERF_SEL_RESERVED_166 = 166 +SC_P0_HIZ_QUAD_PER_TILE_H0 = 167 +SC_P0_HIZ_QUAD_PER_TILE_H1 = 168 +SC_P0_HIZ_QUAD_PER_TILE_H2 = 169 +SC_P0_HIZ_QUAD_PER_TILE_H3 = 170 +SC_P0_HIZ_QUAD_PER_TILE_H4 = 171 +SC_P0_HIZ_QUAD_PER_TILE_H5 = 172 +SC_P0_HIZ_QUAD_PER_TILE_H6 = 173 +SC_P0_HIZ_QUAD_PER_TILE_H7 = 174 +SC_P0_HIZ_QUAD_PER_TILE_H8 = 175 +SC_P0_HIZ_QUAD_PER_TILE_H9 = 176 +SC_P0_HIZ_QUAD_PER_TILE_H10 = 177 +SC_P0_HIZ_QUAD_PER_TILE_H11 = 178 +SC_P0_HIZ_QUAD_PER_TILE_H12 = 179 +SC_P0_HIZ_QUAD_PER_TILE_H13 = 180 +SC_P0_HIZ_QUAD_PER_TILE_H14 = 181 +SC_P0_HIZ_QUAD_PER_TILE_H15 = 182 +SC_P0_HIZ_QUAD_PER_TILE_H16 = 183 +SC_PERF_SEL_RESERVED_184 = 184 +SC_PERF_SEL_RESERVED_185 = 185 +SC_PERF_SEL_RESERVED_186 = 186 +SC_PERF_SEL_RESERVED_187 = 187 +SC_PERF_SEL_RESERVED_188 = 188 +SC_PERF_SEL_RESERVED_189 = 189 +SC_PERF_SEL_RESERVED_190 = 190 +SC_PERF_SEL_RESERVED_191 = 191 +SC_PERF_SEL_RESERVED_192 = 192 +SC_PERF_SEL_RESERVED_193 = 193 +SC_PERF_SEL_RESERVED_194 = 194 +SC_PERF_SEL_RESERVED_195 = 195 +SC_PERF_SEL_RESERVED_196 = 196 +SC_PERF_SEL_RESERVED_197 = 197 +SC_PERF_SEL_RESERVED_198 = 198 +SC_PERF_SEL_RESERVED_199 = 199 +SC_PERF_SEL_RESERVED_200 = 200 +SC_PERF_SEL_RESERVED_201 = 201 +SC_PERF_SEL_RESERVED_202 = 202 +SC_PERF_SEL_RESERVED_203 = 203 +SC_PERF_SEL_RESERVED_204 = 204 +SC_PERF_SEL_RESERVED_205 = 205 +SC_PERF_SEL_RESERVED_206 = 206 +SC_PERF_SEL_RESERVED_207 = 207 +SC_PERF_SEL_RESERVED_208 = 208 +SC_PERF_SEL_RESERVED_209 = 209 +SC_PERF_SEL_RESERVED_210 = 210 +SC_PERF_SEL_RESERVED_211 = 211 +SC_PERF_SEL_RESERVED_212 = 212 +SC_PERF_SEL_RESERVED_213 = 213 +SC_PERF_SEL_RESERVED_214 = 214 +SC_PERF_SEL_RESERVED_215 = 215 +SC_PERF_SEL_RESERVED_216 = 216 +SC_PERF_SEL_RESERVED_217 = 217 +SC_PERF_SEL_RESERVED_218 = 218 +SC_PERF_SEL_RESERVED_219 = 219 +SC_PERF_SEL_RESERVED_220 = 220 +SC_PERF_SEL_RESERVED_221 = 221 +SC_PERF_SEL_RESERVED_222 = 222 +SC_PERF_SEL_RESERVED_223 = 223 +SC_PERF_SEL_RESERVED_224 = 224 +SC_PERF_SEL_RESERVED_225 = 225 +SC_PERF_SEL_RESERVED_226 = 226 +SC_PERF_SEL_RESERVED_227 = 227 +SC_PERF_SEL_RESERVED_228 = 228 +SC_PERF_SEL_RESERVED_229 = 229 +SC_PERF_SEL_RESERVED_230 = 230 +SC_PERF_SEL_RESERVED_231 = 231 +SC_PERF_SEL_RESERVED_232 = 232 +SC_PERF_SEL_RESERVED_233 = 233 +SC_PERF_SEL_RESERVED_234 = 234 +SC_P0_HIZ_QUAD_COUNT = 235 +SC_PERF_SEL_RESERVED_236 = 236 +SC_PERF_SEL_RESERVED_237 = 237 +SC_PERF_SEL_RESERVED_238 = 238 +SC_P0_DETAIL_QUAD_COUNT = 239 +SC_PERF_SEL_RESERVED_240 = 240 +SC_PERF_SEL_RESERVED_241 = 241 +SC_PERF_SEL_RESERVED_242 = 242 +SC_P0_DETAIL_QUAD_WITH_1_PIX = 243 +SC_P0_DETAIL_QUAD_WITH_2_PIX = 244 +SC_P0_DETAIL_QUAD_WITH_3_PIX = 245 +SC_P0_DETAIL_QUAD_WITH_4_PIX = 246 +SC_PERF_SEL_RESERVED_247 = 247 +SC_PERF_SEL_RESERVED_248 = 248 +SC_PERF_SEL_RESERVED_249 = 249 +SC_PERF_SEL_RESERVED_250 = 250 +SC_PERF_SEL_RESERVED_251 = 251 +SC_PERF_SEL_RESERVED_252 = 252 +SC_PERF_SEL_RESERVED_253 = 253 +SC_PERF_SEL_RESERVED_254 = 254 +SC_PERF_SEL_RESERVED_255 = 255 +SC_PERF_SEL_RESERVED_256 = 256 +SC_PERF_SEL_RESERVED_257 = 257 +SC_PERF_SEL_RESERVED_258 = 258 +SC_EARLYZ_QUAD_COUNT = 259 +SC_EARLYZ_QUAD_WITH_1_PIX = 260 +SC_EARLYZ_QUAD_WITH_2_PIX = 261 +SC_EARLYZ_QUAD_WITH_3_PIX = 262 +SC_EARLYZ_QUAD_WITH_4_PIX = 263 +SC_PKR_QUAD_PER_ROW_H1 = 264 +SC_PKR_QUAD_PER_ROW_H2 = 265 +SC_PKR_4X2_QUAD_SPLIT = 266 +SC_PKR_4X2_FILL_QUAD = 267 +SC_PKR_END_OF_VECTOR = 268 +SC_PKR_CONTROL_XFER = 269 +SC_PKR_DBHANG_FORCE_EOV = 270 +SC_REG_SCLK_BUSY = 271 +SC_GRP0_DYN_SCLK_BUSY = 272 +SC_GRP1_DYN_SCLK_BUSY = 273 +SC_GRP2_DYN_SCLK_BUSY = 274 +SC_GRP3_DYN_SCLK_BUSY = 275 +SC_GRP4_DYN_SCLK_BUSY = 276 +SC_PA0_SC_DATA_FIFO_RD = 277 +SC_PA0_SC_DATA_FIFO_WE = 278 +SC_PERF_SEL_RESERVED_279 = 279 +SC_PERF_SEL_RESERVED_280 = 280 +SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 281 +SC_PS_ARB_XFC_ONLY_PRIM_CYCLES = 282 +SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 283 +SC_PS_ARB_STALLED_FROM_BELOW = 284 +SC_PS_ARB_STARVED_FROM_ABOVE = 285 +SC_PS_ARB_SC_BUSY = 286 +SC_PS_ARB_PA_SC_BUSY = 287 +SC_PERF_SEL_RESERVED_288 = 288 +SC_PERF_SEL_RESERVED_289 = 289 +SC_PERF_SEL_RESERVED_290 = 290 +SC_PERF_SEL_RESERVED_291 = 291 +SC_PA_SC_DEALLOC_2_0_WE = 292 +SC_PERF_SEL_RESERVED_293 = 293 +SC_PERF_SEL_RESERVED_294 = 294 +SC_PERF_SEL_RESERVED_295 = 295 +SC_PERF_SEL_RESERVED_296 = 296 +SC_PERF_SEL_RESERVED_297 = 297 +SC_PERF_SEL_RESERVED_298 = 298 +SC_PERF_SEL_RESERVED_299 = 299 +SC_PA0_SC_EOP_WE = 300 +SC_PERF_SEL_RESERVED_301 = 301 +SC_PA0_SC_EVENT_WE = 302 +SC_PERF_SEL_RESERVED_303 = 303 +SC_PERF_SEL_RESERVED_304 = 304 +SC_PERF_SEL_RESERVED_305 = 305 +SC_PERF_SEL_RESERVED_306 = 306 +SC_PERF_SEL_RESERVED_307 = 307 +SC_PERF_SEL_RESERVED_308 = 308 +SC_PERF_SEL_RESERVED_309 = 309 +SC_PERF_SEL_RESERVED_310 = 310 +SC_PERF_SEL_RESERVED_311 = 311 +SC_PERF_SEL_RESERVED_312 = 312 +SC_PERF_SEL_RESERVED_313 = 313 +SC_PERF_SEL_RESERVED_314 = 314 +SC_PERF_SEL_RESERVED_315 = 315 +SC_PERF_SEL_RESERVED_316 = 316 +SC_PERF_SEL_RESERVED_317 = 317 +SC_PA_SC_FPOV_WE = 318 +SC_PERF_SEL_RESERVED_319 = 319 +SC_PERF_SEL_RESERVED_320 = 320 +SC_PERF_SEL_RESERVED_321 = 321 +SC_PERF_SEL_RESERVED_322 = 322 +SC_PERF_SEL_RESERVED_323 = 323 +SC_PERF_SEL_RESERVED_324 = 324 +SC_PERF_SEL_RESERVED_325 = 325 +SC_SPI_DEALLOC_4_0 = 326 +SC_SPI_DEALLOC_7_5 = 327 +SC_PERF_SEL_RESERVED_328 = 328 +SC_PERF_SEL_RESERVED_329 = 329 +SC_PERF_SEL_RESERVED_330 = 330 +SC_PERF_SEL_RESERVED_331 = 331 +SC_PERF_SEL_RESERVED_332 = 332 +SC_PERF_SEL_RESERVED_333 = 333 +SC_PERF_SEL_RESERVED_334 = 334 +SC_PERF_SEL_RESERVED_335 = 335 +SC_PERF_SEL_RESERVED_336 = 336 +SC_PERF_SEL_RESERVED_337 = 337 +SC_SPI_FPOV_4_0 = 338 +SC_SPI_FPOV_7_5 = 339 +SC_PERF_SEL_RESERVED_340 = 340 +SC_PERF_SEL_RESERVED_341 = 341 +SC_SPI_EVENT = 342 +SC_PS_TS_EVENT_FIFO_PUSH = 343 +SC_PS_TS_EVENT_FIFO_POP = 344 +SC_PS_CTX_DONE_FIFO_PUSH = 345 +SC_PS_CTX_DONE_FIFO_POP = 346 +SC_PERF_SEL_RESERVED_347 = 347 +SC_PERF_SEL_RESERVED_348 = 348 +SC_PA0_SC_NULL_WE = 349 +SC_PA0_SC_NULL_DEALLOC_WE = 350 +SC_PERF_SEL_RESERVED_351 = 351 +SC_PA0_SC_DATA_FIFO_EOP_RD = 352 +SC_PA0_SC_DEALLOC_2_0_RD = 353 +SC_PERF_SEL_RESERVED_354 = 354 +SC_PERF_SEL_RESERVED_355 = 355 +SC_PERF_SEL_RESERVED_356 = 356 +SC_PERF_SEL_RESERVED_357 = 357 +SC_PERF_SEL_RESERVED_358 = 358 +SC_PERF_SEL_RESERVED_359 = 359 +SC_PERF_SEL_RESERVED_360 = 360 +SC_PERF_SEL_RESERVED_361 = 361 +SC_PERF_SEL_RESERVED_362 = 362 +SC_PERF_SEL_RESERVED_363 = 363 +SC_PERF_SEL_RESERVED_364 = 364 +SC_PERF_SEL_RESERVED_365 = 365 +SC_PERF_SEL_RESERVED_366 = 366 +SC_PERF_SEL_RESERVED_367 = 367 +SC_PERF_SEL_RESERVED_368 = 368 +SC_PERF_SEL_RESERVED_369 = 369 +SC_PERF_SEL_RESERVED_370 = 370 +SC_PERF_SEL_RESERVED_371 = 371 +SC_PERF_SEL_RESERVED_372 = 372 +SC_PS_PA0_SC_FIFO_EMPTY = 373 +SC_PS_PA0_SC_FIFO_FULL = 374 +SC_PERF_SEL_RESERVED_375 = 375 +SC_PERF_SEL_RESERVED_376 = 376 +SC_PERF_SEL_RESERVED_377 = 377 +SC_PERF_SEL_RESERVED_378 = 378 +SC_PERF_SEL_RESERVED_379 = 379 +SC_PERF_SEL_RESERVED_380 = 380 +SC_PERF_SEL_RESERVED_381 = 381 +SC_PERF_SEL_RESERVED_382 = 382 +SC_PERF_SEL_RESERVED_383 = 383 +SC_PERF_SEL_RESERVED_384 = 384 +SC_PERF_SEL_RESERVED_385 = 385 +SC_BUSY_CNT_NOT_ZERO = 386 +SC_BM_BUSY = 387 +SC_BACKEND_BUSY = 388 +SC_SCF_SCB_INTERFACE_BUSY = 389 +SC_SCB_BUSY = 390 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY = 391 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL = 392 +SC_PBB_BIN_HIST_NUM_PRIMS = 393 +SC_PBB_BATCH_HIST_NUM_PRIMS = 394 +SC_PBB_BIN_HIST_NUM_CONTEXTS = 395 +SC_PBB_BATCH_HIST_NUM_CONTEXTS = 396 +SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES = 397 +SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES = 398 +SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS = 399 +SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS = 400 +SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM = 401 +SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW = 402 +SC_PBB_BUSY = 403 +SC_PBB_BUSY_AND_NO_SENDS = 404 +SC_PBB_STALLS_PA_DUE_TO_NO_TILES = 405 +SC_PBB_NUM_BINS = 406 +SC_PBB_END_OF_BIN = 407 +SC_PBB_END_OF_BATCH = 408 +SC_PBB_PRIMBIN_PROCESSED = 409 +SC_PBB_PRIM_ADDED_TO_BATCH = 410 +SC_PBB_NONBINNED_PRIM = 411 +SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB = 412 +SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB = 413 +SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION = 414 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW = 415 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN = 416 +SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE = 417 +SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE = 418 +SC_PBB_BATCH_BREAK_DUE_TO_PRIM = 419 +SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE = 420 +SC_PBB_BATCH_BREAK_DUE_TO_EVENT = 421 +SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT = 422 +SC_PERF_SEL_RESERVED_423 = 423 +SC_PERF_SEL_RESERVED_424 = 424 +SC_PERF_SEL_RESERVED_425 = 425 +SC_PERF_SEL_RESERVED_426 = 426 +SC_PERF_SEL_RESERVED_427 = 427 +SC_PERF_SEL_RESERVED_428 = 428 +SC_PERF_SEL_RESERVED_429 = 429 +SC_PERF_SEL_RESERVED_430 = 430 +SC_PERF_SEL_RESERVED_431 = 431 +SC_PERF_SEL_RESERVED_432 = 432 +SC_PERF_SEL_RESERVED_433 = 433 +SC_PERF_SEL_RESERVED_434 = 434 +SC_PERF_SEL_RESERVED_435 = 435 +SC_PERF_SEL_RESERVED_436 = 436 +SC_GRP5_DYN_SCLK_BUSY = 437 +SC_GRP6_DYN_SCLK_BUSY = 438 +SC_GRP7_DYN_SCLK_BUSY = 439 +SC_GRP8_DYN_SCLK_BUSY = 440 +SC_GRP9_DYN_SCLK_BUSY = 441 +SC_PS_TO_BE_SCLK_GATE_STALL = 442 +SC_PA_TO_PBB_SCLK_GATE_STALL_STALL = 443 +SC_PK_BUSY = 444 +SC_PK_MAX_DEALLOC_FORCE_EOV = 445 +SC_PK_DEALLOC_WAVE_BREAK = 446 +SC_SPI_SEND = 447 +SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 448 +SC_SPI_CREDIT_AT_MAX = 449 +SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND = 450 +SC_BCI_SEND = 451 +SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND = 452 +SC_BCI_CREDIT_AT_MAX = 453 +SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND = 454 +SC_SPIBC_FULL_FREEZE = 455 +SC_PW_BM_PASS_EMPTY_PRIM = 456 +SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM = 457 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0 = 458 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1 = 459 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2 = 460 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3 = 461 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4 = 462 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5 = 463 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6 = 464 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7 = 465 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8 = 466 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9 = 467 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10 = 468 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11 = 469 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12 = 470 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13 = 471 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14 = 472 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15 = 473 +SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16 = 474 +SC_DB0_TILE_INTERFACE_BUSY = 475 +SC_DB0_TILE_INTERFACE_SEND = 476 +SC_DB0_TILE_INTERFACE_SEND_EVENT = 477 +SC_PERF_SEL_RESERVED_478 = 478 +SC_PERF_SEL_RESERVED_479 = 479 +SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND = 480 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX = 481 +SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND = 482 +SC_PERF_SEL_RESERVED_483 = 483 +SC_PERF_SEL_RESERVED_484 = 484 +SC_PERF_SEL_RESERVED_485 = 485 +SC_PERF_SEL_RESERVED_486 = 486 +SC_PERF_SEL_RESERVED_487 = 487 +SC_PERF_SEL_RESERVED_488 = 488 +SC_PERF_SEL_RESERVED_489 = 489 +SC_PERF_SEL_RESERVED_490 = 490 +SC_BACKEND_PRIM_FIFO_FULL = 491 +SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER = 492 +SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH = 493 +SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH = 494 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT = 495 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT = 496 +SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV = 497 +SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE = 498 +SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE = 499 +SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT = 500 +SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET = 501 +SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE = 502 +SC_STALLED_BY_DB0_TILEFIFO = 503 +SC_DB0_QUAD_INTF_SEND = 504 +SC_DB0_QUAD_INTF_BUSY = 505 +SC_DB0_QUAD_INTF_STALLED_BY_DB = 506 +SC_DB0_QUAD_INTF_CREDIT_AT_MAX = 507 +SC_DB0_QUAD_INTF_IDLE = 508 +SC_PERF_SEL_RESERVED_509 = 509 +SC_PERF_SEL_RESERVED_510 = 510 +SC_PERF_SEL_RESERVED_511 = 511 +SC_PERF_SEL_RESERVED_512 = 512 +SC_PERF_SEL_RESERVED_513 = 513 +SC_PERF_SEL_RESERVED_514 = 514 +SC_PKR_WAVE_BREAK_OUTSIDE_REGION = 515 +SC_PKR_WAVE_BREAK_FULL_TILE = 516 +SC_RESERVED_60 = 517 +SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN = 518 +SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT = 519 +SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL = 520 +SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL = 521 +SC_DB0_TILE_MASK_FIFO_FULL = 522 +SC_PERF_SEL_RESERVED_523 = 523 +SC_PERF_SEL_RESERVED_524 = 524 +SC_PERF_SEL_RESERVED_525 = 525 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL = 526 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL = 527 +SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL = 528 +SC_PS_PM_PFF_PW_FULL = 529 +SC_PS_PM_ZFF_PW_FULL = 530 +SC_PS_PM_PBB_TO_PSE_FIFO_FULL = 531 +SC_PERF_SEL_RESERVED_532 = 532 +SC_PERF_SEL_RESERVED_533 = 533 +SC_PERF_SEL_RESERVED_534 = 534 +SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H = 535 +SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H = 536 +SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H = 537 +SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H = 538 +SC_PERF_SEL_RESERVED_539 = 539 +SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H = 540 +SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H = 541 +SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H = 542 +SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H = 543 +SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H = 544 +SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H = 545 +SC_PK_PM_FULL_TILE_WAVE_BRK_1H = 546 +SC_PK_PM_OREO_CONFLICT_QUAD_FORCE_EOV_WAVE_BRK_1H = 547 +SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H = 548 +SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H = 549 +SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H = 550 +SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H = 551 +SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD = 552 +SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD = 553 +SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD = 554 +SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD = 555 +SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD = 556 +SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD = 557 +SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD = 558 +SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD = 559 +SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD = 560 +SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD = 561 +SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD = 562 +SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD = 563 +SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD = 564 +SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD = 565 +SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD = 566 +SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD = 567 +SC_PERF_SEL_RESERVED_568 = 568 +SC_PBB_RESERVED = 569 +SC_BM_BE0_STALLED = 570 +SC_BM_BE1_STALLED = 571 +SC_BM_BE2_STALLED = 572 +SC_BM_BE3_STALLED = 573 +SC_BM_MULTI_ACCUM_1_BE_STALLED = 574 +SC_BM_MULTI_ACCUM_2_BE_STALLED = 575 +SC_BM_MULTI_ACCUM_3_BE_STALLED = 576 +SC_BM_MULTI_ACCUM_4_BE_STALLED = 577 +SC_PBB_READ_PH0 = 578 +SC_PBB_READ_DEALLOC_4_0 = 579 +SC_PBB_READ_DEALLOC_7_5 = 580 +SC_PBB_READ_FPOG_4_0 = 581 +SC_PBB_READ_FPOG_7_5 = 582 +SC_VRC_SECTOR_HIT = 583 +SC_VRC_TAG_MISS = 584 +SC_VRC_SECTOR_MISS = 585 +SC_VRC_LRU_EVICT_STALL = 586 +SC_VRC_LRU_EVICT_SCHEDULED_EVICT_STALL = 587 +SC_VRC_LRU_EVICT_PENDING_EVICT_STALL = 588 +SC_VRC_REEVICTION_STALL = 589 +SC_VRC_EVICT_NONZERO_INFLIGHT_STALL = 590 +SC_VRC_REPLACE_SCHEDULED_EVICT_STALL = 591 +SC_VRC_REPLACE_PENDING_EVICT_STALL = 592 +SC_VRC_REPLACE_FLUSH_IN_PROGRESS_STALL = 593 +SC_VRC_INFLIGHT_COUNTER_MAXIMUM_STALL = 594 +SC_VRC_READ_OUTPUT_STALL = 595 +SC_VRC_WRITE_OUTPUT_STALL = 596 +SC_VRC_ACK_OUTPUT_STALL = 597 +SC_VRC_FLUSH_EVICT_STALL = 598 +SC_VRC_FLUSH_REFLUSH_STALL = 599 +SC_VRC_FLUSH_FIP_HIT_STALL = 600 +SC_VRC_FLUSH_WRREQ_DRAIN_STALL = 601 +SC_VRC_FLUSH_DONE_STALL = 602 +SC_VRC_FLUSH_STALL = 603 +SC_VRC_STALL = 604 +SC_VRC_FLUSH = 605 +SC_VRC_SECTORS_FLUSHED = 606 +SC_VRC_DIRTY_SECTORS_FLUSHED = 607 +SC_VRC_TAGS_FLUSHED = 608 +SC_VRC_HPF_REQ = 609 +SC_VRC_HPF_EVENT = 610 +SC_VRC_HPF_STALLED = 611 +SC_VRC_PROBE_ACK_TILES = 612 +SC_VRC_GL1X_RD_REQ = 613 +SC_VRC_GL1X_WR_REQ = 614 +SC_VRC_GL1X_SRC_XFR = 615 +SC_VRC_GL1X_RD_RET = 616 +SC_VRC_GL1X_WR_ACK = 617 +SC_VRC_GL1X_RD_XNACK = 618 +SC_VRC_GL1X_WR_XNACK = 619 +SC_VRC_GL1X_REQ_STALLED = 620 +SC_VRC_GL1X_SRC_STALLED = 621 +SC_VRC_RATEMEM_WE_CNT = 622 +SC_VRC_RATEMEM_RE_CNT = 623 +SC_VRC_HINTMEM_WE_CNT = 624 +SC_VRC_HINTMEM_RE_CNT = 625 +SC_VRC_BUSY = 626 +SC_GL1X_BUSY = 627 +SC_BE_VRS_RD_REQ = 628 +SC_BE_VRS_RD_REQ_STALLED = 629 +SC_BE_VRS_RD_REQ_HIT = 630 +SC_BE_VRS_RD_RET = 631 +SC_BE_VRS_RD_RET_STALLED = 632 +SC_BE_VRS_FB_RET = 633 +SC_BE_VRS_FB_RET_STALLED = 634 +SC_BE_VRS_FB_RET_HIT = 635 +SC_VRS_BE_BUSY = 636 +SC_PWS_CS_EVENTS_PWS_ENABLE = 637 +SC_PWS_PS_EVENTS_PWS_ENABLE = 638 +SC_PWS_TS_EVENTS_PWS_ENABLE = 639 +SC_PWS_STALLED = 640 +SC_PWS_P0_CS_SYNC_COMPLETE = 641 +SC_PWS_P0_PS_SYNC_COMPLETE = 642 +SC_PWS_P0_TS_SYNC_COMPLETE = 643 +SC_PWS_P1_CS_SYNC_COMPLETE = 644 +SC_PWS_P1_PS_SYNC_COMPLETE = 645 +SC_PWS_P1_TS_SYNC_COMPLETE = 646 +SC_PKR_PC_NO_CREDITS = 647 +SC_PKR_PC_STALLED = 648 +SC_PKR_PC_SEND = 649 +SC_PKR_PC_SEND_PRIM_VALID_1 = 650 +SC_PKR_PC_SEND_PRIM_VALID_0 = 651 +SC_PKR_PC_SEND_TRUE_PRIM = 652 +SC_PKR_PC_SEND_EOV = 653 +SC_PKR_PC_SEND_EVENT = 654 +SC_PKR_DB_WAVE_STALL = 655 +SC_PKR_PSINVOC_SEDC_FIFO_FULL = 656 +SC_PKR_OREO_STALLED_BY_NO_VALID_WAIVE_ID = 657 +SC_PKR_SPI_QUAD_COUNT = 658 +SC_PKR_DB_OREO_WAVE_QUAD_COUNT = 659 +SC_PKR_BCI_QUAD_NEW_PRIM = 660 +SC_SPI_WAVE_STALLED_BY_SPI = 661 +SC_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ScMap' +ScMap__enumvalues = { + 0: 'RASTER_CONFIG_SC_MAP_0', + 1: 'RASTER_CONFIG_SC_MAP_1', + 2: 'RASTER_CONFIG_SC_MAP_2', + 3: 'RASTER_CONFIG_SC_MAP_3', +} +RASTER_CONFIG_SC_MAP_0 = 0 +RASTER_CONFIG_SC_MAP_1 = 1 +RASTER_CONFIG_SC_MAP_2 = 2 +RASTER_CONFIG_SC_MAP_3 = 3 +ScMap = ctypes.c_uint32 # enum + +# values for enumeration 'ScUncertaintyRegionMode' +ScUncertaintyRegionMode__enumvalues = { + 0: 'SC_HALF_LSB', + 1: 'SC_LSB_ONE_SIDED', + 2: 'SC_LSB_TWO_SIDED', +} +SC_HALF_LSB = 0 +SC_LSB_ONE_SIDED = 1 +SC_LSB_TWO_SIDED = 2 +ScUncertaintyRegionMode = ctypes.c_uint32 # enum + +# values for enumeration 'ScUncertaintyRegionMult' +ScUncertaintyRegionMult__enumvalues = { + 0: 'SC_UR_1X', + 1: 'SC_UR_2X', + 2: 'SC_UR_4X', + 3: 'SC_UR_8X', +} +SC_UR_1X = 0 +SC_UR_2X = 1 +SC_UR_4X = 2 +SC_UR_8X = 3 +ScUncertaintyRegionMult = ctypes.c_uint32 # enum + +# values for enumeration 'ScXsel' +ScXsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_XSEL_64_WIDE_TILE = 3 +ScXsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScYsel' +ScYsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_YSEL_64_WIDE_TILE = 3 +ScYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeMap' +SeMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_MAP_0', + 1: 'RASTER_CONFIG_SE_MAP_1', + 2: 'RASTER_CONFIG_SE_MAP_2', + 3: 'RASTER_CONFIG_SE_MAP_3', +} +RASTER_CONFIG_SE_MAP_0 = 0 +RASTER_CONFIG_SE_MAP_1 = 1 +RASTER_CONFIG_SE_MAP_2 = 2 +RASTER_CONFIG_SE_MAP_3 = 3 +SeMap = ctypes.c_uint32 # enum + +# values for enumeration 'SePairMap' +SePairMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_MAP_0', + 1: 'RASTER_CONFIG_SE_PAIR_MAP_1', + 2: 'RASTER_CONFIG_SE_PAIR_MAP_2', + 3: 'RASTER_CONFIG_SE_PAIR_MAP_3', +} +RASTER_CONFIG_SE_PAIR_MAP_0 = 0 +RASTER_CONFIG_SE_PAIR_MAP_1 = 1 +RASTER_CONFIG_SE_PAIR_MAP_2 = 2 +RASTER_CONFIG_SE_PAIR_MAP_3 = 3 +SePairMap = ctypes.c_uint32 # enum + +# values for enumeration 'SePairXsel' +SePairXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE = 3 +SePairXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairYsel' +SePairYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE = 3 +SePairYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeXsel' +SeXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_XSEL_64_WIDE_TILE = 3 +SeXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeYsel' +SeYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SE_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_YSEL_64_WIDE_TILE = 3 +SeYsel = ctypes.c_uint32 # enum + +# values for enumeration 'VRSCombinerModeSC' +VRSCombinerModeSC__enumvalues = { + 0: 'SC_VRS_COMB_MODE_PASSTHRU', + 1: 'SC_VRS_COMB_MODE_OVERRIDE', + 2: 'SC_VRS_COMB_MODE_MIN', + 3: 'SC_VRS_COMB_MODE_MAX', + 4: 'SC_VRS_COMB_MODE_SATURATE', +} +SC_VRS_COMB_MODE_PASSTHRU = 0 +SC_VRS_COMB_MODE_OVERRIDE = 1 +SC_VRS_COMB_MODE_MIN = 2 +SC_VRS_COMB_MODE_MAX = 3 +SC_VRS_COMB_MODE_SATURATE = 4 +VRSCombinerModeSC = ctypes.c_uint32 # enum + +# values for enumeration 'VRSrate' +VRSrate__enumvalues = { + 0: 'VRS_SHADING_RATE_1X1', + 1: 'VRS_SHADING_RATE_1X2', + 2: 'VRS_SHADING_RATE_UNDEFINED0', + 3: 'VRS_SHADING_RATE_UNDEFINED1', + 4: 'VRS_SHADING_RATE_2X1', + 5: 'VRS_SHADING_RATE_2X2', + 6: 'VRS_SHADING_RATE_2X4', + 7: 'VRS_SHADING_RATE_UNDEFINED2', + 8: 'VRS_SHADING_RATE_UNDEFINED3', + 9: 'VRS_SHADING_RATE_4X2', + 10: 'VRS_SHADING_RATE_4X4', + 11: 'VRS_SHADING_RATE_UNDEFINED4', + 12: 'VRS_SHADING_RATE_16X_SSAA', + 13: 'VRS_SHADING_RATE_8X_SSAA', + 14: 'VRS_SHADING_RATE_4X_SSAA', + 15: 'VRS_SHADING_RATE_2X_SSAA', +} +VRS_SHADING_RATE_1X1 = 0 +VRS_SHADING_RATE_1X2 = 1 +VRS_SHADING_RATE_UNDEFINED0 = 2 +VRS_SHADING_RATE_UNDEFINED1 = 3 +VRS_SHADING_RATE_2X1 = 4 +VRS_SHADING_RATE_2X2 = 5 +VRS_SHADING_RATE_2X4 = 6 +VRS_SHADING_RATE_UNDEFINED2 = 7 +VRS_SHADING_RATE_UNDEFINED3 = 8 +VRS_SHADING_RATE_4X2 = 9 +VRS_SHADING_RATE_4X4 = 10 +VRS_SHADING_RATE_UNDEFINED4 = 11 +VRS_SHADING_RATE_16X_SSAA = 12 +VRS_SHADING_RATE_8X_SSAA = 13 +VRS_SHADING_RATE_4X_SSAA = 14 +VRS_SHADING_RATE_2X_SSAA = 15 +VRSrate = ctypes.c_uint32 # enum + +# values for enumeration 'TC_EA_CID' +TC_EA_CID__enumvalues = { + 0: 'TC_EA_CID_RT', + 1: 'TC_EA_CID_FMASK', + 2: 'TC_EA_CID_DCC', + 3: 'TC_EA_CID_TCPMETA', + 4: 'TC_EA_CID_Z', + 5: 'TC_EA_CID_STENCIL', + 6: 'TC_EA_CID_HTILE', + 7: 'TC_EA_CID_MISC', + 8: 'TC_EA_CID_TCP', + 9: 'TC_EA_CID_SQC', + 10: 'TC_EA_CID_CPF', + 11: 'TC_EA_CID_CPG', + 12: 'TC_EA_CID_IA', + 13: 'TC_EA_CID_WD', + 14: 'TC_EA_CID_PA', + 15: 'TC_EA_CID_UTCL2_TPI', +} +TC_EA_CID_RT = 0 +TC_EA_CID_FMASK = 1 +TC_EA_CID_DCC = 2 +TC_EA_CID_TCPMETA = 3 +TC_EA_CID_Z = 4 +TC_EA_CID_STENCIL = 5 +TC_EA_CID_HTILE = 6 +TC_EA_CID_MISC = 7 +TC_EA_CID_TCP = 8 +TC_EA_CID_SQC = 9 +TC_EA_CID_CPF = 10 +TC_EA_CID_CPG = 11 +TC_EA_CID_IA = 12 +TC_EA_CID_WD = 13 +TC_EA_CID_PA = 14 +TC_EA_CID_UTCL2_TPI = 15 +TC_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'TC_NACKS' +TC_NACKS__enumvalues = { + 0: 'TC_NACK_NO_FAULT', + 1: 'TC_NACK_PAGE_FAULT', + 2: 'TC_NACK_PROTECTION_FAULT', + 3: 'TC_NACK_DATA_ERROR', +} +TC_NACK_NO_FAULT = 0 +TC_NACK_PAGE_FAULT = 1 +TC_NACK_PROTECTION_FAULT = 2 +TC_NACK_DATA_ERROR = 3 +TC_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP' +TC_OP__enumvalues = { + 0: 'TC_OP_READ', + 1: 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'TC_OP_ATOMIC_FMIN_RTN_32', + 3: 'TC_OP_ATOMIC_FMAX_RTN_32', + 4: 'TC_OP_RESERVED_FOP_RTN_32_0', + 5: 'TC_OP_RESERVED_FADD_RTN_32', + 6: 'TC_OP_RESERVED_FOP_RTN_32_2', + 7: 'TC_OP_ATOMIC_SWAP_RTN_32', + 8: 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'TC_OP_PROBE_FILTER', + 13: 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 14: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'TC_OP_ATOMIC_ADD_RTN_32', + 16: 'TC_OP_ATOMIC_SUB_RTN_32', + 17: 'TC_OP_ATOMIC_SMIN_RTN_32', + 18: 'TC_OP_ATOMIC_UMIN_RTN_32', + 19: 'TC_OP_ATOMIC_SMAX_RTN_32', + 20: 'TC_OP_ATOMIC_UMAX_RTN_32', + 21: 'TC_OP_ATOMIC_AND_RTN_32', + 22: 'TC_OP_ATOMIC_OR_RTN_32', + 23: 'TC_OP_ATOMIC_XOR_RTN_32', + 24: 'TC_OP_ATOMIC_INC_RTN_32', + 25: 'TC_OP_ATOMIC_DEC_RTN_32', + 26: 'TC_OP_WBINVL1_VOL', + 27: 'TC_OP_WBINVL1_SD', + 28: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 29: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 30: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 31: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 32: 'TC_OP_WRITE', + 33: 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'TC_OP_ATOMIC_FMIN_RTN_64', + 35: 'TC_OP_ATOMIC_FMAX_RTN_64', + 36: 'TC_OP_RESERVED_FOP_RTN_64_0', + 37: 'TC_OP_RESERVED_FOP_RTN_64_1', + 38: 'TC_OP_RESERVED_FOP_RTN_64_2', + 39: 'TC_OP_ATOMIC_SWAP_RTN_64', + 40: 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 44: 'TC_OP_WBINVL2_SD', + 45: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 46: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 47: 'TC_OP_ATOMIC_ADD_RTN_64', + 48: 'TC_OP_ATOMIC_SUB_RTN_64', + 49: 'TC_OP_ATOMIC_SMIN_RTN_64', + 50: 'TC_OP_ATOMIC_UMIN_RTN_64', + 51: 'TC_OP_ATOMIC_SMAX_RTN_64', + 52: 'TC_OP_ATOMIC_UMAX_RTN_64', + 53: 'TC_OP_ATOMIC_AND_RTN_64', + 54: 'TC_OP_ATOMIC_OR_RTN_64', + 55: 'TC_OP_ATOMIC_XOR_RTN_64', + 56: 'TC_OP_ATOMIC_INC_RTN_64', + 57: 'TC_OP_ATOMIC_DEC_RTN_64', + 58: 'TC_OP_WBL2_NC', + 59: 'TC_OP_WBL2_WC', + 60: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 61: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 62: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 63: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', + 64: 'TC_OP_WBINVL1', + 65: 'TC_OP_ATOMIC_FCMPSWAP_32', + 66: 'TC_OP_ATOMIC_FMIN_32', + 67: 'TC_OP_ATOMIC_FMAX_32', + 68: 'TC_OP_RESERVED_FOP_32_0', + 69: 'TC_OP_RESERVED_FADD_32', + 70: 'TC_OP_RESERVED_FOP_32_2', + 71: 'TC_OP_ATOMIC_SWAP_32', + 72: 'TC_OP_ATOMIC_CMPSWAP_32', + 73: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'TC_OP_INV_METADATA', + 77: 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 78: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 79: 'TC_OP_ATOMIC_ADD_32', + 80: 'TC_OP_ATOMIC_SUB_32', + 81: 'TC_OP_ATOMIC_SMIN_32', + 82: 'TC_OP_ATOMIC_UMIN_32', + 83: 'TC_OP_ATOMIC_SMAX_32', + 84: 'TC_OP_ATOMIC_UMAX_32', + 85: 'TC_OP_ATOMIC_AND_32', + 86: 'TC_OP_ATOMIC_OR_32', + 87: 'TC_OP_ATOMIC_XOR_32', + 88: 'TC_OP_ATOMIC_INC_32', + 89: 'TC_OP_ATOMIC_DEC_32', + 90: 'TC_OP_INVL2_NC', + 91: 'TC_OP_NOP_RTN0', + 92: 'TC_OP_RESERVED_NON_FLOAT_32_1', + 93: 'TC_OP_RESERVED_NON_FLOAT_32_2', + 94: 'TC_OP_RESERVED_NON_FLOAT_32_3', + 95: 'TC_OP_RESERVED_NON_FLOAT_32_4', + 96: 'TC_OP_WBINVL2', + 97: 'TC_OP_ATOMIC_FCMPSWAP_64', + 98: 'TC_OP_ATOMIC_FMIN_64', + 99: 'TC_OP_ATOMIC_FMAX_64', + 100: 'TC_OP_RESERVED_FOP_64_0', + 101: 'TC_OP_RESERVED_FOP_64_1', + 102: 'TC_OP_RESERVED_FOP_64_2', + 103: 'TC_OP_ATOMIC_SWAP_64', + 104: 'TC_OP_ATOMIC_CMPSWAP_64', + 105: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 108: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 109: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 110: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 111: 'TC_OP_ATOMIC_ADD_64', + 112: 'TC_OP_ATOMIC_SUB_64', + 113: 'TC_OP_ATOMIC_SMIN_64', + 114: 'TC_OP_ATOMIC_UMIN_64', + 115: 'TC_OP_ATOMIC_SMAX_64', + 116: 'TC_OP_ATOMIC_UMAX_64', + 117: 'TC_OP_ATOMIC_AND_64', + 118: 'TC_OP_ATOMIC_OR_64', + 119: 'TC_OP_ATOMIC_XOR_64', + 120: 'TC_OP_ATOMIC_INC_64', + 121: 'TC_OP_ATOMIC_DEC_64', + 122: 'TC_OP_WBINVL2_NC', + 123: 'TC_OP_NOP_ACK', + 124: 'TC_OP_RESERVED_NON_FLOAT_64_1', + 125: 'TC_OP_RESERVED_NON_FLOAT_64_2', + 126: 'TC_OP_RESERVED_NON_FLOAT_64_3', + 127: 'TC_OP_RESERVED_NON_FLOAT_64_4', +} +TC_OP_READ = 0 +TC_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +TC_OP_ATOMIC_FMIN_RTN_32 = 2 +TC_OP_ATOMIC_FMAX_RTN_32 = 3 +TC_OP_RESERVED_FOP_RTN_32_0 = 4 +TC_OP_RESERVED_FADD_RTN_32 = 5 +TC_OP_RESERVED_FOP_RTN_32_2 = 6 +TC_OP_ATOMIC_SWAP_RTN_32 = 7 +TC_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +TC_OP_PROBE_FILTER = 12 +TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32 = 13 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +TC_OP_ATOMIC_ADD_RTN_32 = 15 +TC_OP_ATOMIC_SUB_RTN_32 = 16 +TC_OP_ATOMIC_SMIN_RTN_32 = 17 +TC_OP_ATOMIC_UMIN_RTN_32 = 18 +TC_OP_ATOMIC_SMAX_RTN_32 = 19 +TC_OP_ATOMIC_UMAX_RTN_32 = 20 +TC_OP_ATOMIC_AND_RTN_32 = 21 +TC_OP_ATOMIC_OR_RTN_32 = 22 +TC_OP_ATOMIC_XOR_RTN_32 = 23 +TC_OP_ATOMIC_INC_RTN_32 = 24 +TC_OP_ATOMIC_DEC_RTN_32 = 25 +TC_OP_WBINVL1_VOL = 26 +TC_OP_WBINVL1_SD = 27 +TC_OP_RESERVED_NON_FLOAT_RTN_32_0 = 28 +TC_OP_RESERVED_NON_FLOAT_RTN_32_1 = 29 +TC_OP_RESERVED_NON_FLOAT_RTN_32_2 = 30 +TC_OP_RESERVED_NON_FLOAT_RTN_32_3 = 31 +TC_OP_WRITE = 32 +TC_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +TC_OP_ATOMIC_FMIN_RTN_64 = 34 +TC_OP_ATOMIC_FMAX_RTN_64 = 35 +TC_OP_RESERVED_FOP_RTN_64_0 = 36 +TC_OP_RESERVED_FOP_RTN_64_1 = 37 +TC_OP_RESERVED_FOP_RTN_64_2 = 38 +TC_OP_ATOMIC_SWAP_RTN_64 = 39 +TC_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +TC_OP_WBINVL2_SD = 44 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0 = 45 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1 = 46 +TC_OP_ATOMIC_ADD_RTN_64 = 47 +TC_OP_ATOMIC_SUB_RTN_64 = 48 +TC_OP_ATOMIC_SMIN_RTN_64 = 49 +TC_OP_ATOMIC_UMIN_RTN_64 = 50 +TC_OP_ATOMIC_SMAX_RTN_64 = 51 +TC_OP_ATOMIC_UMAX_RTN_64 = 52 +TC_OP_ATOMIC_AND_RTN_64 = 53 +TC_OP_ATOMIC_OR_RTN_64 = 54 +TC_OP_ATOMIC_XOR_RTN_64 = 55 +TC_OP_ATOMIC_INC_RTN_64 = 56 +TC_OP_ATOMIC_DEC_RTN_64 = 57 +TC_OP_WBL2_NC = 58 +TC_OP_WBL2_WC = 59 +TC_OP_RESERVED_NON_FLOAT_RTN_64_1 = 60 +TC_OP_RESERVED_NON_FLOAT_RTN_64_2 = 61 +TC_OP_RESERVED_NON_FLOAT_RTN_64_3 = 62 +TC_OP_RESERVED_NON_FLOAT_RTN_64_4 = 63 +TC_OP_WBINVL1 = 64 +TC_OP_ATOMIC_FCMPSWAP_32 = 65 +TC_OP_ATOMIC_FMIN_32 = 66 +TC_OP_ATOMIC_FMAX_32 = 67 +TC_OP_RESERVED_FOP_32_0 = 68 +TC_OP_RESERVED_FADD_32 = 69 +TC_OP_RESERVED_FOP_32_2 = 70 +TC_OP_ATOMIC_SWAP_32 = 71 +TC_OP_ATOMIC_CMPSWAP_32 = 72 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +TC_OP_INV_METADATA = 76 +TC_OP_ATOMIC_FADD_FLUSH_DENORM_32 = 77 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2 = 78 +TC_OP_ATOMIC_ADD_32 = 79 +TC_OP_ATOMIC_SUB_32 = 80 +TC_OP_ATOMIC_SMIN_32 = 81 +TC_OP_ATOMIC_UMIN_32 = 82 +TC_OP_ATOMIC_SMAX_32 = 83 +TC_OP_ATOMIC_UMAX_32 = 84 +TC_OP_ATOMIC_AND_32 = 85 +TC_OP_ATOMIC_OR_32 = 86 +TC_OP_ATOMIC_XOR_32 = 87 +TC_OP_ATOMIC_INC_32 = 88 +TC_OP_ATOMIC_DEC_32 = 89 +TC_OP_INVL2_NC = 90 +TC_OP_NOP_RTN0 = 91 +TC_OP_RESERVED_NON_FLOAT_32_1 = 92 +TC_OP_RESERVED_NON_FLOAT_32_2 = 93 +TC_OP_RESERVED_NON_FLOAT_32_3 = 94 +TC_OP_RESERVED_NON_FLOAT_32_4 = 95 +TC_OP_WBINVL2 = 96 +TC_OP_ATOMIC_FCMPSWAP_64 = 97 +TC_OP_ATOMIC_FMIN_64 = 98 +TC_OP_ATOMIC_FMAX_64 = 99 +TC_OP_RESERVED_FOP_64_0 = 100 +TC_OP_RESERVED_FOP_64_1 = 101 +TC_OP_RESERVED_FOP_64_2 = 102 +TC_OP_ATOMIC_SWAP_64 = 103 +TC_OP_ATOMIC_CMPSWAP_64 = 104 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0 = 108 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1 = 109 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2 = 110 +TC_OP_ATOMIC_ADD_64 = 111 +TC_OP_ATOMIC_SUB_64 = 112 +TC_OP_ATOMIC_SMIN_64 = 113 +TC_OP_ATOMIC_UMIN_64 = 114 +TC_OP_ATOMIC_SMAX_64 = 115 +TC_OP_ATOMIC_UMAX_64 = 116 +TC_OP_ATOMIC_AND_64 = 117 +TC_OP_ATOMIC_OR_64 = 118 +TC_OP_ATOMIC_XOR_64 = 119 +TC_OP_ATOMIC_INC_64 = 120 +TC_OP_ATOMIC_DEC_64 = 121 +TC_OP_WBINVL2_NC = 122 +TC_OP_NOP_ACK = 123 +TC_OP_RESERVED_NON_FLOAT_64_1 = 124 +TC_OP_RESERVED_NON_FLOAT_64_2 = 125 +TC_OP_RESERVED_NON_FLOAT_64_3 = 126 +TC_OP_RESERVED_NON_FLOAT_64_4 = 127 +TC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP_MASKS' +TC_OP_MASKS__enumvalues = { + 8: 'TC_OP_MASK_FLUSH_DENROM', + 32: 'TC_OP_MASK_64', + 64: 'TC_OP_MASK_NO_RTN', +} +TC_OP_MASK_FLUSH_DENROM = 8 +TC_OP_MASK_64 = 32 +TC_OP_MASK_NO_RTN = 64 +TC_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_BASE_MODE' +CLKGATE_BASE_MODE__enumvalues = { + 0: 'MULT_8', + 1: 'MULT_16', +} +MULT_8 = 0 +MULT_16 = 1 +CLKGATE_BASE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_SM_MODE' +CLKGATE_SM_MODE__enumvalues = { + 0: 'ON_SEQ', + 1: 'OFF_SEQ', + 2: 'PROG_SEQ', + 3: 'READ_SEQ', + 4: 'SM_MODE_RESERVED', +} +ON_SEQ = 0 +OFF_SEQ = 1 +PROG_SEQ = 2 +READ_SEQ = 3 +SM_MODE_RESERVED = 4 +CLKGATE_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CovToShaderSel' +CovToShaderSel__enumvalues = { + 0: 'INPUT_COVERAGE', + 1: 'INPUT_INNER_COVERAGE', + 2: 'INPUT_DEPTH_COVERAGE', + 3: 'RAW', +} +INPUT_COVERAGE = 0 +INPUT_INNER_COVERAGE = 1 +INPUT_DEPTH_COVERAGE = 2 +RAW = 3 +CovToShaderSel = ctypes.c_uint32 # enum + +# values for enumeration 'PC_PERFCNT_SEL' +PC_PERFCNT_SEL__enumvalues = { + 0: 'PC_PERF_SC_PC_PTR_SEND0', + 1: 'PC_PERF_SC_PC_PTR_VALID0', + 2: 'PC_PERF_SC_FPOSG0', + 3: 'PC_PERF_SC_FPOSG_WAIT0', + 4: 'PC_PERF_SC_WAIT_SYNC0', + 5: 'PC_PERF_SC_PQ_FREEZE0', + 6: 'PC_PERF_PKR0_FPOSG_EQ1', + 7: 'PC_PERF_PKR0_FPOSG_GT1', + 8: 'PC_PERF_PKR0_FPOSG_GT16', + 9: 'PC_PERF_PKR0_FPOSG_GT64', + 10: 'PC_PERF_PKR0_FPOSG_GT128', + 11: 'PC_PERF_PKR0_FPOSG_OUT_OF_WAVE', + 12: 'PC_PERF_PKR0_NUM_PROBES', + 13: 'PC_PERF_PKR0_PRIMS_PER_PROBE_EQ1', + 14: 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT1', + 15: 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT2', + 16: 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT4', + 17: 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT8', + 18: 'PC_PERF_PKR0_NUM_WAVES', + 19: 'PC_PERF_PKR0_PRIMS_PER_WAVE_EQ1', + 20: 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT1', + 21: 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT2', + 22: 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT4', + 23: 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT8', + 24: 'PC_PERF_PKR0_PROBES_PER_WAVE_EQ1', + 25: 'PC_PERF_PKR0_PROBES_PER_WAVE_GT1', + 26: 'PC_PERF_PKR0_PROBES_PER_WAVE_GT2', + 27: 'PC_PERF_PKR0_PROBES_PER_WAVE_GT4', + 28: 'PC_PERF_PKR0_PROBES_PER_WAVE_GT8', + 29: 'PC_PERF_PKR0_PRIMS_REUSE', + 30: 'PC_PERF_SC_PC_PTR_SEND1', + 31: 'PC_PERF_SC_PC_PTR_VALID1', + 32: 'PC_PERF_SC_FPOSG1', + 33: 'PC_PERF_SC_FPOSG_WAIT1', + 34: 'PC_PERF_SC_WAIT_SYNC1', + 35: 'PC_PERF_SC_PQ_FREEZE1', + 36: 'PC_PERF_PKR1_FPOSG_EQ1', + 37: 'PC_PERF_PKR1_FPOSG_GT1', + 38: 'PC_PERF_PKR1_FPOSG_GT16', + 39: 'PC_PERF_PKR1_FPOSG_GT64', + 40: 'PC_PERF_PKR1_FPOSG_GT128', + 41: 'PC_PERF_PKR1_FPOSG_OUT_OF_WAVE', + 42: 'PC_PERF_PKR1_NUM_PROBES', + 43: 'PC_PERF_PKR1_PRIMS_PER_PROBE_EQ1', + 44: 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT1', + 45: 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT2', + 46: 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT4', + 47: 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT8', + 48: 'PC_PERF_PKR1_NUM_WAVES', + 49: 'PC_PERF_PKR1_PRIMS_PER_WAVE_EQ1', + 50: 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT1', + 51: 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT2', + 52: 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT4', + 53: 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT8', + 54: 'PC_PERF_PKR1_PROBES_PER_WAVE_EQ1', + 55: 'PC_PERF_PKR1_PROBES_PER_WAVE_GT1', + 56: 'PC_PERF_PKR1_PROBES_PER_WAVE_GT2', + 57: 'PC_PERF_PKR1_PROBES_PER_WAVE_GT4', + 58: 'PC_PERF_PKR1_PROBES_PER_WAVE_GT8', + 59: 'PC_PERF_PKR1_PRIMS_REUSE', + 60: 'PC_PERF_SC_PC_PTR_SEND2', + 61: 'PC_PERF_SC_PC_PTR_VALID2', + 62: 'PC_PERF_SC_FPOSG2', + 63: 'PC_PERF_SC_FPOSG_WAIT2', + 64: 'PC_PERF_SC_WAIT_SYNC2', + 65: 'PC_PERF_SC_PQ_FREEZE2', + 66: 'PC_PERF_PKR2_FPOSG_EQ1', + 67: 'PC_PERF_PKR2_FPOSG_GT1', + 68: 'PC_PERF_PKR2_FPOSG_GT16', + 69: 'PC_PERF_PKR2_FPOSG_GT64', + 70: 'PC_PERF_PKR2_FPOSG_GT128', + 71: 'PC_PERF_PKR2_FPOSG_OUT_OF_WAVE', + 72: 'PC_PERF_PKR2_NUM_PROBES', + 73: 'PC_PERF_PKR2_PRIMS_PER_PROBE_EQ1', + 74: 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT1', + 75: 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT2', + 76: 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT4', + 77: 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT8', + 78: 'PC_PERF_PKR2_NUM_WAVES', + 79: 'PC_PERF_PKR2_PRIMS_PER_WAVE_EQ1', + 80: 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT1', + 81: 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT2', + 82: 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT4', + 83: 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT8', + 84: 'PC_PERF_PKR2_PROBES_PER_WAVE_EQ1', + 85: 'PC_PERF_PKR2_PROBES_PER_WAVE_GT1', + 86: 'PC_PERF_PKR2_PROBES_PER_WAVE_GT2', + 87: 'PC_PERF_PKR2_PROBES_PER_WAVE_GT4', + 88: 'PC_PERF_PKR2_PROBES_PER_WAVE_GT8', + 89: 'PC_PERF_PKR2_PRIMS_REUSE', + 90: 'PC_PERF_SC_PC_PTR_SEND3', + 91: 'PC_PERF_SC_PC_PTR_VALID3', + 92: 'PC_PERF_SC_FPOSG3', + 93: 'PC_PERF_SC_FPOSG_WAIT3', + 94: 'PC_PERF_SC_WAIT_SYNC3', + 95: 'PC_PERF_SC_PQ_FREEZE3', + 96: 'PC_PERF_PKR3_FPOSG_EQ1', + 97: 'PC_PERF_PKR3_FPOSG_GT1', + 98: 'PC_PERF_PKR3_FPOSG_GT16', + 99: 'PC_PERF_PKR3_FPOSG_GT64', + 100: 'PC_PERF_PKR3_FPOSG_GT128', + 101: 'PC_PERF_PKR3_FPOSG_OUT_OF_WAVE', + 102: 'PC_PERF_PKR3_NUM_PROBES', + 103: 'PC_PERF_PKR3_PRIMS_PER_PROBE_EQ1', + 104: 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT1', + 105: 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT2', + 106: 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT4', + 107: 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT8', + 108: 'PC_PERF_PKR3_NUM_WAVES', + 109: 'PC_PERF_PKR3_PRIMS_PER_WAVE_EQ1', + 110: 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT1', + 111: 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT2', + 112: 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT4', + 113: 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT8', + 114: 'PC_PERF_PKR3_PROBES_PER_WAVE_EQ1', + 115: 'PC_PERF_PKR3_PROBES_PER_WAVE_GT1', + 116: 'PC_PERF_PKR3_PROBES_PER_WAVE_GT2', + 117: 'PC_PERF_PKR3_PROBES_PER_WAVE_GT4', + 118: 'PC_PERF_PKR3_PROBES_PER_WAVE_GT8', + 119: 'PC_PERF_PKR3_PRIMS_REUSE', + 120: 'PC_PERF_SC_MW_FREEZE', + 121: 'PC_PERF_SC_NUM_PROBES', + 122: 'PC_PERF_SC_NUM_WAVES', + 123: 'PC_PERF_SC_NUM_SPLIT_WAVES', + 124: 'PC_PERF_GE_GSDONE', + 125: 'PC_PERF_PKR0_GSDONE_WHILE_IDLE', + 126: 'PC_PERF_PKR1_GSDONE_WHILE_IDLE', + 127: 'PC_PERF_PKR2_GSDONE_WHILE_IDLE', + 128: 'PC_PERF_PKR3_GSDONE_WHILE_IDLE', + 129: 'PC_PERF_PC_SPI_PROBE_FREEZE', + 130: 'PC_PERF_PC_SPI_PROBE_OUT_OF_CREDIT', + 131: 'PC_PERF_MW_RTN_ADDR_FREEZE', + 132: 'PC_PERF_MW_PROBE_CNT_FREEZE', + 133: 'PC_PERF_MW_GL1H_REQ_FREEZE', + 134: 'PC_PERF_MW_GL1H_NUM_REQS', + 135: 'PC_PERF_MW_DLINE_ALLOC', + 136: 'PC_PERF_MW_DLINE_DEALLOC', + 137: 'PC_PERF_MW_TAGLINE_ALLOC', + 138: 'PC_PERF_MW_TAGLINE_DEALLOC', + 139: 'PC_PERF_MW_PHY_DLINE_FULL_STALL', + 140: 'PC_PERF_MW_CACHE_CNTL_FULL_STALL', + 141: 'PC_PERF_MW_STAMP_LIMIT_STALL', + 142: 'PC_PERF_MW_CACHE_MISS', + 143: 'PC_PERF_MW_CACHE_HIT', + 144: 'PC_PERF_MW_CACHE_REUSE', + 145: 'PC_PERF_MW_DEALLOC_HIT', + 146: 'PC_PERF_PC_MEM_BANK_CONF0', + 147: 'PC_PERF_PC_MEM_BANK_CONF1', + 148: 'PC_PERF_PC_LDS_VERTEX_REUSE0', + 149: 'PC_PERF_PC_LDS_CNTL_VALID0', + 150: 'PC_PERF_PC_LDS_VERTEX_REUSE1', + 151: 'PC_PERF_PC_LDS_CNTL_VALID1', + 152: 'PC_PERF_GRBM_BUSY', + 153: 'PC_PERF_GL1_RTN_CNT_GTE1', + 154: 'PC_PERF_GL1_RTN_CNT_GT512', + 155: 'PC_PERF_GL1_RTN_CNT_GT768', + 156: 'PC_PERF_LWC0_PROBE_ORDER_STALL', + 157: 'PC_PERF_LWC0_PC_MEM_READ_STALL', + 158: 'PC_PERF_LWC0_PKR2_SA_BDRY_CROSSING', + 159: 'PC_PERF_LWC0_PKR3_SA_BDRY_CROSSING', + 160: 'PC_PERF_LWC1_PROBE_ORDER_STALL', + 161: 'PC_PERF_LWC1_PC_MEM_READ_STALL', + 162: 'PC_PERF_LWC1_PKR0_SA_BDRY_CROSSING', + 163: 'PC_PERF_LWC1_PKR1_SA_BDRY_CROSSING', + 164: 'PC_PERF_NUM_PSWAVE', +} +PC_PERF_SC_PC_PTR_SEND0 = 0 +PC_PERF_SC_PC_PTR_VALID0 = 1 +PC_PERF_SC_FPOSG0 = 2 +PC_PERF_SC_FPOSG_WAIT0 = 3 +PC_PERF_SC_WAIT_SYNC0 = 4 +PC_PERF_SC_PQ_FREEZE0 = 5 +PC_PERF_PKR0_FPOSG_EQ1 = 6 +PC_PERF_PKR0_FPOSG_GT1 = 7 +PC_PERF_PKR0_FPOSG_GT16 = 8 +PC_PERF_PKR0_FPOSG_GT64 = 9 +PC_PERF_PKR0_FPOSG_GT128 = 10 +PC_PERF_PKR0_FPOSG_OUT_OF_WAVE = 11 +PC_PERF_PKR0_NUM_PROBES = 12 +PC_PERF_PKR0_PRIMS_PER_PROBE_EQ1 = 13 +PC_PERF_PKR0_PRIMS_PER_PROBE_GT1 = 14 +PC_PERF_PKR0_PRIMS_PER_PROBE_GT2 = 15 +PC_PERF_PKR0_PRIMS_PER_PROBE_GT4 = 16 +PC_PERF_PKR0_PRIMS_PER_PROBE_GT8 = 17 +PC_PERF_PKR0_NUM_WAVES = 18 +PC_PERF_PKR0_PRIMS_PER_WAVE_EQ1 = 19 +PC_PERF_PKR0_PRIMS_PER_WAVE_GT1 = 20 +PC_PERF_PKR0_PRIMS_PER_WAVE_GT2 = 21 +PC_PERF_PKR0_PRIMS_PER_WAVE_GT4 = 22 +PC_PERF_PKR0_PRIMS_PER_WAVE_GT8 = 23 +PC_PERF_PKR0_PROBES_PER_WAVE_EQ1 = 24 +PC_PERF_PKR0_PROBES_PER_WAVE_GT1 = 25 +PC_PERF_PKR0_PROBES_PER_WAVE_GT2 = 26 +PC_PERF_PKR0_PROBES_PER_WAVE_GT4 = 27 +PC_PERF_PKR0_PROBES_PER_WAVE_GT8 = 28 +PC_PERF_PKR0_PRIMS_REUSE = 29 +PC_PERF_SC_PC_PTR_SEND1 = 30 +PC_PERF_SC_PC_PTR_VALID1 = 31 +PC_PERF_SC_FPOSG1 = 32 +PC_PERF_SC_FPOSG_WAIT1 = 33 +PC_PERF_SC_WAIT_SYNC1 = 34 +PC_PERF_SC_PQ_FREEZE1 = 35 +PC_PERF_PKR1_FPOSG_EQ1 = 36 +PC_PERF_PKR1_FPOSG_GT1 = 37 +PC_PERF_PKR1_FPOSG_GT16 = 38 +PC_PERF_PKR1_FPOSG_GT64 = 39 +PC_PERF_PKR1_FPOSG_GT128 = 40 +PC_PERF_PKR1_FPOSG_OUT_OF_WAVE = 41 +PC_PERF_PKR1_NUM_PROBES = 42 +PC_PERF_PKR1_PRIMS_PER_PROBE_EQ1 = 43 +PC_PERF_PKR1_PRIMS_PER_PROBE_GT1 = 44 +PC_PERF_PKR1_PRIMS_PER_PROBE_GT2 = 45 +PC_PERF_PKR1_PRIMS_PER_PROBE_GT4 = 46 +PC_PERF_PKR1_PRIMS_PER_PROBE_GT8 = 47 +PC_PERF_PKR1_NUM_WAVES = 48 +PC_PERF_PKR1_PRIMS_PER_WAVE_EQ1 = 49 +PC_PERF_PKR1_PRIMS_PER_WAVE_GT1 = 50 +PC_PERF_PKR1_PRIMS_PER_WAVE_GT2 = 51 +PC_PERF_PKR1_PRIMS_PER_WAVE_GT4 = 52 +PC_PERF_PKR1_PRIMS_PER_WAVE_GT8 = 53 +PC_PERF_PKR1_PROBES_PER_WAVE_EQ1 = 54 +PC_PERF_PKR1_PROBES_PER_WAVE_GT1 = 55 +PC_PERF_PKR1_PROBES_PER_WAVE_GT2 = 56 +PC_PERF_PKR1_PROBES_PER_WAVE_GT4 = 57 +PC_PERF_PKR1_PROBES_PER_WAVE_GT8 = 58 +PC_PERF_PKR1_PRIMS_REUSE = 59 +PC_PERF_SC_PC_PTR_SEND2 = 60 +PC_PERF_SC_PC_PTR_VALID2 = 61 +PC_PERF_SC_FPOSG2 = 62 +PC_PERF_SC_FPOSG_WAIT2 = 63 +PC_PERF_SC_WAIT_SYNC2 = 64 +PC_PERF_SC_PQ_FREEZE2 = 65 +PC_PERF_PKR2_FPOSG_EQ1 = 66 +PC_PERF_PKR2_FPOSG_GT1 = 67 +PC_PERF_PKR2_FPOSG_GT16 = 68 +PC_PERF_PKR2_FPOSG_GT64 = 69 +PC_PERF_PKR2_FPOSG_GT128 = 70 +PC_PERF_PKR2_FPOSG_OUT_OF_WAVE = 71 +PC_PERF_PKR2_NUM_PROBES = 72 +PC_PERF_PKR2_PRIMS_PER_PROBE_EQ1 = 73 +PC_PERF_PKR2_PRIMS_PER_PROBE_GT1 = 74 +PC_PERF_PKR2_PRIMS_PER_PROBE_GT2 = 75 +PC_PERF_PKR2_PRIMS_PER_PROBE_GT4 = 76 +PC_PERF_PKR2_PRIMS_PER_PROBE_GT8 = 77 +PC_PERF_PKR2_NUM_WAVES = 78 +PC_PERF_PKR2_PRIMS_PER_WAVE_EQ1 = 79 +PC_PERF_PKR2_PRIMS_PER_WAVE_GT1 = 80 +PC_PERF_PKR2_PRIMS_PER_WAVE_GT2 = 81 +PC_PERF_PKR2_PRIMS_PER_WAVE_GT4 = 82 +PC_PERF_PKR2_PRIMS_PER_WAVE_GT8 = 83 +PC_PERF_PKR2_PROBES_PER_WAVE_EQ1 = 84 +PC_PERF_PKR2_PROBES_PER_WAVE_GT1 = 85 +PC_PERF_PKR2_PROBES_PER_WAVE_GT2 = 86 +PC_PERF_PKR2_PROBES_PER_WAVE_GT4 = 87 +PC_PERF_PKR2_PROBES_PER_WAVE_GT8 = 88 +PC_PERF_PKR2_PRIMS_REUSE = 89 +PC_PERF_SC_PC_PTR_SEND3 = 90 +PC_PERF_SC_PC_PTR_VALID3 = 91 +PC_PERF_SC_FPOSG3 = 92 +PC_PERF_SC_FPOSG_WAIT3 = 93 +PC_PERF_SC_WAIT_SYNC3 = 94 +PC_PERF_SC_PQ_FREEZE3 = 95 +PC_PERF_PKR3_FPOSG_EQ1 = 96 +PC_PERF_PKR3_FPOSG_GT1 = 97 +PC_PERF_PKR3_FPOSG_GT16 = 98 +PC_PERF_PKR3_FPOSG_GT64 = 99 +PC_PERF_PKR3_FPOSG_GT128 = 100 +PC_PERF_PKR3_FPOSG_OUT_OF_WAVE = 101 +PC_PERF_PKR3_NUM_PROBES = 102 +PC_PERF_PKR3_PRIMS_PER_PROBE_EQ1 = 103 +PC_PERF_PKR3_PRIMS_PER_PROBE_GT1 = 104 +PC_PERF_PKR3_PRIMS_PER_PROBE_GT2 = 105 +PC_PERF_PKR3_PRIMS_PER_PROBE_GT4 = 106 +PC_PERF_PKR3_PRIMS_PER_PROBE_GT8 = 107 +PC_PERF_PKR3_NUM_WAVES = 108 +PC_PERF_PKR3_PRIMS_PER_WAVE_EQ1 = 109 +PC_PERF_PKR3_PRIMS_PER_WAVE_GT1 = 110 +PC_PERF_PKR3_PRIMS_PER_WAVE_GT2 = 111 +PC_PERF_PKR3_PRIMS_PER_WAVE_GT4 = 112 +PC_PERF_PKR3_PRIMS_PER_WAVE_GT8 = 113 +PC_PERF_PKR3_PROBES_PER_WAVE_EQ1 = 114 +PC_PERF_PKR3_PROBES_PER_WAVE_GT1 = 115 +PC_PERF_PKR3_PROBES_PER_WAVE_GT2 = 116 +PC_PERF_PKR3_PROBES_PER_WAVE_GT4 = 117 +PC_PERF_PKR3_PROBES_PER_WAVE_GT8 = 118 +PC_PERF_PKR3_PRIMS_REUSE = 119 +PC_PERF_SC_MW_FREEZE = 120 +PC_PERF_SC_NUM_PROBES = 121 +PC_PERF_SC_NUM_WAVES = 122 +PC_PERF_SC_NUM_SPLIT_WAVES = 123 +PC_PERF_GE_GSDONE = 124 +PC_PERF_PKR0_GSDONE_WHILE_IDLE = 125 +PC_PERF_PKR1_GSDONE_WHILE_IDLE = 126 +PC_PERF_PKR2_GSDONE_WHILE_IDLE = 127 +PC_PERF_PKR3_GSDONE_WHILE_IDLE = 128 +PC_PERF_PC_SPI_PROBE_FREEZE = 129 +PC_PERF_PC_SPI_PROBE_OUT_OF_CREDIT = 130 +PC_PERF_MW_RTN_ADDR_FREEZE = 131 +PC_PERF_MW_PROBE_CNT_FREEZE = 132 +PC_PERF_MW_GL1H_REQ_FREEZE = 133 +PC_PERF_MW_GL1H_NUM_REQS = 134 +PC_PERF_MW_DLINE_ALLOC = 135 +PC_PERF_MW_DLINE_DEALLOC = 136 +PC_PERF_MW_TAGLINE_ALLOC = 137 +PC_PERF_MW_TAGLINE_DEALLOC = 138 +PC_PERF_MW_PHY_DLINE_FULL_STALL = 139 +PC_PERF_MW_CACHE_CNTL_FULL_STALL = 140 +PC_PERF_MW_STAMP_LIMIT_STALL = 141 +PC_PERF_MW_CACHE_MISS = 142 +PC_PERF_MW_CACHE_HIT = 143 +PC_PERF_MW_CACHE_REUSE = 144 +PC_PERF_MW_DEALLOC_HIT = 145 +PC_PERF_PC_MEM_BANK_CONF0 = 146 +PC_PERF_PC_MEM_BANK_CONF1 = 147 +PC_PERF_PC_LDS_VERTEX_REUSE0 = 148 +PC_PERF_PC_LDS_CNTL_VALID0 = 149 +PC_PERF_PC_LDS_VERTEX_REUSE1 = 150 +PC_PERF_PC_LDS_CNTL_VALID1 = 151 +PC_PERF_GRBM_BUSY = 152 +PC_PERF_GL1_RTN_CNT_GTE1 = 153 +PC_PERF_GL1_RTN_CNT_GT512 = 154 +PC_PERF_GL1_RTN_CNT_GT768 = 155 +PC_PERF_LWC0_PROBE_ORDER_STALL = 156 +PC_PERF_LWC0_PC_MEM_READ_STALL = 157 +PC_PERF_LWC0_PKR2_SA_BDRY_CROSSING = 158 +PC_PERF_LWC0_PKR3_SA_BDRY_CROSSING = 159 +PC_PERF_LWC1_PROBE_ORDER_STALL = 160 +PC_PERF_LWC1_PC_MEM_READ_STALL = 161 +PC_PERF_LWC1_PKR0_SA_BDRY_CROSSING = 162 +PC_PERF_LWC1_PKR1_SA_BDRY_CROSSING = 163 +PC_PERF_NUM_PSWAVE = 164 +PC_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_FOG_MODE' +SPI_FOG_MODE__enumvalues = { + 0: 'SPI_FOG_NONE', + 1: 'SPI_FOG_EXP', + 2: 'SPI_FOG_EXP2', + 3: 'SPI_FOG_LINEAR', +} +SPI_FOG_NONE = 0 +SPI_FOG_EXP = 1 +SPI_FOG_EXP2 = 2 +SPI_FOG_LINEAR = 3 +SPI_FOG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_LB_WAVES_SELECT' +SPI_LB_WAVES_SELECT__enumvalues = { + 0: 'HS_GS', + 1: 'PS', + 2: 'CS_NA', + 3: 'SPI_LB_WAVES_RSVD', +} +HS_GS = 0 +PS = 1 +CS_NA = 2 +SPI_LB_WAVES_RSVD = 3 +SPI_LB_WAVES_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PERFCNT_SEL' +SPI_PERFCNT_SEL__enumvalues = { + 1: 'SPI_PERF_GS_WINDOW_VALID', + 2: 'SPI_PERF_GS_BUSY', + 3: 'SPI_PERF_GS_CRAWLER_STALL', + 4: 'SPI_PERF_GS_EVENT_WAVE', + 5: 'SPI_PERF_GS_WAVE', + 6: 'SPI_PERF_GS_PERS_UPD_FULL0', + 7: 'SPI_PERF_GS_PERS_UPD_FULL1', + 8: 'SPI_PERF_GS_FIRST_SUBGRP', + 9: 'SPI_PERF_GS_HS_DEALLOC', + 10: 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 11: 'SPI_PERF_GS_POS0_STALL', + 12: 'SPI_PERF_GS_POS1_STALL', + 13: 'SPI_PERF_GS_INDX0_STALL', + 14: 'SPI_PERF_GS_INDX1_STALL', + 15: 'SPI_PERF_GS_PWS_STALL', + 16: 'SPI_PERF_GS_GRP_LIFETIME', + 17: 'SPI_PERF_GS_WAVE_IN_FLIGHT', + 18: 'SPI_PERF_GS_GRP_LIFETIME_SAMPLE', + 21: 'SPI_PERF_HS_WINDOW_VALID', + 22: 'SPI_PERF_HS_BUSY', + 23: 'SPI_PERF_HS_CRAWLER_STALL', + 24: 'SPI_PERF_HS_FIRST_WAVE', + 26: 'SPI_PERF_HS_EVENT_WAVE', + 27: 'SPI_PERF_HS_WAVE', + 28: 'SPI_PERF_HS_PERS_UPD_FULL0', + 29: 'SPI_PERF_HS_PERS_UPD_FULL1', + 30: 'SPI_PERF_HS_PWS_STALL', + 31: 'SPI_PERF_HS_WAVE_IN_FLIGHT', + 37: 'SPI_PERF_CSGN_WINDOW_VALID', + 38: 'SPI_PERF_CSGN_BUSY', + 39: 'SPI_PERF_CSGN_NUM_THREADGROUPS', + 40: 'SPI_PERF_CSGN_CRAWLER_STALL', + 41: 'SPI_PERF_CSGN_EVENT_WAVE', + 42: 'SPI_PERF_CSGN_WAVE', + 43: 'SPI_PERF_CSGN_PWS_STALL', + 44: 'SPI_PERF_CSGN_WAVE_IN_FLIGHT', + 45: 'SPI_PERF_CSN_WINDOW_VALID', + 46: 'SPI_PERF_CSN_BUSY', + 47: 'SPI_PERF_CSN_NUM_THREADGROUPS', + 48: 'SPI_PERF_CSN_CRAWLER_STALL', + 49: 'SPI_PERF_CSN_EVENT_WAVE', + 50: 'SPI_PERF_CSN_WAVE', + 51: 'SPI_PERF_CSN_WAVE_IN_FLIGHT', + 53: 'SPI_PERF_PS0_WINDOW_VALID', + 54: 'SPI_PERF_PS1_WINDOW_VALID', + 55: 'SPI_PERF_PS2_WINDOW_VALID', + 56: 'SPI_PERF_PS3_WINDOW_VALID', + 57: 'SPI_PERF_PS0_BUSY', + 58: 'SPI_PERF_PS1_BUSY', + 59: 'SPI_PERF_PS2_BUSY', + 60: 'SPI_PERF_PS3_BUSY', + 61: 'SPI_PERF_PS0_ACTIVE', + 62: 'SPI_PERF_PS1_ACTIVE', + 63: 'SPI_PERF_PS2_ACTIVE', + 64: 'SPI_PERF_PS3_ACTIVE', + 65: 'SPI_PERF_PS0_DEALLOC', + 66: 'SPI_PERF_PS1_DEALLOC', + 67: 'SPI_PERF_PS2_DEALLOC', + 68: 'SPI_PERF_PS3_DEALLOC', + 69: 'SPI_PERF_PS0_EVENT_WAVE', + 70: 'SPI_PERF_PS1_EVENT_WAVE', + 71: 'SPI_PERF_PS2_EVENT_WAVE', + 72: 'SPI_PERF_PS3_EVENT_WAVE', + 73: 'SPI_PERF_PS0_WAVE', + 74: 'SPI_PERF_PS1_WAVE', + 75: 'SPI_PERF_PS2_WAVE', + 76: 'SPI_PERF_PS3_WAVE', + 77: 'SPI_PERF_PS0_OPT_WAVE', + 78: 'SPI_PERF_PS1_OPT_WAVE', + 79: 'SPI_PERF_PS2_OPT_WAVE', + 80: 'SPI_PERF_PS3_OPT_WAVE', + 81: 'SPI_PERF_PS0_PRIM_BIN0', + 82: 'SPI_PERF_PS1_PRIM_BIN0', + 83: 'SPI_PERF_PS2_PRIM_BIN0', + 84: 'SPI_PERF_PS3_PRIM_BIN0', + 85: 'SPI_PERF_PS0_PRIM_BIN1', + 86: 'SPI_PERF_PS1_PRIM_BIN1', + 87: 'SPI_PERF_PS2_PRIM_BIN1', + 88: 'SPI_PERF_PS3_PRIM_BIN1', + 89: 'SPI_PERF_PS0_CRAWLER_STALL', + 90: 'SPI_PERF_PS1_CRAWLER_STALL', + 91: 'SPI_PERF_PS2_CRAWLER_STALL', + 92: 'SPI_PERF_PS3_CRAWLER_STALL', + 93: 'SPI_PERF_PS_PERS_UPD_FULL0', + 94: 'SPI_PERF_PS_PERS_UPD_FULL1', + 95: 'SPI_PERF_PS0_2_WAVE_GROUPS', + 96: 'SPI_PERF_PS1_2_WAVE_GROUPS', + 97: 'SPI_PERF_PS2_2_WAVE_GROUPS', + 98: 'SPI_PERF_PS3_2_WAVE_GROUPS', + 99: 'SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY', + 100: 'SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY', + 101: 'SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY', + 102: 'SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY', + 103: 'SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS', + 104: 'SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS', + 105: 'SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS', + 106: 'SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS', + 107: 'SPI_PERF_PS_PWS_STALL', + 108: 'SPI_PERF_PS0_LDS_DONE_FULL', + 109: 'SPI_PERF_PS1_LDS_DONE_FULL', + 110: 'SPI_PERF_PS2_LDS_DONE_FULL', + 111: 'SPI_PERF_PS3_LDS_DONE_FULL', + 112: 'SPI_PERF_PS0_DEALLOC_FULL', + 113: 'SPI_PERF_PS1_DEALLOC_FULL', + 114: 'SPI_PERF_PS2_DEALLOC_FULL', + 115: 'SPI_PERF_PS3_DEALLOC_FULL', + 116: 'SPI_PERF_PS0_WAVE_IN_FLIGHT', + 117: 'SPI_PERF_PS1_WAVE_IN_FLIGHT', + 118: 'SPI_PERF_PS2_WAVE_IN_FLIGHT', + 119: 'SPI_PERF_PS3_WAVE_IN_FLIGHT', + 133: 'SPI_PERF_RA_GS_LDS_OCCUPANCY', + 134: 'SPI_PERF_RA_GS_VGPR_OCCUPANCY', + 135: 'SPI_PERF_RA_PS_LDS_OCCUPANCY', + 136: 'SPI_PERF_RA_PS_VGPR_OCCUPANCY', + 137: 'SPI_PERF_RA_SPI_THROTTLE', + 138: 'SPI_PERF_RA_PH_THROTTLE', + 139: 'SPI_PERF_RA_PC_PROBE_STALL_PS', + 140: 'SPI_PERF_RA_PC_PSWAVE_STALL_PS', + 141: 'SPI_PERF_RA_PIPE_REQ_BIN2', + 142: 'SPI_PERF_RA_TASK_REQ_BIN3', + 143: 'SPI_PERF_RA_WR_CTL_FULL', + 144: 'SPI_PERF_RA_REQ_NO_ALLOC', + 145: 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 146: 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 147: 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 148: 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 149: 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', + 150: 'SPI_PERF_RA_RES_STALL_PS', + 151: 'SPI_PERF_RA_RES_STALL_GS', + 152: 'SPI_PERF_RA_RES_STALL_HS', + 153: 'SPI_PERF_RA_RES_STALL_CSG', + 154: 'SPI_PERF_RA_RES_STALL_CSN', + 155: 'SPI_PERF_RA_TMP_STALL_PS', + 156: 'SPI_PERF_RA_TMP_STALL_GS', + 157: 'SPI_PERF_RA_TMP_STALL_HS', + 158: 'SPI_PERF_RA_TMP_STALL_CSG', + 159: 'SPI_PERF_RA_TMP_STALL_CSN', + 160: 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 161: 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 162: 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', + 163: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 164: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', + 165: 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 166: 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 167: 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', + 168: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 169: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', + 170: 'SPI_PERF_RA_LDS_CU_FULL_PS', + 171: 'SPI_PERF_RA_LDS_CU_FULL_HS', + 172: 'SPI_PERF_RA_LDS_CU_FULL_GS', + 173: 'SPI_PERF_RA_LDS_CU_FULL_CSG', + 174: 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 175: 'SPI_PERF_RA_BAR_CU_FULL_PS', + 176: 'SPI_PERF_RA_BAR_CU_FULL_GS', + 177: 'SPI_PERF_RA_BAR_CU_FULL_HS', + 178: 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 179: 'SPI_PERF_RA_BAR_CU_FULL_CSN', + 180: 'SPI_PERF_RA_BULKY_CU_FULL_CSG', + 181: 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 182: 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', + 183: 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 184: 'SPI_PERF_RA_WVLIM_STALL_PS', + 185: 'SPI_PERF_RA_WVLIM_STALL_GS', + 186: 'SPI_PERF_RA_WVLIM_STALL_HS', + 187: 'SPI_PERF_RA_WVLIM_STALL_CSG', + 188: 'SPI_PERF_RA_WVLIM_STALL_CSN', + 189: 'SPI_PERF_RA_GS_LOCK', + 190: 'SPI_PERF_RA_HS_LOCK', + 191: 'SPI_PERF_RA_CSG_LOCK', + 192: 'SPI_PERF_RA_CSN_LOCK', + 193: 'SPI_PERF_RA_RSV_UPD', + 194: 'SPI_PERF_RA_PRE_ALLOC_STALL', + 195: 'SPI_PERF_RA_GFX_UNDER_TUNNEL', + 196: 'SPI_PERF_RA_CSC_UNDER_TUNNEL', + 197: 'SPI_PERF_RA_WVALLOC_STALL', + 198: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_PS', + 199: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_PS', + 200: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_PS', + 201: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_PS', + 202: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_GS', + 203: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_GS', + 204: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_GS', + 205: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_GS', + 206: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_HS', + 207: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_HS', + 208: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_HS', + 209: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_HS', + 210: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG', + 211: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG', + 212: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG', + 213: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG', + 214: 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN', + 215: 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN', + 216: 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN', + 217: 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN', + 218: 'SPI_PERF_EXP_ARB_COL_CNT', + 219: 'SPI_PERF_EXP_ARB_POS_CNT', + 220: 'SPI_PERF_EXP_ARB_GDS_CNT', + 221: 'SPI_PERF_EXP_ARB_IDX_CNT', + 222: 'SPI_PERF_EXP_WITH_CONFLICT', + 223: 'SPI_PERF_EXP_WITH_CONFLICT_CLEAR', + 224: 'SPI_PERF_GS_EXP_DONE', + 225: 'SPI_PERF_PS_EXP_DONE', + 226: 'SPI_PERF_PS_EXP_ARB_CONFLICT', + 227: 'SPI_PERF_GS_SCBD_IDX_CLEANUP', + 228: 'SPI_PERF_GS_SCBD_POS_CLEANUP', + 229: 'SPI_PERF_PS_EXP_ALLOC', + 230: 'SPI_PERF_PS0_WAVEID_STARVED', + 231: 'SPI_PERF_PS1_WAVEID_STARVED', + 232: 'SPI_PERF_PS2_WAVEID_STARVED', + 233: 'SPI_PERF_PS3_WAVEID_STARVED', + 234: 'SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT', + 235: 'SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT', + 236: 'SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT', + 237: 'SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT', + 238: 'SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS', + 239: 'SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS', + 240: 'SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS', + 241: 'SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS', + 242: 'SPI_PERF_NUM_POS_SA0SQ0_EXPORTS', + 243: 'SPI_PERF_NUM_POS_SA0SQ1_EXPORTS', + 244: 'SPI_PERF_NUM_POS_SA1SQ0_EXPORTS', + 245: 'SPI_PERF_NUM_POS_SA1SQ1_EXPORTS', + 246: 'SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS', + 247: 'SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS', + 248: 'SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS', + 249: 'SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS', + 250: 'SPI_PERF_NUM_EXPGRANT_EXPORTS', + 251: 'SPI_PERF_GS_ALLOC_IDX', + 252: 'SPI_PERF_GS_ALLOC_POS', + 253: 'SPI_PERF_PIX_ALLOC_PEND_CNT', + 254: 'SPI_PERF_EXPORT_SCB0_STALL', + 255: 'SPI_PERF_EXPORT_SCB1_STALL', + 256: 'SPI_PERF_EXPORT_SCB2_STALL', + 257: 'SPI_PERF_EXPORT_SCB3_STALL', + 258: 'SPI_PERF_EXPORT_DB0_STALL', + 259: 'SPI_PERF_EXPORT_DB1_STALL', + 260: 'SPI_PERF_EXPORT_DB2_STALL', + 261: 'SPI_PERF_EXPORT_DB3_STALL', + 262: 'SPI_PERF_EXPORT_DB4_STALL', + 263: 'SPI_PERF_EXPORT_DB5_STALL', + 264: 'SPI_PERF_EXPORT_DB6_STALL', + 265: 'SPI_PERF_EXPORT_DB7_STALL', + 266: 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 267: 'SPI_PERF_GS_NGG_STALL_MSG_VAL', + 268: 'SPI_PERF_SWC_PS_WR', + 269: 'SPI_PERF_SWC_GS_WR', + 270: 'SPI_PERF_SWC_HS_WR', + 271: 'SPI_PERF_SWC_CSGN_WR', + 272: 'SPI_PERF_SWC_CSN_WR', + 273: 'SPI_PERF_VWC_PS_WR', + 274: 'SPI_PERF_VWC_ES_WR', + 275: 'SPI_PERF_VWC_GS_WR', + 276: 'SPI_PERF_VWC_LS_WR', + 277: 'SPI_PERF_VWC_HS_WR', + 278: 'SPI_PERF_VWC_CSGN_WR', + 279: 'SPI_PERF_VWC_CSN_WR', + 280: 'SPI_PERF_EXP_THROT_UPSTEP', + 281: 'SPI_PERF_EXP_THROT_DOWNSTEP', + 282: 'SPI_PERF_EXP_THROT_CAUSALITY_DETECTED', + 283: 'SPI_PERF_BUSY', + 284: 'SPI_PERF_ALL_PS_WAVE', + 285: 'SPI_PERF_ALL_PS_WAVE_IN_FLIGHT', + 286: 'SPI_PERF_ALL_WAVE', + 287: 'SPI_PERF_ALL_WAVE_IN_FLIGHT', + 288: 'SPI_PERF_RA_REQ_ALLOC', + 289: 'SPI_PERF_VGPR_INIT', + 290: 'SPI_PERF_SGPR_INIT', + 291: 'SPI_PERF_VGPR_ALLOC_LEVEL', + 292: 'SPI_PERF_LDS_ALLOC_LEVEL', + 293: 'SPI_PERF_GFX_TEMP_ALLOC_LEVEL', + 294: 'SPI_PERF_CSG_TEMP_ALLOC_LEVEL', + 295: 'SPI_PERF_CSN_TEMP_ALLOC_LEVEL', + 296: 'SPI_PERF_ALL_WAVE_RESTORED', + 297: 'SPI_PERF_ALL_WAVE_SAVED', + 298: 'SPI_PERF_ALL_WAVE_W32', + 299: 'SPI_PERF_ALL_WAVE_W64', + 300: 'SPI_PERF_ALL_WAVE_ITEMS', + 301: 'SPI_PERF_ALL_WAVE_ITEMS_W32', + 302: 'SPI_PERF_ALL_WAVE_ITEMS_W64', + 303: 'SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_STALL', + 304: 'SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_LEVEL', + 305: 'SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_STALL', + 306: 'SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_CU_LEVEL', +} +SPI_PERF_GS_WINDOW_VALID = 1 +SPI_PERF_GS_BUSY = 2 +SPI_PERF_GS_CRAWLER_STALL = 3 +SPI_PERF_GS_EVENT_WAVE = 4 +SPI_PERF_GS_WAVE = 5 +SPI_PERF_GS_PERS_UPD_FULL0 = 6 +SPI_PERF_GS_PERS_UPD_FULL1 = 7 +SPI_PERF_GS_FIRST_SUBGRP = 8 +SPI_PERF_GS_HS_DEALLOC = 9 +SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT = 10 +SPI_PERF_GS_POS0_STALL = 11 +SPI_PERF_GS_POS1_STALL = 12 +SPI_PERF_GS_INDX0_STALL = 13 +SPI_PERF_GS_INDX1_STALL = 14 +SPI_PERF_GS_PWS_STALL = 15 +SPI_PERF_GS_GRP_LIFETIME = 16 +SPI_PERF_GS_WAVE_IN_FLIGHT = 17 +SPI_PERF_GS_GRP_LIFETIME_SAMPLE = 18 +SPI_PERF_HS_WINDOW_VALID = 21 +SPI_PERF_HS_BUSY = 22 +SPI_PERF_HS_CRAWLER_STALL = 23 +SPI_PERF_HS_FIRST_WAVE = 24 +SPI_PERF_HS_EVENT_WAVE = 26 +SPI_PERF_HS_WAVE = 27 +SPI_PERF_HS_PERS_UPD_FULL0 = 28 +SPI_PERF_HS_PERS_UPD_FULL1 = 29 +SPI_PERF_HS_PWS_STALL = 30 +SPI_PERF_HS_WAVE_IN_FLIGHT = 31 +SPI_PERF_CSGN_WINDOW_VALID = 37 +SPI_PERF_CSGN_BUSY = 38 +SPI_PERF_CSGN_NUM_THREADGROUPS = 39 +SPI_PERF_CSGN_CRAWLER_STALL = 40 +SPI_PERF_CSGN_EVENT_WAVE = 41 +SPI_PERF_CSGN_WAVE = 42 +SPI_PERF_CSGN_PWS_STALL = 43 +SPI_PERF_CSGN_WAVE_IN_FLIGHT = 44 +SPI_PERF_CSN_WINDOW_VALID = 45 +SPI_PERF_CSN_BUSY = 46 +SPI_PERF_CSN_NUM_THREADGROUPS = 47 +SPI_PERF_CSN_CRAWLER_STALL = 48 +SPI_PERF_CSN_EVENT_WAVE = 49 +SPI_PERF_CSN_WAVE = 50 +SPI_PERF_CSN_WAVE_IN_FLIGHT = 51 +SPI_PERF_PS0_WINDOW_VALID = 53 +SPI_PERF_PS1_WINDOW_VALID = 54 +SPI_PERF_PS2_WINDOW_VALID = 55 +SPI_PERF_PS3_WINDOW_VALID = 56 +SPI_PERF_PS0_BUSY = 57 +SPI_PERF_PS1_BUSY = 58 +SPI_PERF_PS2_BUSY = 59 +SPI_PERF_PS3_BUSY = 60 +SPI_PERF_PS0_ACTIVE = 61 +SPI_PERF_PS1_ACTIVE = 62 +SPI_PERF_PS2_ACTIVE = 63 +SPI_PERF_PS3_ACTIVE = 64 +SPI_PERF_PS0_DEALLOC = 65 +SPI_PERF_PS1_DEALLOC = 66 +SPI_PERF_PS2_DEALLOC = 67 +SPI_PERF_PS3_DEALLOC = 68 +SPI_PERF_PS0_EVENT_WAVE = 69 +SPI_PERF_PS1_EVENT_WAVE = 70 +SPI_PERF_PS2_EVENT_WAVE = 71 +SPI_PERF_PS3_EVENT_WAVE = 72 +SPI_PERF_PS0_WAVE = 73 +SPI_PERF_PS1_WAVE = 74 +SPI_PERF_PS2_WAVE = 75 +SPI_PERF_PS3_WAVE = 76 +SPI_PERF_PS0_OPT_WAVE = 77 +SPI_PERF_PS1_OPT_WAVE = 78 +SPI_PERF_PS2_OPT_WAVE = 79 +SPI_PERF_PS3_OPT_WAVE = 80 +SPI_PERF_PS0_PRIM_BIN0 = 81 +SPI_PERF_PS1_PRIM_BIN0 = 82 +SPI_PERF_PS2_PRIM_BIN0 = 83 +SPI_PERF_PS3_PRIM_BIN0 = 84 +SPI_PERF_PS0_PRIM_BIN1 = 85 +SPI_PERF_PS1_PRIM_BIN1 = 86 +SPI_PERF_PS2_PRIM_BIN1 = 87 +SPI_PERF_PS3_PRIM_BIN1 = 88 +SPI_PERF_PS0_CRAWLER_STALL = 89 +SPI_PERF_PS1_CRAWLER_STALL = 90 +SPI_PERF_PS2_CRAWLER_STALL = 91 +SPI_PERF_PS3_CRAWLER_STALL = 92 +SPI_PERF_PS_PERS_UPD_FULL0 = 93 +SPI_PERF_PS_PERS_UPD_FULL1 = 94 +SPI_PERF_PS0_2_WAVE_GROUPS = 95 +SPI_PERF_PS1_2_WAVE_GROUPS = 96 +SPI_PERF_PS2_2_WAVE_GROUPS = 97 +SPI_PERF_PS3_2_WAVE_GROUPS = 98 +SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY = 99 +SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY = 100 +SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY = 101 +SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY = 102 +SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS = 103 +SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS = 104 +SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS = 105 +SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS = 106 +SPI_PERF_PS_PWS_STALL = 107 +SPI_PERF_PS0_LDS_DONE_FULL = 108 +SPI_PERF_PS1_LDS_DONE_FULL = 109 +SPI_PERF_PS2_LDS_DONE_FULL = 110 +SPI_PERF_PS3_LDS_DONE_FULL = 111 +SPI_PERF_PS0_DEALLOC_FULL = 112 +SPI_PERF_PS1_DEALLOC_FULL = 113 +SPI_PERF_PS2_DEALLOC_FULL = 114 +SPI_PERF_PS3_DEALLOC_FULL = 115 +SPI_PERF_PS0_WAVE_IN_FLIGHT = 116 +SPI_PERF_PS1_WAVE_IN_FLIGHT = 117 +SPI_PERF_PS2_WAVE_IN_FLIGHT = 118 +SPI_PERF_PS3_WAVE_IN_FLIGHT = 119 +SPI_PERF_RA_GS_LDS_OCCUPANCY = 133 +SPI_PERF_RA_GS_VGPR_OCCUPANCY = 134 +SPI_PERF_RA_PS_LDS_OCCUPANCY = 135 +SPI_PERF_RA_PS_VGPR_OCCUPANCY = 136 +SPI_PERF_RA_SPI_THROTTLE = 137 +SPI_PERF_RA_PH_THROTTLE = 138 +SPI_PERF_RA_PC_PROBE_STALL_PS = 139 +SPI_PERF_RA_PC_PSWAVE_STALL_PS = 140 +SPI_PERF_RA_PIPE_REQ_BIN2 = 141 +SPI_PERF_RA_TASK_REQ_BIN3 = 142 +SPI_PERF_RA_WR_CTL_FULL = 143 +SPI_PERF_RA_REQ_NO_ALLOC = 144 +SPI_PERF_RA_REQ_NO_ALLOC_PS = 145 +SPI_PERF_RA_REQ_NO_ALLOC_GS = 146 +SPI_PERF_RA_REQ_NO_ALLOC_HS = 147 +SPI_PERF_RA_REQ_NO_ALLOC_CSG = 148 +SPI_PERF_RA_REQ_NO_ALLOC_CSN = 149 +SPI_PERF_RA_RES_STALL_PS = 150 +SPI_PERF_RA_RES_STALL_GS = 151 +SPI_PERF_RA_RES_STALL_HS = 152 +SPI_PERF_RA_RES_STALL_CSG = 153 +SPI_PERF_RA_RES_STALL_CSN = 154 +SPI_PERF_RA_TMP_STALL_PS = 155 +SPI_PERF_RA_TMP_STALL_GS = 156 +SPI_PERF_RA_TMP_STALL_HS = 157 +SPI_PERF_RA_TMP_STALL_CSG = 158 +SPI_PERF_RA_TMP_STALL_CSN = 159 +SPI_PERF_RA_WAVE_SIMD_FULL_PS = 160 +SPI_PERF_RA_WAVE_SIMD_FULL_GS = 161 +SPI_PERF_RA_WAVE_SIMD_FULL_HS = 162 +SPI_PERF_RA_WAVE_SIMD_FULL_CSG = 163 +SPI_PERF_RA_WAVE_SIMD_FULL_CSN = 164 +SPI_PERF_RA_VGPR_SIMD_FULL_PS = 165 +SPI_PERF_RA_VGPR_SIMD_FULL_GS = 166 +SPI_PERF_RA_VGPR_SIMD_FULL_HS = 167 +SPI_PERF_RA_VGPR_SIMD_FULL_CSG = 168 +SPI_PERF_RA_VGPR_SIMD_FULL_CSN = 169 +SPI_PERF_RA_LDS_CU_FULL_PS = 170 +SPI_PERF_RA_LDS_CU_FULL_HS = 171 +SPI_PERF_RA_LDS_CU_FULL_GS = 172 +SPI_PERF_RA_LDS_CU_FULL_CSG = 173 +SPI_PERF_RA_LDS_CU_FULL_CSN = 174 +SPI_PERF_RA_BAR_CU_FULL_PS = 175 +SPI_PERF_RA_BAR_CU_FULL_GS = 176 +SPI_PERF_RA_BAR_CU_FULL_HS = 177 +SPI_PERF_RA_BAR_CU_FULL_CSG = 178 +SPI_PERF_RA_BAR_CU_FULL_CSN = 179 +SPI_PERF_RA_BULKY_CU_FULL_CSG = 180 +SPI_PERF_RA_BULKY_CU_FULL_CSN = 181 +SPI_PERF_RA_TGLIM_CU_FULL_CSG = 182 +SPI_PERF_RA_TGLIM_CU_FULL_CSN = 183 +SPI_PERF_RA_WVLIM_STALL_PS = 184 +SPI_PERF_RA_WVLIM_STALL_GS = 185 +SPI_PERF_RA_WVLIM_STALL_HS = 186 +SPI_PERF_RA_WVLIM_STALL_CSG = 187 +SPI_PERF_RA_WVLIM_STALL_CSN = 188 +SPI_PERF_RA_GS_LOCK = 189 +SPI_PERF_RA_HS_LOCK = 190 +SPI_PERF_RA_CSG_LOCK = 191 +SPI_PERF_RA_CSN_LOCK = 192 +SPI_PERF_RA_RSV_UPD = 193 +SPI_PERF_RA_PRE_ALLOC_STALL = 194 +SPI_PERF_RA_GFX_UNDER_TUNNEL = 195 +SPI_PERF_RA_CSC_UNDER_TUNNEL = 196 +SPI_PERF_RA_WVALLOC_STALL = 197 +SPI_PERF_RA_ACCUM0_SIMD_FULL_PS = 198 +SPI_PERF_RA_ACCUM1_SIMD_FULL_PS = 199 +SPI_PERF_RA_ACCUM2_SIMD_FULL_PS = 200 +SPI_PERF_RA_ACCUM3_SIMD_FULL_PS = 201 +SPI_PERF_RA_ACCUM0_SIMD_FULL_GS = 202 +SPI_PERF_RA_ACCUM1_SIMD_FULL_GS = 203 +SPI_PERF_RA_ACCUM2_SIMD_FULL_GS = 204 +SPI_PERF_RA_ACCUM3_SIMD_FULL_GS = 205 +SPI_PERF_RA_ACCUM0_SIMD_FULL_HS = 206 +SPI_PERF_RA_ACCUM1_SIMD_FULL_HS = 207 +SPI_PERF_RA_ACCUM2_SIMD_FULL_HS = 208 +SPI_PERF_RA_ACCUM3_SIMD_FULL_HS = 209 +SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG = 210 +SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG = 211 +SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG = 212 +SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG = 213 +SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN = 214 +SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN = 215 +SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN = 216 +SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN = 217 +SPI_PERF_EXP_ARB_COL_CNT = 218 +SPI_PERF_EXP_ARB_POS_CNT = 219 +SPI_PERF_EXP_ARB_GDS_CNT = 220 +SPI_PERF_EXP_ARB_IDX_CNT = 221 +SPI_PERF_EXP_WITH_CONFLICT = 222 +SPI_PERF_EXP_WITH_CONFLICT_CLEAR = 223 +SPI_PERF_GS_EXP_DONE = 224 +SPI_PERF_PS_EXP_DONE = 225 +SPI_PERF_PS_EXP_ARB_CONFLICT = 226 +SPI_PERF_GS_SCBD_IDX_CLEANUP = 227 +SPI_PERF_GS_SCBD_POS_CLEANUP = 228 +SPI_PERF_PS_EXP_ALLOC = 229 +SPI_PERF_PS0_WAVEID_STARVED = 230 +SPI_PERF_PS1_WAVEID_STARVED = 231 +SPI_PERF_PS2_WAVEID_STARVED = 232 +SPI_PERF_PS3_WAVEID_STARVED = 233 +SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT = 234 +SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT = 235 +SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT = 236 +SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT = 237 +SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS = 238 +SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS = 239 +SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS = 240 +SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS = 241 +SPI_PERF_NUM_POS_SA0SQ0_EXPORTS = 242 +SPI_PERF_NUM_POS_SA0SQ1_EXPORTS = 243 +SPI_PERF_NUM_POS_SA1SQ0_EXPORTS = 244 +SPI_PERF_NUM_POS_SA1SQ1_EXPORTS = 245 +SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS = 246 +SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS = 247 +SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS = 248 +SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS = 249 +SPI_PERF_NUM_EXPGRANT_EXPORTS = 250 +SPI_PERF_GS_ALLOC_IDX = 251 +SPI_PERF_GS_ALLOC_POS = 252 +SPI_PERF_PIX_ALLOC_PEND_CNT = 253 +SPI_PERF_EXPORT_SCB0_STALL = 254 +SPI_PERF_EXPORT_SCB1_STALL = 255 +SPI_PERF_EXPORT_SCB2_STALL = 256 +SPI_PERF_EXPORT_SCB3_STALL = 257 +SPI_PERF_EXPORT_DB0_STALL = 258 +SPI_PERF_EXPORT_DB1_STALL = 259 +SPI_PERF_EXPORT_DB2_STALL = 260 +SPI_PERF_EXPORT_DB3_STALL = 261 +SPI_PERF_EXPORT_DB4_STALL = 262 +SPI_PERF_EXPORT_DB5_STALL = 263 +SPI_PERF_EXPORT_DB6_STALL = 264 +SPI_PERF_EXPORT_DB7_STALL = 265 +SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC = 266 +SPI_PERF_GS_NGG_STALL_MSG_VAL = 267 +SPI_PERF_SWC_PS_WR = 268 +SPI_PERF_SWC_GS_WR = 269 +SPI_PERF_SWC_HS_WR = 270 +SPI_PERF_SWC_CSGN_WR = 271 +SPI_PERF_SWC_CSN_WR = 272 +SPI_PERF_VWC_PS_WR = 273 +SPI_PERF_VWC_ES_WR = 274 +SPI_PERF_VWC_GS_WR = 275 +SPI_PERF_VWC_LS_WR = 276 +SPI_PERF_VWC_HS_WR = 277 +SPI_PERF_VWC_CSGN_WR = 278 +SPI_PERF_VWC_CSN_WR = 279 +SPI_PERF_EXP_THROT_UPSTEP = 280 +SPI_PERF_EXP_THROT_DOWNSTEP = 281 +SPI_PERF_EXP_THROT_CAUSALITY_DETECTED = 282 +SPI_PERF_BUSY = 283 +SPI_PERF_ALL_PS_WAVE = 284 +SPI_PERF_ALL_PS_WAVE_IN_FLIGHT = 285 +SPI_PERF_ALL_WAVE = 286 +SPI_PERF_ALL_WAVE_IN_FLIGHT = 287 +SPI_PERF_RA_REQ_ALLOC = 288 +SPI_PERF_VGPR_INIT = 289 +SPI_PERF_SGPR_INIT = 290 +SPI_PERF_VGPR_ALLOC_LEVEL = 291 +SPI_PERF_LDS_ALLOC_LEVEL = 292 +SPI_PERF_GFX_TEMP_ALLOC_LEVEL = 293 +SPI_PERF_CSG_TEMP_ALLOC_LEVEL = 294 +SPI_PERF_CSN_TEMP_ALLOC_LEVEL = 295 +SPI_PERF_ALL_WAVE_RESTORED = 296 +SPI_PERF_ALL_WAVE_SAVED = 297 +SPI_PERF_ALL_WAVE_W32 = 298 +SPI_PERF_ALL_WAVE_W64 = 299 +SPI_PERF_ALL_WAVE_ITEMS = 300 +SPI_PERF_ALL_WAVE_ITEMS_W32 = 301 +SPI_PERF_ALL_WAVE_ITEMS_W64 = 302 +SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_STALL = 303 +SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_LEVEL = 304 +SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_STALL = 305 +SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_CU_LEVEL = 306 +SPI_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PNT_SPRITE_OVERRIDE' +SPI_PNT_SPRITE_OVERRIDE__enumvalues = { + 0: 'SPI_PNT_SPRITE_SEL_0', + 1: 'SPI_PNT_SPRITE_SEL_1', + 2: 'SPI_PNT_SPRITE_SEL_S', + 3: 'SPI_PNT_SPRITE_SEL_T', + 4: 'SPI_PNT_SPRITE_SEL_NONE', +} +SPI_PNT_SPRITE_SEL_0 = 0 +SPI_PNT_SPRITE_SEL_1 = 1 +SPI_PNT_SPRITE_SEL_S = 2 +SPI_PNT_SPRITE_SEL_T = 3 +SPI_PNT_SPRITE_SEL_NONE = 4 +SPI_PNT_SPRITE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PS_LDS_GROUP_SIZE' +SPI_PS_LDS_GROUP_SIZE__enumvalues = { + 0: 'SPI_PS_LDS_GROUP_1', + 1: 'SPI_PS_LDS_GROUP_2', + 2: 'SPI_PS_LDS_GROUP_4', +} +SPI_PS_LDS_GROUP_1 = 0 +SPI_PS_LDS_GROUP_2 = 1 +SPI_PS_LDS_GROUP_4 = 2 +SPI_PS_LDS_GROUP_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SAMPLE_CNTL' +SPI_SAMPLE_CNTL__enumvalues = { + 0: 'CENTROIDS_ONLY', + 1: 'CENTERS_ONLY', + 2: 'CENTROIDS_AND_CENTERS', + 3: 'UNDEF', +} +CENTROIDS_ONLY = 0 +CENTERS_ONLY = 1 +CENTROIDS_AND_CENTERS = 2 +UNDEF = 3 +SPI_SAMPLE_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_EX_FORMAT' +SPI_SHADER_EX_FORMAT__enumvalues = { + 0: 'SPI_SHADER_ZERO', + 1: 'SPI_SHADER_32_R', + 2: 'SPI_SHADER_32_GR', + 3: 'SPI_SHADER_32_AR', + 4: 'SPI_SHADER_FP16_ABGR', + 5: 'SPI_SHADER_UNORM16_ABGR', + 6: 'SPI_SHADER_SNORM16_ABGR', + 7: 'SPI_SHADER_UINT16_ABGR', + 8: 'SPI_SHADER_SINT16_ABGR', + 9: 'SPI_SHADER_32_ABGR', +} +SPI_SHADER_ZERO = 0 +SPI_SHADER_32_R = 1 +SPI_SHADER_32_GR = 2 +SPI_SHADER_32_AR = 3 +SPI_SHADER_FP16_ABGR = 4 +SPI_SHADER_UNORM16_ABGR = 5 +SPI_SHADER_SNORM16_ABGR = 6 +SPI_SHADER_UINT16_ABGR = 7 +SPI_SHADER_SINT16_ABGR = 8 +SPI_SHADER_32_ABGR = 9 +SPI_SHADER_EX_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_FORMAT' +SPI_SHADER_FORMAT__enumvalues = { + 0: 'SPI_SHADER_NONE', + 1: 'SPI_SHADER_1COMP', + 2: 'SPI_SHADER_2COMP', + 3: 'SPI_SHADER_4COMPRESS', + 4: 'SPI_SHADER_4COMP', +} +SPI_SHADER_NONE = 0 +SPI_SHADER_1COMP = 1 +SPI_SHADER_2COMP = 2 +SPI_SHADER_4COMPRESS = 3 +SPI_SHADER_4COMP = 4 +SPI_SHADER_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ADDRESS_MODE' +SH_MEM_ADDRESS_MODE__enumvalues = { + 0: 'SH_MEM_ADDRESS_MODE_64', + 1: 'SH_MEM_ADDRESS_MODE_32', +} +SH_MEM_ADDRESS_MODE_64 = 0 +SH_MEM_ADDRESS_MODE_32 = 1 +SH_MEM_ADDRESS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ALIGNMENT_MODE' +SH_MEM_ALIGNMENT_MODE__enumvalues = { + 0: 'SH_MEM_ALIGNMENT_MODE_DWORD', + 1: 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 2: 'SH_MEM_ALIGNMENT_MODE_STRICT', + 3: 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', +} +SH_MEM_ALIGNMENT_MODE_DWORD = 0 +SH_MEM_ALIGNMENT_MODE_DWORD_STRICT = 1 +SH_MEM_ALIGNMENT_MODE_STRICT = 2 +SH_MEM_ALIGNMENT_MODE_UNALIGNED = 3 +SH_MEM_ALIGNMENT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQG_PERF_SEL' +SQG_PERF_SEL__enumvalues = { + 0: 'SQG_PERF_SEL_NONE', + 1: 'SQG_PERF_SEL_MSG_BUS_BUSY', + 2: 'SQG_PERF_SEL_EXP_REQ0_BUS_BUSY', + 3: 'SQG_PERF_SEL_EXP_REQ1_BUS_BUSY', + 4: 'SQG_PERF_SEL_EXP_BUS0_BUSY', + 5: 'SQG_PERF_SEL_EXP_BUS1_BUSY', + 6: 'SQG_PERF_SEL_TTRACE_WRITE_DATA', + 7: 'SQG_PERF_SEL_TTRACE_STALL', + 8: 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', + 9: 'SQG_PERF_SEL_WAVES_INITIAL_PREFETCH', + 10: 'SQG_PERF_SEL_EVENTS', + 11: 'SQG_PERF_SEL_WAVES_RESTORED', + 12: 'SQG_PERF_SEL_WAVES_SAVED', + 13: 'SQG_PERF_SEL_ACCUM_PREV', + 14: 'SQG_PERF_SEL_CYCLES', + 15: 'SQG_PERF_SEL_BUSY_CYCLES', + 16: 'SQG_PERF_SEL_WAVE_CYCLES', + 17: 'SQG_PERF_SEL_MSG', + 18: 'SQG_PERF_SEL_MSG_INTERRUPT', + 19: 'SQG_PERF_SEL_WAVES', + 20: 'SQG_PERF_SEL_WAVES_32', + 21: 'SQG_PERF_SEL_WAVES_64', + 22: 'SQG_PERF_SEL_LEVEL_WAVES', + 23: 'SQG_PERF_SEL_ITEMS', + 24: 'SQG_PERF_SEL_WAVE32_ITEMS', + 25: 'SQG_PERF_SEL_WAVE64_ITEMS', + 26: 'SQG_PERF_SEL_PS_QUADS', + 27: 'SQG_PERF_SEL_WAVES_EQ_64', + 28: 'SQG_PERF_SEL_WAVES_EQ_32', + 29: 'SQG_PERF_SEL_WAVES_LT_64', + 30: 'SQG_PERF_SEL_WAVES_LT_48', + 31: 'SQG_PERF_SEL_WAVES_LT_32', + 32: 'SQG_PERF_SEL_WAVES_LT_16', + 33: 'SQG_PERF_SEL_REFCLKS', + 34: 'SQG_PERF_SEL_WAVES_WGP_TAKEOVER', + 35: 'SQG_PERF_SEL_WAVES_DYN_VGPR', + 36: 'SQG_PERF_SEL_ITEMS_PS', + 37: 'SQG_PERF_SEL_ITEMS_GS', + 38: 'SQG_PERF_SEL_ITEMS_HS', + 39: 'SQG_PERF_SEL_ITEMS_CS', + 40: 'SQG_PERF_SEL_WAVES_VEC32', + 41: 'SQG_PERF_SEL_WAVES_PS_VEC32', + 42: 'SQG_PERF_SEL_WAVES_GS_VEC32', + 43: 'SQG_PERF_SEL_WAVES_HS_VEC32', + 44: 'SQG_PERF_SEL_WAVES_CS_VEC32', + 45: 'SQG_PERF_SEL_LEVEL_WGP_ACTIVE', + 46: 'SQG_PERF_SEL_DUMMY_LAST', +} +SQG_PERF_SEL_NONE = 0 +SQG_PERF_SEL_MSG_BUS_BUSY = 1 +SQG_PERF_SEL_EXP_REQ0_BUS_BUSY = 2 +SQG_PERF_SEL_EXP_REQ1_BUS_BUSY = 3 +SQG_PERF_SEL_EXP_BUS0_BUSY = 4 +SQG_PERF_SEL_EXP_BUS1_BUSY = 5 +SQG_PERF_SEL_TTRACE_WRITE_DATA = 6 +SQG_PERF_SEL_TTRACE_STALL = 7 +SQG_PERF_SEL_TTRACE_LOST_PACKETS = 8 +SQG_PERF_SEL_WAVES_INITIAL_PREFETCH = 9 +SQG_PERF_SEL_EVENTS = 10 +SQG_PERF_SEL_WAVES_RESTORED = 11 +SQG_PERF_SEL_WAVES_SAVED = 12 +SQG_PERF_SEL_ACCUM_PREV = 13 +SQG_PERF_SEL_CYCLES = 14 +SQG_PERF_SEL_BUSY_CYCLES = 15 +SQG_PERF_SEL_WAVE_CYCLES = 16 +SQG_PERF_SEL_MSG = 17 +SQG_PERF_SEL_MSG_INTERRUPT = 18 +SQG_PERF_SEL_WAVES = 19 +SQG_PERF_SEL_WAVES_32 = 20 +SQG_PERF_SEL_WAVES_64 = 21 +SQG_PERF_SEL_LEVEL_WAVES = 22 +SQG_PERF_SEL_ITEMS = 23 +SQG_PERF_SEL_WAVE32_ITEMS = 24 +SQG_PERF_SEL_WAVE64_ITEMS = 25 +SQG_PERF_SEL_PS_QUADS = 26 +SQG_PERF_SEL_WAVES_EQ_64 = 27 +SQG_PERF_SEL_WAVES_EQ_32 = 28 +SQG_PERF_SEL_WAVES_LT_64 = 29 +SQG_PERF_SEL_WAVES_LT_48 = 30 +SQG_PERF_SEL_WAVES_LT_32 = 31 +SQG_PERF_SEL_WAVES_LT_16 = 32 +SQG_PERF_SEL_REFCLKS = 33 +SQG_PERF_SEL_WAVES_WGP_TAKEOVER = 34 +SQG_PERF_SEL_WAVES_DYN_VGPR = 35 +SQG_PERF_SEL_ITEMS_PS = 36 +SQG_PERF_SEL_ITEMS_GS = 37 +SQG_PERF_SEL_ITEMS_HS = 38 +SQG_PERF_SEL_ITEMS_CS = 39 +SQG_PERF_SEL_WAVES_VEC32 = 40 +SQG_PERF_SEL_WAVES_PS_VEC32 = 41 +SQG_PERF_SEL_WAVES_GS_VEC32 = 42 +SQG_PERF_SEL_WAVES_HS_VEC32 = 43 +SQG_PERF_SEL_WAVES_CS_VEC32 = 44 +SQG_PERF_SEL_LEVEL_WGP_ACTIVE = 45 +SQG_PERF_SEL_DUMMY_LAST = 46 +SQG_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_CAC_POWER_SEL' +SQ_CAC_POWER_SEL__enumvalues = { + 0: 'SQ_CAC_POWER_VALU', + 1: 'SQ_CAC_POWER_VALU0', + 2: 'SQ_CAC_POWER_VALU1', + 3: 'SQ_CAC_POWER_VALU2', + 4: 'SQ_CAC_POWER_GPR_RD', + 5: 'SQ_CAC_POWER_GPR_WR', + 6: 'SQ_CAC_POWER_LDS_BUSY', + 7: 'SQ_CAC_POWER_ALU_BUSY', + 8: 'SQ_CAC_POWER_TEX_BUSY', +} +SQ_CAC_POWER_VALU = 0 +SQ_CAC_POWER_VALU0 = 1 +SQ_CAC_POWER_VALU1 = 2 +SQ_CAC_POWER_VALU2 = 3 +SQ_CAC_POWER_GPR_RD = 4 +SQ_CAC_POWER_GPR_WR = 5 +SQ_CAC_POWER_LDS_BUSY = 6 +SQ_CAC_POWER_ALU_BUSY = 7 +SQ_CAC_POWER_TEX_BUSY = 8 +SQ_CAC_POWER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_EDC_INFO_SOURCE' +SQ_EDC_INFO_SOURCE__enumvalues = { + 0: 'SQ_EDC_INFO_SOURCE_INVALID', + 1: 'SQ_EDC_INFO_SOURCE_INST', + 2: 'SQ_EDC_INFO_SOURCE_SGPR', + 3: 'SQ_EDC_INFO_SOURCE_VGPR', + 4: 'SQ_EDC_INFO_SOURCE_LDS', + 5: 'SQ_EDC_INFO_SOURCE_GDS', + 6: 'SQ_EDC_INFO_SOURCE_TA', +} +SQ_EDC_INFO_SOURCE_INVALID = 0 +SQ_EDC_INFO_SOURCE_INST = 1 +SQ_EDC_INFO_SOURCE_SGPR = 2 +SQ_EDC_INFO_SOURCE_VGPR = 3 +SQ_EDC_INFO_SOURCE_LDS = 4 +SQ_EDC_INFO_SOURCE_GDS = 5 +SQ_EDC_INFO_SOURCE_TA = 6 +SQ_EDC_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IBUF_ST' +SQ_IBUF_ST__enumvalues = { + 0: 'SQ_IBUF_IB_IDLE', + 1: 'SQ_IBUF_IB_INI_WAIT_GNT', + 2: 'SQ_IBUF_IB_INI_WAIT_DRET', + 3: 'SQ_IBUF_IB_LE_4DW', + 4: 'SQ_IBUF_IB_WAIT_DRET', + 5: 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 6: 'SQ_IBUF_IB_DRET', + 7: 'SQ_IBUF_IB_EMPTY_WAIT_GNT', +} +SQ_IBUF_IB_IDLE = 0 +SQ_IBUF_IB_INI_WAIT_GNT = 1 +SQ_IBUF_IB_INI_WAIT_DRET = 2 +SQ_IBUF_IB_LE_4DW = 3 +SQ_IBUF_IB_WAIT_DRET = 4 +SQ_IBUF_IB_EMPTY_WAIT_DRET = 5 +SQ_IBUF_IB_DRET = 6 +SQ_IBUF_IB_EMPTY_WAIT_GNT = 7 +SQ_IBUF_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IMG_FILTER_TYPE' +SQ_IMG_FILTER_TYPE__enumvalues = { + 0: 'SQ_IMG_FILTER_MODE_BLEND', + 1: 'SQ_IMG_FILTER_MODE_MIN', + 2: 'SQ_IMG_FILTER_MODE_MAX', +} +SQ_IMG_FILTER_MODE_BLEND = 0 +SQ_IMG_FILTER_MODE_MIN = 1 +SQ_IMG_FILTER_MODE_MAX = 2 +SQ_IMG_FILTER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_CMD' +SQ_IND_CMD_CMD__enumvalues = { + 0: 'SQ_IND_CMD_CMD_NULL', + 1: 'SQ_IND_CMD_CMD_SETHALT', + 2: 'SQ_IND_CMD_CMD_SAVECTX', + 3: 'SQ_IND_CMD_CMD_KILL', + 4: 'SQ_IND_CMD_CMD_TRAP_AFTER_INST', + 5: 'SQ_IND_CMD_CMD_TRAP', + 6: 'SQ_IND_CMD_CMD_SET_SYS_PRIO', + 7: 'SQ_IND_CMD_CMD_SETFATALHALT', + 8: 'SQ_IND_CMD_CMD_SINGLE_STEP', +} +SQ_IND_CMD_CMD_NULL = 0 +SQ_IND_CMD_CMD_SETHALT = 1 +SQ_IND_CMD_CMD_SAVECTX = 2 +SQ_IND_CMD_CMD_KILL = 3 +SQ_IND_CMD_CMD_TRAP_AFTER_INST = 4 +SQ_IND_CMD_CMD_TRAP = 5 +SQ_IND_CMD_CMD_SET_SYS_PRIO = 6 +SQ_IND_CMD_CMD_SETFATALHALT = 7 +SQ_IND_CMD_CMD_SINGLE_STEP = 8 +SQ_IND_CMD_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_MODE' +SQ_IND_CMD_MODE__enumvalues = { + 0: 'SQ_IND_CMD_MODE_SINGLE', + 1: 'SQ_IND_CMD_MODE_BROADCAST', + 2: 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', + 3: 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 4: 'SQ_IND_CMD_MODE_BROADCAST_ME', +} +SQ_IND_CMD_MODE_SINGLE = 0 +SQ_IND_CMD_MODE_BROADCAST = 1 +SQ_IND_CMD_MODE_BROADCAST_QUEUE = 2 +SQ_IND_CMD_MODE_BROADCAST_PIPE = 3 +SQ_IND_CMD_MODE_BROADCAST_ME = 4 +SQ_IND_CMD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_STR_ST' +SQ_INST_STR_ST__enumvalues = { + 0: 'SQ_INST_STR_IB_WAVE_NORML', + 1: 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 2: 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 3: 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 4: 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', + 5: 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', +} +SQ_INST_STR_IB_WAVE_NORML = 0 +SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV = 1 +SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV = 2 +SQ_INST_STR_IB_WAVE_INST_SKIP_AV = 3 +SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT = 4 +SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT = 5 +SQ_INST_STR_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_TYPE' +SQ_INST_TYPE__enumvalues = { + 0: 'SQ_INST_TYPE_VALU', + 1: 'SQ_INST_TYPE_SCALAR', + 2: 'SQ_INST_TYPE_TEX', + 3: 'SQ_INST_TYPE_LDS', + 4: 'SQ_INST_TYPE_LDS_DIRECT', + 5: 'SQ_INST_TYPE_EXP', + 6: 'SQ_INST_TYPE_MSG', + 7: 'SQ_INST_TYPE_BARRIER', + 8: 'SQ_INST_TYPE_BRANCH_NOT_TAKEN', + 9: 'SQ_INST_TYPE_BRANCH_TAKEN', + 10: 'SQ_INST_TYPE_JUMP', + 11: 'SQ_INST_TYPE_OTHER', + 12: 'SQ_INST_TYPE_NONE', + 13: 'SQ_INST_TYPE_DUAL_VALU', + 14: 'SQ_INST_TYPE_FLAT', + 15: 'SQ_INST_TYPE_VALU_MATRIX', +} +SQ_INST_TYPE_VALU = 0 +SQ_INST_TYPE_SCALAR = 1 +SQ_INST_TYPE_TEX = 2 +SQ_INST_TYPE_LDS = 3 +SQ_INST_TYPE_LDS_DIRECT = 4 +SQ_INST_TYPE_EXP = 5 +SQ_INST_TYPE_MSG = 6 +SQ_INST_TYPE_BARRIER = 7 +SQ_INST_TYPE_BRANCH_NOT_TAKEN = 8 +SQ_INST_TYPE_BRANCH_TAKEN = 9 +SQ_INST_TYPE_JUMP = 10 +SQ_INST_TYPE_OTHER = 11 +SQ_INST_TYPE_NONE = 12 +SQ_INST_TYPE_DUAL_VALU = 13 +SQ_INST_TYPE_FLAT = 14 +SQ_INST_TYPE_VALU_MATRIX = 15 +SQ_INST_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_LLC_CTL' +SQ_LLC_CTL__enumvalues = { + 0: 'SQ_LLC_0', + 1: 'SQ_LLC_1', + 2: 'SQ_LLC_RSVD_2', + 3: 'SQ_LLC_BYPASS', +} +SQ_LLC_0 = 0 +SQ_LLC_1 = 1 +SQ_LLC_RSVD_2 = 2 +SQ_LLC_BYPASS = 3 +SQ_LLC_CTL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_NO_INST_ISSUE' +SQ_NO_INST_ISSUE__enumvalues = { + 0: 'SQ_NO_INST_ISSUE_NO_INSTS', + 1: 'SQ_NO_INST_ISSUE_ALU_DEP', + 2: 'SQ_NO_INST_ISSUE_S_WAITCNT', + 3: 'SQ_NO_INST_ISSUE_NO_ARB_WIN', + 4: 'SQ_NO_INST_ISSUE_SLEEP_WAIT', + 5: 'SQ_NO_INST_ISSUE_BARRIER_WAIT', + 6: 'SQ_NO_INST_ISSUE_OTHER', + 7: 'SQ_NO_INST_ISSUE_INTERNAL', +} +SQ_NO_INST_ISSUE_NO_INSTS = 0 +SQ_NO_INST_ISSUE_ALU_DEP = 1 +SQ_NO_INST_ISSUE_S_WAITCNT = 2 +SQ_NO_INST_ISSUE_NO_ARB_WIN = 3 +SQ_NO_INST_ISSUE_SLEEP_WAIT = 4 +SQ_NO_INST_ISSUE_BARRIER_WAIT = 5 +SQ_NO_INST_ISSUE_OTHER = 6 +SQ_NO_INST_ISSUE_INTERNAL = 7 +SQ_NO_INST_ISSUE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_OOB_SELECT' +SQ_OOB_SELECT__enumvalues = { + 0: 'SQ_OOB_INDEX_AND_OFFSET', + 1: 'SQ_OOB_INDEX_ONLY', + 2: 'SQ_OOB_NUM_RECORDS_0', + 3: 'SQ_OOB_COMPLETE', +} +SQ_OOB_INDEX_AND_OFFSET = 0 +SQ_OOB_INDEX_ONLY = 1 +SQ_OOB_NUM_RECORDS_0 = 2 +SQ_OOB_COMPLETE = 3 +SQ_OOB_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_PERF_SEL' +SQ_PERF_SEL__enumvalues = { + 0: 'SQ_PERF_SEL_NONE', + 1: 'SQ_PERF_SEL_ACCUM_PREV', + 2: 'SQ_PERF_SEL_CYCLES', + 3: 'SQ_PERF_SEL_BUSY_CYCLES', + 4: 'SQ_PERF_SEL_WAVES', + 5: 'SQ_PERF_SEL_WAVES_32', + 6: 'SQ_PERF_SEL_WAVES_64', + 7: 'SQ_PERF_SEL_LEVEL_WAVES', + 8: 'SQ_PERF_SEL_ITEMS', + 9: 'SQ_PERF_SEL_WAVE32_ITEMS', + 10: 'SQ_PERF_SEL_WAVE64_ITEMS', + 11: 'SQ_PERF_SEL_PS_QUADS', + 12: 'SQ_PERF_SEL_EVENTS', + 13: 'SQ_PERF_SEL_WAVES_EQ_32', + 14: 'SQ_PERF_SEL_WAVES_EQ_64', + 15: 'SQ_PERF_SEL_WAVES_LT_64', + 16: 'SQ_PERF_SEL_WAVES_LT_48', + 17: 'SQ_PERF_SEL_WAVES_LT_32', + 18: 'SQ_PERF_SEL_WAVES_LT_16', + 19: 'SQ_PERF_SEL_WAVES_RESTORED', + 20: 'SQ_PERF_SEL_WAVES_SAVED', + 21: 'SQ_PERF_SEL_MSG', + 22: 'SQ_PERF_SEL_MSG_INTERRUPT', + 23: 'SQ_PERF_SEL_WAVES_INITIAL_PREFETCH', + 24: 'SQ_PERF_SEL_WAVE_CYCLES', + 25: 'SQ_PERF_SEL_WAVE_READY', + 26: 'SQ_PERF_SEL_WAIT_INST_ANY', + 27: 'SQ_PERF_SEL_WAIT_ANY', + 28: 'SQ_PERF_SEL_WAIT_CNT_ANY', + 29: 'SQ_PERF_SEL_WAIT_CNT_LOAD', + 30: 'SQ_PERF_SEL_WAIT_CNT_STORE', + 31: 'SQ_PERF_SEL_WAIT_TTRACE', + 32: 'SQ_PERF_SEL_WAIT_IFETCH', + 33: 'SQ_PERF_SEL_WAIT_BARRIER', + 34: 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 35: 'SQ_PERF_SEL_WAIT_SLEEP', + 36: 'SQ_PERF_SEL_WAIT_DELAY_ALU', + 37: 'SQ_PERF_SEL_WAIT_DEPCTR', + 38: 'SQ_PERF_SEL_WAIT_OTHER', + 39: 'SQ_PERF_SEL_INSTS_ALL', + 40: 'SQ_PERF_SEL_INSTS_BRANCH', + 41: 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 42: 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', + 43: 'SQ_PERF_SEL_INSTS_EXP', + 44: 'SQ_PERF_SEL_INSTS_FLAT', + 45: 'SQ_PERF_SEL_INSTS_LDS', + 46: 'SQ_PERF_SEL_INSTS_SALU', + 47: 'SQ_PERF_SEL_INSTS_SMEM', + 48: 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 49: 'SQ_PERF_SEL_INSTS_SENDMSG', + 50: 'SQ_PERF_SEL_INSTS_VALU', + 51: 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 52: 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 53: 'SQ_PERF_SEL_INSTS_TEX', + 54: 'SQ_PERF_SEL_INSTS_TEX_LOAD', + 55: 'SQ_PERF_SEL_INSTS_TEX_STORE', + 56: 'SQ_PERF_SEL_INSTS_DELAY_ALU', + 57: 'SQ_PERF_SEL_INSTS_INTERNAL', + 58: 'SQ_PERF_SEL_INSTS_VEC32', + 59: 'SQ_PERF_SEL_INSTS_VEC32_FLAT', + 60: 'SQ_PERF_SEL_INSTS_VEC32_LDS', + 61: 'SQ_PERF_SEL_INSTS_VEC32_VALU', + 62: 'SQ_PERF_SEL_VEC32_INSTS_EXP', + 63: 'SQ_PERF_SEL_INSTS_VEC32_VALU_TRANS32', + 64: 'SQ_PERF_SEL_INSTS_VEC32_VALU_NO_COEXEC', + 65: 'SQ_PERF_SEL_INSTS_VEC32_TEX', + 66: 'SQ_PERF_SEL_INSTS_VEC32_TEX_LOAD', + 67: 'SQ_PERF_SEL_INSTS_VEC32_TEX_STORE', + 68: 'SQ_PERF_SEL_ITEM_CYCLES_VALU', + 69: 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 70: 'SQ_PERF_SEL_WAVE32_INSTS', + 71: 'SQ_PERF_SEL_WAVE64_INSTS', + 72: 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 73: 'SQ_PERF_SEL_WAVE64_HALF_SKIP', + 74: 'SQ_PERF_SEL_INST_LEVEL_EXP', + 75: 'SQ_PERF_SEL_INST_LEVEL_LDS', + 76: 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 77: 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 78: 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', + 79: 'SQ_PERF_SEL_IFETCH_REQS', + 80: 'SQ_PERF_SEL_IFETCH_LEVEL', + 81: 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 82: 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 83: 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 84: 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 85: 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 86: 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 87: 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 88: 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 89: 'SQ_PERF_SEL_INST_ISSUE_SMEM_STALL', + 90: 'SQ_PERF_SEL_INST_ISSUE_ALL_STALL', + 91: 'SQ_PERF_SEL_INST_ISSUE_VALU_STALL', + 92: 'SQ_PERF_SEL_INST_ISSUE_SALU_STALL', + 93: 'SQ_PERF_SEL_INST_ISSUE_TEX_STALL', + 94: 'SQ_PERF_SEL_INST_ISSUE_LDS_STALL', + 96: 'SQ_PERF_SEL_INST_ISSUE_EXP_STALL', + 97: 'SQ_PERF_SEL_INST_WAITCNT_STALL', + 98: 'SQ_PERF_SEL_INST_BARRIER_STALL', + 99: 'SQ_PERF_SEL_INST_CYCLES_VALU', + 100: 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 101: 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 102: 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 103: 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 104: 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 105: 'SQ_PERF_SEL_INST_CYCLES_LDS', + 106: 'SQ_PERF_SEL_INST_CYCLES_TEX', + 107: 'SQ_PERF_SEL_INST_CYCLES_FLAT', + 108: 'SQ_PERF_SEL_INST_CYCLES_EXP', + 109: 'SQ_PERF_SEL_VALU_STARVE', + 110: 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', + 111: 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 112: 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 113: 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', + 114: 'SQ_PERF_SEL_VMEM_BUS_STALL', + 115: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 116: 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 117: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 118: 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 119: 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', + 120: 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 121: 'SQ_PERF_SEL_SALU_PIPE_STALL', + 122: 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 123: 'SQ_PERF_SEL_MSG_BUS_BUSY', + 124: 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', + 125: 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', + 126: 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 127: 'SQ_PERF_SEL_EXP_BUS0_BUSY', + 128: 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 129: 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', + 130: 'SQ_PERF_SEL_USER0', + 131: 'SQ_PERF_SEL_USER1', + 132: 'SQ_PERF_SEL_USER2', + 133: 'SQ_PERF_SEL_USER3', + 134: 'SQ_PERF_SEL_USER4', + 135: 'SQ_PERF_SEL_USER5', + 136: 'SQ_PERF_SEL_USER6', + 137: 'SQ_PERF_SEL_USER7', + 138: 'SQ_PERF_SEL_USER8', + 139: 'SQ_PERF_SEL_USER9', + 140: 'SQ_PERF_SEL_USER10', + 141: 'SQ_PERF_SEL_USER11', + 142: 'SQ_PERF_SEL_USER12', + 143: 'SQ_PERF_SEL_USER13', + 144: 'SQ_PERF_SEL_USER14', + 145: 'SQ_PERF_SEL_USER15', + 146: 'SQ_PERF_SEL_USER_LEVEL0', + 147: 'SQ_PERF_SEL_USER_LEVEL1', + 148: 'SQ_PERF_SEL_USER_LEVEL2', + 149: 'SQ_PERF_SEL_USER_LEVEL3', + 150: 'SQ_PERF_SEL_USER_LEVEL4', + 151: 'SQ_PERF_SEL_USER_LEVEL5', + 152: 'SQ_PERF_SEL_USER_LEVEL6', + 153: 'SQ_PERF_SEL_USER_LEVEL7', + 154: 'SQ_PERF_SEL_USER_LEVEL8', + 155: 'SQ_PERF_SEL_USER_LEVEL9', + 156: 'SQ_PERF_SEL_USER_LEVEL10', + 157: 'SQ_PERF_SEL_USER_LEVEL11', + 158: 'SQ_PERF_SEL_USER_LEVEL12', + 159: 'SQ_PERF_SEL_USER_LEVEL13', + 160: 'SQ_PERF_SEL_USER_LEVEL14', + 161: 'SQ_PERF_SEL_USER_LEVEL15', + 162: 'SQ_PERF_SEL_VALU_RETURN_SDST', + 163: 'SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT', + 164: 'SQ_PERF_SEL_INSTS_VALU_TRANS', + 165: 'SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD', + 166: 'SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD', + 167: 'SQ_PERF_SEL_INSTS_VEC32_LDS_PARAM_LOAD', + 168: 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64', + 169: 'SQ_PERF_SEL_INSTS_VALU_VINTERP', + 170: 'SQ_PERF_SEL_INSTS_VEC32_VALU_VINTERP', + 171: 'SQ_PERF_SEL_OVERFLOW_PREV', + 172: 'SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32', + 173: 'SQ_PERF_SEL_INSTS_VALU_1_PASS', + 174: 'SQ_PERF_SEL_INSTS_VALU_2_PASS', + 175: 'SQ_PERF_SEL_INSTS_VALU_4_PASS', + 176: 'SQ_PERF_SEL_INSTS_VALU_DP', + 177: 'SQ_PERF_SEL_SP_CONST_CYCLES', + 178: 'SQ_PERF_SEL_SP_CONST_STALL_CYCLES', + 179: 'SQ_PERF_SEL_ITEMS_VALU', + 180: 'SQ_PERF_SEL_ITEMS_MAX_VALU', + 181: 'SQ_PERF_SEL_ITEM_CYCLES_VMEM', + 182: 'SQ_PERF_SEL_INSTS_DELAY_ALU_COISSUE', + 183: 'SQ_PERF_SEL_INSTS_FLAT_LOAD', + 184: 'SQ_PERF_SEL_INSTS_FLAT_STORE', + 185: 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_16BIT', + 186: 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_32BIT', + 187: 'SQ_PERF_SEL_INSTS_NON_VALU_EXEC_SKIPPED', + 188: 'SQ_PERF_SEL_INSTS_BARRIER_LOCK', + 189: 'SQ_PERF_SEL_INSTS_WAKEUP', + 190: 'SQ_PERF_SEL_IS_CACHE_REQ', + 191: 'SQ_PERF_SEL_INSTS_SALU_PS', + 192: 'SQ_PERF_SEL_INSTS_SALU_GS', + 193: 'SQ_PERF_SEL_INSTS_SALU_HS', + 194: 'SQ_PERF_SEL_INSTS_SALU_CS', + 195: 'SQ_PERF_SEL_INSTS_SMEM_PS', + 196: 'SQ_PERF_SEL_INSTS_SMEM_GS', + 197: 'SQ_PERF_SEL_INSTS_SMEM_HS', + 198: 'SQ_PERF_SEL_INSTS_SMEM_CS', + 199: 'SQ_PERF_SEL_INSTS_VEC32_TEX_PS', + 200: 'SQ_PERF_SEL_INSTS_VEC32_TEX_GS', + 201: 'SQ_PERF_SEL_INSTS_VEC32_TEX_HS', + 202: 'SQ_PERF_SEL_INSTS_VEC32_TEX_CS', + 203: 'SQ_PERF_SEL_INSTS_VEC32_VALU_PS', + 204: 'SQ_PERF_SEL_INSTS_VEC32_VALU_GS', + 205: 'SQ_PERF_SEL_INSTS_VEC32_VALU_HS', + 206: 'SQ_PERF_SEL_INSTS_VEC32_VALU_CS', + 207: 'SQ_PERF_SEL_WAIT_CNT_SAMPLE', + 209: 'SQ_PERF_SEL_WAIT_CNT_KM', + 210: 'SQ_PERF_SEL_WAIT_CNT_DS', + 211: 'SQ_PERF_SEL_WAIT_CNT_EXP', + 212: 'SQ_PERF_SEL_INSTS_SALU_FLOAT', + 213: 'SQ_PERF_SEL_INSTS_VGPR_ALLOC', + 214: 'SQ_PERF_SEL_INSTS_VGPR_ALLOC_FAIL', + 215: 'SQ_PERF_SEL_INSTS_LOCK', + 216: 'SQ_PERF_SEL_INSTS_VALU_COISSUE', + 217: 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_LOAD', + 218: 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_STORE', + 219: 'SQ_PERF_SEL_IS_CACHE_MISS', + 220: 'SQ_PERF_SEL_IS_CACHE_DUP_MISS', + 221: 'SQ_PERF_SEL_INST_CYCLES_VMEM_ATOMIC', + 222: 'SQ_PERF_SEL_INSTS_TEX_BLOCK_LOAD', + 224: 'SQ_PERF_SEL_INSTS_TEX_SAMPLE', + 225: 'SQ_PERF_SEL_INSTS_TEX_ATOMIC_RTN', + 226: 'SQ_PERF_SEL_INSTS_TEX_BLOCK_STORE', + 227: 'SQ_PERF_SEL_INSTS_TEX_ATOMIC_NORTN', + 228: 'SQ_PERF_SEL_INSTS_GLOBAL_SCRATCH', + 229: 'SQ_PERF_SEL_INSTS_WMMA_LOAD', + 230: 'SQ_PERF_SEL_INSTS_FLAT_ATOMIC', + 231: 'SQ_PERF_SEL_INSTS_EXP_MRT', + 232: 'SQ_PERF_SEL_INSTS_EXP_Z', + 233: 'SQ_PERF_SEL_INSTS_VEC32_VALU_WMMA', + 234: 'SQ_PERF_SEL_INSTS_VEC32_LDS_LOAD', + 235: 'SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_RTN', + 236: 'SQ_PERF_SEL_INSTS_VEC32_LDS_STORE', + 237: 'SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_NORTN', + 239: 'SQ_PERF_SEL_INSTS_VEC32_LDS_OTHER', + 241: 'SQ_PERF_SEL_INSTS_VEC32_TEX_SAMPLE', + 242: 'SQ_PERF_SEL_INSTS_VEC32_TEX_ATOMIC', + 243: 'SQ_PERF_SEL_INSTS_VEC32_FLAT_LOAD', + 244: 'SQ_PERF_SEL_INSTS_VEC32_FLAT_STORE', + 245: 'SQ_PERF_SEL_INSTS_VEC32_FLAT_ATOMIC', + 246: 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH', + 247: 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_LOAD', + 248: 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_STORE', + 249: 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_ATOMIC', + 250: 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS', + 251: 'SQ_PERF_SEL_DUMMY_END', + 287: 'SQ_PERF_SEL_DUMMY_LAST', + 288: 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 289: 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 290: 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', + 291: 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 292: 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 293: 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 294: 'SQC_PERF_SEL_LDS_ADDR_STALL', + 295: 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', + 296: 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 297: 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 298: 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 299: 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', + 300: 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 301: 'SQC_PERF_SEL_ICACHE_REQ', + 302: 'SQC_PERF_SEL_ICACHE_HITS', + 303: 'SQC_PERF_SEL_ICACHE_MISSES', + 304: 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 305: 'SQC_PERF_SEL_ICACHE_INVAL_INST', + 306: 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 307: 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 308: 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 309: 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', + 310: 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 311: 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 312: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 313: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 314: 'SQC_PERF_SEL_TC_REQ', + 315: 'SQC_PERF_SEL_TC_INST_REQ', + 316: 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 317: 'SQC_PERF_SEL_TC_STALL', + 318: 'SQC_PERF_SEL_TC_STARVE', + 319: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 320: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 321: 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 322: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 323: 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 324: 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 325: 'SQC_PERF_SEL_DCACHE_REQ', + 326: 'SQC_PERF_SEL_DCACHE_HITS', + 327: 'SQC_PERF_SEL_DCACHE_MISSES', + 328: 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 329: 'SQC_PERF_SEL_DCACHE_INVAL_INST', + 330: 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 331: 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 332: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 333: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 334: 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 335: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 336: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 337: 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 338: 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 339: 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 340: 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 341: 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 342: 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 343: 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 344: 'SQC_PERF_SEL_SQ_DCACHE_REQS', + 345: 'SQC_PERF_SEL_DCACHE_FLAT_REQ', + 346: 'SQC_PERF_SEL_TD_VGPR_BUSY', + 347: 'SQC_PERF_SEL_LDS_VGPR_BUSY', + 348: 'SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL', + 349: 'SQC_PERF_SEL_ICACHE_GCR', + 350: 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 351: 'SQC_PERF_SEL_DCACHE_GCR', + 352: 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 353: 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', + 354: 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', + 355: 'SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL', + 356: 'SQC_PERF_SEL_ICACHE_PREFETCH_REQ_CACHELINES', + 357: 'SQC_PERF_SEL_DCACHE_PREFETCH_REQ_CACHELINES', + 358: 'SQC_PERF_SEL_ICACHE_PREFETCH_MISSES', + 359: 'SQC_PERF_SEL_DCACHE_PREFETCH_MISSES', + 360: 'SQC_PERF_SEL_LDS_BANKCONF_LOAD_CNT', + 361: 'SQC_PERF_SEL_LDS_BANKCONF_STORE_CNT', + 362: 'SQC_PERF_SEL_LDS_BANKCONF_ATOMIC_CNT', + 363: 'SQC_PERF_SEL_LDS_ACTIVE_LOAD_CNT', + 364: 'SQC_PERF_SEL_LDS_ACTIVE_STORE_CNT', + 365: 'SQC_PERF_SEL_LDS_ACTIVE_ATOMIC_CNT', + 366: 'SQC_PERF_SEL_LDS_STORE_DWORDS', + 367: 'SQC_PERF_SEL_LDS_LOAD_DWORDS', + 368: 'SQC_PERF_SEL_LDS_ATOMIC_DWORDS', + 369: 'SQC_PERF_SEL_LDS_LDS_EXECUTION_STALL', + 370: 'SQC_PERF_SEL_DUMMY_LAST', + 448: 'SP_PERF_SEL_DST_BUF_ALLOC_STALL', + 449: 'SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS', + 450: 'SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI', + 451: 'SP_PERF_SEL_DST_BUF_EVEN_DIRTY', + 452: 'SP_PERF_SEL_DST_BUF_ODD_DIRTY', + 453: 'SP_PERF_SEL_SRC_CACHE_HIT_B0', + 454: 'SP_PERF_SEL_SRC_CACHE_HIT_B1', + 455: 'SP_PERF_SEL_SRC_CACHE_HIT_B2', + 456: 'SP_PERF_SEL_SRC_CACHE_HIT_B3', + 457: 'SP_PERF_SEL_SRC_CACHE_PROBE_B0', + 458: 'SP_PERF_SEL_SRC_CACHE_PROBE_B1', + 459: 'SP_PERF_SEL_SRC_CACHE_PROBE_B2', + 460: 'SP_PERF_SEL_SRC_CACHE_PROBE_B3', + 461: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0', + 462: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1', + 463: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2', + 464: 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3', + 465: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0', + 466: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1', + 467: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2', + 468: 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3', + 469: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0', + 470: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1', + 471: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2', + 472: 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3', + 473: 'SP_PERF_SEL_VALU_PENDING_QUEUE_STALL', + 474: 'SP_PERF_SEL_VALU_OPERAND', + 475: 'SP_PERF_SEL_VALU_VGPR_OPERAND', + 476: 'SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF', + 477: 'SP_PERF_SEL_VALU_EXEC_MASK_CHANGE', + 478: 'SP_PERF_SEL_VALU_COEXEC_WITH_TRANS', + 479: 'SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL', + 480: 'SP_PERF_SEL_VALU_STALL', + 481: 'SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY', + 482: 'SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY', + 483: 'SP_PERF_SEL_VALU_STALL_VDST_FWD', + 484: 'SP_PERF_SEL_VALU_STALL_SDST_FWD', + 485: 'SP_PERF_SEL_VALU_STALL_DST_STALL', + 486: 'SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY', + 487: 'SP_PERF_SEL_VGPR_VMEM_RD', + 488: 'SP_PERF_SEL_VGPR_EXP_RD', + 489: 'SP_PERF_SEL_VGPR_SPI_WR', + 490: 'SP_PERF_SEL_VGPR_TDLDS_DATA_WR', + 491: 'SP_PERF_SEL_VGPR_WR', + 492: 'SP_PERF_SEL_VGPR_RD', + 493: 'SP_PERF_SEL_VGPR_WR_KILL', + 494: 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_EXP', + 495: 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_LDS', + 496: 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_TEX', + 497: 'SP_PERF_SEL_DUMMY_LAST', + 511: 'SQ_PERF_SEL_NONE2', +} +SQ_PERF_SEL_NONE = 0 +SQ_PERF_SEL_ACCUM_PREV = 1 +SQ_PERF_SEL_CYCLES = 2 +SQ_PERF_SEL_BUSY_CYCLES = 3 +SQ_PERF_SEL_WAVES = 4 +SQ_PERF_SEL_WAVES_32 = 5 +SQ_PERF_SEL_WAVES_64 = 6 +SQ_PERF_SEL_LEVEL_WAVES = 7 +SQ_PERF_SEL_ITEMS = 8 +SQ_PERF_SEL_WAVE32_ITEMS = 9 +SQ_PERF_SEL_WAVE64_ITEMS = 10 +SQ_PERF_SEL_PS_QUADS = 11 +SQ_PERF_SEL_EVENTS = 12 +SQ_PERF_SEL_WAVES_EQ_32 = 13 +SQ_PERF_SEL_WAVES_EQ_64 = 14 +SQ_PERF_SEL_WAVES_LT_64 = 15 +SQ_PERF_SEL_WAVES_LT_48 = 16 +SQ_PERF_SEL_WAVES_LT_32 = 17 +SQ_PERF_SEL_WAVES_LT_16 = 18 +SQ_PERF_SEL_WAVES_RESTORED = 19 +SQ_PERF_SEL_WAVES_SAVED = 20 +SQ_PERF_SEL_MSG = 21 +SQ_PERF_SEL_MSG_INTERRUPT = 22 +SQ_PERF_SEL_WAVES_INITIAL_PREFETCH = 23 +SQ_PERF_SEL_WAVE_CYCLES = 24 +SQ_PERF_SEL_WAVE_READY = 25 +SQ_PERF_SEL_WAIT_INST_ANY = 26 +SQ_PERF_SEL_WAIT_ANY = 27 +SQ_PERF_SEL_WAIT_CNT_ANY = 28 +SQ_PERF_SEL_WAIT_CNT_LOAD = 29 +SQ_PERF_SEL_WAIT_CNT_STORE = 30 +SQ_PERF_SEL_WAIT_TTRACE = 31 +SQ_PERF_SEL_WAIT_IFETCH = 32 +SQ_PERF_SEL_WAIT_BARRIER = 33 +SQ_PERF_SEL_WAIT_EXP_ALLOC = 34 +SQ_PERF_SEL_WAIT_SLEEP = 35 +SQ_PERF_SEL_WAIT_DELAY_ALU = 36 +SQ_PERF_SEL_WAIT_DEPCTR = 37 +SQ_PERF_SEL_WAIT_OTHER = 38 +SQ_PERF_SEL_INSTS_ALL = 39 +SQ_PERF_SEL_INSTS_BRANCH = 40 +SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN = 41 +SQ_PERF_SEL_INSTS_CBRANCH_TAKEN = 42 +SQ_PERF_SEL_INSTS_EXP = 43 +SQ_PERF_SEL_INSTS_FLAT = 44 +SQ_PERF_SEL_INSTS_LDS = 45 +SQ_PERF_SEL_INSTS_SALU = 46 +SQ_PERF_SEL_INSTS_SMEM = 47 +SQ_PERF_SEL_INSTS_SMEM_NORM = 48 +SQ_PERF_SEL_INSTS_SENDMSG = 49 +SQ_PERF_SEL_INSTS_VALU = 50 +SQ_PERF_SEL_INSTS_VALU_TRANS32 = 51 +SQ_PERF_SEL_INSTS_VALU_NO_COEXEC = 52 +SQ_PERF_SEL_INSTS_TEX = 53 +SQ_PERF_SEL_INSTS_TEX_LOAD = 54 +SQ_PERF_SEL_INSTS_TEX_STORE = 55 +SQ_PERF_SEL_INSTS_DELAY_ALU = 56 +SQ_PERF_SEL_INSTS_INTERNAL = 57 +SQ_PERF_SEL_INSTS_VEC32 = 58 +SQ_PERF_SEL_INSTS_VEC32_FLAT = 59 +SQ_PERF_SEL_INSTS_VEC32_LDS = 60 +SQ_PERF_SEL_INSTS_VEC32_VALU = 61 +SQ_PERF_SEL_VEC32_INSTS_EXP = 62 +SQ_PERF_SEL_INSTS_VEC32_VALU_TRANS32 = 63 +SQ_PERF_SEL_INSTS_VEC32_VALU_NO_COEXEC = 64 +SQ_PERF_SEL_INSTS_VEC32_TEX = 65 +SQ_PERF_SEL_INSTS_VEC32_TEX_LOAD = 66 +SQ_PERF_SEL_INSTS_VEC32_TEX_STORE = 67 +SQ_PERF_SEL_ITEM_CYCLES_VALU = 68 +SQ_PERF_SEL_VALU_READWRITELANE_CYCLES = 69 +SQ_PERF_SEL_WAVE32_INSTS = 70 +SQ_PERF_SEL_WAVE64_INSTS = 71 +SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED = 72 +SQ_PERF_SEL_WAVE64_HALF_SKIP = 73 +SQ_PERF_SEL_INST_LEVEL_EXP = 74 +SQ_PERF_SEL_INST_LEVEL_LDS = 75 +SQ_PERF_SEL_INST_LEVEL_SMEM = 76 +SQ_PERF_SEL_INST_LEVEL_TEX_LOAD = 77 +SQ_PERF_SEL_INST_LEVEL_TEX_STORE = 78 +SQ_PERF_SEL_IFETCH_REQS = 79 +SQ_PERF_SEL_IFETCH_LEVEL = 80 +SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL = 81 +SQ_PERF_SEL_VALU_SGATHER_STALL = 82 +SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL = 83 +SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL = 84 +SQ_PERF_SEL_VALU_SGATHER_FULL_STALL = 85 +SQ_PERF_SEL_SALU_SGATHER_STALL = 86 +SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL = 87 +SQ_PERF_SEL_SALU_GATHER_FULL_STALL = 88 +SQ_PERF_SEL_INST_ISSUE_SMEM_STALL = 89 +SQ_PERF_SEL_INST_ISSUE_ALL_STALL = 90 +SQ_PERF_SEL_INST_ISSUE_VALU_STALL = 91 +SQ_PERF_SEL_INST_ISSUE_SALU_STALL = 92 +SQ_PERF_SEL_INST_ISSUE_TEX_STALL = 93 +SQ_PERF_SEL_INST_ISSUE_LDS_STALL = 94 +SQ_PERF_SEL_INST_ISSUE_EXP_STALL = 96 +SQ_PERF_SEL_INST_WAITCNT_STALL = 97 +SQ_PERF_SEL_INST_BARRIER_STALL = 98 +SQ_PERF_SEL_INST_CYCLES_VALU = 99 +SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32 = 100 +SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC = 101 +SQ_PERF_SEL_INST_CYCLES_VMEM = 102 +SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD = 103 +SQ_PERF_SEL_INST_CYCLES_VMEM_STORE = 104 +SQ_PERF_SEL_INST_CYCLES_LDS = 105 +SQ_PERF_SEL_INST_CYCLES_TEX = 106 +SQ_PERF_SEL_INST_CYCLES_FLAT = 107 +SQ_PERF_SEL_INST_CYCLES_EXP = 108 +SQ_PERF_SEL_VALU_STARVE = 109 +SQ_PERF_SEL_VMEM_ARB_FIFO_FULL = 110 +SQ_PERF_SEL_MSG_FIFO_FULL_STALL = 111 +SQ_PERF_SEL_EXP_REQ_FIFO_FULL = 112 +SQ_PERF_SEL_VMEM_BUS_ACTIVE = 113 +SQ_PERF_SEL_VMEM_BUS_STALL = 114 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL = 115 +SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL = 116 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL = 117 +SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL = 118 +SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY = 119 +SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY = 120 +SQ_PERF_SEL_SALU_PIPE_STALL = 121 +SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES = 122 +SQ_PERF_SEL_MSG_BUS_BUSY = 123 +SQ_PERF_SEL_EXP_REQ_BUS_STALL = 124 +SQ_PERF_SEL_EXP_REQ0_BUS_BUSY = 125 +SQ_PERF_SEL_EXP_REQ1_BUS_BUSY = 126 +SQ_PERF_SEL_EXP_BUS0_BUSY = 127 +SQ_PERF_SEL_EXP_BUS1_BUSY = 128 +SQ_PERF_SEL_INST_CACHE_REQ_STALL = 129 +SQ_PERF_SEL_USER0 = 130 +SQ_PERF_SEL_USER1 = 131 +SQ_PERF_SEL_USER2 = 132 +SQ_PERF_SEL_USER3 = 133 +SQ_PERF_SEL_USER4 = 134 +SQ_PERF_SEL_USER5 = 135 +SQ_PERF_SEL_USER6 = 136 +SQ_PERF_SEL_USER7 = 137 +SQ_PERF_SEL_USER8 = 138 +SQ_PERF_SEL_USER9 = 139 +SQ_PERF_SEL_USER10 = 140 +SQ_PERF_SEL_USER11 = 141 +SQ_PERF_SEL_USER12 = 142 +SQ_PERF_SEL_USER13 = 143 +SQ_PERF_SEL_USER14 = 144 +SQ_PERF_SEL_USER15 = 145 +SQ_PERF_SEL_USER_LEVEL0 = 146 +SQ_PERF_SEL_USER_LEVEL1 = 147 +SQ_PERF_SEL_USER_LEVEL2 = 148 +SQ_PERF_SEL_USER_LEVEL3 = 149 +SQ_PERF_SEL_USER_LEVEL4 = 150 +SQ_PERF_SEL_USER_LEVEL5 = 151 +SQ_PERF_SEL_USER_LEVEL6 = 152 +SQ_PERF_SEL_USER_LEVEL7 = 153 +SQ_PERF_SEL_USER_LEVEL8 = 154 +SQ_PERF_SEL_USER_LEVEL9 = 155 +SQ_PERF_SEL_USER_LEVEL10 = 156 +SQ_PERF_SEL_USER_LEVEL11 = 157 +SQ_PERF_SEL_USER_LEVEL12 = 158 +SQ_PERF_SEL_USER_LEVEL13 = 159 +SQ_PERF_SEL_USER_LEVEL14 = 160 +SQ_PERF_SEL_USER_LEVEL15 = 161 +SQ_PERF_SEL_VALU_RETURN_SDST = 162 +SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT = 163 +SQ_PERF_SEL_INSTS_VALU_TRANS = 164 +SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD = 165 +SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD = 166 +SQ_PERF_SEL_INSTS_VEC32_LDS_PARAM_LOAD = 167 +SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64 = 168 +SQ_PERF_SEL_INSTS_VALU_VINTERP = 169 +SQ_PERF_SEL_INSTS_VEC32_VALU_VINTERP = 170 +SQ_PERF_SEL_OVERFLOW_PREV = 171 +SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32 = 172 +SQ_PERF_SEL_INSTS_VALU_1_PASS = 173 +SQ_PERF_SEL_INSTS_VALU_2_PASS = 174 +SQ_PERF_SEL_INSTS_VALU_4_PASS = 175 +SQ_PERF_SEL_INSTS_VALU_DP = 176 +SQ_PERF_SEL_SP_CONST_CYCLES = 177 +SQ_PERF_SEL_SP_CONST_STALL_CYCLES = 178 +SQ_PERF_SEL_ITEMS_VALU = 179 +SQ_PERF_SEL_ITEMS_MAX_VALU = 180 +SQ_PERF_SEL_ITEM_CYCLES_VMEM = 181 +SQ_PERF_SEL_INSTS_DELAY_ALU_COISSUE = 182 +SQ_PERF_SEL_INSTS_FLAT_LOAD = 183 +SQ_PERF_SEL_INSTS_FLAT_STORE = 184 +SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_16BIT = 185 +SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_32BIT = 186 +SQ_PERF_SEL_INSTS_NON_VALU_EXEC_SKIPPED = 187 +SQ_PERF_SEL_INSTS_BARRIER_LOCK = 188 +SQ_PERF_SEL_INSTS_WAKEUP = 189 +SQ_PERF_SEL_IS_CACHE_REQ = 190 +SQ_PERF_SEL_INSTS_SALU_PS = 191 +SQ_PERF_SEL_INSTS_SALU_GS = 192 +SQ_PERF_SEL_INSTS_SALU_HS = 193 +SQ_PERF_SEL_INSTS_SALU_CS = 194 +SQ_PERF_SEL_INSTS_SMEM_PS = 195 +SQ_PERF_SEL_INSTS_SMEM_GS = 196 +SQ_PERF_SEL_INSTS_SMEM_HS = 197 +SQ_PERF_SEL_INSTS_SMEM_CS = 198 +SQ_PERF_SEL_INSTS_VEC32_TEX_PS = 199 +SQ_PERF_SEL_INSTS_VEC32_TEX_GS = 200 +SQ_PERF_SEL_INSTS_VEC32_TEX_HS = 201 +SQ_PERF_SEL_INSTS_VEC32_TEX_CS = 202 +SQ_PERF_SEL_INSTS_VEC32_VALU_PS = 203 +SQ_PERF_SEL_INSTS_VEC32_VALU_GS = 204 +SQ_PERF_SEL_INSTS_VEC32_VALU_HS = 205 +SQ_PERF_SEL_INSTS_VEC32_VALU_CS = 206 +SQ_PERF_SEL_WAIT_CNT_SAMPLE = 207 +SQ_PERF_SEL_WAIT_CNT_KM = 209 +SQ_PERF_SEL_WAIT_CNT_DS = 210 +SQ_PERF_SEL_WAIT_CNT_EXP = 211 +SQ_PERF_SEL_INSTS_SALU_FLOAT = 212 +SQ_PERF_SEL_INSTS_VGPR_ALLOC = 213 +SQ_PERF_SEL_INSTS_VGPR_ALLOC_FAIL = 214 +SQ_PERF_SEL_INSTS_LOCK = 215 +SQ_PERF_SEL_INSTS_VALU_COISSUE = 216 +SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_LOAD = 217 +SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_STORE = 218 +SQ_PERF_SEL_IS_CACHE_MISS = 219 +SQ_PERF_SEL_IS_CACHE_DUP_MISS = 220 +SQ_PERF_SEL_INST_CYCLES_VMEM_ATOMIC = 221 +SQ_PERF_SEL_INSTS_TEX_BLOCK_LOAD = 222 +SQ_PERF_SEL_INSTS_TEX_SAMPLE = 224 +SQ_PERF_SEL_INSTS_TEX_ATOMIC_RTN = 225 +SQ_PERF_SEL_INSTS_TEX_BLOCK_STORE = 226 +SQ_PERF_SEL_INSTS_TEX_ATOMIC_NORTN = 227 +SQ_PERF_SEL_INSTS_GLOBAL_SCRATCH = 228 +SQ_PERF_SEL_INSTS_WMMA_LOAD = 229 +SQ_PERF_SEL_INSTS_FLAT_ATOMIC = 230 +SQ_PERF_SEL_INSTS_EXP_MRT = 231 +SQ_PERF_SEL_INSTS_EXP_Z = 232 +SQ_PERF_SEL_INSTS_VEC32_VALU_WMMA = 233 +SQ_PERF_SEL_INSTS_VEC32_LDS_LOAD = 234 +SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_RTN = 235 +SQ_PERF_SEL_INSTS_VEC32_LDS_STORE = 236 +SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_NORTN = 237 +SQ_PERF_SEL_INSTS_VEC32_LDS_OTHER = 239 +SQ_PERF_SEL_INSTS_VEC32_TEX_SAMPLE = 241 +SQ_PERF_SEL_INSTS_VEC32_TEX_ATOMIC = 242 +SQ_PERF_SEL_INSTS_VEC32_FLAT_LOAD = 243 +SQ_PERF_SEL_INSTS_VEC32_FLAT_STORE = 244 +SQ_PERF_SEL_INSTS_VEC32_FLAT_ATOMIC = 245 +SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH = 246 +SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_LOAD = 247 +SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_STORE = 248 +SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_ATOMIC = 249 +SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS = 250 +SQ_PERF_SEL_DUMMY_END = 251 +SQ_PERF_SEL_DUMMY_LAST = 287 +SQC_PERF_SEL_LDS_BANK_CONFLICT = 288 +SQC_PERF_SEL_LDS_ADDR_CONFLICT = 289 +SQC_PERF_SEL_LDS_UNALIGNED_STALL = 290 +SQC_PERF_SEL_LDS_MEM_VIOLATIONS = 291 +SQC_PERF_SEL_LDS_ATOMIC_RETURN = 292 +SQC_PERF_SEL_LDS_IDX_ACTIVE = 293 +SQC_PERF_SEL_LDS_ADDR_STALL = 294 +SQC_PERF_SEL_LDS_ADDR_ACTIVE = 295 +SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD = 296 +SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD = 297 +SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL = 298 +SQC_PERF_SEL_LDS_FP_ADD_CYCLES = 299 +SQC_PERF_SEL_ICACHE_BUSY_CYCLES = 300 +SQC_PERF_SEL_ICACHE_REQ = 301 +SQC_PERF_SEL_ICACHE_HITS = 302 +SQC_PERF_SEL_ICACHE_MISSES = 303 +SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE = 304 +SQC_PERF_SEL_ICACHE_INVAL_INST = 305 +SQC_PERF_SEL_ICACHE_INVAL_ASYNC = 306 +SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL = 307 +SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL = 308 +SQC_PERF_SEL_TC_INFLIGHT_LEVEL = 309 +SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL = 310 +SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL = 311 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB = 312 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB = 313 +SQC_PERF_SEL_TC_REQ = 314 +SQC_PERF_SEL_TC_INST_REQ = 315 +SQC_PERF_SEL_TC_DATA_READ_REQ = 316 +SQC_PERF_SEL_TC_STALL = 317 +SQC_PERF_SEL_TC_STARVE = 318 +SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT = 319 +SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB = 320 +SQC_PERF_SEL_ICACHE_CACHE_STALLED = 321 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX = 322 +SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT = 323 +SQC_PERF_SEL_DCACHE_BUSY_CYCLES = 324 +SQC_PERF_SEL_DCACHE_REQ = 325 +SQC_PERF_SEL_DCACHE_HITS = 326 +SQC_PERF_SEL_DCACHE_MISSES = 327 +SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE = 328 +SQC_PERF_SEL_DCACHE_INVAL_INST = 329 +SQC_PERF_SEL_DCACHE_INVAL_ASYNC = 330 +SQC_PERF_SEL_DCACHE_HIT_LRU_READ = 331 +SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT = 332 +SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB = 333 +SQC_PERF_SEL_DCACHE_CACHE_STALLED = 334 +SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX = 335 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT = 336 +SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT = 337 +SQC_PERF_SEL_DCACHE_REQ_READ_1 = 338 +SQC_PERF_SEL_DCACHE_REQ_READ_2 = 339 +SQC_PERF_SEL_DCACHE_REQ_READ_4 = 340 +SQC_PERF_SEL_DCACHE_REQ_READ_8 = 341 +SQC_PERF_SEL_DCACHE_REQ_READ_16 = 342 +SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE = 343 +SQC_PERF_SEL_SQ_DCACHE_REQS = 344 +SQC_PERF_SEL_DCACHE_FLAT_REQ = 345 +SQC_PERF_SEL_TD_VGPR_BUSY = 346 +SQC_PERF_SEL_LDS_VGPR_BUSY = 347 +SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL = 348 +SQC_PERF_SEL_ICACHE_GCR = 349 +SQC_PERF_SEL_ICACHE_GCR_HITS = 350 +SQC_PERF_SEL_DCACHE_GCR = 351 +SQC_PERF_SEL_DCACHE_GCR_HITS = 352 +SQC_PERF_SEL_ICACHE_GCR_INVALIDATE = 353 +SQC_PERF_SEL_DCACHE_GCR_INVALIDATE = 354 +SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL = 355 +SQC_PERF_SEL_ICACHE_PREFETCH_REQ_CACHELINES = 356 +SQC_PERF_SEL_DCACHE_PREFETCH_REQ_CACHELINES = 357 +SQC_PERF_SEL_ICACHE_PREFETCH_MISSES = 358 +SQC_PERF_SEL_DCACHE_PREFETCH_MISSES = 359 +SQC_PERF_SEL_LDS_BANKCONF_LOAD_CNT = 360 +SQC_PERF_SEL_LDS_BANKCONF_STORE_CNT = 361 +SQC_PERF_SEL_LDS_BANKCONF_ATOMIC_CNT = 362 +SQC_PERF_SEL_LDS_ACTIVE_LOAD_CNT = 363 +SQC_PERF_SEL_LDS_ACTIVE_STORE_CNT = 364 +SQC_PERF_SEL_LDS_ACTIVE_ATOMIC_CNT = 365 +SQC_PERF_SEL_LDS_STORE_DWORDS = 366 +SQC_PERF_SEL_LDS_LOAD_DWORDS = 367 +SQC_PERF_SEL_LDS_ATOMIC_DWORDS = 368 +SQC_PERF_SEL_LDS_LDS_EXECUTION_STALL = 369 +SQC_PERF_SEL_DUMMY_LAST = 370 +SP_PERF_SEL_DST_BUF_ALLOC_STALL = 448 +SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS = 449 +SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI = 450 +SP_PERF_SEL_DST_BUF_EVEN_DIRTY = 451 +SP_PERF_SEL_DST_BUF_ODD_DIRTY = 452 +SP_PERF_SEL_SRC_CACHE_HIT_B0 = 453 +SP_PERF_SEL_SRC_CACHE_HIT_B1 = 454 +SP_PERF_SEL_SRC_CACHE_HIT_B2 = 455 +SP_PERF_SEL_SRC_CACHE_HIT_B3 = 456 +SP_PERF_SEL_SRC_CACHE_PROBE_B0 = 457 +SP_PERF_SEL_SRC_CACHE_PROBE_B1 = 458 +SP_PERF_SEL_SRC_CACHE_PROBE_B2 = 459 +SP_PERF_SEL_SRC_CACHE_PROBE_B3 = 460 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0 = 461 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1 = 462 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2 = 463 +SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3 = 464 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0 = 465 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1 = 466 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2 = 467 +SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3 = 468 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0 = 469 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1 = 470 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2 = 471 +SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3 = 472 +SP_PERF_SEL_VALU_PENDING_QUEUE_STALL = 473 +SP_PERF_SEL_VALU_OPERAND = 474 +SP_PERF_SEL_VALU_VGPR_OPERAND = 475 +SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF = 476 +SP_PERF_SEL_VALU_EXEC_MASK_CHANGE = 477 +SP_PERF_SEL_VALU_COEXEC_WITH_TRANS = 478 +SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL = 479 +SP_PERF_SEL_VALU_STALL = 480 +SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY = 481 +SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY = 482 +SP_PERF_SEL_VALU_STALL_VDST_FWD = 483 +SP_PERF_SEL_VALU_STALL_SDST_FWD = 484 +SP_PERF_SEL_VALU_STALL_DST_STALL = 485 +SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY = 486 +SP_PERF_SEL_VGPR_VMEM_RD = 487 +SP_PERF_SEL_VGPR_EXP_RD = 488 +SP_PERF_SEL_VGPR_SPI_WR = 489 +SP_PERF_SEL_VGPR_TDLDS_DATA_WR = 490 +SP_PERF_SEL_VGPR_WR = 491 +SP_PERF_SEL_VGPR_RD = 492 +SP_PERF_SEL_VGPR_WR_KILL = 493 +SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_EXP = 494 +SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_LDS = 495 +SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_TEX = 496 +SP_PERF_SEL_DUMMY_LAST = 497 +SQ_PERF_SEL_NONE2 = 511 +SQ_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_ROUND_MODE' +SQ_ROUND_MODE__enumvalues = { + 0: 'SQ_ROUND_NEAREST_EVEN', + 1: 'SQ_ROUND_PLUS_INFINITY', + 2: 'SQ_ROUND_MINUS_INFINITY', + 3: 'SQ_ROUND_TO_ZERO', +} +SQ_ROUND_NEAREST_EVEN = 0 +SQ_ROUND_PLUS_INFINITY = 1 +SQ_ROUND_MINUS_INFINITY = 2 +SQ_ROUND_TO_ZERO = 3 +SQ_ROUND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_BUF_TYPE' +SQ_RSRC_BUF_TYPE__enumvalues = { + 0: 'SQ_RSRC_BUF', + 1: 'SQ_RSRC_BUF_RSVD_1', + 2: 'SQ_RSRC_BUF_RSVD_2', + 3: 'SQ_RSRC_BUF_RSVD_3', +} +SQ_RSRC_BUF = 0 +SQ_RSRC_BUF_RSVD_1 = 1 +SQ_RSRC_BUF_RSVD_2 = 2 +SQ_RSRC_BUF_RSVD_3 = 3 +SQ_RSRC_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_FLAT_TYPE' +SQ_RSRC_FLAT_TYPE__enumvalues = { + 0: 'SQ_RSRC_FLAT_RSVD_0', + 1: 'SQ_RSRC_FLAT', + 2: 'SQ_RSRC_FLAT_RSVD_2', + 3: 'SQ_RSRC_FLAT_RSVD_3', +} +SQ_RSRC_FLAT_RSVD_0 = 0 +SQ_RSRC_FLAT = 1 +SQ_RSRC_FLAT_RSVD_2 = 2 +SQ_RSRC_FLAT_RSVD_3 = 3 +SQ_RSRC_FLAT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_IMG_TYPE' +SQ_RSRC_IMG_TYPE__enumvalues = { + 0: 'SQ_RSRC_IMG_RSVD_0', + 1: 'SQ_RSRC_IMG_RSVD_1', + 2: 'SQ_RSRC_IMG_RSVD_2', + 3: 'SQ_RSRC_IMG_RSVD_3', + 4: 'SQ_RSRC_IMG_RSVD_4', + 5: 'SQ_RSRC_IMG_RSVD_5', + 6: 'SQ_RSRC_IMG_RSVD_6', + 7: 'SQ_RSRC_IMG_RSVD_7', + 8: 'SQ_RSRC_IMG_1D', + 9: 'SQ_RSRC_IMG_2D', + 10: 'SQ_RSRC_IMG_3D', + 11: 'SQ_RSRC_IMG_CUBE', + 12: 'SQ_RSRC_IMG_1D_ARRAY', + 13: 'SQ_RSRC_IMG_2D_ARRAY', + 14: 'SQ_RSRC_IMG_2D_MSAA', + 15: 'SQ_RSRC_IMG_2D_MSAA_ARRAY', +} +SQ_RSRC_IMG_RSVD_0 = 0 +SQ_RSRC_IMG_RSVD_1 = 1 +SQ_RSRC_IMG_RSVD_2 = 2 +SQ_RSRC_IMG_RSVD_3 = 3 +SQ_RSRC_IMG_RSVD_4 = 4 +SQ_RSRC_IMG_RSVD_5 = 5 +SQ_RSRC_IMG_RSVD_6 = 6 +SQ_RSRC_IMG_RSVD_7 = 7 +SQ_RSRC_IMG_1D = 8 +SQ_RSRC_IMG_2D = 9 +SQ_RSRC_IMG_3D = 10 +SQ_RSRC_IMG_CUBE = 11 +SQ_RSRC_IMG_1D_ARRAY = 12 +SQ_RSRC_IMG_2D_ARRAY = 13 +SQ_RSRC_IMG_2D_MSAA = 14 +SQ_RSRC_IMG_2D_MSAA_ARRAY = 15 +SQ_RSRC_IMG_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_SEL_XYZW01' +SQ_SEL_XYZW01__enumvalues = { + 0: 'SQ_SEL_0', + 1: 'SQ_SEL_1', + 2: 'SQ_SEL_N_BC_1', + 3: 'SQ_SEL_RESERVED_1', + 4: 'SQ_SEL_X', + 5: 'SQ_SEL_Y', + 6: 'SQ_SEL_Z', + 7: 'SQ_SEL_W', +} +SQ_SEL_0 = 0 +SQ_SEL_1 = 1 +SQ_SEL_N_BC_1 = 2 +SQ_SEL_RESERVED_1 = 3 +SQ_SEL_X = 4 +SQ_SEL_Y = 5 +SQ_SEL_Z = 6 +SQ_SEL_W = 7 +SQ_SEL_XYZW01 = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_ANISO_RATIO' +SQ_TEX_ANISO_RATIO__enumvalues = { + 0: 'SQ_TEX_ANISO_RATIO_1', + 1: 'SQ_TEX_ANISO_RATIO_2', + 2: 'SQ_TEX_ANISO_RATIO_4', + 3: 'SQ_TEX_ANISO_RATIO_8', + 4: 'SQ_TEX_ANISO_RATIO_16', +} +SQ_TEX_ANISO_RATIO_1 = 0 +SQ_TEX_ANISO_RATIO_2 = 1 +SQ_TEX_ANISO_RATIO_4 = 2 +SQ_TEX_ANISO_RATIO_8 = 3 +SQ_TEX_ANISO_RATIO_16 = 4 +SQ_TEX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_BORDER_COLOR' +SQ_TEX_BORDER_COLOR__enumvalues = { + 0: 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 1: 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 2: 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 3: 'SQ_TEX_BORDER_COLOR_REGISTER', +} +SQ_TEX_BORDER_COLOR_TRANS_BLACK = 0 +SQ_TEX_BORDER_COLOR_OPAQUE_BLACK = 1 +SQ_TEX_BORDER_COLOR_OPAQUE_WHITE = 2 +SQ_TEX_BORDER_COLOR_REGISTER = 3 +SQ_TEX_BORDER_COLOR = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_CLAMP' +SQ_TEX_CLAMP__enumvalues = { + 0: 'SQ_TEX_WRAP', + 1: 'SQ_TEX_MIRROR', + 2: 'SQ_TEX_CLAMP_LAST_TEXEL', + 3: 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 4: 'SQ_TEX_CLAMP_HALF_BORDER', + 5: 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', + 6: 'SQ_TEX_CLAMP_BORDER', + 7: 'SQ_TEX_MIRROR_ONCE_BORDER', +} +SQ_TEX_WRAP = 0 +SQ_TEX_MIRROR = 1 +SQ_TEX_CLAMP_LAST_TEXEL = 2 +SQ_TEX_MIRROR_ONCE_LAST_TEXEL = 3 +SQ_TEX_CLAMP_HALF_BORDER = 4 +SQ_TEX_MIRROR_ONCE_HALF_BORDER = 5 +SQ_TEX_CLAMP_BORDER = 6 +SQ_TEX_MIRROR_ONCE_BORDER = 7 +SQ_TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_DEPTH_COMPARE' +SQ_TEX_DEPTH_COMPARE__enumvalues = { + 0: 'SQ_TEX_DEPTH_COMPARE_NEVER', + 1: 'SQ_TEX_DEPTH_COMPARE_LESS', + 2: 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 3: 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', + 4: 'SQ_TEX_DEPTH_COMPARE_GREATER', + 5: 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', + 6: 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', + 7: 'SQ_TEX_DEPTH_COMPARE_ALWAYS', +} +SQ_TEX_DEPTH_COMPARE_NEVER = 0 +SQ_TEX_DEPTH_COMPARE_LESS = 1 +SQ_TEX_DEPTH_COMPARE_EQUAL = 2 +SQ_TEX_DEPTH_COMPARE_LESSEQUAL = 3 +SQ_TEX_DEPTH_COMPARE_GREATER = 4 +SQ_TEX_DEPTH_COMPARE_NOTEQUAL = 5 +SQ_TEX_DEPTH_COMPARE_GREATEREQUAL = 6 +SQ_TEX_DEPTH_COMPARE_ALWAYS = 7 +SQ_TEX_DEPTH_COMPARE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_MIP_FILTER' +SQ_TEX_MIP_FILTER__enumvalues = { + 0: 'SQ_TEX_MIP_FILTER_NONE', + 1: 'SQ_TEX_MIP_FILTER_POINT', + 2: 'SQ_TEX_MIP_FILTER_LINEAR', + 3: 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', +} +SQ_TEX_MIP_FILTER_NONE = 0 +SQ_TEX_MIP_FILTER_POINT = 1 +SQ_TEX_MIP_FILTER_LINEAR = 2 +SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ = 3 +SQ_TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_XY_FILTER' +SQ_TEX_XY_FILTER__enumvalues = { + 0: 'SQ_TEX_XY_FILTER_POINT', + 1: 'SQ_TEX_XY_FILTER_BILINEAR', + 2: 'SQ_TEX_XY_FILTER_ANISO_POINT', + 3: 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', +} +SQ_TEX_XY_FILTER_POINT = 0 +SQ_TEX_XY_FILTER_BILINEAR = 1 +SQ_TEX_XY_FILTER_ANISO_POINT = 2 +SQ_TEX_XY_FILTER_ANISO_BILINEAR = 3 +SQ_TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_Z_FILTER' +SQ_TEX_Z_FILTER__enumvalues = { + 0: 'SQ_TEX_Z_FILTER_NONE', + 1: 'SQ_TEX_Z_FILTER_POINT', + 2: 'SQ_TEX_Z_FILTER_LINEAR', +} +SQ_TEX_Z_FILTER_NONE = 0 +SQ_TEX_Z_FILTER_POINT = 1 +SQ_TEX_Z_FILTER_LINEAR = 2 +SQ_TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WATCH_MODES' +SQ_WATCH_MODES__enumvalues = { + 0: 'SQ_WATCH_MODE_READ', + 1: 'SQ_WATCH_MODE_NONREAD', + 2: 'SQ_WATCH_MODE_ATOMIC', + 3: 'SQ_WATCH_MODE_ALL', +} +SQ_WATCH_MODE_READ = 0 +SQ_WATCH_MODE_NONREAD = 1 +SQ_WATCH_MODE_ATOMIC = 2 +SQ_WATCH_MODE_ALL = 3 +SQ_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_FWD_PROG_INTERVAL' +SQ_WAVE_FWD_PROG_INTERVAL__enumvalues = { + 0: 'SQ_WAVE_FWD_PROG_INTERVAL_NEVER', + 1: 'SQ_WAVE_FWD_PROG_INTERVAL_256', + 2: 'SQ_WAVE_FWD_PROG_INTERVAL_1024', + 3: 'SQ_WAVE_FWD_PROG_INTERVAL_4096', +} +SQ_WAVE_FWD_PROG_INTERVAL_NEVER = 0 +SQ_WAVE_FWD_PROG_INTERVAL_256 = 1 +SQ_WAVE_FWD_PROG_INTERVAL_1024 = 2 +SQ_WAVE_FWD_PROG_INTERVAL_4096 = 3 +SQ_WAVE_FWD_PROG_INTERVAL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_SCHED_MODES' +SQ_WAVE_SCHED_MODES__enumvalues = { + 0: 'SQ_WAVE_SCHED_MODE_NORMAL', + 1: 'SQ_WAVE_SCHED_MODE_EXPERT', + 2: 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST_VM_VSRC', +} +SQ_WAVE_SCHED_MODE_NORMAL = 0 +SQ_WAVE_SCHED_MODE_EXPERT = 1 +SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST_VM_VSRC = 2 +SQ_WAVE_SCHED_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_TYPE' +SQ_WAVE_TYPE__enumvalues = { + 0: 'SQ_WAVE_TYPE_PS', + 1: 'SQ_WAVE_TYPE_RSVD0', + 2: 'SQ_WAVE_TYPE_GS', + 3: 'SQ_WAVE_TYPE_RSVD1', + 4: 'SQ_WAVE_TYPE_HS', + 5: 'SQ_WAVE_TYPE_RSVD2', + 6: 'SQ_WAVE_TYPE_CS', + 7: 'SQ_WAVE_TYPE_PS1', + 8: 'SQ_WAVE_TYPE_PS2', + 9: 'SQ_WAVE_TYPE_PS3', +} +SQ_WAVE_TYPE_PS = 0 +SQ_WAVE_TYPE_RSVD0 = 1 +SQ_WAVE_TYPE_GS = 2 +SQ_WAVE_TYPE_RSVD1 = 3 +SQ_WAVE_TYPE_HS = 4 +SQ_WAVE_TYPE_RSVD2 = 5 +SQ_WAVE_TYPE_CS = 6 +SQ_WAVE_TYPE_PS1 = 7 +SQ_WAVE_TYPE_PS2 = 8 +SQ_WAVE_TYPE_PS3 = 9 +SQ_WAVE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'GL1A_PERF_SEL' +GL1A_PERF_SEL__enumvalues = { + 0: 'GL1A_PERF_SEL_BUSY', + 1: 'GL1A_PERF_SEL_STALL_GL1C0', + 2: 'GL1A_PERF_SEL_STALL_GL1C1', + 3: 'GL1A_PERF_SEL_STALL_GL1C2', + 4: 'GL1A_PERF_SEL_STALL_GL1C3', + 5: 'GL1A_PERF_SEL_REQUEST_GL1C0', + 6: 'GL1A_PERF_SEL_REQUEST_GL1C1', + 7: 'GL1A_PERF_SEL_REQUEST_GL1C2', + 8: 'GL1A_PERF_SEL_REQUEST_GL1C3', + 9: 'GL1A_PERF_SEL_WDS_32B_GL1C0', + 10: 'GL1A_PERF_SEL_WDS_32B_GL1C1', + 11: 'GL1A_PERF_SEL_WDS_32B_GL1C2', + 12: 'GL1A_PERF_SEL_WDS_32B_GL1C3', + 13: 'GL1A_PERF_SEL_BURST_COUNT_GL1C0', + 14: 'GL1A_PERF_SEL_BURST_COUNT_GL1C1', + 15: 'GL1A_PERF_SEL_BURST_COUNT_GL1C2', + 16: 'GL1A_PERF_SEL_BURST_COUNT_GL1C3', + 17: 'GL1A_PERF_SEL_ARB_REQUESTS', + 18: 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 19: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 20: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 21: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 22: 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 23: 'GL1A_PERF_SEL_CYCLE', +} +GL1A_PERF_SEL_BUSY = 0 +GL1A_PERF_SEL_STALL_GL1C0 = 1 +GL1A_PERF_SEL_STALL_GL1C1 = 2 +GL1A_PERF_SEL_STALL_GL1C2 = 3 +GL1A_PERF_SEL_STALL_GL1C3 = 4 +GL1A_PERF_SEL_REQUEST_GL1C0 = 5 +GL1A_PERF_SEL_REQUEST_GL1C1 = 6 +GL1A_PERF_SEL_REQUEST_GL1C2 = 7 +GL1A_PERF_SEL_REQUEST_GL1C3 = 8 +GL1A_PERF_SEL_WDS_32B_GL1C0 = 9 +GL1A_PERF_SEL_WDS_32B_GL1C1 = 10 +GL1A_PERF_SEL_WDS_32B_GL1C2 = 11 +GL1A_PERF_SEL_WDS_32B_GL1C3 = 12 +GL1A_PERF_SEL_BURST_COUNT_GL1C0 = 13 +GL1A_PERF_SEL_BURST_COUNT_GL1C1 = 14 +GL1A_PERF_SEL_BURST_COUNT_GL1C2 = 15 +GL1A_PERF_SEL_BURST_COUNT_GL1C3 = 16 +GL1A_PERF_SEL_ARB_REQUESTS = 17 +GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL = 18 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0 = 19 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1 = 20 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2 = 21 +GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3 = 22 +GL1A_PERF_SEL_CYCLE = 23 +GL1A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1C_PERF_SEL' +GL1C_PERF_SEL__enumvalues = { + 0: 'GL1C_PERF_SEL_CYCLE', + 1: 'GL1C_PERF_SEL_BUSY', + 2: 'GL1C_PERF_SEL_STARVE', + 3: 'GL1C_PERF_SEL_ARB_RET_LEVEL', + 4: 'GL1C_PERF_SEL_GL2_REQ_READ_LATENCY', + 5: 'GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 6: 'GL1C_PERF_SEL_REQ', + 7: 'GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET', + 8: 'GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 9: 'GL1C_PERF_SEL_REQ_NOP_ACK', + 10: 'GL1C_PERF_SEL_REQ_NOP_RTN0', + 11: 'GL1C_PERF_SEL_REQ_READ', + 12: 'GL1C_PERF_SEL_REQ_READ_128B', + 13: 'GL1C_PERF_SEL_REQ_READ_32B', + 14: 'GL1C_PERF_SEL_REQ_READ_64B', + 15: 'GL1C_PERF_SEL_REQ_WRITE', + 16: 'GL1C_PERF_SEL_REQ_WRITE_32B', + 17: 'GL1C_PERF_SEL_REQ_WRITE_64B', + 18: 'GL1C_PERF_SEL_STALL_GL2_GL1', + 19: 'GL1C_PERF_SEL_STALL_BUFFER_FULL', + 20: 'GL1C_PERF_SEL_STALL_VM', + 21: 'GL1C_PERF_SEL_REQ_CLIENT0', + 22: 'GL1C_PERF_SEL_REQ_CLIENT1', + 23: 'GL1C_PERF_SEL_REQ_CLIENT2', + 24: 'GL1C_PERF_SEL_REQ_CLIENT3', + 25: 'GL1C_PERF_SEL_REQ_CLIENT4', + 26: 'GL1C_PERF_SEL_REQ_CLIENT5', + 27: 'GL1C_PERF_SEL_REQ_CLIENT6', + 28: 'GL1C_PERF_SEL_REQ_CLIENT7', + 29: 'GL1C_PERF_SEL_REQ_CLIENT8', + 30: 'GL1C_PERF_SEL_REQ_CLIENT9', + 31: 'GL1C_PERF_SEL_REQ_CLIENT10', + 32: 'GL1C_PERF_SEL_REQ_CLIENT11', + 33: 'GL1C_PERF_SEL_REQ_CLIENT12', + 34: 'GL1C_PERF_SEL_REQ_CLIENT13', + 35: 'GL1C_PERF_SEL_REQ_CLIENT14', + 36: 'GL1C_PERF_SEL_REQ_CLIENT15', + 37: 'GL1C_PERF_SEL_REQ_CLIENT16', + 38: 'GL1C_PERF_SEL_REQ_CLIENT17', + 39: 'GL1C_PERF_SEL_REQ_CLIENT18', + 40: 'GL1C_PERF_SEL_REQ_CLIENT19', + 41: 'GL1C_PERF_SEL_REQ_CLIENT20', + 42: 'GL1C_PERF_SEL_REQ_CLIENT21', + 43: 'GL1C_PERF_SEL_REQ_CLIENT22', + 44: 'GL1C_PERF_SEL_REQ_CLIENT23', + 45: 'GL1C_PERF_SEL_REQ_CLIENT24', + 46: 'GL1C_PERF_SEL_REQ_CLIENT25', + 47: 'GL1C_PERF_SEL_REQ_CLIENT26', + 48: 'GL1C_PERF_SEL_REQ_CLIENT27', + 49: 'GL1C_PERF_SEL_UTCL0_REQUEST', + 50: 'GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT', + 51: 'GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS', + 52: 'GL1C_PERF_SEL_UTCL0_PERMISSION_MISS', + 53: 'GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 54: 'GL1C_PERF_SEL_UTCL0_LFIFO_FULL', + 55: 'GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 56: 'GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 57: 'GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 58: 'GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 59: 'GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 60: 'GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 61: 'GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 62: 'GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 63: 'GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 64: 'GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 65: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', + 66: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 67: 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', + 68: 'GL1C_PERF_SEL_UTCL0_GPA3_REQUEST', +} +GL1C_PERF_SEL_CYCLE = 0 +GL1C_PERF_SEL_BUSY = 1 +GL1C_PERF_SEL_STARVE = 2 +GL1C_PERF_SEL_ARB_RET_LEVEL = 3 +GL1C_PERF_SEL_GL2_REQ_READ_LATENCY = 4 +GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY = 5 +GL1C_PERF_SEL_REQ = 6 +GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET = 7 +GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 8 +GL1C_PERF_SEL_REQ_NOP_ACK = 9 +GL1C_PERF_SEL_REQ_NOP_RTN0 = 10 +GL1C_PERF_SEL_REQ_READ = 11 +GL1C_PERF_SEL_REQ_READ_128B = 12 +GL1C_PERF_SEL_REQ_READ_32B = 13 +GL1C_PERF_SEL_REQ_READ_64B = 14 +GL1C_PERF_SEL_REQ_WRITE = 15 +GL1C_PERF_SEL_REQ_WRITE_32B = 16 +GL1C_PERF_SEL_REQ_WRITE_64B = 17 +GL1C_PERF_SEL_STALL_GL2_GL1 = 18 +GL1C_PERF_SEL_STALL_BUFFER_FULL = 19 +GL1C_PERF_SEL_STALL_VM = 20 +GL1C_PERF_SEL_REQ_CLIENT0 = 21 +GL1C_PERF_SEL_REQ_CLIENT1 = 22 +GL1C_PERF_SEL_REQ_CLIENT2 = 23 +GL1C_PERF_SEL_REQ_CLIENT3 = 24 +GL1C_PERF_SEL_REQ_CLIENT4 = 25 +GL1C_PERF_SEL_REQ_CLIENT5 = 26 +GL1C_PERF_SEL_REQ_CLIENT6 = 27 +GL1C_PERF_SEL_REQ_CLIENT7 = 28 +GL1C_PERF_SEL_REQ_CLIENT8 = 29 +GL1C_PERF_SEL_REQ_CLIENT9 = 30 +GL1C_PERF_SEL_REQ_CLIENT10 = 31 +GL1C_PERF_SEL_REQ_CLIENT11 = 32 +GL1C_PERF_SEL_REQ_CLIENT12 = 33 +GL1C_PERF_SEL_REQ_CLIENT13 = 34 +GL1C_PERF_SEL_REQ_CLIENT14 = 35 +GL1C_PERF_SEL_REQ_CLIENT15 = 36 +GL1C_PERF_SEL_REQ_CLIENT16 = 37 +GL1C_PERF_SEL_REQ_CLIENT17 = 38 +GL1C_PERF_SEL_REQ_CLIENT18 = 39 +GL1C_PERF_SEL_REQ_CLIENT19 = 40 +GL1C_PERF_SEL_REQ_CLIENT20 = 41 +GL1C_PERF_SEL_REQ_CLIENT21 = 42 +GL1C_PERF_SEL_REQ_CLIENT22 = 43 +GL1C_PERF_SEL_REQ_CLIENT23 = 44 +GL1C_PERF_SEL_REQ_CLIENT24 = 45 +GL1C_PERF_SEL_REQ_CLIENT25 = 46 +GL1C_PERF_SEL_REQ_CLIENT26 = 47 +GL1C_PERF_SEL_REQ_CLIENT27 = 48 +GL1C_PERF_SEL_UTCL0_REQUEST = 49 +GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT = 50 +GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS = 51 +GL1C_PERF_SEL_UTCL0_PERMISSION_MISS = 52 +GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS = 53 +GL1C_PERF_SEL_UTCL0_LFIFO_FULL = 54 +GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX = 55 +GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES = 56 +GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT = 57 +GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL = 58 +GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS = 59 +GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 60 +GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT = 61 +GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT = 62 +GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT = 63 +GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ = 64 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT = 65 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT = 66 +GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT = 67 +GL1C_PERF_SEL_UTCL0_GPA3_REQUEST = 68 +GL1C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1XA_PERF_SEL' +GL1XA_PERF_SEL__enumvalues = { + 0: 'GL1XA_PERF_SEL_BUSY', + 1: 'GL1XA_PERF_SEL_STALL_GL1XC0', + 2: 'GL1XA_PERF_SEL_STALL_GL1XC1', + 3: 'GL1XA_PERF_SEL_STALL_GL1XC2', + 4: 'GL1XA_PERF_SEL_STALL_GL1XC3', + 5: 'GL1XA_PERF_SEL_REQUEST_GL1XC0', + 6: 'GL1XA_PERF_SEL_REQUEST_GL1XC1', + 7: 'GL1XA_PERF_SEL_REQUEST_GL1XC2', + 8: 'GL1XA_PERF_SEL_REQUEST_GL1XC3', + 9: 'GL1XA_PERF_SEL_WDS_32B_GL1XC0', + 10: 'GL1XA_PERF_SEL_WDS_32B_GL1XC1', + 11: 'GL1XA_PERF_SEL_WDS_32B_GL1XC2', + 12: 'GL1XA_PERF_SEL_WDS_32B_GL1XC3', + 13: 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC0', + 14: 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC1', + 15: 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC2', + 16: 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC3', + 17: 'GL1XA_PERF_SEL_ARB_REQUESTS', + 18: 'GL1XA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 19: 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC0', + 20: 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC1', + 21: 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC2', + 22: 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC3', + 23: 'GL1XA_PERF_SEL_CYCLE', +} +GL1XA_PERF_SEL_BUSY = 0 +GL1XA_PERF_SEL_STALL_GL1XC0 = 1 +GL1XA_PERF_SEL_STALL_GL1XC1 = 2 +GL1XA_PERF_SEL_STALL_GL1XC2 = 3 +GL1XA_PERF_SEL_STALL_GL1XC3 = 4 +GL1XA_PERF_SEL_REQUEST_GL1XC0 = 5 +GL1XA_PERF_SEL_REQUEST_GL1XC1 = 6 +GL1XA_PERF_SEL_REQUEST_GL1XC2 = 7 +GL1XA_PERF_SEL_REQUEST_GL1XC3 = 8 +GL1XA_PERF_SEL_WDS_32B_GL1XC0 = 9 +GL1XA_PERF_SEL_WDS_32B_GL1XC1 = 10 +GL1XA_PERF_SEL_WDS_32B_GL1XC2 = 11 +GL1XA_PERF_SEL_WDS_32B_GL1XC3 = 12 +GL1XA_PERF_SEL_BURST_COUNT_GL1XC0 = 13 +GL1XA_PERF_SEL_BURST_COUNT_GL1XC1 = 14 +GL1XA_PERF_SEL_BURST_COUNT_GL1XC2 = 15 +GL1XA_PERF_SEL_BURST_COUNT_GL1XC3 = 16 +GL1XA_PERF_SEL_ARB_REQUESTS = 17 +GL1XA_PERF_SEL_REQ_INFLIGHT_LEVEL = 18 +GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC0 = 19 +GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC1 = 20 +GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC2 = 21 +GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC3 = 22 +GL1XA_PERF_SEL_CYCLE = 23 +GL1XA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL1XC_PERF_SEL' +GL1XC_PERF_SEL__enumvalues = { + 0: 'GL1XC_PERF_SEL_CYCLE', + 1: 'GL1XC_PERF_SEL_BUSY', + 2: 'GL1XC_PERF_SEL_STARVE', + 3: 'GL1XC_PERF_SEL_ARB_RET_LEVEL', + 4: 'GL1XC_PERF_SEL_GL2_REQ_READ_LATENCY', + 5: 'GL1XC_PERF_SEL_GL2_REQ_WRITE_LATENCY', + 6: 'GL1XC_PERF_SEL_REQ', + 7: 'GL1XC_PERF_SEL_REQ_ATOMIC_WITH_RET', + 8: 'GL1XC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 9: 'GL1XC_PERF_SEL_REQ_NOP_ACK', + 10: 'GL1XC_PERF_SEL_REQ_NOP_RTN0', + 11: 'GL1XC_PERF_SEL_REQ_READ', + 12: 'GL1XC_PERF_SEL_REQ_READ_128B', + 13: 'GL1XC_PERF_SEL_REQ_READ_32B', + 14: 'GL1XC_PERF_SEL_REQ_READ_64B', + 15: 'GL1XC_PERF_SEL_REQ_WRITE', + 16: 'GL1XC_PERF_SEL_REQ_WRITE_32B', + 17: 'GL1XC_PERF_SEL_REQ_WRITE_64B', + 18: 'GL1XC_PERF_SEL_STALL_GL2_GL1', + 19: 'GL1XC_PERF_SEL_STALL_BUFFER_FULL', + 20: 'GL1XC_PERF_SEL_STALL_VM', + 21: 'GL1XC_PERF_SEL_REQ_CLIENT0', + 22: 'GL1XC_PERF_SEL_REQ_CLIENT1', + 23: 'GL1XC_PERF_SEL_REQ_CLIENT2', + 24: 'GL1XC_PERF_SEL_REQ_CLIENT3', + 25: 'GL1XC_PERF_SEL_REQ_CLIENT4', + 26: 'GL1XC_PERF_SEL_REQ_CLIENT5', + 27: 'GL1XC_PERF_SEL_REQ_CLIENT6', + 28: 'GL1XC_PERF_SEL_REQ_CLIENT7', + 29: 'GL1XC_PERF_SEL_REQ_CLIENT8', + 30: 'GL1XC_PERF_SEL_REQ_CLIENT9', + 31: 'GL1XC_PERF_SEL_REQ_CLIENT10', + 32: 'GL1XC_PERF_SEL_REQ_CLIENT11', + 33: 'GL1XC_PERF_SEL_REQ_CLIENT12', + 34: 'GL1XC_PERF_SEL_REQ_CLIENT13', + 35: 'GL1XC_PERF_SEL_REQ_CLIENT14', + 36: 'GL1XC_PERF_SEL_REQ_CLIENT15', + 37: 'GL1XC_PERF_SEL_REQ_CLIENT16', + 38: 'GL1XC_PERF_SEL_REQ_CLIENT17', + 39: 'GL1XC_PERF_SEL_REQ_CLIENT18', + 40: 'GL1XC_PERF_SEL_REQ_CLIENT19', + 41: 'GL1XC_PERF_SEL_REQ_CLIENT20', + 42: 'GL1XC_PERF_SEL_REQ_CLIENT21', + 43: 'GL1XC_PERF_SEL_REQ_CLIENT22', + 44: 'GL1XC_PERF_SEL_REQ_CLIENT23', + 45: 'GL1XC_PERF_SEL_REQ_CLIENT24', + 46: 'GL1XC_PERF_SEL_REQ_CLIENT25', + 47: 'GL1XC_PERF_SEL_REQ_CLIENT26', + 48: 'GL1XC_PERF_SEL_REQ_CLIENT27', + 49: 'GL1XC_PERF_SEL_UTCL0_REQUEST', + 50: 'GL1XC_PERF_SEL_UTCL0_TRANSLATION_HIT', + 51: 'GL1XC_PERF_SEL_UTCL0_TRANSLATION_MISS', + 52: 'GL1XC_PERF_SEL_UTCL0_PERMISSION_MISS', + 53: 'GL1XC_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 54: 'GL1XC_PERF_SEL_UTCL0_LFIFO_FULL', + 55: 'GL1XC_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 56: 'GL1XC_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 57: 'GL1XC_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 58: 'GL1XC_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 59: 'GL1XC_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 60: 'GL1XC_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 61: 'GL1XC_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 62: 'GL1XC_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 63: 'GL1XC_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 64: 'GL1XC_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 65: 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', + 66: 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 67: 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', + 68: 'GL1XC_PERF_SEL_UTCL0_GPA3_REQUEST', +} +GL1XC_PERF_SEL_CYCLE = 0 +GL1XC_PERF_SEL_BUSY = 1 +GL1XC_PERF_SEL_STARVE = 2 +GL1XC_PERF_SEL_ARB_RET_LEVEL = 3 +GL1XC_PERF_SEL_GL2_REQ_READ_LATENCY = 4 +GL1XC_PERF_SEL_GL2_REQ_WRITE_LATENCY = 5 +GL1XC_PERF_SEL_REQ = 6 +GL1XC_PERF_SEL_REQ_ATOMIC_WITH_RET = 7 +GL1XC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET = 8 +GL1XC_PERF_SEL_REQ_NOP_ACK = 9 +GL1XC_PERF_SEL_REQ_NOP_RTN0 = 10 +GL1XC_PERF_SEL_REQ_READ = 11 +GL1XC_PERF_SEL_REQ_READ_128B = 12 +GL1XC_PERF_SEL_REQ_READ_32B = 13 +GL1XC_PERF_SEL_REQ_READ_64B = 14 +GL1XC_PERF_SEL_REQ_WRITE = 15 +GL1XC_PERF_SEL_REQ_WRITE_32B = 16 +GL1XC_PERF_SEL_REQ_WRITE_64B = 17 +GL1XC_PERF_SEL_STALL_GL2_GL1 = 18 +GL1XC_PERF_SEL_STALL_BUFFER_FULL = 19 +GL1XC_PERF_SEL_STALL_VM = 20 +GL1XC_PERF_SEL_REQ_CLIENT0 = 21 +GL1XC_PERF_SEL_REQ_CLIENT1 = 22 +GL1XC_PERF_SEL_REQ_CLIENT2 = 23 +GL1XC_PERF_SEL_REQ_CLIENT3 = 24 +GL1XC_PERF_SEL_REQ_CLIENT4 = 25 +GL1XC_PERF_SEL_REQ_CLIENT5 = 26 +GL1XC_PERF_SEL_REQ_CLIENT6 = 27 +GL1XC_PERF_SEL_REQ_CLIENT7 = 28 +GL1XC_PERF_SEL_REQ_CLIENT8 = 29 +GL1XC_PERF_SEL_REQ_CLIENT9 = 30 +GL1XC_PERF_SEL_REQ_CLIENT10 = 31 +GL1XC_PERF_SEL_REQ_CLIENT11 = 32 +GL1XC_PERF_SEL_REQ_CLIENT12 = 33 +GL1XC_PERF_SEL_REQ_CLIENT13 = 34 +GL1XC_PERF_SEL_REQ_CLIENT14 = 35 +GL1XC_PERF_SEL_REQ_CLIENT15 = 36 +GL1XC_PERF_SEL_REQ_CLIENT16 = 37 +GL1XC_PERF_SEL_REQ_CLIENT17 = 38 +GL1XC_PERF_SEL_REQ_CLIENT18 = 39 +GL1XC_PERF_SEL_REQ_CLIENT19 = 40 +GL1XC_PERF_SEL_REQ_CLIENT20 = 41 +GL1XC_PERF_SEL_REQ_CLIENT21 = 42 +GL1XC_PERF_SEL_REQ_CLIENT22 = 43 +GL1XC_PERF_SEL_REQ_CLIENT23 = 44 +GL1XC_PERF_SEL_REQ_CLIENT24 = 45 +GL1XC_PERF_SEL_REQ_CLIENT25 = 46 +GL1XC_PERF_SEL_REQ_CLIENT26 = 47 +GL1XC_PERF_SEL_REQ_CLIENT27 = 48 +GL1XC_PERF_SEL_UTCL0_REQUEST = 49 +GL1XC_PERF_SEL_UTCL0_TRANSLATION_HIT = 50 +GL1XC_PERF_SEL_UTCL0_TRANSLATION_MISS = 51 +GL1XC_PERF_SEL_UTCL0_PERMISSION_MISS = 52 +GL1XC_PERF_SEL_UTCL0_MISS_UNDER_MISS = 53 +GL1XC_PERF_SEL_UTCL0_LFIFO_FULL = 54 +GL1XC_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX = 55 +GL1XC_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES = 56 +GL1XC_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT = 57 +GL1XC_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL = 58 +GL1XC_PERF_SEL_UTCL0_STALL_MULTI_MISS = 59 +GL1XC_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS = 60 +GL1XC_PERF_SEL_UTCL0_UTCL1_PERM_FAULT = 61 +GL1XC_PERF_SEL_CLIENT_UTCL0_INFLIGHT = 62 +GL1XC_PERF_SEL_UTCL0_UTCL1_INFLIGHT = 63 +GL1XC_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ = 64 +GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT = 65 +GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT = 66 +GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT = 67 +GL1XC_PERF_SEL_UTCL0_GPA3_REQUEST = 68 +GL1XC_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBMH_PERF_SEL' +GRBMH_PERF_SEL__enumvalues = { + 0: 'GRBMH_PERF_SEL_COUNT', + 1: 'GRBMH_PERF_SEL_USER_DEFINED', + 2: 'GRBMH_PERF_SEL_CB_BUSY', + 3: 'GRBMH_PERF_SEL_CB_CLEAN', + 4: 'GRBMH_PERF_SEL_DB_BUSY', + 5: 'GRBMH_PERF_SEL_DB_CLEAN', + 6: 'GRBMH_PERF_SEL_SC_BUSY', + 7: 'GRBMH_PERF_SEL_SC_CLEAN', + 9: 'GRBMH_PERF_SEL_SPI_BUSY', + 10: 'GRBMH_PERF_SEL_SX_BUSY', + 11: 'GRBMH_PERF_SEL_TA_BUSY', + 12: 'GRBMH_PERF_SEL_EA_BUSY', + 13: 'GRBMH_PERF_SEL_EA_LINK_BUSY', + 14: 'GRBMH_PERF_SEL_PA_BUSY', + 15: 'GRBMH_PERF_SEL_BCI_BUSY', + 16: 'GRBMH_PERF_SEL_GL2A_BUSY', + 17: 'GRBMH_PERF_SEL_GL2C_BUSY', + 18: 'GRBMH_PERF_SEL_UTCL1_BUSY', + 19: 'GRBMH_PERF_SEL_TCP_BUSY', + 20: 'GRBMH_PERF_SEL_GL1A_BUSY', + 21: 'GRBMH_PERF_SEL_GL1CC_BUSY', + 22: 'GRBMH_PERF_SEL_GL1XCC_BUSY', + 23: 'GRBMH_PERF_SEL_PC_BUSY', + 24: 'GRBMH_PERF_SEL_GE_BUSY', + 25: 'GRBMH_PERF_SEL_RLC_BUSY', +} +GRBMH_PERF_SEL_COUNT = 0 +GRBMH_PERF_SEL_USER_DEFINED = 1 +GRBMH_PERF_SEL_CB_BUSY = 2 +GRBMH_PERF_SEL_CB_CLEAN = 3 +GRBMH_PERF_SEL_DB_BUSY = 4 +GRBMH_PERF_SEL_DB_CLEAN = 5 +GRBMH_PERF_SEL_SC_BUSY = 6 +GRBMH_PERF_SEL_SC_CLEAN = 7 +GRBMH_PERF_SEL_SPI_BUSY = 9 +GRBMH_PERF_SEL_SX_BUSY = 10 +GRBMH_PERF_SEL_TA_BUSY = 11 +GRBMH_PERF_SEL_EA_BUSY = 12 +GRBMH_PERF_SEL_EA_LINK_BUSY = 13 +GRBMH_PERF_SEL_PA_BUSY = 14 +GRBMH_PERF_SEL_BCI_BUSY = 15 +GRBMH_PERF_SEL_GL2A_BUSY = 16 +GRBMH_PERF_SEL_GL2C_BUSY = 17 +GRBMH_PERF_SEL_UTCL1_BUSY = 18 +GRBMH_PERF_SEL_TCP_BUSY = 19 +GRBMH_PERF_SEL_GL1A_BUSY = 20 +GRBMH_PERF_SEL_GL1CC_BUSY = 21 +GRBMH_PERF_SEL_GL1XCC_BUSY = 22 +GRBMH_PERF_SEL_PC_BUSY = 23 +GRBMH_PERF_SEL_GE_BUSY = 24 +GRBMH_PERF_SEL_RLC_BUSY = 25 +GRBMH_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TA_PERFCOUNT_SEL' +TA_PERFCOUNT_SEL__enumvalues = { + 0: 'TA_PERF_SEL_NULL', + 1: 'TA_PERF_SEL_image_sampler_has_offset_instructions', + 2: 'TA_PERF_SEL_image_sampler_has_bias_instructions', + 3: 'TA_PERF_SEL_image_sampler_has_reference_instructions', + 4: 'TA_PERF_SEL_image_sampler_has_ds_instructions', + 5: 'TA_PERF_SEL_image_sampler_has_dt_instructions', + 6: 'TA_PERF_SEL_image_sampler_has_dr_instructions', + 7: 'TA_PERF_SEL_gradient_busy', + 8: 'TA_PERF_SEL_gradient_fifo_busy', + 9: 'TA_PERF_SEL_lod_busy', + 10: 'TA_PERF_SEL_lod_fifo_busy', + 11: 'TA_PERF_SEL_addresser_busy', + 12: 'TA_PERF_SEL_addresser_fifo_busy', + 13: 'TA_PERF_SEL_aligner_busy', + 14: 'TA_PERF_SEL_write_path_busy', + 15: 'TA_PERF_SEL_ta_busy', + 16: 'TA_PERF_SEL_image_sampler_1_input_vgpr_instructions', + 17: 'TA_PERF_SEL_image_sampler_2_input_vgpr_instructions', + 18: 'TA_PERF_SEL_image_sampler_3_input_vgpr_instructions', + 19: 'TA_PERF_SEL_image_sampler_4_input_vgpr_instructions', + 20: 'TA_PERF_SEL_image_sampler_5_input_vgpr_instructions', + 21: 'TA_PERF_SEL_image_sampler_6_input_vgpr_instructions', + 22: 'TA_PERF_SEL_image_sampler_7_input_vgpr_instructions', + 23: 'TA_PERF_SEL_image_sampler_8_input_vgpr_instructions', + 24: 'TA_PERF_SEL_image_sampler_9_input_vgpr_instructions', + 25: 'TA_PERF_SEL_image_sampler_10_input_vgpr_instructions', + 26: 'TA_PERF_SEL_image_sampler_11_input_vgpr_instructions', + 27: 'TA_PERF_SEL_image_sampler_12_input_vgpr_instructions', + 28: 'TA_PERF_SEL_image_sampler_has_t_instructions', + 29: 'TA_PERF_SEL_image_sampler_has_r_instructions', + 30: 'TA_PERF_SEL_image_sampler_has_q_instructions', + 32: 'TA_PERF_SEL_total_wavefronts', + 33: 'TA_PERF_SEL_gradient_cycles', + 34: 'TA_PERF_SEL_walker_cycles', + 35: 'TA_PERF_SEL_aligner_cycles', + 36: 'TA_PERF_SEL_image_wavefronts', + 37: 'TA_PERF_SEL_image_read_wavefronts', + 38: 'TA_PERF_SEL_image_store_wavefronts', + 39: 'TA_PERF_SEL_image_atomic_wavefronts', + 40: 'TA_PERF_SEL_image_sampler_total_cycles', + 41: 'TA_PERF_SEL_image_nosampler_total_cycles', + 42: 'TA_PERF_SEL_flat_total_cycles', + 44: 'TA_PERF_SEL_buffer_wavefronts', + 45: 'TA_PERF_SEL_buffer_load_wavefronts', + 46: 'TA_PERF_SEL_buffer_store_wavefronts', + 47: 'TA_PERF_SEL_buffer_atomic_wavefronts', + 49: 'TA_PERF_SEL_buffer_total_cycles', + 50: 'TA_PERF_SEL_buffer_1_address_input_vgpr_instructions', + 51: 'TA_PERF_SEL_buffer_2_address_input_vgpr_instructions', + 52: 'TA_PERF_SEL_buffer_has_index_instructions', + 53: 'TA_PERF_SEL_buffer_has_offset_instructions', + 54: 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 55: 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 56: 'TA_PERF_SEL_image_sampler_wavefronts', + 57: 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 58: 'TA_PERF_SEL_addresser_stalled_cycles', + 59: 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 60: 'TA_PERF_SEL_aniso_stalled_cycles', + 61: 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 62: 'TA_PERF_SEL_deriv_stalled_cycles', + 63: 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 64: 'TA_PERF_SEL_color_1_cycle_quads', + 65: 'TA_PERF_SEL_color_2_cycle_quads', + 66: 'TA_PERF_SEL_color_3_cycle_quads', + 68: 'TA_PERF_SEL_mip_1_cycle_quads', + 69: 'TA_PERF_SEL_mip_2_cycle_quads', + 70: 'TA_PERF_SEL_vol_1_cycle_quads', + 71: 'TA_PERF_SEL_vol_2_cycle_quads', + 72: 'TA_PERF_SEL_sampler_op_quads', + 73: 'TA_PERF_SEL_mipmap_lod_0_samples', + 74: 'TA_PERF_SEL_mipmap_lod_1_samples', + 75: 'TA_PERF_SEL_mipmap_lod_2_samples', + 76: 'TA_PERF_SEL_mipmap_lod_3_samples', + 77: 'TA_PERF_SEL_mipmap_lod_4_samples', + 78: 'TA_PERF_SEL_mipmap_lod_5_samples', + 79: 'TA_PERF_SEL_mipmap_lod_6_samples', + 80: 'TA_PERF_SEL_mipmap_lod_7_samples', + 81: 'TA_PERF_SEL_mipmap_lod_8_samples', + 82: 'TA_PERF_SEL_mipmap_lod_9_samples', + 83: 'TA_PERF_SEL_mipmap_lod_10_samples', + 84: 'TA_PERF_SEL_mipmap_lod_11_samples', + 85: 'TA_PERF_SEL_mipmap_lod_12_samples', + 86: 'TA_PERF_SEL_mipmap_lod_13_samples', + 87: 'TA_PERF_SEL_mipmap_lod_14_samples', + 88: 'TA_PERF_SEL_mipmap_invalid_samples', + 89: 'TA_PERF_SEL_aniso_1_cycle_quads', + 90: 'TA_PERF_SEL_aniso_2_cycle_quads', + 91: 'TA_PERF_SEL_aniso_4_cycle_quads', + 92: 'TA_PERF_SEL_aniso_6_cycle_quads', + 93: 'TA_PERF_SEL_aniso_8_cycle_quads', + 94: 'TA_PERF_SEL_aniso_10_cycle_quads', + 95: 'TA_PERF_SEL_aniso_12_cycle_quads', + 96: 'TA_PERF_SEL_aniso_14_cycle_quads', + 97: 'TA_PERF_SEL_aniso_16_cycle_quads', + 98: 'TA_PERF_SEL_store_write_data_input_cycles', + 99: 'TA_PERF_SEL_store_write_data_output_cycles', + 100: 'TA_PERF_SEL_flat_wavefronts', + 101: 'TA_PERF_SEL_flat_load_wavefronts', + 102: 'TA_PERF_SEL_flat_store_wavefronts', + 103: 'TA_PERF_SEL_flat_atomic_wavefronts', + 104: 'TA_PERF_SEL_flat_1_address_input_vgpr_instructions', + 105: 'TA_PERF_SEL_register_clk_valid_cycles', + 106: 'TA_PERF_SEL_non_harvestable_clk_enabled_cycles', + 107: 'TA_PERF_SEL_harvestable_clk_enabled_cycles', + 108: 'TA_PERF_SEL_flat_2_address_input_vgpr_instructions', + 109: 'TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles', + 110: 'TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles', + 112: 'TA_PERF_SEL_mipmap_lod_15_samples', + 113: 'TA_PERF_SEL_mipmap_lod_16_samples', + 114: 'TA_PERF_SEL_store_2_write_data_vgpr_instructions', + 115: 'TA_PERF_SEL_store_3_write_data_vgpr_instructions', + 116: 'TA_PERF_SEL_store_4_write_data_vgpr_instructions', + 117: 'TA_PERF_SEL_store_has_x_instructions', + 118: 'TA_PERF_SEL_store_has_y_instructions', + 119: 'TA_PERF_SEL_store_has_z_instructions', + 120: 'TA_PERF_SEL_store_has_w_instructions', + 121: 'TA_PERF_SEL_image_nosampler_has_t_instructions', + 122: 'TA_PERF_SEL_image_nosampler_has_r_instructions', + 123: 'TA_PERF_SEL_image_nosampler_has_q_instructions', + 124: 'TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions', + 125: 'TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions', + 126: 'TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions', + 127: 'TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions', + 128: 'TA_PERF_SEL_in_busy', + 129: 'TA_PERF_SEL_in_fifos_busy', + 130: 'TA_PERF_SEL_in_cfifo_busy', + 131: 'TA_PERF_SEL_in_qfifo_busy', + 132: 'TA_PERF_SEL_in_wfifo_busy', + 133: 'TA_PERF_SEL_in_rfifo_busy', + 134: 'TA_PERF_SEL_bf_busy', + 135: 'TA_PERF_SEL_ns_busy', + 136: 'TA_PERF_SEL_smp_busy_ns_idle', + 137: 'TA_PERF_SEL_smp_idle_ns_busy', + 144: 'TA_PERF_SEL_vmemcmd_cycles', + 145: 'TA_PERF_SEL_vmemreq_cycles', + 146: 'TA_PERF_SEL_in_waiting_on_req_cycles', + 150: 'TA_PERF_SEL_in_addr_cycles', + 151: 'TA_PERF_SEL_in_data_cycles', + 160: 'TA_PERF_SEL_point_sampled_quads', + 162: 'TA_PERF_SEL_atomic_2_write_data_vgpr_instructions', + 163: 'TA_PERF_SEL_atomic_4_write_data_vgpr_instructions', + 164: 'TA_PERF_SEL_atomic_write_data_input_cycles', + 165: 'TA_PERF_SEL_atomic_write_data_output_cycles', + 173: 'TA_PERF_SEL_num_unlit_nodes_ta_opt', + 174: 'TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input', + 175: 'TA_PERF_SEL_num_nodes_invalidated_due_to_oob', + 192: 'TA_PERF_SEL_image_sampler_1_op_burst', + 193: 'TA_PERF_SEL_image_sampler_2to3_op_burst', + 194: 'TA_PERF_SEL_image_sampler_4to7_op_burst', + 195: 'TA_PERF_SEL_image_sampler_ge8_op_burst', + 196: 'TA_PERF_SEL_image_linked_1_op_burst', + 197: 'TA_PERF_SEL_image_linked_2to3_op_burst', + 198: 'TA_PERF_SEL_image_linked_4to7_op_burst', + 199: 'TA_PERF_SEL_image_linked_ge8_op_burst', + 204: 'TA_PERF_SEL_image_nosampler_1_op_burst', + 205: 'TA_PERF_SEL_image_nosampler_2to3_op_burst', + 206: 'TA_PERF_SEL_image_nosampler_4to31_op_burst', + 207: 'TA_PERF_SEL_image_nosampler_ge32_op_burst', + 208: 'TA_PERF_SEL_buffer_flat_1_op_burst', + 209: 'TA_PERF_SEL_buffer_flat_2to3_op_burst', + 210: 'TA_PERF_SEL_buffer_flat_4to31_op_burst', + 211: 'TA_PERF_SEL_buffer_flat_ge32_op_burst', + 212: 'TA_PERF_SEL_write_1_op_burst', + 213: 'TA_PERF_SEL_write_2to3_op_burst', + 214: 'TA_PERF_SEL_write_4to31_op_burst', + 215: 'TA_PERF_SEL_write_ge32_op_burst', + 216: 'TA_PERF_SEL_ibubble_1_cycle_burst', + 217: 'TA_PERF_SEL_ibubble_2to3_cycle_burst', + 218: 'TA_PERF_SEL_ibubble_4to15_cycle_burst', + 219: 'TA_PERF_SEL_ibubble_16to31_cycle_burst', + 220: 'TA_PERF_SEL_ibubble_32to63_cycle_burst', + 221: 'TA_PERF_SEL_ibubble_ge64_cycle_burst', + 224: 'TA_PERF_SEL_sampler_clk_valid_cycles', + 225: 'TA_PERF_SEL_nonsampler_clk_valid_cycles', + 226: 'TA_PERF_SEL_buffer_flat_clk_valid_cycles', + 227: 'TA_PERF_SEL_write_data_clk_valid_cycles', + 228: 'TA_PERF_SEL_gradient_clk_valid_cycles', + 229: 'TA_PERF_SEL_lod_aniso_clk_valid_cycles', + 230: 'TA_PERF_SEL_sampler_addressing_clk_valid_cycles', + 231: 'TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles', + 232: 'TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles', + 233: 'TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles', + 234: 'TA_PERF_SEL_aligner_clk_valid_cycles', + 235: 'TA_PERF_SEL_tcreq_clk_valid_cycles', +} +TA_PERF_SEL_NULL = 0 +TA_PERF_SEL_image_sampler_has_offset_instructions = 1 +TA_PERF_SEL_image_sampler_has_bias_instructions = 2 +TA_PERF_SEL_image_sampler_has_reference_instructions = 3 +TA_PERF_SEL_image_sampler_has_ds_instructions = 4 +TA_PERF_SEL_image_sampler_has_dt_instructions = 5 +TA_PERF_SEL_image_sampler_has_dr_instructions = 6 +TA_PERF_SEL_gradient_busy = 7 +TA_PERF_SEL_gradient_fifo_busy = 8 +TA_PERF_SEL_lod_busy = 9 +TA_PERF_SEL_lod_fifo_busy = 10 +TA_PERF_SEL_addresser_busy = 11 +TA_PERF_SEL_addresser_fifo_busy = 12 +TA_PERF_SEL_aligner_busy = 13 +TA_PERF_SEL_write_path_busy = 14 +TA_PERF_SEL_ta_busy = 15 +TA_PERF_SEL_image_sampler_1_input_vgpr_instructions = 16 +TA_PERF_SEL_image_sampler_2_input_vgpr_instructions = 17 +TA_PERF_SEL_image_sampler_3_input_vgpr_instructions = 18 +TA_PERF_SEL_image_sampler_4_input_vgpr_instructions = 19 +TA_PERF_SEL_image_sampler_5_input_vgpr_instructions = 20 +TA_PERF_SEL_image_sampler_6_input_vgpr_instructions = 21 +TA_PERF_SEL_image_sampler_7_input_vgpr_instructions = 22 +TA_PERF_SEL_image_sampler_8_input_vgpr_instructions = 23 +TA_PERF_SEL_image_sampler_9_input_vgpr_instructions = 24 +TA_PERF_SEL_image_sampler_10_input_vgpr_instructions = 25 +TA_PERF_SEL_image_sampler_11_input_vgpr_instructions = 26 +TA_PERF_SEL_image_sampler_12_input_vgpr_instructions = 27 +TA_PERF_SEL_image_sampler_has_t_instructions = 28 +TA_PERF_SEL_image_sampler_has_r_instructions = 29 +TA_PERF_SEL_image_sampler_has_q_instructions = 30 +TA_PERF_SEL_total_wavefronts = 32 +TA_PERF_SEL_gradient_cycles = 33 +TA_PERF_SEL_walker_cycles = 34 +TA_PERF_SEL_aligner_cycles = 35 +TA_PERF_SEL_image_wavefronts = 36 +TA_PERF_SEL_image_read_wavefronts = 37 +TA_PERF_SEL_image_store_wavefronts = 38 +TA_PERF_SEL_image_atomic_wavefronts = 39 +TA_PERF_SEL_image_sampler_total_cycles = 40 +TA_PERF_SEL_image_nosampler_total_cycles = 41 +TA_PERF_SEL_flat_total_cycles = 42 +TA_PERF_SEL_buffer_wavefronts = 44 +TA_PERF_SEL_buffer_load_wavefronts = 45 +TA_PERF_SEL_buffer_store_wavefronts = 46 +TA_PERF_SEL_buffer_atomic_wavefronts = 47 +TA_PERF_SEL_buffer_total_cycles = 49 +TA_PERF_SEL_buffer_1_address_input_vgpr_instructions = 50 +TA_PERF_SEL_buffer_2_address_input_vgpr_instructions = 51 +TA_PERF_SEL_buffer_has_index_instructions = 52 +TA_PERF_SEL_buffer_has_offset_instructions = 53 +TA_PERF_SEL_addr_stalled_by_tc_cycles = 54 +TA_PERF_SEL_addr_stalled_by_td_cycles = 55 +TA_PERF_SEL_image_sampler_wavefronts = 56 +TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles = 57 +TA_PERF_SEL_addresser_stalled_cycles = 58 +TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles = 59 +TA_PERF_SEL_aniso_stalled_cycles = 60 +TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles = 61 +TA_PERF_SEL_deriv_stalled_cycles = 62 +TA_PERF_SEL_aniso_gt1_cycle_quads = 63 +TA_PERF_SEL_color_1_cycle_quads = 64 +TA_PERF_SEL_color_2_cycle_quads = 65 +TA_PERF_SEL_color_3_cycle_quads = 66 +TA_PERF_SEL_mip_1_cycle_quads = 68 +TA_PERF_SEL_mip_2_cycle_quads = 69 +TA_PERF_SEL_vol_1_cycle_quads = 70 +TA_PERF_SEL_vol_2_cycle_quads = 71 +TA_PERF_SEL_sampler_op_quads = 72 +TA_PERF_SEL_mipmap_lod_0_samples = 73 +TA_PERF_SEL_mipmap_lod_1_samples = 74 +TA_PERF_SEL_mipmap_lod_2_samples = 75 +TA_PERF_SEL_mipmap_lod_3_samples = 76 +TA_PERF_SEL_mipmap_lod_4_samples = 77 +TA_PERF_SEL_mipmap_lod_5_samples = 78 +TA_PERF_SEL_mipmap_lod_6_samples = 79 +TA_PERF_SEL_mipmap_lod_7_samples = 80 +TA_PERF_SEL_mipmap_lod_8_samples = 81 +TA_PERF_SEL_mipmap_lod_9_samples = 82 +TA_PERF_SEL_mipmap_lod_10_samples = 83 +TA_PERF_SEL_mipmap_lod_11_samples = 84 +TA_PERF_SEL_mipmap_lod_12_samples = 85 +TA_PERF_SEL_mipmap_lod_13_samples = 86 +TA_PERF_SEL_mipmap_lod_14_samples = 87 +TA_PERF_SEL_mipmap_invalid_samples = 88 +TA_PERF_SEL_aniso_1_cycle_quads = 89 +TA_PERF_SEL_aniso_2_cycle_quads = 90 +TA_PERF_SEL_aniso_4_cycle_quads = 91 +TA_PERF_SEL_aniso_6_cycle_quads = 92 +TA_PERF_SEL_aniso_8_cycle_quads = 93 +TA_PERF_SEL_aniso_10_cycle_quads = 94 +TA_PERF_SEL_aniso_12_cycle_quads = 95 +TA_PERF_SEL_aniso_14_cycle_quads = 96 +TA_PERF_SEL_aniso_16_cycle_quads = 97 +TA_PERF_SEL_store_write_data_input_cycles = 98 +TA_PERF_SEL_store_write_data_output_cycles = 99 +TA_PERF_SEL_flat_wavefronts = 100 +TA_PERF_SEL_flat_load_wavefronts = 101 +TA_PERF_SEL_flat_store_wavefronts = 102 +TA_PERF_SEL_flat_atomic_wavefronts = 103 +TA_PERF_SEL_flat_1_address_input_vgpr_instructions = 104 +TA_PERF_SEL_register_clk_valid_cycles = 105 +TA_PERF_SEL_non_harvestable_clk_enabled_cycles = 106 +TA_PERF_SEL_harvestable_clk_enabled_cycles = 107 +TA_PERF_SEL_flat_2_address_input_vgpr_instructions = 108 +TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles = 109 +TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles = 110 +TA_PERF_SEL_mipmap_lod_15_samples = 112 +TA_PERF_SEL_mipmap_lod_16_samples = 113 +TA_PERF_SEL_store_2_write_data_vgpr_instructions = 114 +TA_PERF_SEL_store_3_write_data_vgpr_instructions = 115 +TA_PERF_SEL_store_4_write_data_vgpr_instructions = 116 +TA_PERF_SEL_store_has_x_instructions = 117 +TA_PERF_SEL_store_has_y_instructions = 118 +TA_PERF_SEL_store_has_z_instructions = 119 +TA_PERF_SEL_store_has_w_instructions = 120 +TA_PERF_SEL_image_nosampler_has_t_instructions = 121 +TA_PERF_SEL_image_nosampler_has_r_instructions = 122 +TA_PERF_SEL_image_nosampler_has_q_instructions = 123 +TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions = 124 +TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions = 125 +TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions = 126 +TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions = 127 +TA_PERF_SEL_in_busy = 128 +TA_PERF_SEL_in_fifos_busy = 129 +TA_PERF_SEL_in_cfifo_busy = 130 +TA_PERF_SEL_in_qfifo_busy = 131 +TA_PERF_SEL_in_wfifo_busy = 132 +TA_PERF_SEL_in_rfifo_busy = 133 +TA_PERF_SEL_bf_busy = 134 +TA_PERF_SEL_ns_busy = 135 +TA_PERF_SEL_smp_busy_ns_idle = 136 +TA_PERF_SEL_smp_idle_ns_busy = 137 +TA_PERF_SEL_vmemcmd_cycles = 144 +TA_PERF_SEL_vmemreq_cycles = 145 +TA_PERF_SEL_in_waiting_on_req_cycles = 146 +TA_PERF_SEL_in_addr_cycles = 150 +TA_PERF_SEL_in_data_cycles = 151 +TA_PERF_SEL_point_sampled_quads = 160 +TA_PERF_SEL_atomic_2_write_data_vgpr_instructions = 162 +TA_PERF_SEL_atomic_4_write_data_vgpr_instructions = 163 +TA_PERF_SEL_atomic_write_data_input_cycles = 164 +TA_PERF_SEL_atomic_write_data_output_cycles = 165 +TA_PERF_SEL_num_unlit_nodes_ta_opt = 173 +TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input = 174 +TA_PERF_SEL_num_nodes_invalidated_due_to_oob = 175 +TA_PERF_SEL_image_sampler_1_op_burst = 192 +TA_PERF_SEL_image_sampler_2to3_op_burst = 193 +TA_PERF_SEL_image_sampler_4to7_op_burst = 194 +TA_PERF_SEL_image_sampler_ge8_op_burst = 195 +TA_PERF_SEL_image_linked_1_op_burst = 196 +TA_PERF_SEL_image_linked_2to3_op_burst = 197 +TA_PERF_SEL_image_linked_4to7_op_burst = 198 +TA_PERF_SEL_image_linked_ge8_op_burst = 199 +TA_PERF_SEL_image_nosampler_1_op_burst = 204 +TA_PERF_SEL_image_nosampler_2to3_op_burst = 205 +TA_PERF_SEL_image_nosampler_4to31_op_burst = 206 +TA_PERF_SEL_image_nosampler_ge32_op_burst = 207 +TA_PERF_SEL_buffer_flat_1_op_burst = 208 +TA_PERF_SEL_buffer_flat_2to3_op_burst = 209 +TA_PERF_SEL_buffer_flat_4to31_op_burst = 210 +TA_PERF_SEL_buffer_flat_ge32_op_burst = 211 +TA_PERF_SEL_write_1_op_burst = 212 +TA_PERF_SEL_write_2to3_op_burst = 213 +TA_PERF_SEL_write_4to31_op_burst = 214 +TA_PERF_SEL_write_ge32_op_burst = 215 +TA_PERF_SEL_ibubble_1_cycle_burst = 216 +TA_PERF_SEL_ibubble_2to3_cycle_burst = 217 +TA_PERF_SEL_ibubble_4to15_cycle_burst = 218 +TA_PERF_SEL_ibubble_16to31_cycle_burst = 219 +TA_PERF_SEL_ibubble_32to63_cycle_burst = 220 +TA_PERF_SEL_ibubble_ge64_cycle_burst = 221 +TA_PERF_SEL_sampler_clk_valid_cycles = 224 +TA_PERF_SEL_nonsampler_clk_valid_cycles = 225 +TA_PERF_SEL_buffer_flat_clk_valid_cycles = 226 +TA_PERF_SEL_write_data_clk_valid_cycles = 227 +TA_PERF_SEL_gradient_clk_valid_cycles = 228 +TA_PERF_SEL_lod_aniso_clk_valid_cycles = 229 +TA_PERF_SEL_sampler_addressing_clk_valid_cycles = 230 +TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles = 231 +TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles = 232 +TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles = 233 +TA_PERF_SEL_aligner_clk_valid_cycles = 234 +TA_PERF_SEL_tcreq_clk_valid_cycles = 235 +TA_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BC_SWIZZLE' +TEX_BC_SWIZZLE__enumvalues = { + 0: 'TEX_BC_Swizzle_XYZW', + 1: 'TEX_BC_Swizzle_XWYZ', + 2: 'TEX_BC_Swizzle_WZYX', + 3: 'TEX_BC_Swizzle_WXYZ', + 4: 'TEX_BC_Swizzle_ZYXW', + 5: 'TEX_BC_Swizzle_YXWZ', +} +TEX_BC_Swizzle_XYZW = 0 +TEX_BC_Swizzle_XWYZ = 1 +TEX_BC_Swizzle_WZYX = 2 +TEX_BC_Swizzle_WXYZ = 3 +TEX_BC_Swizzle_ZYXW = 4 +TEX_BC_Swizzle_YXWZ = 5 +TEX_BC_SWIZZLE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BORDER_COLOR_TYPE' +TEX_BORDER_COLOR_TYPE__enumvalues = { + 0: 'TEX_BorderColor_TransparentBlack', + 1: 'TEX_BorderColor_OpaqueBlack', + 2: 'TEX_BorderColor_OpaqueWhite', + 3: 'TEX_BorderColor_Register', +} +TEX_BorderColor_TransparentBlack = 0 +TEX_BorderColor_OpaqueBlack = 1 +TEX_BorderColor_OpaqueWhite = 2 +TEX_BorderColor_Register = 3 +TEX_BORDER_COLOR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CHROMA_KEY' +TEX_CHROMA_KEY__enumvalues = { + 0: 'TEX_ChromaKey_Disabled', + 1: 'TEX_ChromaKey_Kill', + 2: 'TEX_ChromaKey_Blend', + 3: 'TEX_ChromaKey_RESERVED_3', +} +TEX_ChromaKey_Disabled = 0 +TEX_ChromaKey_Kill = 1 +TEX_ChromaKey_Blend = 2 +TEX_ChromaKey_RESERVED_3 = 3 +TEX_CHROMA_KEY = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CLAMP' +TEX_CLAMP__enumvalues = { + 0: 'TEX_Clamp_Repeat', + 1: 'TEX_Clamp_Mirror', + 2: 'TEX_Clamp_ClampToLast', + 3: 'TEX_Clamp_MirrorOnceToLast', + 4: 'TEX_Clamp_ClampHalfToBorder', + 5: 'TEX_Clamp_MirrorOnceHalfToBorder', + 6: 'TEX_Clamp_ClampToBorder', + 7: 'TEX_Clamp_MirrorOnceToBorder', +} +TEX_Clamp_Repeat = 0 +TEX_Clamp_Mirror = 1 +TEX_Clamp_ClampToLast = 2 +TEX_Clamp_MirrorOnceToLast = 3 +TEX_Clamp_ClampHalfToBorder = 4 +TEX_Clamp_MirrorOnceHalfToBorder = 5 +TEX_Clamp_ClampToBorder = 6 +TEX_Clamp_MirrorOnceToBorder = 7 +TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_COORD_TYPE' +TEX_COORD_TYPE__enumvalues = { + 0: 'TEX_CoordType_Unnormalized', + 1: 'TEX_CoordType_Normalized', +} +TEX_CoordType_Unnormalized = 0 +TEX_CoordType_Normalized = 1 +TEX_COORD_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DEPTH_COMPARE_FUNCTION' +TEX_DEPTH_COMPARE_FUNCTION__enumvalues = { + 0: 'TEX_DepthCompareFunction_Never', + 1: 'TEX_DepthCompareFunction_Less', + 2: 'TEX_DepthCompareFunction_Equal', + 3: 'TEX_DepthCompareFunction_LessEqual', + 4: 'TEX_DepthCompareFunction_Greater', + 5: 'TEX_DepthCompareFunction_NotEqual', + 6: 'TEX_DepthCompareFunction_GreaterEqual', + 7: 'TEX_DepthCompareFunction_Always', +} +TEX_DepthCompareFunction_Never = 0 +TEX_DepthCompareFunction_Less = 1 +TEX_DepthCompareFunction_Equal = 2 +TEX_DepthCompareFunction_LessEqual = 3 +TEX_DepthCompareFunction_Greater = 4 +TEX_DepthCompareFunction_NotEqual = 5 +TEX_DepthCompareFunction_GreaterEqual = 6 +TEX_DepthCompareFunction_Always = 7 +TEX_DEPTH_COMPARE_FUNCTION = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_FORMAT_COMP' +TEX_FORMAT_COMP__enumvalues = { + 0: 'TEX_FormatComp_Unsigned', + 1: 'TEX_FormatComp_Signed', + 2: 'TEX_FormatComp_UnsignedBiased', + 3: 'TEX_FormatComp_RESERVED_3', +} +TEX_FormatComp_Unsigned = 0 +TEX_FormatComp_Signed = 1 +TEX_FormatComp_UnsignedBiased = 2 +TEX_FormatComp_RESERVED_3 = 3 +TEX_FORMAT_COMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MAX_ANISO_RATIO' +TEX_MAX_ANISO_RATIO__enumvalues = { + 0: 'TEX_MaxAnisoRatio_1to1', + 1: 'TEX_MaxAnisoRatio_2to1', + 2: 'TEX_MaxAnisoRatio_4to1', + 3: 'TEX_MaxAnisoRatio_8to1', + 4: 'TEX_MaxAnisoRatio_16to1', + 5: 'TEX_MaxAnisoRatio_RESERVED_5', + 6: 'TEX_MaxAnisoRatio_RESERVED_6', + 7: 'TEX_MaxAnisoRatio_RESERVED_7', +} +TEX_MaxAnisoRatio_1to1 = 0 +TEX_MaxAnisoRatio_2to1 = 1 +TEX_MaxAnisoRatio_4to1 = 2 +TEX_MaxAnisoRatio_8to1 = 3 +TEX_MaxAnisoRatio_16to1 = 4 +TEX_MaxAnisoRatio_RESERVED_5 = 5 +TEX_MaxAnisoRatio_RESERVED_6 = 6 +TEX_MaxAnisoRatio_RESERVED_7 = 7 +TEX_MAX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MIP_FILTER' +TEX_MIP_FILTER__enumvalues = { + 0: 'TEX_MipFilter_None', + 1: 'TEX_MipFilter_Point', + 2: 'TEX_MipFilter_Linear', + 3: 'TEX_MipFilter_Point_Aniso_Adj', +} +TEX_MipFilter_None = 0 +TEX_MipFilter_Point = 1 +TEX_MipFilter_Linear = 2 +TEX_MipFilter_Point_Aniso_Adj = 3 +TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_REQUEST_SIZE' +TEX_REQUEST_SIZE__enumvalues = { + 0: 'TEX_RequestSize_32B', + 1: 'TEX_RequestSize_64B', + 2: 'TEX_RequestSize_128B', + 3: 'TEX_RequestSize_2X64B', +} +TEX_RequestSize_32B = 0 +TEX_RequestSize_64B = 1 +TEX_RequestSize_128B = 2 +TEX_RequestSize_2X64B = 3 +TEX_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_SAMPLER_TYPE' +TEX_SAMPLER_TYPE__enumvalues = { + 0: 'TEX_SamplerType_Invalid', + 1: 'TEX_SamplerType_Valid', +} +TEX_SamplerType_Invalid = 0 +TEX_SamplerType_Valid = 1 +TEX_SAMPLER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_XY_FILTER' +TEX_XY_FILTER__enumvalues = { + 0: 'TEX_XYFilter_Point', + 1: 'TEX_XYFilter_Linear', + 2: 'TEX_XYFilter_AnisoPoint', + 3: 'TEX_XYFilter_AnisoLinear', +} +TEX_XYFilter_Point = 0 +TEX_XYFilter_Linear = 1 +TEX_XYFilter_AnisoPoint = 2 +TEX_XYFilter_AnisoLinear = 3 +TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_Z_FILTER' +TEX_Z_FILTER__enumvalues = { + 0: 'TEX_ZFilter_None', + 1: 'TEX_ZFilter_Point', + 2: 'TEX_ZFilter_Linear', + 3: 'TEX_ZFilter_RESERVED_3', +} +TEX_ZFilter_None = 0 +TEX_ZFilter_Point = 1 +TEX_ZFilter_Linear = 2 +TEX_ZFilter_RESERVED_3 = 3 +TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_TYPE' +TVX_TYPE__enumvalues = { + 0: 'TVX_Type_InvalidTextureResource', + 1: 'TVX_Type_InvalidVertexBuffer', + 2: 'TVX_Type_ValidTextureResource', + 3: 'TVX_Type_ValidVertexBuffer', +} +TVX_Type_InvalidTextureResource = 0 +TVX_Type_InvalidVertexBuffer = 1 +TVX_Type_ValidTextureResource = 2 +TVX_Type_ValidVertexBuffer = 3 +TVX_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_ADDR_MODES' +TA_TC_ADDR_MODES__enumvalues = { + 0: 'TA_TC_ADDR_MODE_DEFAULT', + 1: 'TA_TC_ADDR_MODE_COMP0', + 2: 'TA_TC_ADDR_MODE_COMP1', + 3: 'TA_TC_ADDR_MODE_COMP2', + 4: 'TA_TC_ADDR_MODE_COMP3', + 5: 'TA_TC_ADDR_MODE_UNALIGNED', + 6: 'TA_TC_ADDR_MODE_BORDER_COLOR', +} +TA_TC_ADDR_MODE_DEFAULT = 0 +TA_TC_ADDR_MODE_COMP0 = 1 +TA_TC_ADDR_MODE_COMP1 = 2 +TA_TC_ADDR_MODE_COMP2 = 3 +TA_TC_ADDR_MODE_COMP3 = 4 +TA_TC_ADDR_MODE_UNALIGNED = 5 +TA_TC_ADDR_MODE_BORDER_COLOR = 6 +TA_TC_ADDR_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_REQ_MODES' +TA_TC_REQ_MODES__enumvalues = { + 0: 'TA_TC_REQ_MODE_BORDER', + 1: 'TA_TC_REQ_MODE_TEX2', + 2: 'TA_TC_REQ_MODE_TEX1', + 3: 'TA_TC_REQ_MODE_TEX0', + 4: 'TA_TC_REQ_MODE_NORMAL', + 5: 'TA_TC_REQ_MODE_DWORD', + 6: 'TA_TC_REQ_MODE_BYTE', + 7: 'TA_TC_REQ_MODE_BYTE_NV', +} +TA_TC_REQ_MODE_BORDER = 0 +TA_TC_REQ_MODE_TEX2 = 1 +TA_TC_REQ_MODE_TEX1 = 2 +TA_TC_REQ_MODE_TEX0 = 3 +TA_TC_REQ_MODE_NORMAL = 4 +TA_TC_REQ_MODE_DWORD = 5 +TA_TC_REQ_MODE_BYTE = 6 +TA_TC_REQ_MODE_BYTE_NV = 7 +TA_TC_REQ_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_POLICIES' +TCP_CACHE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_POLICY_MISS_LRU', + 1: 'TCP_CACHE_POLICY_MISS_EVICT', + 2: 'TCP_CACHE_POLICY_HIT_LRU', + 3: 'TCP_CACHE_POLICY_HIT_EVICT', +} +TCP_CACHE_POLICY_MISS_LRU = 0 +TCP_CACHE_POLICY_MISS_EVICT = 1 +TCP_CACHE_POLICY_HIT_LRU = 2 +TCP_CACHE_POLICY_HIT_EVICT = 3 +TCP_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_STORE_POLICIES' +TCP_CACHE_STORE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_STORE_POLICY_WT_LRU', + 1: 'TCP_CACHE_STORE_POLICY_WT_EVICT', +} +TCP_CACHE_STORE_POLICY_WT_LRU = 0 +TCP_CACHE_STORE_POLICY_WT_EVICT = 1 +TCP_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_COMPRESSION_BYPASS' +TCP_COMPRESSION_BYPASS__enumvalues = { + 0: 'TCP_COMPRESSION_BYPASS_DIS', + 1: 'TCP_COMPRESSION_BYPASS_EN', +} +TCP_COMPRESSION_BYPASS_DIS = 0 +TCP_COMPRESSION_BYPASS_EN = 1 +TCP_COMPRESSION_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_COMPRESSION_OVERRIDE' +TCP_COMPRESSION_OVERRIDE__enumvalues = { + 0: 'TCP_COMPRESSION_OVERRIDE_DIS', + 1: 'TCP_COMPRESSION_OVERRIDE_EN', +} +TCP_COMPRESSION_OVERRIDE_DIS = 0 +TCP_COMPRESSION_OVERRIDE_EN = 1 +TCP_COMPRESSION_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_OPCODE_TYPE' +TCP_OPCODE_TYPE__enumvalues = { + 0: 'TCP_OPCODE_READ', + 1: 'TCP_OPCODE_WRITE', + 2: 'TCP_OPCODE_ATOMIC', + 3: 'TCP_OPCODE_INV', + 4: 'TCP_OPCODE_ATOMIC_CMPSWAP', + 5: 'TCP_OPCODE_SAMPLER', + 6: 'TCP_OPCODE_LOAD', + 7: 'TCP_OPCODE_GATHERH', +} +TCP_OPCODE_READ = 0 +TCP_OPCODE_WRITE = 1 +TCP_OPCODE_ATOMIC = 2 +TCP_OPCODE_INV = 3 +TCP_OPCODE_ATOMIC_CMPSWAP = 4 +TCP_OPCODE_SAMPLER = 5 +TCP_OPCODE_LOAD = 6 +TCP_OPCODE_GATHERH = 7 +TCP_OPCODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_PERFCOUNT_SELECT' +TCP_PERFCOUNT_SELECT__enumvalues = { + 0: 'TCP_PERF_SEL_GATE_EN1', + 1: 'TCP_PERF_SEL_GATE_EN2', + 2: 'TCP_PERF_SEL_TA_REQ', + 3: 'TCP_PERF_SEL_TA_REQ_STATE_READ', + 4: 'TCP_PERF_SEL_TA_REQ_READ', + 5: 'TCP_PERF_SEL_TA_REQ_WRITE', + 6: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', + 7: 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 8: 'TCP_PERF_SEL_TA_REQ_GL0_INV', + 9: 'TCP_PERF_SEL_REQ', + 10: 'TCP_PERF_SEL_REQ_READ', + 12: 'TCP_PERF_SEL_REQ_READ_HIT_LRU', + 13: 'TCP_PERF_SEL_REQ_READ_MISS_EVICT', + 14: 'TCP_PERF_SEL_REQ_WRITE', + 15: 'TCP_PERF_SEL_REQ_WRITE_MISS_EVICT', + 16: 'TCP_PERF_SEL_REQ_NON_READ', + 17: 'TCP_PERF_SEL_REQ_MISS', + 18: 'TCP_PERF_SEL_REQ_TAGBANK0_SET0', + 19: 'TCP_PERF_SEL_REQ_TAGBANK0_SET1', + 20: 'TCP_PERF_SEL_REQ_TAGBANK1_SET0', + 21: 'TCP_PERF_SEL_REQ_TAGBANK1_SET1', + 22: 'TCP_PERF_SEL_REQ_TAGBANK2_SET0', + 23: 'TCP_PERF_SEL_REQ_TAGBANK2_SET1', + 24: 'TCP_PERF_SEL_REQ_TAGBANK3_SET0', + 25: 'TCP_PERF_SEL_REQ_TAGBANK3_SET1', + 26: 'TCP_PERF_SEL_REQ_MISS_TAGBANK0', + 27: 'TCP_PERF_SEL_REQ_MISS_TAGBANK1', + 28: 'TCP_PERF_SEL_REQ_MISS_TAGBANK2', + 29: 'TCP_PERF_SEL_REQ_MISS_TAGBANK3', + 30: 'TCP_PERF_SEL_GL1_REQ_READ', + 31: 'TCP_PERF_SEL_GL1_REQ_READ_128B', + 32: 'TCP_PERF_SEL_GL1_REQ_READ_64B', + 33: 'TCP_PERF_SEL_GL1_REQ_WRITE', + 34: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', + 35: 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 36: 'TCP_PERF_SEL_GL1_READ_LATENCY', + 37: 'TCP_PERF_SEL_GL1_WRITE_LATENCY', + 38: 'TCP_PERF_SEL_TCP_LATENCY', + 39: 'TCP_PERF_SEL_TCP_TA_REQ_STALL', + 40: 'TCP_PERF_SEL_TA_TCP_REQ_STARVE', + 41: 'TCP_PERF_SEL_DATA_FIFO_STALL', + 42: 'TCP_PERF_SEL_LOD_STALL', + 43: 'TCP_PERF_SEL_POWER_STALL', + 44: 'TCP_PERF_SEL_ALLOC_STALL', + 46: 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL', + 47: 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL', + 48: 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL', + 49: 'TCP_PERF_SEL_LFIFO_STALL', + 50: 'TCP_PERF_SEL_MEM_REQ_FIFO_STALL', + 51: 'TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE', + 52: 'TCP_PERF_SEL_GL1_TCP_RDRET_STALL', + 53: 'TCP_PERF_SEL_GL1_GRANT_READ_STALL', + 54: 'TCP_PERF_SEL_GL1_PENDING_STALL', + 55: 'TCP_PERF_SEL_TD_DATA_CYCLE_STALL', + 56: 'TCP_PERF_SEL_COMP_TEX_LOAD_STALL', + 57: 'TCP_PERF_SEL_READ_DATACONFLICT_STALL', + 58: 'TCP_PERF_SEL_WRITE_DATACONFLICT_STALL', + 59: 'TCP_PERF_SEL_TD_TCP_STALL', + 60: 'TCP_PERF_SEL_TA_REQ_BUFFERNOP', + 61: 'TCP_PERF_SEL_WRITECOMBINE_ENDCLAUSE', + 62: 'TCP_PERF_SEL_TAGFAKE_EOW', + 63: 'TCP_PERF_SEL_REQ_TAG_MATCH_AND_NOT_VALID', + 64: 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_0', + 65: 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_1to2', + 66: 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_3to4', + 67: 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_5to8', + 68: 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_9to16', + 70: 'TCP_PERF_SEL_BURST_BIN_READHIT_0', + 71: 'TCP_PERF_SEL_BURST_BIN_READHIT_1', + 72: 'TCP_PERF_SEL_BURST_BIN_READHIT_2to4', + 73: 'TCP_PERF_SEL_BURST_BIN_READHIT_5to8', + 74: 'TCP_PERF_SEL_BURST_BIN_READHIT_9to16', + 75: 'TCP_PERF_SEL_BURST_BIN_READHIT_gt16', + 76: 'TCP_PERF_SEL_TA_TC_REQ_EN_SUM', + 77: 'TCP_PERF_SEL_GL1_REQ_LU', + 78: 'TCP_PERF_SEL_REQ_TAG_MATCH_AND_LU_INVALIDATE', +} +TCP_PERF_SEL_GATE_EN1 = 0 +TCP_PERF_SEL_GATE_EN2 = 1 +TCP_PERF_SEL_TA_REQ = 2 +TCP_PERF_SEL_TA_REQ_STATE_READ = 3 +TCP_PERF_SEL_TA_REQ_READ = 4 +TCP_PERF_SEL_TA_REQ_WRITE = 5 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET = 6 +TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET = 7 +TCP_PERF_SEL_TA_REQ_GL0_INV = 8 +TCP_PERF_SEL_REQ = 9 +TCP_PERF_SEL_REQ_READ = 10 +TCP_PERF_SEL_REQ_READ_HIT_LRU = 12 +TCP_PERF_SEL_REQ_READ_MISS_EVICT = 13 +TCP_PERF_SEL_REQ_WRITE = 14 +TCP_PERF_SEL_REQ_WRITE_MISS_EVICT = 15 +TCP_PERF_SEL_REQ_NON_READ = 16 +TCP_PERF_SEL_REQ_MISS = 17 +TCP_PERF_SEL_REQ_TAGBANK0_SET0 = 18 +TCP_PERF_SEL_REQ_TAGBANK0_SET1 = 19 +TCP_PERF_SEL_REQ_TAGBANK1_SET0 = 20 +TCP_PERF_SEL_REQ_TAGBANK1_SET1 = 21 +TCP_PERF_SEL_REQ_TAGBANK2_SET0 = 22 +TCP_PERF_SEL_REQ_TAGBANK2_SET1 = 23 +TCP_PERF_SEL_REQ_TAGBANK3_SET0 = 24 +TCP_PERF_SEL_REQ_TAGBANK3_SET1 = 25 +TCP_PERF_SEL_REQ_MISS_TAGBANK0 = 26 +TCP_PERF_SEL_REQ_MISS_TAGBANK1 = 27 +TCP_PERF_SEL_REQ_MISS_TAGBANK2 = 28 +TCP_PERF_SEL_REQ_MISS_TAGBANK3 = 29 +TCP_PERF_SEL_GL1_REQ_READ = 30 +TCP_PERF_SEL_GL1_REQ_READ_128B = 31 +TCP_PERF_SEL_GL1_REQ_READ_64B = 32 +TCP_PERF_SEL_GL1_REQ_WRITE = 33 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET = 34 +TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET = 35 +TCP_PERF_SEL_GL1_READ_LATENCY = 36 +TCP_PERF_SEL_GL1_WRITE_LATENCY = 37 +TCP_PERF_SEL_TCP_LATENCY = 38 +TCP_PERF_SEL_TCP_TA_REQ_STALL = 39 +TCP_PERF_SEL_TA_TCP_REQ_STARVE = 40 +TCP_PERF_SEL_DATA_FIFO_STALL = 41 +TCP_PERF_SEL_LOD_STALL = 42 +TCP_PERF_SEL_POWER_STALL = 43 +TCP_PERF_SEL_ALLOC_STALL = 44 +TCP_PERF_SEL_READ_TAGCONFLICT_STALL = 46 +TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL = 47 +TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL = 48 +TCP_PERF_SEL_LFIFO_STALL = 49 +TCP_PERF_SEL_MEM_REQ_FIFO_STALL = 50 +TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE = 51 +TCP_PERF_SEL_GL1_TCP_RDRET_STALL = 52 +TCP_PERF_SEL_GL1_GRANT_READ_STALL = 53 +TCP_PERF_SEL_GL1_PENDING_STALL = 54 +TCP_PERF_SEL_TD_DATA_CYCLE_STALL = 55 +TCP_PERF_SEL_COMP_TEX_LOAD_STALL = 56 +TCP_PERF_SEL_READ_DATACONFLICT_STALL = 57 +TCP_PERF_SEL_WRITE_DATACONFLICT_STALL = 58 +TCP_PERF_SEL_TD_TCP_STALL = 59 +TCP_PERF_SEL_TA_REQ_BUFFERNOP = 60 +TCP_PERF_SEL_WRITECOMBINE_ENDCLAUSE = 61 +TCP_PERF_SEL_TAGFAKE_EOW = 62 +TCP_PERF_SEL_REQ_TAG_MATCH_AND_NOT_VALID = 63 +TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_0 = 64 +TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_1to2 = 65 +TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_3to4 = 66 +TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_5to8 = 67 +TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_9to16 = 68 +TCP_PERF_SEL_BURST_BIN_READHIT_0 = 70 +TCP_PERF_SEL_BURST_BIN_READHIT_1 = 71 +TCP_PERF_SEL_BURST_BIN_READHIT_2to4 = 72 +TCP_PERF_SEL_BURST_BIN_READHIT_5to8 = 73 +TCP_PERF_SEL_BURST_BIN_READHIT_9to16 = 74 +TCP_PERF_SEL_BURST_BIN_READHIT_gt16 = 75 +TCP_PERF_SEL_TA_TC_REQ_EN_SUM = 76 +TCP_PERF_SEL_GL1_REQ_LU = 77 +TCP_PERF_SEL_REQ_TAG_MATCH_AND_LU_INVALIDATE = 78 +TCP_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_WATCH_MODES' +TCP_WATCH_MODES__enumvalues = { + 0: 'TCP_WATCH_MODE_READ', + 1: 'TCP_WATCH_MODE_NONREAD', + 2: 'TCP_WATCH_MODE_ATOMIC', + 3: 'TCP_WATCH_MODE_ALL', +} +TCP_WATCH_MODE_READ = 0 +TCP_WATCH_MODE_NONREAD = 1 +TCP_WATCH_MODE_ATOMIC = 2 +TCP_WATCH_MODE_ALL = 3 +TCP_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_WRITE_COMPRESSION_DISABLE' +TCP_WRITE_COMPRESSION_DISABLE__enumvalues = { + 0: 'TCP_WRITE_COMPRESSION_DISABLE_DIS', + 1: 'TCP_WRITE_COMPRESSION_DISABLE_EN', +} +TCP_WRITE_COMPRESSION_DISABLE_DIS = 0 +TCP_WRITE_COMPRESSION_DISABLE_EN = 1 +TCP_WRITE_COMPRESSION_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'TD_PERFCOUNT_SEL' +TD_PERFCOUNT_SEL__enumvalues = { + 0: 'TD_PERF_SEL_none', + 1: 'TD_PERF_SEL_td_busy', + 2: 'TD_PERF_SEL_input_busy', + 3: 'TD_PERF_SEL_sampler_lerp_busy', + 4: 'TD_PERF_SEL_sampler_out_busy', + 5: 'TD_PERF_SEL_nofilter_busy', + 7: 'TD_PERF_SEL_sampler_core_sclk_en', + 8: 'TD_PERF_SEL_sampler_preformatter_sclk_en', + 9: 'TD_PERF_SEL_sampler_bilerp_sclk_en', + 10: 'TD_PERF_SEL_sampler_bypass_sclk_en', + 11: 'TD_PERF_SEL_sampler_minmax_sclk_en', + 12: 'TD_PERF_SEL_sampler_accum_sclk_en', + 13: 'TD_PERF_SEL_sampler_format_flt_sclk_en', + 14: 'TD_PERF_SEL_sampler_format_fxdpt_sclk_en', + 15: 'TD_PERF_SEL_sampler_out_sclk_en', + 16: 'TD_PERF_SEL_nofilter_sclk_en', + 17: 'TD_PERF_SEL_nofilter_d32_sclk_en', + 18: 'TD_PERF_SEL_nofilter_d16_sclk_en', + 26: 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 27: 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 28: 'TD_PERF_SEL_all_pipes_sclk_on_at_same_time', + 32: 'TD_PERF_SEL_core_state_ram_max_cnt', + 33: 'TD_PERF_SEL_core_state_rams_read', + 34: 'TD_PERF_SEL_weight_data_rams_read', + 35: 'TD_PERF_SEL_reference_data_rams_read', + 36: 'TD_PERF_SEL_tc_td_ram_fifo_full', + 37: 'TD_PERF_SEL_tc_td_ram_fifo_max_cnt', + 38: 'TD_PERF_SEL_tc_td_data_fifo_full', + 39: 'TD_PERF_SEL_input_state_fifo_full', + 40: 'TD_PERF_SEL_ta_data_stall', + 41: 'TD_PERF_SEL_tc_data_stall', + 42: 'TD_PERF_SEL_tc_ram_stall', + 43: 'TD_PERF_SEL_lds_stall', + 44: 'TD_PERF_SEL_sampler_pkr_full', + 45: 'TD_PERF_SEL_sampler_pkr_full_due_to_arb', + 46: 'TD_PERF_SEL_nofilter_pkr_full', + 47: 'TD_PERF_SEL_nofilter_pkr_full_due_to_arb', + 50: 'TD_PERF_SEL_gather4_instr', + 51: 'TD_PERF_SEL_gather4h_instr', + 52: 'TD_PERF_SEL_getlod_instr', + 54: 'TD_PERF_SEL_sample_instr', + 55: 'TD_PERF_SEL_sample_c_instr', + 56: 'TD_PERF_SEL_load_instr', + 57: 'TD_PERF_SEL_ps_load_instr', + 58: 'TD_PERF_SEL_write_ack_instr', + 59: 'TD_PERF_SEL_d16_en_instr', + 60: 'TD_PERF_SEL_bypassLerp_instr', + 61: 'TD_PERF_SEL_min_max_filter_instr', + 62: 'TD_PERF_SEL_one_comp_return_instr', + 63: 'TD_PERF_SEL_two_comp_return_instr', + 64: 'TD_PERF_SEL_three_comp_return_instr', + 65: 'TD_PERF_SEL_four_comp_return_instr', + 66: 'TD_PERF_SEL_user_defined_border', + 67: 'TD_PERF_SEL_white_border', + 68: 'TD_PERF_SEL_opaque_black_border', + 69: 'TD_PERF_SEL_lod_warn_from_ta', + 70: 'TD_PERF_SEL_instruction_dest_is_lds', + 71: 'TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles', + 72: 'TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles', + 73: 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles', + 74: 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles', + 75: 'TD_PERF_SEL_out_of_order_instr', + 76: 'TD_PERF_SEL_total_num_instr', + 77: 'TD_PERF_SEL_total_num_instr_with_perf_wdw', + 78: 'TD_PERF_SEL_total_num_sampler_instr', + 79: 'TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw', + 80: 'TD_PERF_SEL_total_num_nofilter_instr', + 81: 'TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw', + 84: 'TD_PERF_SEL_mixmode_instr', + 85: 'TD_PERF_SEL_mixmode_resource', + 86: 'TD_PERF_SEL_status_packet', + 89: 'TD_PERF_SEL_done_scoreboard_max_stored_cnt', + 90: 'TD_PERF_SEL_done_scoreboard_max_waiting_cnt', + 91: 'TD_PERF_SEL_done_scoreboard_not_empty', + 92: 'TD_PERF_SEL_done_scoreboard_is_full', + 93: 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 94: 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 95: 'TD_PERF_SEL_nofilter_formatters_turned_on', + 96: 'TD_PERF_SEL_nofilter_insert_extra_comps', + 97: 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 98: 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', + 99: 'TD_PERF_SEL_msaa_load_instr', + 100: 'TD_PERF_SEL_blend_prt_with_prt_default_0', + 102: 'TD_PERF_SEL_resmap_instr', + 103: 'TD_PERF_SEL_prt_ack_instr', + 104: 'TD_PERF_SEL_resmap_with_volume_filtering', + 105: 'TD_PERF_SEL_resmap_with_aniso_filtering', + 106: 'TD_PERF_SEL_resmap_with_no_more_filtering', + 107: 'TD_PERF_SEL_resmap_with_cubemap_corner', + 131: 'TD_PERF_SEL_burst_bin_preempting_nofilter_1', + 132: 'TD_PERF_SEL_burst_bin_preempting_nofilter_2to4', + 133: 'TD_PERF_SEL_burst_bin_preempting_nofilter_5to7', + 134: 'TD_PERF_SEL_burst_bin_preempting_nofilter_8to16', + 135: 'TD_PERF_SEL_burst_bin_preempting_nofilter_gt16', + 136: 'TD_PERF_SEL_burst_bin_sampler_1', + 137: 'TD_PERF_SEL_burst_bin_sampler_2to8', + 138: 'TD_PERF_SEL_burst_bin_sampler_9to16', + 139: 'TD_PERF_SEL_burst_bin_sampler_gt16', + 140: 'TD_PERF_SEL_burst_bin_gather_1', + 141: 'TD_PERF_SEL_burst_bin_gather_2to8', + 142: 'TD_PERF_SEL_burst_bin_gather_9to16', + 143: 'TD_PERF_SEL_burst_bin_gather_gt16', + 144: 'TD_PERF_SEL_burst_bin_nofilter_1', + 145: 'TD_PERF_SEL_burst_bin_nofilter_2to4', + 146: 'TD_PERF_SEL_burst_bin_nofilter_5to7', + 147: 'TD_PERF_SEL_burst_bin_nofilter_8to16', + 148: 'TD_PERF_SEL_burst_bin_nofilter_gt16', + 170: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0', + 171: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1', + 172: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31', + 173: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127', + 174: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511', + 175: 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511', + 176: 'TD_PERF_SEL_bubble_bin_lds_stall_1to3', + 177: 'TD_PERF_SEL_bubble_bin_lds_stall_4to7', + 178: 'TD_PERF_SEL_bubble_bin_lds_stall_8to15', + 179: 'TD_PERF_SEL_bubble_bin_lds_stall_gt15', + 180: 'TD_PERF_SEL_preempting_nofilter_max_cnt', + 181: 'TD_PERF_SEL_sampler_lerp0_active', + 182: 'TD_PERF_SEL_sampler_lerp1_active', + 183: 'TD_PERF_SEL_sampler_lerp2_active', + 184: 'TD_PERF_SEL_sampler_lerp3_active', + 185: 'TD_PERF_SEL_sampler_lerp4_active', + 186: 'TD_PERF_SEL_sampler_lerp5_active', + 187: 'TD_PERF_SEL_sampler_lerp6_active', + 188: 'TD_PERF_SEL_sampler_lerp7_active', + 189: 'TD_PERF_SEL_nofilter_total_num_comps_to_lds', + 190: 'TD_PERF_SEL_nofilter_byte_cycling_4cycles', + 191: 'TD_PERF_SEL_nofilter_byte_cycling_8cycles', + 192: 'TD_PERF_SEL_nofilter_byte_cycling_16cycles', + 193: 'TD_PERF_SEL_nofilter_dword_cycling_2cycles', + 194: 'TD_PERF_SEL_nofilter_dword_cycling_4cycles', + 195: 'TD_PERF_SEL_input_bp_due_to_done_scoreboard_full', + 200: 'TD_PERF_SEL_store_preempts_a_load', + 201: 'TD_PERF_SEL_sample_2x_instr', + 202: 'TD_PERF_SEL_gather4_2x_instr', + 203: 'TD_PERF_SEL_gather4h_2x_instr', + 204: 'TD_PERF_SEL_getlod_2x_instr', + 205: 'TD_PERF_SEL_resmap_2x_instr', + 206: 'TD_PERF_SEL_2x_sampler_op_with_1_unlit_quad', + 207: 'TD_PERF_SEL_2x_sampler_op_with_both_quads_unlit', + 208: 'TD_PERF_SEL_tri_proc_node_override_slot0', + 209: 'TD_PERF_SEL_tri_run_intersect_ahs_slot0', + 210: 'TD_PERF_SEL_tri_run_ahs_slot0', + 231: 'TD_PERF_SEL_tri_proc_node_override_slot1', + 232: 'TD_PERF_SEL_tri_run_intersect_ahs_slot1', + 233: 'TD_PERF_SEL_tri_run_ahs_slot1', + 241: 'TD_PERF_SEL_instance_mask_culled', + 242: 'TD_PERF_SEL_box_opaque_culled', + 243: 'TD_PERF_SEL_box_non_opaque_culled', + 244: 'TD_PERF_SEL_box_with_triangle_children_only_culled', + 245: 'TD_PERF_SEL_box_with_procedural_children_only_culled', + 246: 'TD_PERF_SEL_triangle_opaque_culled', + 247: 'TD_PERF_SEL_triangle_non_opaque_culled', + 248: 'TD_PERF_SEL_triangle_front_facing_culled', + 249: 'TD_PERF_SEL_triangle_back_facing_culled', +} +TD_PERF_SEL_none = 0 +TD_PERF_SEL_td_busy = 1 +TD_PERF_SEL_input_busy = 2 +TD_PERF_SEL_sampler_lerp_busy = 3 +TD_PERF_SEL_sampler_out_busy = 4 +TD_PERF_SEL_nofilter_busy = 5 +TD_PERF_SEL_sampler_core_sclk_en = 7 +TD_PERF_SEL_sampler_preformatter_sclk_en = 8 +TD_PERF_SEL_sampler_bilerp_sclk_en = 9 +TD_PERF_SEL_sampler_bypass_sclk_en = 10 +TD_PERF_SEL_sampler_minmax_sclk_en = 11 +TD_PERF_SEL_sampler_accum_sclk_en = 12 +TD_PERF_SEL_sampler_format_flt_sclk_en = 13 +TD_PERF_SEL_sampler_format_fxdpt_sclk_en = 14 +TD_PERF_SEL_sampler_out_sclk_en = 15 +TD_PERF_SEL_nofilter_sclk_en = 16 +TD_PERF_SEL_nofilter_d32_sclk_en = 17 +TD_PERF_SEL_nofilter_d16_sclk_en = 18 +TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off = 26 +TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off = 27 +TD_PERF_SEL_all_pipes_sclk_on_at_same_time = 28 +TD_PERF_SEL_core_state_ram_max_cnt = 32 +TD_PERF_SEL_core_state_rams_read = 33 +TD_PERF_SEL_weight_data_rams_read = 34 +TD_PERF_SEL_reference_data_rams_read = 35 +TD_PERF_SEL_tc_td_ram_fifo_full = 36 +TD_PERF_SEL_tc_td_ram_fifo_max_cnt = 37 +TD_PERF_SEL_tc_td_data_fifo_full = 38 +TD_PERF_SEL_input_state_fifo_full = 39 +TD_PERF_SEL_ta_data_stall = 40 +TD_PERF_SEL_tc_data_stall = 41 +TD_PERF_SEL_tc_ram_stall = 42 +TD_PERF_SEL_lds_stall = 43 +TD_PERF_SEL_sampler_pkr_full = 44 +TD_PERF_SEL_sampler_pkr_full_due_to_arb = 45 +TD_PERF_SEL_nofilter_pkr_full = 46 +TD_PERF_SEL_nofilter_pkr_full_due_to_arb = 47 +TD_PERF_SEL_gather4_instr = 50 +TD_PERF_SEL_gather4h_instr = 51 +TD_PERF_SEL_getlod_instr = 52 +TD_PERF_SEL_sample_instr = 54 +TD_PERF_SEL_sample_c_instr = 55 +TD_PERF_SEL_load_instr = 56 +TD_PERF_SEL_ps_load_instr = 57 +TD_PERF_SEL_write_ack_instr = 58 +TD_PERF_SEL_d16_en_instr = 59 +TD_PERF_SEL_bypassLerp_instr = 60 +TD_PERF_SEL_min_max_filter_instr = 61 +TD_PERF_SEL_one_comp_return_instr = 62 +TD_PERF_SEL_two_comp_return_instr = 63 +TD_PERF_SEL_three_comp_return_instr = 64 +TD_PERF_SEL_four_comp_return_instr = 65 +TD_PERF_SEL_user_defined_border = 66 +TD_PERF_SEL_white_border = 67 +TD_PERF_SEL_opaque_black_border = 68 +TD_PERF_SEL_lod_warn_from_ta = 69 +TD_PERF_SEL_instruction_dest_is_lds = 70 +TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles = 71 +TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles = 72 +TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles = 73 +TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles = 74 +TD_PERF_SEL_out_of_order_instr = 75 +TD_PERF_SEL_total_num_instr = 76 +TD_PERF_SEL_total_num_instr_with_perf_wdw = 77 +TD_PERF_SEL_total_num_sampler_instr = 78 +TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw = 79 +TD_PERF_SEL_total_num_nofilter_instr = 80 +TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw = 81 +TD_PERF_SEL_mixmode_instr = 84 +TD_PERF_SEL_mixmode_resource = 85 +TD_PERF_SEL_status_packet = 86 +TD_PERF_SEL_done_scoreboard_max_stored_cnt = 89 +TD_PERF_SEL_done_scoreboard_max_waiting_cnt = 90 +TD_PERF_SEL_done_scoreboard_not_empty = 91 +TD_PERF_SEL_done_scoreboard_is_full = 92 +TD_PERF_SEL_done_scoreboard_bp_due_to_ooo = 93 +TD_PERF_SEL_done_scoreboard_bp_due_to_lds = 94 +TD_PERF_SEL_nofilter_formatters_turned_on = 95 +TD_PERF_SEL_nofilter_insert_extra_comps = 96 +TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt = 97 +TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt = 98 +TD_PERF_SEL_msaa_load_instr = 99 +TD_PERF_SEL_blend_prt_with_prt_default_0 = 100 +TD_PERF_SEL_resmap_instr = 102 +TD_PERF_SEL_prt_ack_instr = 103 +TD_PERF_SEL_resmap_with_volume_filtering = 104 +TD_PERF_SEL_resmap_with_aniso_filtering = 105 +TD_PERF_SEL_resmap_with_no_more_filtering = 106 +TD_PERF_SEL_resmap_with_cubemap_corner = 107 +TD_PERF_SEL_burst_bin_preempting_nofilter_1 = 131 +TD_PERF_SEL_burst_bin_preempting_nofilter_2to4 = 132 +TD_PERF_SEL_burst_bin_preempting_nofilter_5to7 = 133 +TD_PERF_SEL_burst_bin_preempting_nofilter_8to16 = 134 +TD_PERF_SEL_burst_bin_preempting_nofilter_gt16 = 135 +TD_PERF_SEL_burst_bin_sampler_1 = 136 +TD_PERF_SEL_burst_bin_sampler_2to8 = 137 +TD_PERF_SEL_burst_bin_sampler_9to16 = 138 +TD_PERF_SEL_burst_bin_sampler_gt16 = 139 +TD_PERF_SEL_burst_bin_gather_1 = 140 +TD_PERF_SEL_burst_bin_gather_2to8 = 141 +TD_PERF_SEL_burst_bin_gather_9to16 = 142 +TD_PERF_SEL_burst_bin_gather_gt16 = 143 +TD_PERF_SEL_burst_bin_nofilter_1 = 144 +TD_PERF_SEL_burst_bin_nofilter_2to4 = 145 +TD_PERF_SEL_burst_bin_nofilter_5to7 = 146 +TD_PERF_SEL_burst_bin_nofilter_8to16 = 147 +TD_PERF_SEL_burst_bin_nofilter_gt16 = 148 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0 = 170 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1 = 171 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31 = 172 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127 = 173 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511 = 174 +TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511 = 175 +TD_PERF_SEL_bubble_bin_lds_stall_1to3 = 176 +TD_PERF_SEL_bubble_bin_lds_stall_4to7 = 177 +TD_PERF_SEL_bubble_bin_lds_stall_8to15 = 178 +TD_PERF_SEL_bubble_bin_lds_stall_gt15 = 179 +TD_PERF_SEL_preempting_nofilter_max_cnt = 180 +TD_PERF_SEL_sampler_lerp0_active = 181 +TD_PERF_SEL_sampler_lerp1_active = 182 +TD_PERF_SEL_sampler_lerp2_active = 183 +TD_PERF_SEL_sampler_lerp3_active = 184 +TD_PERF_SEL_sampler_lerp4_active = 185 +TD_PERF_SEL_sampler_lerp5_active = 186 +TD_PERF_SEL_sampler_lerp6_active = 187 +TD_PERF_SEL_sampler_lerp7_active = 188 +TD_PERF_SEL_nofilter_total_num_comps_to_lds = 189 +TD_PERF_SEL_nofilter_byte_cycling_4cycles = 190 +TD_PERF_SEL_nofilter_byte_cycling_8cycles = 191 +TD_PERF_SEL_nofilter_byte_cycling_16cycles = 192 +TD_PERF_SEL_nofilter_dword_cycling_2cycles = 193 +TD_PERF_SEL_nofilter_dword_cycling_4cycles = 194 +TD_PERF_SEL_input_bp_due_to_done_scoreboard_full = 195 +TD_PERF_SEL_store_preempts_a_load = 200 +TD_PERF_SEL_sample_2x_instr = 201 +TD_PERF_SEL_gather4_2x_instr = 202 +TD_PERF_SEL_gather4h_2x_instr = 203 +TD_PERF_SEL_getlod_2x_instr = 204 +TD_PERF_SEL_resmap_2x_instr = 205 +TD_PERF_SEL_2x_sampler_op_with_1_unlit_quad = 206 +TD_PERF_SEL_2x_sampler_op_with_both_quads_unlit = 207 +TD_PERF_SEL_tri_proc_node_override_slot0 = 208 +TD_PERF_SEL_tri_run_intersect_ahs_slot0 = 209 +TD_PERF_SEL_tri_run_ahs_slot0 = 210 +TD_PERF_SEL_tri_proc_node_override_slot1 = 231 +TD_PERF_SEL_tri_run_intersect_ahs_slot1 = 232 +TD_PERF_SEL_tri_run_ahs_slot1 = 233 +TD_PERF_SEL_instance_mask_culled = 241 +TD_PERF_SEL_box_opaque_culled = 242 +TD_PERF_SEL_box_non_opaque_culled = 243 +TD_PERF_SEL_box_with_triangle_children_only_culled = 244 +TD_PERF_SEL_box_with_procedural_children_only_culled = 245 +TD_PERF_SEL_triangle_opaque_culled = 246 +TD_PERF_SEL_triangle_non_opaque_culled = 247 +TD_PERF_SEL_triangle_front_facing_culled = 248 +TD_PERF_SEL_triangle_back_facing_culled = 249 +TD_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL2A_PERF_SEL' +GL2A_PERF_SEL__enumvalues = { + 0: 'GL2A_PERF_SEL_NONE', + 1: 'GL2A_PERF_SEL_CYCLE', + 2: 'GL2A_PERF_SEL_BUSY', + 3: 'GL2A_PERF_SEL_REQ_GL2C0', + 4: 'GL2A_PERF_SEL_REQ_GL2C1', + 5: 'GL2A_PERF_SEL_REQ_GL2C2', + 6: 'GL2A_PERF_SEL_REQ_GL2C3', + 7: 'GL2A_PERF_SEL_REQ_GL2C4', + 8: 'GL2A_PERF_SEL_REQ_GL2C5', + 9: 'GL2A_PERF_SEL_REQ_GL2C6', + 10: 'GL2A_PERF_SEL_REQ_GL2C7', + 19: 'GL2A_PERF_SEL_REQ_BURST_GL2C0', + 20: 'GL2A_PERF_SEL_REQ_BURST_GL2C1', + 21: 'GL2A_PERF_SEL_REQ_BURST_GL2C2', + 22: 'GL2A_PERF_SEL_REQ_BURST_GL2C3', + 23: 'GL2A_PERF_SEL_REQ_BURST_GL2C4', + 24: 'GL2A_PERF_SEL_REQ_BURST_GL2C5', + 25: 'GL2A_PERF_SEL_REQ_BURST_GL2C6', + 26: 'GL2A_PERF_SEL_REQ_BURST_GL2C7', + 27: 'GL2A_PERF_SEL_REQ_STALL_GL2C0', + 28: 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 29: 'GL2A_PERF_SEL_REQ_STALL_GL2C2', + 30: 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 31: 'GL2A_PERF_SEL_REQ_STALL_GL2C4', + 32: 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 33: 'GL2A_PERF_SEL_REQ_STALL_GL2C6', + 34: 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 35: 'GL2A_PERF_SEL_RTN_STALL_GL2C0', + 36: 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 37: 'GL2A_PERF_SEL_RTN_STALL_GL2C2', + 38: 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 39: 'GL2A_PERF_SEL_RTN_STALL_GL2C4', + 40: 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 41: 'GL2A_PERF_SEL_RTN_STALL_GL2C6', + 42: 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 43: 'GL2A_PERF_SEL_RTN_CLIENT0', + 44: 'GL2A_PERF_SEL_RTN_CLIENT1', + 45: 'GL2A_PERF_SEL_RTN_CLIENT2', + 46: 'GL2A_PERF_SEL_RTN_CLIENT3', + 47: 'GL2A_PERF_SEL_RTN_CLIENT4', + 48: 'GL2A_PERF_SEL_RTN_CLIENT5', + 49: 'GL2A_PERF_SEL_RTN_CLIENT6', + 50: 'GL2A_PERF_SEL_RTN_CLIENT7', + 51: 'GL2A_PERF_SEL_RTN_CLIENT8', + 52: 'GL2A_PERF_SEL_RTN_CLIENT9', + 53: 'GL2A_PERF_SEL_RTN_CLIENT10', + 54: 'GL2A_PERF_SEL_RTN_CLIENT11', + 55: 'GL2A_PERF_SEL_RTN_CLIENT12', + 56: 'GL2A_PERF_SEL_RTN_CLIENT13', + 57: 'GL2A_PERF_SEL_RTN_CLIENT14', + 58: 'GL2A_PERF_SEL_RTN_CLIENT15', + 59: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 60: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 61: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 62: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 63: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 64: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 65: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 66: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', + 67: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8', + 68: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9', + 69: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10', + 70: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11', + 71: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12', + 72: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13', + 73: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14', + 74: 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15', + 75: 'GL2A_PERF_SEL_REQ_BURST_CLIENT0', + 76: 'GL2A_PERF_SEL_REQ_BURST_CLIENT1', + 77: 'GL2A_PERF_SEL_REQ_BURST_CLIENT2', + 78: 'GL2A_PERF_SEL_REQ_BURST_CLIENT3', + 79: 'GL2A_PERF_SEL_REQ_BURST_CLIENT4', + 80: 'GL2A_PERF_SEL_REQ_BURST_CLIENT5', + 81: 'GL2A_PERF_SEL_REQ_BURST_CLIENT6', + 82: 'GL2A_PERF_SEL_REQ_BURST_CLIENT7', + 83: 'GL2A_PERF_SEL_REQ_BURST_CLIENT8', + 84: 'GL2A_PERF_SEL_REQ_BURST_CLIENT9', + 85: 'GL2A_PERF_SEL_REQ_BURST_CLIENT10', + 86: 'GL2A_PERF_SEL_REQ_BURST_CLIENT11', + 87: 'GL2A_PERF_SEL_REQ_BURST_CLIENT12', + 88: 'GL2A_PERF_SEL_REQ_BURST_CLIENT13', + 89: 'GL2A_PERF_SEL_REQ_BURST_CLIENT14', + 90: 'GL2A_PERF_SEL_REQ_BURST_CLIENT15', + 91: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0', + 92: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1', + 93: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2', + 94: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3', + 95: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4', + 96: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5', + 97: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6', + 98: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7', + 99: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8', + 100: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9', + 101: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10', + 103: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11', + 104: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12', + 105: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13', + 106: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14', + 107: 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15', +} +GL2A_PERF_SEL_NONE = 0 +GL2A_PERF_SEL_CYCLE = 1 +GL2A_PERF_SEL_BUSY = 2 +GL2A_PERF_SEL_REQ_GL2C0 = 3 +GL2A_PERF_SEL_REQ_GL2C1 = 4 +GL2A_PERF_SEL_REQ_GL2C2 = 5 +GL2A_PERF_SEL_REQ_GL2C3 = 6 +GL2A_PERF_SEL_REQ_GL2C4 = 7 +GL2A_PERF_SEL_REQ_GL2C5 = 8 +GL2A_PERF_SEL_REQ_GL2C6 = 9 +GL2A_PERF_SEL_REQ_GL2C7 = 10 +GL2A_PERF_SEL_REQ_BURST_GL2C0 = 19 +GL2A_PERF_SEL_REQ_BURST_GL2C1 = 20 +GL2A_PERF_SEL_REQ_BURST_GL2C2 = 21 +GL2A_PERF_SEL_REQ_BURST_GL2C3 = 22 +GL2A_PERF_SEL_REQ_BURST_GL2C4 = 23 +GL2A_PERF_SEL_REQ_BURST_GL2C5 = 24 +GL2A_PERF_SEL_REQ_BURST_GL2C6 = 25 +GL2A_PERF_SEL_REQ_BURST_GL2C7 = 26 +GL2A_PERF_SEL_REQ_STALL_GL2C0 = 27 +GL2A_PERF_SEL_REQ_STALL_GL2C1 = 28 +GL2A_PERF_SEL_REQ_STALL_GL2C2 = 29 +GL2A_PERF_SEL_REQ_STALL_GL2C3 = 30 +GL2A_PERF_SEL_REQ_STALL_GL2C4 = 31 +GL2A_PERF_SEL_REQ_STALL_GL2C5 = 32 +GL2A_PERF_SEL_REQ_STALL_GL2C6 = 33 +GL2A_PERF_SEL_REQ_STALL_GL2C7 = 34 +GL2A_PERF_SEL_RTN_STALL_GL2C0 = 35 +GL2A_PERF_SEL_RTN_STALL_GL2C1 = 36 +GL2A_PERF_SEL_RTN_STALL_GL2C2 = 37 +GL2A_PERF_SEL_RTN_STALL_GL2C3 = 38 +GL2A_PERF_SEL_RTN_STALL_GL2C4 = 39 +GL2A_PERF_SEL_RTN_STALL_GL2C5 = 40 +GL2A_PERF_SEL_RTN_STALL_GL2C6 = 41 +GL2A_PERF_SEL_RTN_STALL_GL2C7 = 42 +GL2A_PERF_SEL_RTN_CLIENT0 = 43 +GL2A_PERF_SEL_RTN_CLIENT1 = 44 +GL2A_PERF_SEL_RTN_CLIENT2 = 45 +GL2A_PERF_SEL_RTN_CLIENT3 = 46 +GL2A_PERF_SEL_RTN_CLIENT4 = 47 +GL2A_PERF_SEL_RTN_CLIENT5 = 48 +GL2A_PERF_SEL_RTN_CLIENT6 = 49 +GL2A_PERF_SEL_RTN_CLIENT7 = 50 +GL2A_PERF_SEL_RTN_CLIENT8 = 51 +GL2A_PERF_SEL_RTN_CLIENT9 = 52 +GL2A_PERF_SEL_RTN_CLIENT10 = 53 +GL2A_PERF_SEL_RTN_CLIENT11 = 54 +GL2A_PERF_SEL_RTN_CLIENT12 = 55 +GL2A_PERF_SEL_RTN_CLIENT13 = 56 +GL2A_PERF_SEL_RTN_CLIENT14 = 57 +GL2A_PERF_SEL_RTN_CLIENT15 = 58 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0 = 59 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1 = 60 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2 = 61 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3 = 62 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4 = 63 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5 = 64 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6 = 65 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7 = 66 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8 = 67 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9 = 68 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10 = 69 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11 = 70 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12 = 71 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13 = 72 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14 = 73 +GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15 = 74 +GL2A_PERF_SEL_REQ_BURST_CLIENT0 = 75 +GL2A_PERF_SEL_REQ_BURST_CLIENT1 = 76 +GL2A_PERF_SEL_REQ_BURST_CLIENT2 = 77 +GL2A_PERF_SEL_REQ_BURST_CLIENT3 = 78 +GL2A_PERF_SEL_REQ_BURST_CLIENT4 = 79 +GL2A_PERF_SEL_REQ_BURST_CLIENT5 = 80 +GL2A_PERF_SEL_REQ_BURST_CLIENT6 = 81 +GL2A_PERF_SEL_REQ_BURST_CLIENT7 = 82 +GL2A_PERF_SEL_REQ_BURST_CLIENT8 = 83 +GL2A_PERF_SEL_REQ_BURST_CLIENT9 = 84 +GL2A_PERF_SEL_REQ_BURST_CLIENT10 = 85 +GL2A_PERF_SEL_REQ_BURST_CLIENT11 = 86 +GL2A_PERF_SEL_REQ_BURST_CLIENT12 = 87 +GL2A_PERF_SEL_REQ_BURST_CLIENT13 = 88 +GL2A_PERF_SEL_REQ_BURST_CLIENT14 = 89 +GL2A_PERF_SEL_REQ_BURST_CLIENT15 = 90 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0 = 91 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1 = 92 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2 = 93 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3 = 94 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4 = 95 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5 = 96 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6 = 97 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7 = 98 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8 = 99 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9 = 100 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10 = 101 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11 = 103 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12 = 104 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13 = 105 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14 = 106 +GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15 = 107 +GL2A_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GL2C_PERF_SEL' +GL2C_PERF_SEL__enumvalues = { + 0: 'GL2C_PERF_SEL_NONE', + 1: 'GL2C_PERF_SEL_CYCLE', + 2: 'GL2C_PERF_SEL_BUSY', + 3: 'GL2C_PERF_SEL_REQ', + 4: 'GL2C_PERF_SEL_VOL_REQ', + 5: 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', + 6: 'GL2C_PERF_SEL_READ', + 7: 'GL2C_PERF_SEL_WRITE', + 8: 'GL2C_PERF_SEL_ATOMIC', + 9: 'GL2C_PERF_SEL_NOP_ACK', + 10: 'GL2C_PERF_SEL_NOP_RTN0', + 11: 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', + 12: 'GL2C_PERF_SEL_METADATA_READ_REQ', + 13: 'GL2C_PERF_SEL_CLIENT0_REQ', + 14: 'GL2C_PERF_SEL_CLIENT1_REQ', + 15: 'GL2C_PERF_SEL_CLIENT2_REQ', + 16: 'GL2C_PERF_SEL_CLIENT3_REQ', + 17: 'GL2C_PERF_SEL_CLIENT4_REQ', + 18: 'GL2C_PERF_SEL_CLIENT5_REQ', + 19: 'GL2C_PERF_SEL_CLIENT6_REQ', + 20: 'GL2C_PERF_SEL_CLIENT7_REQ', + 21: 'GL2C_PERF_SEL_CLIENT8_REQ', + 22: 'GL2C_PERF_SEL_CLIENT9_REQ', + 23: 'GL2C_PERF_SEL_CLIENT10_REQ', + 24: 'GL2C_PERF_SEL_CLIENT11_REQ', + 25: 'GL2C_PERF_SEL_CLIENT12_REQ', + 26: 'GL2C_PERF_SEL_CLIENT13_REQ', + 27: 'GL2C_PERF_SEL_CLIENT14_REQ', + 28: 'GL2C_PERF_SEL_CLIENT15_REQ', + 29: 'GL2C_PERF_SEL_C_RW_S_REQ', + 30: 'GL2C_PERF_SEL_C_RW_US_REQ', + 31: 'GL2C_PERF_SEL_C_RO_S_REQ', + 32: 'GL2C_PERF_SEL_C_RO_US_REQ', + 33: 'GL2C_PERF_SEL_UC_REQ', + 34: 'GL2C_PERF_SEL_LRU_REQ', + 35: 'GL2C_PERF_SEL_STREAM_REQ', + 36: 'GL2C_PERF_SEL_BYPASS_REQ', + 37: 'GL2C_PERF_SEL_NOA_REQ', + 38: 'GL2C_PERF_SEL_SHARED_REQ', + 39: 'GL2C_PERF_SEL_HIT', + 40: 'GL2C_PERF_SEL_MISS', + 41: 'GL2C_PERF_SEL_FULL_HIT', + 42: 'GL2C_PERF_SEL_PARTIAL_32B_HIT', + 43: 'GL2C_PERF_SEL_PARTIAL_64B_HIT', + 44: 'GL2C_PERF_SEL_PARTIAL_96B_HIT', + 45: 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', + 46: 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', + 47: 'GL2C_PERF_SEL_UNCACHED_WRITE', + 48: 'GL2C_PERF_SEL_WRITEBACK', + 49: 'GL2C_PERF_SEL_NORMAL_WRITEBACK', + 50: 'GL2C_PERF_SEL_EVICT', + 51: 'GL2C_PERF_SEL_NORMAL_EVICT', + 52: 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', + 53: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 54: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 55: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 56: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 57: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 58: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 59: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 60: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 61: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8', + 62: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9', + 63: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10', + 64: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11', + 65: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12', + 66: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13', + 67: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14', + 68: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15', + 69: 'GL2C_PERF_SEL_READ_32_REQ', + 70: 'GL2C_PERF_SEL_READ_64_REQ', + 71: 'GL2C_PERF_SEL_READ_128_REQ', + 72: 'GL2C_PERF_SEL_WRITE_32_REQ', + 73: 'GL2C_PERF_SEL_WRITE_64_REQ', + 74: 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 75: 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 76: 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 77: 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 78: 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 79: 'GL2C_PERF_SEL_MC_WRREQ', + 80: 'GL2C_PERF_SEL_EA_WRREQ_SNOOP', + 81: 'GL2C_PERF_SEL_EA_WRREQ_64B', + 82: 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', + 83: 'GL2C_PERF_SEL_MC_WRREQ_STALL', + 84: 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 85: 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 86: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 87: 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', + 88: 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', + 89: 'GL2C_PERF_SEL_EA_ATOMIC', + 90: 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', + 91: 'GL2C_PERF_SEL_MC_RDREQ', + 92: 'GL2C_PERF_SEL_EA_RDREQ_SNOOP', + 93: 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', + 94: 'GL2C_PERF_SEL_EA_RDREQ_32B', + 95: 'GL2C_PERF_SEL_EA_RDREQ_64B', + 96: 'GL2C_PERF_SEL_EA_RDREQ_96B', + 97: 'GL2C_PERF_SEL_EA_RDREQ_128B', + 98: 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', + 99: 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 100: 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 101: 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 102: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 103: 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', + 104: 'GL2C_PERF_SEL_EA_RDREQ_DRAM', + 105: 'GL2C_PERF_SEL_EA_WRREQ_DRAM', + 106: 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 107: 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 108: 'GL2C_PERF_SEL_ONION_READ', + 109: 'GL2C_PERF_SEL_ONION_WRITE', + 110: 'GL2C_PERF_SEL_IO_READ', + 111: 'GL2C_PERF_SEL_IO_WRITE', + 112: 'GL2C_PERF_SEL_GARLIC_READ', + 113: 'GL2C_PERF_SEL_GARLIC_WRITE', + 114: 'GL2C_PERF_SEL_EA_OUTSTANDING', + 115: 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', + 116: 'GL2C_PERF_SEL_SRC_FIFO_FULL', + 117: 'GL2C_PERF_SEL_TAG_STALL', + 118: 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 119: 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 120: 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 121: 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 122: 'GL2C_PERF_SEL_TAG_READ_DST_STALL', + 123: 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', + 124: 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 125: 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 126: 'GL2C_PERF_SEL_BUBBLE', + 127: 'GL2C_PERF_SEL_IB_REQ', + 128: 'GL2C_PERF_SEL_IB_STALL', + 129: 'GL2C_PERF_SEL_IB_TAG_STALL', + 130: 'GL2C_PERF_SEL_RETURN_ACK', + 131: 'GL2C_PERF_SEL_RETURN_DATA', + 132: 'GL2C_PERF_SEL_EA_RDRET_NACK', + 133: 'GL2C_PERF_SEL_EA_WRRET_NACK', + 134: 'GL2C_PERF_SEL_GL2A_LEVEL', + 135: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 136: 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 137: 'GL2C_PERF_SEL_GCR_INV', + 138: 'GL2C_PERF_SEL_GCR_WB', + 139: 'GL2C_PERF_SEL_GCR_DISCARD', + 140: 'GL2C_PERF_SEL_GCR_RANGE', + 141: 'GL2C_PERF_SEL_GCR_ALL', + 142: 'GL2C_PERF_SEL_GCR_VOL', + 143: 'GL2C_PERF_SEL_GCR_UNSHARED', + 144: 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 145: 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 146: 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', + 147: 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', + 148: 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 149: 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 150: 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 151: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 152: 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 153: 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 154: 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 155: 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 156: 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', + 157: 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 158: 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', + 159: 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 160: 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 161: 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 162: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16', + 163: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17', + 164: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18', + 165: 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19', +} +GL2C_PERF_SEL_NONE = 0 +GL2C_PERF_SEL_CYCLE = 1 +GL2C_PERF_SEL_BUSY = 2 +GL2C_PERF_SEL_REQ = 3 +GL2C_PERF_SEL_VOL_REQ = 4 +GL2C_PERF_SEL_HIGH_PRIORITY_REQ = 5 +GL2C_PERF_SEL_READ = 6 +GL2C_PERF_SEL_WRITE = 7 +GL2C_PERF_SEL_ATOMIC = 8 +GL2C_PERF_SEL_NOP_ACK = 9 +GL2C_PERF_SEL_NOP_RTN0 = 10 +GL2C_PERF_SEL_COMPRESSED_READ_REQ = 11 +GL2C_PERF_SEL_METADATA_READ_REQ = 12 +GL2C_PERF_SEL_CLIENT0_REQ = 13 +GL2C_PERF_SEL_CLIENT1_REQ = 14 +GL2C_PERF_SEL_CLIENT2_REQ = 15 +GL2C_PERF_SEL_CLIENT3_REQ = 16 +GL2C_PERF_SEL_CLIENT4_REQ = 17 +GL2C_PERF_SEL_CLIENT5_REQ = 18 +GL2C_PERF_SEL_CLIENT6_REQ = 19 +GL2C_PERF_SEL_CLIENT7_REQ = 20 +GL2C_PERF_SEL_CLIENT8_REQ = 21 +GL2C_PERF_SEL_CLIENT9_REQ = 22 +GL2C_PERF_SEL_CLIENT10_REQ = 23 +GL2C_PERF_SEL_CLIENT11_REQ = 24 +GL2C_PERF_SEL_CLIENT12_REQ = 25 +GL2C_PERF_SEL_CLIENT13_REQ = 26 +GL2C_PERF_SEL_CLIENT14_REQ = 27 +GL2C_PERF_SEL_CLIENT15_REQ = 28 +GL2C_PERF_SEL_C_RW_S_REQ = 29 +GL2C_PERF_SEL_C_RW_US_REQ = 30 +GL2C_PERF_SEL_C_RO_S_REQ = 31 +GL2C_PERF_SEL_C_RO_US_REQ = 32 +GL2C_PERF_SEL_UC_REQ = 33 +GL2C_PERF_SEL_LRU_REQ = 34 +GL2C_PERF_SEL_STREAM_REQ = 35 +GL2C_PERF_SEL_BYPASS_REQ = 36 +GL2C_PERF_SEL_NOA_REQ = 37 +GL2C_PERF_SEL_SHARED_REQ = 38 +GL2C_PERF_SEL_HIT = 39 +GL2C_PERF_SEL_MISS = 40 +GL2C_PERF_SEL_FULL_HIT = 41 +GL2C_PERF_SEL_PARTIAL_32B_HIT = 42 +GL2C_PERF_SEL_PARTIAL_64B_HIT = 43 +GL2C_PERF_SEL_PARTIAL_96B_HIT = 44 +GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT = 45 +GL2C_PERF_SEL_FULLY_WRITTEN_HIT = 46 +GL2C_PERF_SEL_UNCACHED_WRITE = 47 +GL2C_PERF_SEL_WRITEBACK = 48 +GL2C_PERF_SEL_NORMAL_WRITEBACK = 49 +GL2C_PERF_SEL_EVICT = 50 +GL2C_PERF_SEL_NORMAL_EVICT = 51 +GL2C_PERF_SEL_REQ_TO_MISS_QUEUE = 52 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0 = 53 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1 = 54 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2 = 55 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3 = 56 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4 = 57 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5 = 58 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6 = 59 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7 = 60 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8 = 61 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9 = 62 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10 = 63 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11 = 64 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12 = 65 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13 = 66 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14 = 67 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15 = 68 +GL2C_PERF_SEL_READ_32_REQ = 69 +GL2C_PERF_SEL_READ_64_REQ = 70 +GL2C_PERF_SEL_READ_128_REQ = 71 +GL2C_PERF_SEL_WRITE_32_REQ = 72 +GL2C_PERF_SEL_WRITE_64_REQ = 73 +GL2C_PERF_SEL_COMPRESSED_READ_0_REQ = 74 +GL2C_PERF_SEL_COMPRESSED_READ_32_REQ = 75 +GL2C_PERF_SEL_COMPRESSED_READ_64_REQ = 76 +GL2C_PERF_SEL_COMPRESSED_READ_96_REQ = 77 +GL2C_PERF_SEL_COMPRESSED_READ_128_REQ = 78 +GL2C_PERF_SEL_MC_WRREQ = 79 +GL2C_PERF_SEL_EA_WRREQ_SNOOP = 80 +GL2C_PERF_SEL_EA_WRREQ_64B = 81 +GL2C_PERF_SEL_EA_WR_UNCACHED_32B = 82 +GL2C_PERF_SEL_MC_WRREQ_STALL = 83 +GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL = 84 +GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL = 85 +GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL = 86 +GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL = 87 +GL2C_PERF_SEL_MC_WRREQ_LEVEL = 88 +GL2C_PERF_SEL_EA_ATOMIC = 89 +GL2C_PERF_SEL_EA_ATOMIC_LEVEL = 90 +GL2C_PERF_SEL_MC_RDREQ = 91 +GL2C_PERF_SEL_EA_RDREQ_SNOOP = 92 +GL2C_PERF_SEL_EA_RDREQ_SPLIT = 93 +GL2C_PERF_SEL_EA_RDREQ_32B = 94 +GL2C_PERF_SEL_EA_RDREQ_64B = 95 +GL2C_PERF_SEL_EA_RDREQ_96B = 96 +GL2C_PERF_SEL_EA_RDREQ_128B = 97 +GL2C_PERF_SEL_EA_RD_UNCACHED_32B = 98 +GL2C_PERF_SEL_EA_RD_COMPRESSED_32B = 99 +GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL = 100 +GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL = 101 +GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL = 102 +GL2C_PERF_SEL_MC_RDREQ_LEVEL = 103 +GL2C_PERF_SEL_EA_RDREQ_DRAM = 104 +GL2C_PERF_SEL_EA_WRREQ_DRAM = 105 +GL2C_PERF_SEL_EA_RDREQ_DRAM_32B = 106 +GL2C_PERF_SEL_EA_WRREQ_DRAM_32B = 107 +GL2C_PERF_SEL_ONION_READ = 108 +GL2C_PERF_SEL_ONION_WRITE = 109 +GL2C_PERF_SEL_IO_READ = 110 +GL2C_PERF_SEL_IO_WRITE = 111 +GL2C_PERF_SEL_GARLIC_READ = 112 +GL2C_PERF_SEL_GARLIC_WRITE = 113 +GL2C_PERF_SEL_EA_OUTSTANDING = 114 +GL2C_PERF_SEL_LATENCY_FIFO_FULL = 115 +GL2C_PERF_SEL_SRC_FIFO_FULL = 116 +GL2C_PERF_SEL_TAG_STALL = 117 +GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL = 118 +GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL = 119 +GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL = 120 +GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL = 121 +GL2C_PERF_SEL_TAG_READ_DST_STALL = 122 +GL2C_PERF_SEL_READ_RETURN_TIMEOUT = 123 +GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT = 124 +GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE = 125 +GL2C_PERF_SEL_BUBBLE = 126 +GL2C_PERF_SEL_IB_REQ = 127 +GL2C_PERF_SEL_IB_STALL = 128 +GL2C_PERF_SEL_IB_TAG_STALL = 129 +GL2C_PERF_SEL_RETURN_ACK = 130 +GL2C_PERF_SEL_RETURN_DATA = 131 +GL2C_PERF_SEL_EA_RDRET_NACK = 132 +GL2C_PERF_SEL_EA_WRRET_NACK = 133 +GL2C_PERF_SEL_GL2A_LEVEL = 134 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START = 135 +GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START = 136 +GL2C_PERF_SEL_GCR_INV = 137 +GL2C_PERF_SEL_GCR_WB = 138 +GL2C_PERF_SEL_GCR_DISCARD = 139 +GL2C_PERF_SEL_GCR_RANGE = 140 +GL2C_PERF_SEL_GCR_ALL = 141 +GL2C_PERF_SEL_GCR_VOL = 142 +GL2C_PERF_SEL_GCR_UNSHARED = 143 +GL2C_PERF_SEL_GCR_GL2_INV_ALL = 144 +GL2C_PERF_SEL_GCR_GL2_WB_ALL = 145 +GL2C_PERF_SEL_GCR_GL2_INV_RANGE = 146 +GL2C_PERF_SEL_GCR_GL2_WB_RANGE = 147 +GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE = 148 +GL2C_PERF_SEL_ALL_GCR_INV_EVICT = 149 +GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT = 150 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE = 151 +GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE = 152 +GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK = 153 +GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE = 154 +GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT = 155 +GL2C_PERF_SEL_GCR_INVL2_VOL_START = 156 +GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE = 157 +GL2C_PERF_SEL_GCR_WBL2_VOL_START = 158 +GL2C_PERF_SEL_GCR_WBINVL2_CYCLE = 159 +GL2C_PERF_SEL_GCR_WBINVL2_EVICT = 160 +GL2C_PERF_SEL_GCR_WBINVL2_START = 161 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16 = 162 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17 = 163 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18 = 164 +GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19 = 165 +GL2C_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SX_BLEND_OPT' +SX_BLEND_OPT__enumvalues = { + 0: 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 1: 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 2: 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 3: 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 4: 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 5: 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 6: 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 7: 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', +} +BLEND_OPT_PRESERVE_NONE_IGNORE_ALL = 0 +BLEND_OPT_PRESERVE_ALL_IGNORE_NONE = 1 +BLEND_OPT_PRESERVE_C1_IGNORE_C0 = 2 +BLEND_OPT_PRESERVE_C0_IGNORE_C1 = 3 +BLEND_OPT_PRESERVE_A1_IGNORE_A0 = 4 +BLEND_OPT_PRESERVE_A0_IGNORE_A1 = 5 +BLEND_OPT_PRESERVE_NONE_IGNORE_A0 = 6 +BLEND_OPT_PRESERVE_NONE_IGNORE_NONE = 7 +SX_BLEND_OPT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_DOWNCONVERT_FORMAT' +SX_DOWNCONVERT_FORMAT__enumvalues = { + 0: 'SX_RT_EXPORT_NO_CONVERSION', + 1: 'SX_RT_EXPORT_32_R', + 2: 'SX_RT_EXPORT_32_A', + 3: 'SX_RT_EXPORT_10_11_11', + 4: 'SX_RT_EXPORT_2_10_10_10', + 5: 'SX_RT_EXPORT_8_8_8_8', + 6: 'SX_RT_EXPORT_5_6_5', + 7: 'SX_RT_EXPORT_1_5_5_5', + 8: 'SX_RT_EXPORT_4_4_4_4', + 9: 'SX_RT_EXPORT_16_16_GR', + 10: 'SX_RT_EXPORT_16_16_AR', + 11: 'SX_RT_EXPORT_9_9_9_E5', + 12: 'SX_RT_EXPORT_2_10_10_10_7E3', + 13: 'SX_RT_EXPORT_2_10_10_10_6E4', +} +SX_RT_EXPORT_NO_CONVERSION = 0 +SX_RT_EXPORT_32_R = 1 +SX_RT_EXPORT_32_A = 2 +SX_RT_EXPORT_10_11_11 = 3 +SX_RT_EXPORT_2_10_10_10 = 4 +SX_RT_EXPORT_8_8_8_8 = 5 +SX_RT_EXPORT_5_6_5 = 6 +SX_RT_EXPORT_1_5_5_5 = 7 +SX_RT_EXPORT_4_4_4_4 = 8 +SX_RT_EXPORT_16_16_GR = 9 +SX_RT_EXPORT_16_16_AR = 10 +SX_RT_EXPORT_9_9_9_E5 = 11 +SX_RT_EXPORT_2_10_10_10_7E3 = 12 +SX_RT_EXPORT_2_10_10_10_6E4 = 13 +SX_DOWNCONVERT_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_OPT_COMB_FCN' +SX_OPT_COMB_FCN__enumvalues = { + 0: 'OPT_COMB_NONE', + 1: 'OPT_COMB_ADD', + 2: 'OPT_COMB_SUBTRACT', + 3: 'OPT_COMB_MIN', + 4: 'OPT_COMB_MAX', + 5: 'OPT_COMB_REVSUBTRACT', + 6: 'OPT_COMB_BLEND_DISABLED', + 7: 'OPT_COMB_SAFE_ADD', +} +OPT_COMB_NONE = 0 +OPT_COMB_ADD = 1 +OPT_COMB_SUBTRACT = 2 +OPT_COMB_MIN = 3 +OPT_COMB_MAX = 4 +OPT_COMB_REVSUBTRACT = 5 +OPT_COMB_BLEND_DISABLED = 6 +OPT_COMB_SAFE_ADD = 7 +SX_OPT_COMB_FCN = ctypes.c_uint32 # enum + +# values for enumeration 'SX_PERFCOUNTER_VALS' +SX_PERFCOUNTER_VALS__enumvalues = { + 0: 'SX_PERF_SEL_PA_IDLE_CYCLES', + 1: 'SX_PERF_SEL_PA_REQ', + 2: 'SX_PERF_SEL_PA_POS', + 3: 'SX_PERF_SEL_CLOCK', + 4: 'SX_PERF_SEL_GATE_EN1', + 5: 'SX_PERF_SEL_GATE_EN2', + 6: 'SX_PERF_SEL_GATE_EN3', + 7: 'SX_PERF_SEL_GATE_EN4', + 8: 'SX_PERF_SEL_SH_POS_STARVE', + 9: 'SX_PERF_SEL_SH_COLOR_STARVE', + 10: 'SX_PERF_SEL_SH_POS_STALL', + 11: 'SX_PERF_SEL_SH_COLOR_STALL', + 12: 'SX_PERF_SEL_DB0_PIXELS', + 13: 'SX_PERF_SEL_DB0_HALF_QUADS', + 14: 'SX_PERF_SEL_DB0_PIXEL_STALL', + 15: 'SX_PERF_SEL_DB0_PIXEL_IDLE', + 16: 'SX_PERF_SEL_DB0_PRED_PIXELS', + 17: 'SX_PERF_SEL_DB1_PIXELS', + 18: 'SX_PERF_SEL_DB1_HALF_QUADS', + 19: 'SX_PERF_SEL_DB1_PIXEL_STALL', + 20: 'SX_PERF_SEL_DB1_PIXEL_IDLE', + 21: 'SX_PERF_SEL_DB1_PRED_PIXELS', + 22: 'SX_PERF_SEL_DB2_PIXELS', + 23: 'SX_PERF_SEL_DB2_HALF_QUADS', + 24: 'SX_PERF_SEL_DB2_PIXEL_STALL', + 25: 'SX_PERF_SEL_DB2_PIXEL_IDLE', + 26: 'SX_PERF_SEL_DB2_PRED_PIXELS', + 27: 'SX_PERF_SEL_DB3_PIXELS', + 28: 'SX_PERF_SEL_DB3_HALF_QUADS', + 29: 'SX_PERF_SEL_DB3_PIXEL_STALL', + 30: 'SX_PERF_SEL_DB3_PIXEL_IDLE', + 31: 'SX_PERF_SEL_DB3_PRED_PIXELS', + 32: 'SX_PERF_SEL_COL_BUSY', + 33: 'SX_PERF_SEL_POS_BUSY', + 34: 'SX_PERF_SEL_DB0_MRT_BLEND_BYPASS', + 35: 'SX_PERF_SEL_DB0_MRT_DONT_RD_DEST', + 36: 'SX_PERF_SEL_DB0_MRT_DISCARD_SRC', + 37: 'SX_PERF_SEL_DB0_MRT_SINGLE_QUADS', + 38: 'SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS', + 39: 'SX_PERF_SEL_DB1_MRT_BLEND_BYPASS', + 40: 'SX_PERF_SEL_DB1_MRT_DONT_RD_DEST', + 41: 'SX_PERF_SEL_DB1_MRT_DISCARD_SRC', + 42: 'SX_PERF_SEL_DB1_MRT_SINGLE_QUADS', + 43: 'SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS', + 44: 'SX_PERF_SEL_DB2_MRT_BLEND_BYPASS', + 45: 'SX_PERF_SEL_DB2_MRT_DONT_RD_DEST', + 46: 'SX_PERF_SEL_DB2_MRT_DISCARD_SRC', + 47: 'SX_PERF_SEL_DB2_MRT_SINGLE_QUADS', + 48: 'SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS', + 49: 'SX_PERF_SEL_DB3_MRT_BLEND_BYPASS', + 50: 'SX_PERF_SEL_DB3_MRT_DONT_RD_DEST', + 51: 'SX_PERF_SEL_DB3_MRT_DISCARD_SRC', + 52: 'SX_PERF_SEL_DB3_MRT_SINGLE_QUADS', + 53: 'SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS', + 54: 'SX_PERF_SEL_PA_REQ_LATENCY', + 55: 'SX_PERF_SEL_POS_SCBD_STALL', + 56: 'SX_PERF_SEL_CLOCK_DROP_STALL', + 57: 'SX_PERF_SEL_GATE_EN5', + 58: 'SX_PERF_SEL_GATE_EN6', + 59: 'SX_PERF_SEL_DB0_SIZE', + 60: 'SX_PERF_SEL_DB1_SIZE', + 61: 'SX_PERF_SEL_DB2_SIZE', + 62: 'SX_PERF_SEL_DB3_SIZE', + 63: 'SX_PERF_SEL_IDX_STALL_CYCLES', + 64: 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 65: 'SX_PERF_SEL_IDX_REQ', + 66: 'SX_PERF_SEL_IDX_RET', + 67: 'SX_PERF_SEL_IDX_REQ_LATENCY', + 68: 'SX_PERF_SEL_IDX_SCBD_STALL', + 69: 'SX_PERF_SEL_GATE_EN7', + 70: 'SX_PERF_SEL_GATE_EN8', + 71: 'SX_PERF_SEL_SH_IDX_STARVE', + 72: 'SX_PERF_SEL_IDX_BUSY', + 73: 'SX_PERF_SEL_PA_POS_BANK_CONF', + 74: 'SX_PERF_SEL_DB0_END_OF_WAVE', + 75: 'SX_PERF_SEL_DB0_4X2_DISCARD', + 76: 'SX_PERF_SEL_DB1_END_OF_WAVE', + 77: 'SX_PERF_SEL_DB1_4X2_DISCARD', + 78: 'SX_PERF_SEL_DB2_END_OF_WAVE', + 79: 'SX_PERF_SEL_DB2_4X2_DISCARD', + 80: 'SX_PERF_SEL_DB3_END_OF_WAVE', + 81: 'SX_PERF_SEL_DB3_4X2_DISCARD', +} +SX_PERF_SEL_PA_IDLE_CYCLES = 0 +SX_PERF_SEL_PA_REQ = 1 +SX_PERF_SEL_PA_POS = 2 +SX_PERF_SEL_CLOCK = 3 +SX_PERF_SEL_GATE_EN1 = 4 +SX_PERF_SEL_GATE_EN2 = 5 +SX_PERF_SEL_GATE_EN3 = 6 +SX_PERF_SEL_GATE_EN4 = 7 +SX_PERF_SEL_SH_POS_STARVE = 8 +SX_PERF_SEL_SH_COLOR_STARVE = 9 +SX_PERF_SEL_SH_POS_STALL = 10 +SX_PERF_SEL_SH_COLOR_STALL = 11 +SX_PERF_SEL_DB0_PIXELS = 12 +SX_PERF_SEL_DB0_HALF_QUADS = 13 +SX_PERF_SEL_DB0_PIXEL_STALL = 14 +SX_PERF_SEL_DB0_PIXEL_IDLE = 15 +SX_PERF_SEL_DB0_PRED_PIXELS = 16 +SX_PERF_SEL_DB1_PIXELS = 17 +SX_PERF_SEL_DB1_HALF_QUADS = 18 +SX_PERF_SEL_DB1_PIXEL_STALL = 19 +SX_PERF_SEL_DB1_PIXEL_IDLE = 20 +SX_PERF_SEL_DB1_PRED_PIXELS = 21 +SX_PERF_SEL_DB2_PIXELS = 22 +SX_PERF_SEL_DB2_HALF_QUADS = 23 +SX_PERF_SEL_DB2_PIXEL_STALL = 24 +SX_PERF_SEL_DB2_PIXEL_IDLE = 25 +SX_PERF_SEL_DB2_PRED_PIXELS = 26 +SX_PERF_SEL_DB3_PIXELS = 27 +SX_PERF_SEL_DB3_HALF_QUADS = 28 +SX_PERF_SEL_DB3_PIXEL_STALL = 29 +SX_PERF_SEL_DB3_PIXEL_IDLE = 30 +SX_PERF_SEL_DB3_PRED_PIXELS = 31 +SX_PERF_SEL_COL_BUSY = 32 +SX_PERF_SEL_POS_BUSY = 33 +SX_PERF_SEL_DB0_MRT_BLEND_BYPASS = 34 +SX_PERF_SEL_DB0_MRT_DONT_RD_DEST = 35 +SX_PERF_SEL_DB0_MRT_DISCARD_SRC = 36 +SX_PERF_SEL_DB0_MRT_SINGLE_QUADS = 37 +SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS = 38 +SX_PERF_SEL_DB1_MRT_BLEND_BYPASS = 39 +SX_PERF_SEL_DB1_MRT_DONT_RD_DEST = 40 +SX_PERF_SEL_DB1_MRT_DISCARD_SRC = 41 +SX_PERF_SEL_DB1_MRT_SINGLE_QUADS = 42 +SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS = 43 +SX_PERF_SEL_DB2_MRT_BLEND_BYPASS = 44 +SX_PERF_SEL_DB2_MRT_DONT_RD_DEST = 45 +SX_PERF_SEL_DB2_MRT_DISCARD_SRC = 46 +SX_PERF_SEL_DB2_MRT_SINGLE_QUADS = 47 +SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS = 48 +SX_PERF_SEL_DB3_MRT_BLEND_BYPASS = 49 +SX_PERF_SEL_DB3_MRT_DONT_RD_DEST = 50 +SX_PERF_SEL_DB3_MRT_DISCARD_SRC = 51 +SX_PERF_SEL_DB3_MRT_SINGLE_QUADS = 52 +SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS = 53 +SX_PERF_SEL_PA_REQ_LATENCY = 54 +SX_PERF_SEL_POS_SCBD_STALL = 55 +SX_PERF_SEL_CLOCK_DROP_STALL = 56 +SX_PERF_SEL_GATE_EN5 = 57 +SX_PERF_SEL_GATE_EN6 = 58 +SX_PERF_SEL_DB0_SIZE = 59 +SX_PERF_SEL_DB1_SIZE = 60 +SX_PERF_SEL_DB2_SIZE = 61 +SX_PERF_SEL_DB3_SIZE = 62 +SX_PERF_SEL_IDX_STALL_CYCLES = 63 +SX_PERF_SEL_IDX_IDLE_CYCLES = 64 +SX_PERF_SEL_IDX_REQ = 65 +SX_PERF_SEL_IDX_RET = 66 +SX_PERF_SEL_IDX_REQ_LATENCY = 67 +SX_PERF_SEL_IDX_SCBD_STALL = 68 +SX_PERF_SEL_GATE_EN7 = 69 +SX_PERF_SEL_GATE_EN8 = 70 +SX_PERF_SEL_SH_IDX_STARVE = 71 +SX_PERF_SEL_IDX_BUSY = 72 +SX_PERF_SEL_PA_POS_BANK_CONF = 73 +SX_PERF_SEL_DB0_END_OF_WAVE = 74 +SX_PERF_SEL_DB0_4X2_DISCARD = 75 +SX_PERF_SEL_DB1_END_OF_WAVE = 76 +SX_PERF_SEL_DB1_4X2_DISCARD = 77 +SX_PERF_SEL_DB2_END_OF_WAVE = 78 +SX_PERF_SEL_DB2_4X2_DISCARD = 79 +SX_PERF_SEL_DB3_END_OF_WAVE = 80 +SX_PERF_SEL_DB3_4X2_DISCARD = 81 +SX_PERFCOUNTER_VALS = ctypes.c_uint32 # enum + +# values for enumeration 'CompareFrag' +CompareFrag__enumvalues = { + 0: 'FRAG_NEVER', + 1: 'FRAG_LESS', + 2: 'FRAG_EQUAL', + 3: 'FRAG_LEQUAL', + 4: 'FRAG_GREATER', + 5: 'FRAG_NOTEQUAL', + 6: 'FRAG_GEQUAL', + 7: 'FRAG_ALWAYS', +} +FRAG_NEVER = 0 +FRAG_LESS = 1 +FRAG_EQUAL = 2 +FRAG_LEQUAL = 3 +FRAG_GREATER = 4 +FRAG_NOTEQUAL = 5 +FRAG_GEQUAL = 6 +FRAG_ALWAYS = 7 +CompareFrag = ctypes.c_uint32 # enum + +# values for enumeration 'ConservativeZExport' +ConservativeZExport__enumvalues = { + 0: 'EXPORT_ANY_Z', + 1: 'EXPORT_LESS_THAN_Z', + 2: 'EXPORT_GREATER_THAN_Z', + 3: 'EXPORT_RESERVED', +} +EXPORT_ANY_Z = 0 +EXPORT_LESS_THAN_Z = 1 +EXPORT_GREATER_THAN_Z = 2 +EXPORT_RESERVED = 3 +ConservativeZExport = ctypes.c_uint32 # enum + +# values for enumeration 'DbMemArbWatermarks' +DbMemArbWatermarks__enumvalues = { + 0: 'TRANSFERRED_64_BYTES', + 1: 'TRANSFERRED_128_BYTES', + 2: 'TRANSFERRED_256_BYTES', + 3: 'TRANSFERRED_512_BYTES', + 4: 'TRANSFERRED_1024_BYTES', + 5: 'TRANSFERRED_2048_BYTES', + 6: 'TRANSFERRED_4096_BYTES', + 7: 'TRANSFERRED_8192_BYTES', +} +TRANSFERRED_64_BYTES = 0 +TRANSFERRED_128_BYTES = 1 +TRANSFERRED_256_BYTES = 2 +TRANSFERRED_512_BYTES = 3 +TRANSFERRED_1024_BYTES = 4 +TRANSFERRED_2048_BYTES = 5 +TRANSFERRED_4096_BYTES = 6 +TRANSFERRED_8192_BYTES = 7 +DbMemArbWatermarks = ctypes.c_uint32 # enum + +# values for enumeration 'DbPRTFaultBehavior' +DbPRTFaultBehavior__enumvalues = { + 0: 'FAULT_ZERO', + 1: 'FAULT_ONE', + 2: 'FAULT_FAIL', + 3: 'FAULT_PASS', +} +FAULT_ZERO = 0 +FAULT_ONE = 1 +FAULT_FAIL = 2 +FAULT_PASS = 3 +DbPRTFaultBehavior = ctypes.c_uint32 # enum + +# values for enumeration 'DbPSLControl' +DbPSLControl__enumvalues = { + 0: 'PSLC_AUTO', + 1: 'PSLC_ON_HANG_ONLY', + 2: 'PSLC_ASAP', + 3: 'PSLC_COUNTDOWN', +} +PSLC_AUTO = 0 +PSLC_ON_HANG_ONLY = 1 +PSLC_ASAP = 2 +PSLC_COUNTDOWN = 3 +DbPSLControl = ctypes.c_uint32 # enum + +# values for enumeration 'ForceControl' +ForceControl__enumvalues = { + 0: 'FORCE_OFF', + 1: 'FORCE_ENABLE', + 2: 'FORCE_DISABLE', + 3: 'FORCE_RESERVED', +} +FORCE_OFF = 0 +FORCE_ENABLE = 1 +FORCE_DISABLE = 2 +FORCE_RESERVED = 3 +ForceControl = ctypes.c_uint32 # enum + +# values for enumeration 'GLCompressionMode' +GLCompressionMode__enumvalues = { + 0: 'DB_DEFAULT', + 1: 'DB_BYPASS', + 2: 'DB_COMP_WR_DISABLE', + 3: 'DB_BYPASS_WR_DISABLE', +} +DB_DEFAULT = 0 +DB_BYPASS = 1 +DB_COMP_WR_DISABLE = 2 +DB_BYPASS_WR_DISABLE = 3 +GLCompressionMode = ctypes.c_uint32 # enum + +# values for enumeration 'OreoMode' +OreoMode__enumvalues = { + 0: 'OMODE_BLEND', + 1: 'OMODE_O_THEN_B', + 2: 'OMODE_P_THEN_O_THEN_B', + 3: 'OMODE_RESERVED_3', +} +OMODE_BLEND = 0 +OMODE_O_THEN_B = 1 +OMODE_P_THEN_O_THEN_B = 2 +OMODE_RESERVED_3 = 3 +OreoMode = ctypes.c_uint32 # enum + +# values for enumeration 'PerfCounter_Vals' +PerfCounter_Vals__enumvalues = { + 0: 'DB_PERF_SEL_SC_DB_tile_sends', + 1: 'DB_PERF_SEL_SC_DB_tile_busy', + 2: 'DB_PERF_SEL_SC_DB_tile_stalls', + 3: 'DB_PERF_SEL_SC_DB_tile_events', + 4: 'DB_PERF_SEL_SC_DB_tile_tiles', + 5: 'DB_PERF_SEL_SC_DB_tile_covered', + 6: 'DB_PERF_SEL_hiz_tc_read_starved', + 7: 'DB_PERF_SEL_hiz_tc_write_stall', + 8: 'DB_PERF_SEL_hiz_tile_culled', + 9: 'DB_PERF_SEL_his_tile_culled', + 10: 'DB_PERF_SEL_DB_SC_tile_sends', + 11: 'DB_PERF_SEL_DB_SC_tile_busy', + 12: 'DB_PERF_SEL_DB_SC_tile_stalls', + 13: 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 14: 'DB_PERF_SEL_DB_SC_tile_tiles', + 15: 'DB_PERF_SEL_DB_SC_tile_culled', + 16: 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 17: 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 18: 'DB_PERF_SEL_DB_SC_tile_no_ops', + 19: 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 20: 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 21: 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 22: 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 23: 'DB_PERF_SEL_SC_DB_quad_sends', + 24: 'DB_PERF_SEL_SC_DB_quad_busy', + 25: 'DB_PERF_SEL_SC_DB_quad_squads', + 26: 'DB_PERF_SEL_SC_DB_quad_tiles', + 27: 'DB_PERF_SEL_SC_DB_quad_pixels', + 28: 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 29: 'DB_PERF_SEL_DB_SC_quad_sends', + 30: 'DB_PERF_SEL_DB_SC_quad_busy', + 31: 'DB_PERF_SEL_DB_SC_quad_stalls', + 32: 'DB_PERF_SEL_DB_SC_quad_tiles', + 33: 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 34: 'DB_PERF_SEL_DB_CB_export_events', + 37: 'DB_PERF_SEL_SX_DB_quad_sends', + 38: 'DB_PERF_SEL_SX_DB_quad_busy', + 39: 'DB_PERF_SEL_SX_DB_quad_stalls', + 40: 'DB_PERF_SEL_SX_DB_quad_quads', + 41: 'DB_PERF_SEL_SX_DB_quad_pixels', + 42: 'DB_PERF_SEL_SX_DB_quad_exports', + 43: 'DB_PERF_SEL_SH_quads_outstanding_sum', + 44: 'DB_PERF_SEL_DB_CB_export_sends', + 45: 'DB_PERF_SEL_DB_CB_export_busy', + 46: 'DB_PERF_SEL_DB_CB_export_stalls', + 47: 'DB_PERF_SEL_DB_CB_export_quads', + 48: 'DB_PERF_SEL_tile_rd_sends', + 49: 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 50: 'DB_PERF_SEL_quad_rd_sends', + 51: 'DB_PERF_SEL_quad_rd_busy', + 52: 'DB_PERF_SEL_quad_rd_mi_stall', + 53: 'DB_PERF_SEL_quad_rd_rw_collision', + 54: 'DB_PERF_SEL_quad_rd_tag_stall', + 55: 'DB_PERF_SEL_quad_rd_32byte_reqs', + 56: 'DB_PERF_SEL_quad_rd_panic', + 57: 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 58: 'DB_PERF_SEL_quad_rdret_sends', + 59: 'DB_PERF_SEL_quad_rdret_busy', + 60: 'DB_PERF_SEL_tile_wr_sends', + 61: 'DB_PERF_SEL_tile_wr_acks', + 62: 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 63: 'DB_PERF_SEL_quad_wr_sends', + 64: 'DB_PERF_SEL_quad_wr_busy', + 65: 'DB_PERF_SEL_quad_wr_mi_stall', + 66: 'DB_PERF_SEL_quad_wr_coherency_stall', + 67: 'DB_PERF_SEL_quad_wr_acks', + 68: 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 69: 'DB_PERF_SEL_Tile_Cache_misses', + 70: 'DB_PERF_SEL_Tile_Cache_hits', + 71: 'DB_PERF_SEL_Tile_Cache_flushes', + 72: 'DB_PERF_SEL_Tile_Cache_surface_stall', + 73: 'DB_PERF_SEL_Tile_Cache_starves', + 74: 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 75: 'DB_PERF_SEL_tcp_dispatcher_reads', + 76: 'DB_PERF_SEL_tcp_prefetcher_reads', + 77: 'DB_PERF_SEL_tcp_preloader_reads', + 78: 'DB_PERF_SEL_tcp_dispatcher_flushes', + 79: 'DB_PERF_SEL_tcp_prefetcher_flushes', + 80: 'DB_PERF_SEL_tcp_preloader_flushes', + 81: 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 82: 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 83: 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 84: 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 85: 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 86: 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 87: 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 88: 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 89: 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 90: 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 91: 'DB_PERF_SEL_Depth_Tile_Cache_event', + 92: 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 93: 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 94: 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 95: 'DB_PERF_SEL_Stencil_Cache_misses', + 96: 'DB_PERF_SEL_Stencil_Cache_hits', + 97: 'DB_PERF_SEL_Stencil_Cache_flushes', + 98: 'DB_PERF_SEL_Stencil_Cache_starves', + 99: 'DB_PERF_SEL_Stencil_Cache_frees', + 100: 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 101: 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 102: 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 103: 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 104: 'DB_PERF_SEL_Z_Cache_pmask_misses', + 105: 'DB_PERF_SEL_Z_Cache_pmask_hits', + 106: 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 107: 'DB_PERF_SEL_Z_Cache_pmask_starves', + 108: 'DB_PERF_SEL_Z_Cache_frees', + 109: 'DB_PERF_SEL_Plane_Cache_misses', + 110: 'DB_PERF_SEL_Plane_Cache_hits', + 111: 'DB_PERF_SEL_Plane_Cache_flushes', + 112: 'DB_PERF_SEL_Plane_Cache_starves', + 113: 'DB_PERF_SEL_Plane_Cache_frees', + 114: 'DB_PERF_SEL_flush_expanded_stencil', + 115: 'DB_PERF_SEL_flush_compressed_stencil', + 116: 'DB_PERF_SEL_flush_single_stencil', + 117: 'DB_PERF_SEL_planes_flushed', + 118: 'DB_PERF_SEL_flush_1plane', + 119: 'DB_PERF_SEL_flush_2plane', + 120: 'DB_PERF_SEL_flush_3plane', + 121: 'DB_PERF_SEL_flush_4plane', + 122: 'DB_PERF_SEL_flush_5plane', + 123: 'DB_PERF_SEL_flush_6plane', + 124: 'DB_PERF_SEL_flush_7plane', + 125: 'DB_PERF_SEL_flush_8plane', + 126: 'DB_PERF_SEL_flush_9plane', + 127: 'DB_PERF_SEL_flush_10plane', + 128: 'DB_PERF_SEL_flush_11plane', + 129: 'DB_PERF_SEL_flush_12plane', + 130: 'DB_PERF_SEL_flush_13plane', + 131: 'DB_PERF_SEL_flush_14plane', + 132: 'DB_PERF_SEL_flush_15plane', + 133: 'DB_PERF_SEL_flush_16plane', + 134: 'DB_PERF_SEL_flush_expanded_z', + 135: 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 136: 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 137: 'DB_PERF_SEL_dk_tile_sends', + 138: 'DB_PERF_SEL_dk_tile_busy', + 139: 'DB_PERF_SEL_dk_tile_quad_starves', + 140: 'DB_PERF_SEL_dk_tile_stalls', + 141: 'DB_PERF_SEL_dk_squad_sends', + 142: 'DB_PERF_SEL_dk_squad_busy', + 143: 'DB_PERF_SEL_dk_squad_stalls', + 144: 'DB_PERF_SEL_Op_Pipe_Busy', + 145: 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 146: 'DB_PERF_SEL_qc_busy', + 147: 'DB_PERF_SEL_qc_xfc', + 148: 'DB_PERF_SEL_qc_conflicts', + 149: 'DB_PERF_SEL_qc_full_stall', + 150: 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', + 151: 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 152: 'DB_PERF_SEL_tsc_insert_summarize_stall', + 153: 'DB_PERF_SEL_tl_busy', + 154: 'DB_PERF_SEL_tl_dtc_read_starved', + 155: 'DB_PERF_SEL_tl_z_fetch_stall', + 156: 'DB_PERF_SEL_tl_stencil_stall', + 157: 'DB_PERF_SEL_tl_z_decompress_stall', + 158: 'DB_PERF_SEL_tl_stencil_locked_stall', + 159: 'DB_PERF_SEL_tl_events', + 160: 'DB_PERF_SEL_tl_summarize_squads', + 161: 'DB_PERF_SEL_tl_flush_expand_squads', + 162: 'DB_PERF_SEL_tl_expand_squads', + 163: 'DB_PERF_SEL_tl_preZ_squads', + 164: 'DB_PERF_SEL_tl_postZ_squads', + 165: 'DB_PERF_SEL_tl_preZ_noop_squads', + 166: 'DB_PERF_SEL_tl_postZ_noop_squads', + 167: 'DB_PERF_SEL_tl_tile_ops', + 168: 'DB_PERF_SEL_tl_in_xfc', + 169: 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 170: 'DB_PERF_SEL_tl_in_fast_z_stall', + 171: 'DB_PERF_SEL_tl_out_xfc', + 172: 'DB_PERF_SEL_tl_out_squads', + 173: 'DB_PERF_SEL_zf_plane_multicycle', + 174: 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 175: 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 176: 'DB_PERF_SEL_PostZ_Samples_failing_S', + 177: 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 178: 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 179: 'DB_PERF_SEL_PreZ_Samples_failing_S', + 180: 'DB_PERF_SEL_ts_tc_update_stall', + 181: 'DB_PERF_SEL_sc_kick_start', + 182: 'DB_PERF_SEL_sc_kick_end', + 183: 'DB_PERF_SEL_clock_reg_active', + 184: 'DB_PERF_SEL_clock_main_active', + 185: 'DB_PERF_SEL_clock_mem_export_active', + 186: 'DB_PERF_SEL_esr_ps_out_busy', + 187: 'DB_PERF_SEL_esr_ps_lqf_busy', + 188: 'DB_PERF_SEL_esr_ps_lqf_stall', + 189: 'DB_PERF_SEL_etr_out_send', + 190: 'DB_PERF_SEL_etr_out_busy', + 191: 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 193: 'DB_PERF_SEL_etr_out_esr_stall', + 194: 'DB_PERF_SEL_esr_ps_vic_busy', + 195: 'DB_PERF_SEL_esr_ps_vic_stall', + 196: 'DB_PERF_SEL_esr_eot_fwd_busy', + 197: 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 198: 'DB_PERF_SEL_esr_eot_fwd_forward', + 199: 'DB_PERF_SEL_esr_sqq_zi_busy', + 200: 'DB_PERF_SEL_esr_sqq_zi_stall', + 201: 'DB_PERF_SEL_postzl_sq_pt_busy', + 202: 'DB_PERF_SEL_postzl_sq_pt_stall', + 203: 'DB_PERF_SEL_postzl_se_busy', + 204: 'DB_PERF_SEL_postzl_se_stall', + 205: 'DB_PERF_SEL_postzl_partial_launch', + 206: 'DB_PERF_SEL_postzl_full_launch', + 207: 'DB_PERF_SEL_postzl_partial_waiting', + 208: 'DB_PERF_SEL_postzl_tile_mem_stall', + 209: 'DB_PERF_SEL_postzl_tile_init_stall', + 210: 'DB_PERF_SEL_prezl_tile_mem_stall', + 211: 'DB_PERF_SEL_prezl_tile_init_stall', + 212: 'DB_PERF_SEL_dtt_sm_clash_stall', + 213: 'DB_PERF_SEL_dtt_sm_slot_stall', + 214: 'DB_PERF_SEL_dtt_sm_miss_stall', + 215: 'DB_PERF_SEL_mi_rdreq_busy', + 216: 'DB_PERF_SEL_mi_rdreq_stall', + 217: 'DB_PERF_SEL_mi_wrreq_busy', + 218: 'DB_PERF_SEL_mi_wrreq_stall', + 219: 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 220: 'DB_PERF_SEL_dkg_tile_rate_tile', + 221: 'DB_PERF_SEL_prezl_src_in_sends', + 222: 'DB_PERF_SEL_prezl_src_in_stall', + 223: 'DB_PERF_SEL_prezl_src_in_squads', + 224: 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 225: 'DB_PERF_SEL_prezl_src_in_tile_rate', + 226: 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 227: 'DB_PERF_SEL_prezl_src_out_stall', + 228: 'DB_PERF_SEL_postzl_src_in_sends', + 229: 'DB_PERF_SEL_postzl_src_in_stall', + 230: 'DB_PERF_SEL_postzl_src_in_squads', + 231: 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 232: 'DB_PERF_SEL_postzl_src_in_tile_rate', + 233: 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 234: 'DB_PERF_SEL_postzl_src_out_stall', + 235: 'DB_PERF_SEL_esr_ps_src_in_sends', + 236: 'DB_PERF_SEL_esr_ps_src_in_stall', + 237: 'DB_PERF_SEL_esr_ps_src_in_squads', + 238: 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 239: 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 240: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 241: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 242: 'DB_PERF_SEL_esr_ps_src_out_stall', + 243: 'DB_PERF_SEL_depth_bounds_tile_culled', + 244: 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 245: 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 246: 'DB_PERF_SEL_flush_compressed', + 247: 'DB_PERF_SEL_flush_plane_le4', + 248: 'DB_PERF_SEL_tiles_z_fully_summarized', + 249: 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 250: 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 251: 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 252: 'DB_PERF_SEL_tiles_decomp_on_expclear', + 253: 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 254: 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 255: 'DB_PERF_SEL_Op_Pipe_Postz_Busy', + 256: 'DB_PERF_SEL_di_dt_stall', + 258: 'DB_PERF_SEL_DB_SC_s_tile_rate', + 259: 'DB_PERF_SEL_DB_SC_c_tile_rate', + 260: 'DB_PERF_SEL_DB_SC_z_tile_rate', + 261: 'DB_PERF_SEL_DB_CB_export_export_quads', + 262: 'DB_PERF_SEL_DB_CB_export_double_format', + 263: 'DB_PERF_SEL_DB_CB_export_fast_format', + 264: 'DB_PERF_SEL_DB_CB_export_slow_format', + 265: 'DB_PERF_SEL_CB_DB_rdreq_sends', + 266: 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 267: 'DB_PERF_SEL_CB_DB_wrreq_sends', + 268: 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 269: 'DB_PERF_SEL_DB_CB_rdret_ack', + 270: 'DB_PERF_SEL_DB_CB_rdret_nack', + 271: 'DB_PERF_SEL_DB_CB_wrret_ack', + 272: 'DB_PERF_SEL_DB_CB_wrret_nack', + 273: 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 274: 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 275: 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 276: 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 277: 'DB_PERF_SEL_unmapped_z_tile_culled', + 278: 'DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_DB_DATA_TS', + 279: 'DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 280: 'DB_PERF_SEL_DB_CB_export_is_event_BOTTOM_OF_PIPE_TS', + 281: 'DB_PERF_SEL_DB_CB_export_waiting_for_perfcounter_stop_event', + 282: 'DB_PERF_SEL_DB_CB_export_fmt_32bpp_8pix', + 283: 'DB_PERF_SEL_DB_CB_export_fmt_16_16_unsigned_8pix', + 284: 'DB_PERF_SEL_DB_CB_export_fmt_16_16_signed_8pix', + 285: 'DB_PERF_SEL_DB_CB_export_fmt_16_16_float_8pix', + 286: 'DB_PERF_SEL_DB_CB_export_num_pixels_need_blending', + 287: 'DB_PERF_SEL_DB_CB_context_dones', + 288: 'DB_PERF_SEL_DB_CB_eop_dones', + 289: 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 290: 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 291: 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 292: 'DB_PERF_SEL_SC_DB_tile_backface', + 293: 'DB_PERF_SEL_SC_DB_quad_quads', + 294: 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 295: 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 296: 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 297: 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 298: 'DB_PERF_SEL_DB_SC_quad_double_quad', + 299: 'DB_PERF_SEL_SX_DB_quad_export_quads', + 300: 'DB_PERF_SEL_SX_DB_quad_double_format', + 301: 'DB_PERF_SEL_SX_DB_quad_fast_format', + 302: 'DB_PERF_SEL_SX_DB_quad_slow_format', + 303: 'DB_PERF_SEL_quad_rd_sends_unc', + 304: 'DB_PERF_SEL_quad_rd_mi_stall_unc', + 305: 'DB_PERF_SEL_SC_DB_tile_tiles_pipe0', + 306: 'DB_PERF_SEL_SC_DB_tile_tiles_pipe1', + 307: 'DB_PERF_SEL_SC_DB_quad_quads_pipe0', + 308: 'DB_PERF_SEL_SC_DB_quad_quads_pipe1', + 309: 'DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits', + 310: 'DB_PERF_SEL_noz_waiting_for_postz_done', + 311: 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x1', + 312: 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x1', + 313: 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x2', + 314: 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x2', + 315: 'DB_PERF_SEL_RMI_rd_tile_32byte_req', + 316: 'DB_PERF_SEL_RMI_rd_z_32byte_req', + 317: 'DB_PERF_SEL_RMI_rd_s_32byte_req', + 318: 'DB_PERF_SEL_RMI_wr_tile_32byte_req', + 319: 'DB_PERF_SEL_RMI_wr_z_32byte_req', + 320: 'DB_PERF_SEL_RMI_wr_s_32byte_req', + 321: 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_req', + 322: 'DB_PERF_SEL_RMI_rd_tile_32byte_ret', + 323: 'DB_PERF_SEL_RMI_rd_z_32byte_ret', + 324: 'DB_PERF_SEL_RMI_rd_s_32byte_ret', + 325: 'DB_PERF_SEL_RMI_wr_tile_32byte_ack', + 326: 'DB_PERF_SEL_RMI_wr_z_32byte_ack', + 327: 'DB_PERF_SEL_RMI_wr_s_32byte_ack', + 328: 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack', + 329: 'DB_PERF_SEL_esr_vic_sqq_busy', + 330: 'DB_PERF_SEL_esr_vic_sqq_stall', + 331: 'DB_PERF_SEL_esr_psi_vic_tile_rate', + 332: 'DB_PERF_SEL_esr_vic_footprint_match_2x2', + 333: 'DB_PERF_SEL_esr_vic_footprint_match_2x1', + 334: 'DB_PERF_SEL_esr_vic_footprint_match_1x2', + 335: 'DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels', + 336: 'DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels', + 337: 'DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels', + 338: 'DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1', + 339: 'DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1', + 340: 'DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut', + 341: 'DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut', + 342: 'DB_PERF_SEL_prez_ps_invoked_pixel_cnt', + 343: 'DB_PERF_SEL_postz_ps_invoked_pixel_cnt', + 344: 'DB_PERF_SEL_ts_events_pws_enable', + 345: 'DB_PERF_SEL_ps_events_pws_enable', + 346: 'DB_PERF_SEL_cs_events_pws_enable', + 347: 'DB_PERF_SEL_DB_SC_quad_noz_tiles', + 348: 'DB_PERF_SEL_DB_SC_quad_lit_noz_quad', + 349: 'DB_PERF_SEL_DB_SC_quad_conflicts', + 350: 'DB_PERF_SEL_SC_DB_quad_vrs_1x1', + 351: 'DB_PERF_SEL_SC_DB_quad_vrs_1x2', + 352: 'DB_PERF_SEL_SC_DB_quad_vrs_2x1', + 353: 'DB_PERF_SEL_SC_DB_quad_vrs_2x2', + 354: 'DB_PERF_SEL_SC_DB_quad_vrs_2x_ssaa', + 355: 'DB_PERF_SEL_SC_DB_quad_vrs_4x_ssaa', + 356: 'DB_PERF_SEL_SC_DB_quad_vrs_8x_ssaa', + 357: 'DB_PERF_SEL_SC_DB_wave_sends', + 358: 'DB_PERF_SEL_SC_DB_wave_busy', + 359: 'DB_PERF_SEL_SC_DB_wave_quads', + 360: 'DB_PERF_SEL_SC_DB_wave_id_wrapped', + 361: 'DB_PERF_SEL_DB_SC_wave_sends', + 362: 'DB_PERF_SEL_DB_SC_wave_busy', + 363: 'DB_PERF_SEL_DB_SC_wave_stalls', + 364: 'DB_PERF_SEL_DB_SC_wave_conflict', + 365: 'DB_PERF_SEL_DB_SC_wave_hard_conflict', + 366: 'DB_PERF_SEL_DB_SC_wave_id_wrapped', + 367: 'DB_PERF_SEL_SX_DB_quad_waves', + 368: 'DB_PERF_SEL_pws_stall', + 369: 'DB_PERF_SEL_pws_liveness_stall_dtt_tag', + 370: 'DB_PERF_SEL_pws_liveness_stall_tcp_cache_mgr', + 371: 'DB_PERF_SEL_OREO_TT_load', + 372: 'DB_PERF_SEL_OREO_TT_read', + 373: 'DB_PERF_SEL_OREO_TT_stalls', + 374: 'DB_PERF_SEL_OREO_ST_load', + 375: 'DB_PERF_SEL_OREO_ST_read', + 376: 'DB_PERF_SEL_OREO_ST_stalls', + 377: 'DB_PERF_SEL_OREO_WT_load', + 378: 'DB_PERF_SEL_OREO_WT_read', + 379: 'DB_PERF_SEL_OREO_SB_misses', + 380: 'DB_PERF_SEL_OREO_SB_hits', + 381: 'DB_PERF_SEL_OREO_SB_evicts', + 382: 'DB_PERF_SEL_OREO_SB_stalls', + 383: 'DB_PERF_SEL_OREO_Events_load', + 384: 'DB_PERF_SEL_OREO_Events_transition', + 385: 'DB_PERF_SEL_OREO_Events_non_transition', + 386: 'DB_PERF_SEL_OREO_Events_delayed', + 387: 'DB_PERF_SEL_OREO_Events_stalls', +} +DB_PERF_SEL_SC_DB_tile_sends = 0 +DB_PERF_SEL_SC_DB_tile_busy = 1 +DB_PERF_SEL_SC_DB_tile_stalls = 2 +DB_PERF_SEL_SC_DB_tile_events = 3 +DB_PERF_SEL_SC_DB_tile_tiles = 4 +DB_PERF_SEL_SC_DB_tile_covered = 5 +DB_PERF_SEL_hiz_tc_read_starved = 6 +DB_PERF_SEL_hiz_tc_write_stall = 7 +DB_PERF_SEL_hiz_tile_culled = 8 +DB_PERF_SEL_his_tile_culled = 9 +DB_PERF_SEL_DB_SC_tile_sends = 10 +DB_PERF_SEL_DB_SC_tile_busy = 11 +DB_PERF_SEL_DB_SC_tile_stalls = 12 +DB_PERF_SEL_DB_SC_tile_df_stalls = 13 +DB_PERF_SEL_DB_SC_tile_tiles = 14 +DB_PERF_SEL_DB_SC_tile_culled = 15 +DB_PERF_SEL_DB_SC_tile_hier_kill = 16 +DB_PERF_SEL_DB_SC_tile_fast_ops = 17 +DB_PERF_SEL_DB_SC_tile_no_ops = 18 +DB_PERF_SEL_DB_SC_tile_tile_rate = 19 +DB_PERF_SEL_DB_SC_tile_ssaa_kill = 20 +DB_PERF_SEL_DB_SC_tile_fast_z_ops = 21 +DB_PERF_SEL_DB_SC_tile_fast_stencil_ops = 22 +DB_PERF_SEL_SC_DB_quad_sends = 23 +DB_PERF_SEL_SC_DB_quad_busy = 24 +DB_PERF_SEL_SC_DB_quad_squads = 25 +DB_PERF_SEL_SC_DB_quad_tiles = 26 +DB_PERF_SEL_SC_DB_quad_pixels = 27 +DB_PERF_SEL_SC_DB_quad_killed_tiles = 28 +DB_PERF_SEL_DB_SC_quad_sends = 29 +DB_PERF_SEL_DB_SC_quad_busy = 30 +DB_PERF_SEL_DB_SC_quad_stalls = 31 +DB_PERF_SEL_DB_SC_quad_tiles = 32 +DB_PERF_SEL_DB_SC_quad_lit_quad = 33 +DB_PERF_SEL_DB_CB_export_events = 34 +DB_PERF_SEL_SX_DB_quad_sends = 37 +DB_PERF_SEL_SX_DB_quad_busy = 38 +DB_PERF_SEL_SX_DB_quad_stalls = 39 +DB_PERF_SEL_SX_DB_quad_quads = 40 +DB_PERF_SEL_SX_DB_quad_pixels = 41 +DB_PERF_SEL_SX_DB_quad_exports = 42 +DB_PERF_SEL_SH_quads_outstanding_sum = 43 +DB_PERF_SEL_DB_CB_export_sends = 44 +DB_PERF_SEL_DB_CB_export_busy = 45 +DB_PERF_SEL_DB_CB_export_stalls = 46 +DB_PERF_SEL_DB_CB_export_quads = 47 +DB_PERF_SEL_tile_rd_sends = 48 +DB_PERF_SEL_mi_tile_rd_outstanding_sum = 49 +DB_PERF_SEL_quad_rd_sends = 50 +DB_PERF_SEL_quad_rd_busy = 51 +DB_PERF_SEL_quad_rd_mi_stall = 52 +DB_PERF_SEL_quad_rd_rw_collision = 53 +DB_PERF_SEL_quad_rd_tag_stall = 54 +DB_PERF_SEL_quad_rd_32byte_reqs = 55 +DB_PERF_SEL_quad_rd_panic = 56 +DB_PERF_SEL_mi_quad_rd_outstanding_sum = 57 +DB_PERF_SEL_quad_rdret_sends = 58 +DB_PERF_SEL_quad_rdret_busy = 59 +DB_PERF_SEL_tile_wr_sends = 60 +DB_PERF_SEL_tile_wr_acks = 61 +DB_PERF_SEL_mi_tile_wr_outstanding_sum = 62 +DB_PERF_SEL_quad_wr_sends = 63 +DB_PERF_SEL_quad_wr_busy = 64 +DB_PERF_SEL_quad_wr_mi_stall = 65 +DB_PERF_SEL_quad_wr_coherency_stall = 66 +DB_PERF_SEL_quad_wr_acks = 67 +DB_PERF_SEL_mi_quad_wr_outstanding_sum = 68 +DB_PERF_SEL_Tile_Cache_misses = 69 +DB_PERF_SEL_Tile_Cache_hits = 70 +DB_PERF_SEL_Tile_Cache_flushes = 71 +DB_PERF_SEL_Tile_Cache_surface_stall = 72 +DB_PERF_SEL_Tile_Cache_starves = 73 +DB_PERF_SEL_Tile_Cache_mem_return_starve = 74 +DB_PERF_SEL_tcp_dispatcher_reads = 75 +DB_PERF_SEL_tcp_prefetcher_reads = 76 +DB_PERF_SEL_tcp_preloader_reads = 77 +DB_PERF_SEL_tcp_dispatcher_flushes = 78 +DB_PERF_SEL_tcp_prefetcher_flushes = 79 +DB_PERF_SEL_tcp_preloader_flushes = 80 +DB_PERF_SEL_Depth_Tile_Cache_sends = 81 +DB_PERF_SEL_Depth_Tile_Cache_busy = 82 +DB_PERF_SEL_Depth_Tile_Cache_starves = 83 +DB_PERF_SEL_Depth_Tile_Cache_dtile_locked = 84 +DB_PERF_SEL_Depth_Tile_Cache_alloc_stall = 85 +DB_PERF_SEL_Depth_Tile_Cache_misses = 86 +DB_PERF_SEL_Depth_Tile_Cache_hits = 87 +DB_PERF_SEL_Depth_Tile_Cache_flushes = 88 +DB_PERF_SEL_Depth_Tile_Cache_noop_tile = 89 +DB_PERF_SEL_Depth_Tile_Cache_detailed_noop = 90 +DB_PERF_SEL_Depth_Tile_Cache_event = 91 +DB_PERF_SEL_Depth_Tile_Cache_tile_frees = 92 +DB_PERF_SEL_Depth_Tile_Cache_data_frees = 93 +DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve = 94 +DB_PERF_SEL_Stencil_Cache_misses = 95 +DB_PERF_SEL_Stencil_Cache_hits = 96 +DB_PERF_SEL_Stencil_Cache_flushes = 97 +DB_PERF_SEL_Stencil_Cache_starves = 98 +DB_PERF_SEL_Stencil_Cache_frees = 99 +DB_PERF_SEL_Z_Cache_separate_Z_misses = 100 +DB_PERF_SEL_Z_Cache_separate_Z_hits = 101 +DB_PERF_SEL_Z_Cache_separate_Z_flushes = 102 +DB_PERF_SEL_Z_Cache_separate_Z_starves = 103 +DB_PERF_SEL_Z_Cache_pmask_misses = 104 +DB_PERF_SEL_Z_Cache_pmask_hits = 105 +DB_PERF_SEL_Z_Cache_pmask_flushes = 106 +DB_PERF_SEL_Z_Cache_pmask_starves = 107 +DB_PERF_SEL_Z_Cache_frees = 108 +DB_PERF_SEL_Plane_Cache_misses = 109 +DB_PERF_SEL_Plane_Cache_hits = 110 +DB_PERF_SEL_Plane_Cache_flushes = 111 +DB_PERF_SEL_Plane_Cache_starves = 112 +DB_PERF_SEL_Plane_Cache_frees = 113 +DB_PERF_SEL_flush_expanded_stencil = 114 +DB_PERF_SEL_flush_compressed_stencil = 115 +DB_PERF_SEL_flush_single_stencil = 116 +DB_PERF_SEL_planes_flushed = 117 +DB_PERF_SEL_flush_1plane = 118 +DB_PERF_SEL_flush_2plane = 119 +DB_PERF_SEL_flush_3plane = 120 +DB_PERF_SEL_flush_4plane = 121 +DB_PERF_SEL_flush_5plane = 122 +DB_PERF_SEL_flush_6plane = 123 +DB_PERF_SEL_flush_7plane = 124 +DB_PERF_SEL_flush_8plane = 125 +DB_PERF_SEL_flush_9plane = 126 +DB_PERF_SEL_flush_10plane = 127 +DB_PERF_SEL_flush_11plane = 128 +DB_PERF_SEL_flush_12plane = 129 +DB_PERF_SEL_flush_13plane = 130 +DB_PERF_SEL_flush_14plane = 131 +DB_PERF_SEL_flush_15plane = 132 +DB_PERF_SEL_flush_16plane = 133 +DB_PERF_SEL_flush_expanded_z = 134 +DB_PERF_SEL_earlyZ_waiting_for_postZ_done = 135 +DB_PERF_SEL_reZ_waiting_for_postZ_done = 136 +DB_PERF_SEL_dk_tile_sends = 137 +DB_PERF_SEL_dk_tile_busy = 138 +DB_PERF_SEL_dk_tile_quad_starves = 139 +DB_PERF_SEL_dk_tile_stalls = 140 +DB_PERF_SEL_dk_squad_sends = 141 +DB_PERF_SEL_dk_squad_busy = 142 +DB_PERF_SEL_dk_squad_stalls = 143 +DB_PERF_SEL_Op_Pipe_Busy = 144 +DB_PERF_SEL_Op_Pipe_MC_Read_stall = 145 +DB_PERF_SEL_qc_busy = 146 +DB_PERF_SEL_qc_xfc = 147 +DB_PERF_SEL_qc_conflicts = 148 +DB_PERF_SEL_qc_full_stall = 149 +DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ = 150 +DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ = 151 +DB_PERF_SEL_tsc_insert_summarize_stall = 152 +DB_PERF_SEL_tl_busy = 153 +DB_PERF_SEL_tl_dtc_read_starved = 154 +DB_PERF_SEL_tl_z_fetch_stall = 155 +DB_PERF_SEL_tl_stencil_stall = 156 +DB_PERF_SEL_tl_z_decompress_stall = 157 +DB_PERF_SEL_tl_stencil_locked_stall = 158 +DB_PERF_SEL_tl_events = 159 +DB_PERF_SEL_tl_summarize_squads = 160 +DB_PERF_SEL_tl_flush_expand_squads = 161 +DB_PERF_SEL_tl_expand_squads = 162 +DB_PERF_SEL_tl_preZ_squads = 163 +DB_PERF_SEL_tl_postZ_squads = 164 +DB_PERF_SEL_tl_preZ_noop_squads = 165 +DB_PERF_SEL_tl_postZ_noop_squads = 166 +DB_PERF_SEL_tl_tile_ops = 167 +DB_PERF_SEL_tl_in_xfc = 168 +DB_PERF_SEL_tl_in_single_stencil_expand_stall = 169 +DB_PERF_SEL_tl_in_fast_z_stall = 170 +DB_PERF_SEL_tl_out_xfc = 171 +DB_PERF_SEL_tl_out_squads = 172 +DB_PERF_SEL_zf_plane_multicycle = 173 +DB_PERF_SEL_PostZ_Samples_passing_Z = 174 +DB_PERF_SEL_PostZ_Samples_failing_Z = 175 +DB_PERF_SEL_PostZ_Samples_failing_S = 176 +DB_PERF_SEL_PreZ_Samples_passing_Z = 177 +DB_PERF_SEL_PreZ_Samples_failing_Z = 178 +DB_PERF_SEL_PreZ_Samples_failing_S = 179 +DB_PERF_SEL_ts_tc_update_stall = 180 +DB_PERF_SEL_sc_kick_start = 181 +DB_PERF_SEL_sc_kick_end = 182 +DB_PERF_SEL_clock_reg_active = 183 +DB_PERF_SEL_clock_main_active = 184 +DB_PERF_SEL_clock_mem_export_active = 185 +DB_PERF_SEL_esr_ps_out_busy = 186 +DB_PERF_SEL_esr_ps_lqf_busy = 187 +DB_PERF_SEL_esr_ps_lqf_stall = 188 +DB_PERF_SEL_etr_out_send = 189 +DB_PERF_SEL_etr_out_busy = 190 +DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall = 191 +DB_PERF_SEL_etr_out_esr_stall = 193 +DB_PERF_SEL_esr_ps_vic_busy = 194 +DB_PERF_SEL_esr_ps_vic_stall = 195 +DB_PERF_SEL_esr_eot_fwd_busy = 196 +DB_PERF_SEL_esr_eot_fwd_holding_squad = 197 +DB_PERF_SEL_esr_eot_fwd_forward = 198 +DB_PERF_SEL_esr_sqq_zi_busy = 199 +DB_PERF_SEL_esr_sqq_zi_stall = 200 +DB_PERF_SEL_postzl_sq_pt_busy = 201 +DB_PERF_SEL_postzl_sq_pt_stall = 202 +DB_PERF_SEL_postzl_se_busy = 203 +DB_PERF_SEL_postzl_se_stall = 204 +DB_PERF_SEL_postzl_partial_launch = 205 +DB_PERF_SEL_postzl_full_launch = 206 +DB_PERF_SEL_postzl_partial_waiting = 207 +DB_PERF_SEL_postzl_tile_mem_stall = 208 +DB_PERF_SEL_postzl_tile_init_stall = 209 +DB_PERF_SEL_prezl_tile_mem_stall = 210 +DB_PERF_SEL_prezl_tile_init_stall = 211 +DB_PERF_SEL_dtt_sm_clash_stall = 212 +DB_PERF_SEL_dtt_sm_slot_stall = 213 +DB_PERF_SEL_dtt_sm_miss_stall = 214 +DB_PERF_SEL_mi_rdreq_busy = 215 +DB_PERF_SEL_mi_rdreq_stall = 216 +DB_PERF_SEL_mi_wrreq_busy = 217 +DB_PERF_SEL_mi_wrreq_stall = 218 +DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop = 219 +DB_PERF_SEL_dkg_tile_rate_tile = 220 +DB_PERF_SEL_prezl_src_in_sends = 221 +DB_PERF_SEL_prezl_src_in_stall = 222 +DB_PERF_SEL_prezl_src_in_squads = 223 +DB_PERF_SEL_prezl_src_in_squads_unrolled = 224 +DB_PERF_SEL_prezl_src_in_tile_rate = 225 +DB_PERF_SEL_prezl_src_in_tile_rate_unrolled = 226 +DB_PERF_SEL_prezl_src_out_stall = 227 +DB_PERF_SEL_postzl_src_in_sends = 228 +DB_PERF_SEL_postzl_src_in_stall = 229 +DB_PERF_SEL_postzl_src_in_squads = 230 +DB_PERF_SEL_postzl_src_in_squads_unrolled = 231 +DB_PERF_SEL_postzl_src_in_tile_rate = 232 +DB_PERF_SEL_postzl_src_in_tile_rate_unrolled = 233 +DB_PERF_SEL_postzl_src_out_stall = 234 +DB_PERF_SEL_esr_ps_src_in_sends = 235 +DB_PERF_SEL_esr_ps_src_in_stall = 236 +DB_PERF_SEL_esr_ps_src_in_squads = 237 +DB_PERF_SEL_esr_ps_src_in_squads_unrolled = 238 +DB_PERF_SEL_esr_ps_src_in_tile_rate = 239 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled = 240 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate = 241 +DB_PERF_SEL_esr_ps_src_out_stall = 242 +DB_PERF_SEL_depth_bounds_tile_culled = 243 +DB_PERF_SEL_PreZ_Samples_failing_DB = 244 +DB_PERF_SEL_PostZ_Samples_failing_DB = 245 +DB_PERF_SEL_flush_compressed = 246 +DB_PERF_SEL_flush_plane_le4 = 247 +DB_PERF_SEL_tiles_z_fully_summarized = 248 +DB_PERF_SEL_tiles_stencil_fully_summarized = 249 +DB_PERF_SEL_tiles_z_clear_on_expclear = 250 +DB_PERF_SEL_tiles_s_clear_on_expclear = 251 +DB_PERF_SEL_tiles_decomp_on_expclear = 252 +DB_PERF_SEL_tiles_compressed_to_decompressed = 253 +DB_PERF_SEL_Op_Pipe_Prez_Busy = 254 +DB_PERF_SEL_Op_Pipe_Postz_Busy = 255 +DB_PERF_SEL_di_dt_stall = 256 +DB_PERF_SEL_DB_SC_s_tile_rate = 258 +DB_PERF_SEL_DB_SC_c_tile_rate = 259 +DB_PERF_SEL_DB_SC_z_tile_rate = 260 +DB_PERF_SEL_DB_CB_export_export_quads = 261 +DB_PERF_SEL_DB_CB_export_double_format = 262 +DB_PERF_SEL_DB_CB_export_fast_format = 263 +DB_PERF_SEL_DB_CB_export_slow_format = 264 +DB_PERF_SEL_CB_DB_rdreq_sends = 265 +DB_PERF_SEL_CB_DB_rdreq_prt_sends = 266 +DB_PERF_SEL_CB_DB_wrreq_sends = 267 +DB_PERF_SEL_CB_DB_wrreq_prt_sends = 268 +DB_PERF_SEL_DB_CB_rdret_ack = 269 +DB_PERF_SEL_DB_CB_rdret_nack = 270 +DB_PERF_SEL_DB_CB_wrret_ack = 271 +DB_PERF_SEL_DB_CB_wrret_nack = 272 +DB_PERF_SEL_MI_tile_req_wrack_counter_stall = 273 +DB_PERF_SEL_MI_quad_req_wrack_counter_stall = 274 +DB_PERF_SEL_MI_zpc_req_wrack_counter_stall = 275 +DB_PERF_SEL_MI_psd_req_wrack_counter_stall = 276 +DB_PERF_SEL_unmapped_z_tile_culled = 277 +DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_DB_DATA_TS = 278 +DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_CB_PIXEL_DATA = 279 +DB_PERF_SEL_DB_CB_export_is_event_BOTTOM_OF_PIPE_TS = 280 +DB_PERF_SEL_DB_CB_export_waiting_for_perfcounter_stop_event = 281 +DB_PERF_SEL_DB_CB_export_fmt_32bpp_8pix = 282 +DB_PERF_SEL_DB_CB_export_fmt_16_16_unsigned_8pix = 283 +DB_PERF_SEL_DB_CB_export_fmt_16_16_signed_8pix = 284 +DB_PERF_SEL_DB_CB_export_fmt_16_16_float_8pix = 285 +DB_PERF_SEL_DB_CB_export_num_pixels_need_blending = 286 +DB_PERF_SEL_DB_CB_context_dones = 287 +DB_PERF_SEL_DB_CB_eop_dones = 288 +DB_PERF_SEL_SX_DB_quad_all_pixels_killed = 289 +DB_PERF_SEL_SX_DB_quad_all_pixels_enabled = 290 +DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read = 291 +DB_PERF_SEL_SC_DB_tile_backface = 292 +DB_PERF_SEL_SC_DB_quad_quads = 293 +DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel = 294 +DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels = 295 +DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels = 296 +DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels = 297 +DB_PERF_SEL_DB_SC_quad_double_quad = 298 +DB_PERF_SEL_SX_DB_quad_export_quads = 299 +DB_PERF_SEL_SX_DB_quad_double_format = 300 +DB_PERF_SEL_SX_DB_quad_fast_format = 301 +DB_PERF_SEL_SX_DB_quad_slow_format = 302 +DB_PERF_SEL_quad_rd_sends_unc = 303 +DB_PERF_SEL_quad_rd_mi_stall_unc = 304 +DB_PERF_SEL_SC_DB_tile_tiles_pipe0 = 305 +DB_PERF_SEL_SC_DB_tile_tiles_pipe1 = 306 +DB_PERF_SEL_SC_DB_quad_quads_pipe0 = 307 +DB_PERF_SEL_SC_DB_quad_quads_pipe1 = 308 +DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits = 309 +DB_PERF_SEL_noz_waiting_for_postz_done = 310 +DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x1 = 311 +DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x1 = 312 +DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x2 = 313 +DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x2 = 314 +DB_PERF_SEL_RMI_rd_tile_32byte_req = 315 +DB_PERF_SEL_RMI_rd_z_32byte_req = 316 +DB_PERF_SEL_RMI_rd_s_32byte_req = 317 +DB_PERF_SEL_RMI_wr_tile_32byte_req = 318 +DB_PERF_SEL_RMI_wr_z_32byte_req = 319 +DB_PERF_SEL_RMI_wr_s_32byte_req = 320 +DB_PERF_SEL_RMI_wr_psdzpc_32byte_req = 321 +DB_PERF_SEL_RMI_rd_tile_32byte_ret = 322 +DB_PERF_SEL_RMI_rd_z_32byte_ret = 323 +DB_PERF_SEL_RMI_rd_s_32byte_ret = 324 +DB_PERF_SEL_RMI_wr_tile_32byte_ack = 325 +DB_PERF_SEL_RMI_wr_z_32byte_ack = 326 +DB_PERF_SEL_RMI_wr_s_32byte_ack = 327 +DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack = 328 +DB_PERF_SEL_esr_vic_sqq_busy = 329 +DB_PERF_SEL_esr_vic_sqq_stall = 330 +DB_PERF_SEL_esr_psi_vic_tile_rate = 331 +DB_PERF_SEL_esr_vic_footprint_match_2x2 = 332 +DB_PERF_SEL_esr_vic_footprint_match_2x1 = 333 +DB_PERF_SEL_esr_vic_footprint_match_1x2 = 334 +DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels = 335 +DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels = 336 +DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels = 337 +DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1 = 338 +DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1 = 339 +DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut = 340 +DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut = 341 +DB_PERF_SEL_prez_ps_invoked_pixel_cnt = 342 +DB_PERF_SEL_postz_ps_invoked_pixel_cnt = 343 +DB_PERF_SEL_ts_events_pws_enable = 344 +DB_PERF_SEL_ps_events_pws_enable = 345 +DB_PERF_SEL_cs_events_pws_enable = 346 +DB_PERF_SEL_DB_SC_quad_noz_tiles = 347 +DB_PERF_SEL_DB_SC_quad_lit_noz_quad = 348 +DB_PERF_SEL_DB_SC_quad_conflicts = 349 +DB_PERF_SEL_SC_DB_quad_vrs_1x1 = 350 +DB_PERF_SEL_SC_DB_quad_vrs_1x2 = 351 +DB_PERF_SEL_SC_DB_quad_vrs_2x1 = 352 +DB_PERF_SEL_SC_DB_quad_vrs_2x2 = 353 +DB_PERF_SEL_SC_DB_quad_vrs_2x_ssaa = 354 +DB_PERF_SEL_SC_DB_quad_vrs_4x_ssaa = 355 +DB_PERF_SEL_SC_DB_quad_vrs_8x_ssaa = 356 +DB_PERF_SEL_SC_DB_wave_sends = 357 +DB_PERF_SEL_SC_DB_wave_busy = 358 +DB_PERF_SEL_SC_DB_wave_quads = 359 +DB_PERF_SEL_SC_DB_wave_id_wrapped = 360 +DB_PERF_SEL_DB_SC_wave_sends = 361 +DB_PERF_SEL_DB_SC_wave_busy = 362 +DB_PERF_SEL_DB_SC_wave_stalls = 363 +DB_PERF_SEL_DB_SC_wave_conflict = 364 +DB_PERF_SEL_DB_SC_wave_hard_conflict = 365 +DB_PERF_SEL_DB_SC_wave_id_wrapped = 366 +DB_PERF_SEL_SX_DB_quad_waves = 367 +DB_PERF_SEL_pws_stall = 368 +DB_PERF_SEL_pws_liveness_stall_dtt_tag = 369 +DB_PERF_SEL_pws_liveness_stall_tcp_cache_mgr = 370 +DB_PERF_SEL_OREO_TT_load = 371 +DB_PERF_SEL_OREO_TT_read = 372 +DB_PERF_SEL_OREO_TT_stalls = 373 +DB_PERF_SEL_OREO_ST_load = 374 +DB_PERF_SEL_OREO_ST_read = 375 +DB_PERF_SEL_OREO_ST_stalls = 376 +DB_PERF_SEL_OREO_WT_load = 377 +DB_PERF_SEL_OREO_WT_read = 378 +DB_PERF_SEL_OREO_SB_misses = 379 +DB_PERF_SEL_OREO_SB_hits = 380 +DB_PERF_SEL_OREO_SB_evicts = 381 +DB_PERF_SEL_OREO_SB_stalls = 382 +DB_PERF_SEL_OREO_Events_load = 383 +DB_PERF_SEL_OREO_Events_transition = 384 +DB_PERF_SEL_OREO_Events_non_transition = 385 +DB_PERF_SEL_OREO_Events_delayed = 386 +DB_PERF_SEL_OREO_Events_stalls = 387 +PerfCounter_Vals = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeCounterId' +PixelPipeCounterId__enumvalues = { + 0: 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 1: 'PIXEL_PIPE_OCCLUSION_COUNT_1', + 2: 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 3: 'PIXEL_PIPE_OCCLUSION_COUNT_3', + 4: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 5: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 6: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', + 7: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', +} +PIXEL_PIPE_OCCLUSION_COUNT_0 = 0 +PIXEL_PIPE_OCCLUSION_COUNT_1 = 1 +PIXEL_PIPE_OCCLUSION_COUNT_2 = 2 +PIXEL_PIPE_OCCLUSION_COUNT_3 = 3 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_0 = 4 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_0 = 5 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_1 = 6 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_1 = 7 +PixelPipeCounterId = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeStride' +PixelPipeStride__enumvalues = { + 0: 'PIXEL_PIPE_STRIDE_32_BITS', + 1: 'PIXEL_PIPE_STRIDE_64_BITS', + 2: 'PIXEL_PIPE_STRIDE_128_BITS', + 3: 'PIXEL_PIPE_STRIDE_256_BITS', +} +PIXEL_PIPE_STRIDE_32_BITS = 0 +PIXEL_PIPE_STRIDE_64_BITS = 1 +PIXEL_PIPE_STRIDE_128_BITS = 2 +PIXEL_PIPE_STRIDE_256_BITS = 3 +PixelPipeStride = ctypes.c_uint32 # enum + +# values for enumeration 'RingCounterControl' +RingCounterControl__enumvalues = { + 0: 'COUNTER_RING_SPLIT', + 1: 'COUNTER_RING_0', + 2: 'COUNTER_RING_1', +} +COUNTER_RING_SPLIT = 0 +COUNTER_RING_0 = 1 +COUNTER_RING_1 = 2 +RingCounterControl = ctypes.c_uint32 # enum + +# values for enumeration 'StencilOp' +StencilOp__enumvalues = { + 0: 'STENCIL_KEEP', + 1: 'STENCIL_ZERO', + 2: 'STENCIL_ONES', + 3: 'STENCIL_REPLACE_TEST', + 4: 'STENCIL_REPLACE_OP', + 5: 'STENCIL_ADD_CLAMP', + 6: 'STENCIL_SUB_CLAMP', + 7: 'STENCIL_INVERT', + 8: 'STENCIL_ADD_WRAP', + 9: 'STENCIL_SUB_WRAP', + 10: 'STENCIL_AND', + 11: 'STENCIL_OR', + 12: 'STENCIL_XOR', + 13: 'STENCIL_NAND', + 14: 'STENCIL_NOR', + 15: 'STENCIL_XNOR', +} +STENCIL_KEEP = 0 +STENCIL_ZERO = 1 +STENCIL_ONES = 2 +STENCIL_REPLACE_TEST = 3 +STENCIL_REPLACE_OP = 4 +STENCIL_ADD_CLAMP = 5 +STENCIL_SUB_CLAMP = 6 +STENCIL_INVERT = 7 +STENCIL_ADD_WRAP = 8 +STENCIL_SUB_WRAP = 9 +STENCIL_AND = 10 +STENCIL_OR = 11 +STENCIL_XOR = 12 +STENCIL_NAND = 13 +STENCIL_NOR = 14 +STENCIL_XNOR = 15 +StencilOp = ctypes.c_uint32 # enum + +# values for enumeration 'ZLimitSumm' +ZLimitSumm__enumvalues = { + 0: 'FORCE_SUMM_OFF', + 1: 'FORCE_SUMM_MINZ', + 2: 'FORCE_SUMM_MAXZ', + 3: 'FORCE_SUMM_BOTH', +} +FORCE_SUMM_OFF = 0 +FORCE_SUMM_MINZ = 1 +FORCE_SUMM_MAXZ = 2 +FORCE_SUMM_BOTH = 3 +ZLimitSumm = ctypes.c_uint32 # enum + +# values for enumeration 'ZModeForce' +ZModeForce__enumvalues = { + 0: 'NO_FORCE', + 1: 'FORCE_EARLY_Z', + 2: 'FORCE_LATE_Z', + 3: 'FORCE_RE_Z', +} +NO_FORCE = 0 +FORCE_EARLY_Z = 1 +FORCE_LATE_Z = 2 +FORCE_RE_Z = 3 +ZModeForce = ctypes.c_uint32 # enum + +# values for enumeration 'ZOrder' +ZOrder__enumvalues = { + 0: 'LATE_Z', + 1: 'EARLY_Z_THEN_LATE_Z', + 2: 'RE_Z', + 3: 'EARLY_Z_THEN_RE_Z', +} +LATE_Z = 0 +EARLY_Z_THEN_LATE_Z = 1 +RE_Z = 2 +EARLY_Z_THEN_RE_Z = 3 +ZOrder = ctypes.c_uint32 # enum + +# values for enumeration 'ZSamplePosition' +ZSamplePosition__enumvalues = { + 0: 'Z_SAMPLE_CENTER', + 1: 'Z_SAMPLE_CENTROID', +} +Z_SAMPLE_CENTER = 0 +Z_SAMPLE_CENTROID = 1 +ZSamplePosition = ctypes.c_uint32 # enum + +# values for enumeration 'SU_PERFCNT_SEL' +SU_PERFCNT_SEL__enumvalues = { + 0: 'PERF_PAPC_PASX_REQ', + 6: 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 7: 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 8: 'PERF_CLPR_INPUT_PRIM', + 9: 'PERF_CLPR_INPUT_NULL_PRIM', + 10: 'PERF_CLPR_INPUT_EVENT', + 11: 'PERF_CLPR_INPUT_FIRST_OF_SUBGROUP', + 12: 'PERF_CLPR_INPUT_END_OF_PACKET', + 13: 'PERF_CLPR_INPUT_EXTENDED_EVENT', + 14: 'PERF_PAPC_CLPR_CULL_PRIM', + 15: 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', + 16: 'PERF_PAPC_CLPR_VV_CULL_PRIM', + 17: 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 18: 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 19: 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 20: 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 21: 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 22: 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 23: 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', + 24: 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 25: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 26: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 27: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 28: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 29: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 30: 'PERF_CLPR_CLIP_PLANE_CNT_9_PLUS', + 31: 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 32: 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', + 33: 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 34: 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 35: 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', + 36: 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 38: 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 39: 'PERF_PAPC_CLSM_NULL_PRIM', + 40: 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 41: 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', + 42: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', + 43: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 44: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', + 45: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 46: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 47: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_PLUS', + 48: 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', + 49: 'PERF_PAPC_SU_INPUT_PRIM', + 50: 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 51: 'PERF_PAPC_SU_INPUT_NULL_PRIM', + 52: 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 53: 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 54: 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 55: 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 56: 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 57: 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 58: 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 59: 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 60: 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 61: 'PERF_PAPC_SU_OUTPUT_PRIM', + 62: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 63: 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 64: 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 65: 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 66: 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', + 67: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 68: 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 69: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', + 70: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 71: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 72: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 73: 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 74: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 75: 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 76: 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 77: 'PERF_PAPC_PASX_REQ_IDLE', + 78: 'PERF_PAPC_PASX_REQ_BUSY', + 79: 'PERF_PAPC_PASX_REQ_STALLED', + 80: 'PERF_PAPC_PASX_REC_IDLE', + 81: 'PERF_PAPC_PASX_REC_BUSY', + 82: 'PERF_PAPC_PASX_REC_STARVED_SX', + 83: 'PERF_PAPC_PASX_REC_STALLED', + 84: 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 85: 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 86: 'PERF_PAPC_CCGSM_IDLE', + 87: 'PERF_PAPC_CCGSM_BUSY', + 88: 'PERF_PAPC_CCGSM_STALLED', + 89: 'PERF_PAPC_CLPRIM_IDLE', + 90: 'PERF_PAPC_CLPRIM_BUSY', + 91: 'PERF_PAPC_CLPRIM_STALLED', + 92: 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 93: 'PERF_PAPC_CLIPSM_IDLE', + 94: 'PERF_PAPC_CLIPSM_BUSY', + 95: 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 96: 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', + 97: 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 98: 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 99: 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 100: 'PERF_PAPC_CLIPGA_IDLE', + 101: 'PERF_PAPC_CLIPGA_BUSY', + 102: 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 103: 'PERF_PAPC_CLIPGA_STALLED', + 104: 'PERF_PAPC_CLIP_IDLE', + 105: 'PERF_PAPC_CLIP_BUSY', + 106: 'PERF_PAPC_SU_IDLE', + 107: 'PERF_PAPC_SU_BUSY', + 108: 'PERF_PAPC_SU_STARVED_CLIP', + 109: 'PERF_PAPC_SU_STALLED_SC', + 110: 'PERF_PAPC_CL_DYN_SCLK_VLD', + 111: 'PERF_PAPC_SU_DYN_SCLK_VLD', + 112: 'PERF_PAPC_PA_REG_SCLK_VLD', + 120: 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 121: 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 123: 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 124: 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 125: 'PERF_PAPC_SU_ALL_OUTPUT_PRIM', + 126: 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 127: 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 128: 'PERF_PAPC_SU_ALL_OUTPUT_NULL_PRIM', + 131: 'PERF_PAPC_SU_SE0_STALLED_SC', + 132: 'PERF_PAPC_SU_SE1_STALLED_SC', + 133: 'PERF_PAPC_SU_ALL_STALLED_SC', + 134: 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 135: 'PERF_PAPC_SU_CULLED_PRIM', + 136: 'PERF_PAPC_SU_OUTPUT_EOPG', + 137: 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 138: 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 139: 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 140: 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 141: 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 142: 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 151: 'PERF_PAPC_SU_SE2_STALLED_SC', + 152: 'PERF_PAPC_SU_SE3_STALLED_SC', + 153: 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', + 154: 'PERF_SMALL_PRIM_CULL_PRIM_1X1', + 155: 'PERF_SMALL_PRIM_CULL_PRIM_2X1', + 156: 'PERF_SMALL_PRIM_CULL_PRIM_1X2', + 157: 'PERF_SMALL_PRIM_CULL_PRIM_2X2', + 158: 'PERF_SMALL_PRIM_CULL_PRIM_3X1', + 159: 'PERF_SMALL_PRIM_CULL_PRIM_1X3', + 160: 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 161: 'PERF_SMALL_PRIM_CULL_PRIM_2X3', + 162: 'PERF_SMALL_PRIM_CULL_PRIM_NX1', + 163: 'PERF_SMALL_PRIM_CULL_PRIM_1XN', + 164: 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 165: 'PERF_SMALL_PRIM_CULL_PRIM_2XN', + 169: 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 170: 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 171: 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 172: 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 173: 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 174: 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 175: 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 176: 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 177: 'PERF_PA_VERTEX_FIFO_FULL', + 178: 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', + 179: 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 183: 'PERF_ENGG_CSB_MACHINE_IS_STARVED', + 184: 'PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 185: 'PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI', + 186: 'PERF_ENGG_CSB_GE_INPUT_FIFO_FULL', + 188: 'PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL', + 189: 'PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT', + 190: 'PERF_ENGG_CSB_PRIM_COUNT_EQ0', + 191: 'PERF_ENGG_CSB_NULL_SUBGROUP', + 192: 'PERF_ENGG_CSB_GE_SENDING_SUBGROUP', + 193: 'PERF_ENGG_CSB_GE_MEMORY_FULL', + 194: 'PERF_ENGG_CSB_GE_MEMORY_EMPTY', + 195: 'PERF_ENGG_CSB_SPI_MEMORY_FULL', + 196: 'PERF_ENGG_CSB_SPI_MEMORY_EMPTY', + 224: 'PERF_ENGG_INDEX_REQ_NULL_REQUEST', + 225: 'PERF_ENGG_INDEX_RET_0_NEW_VERTS_THIS_PRIM', + 226: 'PERF_ENGG_INDEX_RET_1_NEW_VERTS_THIS_PRIM', + 227: 'PERF_ENGG_INDEX_RET_2_NEW_VERTS_THIS_PRIM', + 228: 'PERF_ENGG_INDEX_RET_3_NEW_VERTS_THIS_PRIM', + 229: 'PERF_ENGG_INDEX_REQ_STARVED', + 230: 'PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 231: 'PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 232: 'PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', + 233: 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 234: 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 235: 'PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 236: 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 237: 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 238: 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 239: 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 240: 'PERF_ENGG_INDEX_RET_SXRX_READING_EVENT', + 241: 'PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 242: 'PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 243: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 244: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 245: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL', + 246: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL', + 247: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL', + 248: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 249: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 250: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL', + 251: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL', + 252: 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL', + 258: 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 259: 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 260: 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB', + 261: 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 262: 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 263: 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 264: 'PERF_ENGG_POS_REQ_STARVED', + 265: 'PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO', + 266: 'PERF_ENGG_BUSY', + 267: 'PERF_CLIPSM_CULL_PRIMS_CNT', + 268: 'PERF_PH_SEND_1_SC', + 269: 'PERF_PH_SEND_2_SC', + 270: 'PERF_PH_SEND_3_SC', + 271: 'PERF_PH_SEND_4_SC', + 272: 'PERF_OUTPUT_PRIM_1_SC', + 273: 'PERF_OUTPUT_PRIM_2_SC', + 274: 'PERF_OUTPUT_PRIM_3_SC', + 275: 'PERF_OUTPUT_PRIM_4_SC', + 276: 'PERF_PASX_POS_VECTOR', + 277: 'PERF_PASX_MISC_VECTOR', + 278: 'PERF_PASX_CCDIST0_VECTOR', + 279: 'PERF_PASX_CCDIST1_VECTOR', + 280: 'PERF_PASX_STEREO_POS_VECTOR', + 281: 'PERF_CLPR_INPUT_SEND', + 282: 'PERF_SU_INPUT_SEND', + 283: 'PERF_SU_OUTPUT_SEND', + 284: 'PERF_PAPC_SU_SE4_PRIM_FILTER_CULL', + 285: 'PERF_PAPC_SU_SE5_PRIM_FILTER_CULL', + 286: 'PERF_PAPC_SU_SE4_OUTPUT_PRIM', + 287: 'PERF_PAPC_SU_SE5_OUTPUT_PRIM', + 288: 'PERF_PAPC_SU_SE4_OUTPUT_NULL_PRIM', + 289: 'PERF_PAPC_SU_SE5_OUTPUT_NULL_PRIM', + 290: 'PERF_PAPC_SU_SE4_STALLED_SC', + 291: 'PERF_PAPC_SU_SE5_STALLED_SC', + 292: 'PERF_ENGG_INDEX_RET0_NEW_VERTS', + 293: 'PERF_ENGG_INDEX_RET1_NEW_VERTS', + 294: 'PERF_ENGG_INDEX_RET2_NEW_VERTS', + 295: 'PERF_ENGG_INDEX_RET3_NEW_VERTS', + 296: 'PERF_ENGG_INDEX_RET4_NEW_VERTS', + 297: 'PERF_ENGG_INDEX_RET5_NEW_VERTS', + 298: 'PERF_ENGG_INDEX_RET6_NEW_VERTS', + 299: 'PERF_ENGG_INDEX_RET7_NEW_VERTS', + 300: 'PERF_ENGG_INDEX_RET8_NEW_VERTS', + 301: 'PERF_ENGG_INDEX_RET9_NEW_VERTS', + 302: 'PERF_ENGG_INDEX_RET10_NEW_VERTS', + 303: 'PERF_ENGG_INDEX_RET11_NEW_VERTS', + 304: 'PERF_ENGG_INDEX_RET12_NEW_VERTS', + 305: 'PERF_PH_SEND_5_SC', + 306: 'PERF_PH_SEND_6_SC', + 307: 'PERF_OUTPUT_PRIM_5_SC', + 308: 'PERF_OUTPUT_PRIM_6_SC', + 309: 'PERF_CLPR_BACK_PRIM', + 310: 'PERF_PA_BUSY', +} +PERF_PAPC_PASX_REQ = 0 +PERF_PAPC_PASX_VTX_KILL_DISCARD = 6 +PERF_PAPC_PASX_VTX_NAN_DISCARD = 7 +PERF_CLPR_INPUT_PRIM = 8 +PERF_CLPR_INPUT_NULL_PRIM = 9 +PERF_CLPR_INPUT_EVENT = 10 +PERF_CLPR_INPUT_FIRST_OF_SUBGROUP = 11 +PERF_CLPR_INPUT_END_OF_PACKET = 12 +PERF_CLPR_INPUT_EXTENDED_EVENT = 13 +PERF_PAPC_CLPR_CULL_PRIM = 14 +PERF_PAPC_CLPR_VVUCP_CULL_PRIM = 15 +PERF_PAPC_CLPR_VV_CULL_PRIM = 16 +PERF_PAPC_CLPR_UCP_CULL_PRIM = 17 +PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM = 18 +PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM = 19 +PERF_PAPC_CLPR_CULL_TO_NULL_PRIM = 20 +PERF_PAPC_CLPR_VVUCP_CLIP_PRIM = 21 +PERF_PAPC_CLPR_VV_CLIP_PRIM = 22 +PERF_PAPC_CLPR_UCP_CLIP_PRIM = 23 +PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE = 24 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_1 = 25 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_2 = 26 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_3 = 27 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_4 = 28 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8 = 29 +PERF_CLPR_CLIP_PLANE_CNT_9_PLUS = 30 +PERF_PAPC_CLPR_CLIP_PLANE_NEAR = 31 +PERF_PAPC_CLPR_CLIP_PLANE_FAR = 32 +PERF_PAPC_CLPR_CLIP_PLANE_LEFT = 33 +PERF_PAPC_CLPR_CLIP_PLANE_RIGHT = 34 +PERF_PAPC_CLPR_CLIP_PLANE_TOP = 35 +PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM = 36 +PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM = 38 +PERF_PAPC_CLSM_NULL_PRIM = 39 +PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM = 40 +PERF_PAPC_CLSM_CULL_TO_NULL_PRIM = 41 +PERF_PAPC_CLSM_OUT_PRIM_CNT_1 = 42 +PERF_PAPC_CLSM_OUT_PRIM_CNT_2 = 43 +PERF_PAPC_CLSM_OUT_PRIM_CNT_3 = 44 +PERF_PAPC_CLSM_OUT_PRIM_CNT_4 = 45 +PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8 = 46 +PERF_PAPC_CLSM_OUT_PRIM_CNT_9_PLUS = 47 +PERF_PAPC_CLIPGA_VTE_KILL_PRIM = 48 +PERF_PAPC_SU_INPUT_PRIM = 49 +PERF_PAPC_SU_INPUT_CLIP_PRIM = 50 +PERF_PAPC_SU_INPUT_NULL_PRIM = 51 +PERF_PAPC_SU_INPUT_PRIM_DUAL = 52 +PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL = 53 +PERF_PAPC_SU_ZERO_AREA_CULL_PRIM = 54 +PERF_PAPC_SU_BACK_FACE_CULL_PRIM = 55 +PERF_PAPC_SU_FRONT_FACE_CULL_PRIM = 56 +PERF_PAPC_SU_POLYMODE_FACE_CULL = 57 +PERF_PAPC_SU_POLYMODE_BACK_CULL = 58 +PERF_PAPC_SU_POLYMODE_FRONT_CULL = 59 +PERF_PAPC_SU_POLYMODE_INVALID_FILL = 60 +PERF_PAPC_SU_OUTPUT_PRIM = 61 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM = 62 +PERF_PAPC_SU_OUTPUT_NULL_PRIM = 63 +PERF_PAPC_SU_OUTPUT_EVENT_FLAG = 64 +PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT = 65 +PERF_PAPC_SU_OUTPUT_END_OF_PACKET = 66 +PERF_PAPC_SU_OUTPUT_POLYMODE_FACE = 67 +PERF_PAPC_SU_OUTPUT_POLYMODE_BACK = 68 +PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT = 69 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE = 70 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK = 71 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT = 72 +PERF_PAPC_SU_OUTPUT_PRIM_DUAL = 73 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL = 74 +PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL = 75 +PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL = 76 +PERF_PAPC_PASX_REQ_IDLE = 77 +PERF_PAPC_PASX_REQ_BUSY = 78 +PERF_PAPC_PASX_REQ_STALLED = 79 +PERF_PAPC_PASX_REC_IDLE = 80 +PERF_PAPC_PASX_REC_BUSY = 81 +PERF_PAPC_PASX_REC_STARVED_SX = 82 +PERF_PAPC_PASX_REC_STALLED = 83 +PERF_PAPC_PASX_REC_STALLED_POS_MEM = 84 +PERF_PAPC_PASX_REC_STALLED_CCGSM_IN = 85 +PERF_PAPC_CCGSM_IDLE = 86 +PERF_PAPC_CCGSM_BUSY = 87 +PERF_PAPC_CCGSM_STALLED = 88 +PERF_PAPC_CLPRIM_IDLE = 89 +PERF_PAPC_CLPRIM_BUSY = 90 +PERF_PAPC_CLPRIM_STALLED = 91 +PERF_PAPC_CLPRIM_STARVED_CCGSM = 92 +PERF_PAPC_CLIPSM_IDLE = 93 +PERF_PAPC_CLIPSM_BUSY = 94 +PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH = 95 +PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ = 96 +PERF_PAPC_CLIPSM_WAIT_CLIPGA = 97 +PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP = 98 +PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM = 99 +PERF_PAPC_CLIPGA_IDLE = 100 +PERF_PAPC_CLIPGA_BUSY = 101 +PERF_PAPC_CLIPGA_STARVED_VTE_CLIP = 102 +PERF_PAPC_CLIPGA_STALLED = 103 +PERF_PAPC_CLIP_IDLE = 104 +PERF_PAPC_CLIP_BUSY = 105 +PERF_PAPC_SU_IDLE = 106 +PERF_PAPC_SU_BUSY = 107 +PERF_PAPC_SU_STARVED_CLIP = 108 +PERF_PAPC_SU_STALLED_SC = 109 +PERF_PAPC_CL_DYN_SCLK_VLD = 110 +PERF_PAPC_SU_DYN_SCLK_VLD = 111 +PERF_PAPC_PA_REG_SCLK_VLD = 112 +PERF_PAPC_SU_SE0_PRIM_FILTER_CULL = 120 +PERF_PAPC_SU_SE1_PRIM_FILTER_CULL = 121 +PERF_PAPC_SU_SE0_OUTPUT_PRIM = 123 +PERF_PAPC_SU_SE1_OUTPUT_PRIM = 124 +PERF_PAPC_SU_ALL_OUTPUT_PRIM = 125 +PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM = 126 +PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM = 127 +PERF_PAPC_SU_ALL_OUTPUT_NULL_PRIM = 128 +PERF_PAPC_SU_SE0_STALLED_SC = 131 +PERF_PAPC_SU_SE1_STALLED_SC = 132 +PERF_PAPC_SU_ALL_STALLED_SC = 133 +PERF_PAPC_CLSM_CLIPPING_PRIM = 134 +PERF_PAPC_SU_CULLED_PRIM = 135 +PERF_PAPC_SU_OUTPUT_EOPG = 136 +PERF_PAPC_SU_SE2_PRIM_FILTER_CULL = 137 +PERF_PAPC_SU_SE3_PRIM_FILTER_CULL = 138 +PERF_PAPC_SU_SE2_OUTPUT_PRIM = 139 +PERF_PAPC_SU_SE3_OUTPUT_PRIM = 140 +PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM = 141 +PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM = 142 +PERF_PAPC_SU_SE2_STALLED_SC = 151 +PERF_PAPC_SU_SE3_STALLED_SC = 152 +PERF_SU_SMALL_PRIM_FILTER_CULL_CNT = 153 +PERF_SMALL_PRIM_CULL_PRIM_1X1 = 154 +PERF_SMALL_PRIM_CULL_PRIM_2X1 = 155 +PERF_SMALL_PRIM_CULL_PRIM_1X2 = 156 +PERF_SMALL_PRIM_CULL_PRIM_2X2 = 157 +PERF_SMALL_PRIM_CULL_PRIM_3X1 = 158 +PERF_SMALL_PRIM_CULL_PRIM_1X3 = 159 +PERF_SMALL_PRIM_CULL_PRIM_3X2 = 160 +PERF_SMALL_PRIM_CULL_PRIM_2X3 = 161 +PERF_SMALL_PRIM_CULL_PRIM_NX1 = 162 +PERF_SMALL_PRIM_CULL_PRIM_1XN = 163 +PERF_SMALL_PRIM_CULL_PRIM_NX2 = 164 +PERF_SMALL_PRIM_CULL_PRIM_2XN = 165 +PERF_SC0_QUALIFIED_SEND_BUSY_EVENT = 169 +PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT = 170 +PERF_SC1_QUALIFIED_SEND_BUSY_EVENT = 171 +PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT = 172 +PERF_SC2_QUALIFIED_SEND_BUSY_EVENT = 173 +PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT = 174 +PERF_SC3_QUALIFIED_SEND_BUSY_EVENT = 175 +PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT = 176 +PERF_PA_VERTEX_FIFO_FULL = 177 +PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL = 178 +PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL = 179 +PERF_ENGG_CSB_MACHINE_IS_STARVED = 183 +PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY = 184 +PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI = 185 +PERF_ENGG_CSB_GE_INPUT_FIFO_FULL = 186 +PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL = 188 +PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT = 189 +PERF_ENGG_CSB_PRIM_COUNT_EQ0 = 190 +PERF_ENGG_CSB_NULL_SUBGROUP = 191 +PERF_ENGG_CSB_GE_SENDING_SUBGROUP = 192 +PERF_ENGG_CSB_GE_MEMORY_FULL = 193 +PERF_ENGG_CSB_GE_MEMORY_EMPTY = 194 +PERF_ENGG_CSB_SPI_MEMORY_FULL = 195 +PERF_ENGG_CSB_SPI_MEMORY_EMPTY = 196 +PERF_ENGG_INDEX_REQ_NULL_REQUEST = 224 +PERF_ENGG_INDEX_RET_0_NEW_VERTS_THIS_PRIM = 225 +PERF_ENGG_INDEX_RET_1_NEW_VERTS_THIS_PRIM = 226 +PERF_ENGG_INDEX_RET_2_NEW_VERTS_THIS_PRIM = 227 +PERF_ENGG_INDEX_RET_3_NEW_VERTS_THIS_PRIM = 228 +PERF_ENGG_INDEX_REQ_STARVED = 229 +PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 230 +PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL = 231 +PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS = 232 +PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL = 233 +PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY = 234 +PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL = 235 +PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB = 236 +PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS = 237 +PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO = 238 +PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO = 239 +PERF_ENGG_INDEX_RET_SXRX_READING_EVENT = 240 +PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP = 241 +PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0 = 242 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL = 243 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL = 244 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL = 245 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL = 246 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL = 247 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL = 248 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL = 249 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL = 250 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL = 251 +PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL = 252 +PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO = 258 +PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO = 259 +PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB = 260 +PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM = 261 +PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE = 262 +PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE = 263 +PERF_ENGG_POS_REQ_STARVED = 264 +PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO = 265 +PERF_ENGG_BUSY = 266 +PERF_CLIPSM_CULL_PRIMS_CNT = 267 +PERF_PH_SEND_1_SC = 268 +PERF_PH_SEND_2_SC = 269 +PERF_PH_SEND_3_SC = 270 +PERF_PH_SEND_4_SC = 271 +PERF_OUTPUT_PRIM_1_SC = 272 +PERF_OUTPUT_PRIM_2_SC = 273 +PERF_OUTPUT_PRIM_3_SC = 274 +PERF_OUTPUT_PRIM_4_SC = 275 +PERF_PASX_POS_VECTOR = 276 +PERF_PASX_MISC_VECTOR = 277 +PERF_PASX_CCDIST0_VECTOR = 278 +PERF_PASX_CCDIST1_VECTOR = 279 +PERF_PASX_STEREO_POS_VECTOR = 280 +PERF_CLPR_INPUT_SEND = 281 +PERF_SU_INPUT_SEND = 282 +PERF_SU_OUTPUT_SEND = 283 +PERF_PAPC_SU_SE4_PRIM_FILTER_CULL = 284 +PERF_PAPC_SU_SE5_PRIM_FILTER_CULL = 285 +PERF_PAPC_SU_SE4_OUTPUT_PRIM = 286 +PERF_PAPC_SU_SE5_OUTPUT_PRIM = 287 +PERF_PAPC_SU_SE4_OUTPUT_NULL_PRIM = 288 +PERF_PAPC_SU_SE5_OUTPUT_NULL_PRIM = 289 +PERF_PAPC_SU_SE4_STALLED_SC = 290 +PERF_PAPC_SU_SE5_STALLED_SC = 291 +PERF_ENGG_INDEX_RET0_NEW_VERTS = 292 +PERF_ENGG_INDEX_RET1_NEW_VERTS = 293 +PERF_ENGG_INDEX_RET2_NEW_VERTS = 294 +PERF_ENGG_INDEX_RET3_NEW_VERTS = 295 +PERF_ENGG_INDEX_RET4_NEW_VERTS = 296 +PERF_ENGG_INDEX_RET5_NEW_VERTS = 297 +PERF_ENGG_INDEX_RET6_NEW_VERTS = 298 +PERF_ENGG_INDEX_RET7_NEW_VERTS = 299 +PERF_ENGG_INDEX_RET8_NEW_VERTS = 300 +PERF_ENGG_INDEX_RET9_NEW_VERTS = 301 +PERF_ENGG_INDEX_RET10_NEW_VERTS = 302 +PERF_ENGG_INDEX_RET11_NEW_VERTS = 303 +PERF_ENGG_INDEX_RET12_NEW_VERTS = 304 +PERF_PH_SEND_5_SC = 305 +PERF_PH_SEND_6_SC = 306 +PERF_OUTPUT_PRIM_5_SC = 307 +PERF_OUTPUT_PRIM_6_SC = 308 +PERF_CLPR_BACK_PRIM = 309 +PERF_PA_BUSY = 310 +SU_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'RMIPerfSel' +RMIPerfSel__enumvalues = { + 0: 'RMI_PERF_SEL_NONE', + 1: 'RMI_PERF_SEL_BUSY', + 2: 'RMI_PERF_SEL_REG_CLK_VLD', + 3: 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', + 4: 'RMI_PERF_SEL_DYN_CLK_RB_VLD', + 5: 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 6: 'RMI_PERF_SEL_PERF_WINDOW', + 7: 'RMI_PERF_SEL_EVENT_SEND', + 8: 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 9: 'RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY', + 10: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 11: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 12: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 13: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 14: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 15: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 16: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 17: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 18: 'RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID', + 19: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 20: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 21: 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 22: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 23: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 24: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 25: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 26: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 27: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 28: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 29: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 30: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 31: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 32: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 33: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 34: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 35: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 36: 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 37: 'RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY', + 38: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 39: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 40: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 41: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 42: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 43: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 44: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 45: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 46: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 47: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 48: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 49: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 50: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 51: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 52: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 53: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 54: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 55: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 56: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 57: 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 58: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 59: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 60: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 61: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 62: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 63: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 64: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 65: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 66: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 67: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 68: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 69: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 70: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 71: 'RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX', + 72: 'RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY', + 73: 'RMI_PERF_SEL_RB_RMI_WR_IDLE', + 74: 'RMI_PERF_SEL_RB_RMI_WR_STARVE', + 75: 'RMI_PERF_SEL_RB_RMI_WR_STALL', + 76: 'RMI_PERF_SEL_RB_RMI_WR_BUSY', + 77: 'RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY', + 78: 'RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX', + 79: 'RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY', + 80: 'RMI_PERF_SEL_RB_RMI_RD_IDLE', + 81: 'RMI_PERF_SEL_RB_RMI_RD_STARVE', + 82: 'RMI_PERF_SEL_RB_RMI_RD_STALL', + 83: 'RMI_PERF_SEL_RB_RMI_RD_BUSY', + 84: 'RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY', + 85: 'RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID', + 86: 'RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID', + 87: 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 88: 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 89: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 90: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 91: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 92: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 93: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 94: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 95: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 96: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 97: 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 98: 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', + 99: 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 100: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 101: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 102: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 103: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 104: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 105: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 106: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 107: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 108: 'RMI_PERF_SEL_RMI_TC_STALL_RDREQ', + 109: 'RMI_PERF_SEL_RMI_TC_STALL_WRREQ', + 110: 'RMI_PERF_SEL_RMI_TC_STALL_ALLREQ', + 111: 'RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND', + 112: 'RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND', + 113: 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 114: 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 115: 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 116: 'RMI_PERF_SEL_TCIW_REQ', + 117: 'RMI_PERF_SEL_TCIW_BUSY', + 118: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 119: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 120: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 121: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 122: 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 123: 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 124: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 125: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 126: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 127: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 128: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 129: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 130: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 131: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 132: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 133: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_READ_RTS_RTR', + 134: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_WRITE_RTS_RTR', + 135: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_IN0_RTS_RTR', + 136: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_IN1_RTS_RTR', + 137: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_CB_RTS_RTR', + 138: 'RMI_PERF_SEL_CONSUMER_PROBEGEN_DB_RTS_RTR', +} +RMI_PERF_SEL_NONE = 0 +RMI_PERF_SEL_BUSY = 1 +RMI_PERF_SEL_REG_CLK_VLD = 2 +RMI_PERF_SEL_DYN_CLK_CMN_VLD = 3 +RMI_PERF_SEL_DYN_CLK_RB_VLD = 4 +RMI_PERF_SEL_DYN_CLK_PERF_VLD = 5 +RMI_PERF_SEL_PERF_WINDOW = 6 +RMI_PERF_SEL_EVENT_SEND = 7 +RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID = 8 +RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY = 9 +RMI_PERF_SEL_RB_RMI_WRREQ_CID0 = 10 +RMI_PERF_SEL_RB_RMI_WRREQ_CID1 = 11 +RMI_PERF_SEL_RB_RMI_WRREQ_CID2 = 12 +RMI_PERF_SEL_RB_RMI_WRREQ_CID3 = 13 +RMI_PERF_SEL_RB_RMI_WRREQ_CID4 = 14 +RMI_PERF_SEL_RB_RMI_WRREQ_CID5 = 15 +RMI_PERF_SEL_RB_RMI_WRREQ_CID6 = 16 +RMI_PERF_SEL_RB_RMI_WRREQ_CID7 = 17 +RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID = 18 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID = 19 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID = 20 +RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY = 21 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID = 22 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0 = 23 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1 = 24 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2 = 25 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3 = 26 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4 = 27 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5 = 28 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6 = 29 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7 = 30 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0 = 31 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1 = 32 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2 = 33 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3 = 34 +RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID = 35 +RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID = 36 +RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY = 37 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0 = 38 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1 = 39 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2 = 40 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3 = 41 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4 = 42 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5 = 43 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6 = 44 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7 = 45 +RMI_PERF_SEL_RB_RMI_RDREQ_CID0 = 46 +RMI_PERF_SEL_RB_RMI_RDREQ_CID1 = 47 +RMI_PERF_SEL_RB_RMI_RDREQ_CID2 = 48 +RMI_PERF_SEL_RB_RMI_RDREQ_CID3 = 49 +RMI_PERF_SEL_RB_RMI_RDREQ_CID4 = 50 +RMI_PERF_SEL_RB_RMI_RDREQ_CID5 = 51 +RMI_PERF_SEL_RB_RMI_RDREQ_CID6 = 52 +RMI_PERF_SEL_RB_RMI_RDREQ_CID7 = 53 +RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID = 54 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID = 55 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID = 56 +RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY = 57 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID = 58 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0 = 59 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1 = 60 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2 = 61 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3 = 62 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4 = 63 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5 = 64 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6 = 65 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7 = 66 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0 = 67 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1 = 68 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2 = 69 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3 = 70 +RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX = 71 +RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY = 72 +RMI_PERF_SEL_RB_RMI_WR_IDLE = 73 +RMI_PERF_SEL_RB_RMI_WR_STARVE = 74 +RMI_PERF_SEL_RB_RMI_WR_STALL = 75 +RMI_PERF_SEL_RB_RMI_WR_BUSY = 76 +RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY = 77 +RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX = 78 +RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY = 79 +RMI_PERF_SEL_RB_RMI_RD_IDLE = 80 +RMI_PERF_SEL_RB_RMI_RD_STARVE = 81 +RMI_PERF_SEL_RB_RMI_RD_STALL = 82 +RMI_PERF_SEL_RB_RMI_RD_BUSY = 83 +RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY = 84 +RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID = 85 +RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID = 86 +RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID = 87 +RMI_PERF_SEL_RMI_TC_REQ_BUSY = 88 +RMI_PERF_SEL_RMI_TC_WRREQ_CID0 = 89 +RMI_PERF_SEL_RMI_TC_WRREQ_CID1 = 90 +RMI_PERF_SEL_RMI_TC_WRREQ_CID2 = 91 +RMI_PERF_SEL_RMI_TC_WRREQ_CID3 = 92 +RMI_PERF_SEL_RMI_TC_WRREQ_CID4 = 93 +RMI_PERF_SEL_RMI_TC_WRREQ_CID5 = 94 +RMI_PERF_SEL_RMI_TC_WRREQ_CID6 = 95 +RMI_PERF_SEL_RMI_TC_WRREQ_CID7 = 96 +RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID = 97 +RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID = 98 +RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID = 99 +RMI_PERF_SEL_RMI_TC_RDREQ_CID0 = 100 +RMI_PERF_SEL_RMI_TC_RDREQ_CID1 = 101 +RMI_PERF_SEL_RMI_TC_RDREQ_CID2 = 102 +RMI_PERF_SEL_RMI_TC_RDREQ_CID3 = 103 +RMI_PERF_SEL_RMI_TC_RDREQ_CID4 = 104 +RMI_PERF_SEL_RMI_TC_RDREQ_CID5 = 105 +RMI_PERF_SEL_RMI_TC_RDREQ_CID6 = 106 +RMI_PERF_SEL_RMI_TC_RDREQ_CID7 = 107 +RMI_PERF_SEL_RMI_TC_STALL_RDREQ = 108 +RMI_PERF_SEL_RMI_TC_STALL_WRREQ = 109 +RMI_PERF_SEL_RMI_TC_STALL_ALLREQ = 110 +RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND = 111 +RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND = 112 +RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID = 113 +RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID = 114 +RMI_PERF_SEL_TCIW_INFLIGHT_COUNT = 115 +RMI_PERF_SEL_TCIW_REQ = 116 +RMI_PERF_SEL_TCIW_BUSY = 117 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR = 118 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR = 119 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB = 120 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB = 121 +RMI_PERF_SEL_REORDER_FIFO_REQ = 122 +RMI_PERF_SEL_REORDER_FIFO_BUSY = 123 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID = 124 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0 = 125 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1 = 126 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2 = 127 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3 = 128 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4 = 129 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5 = 130 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6 = 131 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7 = 132 +RMI_PERF_SEL_CONSUMER_PROBEGEN_READ_RTS_RTR = 133 +RMI_PERF_SEL_CONSUMER_PROBEGEN_WRITE_RTS_RTR = 134 +RMI_PERF_SEL_CONSUMER_PROBEGEN_IN0_RTS_RTR = 135 +RMI_PERF_SEL_CONSUMER_PROBEGEN_IN1_RTS_RTR = 136 +RMI_PERF_SEL_CONSUMER_PROBEGEN_CB_RTS_RTR = 137 +RMI_PERF_SEL_CONSUMER_PROBEGEN_DB_RTS_RTR = 138 +RMIPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1PerfSel' +UTCL1PerfSel__enumvalues = { + 0: 'UTCL1_PERF_SEL_NONE', + 1: 'UTCL1_PERF_SEL_REQS', + 2: 'UTCL1_PERF_SEL_HITS', + 3: 'UTCL1_PERF_SEL_MISSES', + 4: 'UTCL1_PERF_SEL_MH_RECENT_BUF_HIT', + 5: 'UTCL1_PERF_SEL_MH_DUPLICATE_DETECT', + 6: 'UTCL1_PERF_SEL_UTCL2_REQS', + 7: 'UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY', + 8: 'UTCL1_PERF_SEL_UTCL2_RET_FAULT', + 9: 'UTCL1_PERF_SEL_STALL_UTCL2_CREDITS', + 10: 'UTCL1_PERF_SEL_STALL_MH_FULL', + 11: 'UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM', + 12: 'UTCL1_PERF_SEL_UTCL2_RET_CNT', + 13: 'UTCL1_PERF_SEL_RTNS', + 14: 'UTCL1_PERF_SEL_XLAT_REQ_BUSY', + 15: 'UTCL1_PERF_SEL_RANGE_INVREQS', + 16: 'UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS', + 17: 'UTCL1_PERF_SEL_BYPASS_REQS', + 18: 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 19: 'UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT', + 20: 'UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT', + 21: 'UTCL1_PERF_SEL_CP_INVREQS', + 22: 'UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS', + 23: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4K_64K', + 24: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_64K_256K', + 25: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_256K_512K', + 26: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_512K_1M', + 27: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_1M_2M', + 28: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_2M_4M', + 29: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4M_8M', + 30: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_8M_16M', + 31: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_16M_32M', + 32: 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_32M_INF', + 33: 'UTCL1_PERF_SEL_UTCL2_REQ_SQUASHED_NUM', + 34: 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_0', + 35: 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_1', + 36: 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_2', + 37: 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_3', + 38: 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_0', + 39: 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_1', + 40: 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_2', + 41: 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_3', + 42: 'UTCL1_PERF_SEL_UTCL1_UTCL2_INVACKS', + 43: 'UTCL1_PERF_SEL_UTCL0_UTCL1_INVACKS', + 44: 'UTCL1_PERF_SEL_HITS_PG_SIZE_1', + 45: 'UTCL1_PERF_SEL_HITS_PG_SIZE_2', + 46: 'UTCL1_PERF_SEL_HITS_PG_SIZE_3', + 47: 'UTCL1_PERF_SEL_HITS_PG_SIZE_4', + 48: 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_0', + 49: 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_1', + 50: 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_2', + 51: 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_3', + 52: 'UTCL1_PERF_SEL_AVG_INV_LATENCY', + 53: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC0', + 54: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC1', + 55: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC2', + 56: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC3', + 57: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC0', + 58: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC1', + 59: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC2', + 60: 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC3', + 61: 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC0', + 62: 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC1', + 63: 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC2', + 64: 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC3', + 65: 'UTCL1_PERF_SEL_ALOG_INTERRUPT', + 66: 'UTCL1_PERF_SEL_ALOG_INTERRUPT_DROPPED', + 67: 'UTCL1_PERF_SEL_ALOG_CACHE_REQ', + 68: 'UTCL1_PERF_SEL_ALOG_CACHE_HIT', + 69: 'UTCL1_PERF_SEL_ALOG_STALL_PMM_CREDITS', +} +UTCL1_PERF_SEL_NONE = 0 +UTCL1_PERF_SEL_REQS = 1 +UTCL1_PERF_SEL_HITS = 2 +UTCL1_PERF_SEL_MISSES = 3 +UTCL1_PERF_SEL_MH_RECENT_BUF_HIT = 4 +UTCL1_PERF_SEL_MH_DUPLICATE_DETECT = 5 +UTCL1_PERF_SEL_UTCL2_REQS = 6 +UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY = 7 +UTCL1_PERF_SEL_UTCL2_RET_FAULT = 8 +UTCL1_PERF_SEL_STALL_UTCL2_CREDITS = 9 +UTCL1_PERF_SEL_STALL_MH_FULL = 10 +UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM = 11 +UTCL1_PERF_SEL_UTCL2_RET_CNT = 12 +UTCL1_PERF_SEL_RTNS = 13 +UTCL1_PERF_SEL_XLAT_REQ_BUSY = 14 +UTCL1_PERF_SEL_RANGE_INVREQS = 15 +UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS = 16 +UTCL1_PERF_SEL_BYPASS_REQS = 17 +UTCL1_PERF_SEL_HIT_INV_FILTER_REQS = 18 +UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT = 19 +UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT = 20 +UTCL1_PERF_SEL_CP_INVREQS = 21 +UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS = 22 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4K_64K = 23 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_64K_256K = 24 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_256K_512K = 25 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_512K_1M = 26 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_1M_2M = 27 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_2M_4M = 28 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4M_8M = 29 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_8M_16M = 30 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_16M_32M = 31 +UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_32M_INF = 32 +UTCL1_PERF_SEL_UTCL2_REQ_SQUASHED_NUM = 33 +UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_0 = 34 +UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_1 = 35 +UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_2 = 36 +UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_3 = 37 +UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_0 = 38 +UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_1 = 39 +UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_2 = 40 +UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_3 = 41 +UTCL1_PERF_SEL_UTCL1_UTCL2_INVACKS = 42 +UTCL1_PERF_SEL_UTCL0_UTCL1_INVACKS = 43 +UTCL1_PERF_SEL_HITS_PG_SIZE_1 = 44 +UTCL1_PERF_SEL_HITS_PG_SIZE_2 = 45 +UTCL1_PERF_SEL_HITS_PG_SIZE_3 = 46 +UTCL1_PERF_SEL_HITS_PG_SIZE_4 = 47 +UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_0 = 48 +UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_1 = 49 +UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_2 = 50 +UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_3 = 51 +UTCL1_PERF_SEL_AVG_INV_LATENCY = 52 +UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC0 = 53 +UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC1 = 54 +UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC2 = 55 +UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC3 = 56 +UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC0 = 57 +UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC1 = 58 +UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC2 = 59 +UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC3 = 60 +UTCL1_PERF_SEL_EVICTIONS_NUM_CC0 = 61 +UTCL1_PERF_SEL_EVICTIONS_NUM_CC1 = 62 +UTCL1_PERF_SEL_EVICTIONS_NUM_CC2 = 63 +UTCL1_PERF_SEL_EVICTIONS_NUM_CC3 = 64 +UTCL1_PERF_SEL_ALOG_INTERRUPT = 65 +UTCL1_PERF_SEL_ALOG_INTERRUPT_DROPPED = 66 +UTCL1_PERF_SEL_ALOG_CACHE_REQ = 67 +UTCL1_PERF_SEL_ALOG_CACHE_HIT = 68 +UTCL1_PERF_SEL_ALOG_STALL_PMM_CREDITS = 69 +UTCL1PerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'GC_EA_SE_PERFCOUNT_SEL' +GC_EA_SE_PERFCOUNT_SEL__enumvalues = { + 0: 'GC_EA_SE_PERF_SEL_ALWAYS_COUNT', + 1: 'GC_EA_SE_PERF_SEL_RDRAM_NUM_BANKS_VLD', + 2: 'GC_EA_SE_PERF_SEL_RDRAM_REQ_PER_CLIGRP', + 3: 'GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP', + 4: 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START0', + 5: 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END0', + 6: 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START1', + 7: 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END1', + 8: 'GC_EA_SE_PERF_SEL_WDRAM_NUM_BANKS_VLD', + 9: 'GC_EA_SE_PERF_SEL_WDRAM_REQ_PER_CLIGRP', + 10: 'GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP', + 11: 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START0', + 12: 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END0', + 13: 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START1', + 14: 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END1', + 15: 'GC_EA_SE_PERF_SEL_RGMI_NUM_BANKS_VLD', + 16: 'GC_EA_SE_PERF_SEL_RGMI_REQ_PER_CLIGRP', + 17: 'GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR', + 18: 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_START0', + 19: 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_END0', + 20: 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_START1', + 21: 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_END1', + 22: 'GC_EA_SE_PERF_SEL_WGMI_NUM_BANKS_VLD', + 23: 'GC_EA_SE_PERF_SEL_WGMI_REQ_PER_CLIGRP', + 24: 'GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP', + 25: 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_START0', + 26: 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_END0', + 27: 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_START1', + 28: 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_END1', + 29: 'GC_EA_SE_PERF_SEL_RIO_REQ_PER_CLIGRP', + 30: 'GC_EA_SE_PERF_SEL_RIO_SIZE_REQ', + 31: 'GC_EA_SE_PERF_SEL_RIO_GRP0_SIZE_REQ', + 32: 'GC_EA_SE_PERF_SEL_RIO_GRP1_SIZE_REQ', + 33: 'GC_EA_SE_PERF_SEL_RIO_GRP2_SIZE_REQ', + 34: 'GC_EA_SE_PERF_SEL_RIO_GRP3_SIZE_REQ', + 35: 'GC_EA_SE_PERF_SEL_RIO_LATENCY_START0', + 36: 'GC_EA_SE_PERF_SEL_RIO_LATENCY_END0', + 37: 'GC_EA_SE_PERF_SEL_RIO_LATENCY_START1', + 38: 'GC_EA_SE_PERF_SEL_RIO_LATENCY_END1', + 39: 'GC_EA_SE_PERF_SEL_WIO_REQ_PER_CLIGRP', + 40: 'GC_EA_SE_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP', + 41: 'GC_EA_SE_PERF_SEL_WIO_SIZE_REQ', + 42: 'GC_EA_SE_PERF_SEL_WIO_GRP0_SIZE_REQ', + 43: 'GC_EA_SE_PERF_SEL_WIO_GRP1_SIZE_REQ', + 44: 'GC_EA_SE_PERF_SEL_WIO_GRP2_SIZE_REQ', + 45: 'GC_EA_SE_PERF_SEL_WIO_GRP3_SIZE_REQ', + 46: 'GC_EA_SE_PERF_SEL_WIO_LATENCY_START0', + 47: 'GC_EA_SE_PERF_SEL_WIO_LATENCY_END0', + 48: 'GC_EA_SE_PERF_SEL_WIO_LATENCY_START1', + 49: 'GC_EA_SE_PERF_SEL_WIO_LATENCY_END1', + 50: 'GC_EA_SE_PERF_SEL_SARB_REQ_PER_VC', + 51: 'GC_EA_SE_PERF_SEL_SARB_DRAM_REQ_PER_VC', + 52: 'GC_EA_SE_PERF_SEL_SARB_GMI_REQ_PER_VC', + 53: 'GC_EA_SE_PERF_SEL_SARB_IO_REQ_PER_VC', + 54: 'GC_EA_SE_PERF_SEL_SARB_SIZE_REQ', + 55: 'GC_EA_SE_PERF_SEL_SARB_DRAM_SIZE_REQ', + 56: 'GC_EA_SE_PERF_SEL_SARB_GMI_SIZE_REQ', + 57: 'GC_EA_SE_PERF_SEL_SARB_IO_SIZE_REQ', + 58: 'GC_EA_SE_PERF_SEL_SARB_LATENCY_START0', + 59: 'GC_EA_SE_PERF_SEL_SARB_LATENCY_END0', + 60: 'GC_EA_SE_PERF_SEL_SARB_LATENCY_START1', + 61: 'GC_EA_SE_PERF_SEL_SARB_LATENCY_END1', + 62: 'GC_EA_SE_PERF_SEL_SARB_BUSY', + 63: 'GC_EA_SE_PERF_SEL_SARB_STALLED', + 64: 'GC_EA_SE_PERF_SEL_SARB_STARVING', + 65: 'GC_EA_SE_PERF_SEL_SARB_IDLE', + 66: 'GC_EA_SE_PERF_SEL_RRET_VLD', + 67: 'GC_EA_SE_PERF_SEL_WRET_VLD', + 68: 'GC_EA_SE_PERF_SEL_PRB_REQ', + 69: 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_EVICT', + 70: 'GC_EA_SE_PERF_SEL_MAM_ARAM_REQ_VLD', + 71: 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT', + 72: 'GC_EA_SE_PERF_SEL_MAM_NUM_DQRY', + 73: 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT', + 74: 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED', + 75: 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_COMPLETED', + 76: 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_ONGOING', + 77: 'GC_EA_SE_PERF_SEL_RDRAM_SIZE_REQ', + 78: 'GC_EA_SE_PERF_SEL_WDRAM_SIZE_REQ', + 79: 'GC_EA_SE_PERF_SEL_RGMI_SIZE_REQ', + 80: 'GC_EA_SE_PERF_SEL_WGMI_SIZE_REQ', + 81: 'GC_EA_SE_PERF_SEL_SARB_DRAM_RW_TURN_AROUND', + 82: 'GC_EA_SE_PERF_SEL_SARB_GMI_RW_TURN_AROUND', + 83: 'GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 84: 'GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 85: 'GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 86: 'GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 87: 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_EVICT', + 88: 'GC_EA_SE_PERF_SEL_MAM_DBIT_REQ_VLD', + 89: 'GC_EA_SE_PERF_SEL_SARB_COHERENT_SIZE_REQ', + 90: 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT_EVICT', + 91: 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_LRU_EVICT', + 92: 'GC_EA_SE_PERF_SEL_MAM_FLUSH_REQ', + 93: 'GC_EA_SE_PERF_SEL_MAM_FLUSH_RESP', + 94: 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT_EVICT', + 95: 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_LRU_EVICT', + 96: 'GC_EA_SE_PERF_SEL_MAM_DQRY_ONGOING', + 97: 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT', +} +GC_EA_SE_PERF_SEL_ALWAYS_COUNT = 0 +GC_EA_SE_PERF_SEL_RDRAM_NUM_BANKS_VLD = 1 +GC_EA_SE_PERF_SEL_RDRAM_REQ_PER_CLIGRP = 2 +GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP = 3 +GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START0 = 4 +GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END0 = 5 +GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START1 = 6 +GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END1 = 7 +GC_EA_SE_PERF_SEL_WDRAM_NUM_BANKS_VLD = 8 +GC_EA_SE_PERF_SEL_WDRAM_REQ_PER_CLIGRP = 9 +GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP = 10 +GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START0 = 11 +GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END0 = 12 +GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START1 = 13 +GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END1 = 14 +GC_EA_SE_PERF_SEL_RGMI_NUM_BANKS_VLD = 15 +GC_EA_SE_PERF_SEL_RGMI_REQ_PER_CLIGRP = 16 +GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR = 17 +GC_EA_SE_PERF_SEL_RGMI_LATENCY_START0 = 18 +GC_EA_SE_PERF_SEL_RGMI_LATENCY_END0 = 19 +GC_EA_SE_PERF_SEL_RGMI_LATENCY_START1 = 20 +GC_EA_SE_PERF_SEL_RGMI_LATENCY_END1 = 21 +GC_EA_SE_PERF_SEL_WGMI_NUM_BANKS_VLD = 22 +GC_EA_SE_PERF_SEL_WGMI_REQ_PER_CLIGRP = 23 +GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP = 24 +GC_EA_SE_PERF_SEL_WGMI_LATENCY_START0 = 25 +GC_EA_SE_PERF_SEL_WGMI_LATENCY_END0 = 26 +GC_EA_SE_PERF_SEL_WGMI_LATENCY_START1 = 27 +GC_EA_SE_PERF_SEL_WGMI_LATENCY_END1 = 28 +GC_EA_SE_PERF_SEL_RIO_REQ_PER_CLIGRP = 29 +GC_EA_SE_PERF_SEL_RIO_SIZE_REQ = 30 +GC_EA_SE_PERF_SEL_RIO_GRP0_SIZE_REQ = 31 +GC_EA_SE_PERF_SEL_RIO_GRP1_SIZE_REQ = 32 +GC_EA_SE_PERF_SEL_RIO_GRP2_SIZE_REQ = 33 +GC_EA_SE_PERF_SEL_RIO_GRP3_SIZE_REQ = 34 +GC_EA_SE_PERF_SEL_RIO_LATENCY_START0 = 35 +GC_EA_SE_PERF_SEL_RIO_LATENCY_END0 = 36 +GC_EA_SE_PERF_SEL_RIO_LATENCY_START1 = 37 +GC_EA_SE_PERF_SEL_RIO_LATENCY_END1 = 38 +GC_EA_SE_PERF_SEL_WIO_REQ_PER_CLIGRP = 39 +GC_EA_SE_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP = 40 +GC_EA_SE_PERF_SEL_WIO_SIZE_REQ = 41 +GC_EA_SE_PERF_SEL_WIO_GRP0_SIZE_REQ = 42 +GC_EA_SE_PERF_SEL_WIO_GRP1_SIZE_REQ = 43 +GC_EA_SE_PERF_SEL_WIO_GRP2_SIZE_REQ = 44 +GC_EA_SE_PERF_SEL_WIO_GRP3_SIZE_REQ = 45 +GC_EA_SE_PERF_SEL_WIO_LATENCY_START0 = 46 +GC_EA_SE_PERF_SEL_WIO_LATENCY_END0 = 47 +GC_EA_SE_PERF_SEL_WIO_LATENCY_START1 = 48 +GC_EA_SE_PERF_SEL_WIO_LATENCY_END1 = 49 +GC_EA_SE_PERF_SEL_SARB_REQ_PER_VC = 50 +GC_EA_SE_PERF_SEL_SARB_DRAM_REQ_PER_VC = 51 +GC_EA_SE_PERF_SEL_SARB_GMI_REQ_PER_VC = 52 +GC_EA_SE_PERF_SEL_SARB_IO_REQ_PER_VC = 53 +GC_EA_SE_PERF_SEL_SARB_SIZE_REQ = 54 +GC_EA_SE_PERF_SEL_SARB_DRAM_SIZE_REQ = 55 +GC_EA_SE_PERF_SEL_SARB_GMI_SIZE_REQ = 56 +GC_EA_SE_PERF_SEL_SARB_IO_SIZE_REQ = 57 +GC_EA_SE_PERF_SEL_SARB_LATENCY_START0 = 58 +GC_EA_SE_PERF_SEL_SARB_LATENCY_END0 = 59 +GC_EA_SE_PERF_SEL_SARB_LATENCY_START1 = 60 +GC_EA_SE_PERF_SEL_SARB_LATENCY_END1 = 61 +GC_EA_SE_PERF_SEL_SARB_BUSY = 62 +GC_EA_SE_PERF_SEL_SARB_STALLED = 63 +GC_EA_SE_PERF_SEL_SARB_STARVING = 64 +GC_EA_SE_PERF_SEL_SARB_IDLE = 65 +GC_EA_SE_PERF_SEL_RRET_VLD = 66 +GC_EA_SE_PERF_SEL_WRET_VLD = 67 +GC_EA_SE_PERF_SEL_PRB_REQ = 68 +GC_EA_SE_PERF_SEL_MAM_ARAM_FA_EVICT = 69 +GC_EA_SE_PERF_SEL_MAM_ARAM_REQ_VLD = 70 +GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT = 71 +GC_EA_SE_PERF_SEL_MAM_NUM_DQRY = 72 +GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT = 73 +GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED = 74 +GC_EA_SE_PERF_SEL_MAM_AFLUSH_COMPLETED = 75 +GC_EA_SE_PERF_SEL_MAM_AFLUSH_ONGOING = 76 +GC_EA_SE_PERF_SEL_RDRAM_SIZE_REQ = 77 +GC_EA_SE_PERF_SEL_WDRAM_SIZE_REQ = 78 +GC_EA_SE_PERF_SEL_RGMI_SIZE_REQ = 79 +GC_EA_SE_PERF_SEL_WGMI_SIZE_REQ = 80 +GC_EA_SE_PERF_SEL_SARB_DRAM_RW_TURN_AROUND = 81 +GC_EA_SE_PERF_SEL_SARB_GMI_RW_TURN_AROUND = 82 +GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH = 83 +GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH = 84 +GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH = 85 +GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH = 86 +GC_EA_SE_PERF_SEL_MAM_DBIT_FA_EVICT = 87 +GC_EA_SE_PERF_SEL_MAM_DBIT_REQ_VLD = 88 +GC_EA_SE_PERF_SEL_SARB_COHERENT_SIZE_REQ = 89 +GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT_EVICT = 90 +GC_EA_SE_PERF_SEL_MAM_ARAM_FA_LRU_EVICT = 91 +GC_EA_SE_PERF_SEL_MAM_FLUSH_REQ = 92 +GC_EA_SE_PERF_SEL_MAM_FLUSH_RESP = 93 +GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT_EVICT = 94 +GC_EA_SE_PERF_SEL_MAM_DBIT_FA_LRU_EVICT = 95 +GC_EA_SE_PERF_SEL_MAM_DQRY_ONGOING = 96 +GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT = 97 +GC_EA_SE_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'LSDMA_PERF_SEL' +LSDMA_PERF_SEL__enumvalues = { + 0: 'LSDMA_PERF_SEL_CYCLE', + 1: 'LSDMA_PERF_SEL_IDLE', + 2: 'LSDMA_PERF_SEL_REG_IDLE', + 3: 'LSDMA_PERF_SEL_RB_EMPTY', + 4: 'LSDMA_PERF_SEL_RB_FULL', + 5: 'LSDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'LSDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'LSDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'LSDMA_PERF_SEL_RB_RPTR_WB', + 9: 'LSDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'LSDMA_PERF_SEL_RB_CMD_FULL', + 11: 'LSDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'LSDMA_PERF_SEL_IB_CMD_FULL', + 13: 'LSDMA_PERF_SEL_EX_IDLE', + 14: 'LSDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'LSDMA_PERF_SEL_MC_WR_IDLE', + 17: 'LSDMA_PERF_SEL_MC_WR_COUNT', + 18: 'LSDMA_PERF_SEL_MC_RD_IDLE', + 19: 'LSDMA_PERF_SEL_MC_RD_COUNT', + 20: 'LSDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'LSDMA_PERF_SEL_SEM_IDLE', + 25: 'LSDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'LSDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'LSDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'LSDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'LSDMA_PERF_SEL_INT_IDLE', + 31: 'LSDMA_PERF_SEL_INT_REQ_STALL', + 32: 'LSDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'LSDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'LSDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'LSDMA_PERF_SEL_NUM_PACKET', + 37: 'LSDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'LSDMA_PERF_SEL_CE_WR_IDLE', + 39: 'LSDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'LSDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'LSDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'LSDMA_PERF_SEL_CE_IN_IDLE', + 43: 'LSDMA_PERF_SEL_CE_DST_IDLE', + 46: 'LSDMA_PERF_SEL_CE_AFIFO_FULL', + 47: 'LSDMA_PERF_SEL_DUMMY_0', + 48: 'LSDMA_PERF_SEL_DUMMY_1', + 49: 'LSDMA_PERF_SEL_CE_INFO_FULL', + 50: 'LSDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'LSDMA_PERF_SEL_CE_RD_STALL', + 52: 'LSDMA_PERF_SEL_CE_WR_STALL', + 53: 'LSDMA_PERF_SEL_GFX_SELECT', + 54: 'LSDMA_PERF_SEL_RLC0_SELECT', + 55: 'LSDMA_PERF_SEL_RLC1_SELECT', + 56: 'LSDMA_PERF_SEL_PAGE_SELECT', + 57: 'LSDMA_PERF_SEL_CTX_CHANGE', + 58: 'LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'LSDMA_PERF_SEL_DOORBELL', + 61: 'LSDMA_PERF_SEL_RD_BA_RTR', + 62: 'LSDMA_PERF_SEL_WR_BA_RTR', + 63: 'LSDMA_PERF_SEL_F32_L1_WR_VLD', + 64: 'LSDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'LSDMA_PERF_SEL_CE_L1_STALL', + 66: 'LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH', + 67: 'LSDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 68: 'LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 69: 'LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 70: 'LSDMA_PERF_SEL_ATCL2_RET_XNACK', + 71: 'LSDMA_PERF_SEL_ATCL2_RET_ACK', + 72: 'LSDMA_PERF_SEL_ATCL2_FREE', + 73: 'LSDMA_PERF_SEL_SDMA_ATCL2_SEND', + 74: 'LSDMA_PERF_SEL_DMA_L1_WR_SEND', + 75: 'LSDMA_PERF_SEL_DMA_L1_RD_SEND', + 76: 'LSDMA_PERF_SEL_DMA_MC_WR_SEND', + 77: 'LSDMA_PERF_SEL_DMA_MC_RD_SEND', + 78: 'LSDMA_PERF_SEL_L1_WR_FIFO_IDLE', + 79: 'LSDMA_PERF_SEL_L1_RD_FIFO_IDLE', + 80: 'LSDMA_PERF_SEL_L1_WRL2_IDLE', + 81: 'LSDMA_PERF_SEL_L1_RDL2_IDLE', + 82: 'LSDMA_PERF_SEL_L1_WRMC_IDLE', + 83: 'LSDMA_PERF_SEL_L1_RDMC_IDLE', + 84: 'LSDMA_PERF_SEL_L1_WR_INV_IDLE', + 85: 'LSDMA_PERF_SEL_L1_RD_INV_IDLE', + 86: 'LSDMA_PERF_SEL_L1_WR_INV_EN', + 87: 'LSDMA_PERF_SEL_L1_RD_INV_EN', + 88: 'LSDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 89: 'LSDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 90: 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR', + 91: 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 92: 'LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', + 93: 'LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', + 94: 'LSDMA_PERF_SEL_L1_INV_MIDDLE', + 95: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ', + 96: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET', + 97: 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ', + 98: 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET', + 99: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ', + 100: 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET', + 101: 'LSDMA_PERF_SEL_RB_MMHUB_RD_REQ', + 102: 'LSDMA_PERF_SEL_RB_MMHUB_RD_RET', + 103: 'LSDMA_PERF_SEL_IB_MMHUB_RD_REQ', + 104: 'LSDMA_PERF_SEL_IB_MMHUB_RD_RET', + 105: 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ', + 106: 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET', + 107: 'LSDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 108: 'LSDMA_PERF_SEL_UTCL1_UTCL2_RET', + 109: 'LSDMA_PERF_SEL_CMD_OP_MATCH', + 110: 'LSDMA_PERF_SEL_CMD_OP_START', + 111: 'LSDMA_PERF_SEL_CMD_OP_END', + 112: 'LSDMA_PERF_SEL_CE_BUSY', + 113: 'LSDMA_PERF_SEL_CE_BUSY_START', + 114: 'LSDMA_PERF_SEL_CE_BUSY_END', + 115: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 116: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 117: 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 118: 'LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND', + 119: 'LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID', + 120: 'LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND', + 121: 'LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID', + 122: 'LSDMA_PERF_SEL_DRAM_ECC', + 123: 'LSDMA_PERF_SEL_NACK_GEN_ERR', +} +LSDMA_PERF_SEL_CYCLE = 0 +LSDMA_PERF_SEL_IDLE = 1 +LSDMA_PERF_SEL_REG_IDLE = 2 +LSDMA_PERF_SEL_RB_EMPTY = 3 +LSDMA_PERF_SEL_RB_FULL = 4 +LSDMA_PERF_SEL_RB_WPTR_WRAP = 5 +LSDMA_PERF_SEL_RB_RPTR_WRAP = 6 +LSDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +LSDMA_PERF_SEL_RB_RPTR_WB = 8 +LSDMA_PERF_SEL_RB_CMD_IDLE = 9 +LSDMA_PERF_SEL_RB_CMD_FULL = 10 +LSDMA_PERF_SEL_IB_CMD_IDLE = 11 +LSDMA_PERF_SEL_IB_CMD_FULL = 12 +LSDMA_PERF_SEL_EX_IDLE = 13 +LSDMA_PERF_SEL_SRBM_REG_SEND = 14 +LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +LSDMA_PERF_SEL_MC_WR_IDLE = 16 +LSDMA_PERF_SEL_MC_WR_COUNT = 17 +LSDMA_PERF_SEL_MC_RD_IDLE = 18 +LSDMA_PERF_SEL_MC_RD_COUNT = 19 +LSDMA_PERF_SEL_MC_RD_RET_STALL = 20 +LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +LSDMA_PERF_SEL_SEM_IDLE = 24 +LSDMA_PERF_SEL_SEM_REQ_STALL = 25 +LSDMA_PERF_SEL_SEM_REQ_COUNT = 26 +LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +LSDMA_PERF_SEL_SEM_RESP_FAIL = 28 +LSDMA_PERF_SEL_SEM_RESP_PASS = 29 +LSDMA_PERF_SEL_INT_IDLE = 30 +LSDMA_PERF_SEL_INT_REQ_STALL = 31 +LSDMA_PERF_SEL_INT_REQ_COUNT = 32 +LSDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +LSDMA_PERF_SEL_INT_RESP_RETRY = 34 +LSDMA_PERF_SEL_NUM_PACKET = 35 +LSDMA_PERF_SEL_CE_WREQ_IDLE = 37 +LSDMA_PERF_SEL_CE_WR_IDLE = 38 +LSDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +LSDMA_PERF_SEL_CE_RREQ_IDLE = 40 +LSDMA_PERF_SEL_CE_OUT_IDLE = 41 +LSDMA_PERF_SEL_CE_IN_IDLE = 42 +LSDMA_PERF_SEL_CE_DST_IDLE = 43 +LSDMA_PERF_SEL_CE_AFIFO_FULL = 46 +LSDMA_PERF_SEL_DUMMY_0 = 47 +LSDMA_PERF_SEL_DUMMY_1 = 48 +LSDMA_PERF_SEL_CE_INFO_FULL = 49 +LSDMA_PERF_SEL_CE_INFO1_FULL = 50 +LSDMA_PERF_SEL_CE_RD_STALL = 51 +LSDMA_PERF_SEL_CE_WR_STALL = 52 +LSDMA_PERF_SEL_GFX_SELECT = 53 +LSDMA_PERF_SEL_RLC0_SELECT = 54 +LSDMA_PERF_SEL_RLC1_SELECT = 55 +LSDMA_PERF_SEL_PAGE_SELECT = 56 +LSDMA_PERF_SEL_CTX_CHANGE = 57 +LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +LSDMA_PERF_SEL_DOORBELL = 60 +LSDMA_PERF_SEL_RD_BA_RTR = 61 +LSDMA_PERF_SEL_WR_BA_RTR = 62 +LSDMA_PERF_SEL_F32_L1_WR_VLD = 63 +LSDMA_PERF_SEL_CE_L1_WR_VLD = 64 +LSDMA_PERF_SEL_CE_L1_STALL = 65 +LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH = 66 +LSDMA_PERF_SEL_SDMA_INVACK_FLUSH = 67 +LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH = 68 +LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH = 69 +LSDMA_PERF_SEL_ATCL2_RET_XNACK = 70 +LSDMA_PERF_SEL_ATCL2_RET_ACK = 71 +LSDMA_PERF_SEL_ATCL2_FREE = 72 +LSDMA_PERF_SEL_SDMA_ATCL2_SEND = 73 +LSDMA_PERF_SEL_DMA_L1_WR_SEND = 74 +LSDMA_PERF_SEL_DMA_L1_RD_SEND = 75 +LSDMA_PERF_SEL_DMA_MC_WR_SEND = 76 +LSDMA_PERF_SEL_DMA_MC_RD_SEND = 77 +LSDMA_PERF_SEL_L1_WR_FIFO_IDLE = 78 +LSDMA_PERF_SEL_L1_RD_FIFO_IDLE = 79 +LSDMA_PERF_SEL_L1_WRL2_IDLE = 80 +LSDMA_PERF_SEL_L1_RDL2_IDLE = 81 +LSDMA_PERF_SEL_L1_WRMC_IDLE = 82 +LSDMA_PERF_SEL_L1_RDMC_IDLE = 83 +LSDMA_PERF_SEL_L1_WR_INV_IDLE = 84 +LSDMA_PERF_SEL_L1_RD_INV_IDLE = 85 +LSDMA_PERF_SEL_L1_WR_INV_EN = 86 +LSDMA_PERF_SEL_L1_RD_INV_EN = 87 +LSDMA_PERF_SEL_L1_WR_WAIT_INVADR = 88 +LSDMA_PERF_SEL_L1_RD_WAIT_INVADR = 89 +LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR = 90 +LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD = 91 +LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT = 92 +LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT = 93 +LSDMA_PERF_SEL_L1_INV_MIDDLE = 94 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ = 95 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET = 96 +LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ = 97 +LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET = 98 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ = 99 +LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET = 100 +LSDMA_PERF_SEL_RB_MMHUB_RD_REQ = 101 +LSDMA_PERF_SEL_RB_MMHUB_RD_RET = 102 +LSDMA_PERF_SEL_IB_MMHUB_RD_REQ = 103 +LSDMA_PERF_SEL_IB_MMHUB_RD_RET = 104 +LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ = 105 +LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET = 106 +LSDMA_PERF_SEL_UTCL1_UTCL2_REQ = 107 +LSDMA_PERF_SEL_UTCL1_UTCL2_RET = 108 +LSDMA_PERF_SEL_CMD_OP_MATCH = 109 +LSDMA_PERF_SEL_CMD_OP_START = 110 +LSDMA_PERF_SEL_CMD_OP_END = 111 +LSDMA_PERF_SEL_CE_BUSY = 112 +LSDMA_PERF_SEL_CE_BUSY_START = 113 +LSDMA_PERF_SEL_CE_BUSY_END = 114 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER = 115 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START = 116 +LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END = 117 +LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND = 118 +LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID = 119 +LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND = 120 +LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID = 121 +LSDMA_PERF_SEL_DRAM_ECC = 122 +LSDMA_PERF_SEL_NACK_GEN_ERR = 123 +LSDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'EFC_SURFACE_PIXEL_FORMAT' +EFC_SURFACE_PIXEL_FORMAT__enumvalues = { + 1: 'EFC_ARGB1555', + 2: 'EFC_RGBA5551', + 3: 'EFC_RGB565', + 4: 'EFC_BGR565', + 5: 'EFC_ARGB4444', + 6: 'EFC_RGBA4444', + 8: 'EFC_ARGB8888', + 9: 'EFC_RGBA8888', + 10: 'EFC_ARGB2101010', + 11: 'EFC_RGBA1010102', + 12: 'EFC_AYCrCb8888', + 13: 'EFC_YCrCbA8888', + 14: 'EFC_ACrYCb8888', + 15: 'EFC_CrYCbA8888', + 16: 'EFC_ARGB16161616_10MSB', + 17: 'EFC_RGBA16161616_10MSB', + 18: 'EFC_ARGB16161616_10LSB', + 19: 'EFC_RGBA16161616_10LSB', + 20: 'EFC_ARGB16161616_12MSB', + 21: 'EFC_RGBA16161616_12MSB', + 22: 'EFC_ARGB16161616_12LSB', + 23: 'EFC_RGBA16161616_12LSB', + 24: 'EFC_ARGB16161616_FLOAT', + 25: 'EFC_RGBA16161616_FLOAT', + 26: 'EFC_ARGB16161616_UNORM', + 27: 'EFC_RGBA16161616_UNORM', + 28: 'EFC_ARGB16161616_SNORM', + 29: 'EFC_RGBA16161616_SNORM', + 32: 'EFC_AYCrCb16161616_10MSB', + 33: 'EFC_AYCrCb16161616_10LSB', + 34: 'EFC_YCrCbA16161616_10MSB', + 35: 'EFC_YCrCbA16161616_10LSB', + 36: 'EFC_ACrYCb16161616_10MSB', + 37: 'EFC_ACrYCb16161616_10LSB', + 38: 'EFC_CrYCbA16161616_10MSB', + 39: 'EFC_CrYCbA16161616_10LSB', + 40: 'EFC_AYCrCb16161616_12MSB', + 41: 'EFC_AYCrCb16161616_12LSB', + 42: 'EFC_YCrCbA16161616_12MSB', + 43: 'EFC_YCrCbA16161616_12LSB', + 44: 'EFC_ACrYCb16161616_12MSB', + 45: 'EFC_ACrYCb16161616_12LSB', + 46: 'EFC_CrYCbA16161616_12MSB', + 47: 'EFC_CrYCbA16161616_12LSB', + 64: 'EFC_Y8_CrCb88_420_PLANAR', + 65: 'EFC_Y8_CbCr88_420_PLANAR', + 66: 'EFC_Y10_CrCb1010_420_PLANAR', + 67: 'EFC_Y10_CbCr1010_420_PLANAR', + 68: 'EFC_Y12_CrCb1212_420_PLANAR', + 69: 'EFC_Y12_CbCr1212_420_PLANAR', + 72: 'EFC_YCrYCb8888_422_PACKED', + 73: 'EFC_YCbYCr8888_422_PACKED', + 74: 'EFC_CrYCbY8888_422_PACKED', + 75: 'EFC_CbYCrY8888_422_PACKED', + 76: 'EFC_YCrYCb10101010_422_PACKED', + 77: 'EFC_YCbYCr10101010_422_PACKED', + 78: 'EFC_CrYCbY10101010_422_PACKED', + 79: 'EFC_CbYCrY10101010_422_PACKED', + 80: 'EFC_YCrYCb12121212_422_PACKED', + 81: 'EFC_YCbYCr12121212_422_PACKED', + 82: 'EFC_CrYCbY12121212_422_PACKED', + 83: 'EFC_CbYCrY12121212_422_PACKED', + 112: 'EFC_RGB111110_FIX', + 113: 'EFC_BGR101111_FIX', + 114: 'EFC_ACrYCb2101010', + 115: 'EFC_CrYCbA1010102', + 118: 'EFC_RGB111110_FLOAT', + 119: 'EFC_BGR101111_FLOAT', + 120: 'EFC_MONO_8', + 121: 'EFC_MONO_10MSB', + 122: 'EFC_MONO_10LSB', + 123: 'EFC_MONO_12MSB', + 124: 'EFC_MONO_12LSB', + 125: 'EFC_MONO_16', +} +EFC_ARGB1555 = 1 +EFC_RGBA5551 = 2 +EFC_RGB565 = 3 +EFC_BGR565 = 4 +EFC_ARGB4444 = 5 +EFC_RGBA4444 = 6 +EFC_ARGB8888 = 8 +EFC_RGBA8888 = 9 +EFC_ARGB2101010 = 10 +EFC_RGBA1010102 = 11 +EFC_AYCrCb8888 = 12 +EFC_YCrCbA8888 = 13 +EFC_ACrYCb8888 = 14 +EFC_CrYCbA8888 = 15 +EFC_ARGB16161616_10MSB = 16 +EFC_RGBA16161616_10MSB = 17 +EFC_ARGB16161616_10LSB = 18 +EFC_RGBA16161616_10LSB = 19 +EFC_ARGB16161616_12MSB = 20 +EFC_RGBA16161616_12MSB = 21 +EFC_ARGB16161616_12LSB = 22 +EFC_RGBA16161616_12LSB = 23 +EFC_ARGB16161616_FLOAT = 24 +EFC_RGBA16161616_FLOAT = 25 +EFC_ARGB16161616_UNORM = 26 +EFC_RGBA16161616_UNORM = 27 +EFC_ARGB16161616_SNORM = 28 +EFC_RGBA16161616_SNORM = 29 +EFC_AYCrCb16161616_10MSB = 32 +EFC_AYCrCb16161616_10LSB = 33 +EFC_YCrCbA16161616_10MSB = 34 +EFC_YCrCbA16161616_10LSB = 35 +EFC_ACrYCb16161616_10MSB = 36 +EFC_ACrYCb16161616_10LSB = 37 +EFC_CrYCbA16161616_10MSB = 38 +EFC_CrYCbA16161616_10LSB = 39 +EFC_AYCrCb16161616_12MSB = 40 +EFC_AYCrCb16161616_12LSB = 41 +EFC_YCrCbA16161616_12MSB = 42 +EFC_YCrCbA16161616_12LSB = 43 +EFC_ACrYCb16161616_12MSB = 44 +EFC_ACrYCb16161616_12LSB = 45 +EFC_CrYCbA16161616_12MSB = 46 +EFC_CrYCbA16161616_12LSB = 47 +EFC_Y8_CrCb88_420_PLANAR = 64 +EFC_Y8_CbCr88_420_PLANAR = 65 +EFC_Y10_CrCb1010_420_PLANAR = 66 +EFC_Y10_CbCr1010_420_PLANAR = 67 +EFC_Y12_CrCb1212_420_PLANAR = 68 +EFC_Y12_CbCr1212_420_PLANAR = 69 +EFC_YCrYCb8888_422_PACKED = 72 +EFC_YCbYCr8888_422_PACKED = 73 +EFC_CrYCbY8888_422_PACKED = 74 +EFC_CbYCrY8888_422_PACKED = 75 +EFC_YCrYCb10101010_422_PACKED = 76 +EFC_YCbYCr10101010_422_PACKED = 77 +EFC_CrYCbY10101010_422_PACKED = 78 +EFC_CbYCrY10101010_422_PACKED = 79 +EFC_YCrYCb12121212_422_PACKED = 80 +EFC_YCbYCr12121212_422_PACKED = 81 +EFC_CrYCbY12121212_422_PACKED = 82 +EFC_CbYCrY12121212_422_PACKED = 83 +EFC_RGB111110_FIX = 112 +EFC_BGR101111_FIX = 113 +EFC_ACrYCb2101010 = 114 +EFC_CrYCbA1010102 = 115 +EFC_RGB111110_FLOAT = 118 +EFC_BGR101111_FLOAT = 119 +EFC_MONO_8 = 120 +EFC_MONO_10MSB = 121 +EFC_MONO_10LSB = 122 +EFC_MONO_12MSB = 123 +EFC_MONO_12LSB = 124 +EFC_MONO_16 = 125 +EFC_SURFACE_PIXEL_FORMAT = ctypes.c_uint32 # enum +__all__ = \ + ['ACCEPT_UNSOLICITED_RESPONSE_ENABLE', + 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', 'ACP_TYPE_DVD_AUDIO', + 'ACP_TYPE_GENERIC_AUDIO', 'ACP_TYPE_ICE60958_AUDIO', + 'ACP_TYPE_SUPER_AUDIO_CD', 'ACrYCb16161616_10LSB', + 'ACrYCb16161616_10MSB', 'ACrYCb16161616_12LSB', + 'ACrYCb16161616_12MSB', 'ACrYCb2101010', 'ACrYCb8888', + 'AFMT_ACP_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_ACP_SOURCE_FROM_AZALIA', 'AFMT_ACP_TYPE', + 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', + 'AFMT_AUDIO_CRC_AUTO_RESTART', 'AFMT_AUDIO_CRC_CH0_SIG', + 'AFMT_AUDIO_CRC_CH1_SIG', 'AFMT_AUDIO_CRC_CH2_SIG', + 'AFMT_AUDIO_CRC_CH3_SIG', 'AFMT_AUDIO_CRC_CH4_SIG', + 'AFMT_AUDIO_CRC_CH5_SIG', 'AFMT_AUDIO_CRC_CH6_SIG', + 'AFMT_AUDIO_CRC_CH7_SIG', 'AFMT_AUDIO_CRC_CONTROL_CH_SEL', + 'AFMT_AUDIO_CRC_CONTROL_CONT', 'AFMT_AUDIO_CRC_CONTROL_SOURCE', + 'AFMT_AUDIO_CRC_ONESHOT', 'AFMT_AUDIO_CRC_RESERVED_10', + 'AFMT_AUDIO_CRC_RESERVED_11', 'AFMT_AUDIO_CRC_RESERVED_12', + 'AFMT_AUDIO_CRC_RESERVED_13', 'AFMT_AUDIO_CRC_RESERVED_14', + 'AFMT_AUDIO_CRC_RESERVED_8', 'AFMT_AUDIO_CRC_RESERVED_9', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', + 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', + 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD', + 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND', + 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS', + 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 'AFMT_AUDIO_PACKET_SENT_ENABLED', 'AFMT_AUDIO_SRC_CONTROL_SELECT', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', + 'AFMT_HDMI_AUDIO_SEND_MAX_PACKETS', + 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE', + 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 'AFMT_INTERRUPT_DISABLE', 'AFMT_INTERRUPT_ENABLE', + 'AFMT_INTERRUPT_STATUS_CHG_MASK', 'AFMT_MEM_DISABLE_MEM_PWR_CTRL', + 'AFMT_MEM_ENABLE_MEM_PWR_CTRL', + 'AFMT_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'AFMT_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'AFMT_MEM_FORCE_SHUT_DOWN_REQUEST', 'AFMT_MEM_NO_FORCE_REQUEST', + 'AFMT_MEM_PWR_DIS_CTRL', 'AFMT_MEM_PWR_FORCE_CTRL', + 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 'AFMT_RAMP_CONTROL0_SIGN', 'AFMT_RAMP_SIGNED', + 'AFMT_RAMP_UNSIGNED', 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', + 'AFMT_VBI_PACKET_CONTROL_ACP_SOURCE', 'ALLOW_SR_ON_TRANS_REQ', + 'ALLOW_SR_ON_TRANS_REQ_DISABLE', 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 'ALL_USE_R', 'ALPHA_DATA_ONTO_ALPHA_PORT', + 'ALPHA_DATA_ONTO_CB_B_PORT', 'ALPHA_DATA_ONTO_CR_R_PORT', + 'ALPHA_DATA_ONTO_Y_G_PORT', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', 'AMCLOCK_ENABLE', + 'APG_ACP_OVERRIDE', 'APG_ACP_SOURCE_NO_OVERRIDE', + 'APG_ACP_TYPE_DVD_AUDIO', 'APG_ACP_TYPE_GENERIC_AUDIO', + 'APG_ACP_TYPE_ICE60958_AUDIO', 'APG_ACP_TYPE_SUPER_AUDIO_CD', + 'APG_AUDIO_CRC_CH0_SIG', 'APG_AUDIO_CRC_CH1_SIG', + 'APG_AUDIO_CRC_CH2_SIG', 'APG_AUDIO_CRC_CH3_SIG', + 'APG_AUDIO_CRC_CH4_SIG', 'APG_AUDIO_CRC_CH5_SIG', + 'APG_AUDIO_CRC_CH6_SIG', 'APG_AUDIO_CRC_CH7_SIG', + 'APG_AUDIO_CRC_CONTINUOUS', 'APG_AUDIO_CRC_CONTROL_CH_SEL', + 'APG_AUDIO_CRC_CONTROL_CONT', 'APG_AUDIO_CRC_ONESHOT', + 'APG_AUDIO_CRC_RESERVED_10', 'APG_AUDIO_CRC_RESERVED_11', + 'APG_AUDIO_CRC_RESERVED_12', 'APG_AUDIO_CRC_RESERVED_13', + 'APG_AUDIO_CRC_RESERVED_14', 'APG_AUDIO_CRC_RESERVED_15', + 'APG_AUDIO_CRC_RESERVED_8', 'APG_AUDIO_CRC_RESERVED_9', + 'APG_DBG_ACP_TYPE', 'APG_DBG_AUDIO_DTO_BASE', + 'APG_DBG_AUDIO_DTO_DIV', 'APG_DBG_AUDIO_DTO_MULTI', + 'APG_DBG_MUX_SEL', 'APG_DEBUG_AUDIO_MODE', + 'APG_DP_ASP_CHANNEL_COUNT_FROM_AZ', + 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE', + 'APG_DP_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'APG_FUNCTIONAL_MODE', 'APG_INFOFRAME_SOURCE_FROM_APG_REGISTERS', + 'APG_INFOFRAME_SOURCE_NO_OVERRIDE', + 'APG_MEM_DISABLE_MEM_PWR_CTRL', 'APG_MEM_ENABLE_MEM_PWR_CTRL', + 'APG_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'APG_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'APG_MEM_FORCE_SHUT_DOWN_REQUEST', 'APG_MEM_NO_FORCE_REQUEST', + 'APG_MEM_POWER_STATE', 'APG_MEM_POWER_STATE_DS', + 'APG_MEM_POWER_STATE_LS', 'APG_MEM_POWER_STATE_ON', + 'APG_MEM_POWER_STATE_SD', 'APG_MEM_PWR_DIS_CTRL', + 'APG_MEM_PWR_FORCE_CTRL', 'APG_PACKET_CONTROL_ACP_SOURCE', + 'APG_PACKET_CONTROL_AUDIO_INFO_SOURCE', 'APG_RAMP_CONTROL_SIGN', + 'APG_RAMP_SIGNED', 'APG_RAMP_UNSIGNED', 'ARGB1555', + 'ARGB16161616_10LSB', 'ARGB16161616_10MSB', 'ARGB16161616_12LSB', + 'ARGB16161616_12MSB', 'ARGB16161616_FLOAT', 'ARGB16161616_SNORM', + 'ARGB16161616_UNORM', 'ARGB2101010', 'ARGB4444', 'ARGB8888', + 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', 'AUDIO_LAYOUT_SELECT', + 'AUTOCAL_MODE_AUTOCENTER', 'AUTOCAL_MODE_AUTOREPLICATE', + 'AUTOCAL_MODE_AUTOSCALE', 'AUTOCAL_MODE_OFF', + 'AYCrCb16161616_10LSB', 'AYCrCb16161616_10MSB', + 'AYCrCb16161616_12LSB', 'AYCrCb16161616_12MSB', 'AYCrCb8888', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_0', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_1', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_10', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_11', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_12', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_13', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_14', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_15', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_2', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_3', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_4', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_5', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_6', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_7', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_8', + 'AZALIA_F2_CODEC_PIN_CONTROL_AUDIO_DESCRIPTOR_FORMAT_CODE_9', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', + 'AZ_CORB_SIZE', 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 'AZ_CORB_SIZE_256ENTRIES', 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 'AZ_CORB_SIZE_RESERVED', 'AZ_GLOBAL_CAPABILITIES', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', + 'AZ_LATENCY_COUNTER_CONTROL', 'AZ_LATENCY_COUNTER_NO_RESET', + 'AZ_LATENCY_COUNTER_RESET_DONE', 'AZ_RIRB_SIZE', + 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', 'AZ_RIRB_SIZE_256ENTRIES', + 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', 'AZ_RIRB_SIZE_UNDEFINED', + 'AZ_RIRB_WRITE_POINTER_DO_RESET', + 'AZ_RIRB_WRITE_POINTER_NOT_RESET', 'AZ_RIRB_WRITE_POINTER_RESET', + 'AZ_STATE_CHANGE_STATUS', + 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', 'BASE_RATE_44P1KHZ', + 'BASE_RATE_48KHZ', 'BGR101111_FIX', 'BGR101111_FLOAT', 'BGR565', + 'BIGK_FRAGMENT_SIZE', 'BINNER_BREAK_BATCH', 'BINNER_DROP', + 'BINNER_PIPELINE', 'BINNER_PIPELINE_BREAK', 'BINNING_ALLOWED', + 'BINNING_DISABLED', 'BINNING_ONE_PRIM_PER_BATCH', + 'BIN_CONF_OVERRIDE_CHECK', 'BIN_MAP_MODE_NONE', + 'BIN_MAP_MODE_POPS', 'BIN_MAP_MODE_RTA_INDEX', + 'BIN_SIZE_128_PIXELS', 'BIN_SIZE_256_PIXELS', + 'BIN_SIZE_32_PIXELS', 'BIN_SIZE_512_PIXELS', 'BIN_SIZE_64_PIXELS', + 'BITS_31_0', 'BITS_32_1', 'BITS_33_2', 'BITS_34_3', 'BITS_35_4', + 'BITS_36_5', 'BITS_37_6', 'BITS_38_7', 'BLEND_CONSTANT_ALPHA', + 'BLEND_CONSTANT_COLOR', 'BLEND_DST_ALPHA', 'BLEND_DST_COLOR', + 'BLEND_INV_SRC1_ALPHA', 'BLEND_INV_SRC1_COLOR', 'BLEND_ONE', + 'BLEND_ONE_MINUS_CONSTANT_ALPHA', + 'BLEND_ONE_MINUS_CONSTANT_COLOR', 'BLEND_ONE_MINUS_DST_ALPHA', + 'BLEND_ONE_MINUS_DST_COLOR', 'BLEND_ONE_MINUS_SRC_ALPHA', + 'BLEND_ONE_MINUS_SRC_COLOR', 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', 'BLEND_SRC1_ALPHA', + 'BLEND_SRC1_COLOR', 'BLEND_SRC_ALPHA', 'BLEND_SRC_ALPHA_SATURATE', + 'BLEND_SRC_COLOR', 'BLEND_ZERO', 'BLOCK_CONTEXT_DONE', 'BLUE_LUT', + 'BOTTOM_OF_PIPE_TS', 'BREAK_BATCH', 'BYPASS', 'BYPASS_EN', + 'BYPASS_POST_CSC', 'BinEventCntl', 'BinMapMode', 'BinSizeExtend', + 'BinningMode', 'BlendOp', 'BlendOpt', 'CACHE_BYPASS', + 'CACHE_FLUSH', 'CACHE_FLUSH_AND_INV_EVENT', + 'CACHE_FLUSH_AND_INV_TS_EVENT', 'CACHE_FLUSH_TS', 'CACHE_LRU_RD', + 'CACHE_LRU_WR', 'CACHE_NOA', 'CACHE_NOA_WR', 'CACHE_STREAM', + 'CACHE_STREAM_RD', 'CBMode', 'CBPerfClearFilterSel', + 'CBPerfOpFilterSel', 'CBPerfSel', 'CB_B_DATA_ONTO_ALPHA_PORT', + 'CB_B_DATA_ONTO_CB_B_PORT', 'CB_B_DATA_ONTO_CR_R_PORT', + 'CB_B_DATA_ONTO_Y_G_PORT', 'CB_DCC_DECOMPRESS', 'CB_DISABLE', + 'CB_ELIMINATE_FAST_CLEAR', 'CB_NORMAL', + 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', + 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', + 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 'CB_PERF_SEL_BACKEND_CACHE_CTL_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_EVICT_PIPE_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_FRAGOP_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_READ_CLOCK_EN', + 'CB_PERF_SEL_BACKEND_SRC_FIFO_CLOCK_EN', + 'CB_PERF_SEL_BE_CS_FILLRATE_1X2', + 'CB_PERF_SEL_BE_CS_FILLRATE_2X1', + 'CB_PERF_SEL_BE_CS_FILLRATE_2X2', 'CB_PERF_SEL_BE_RDLATFIFO_FULL', + 'CB_PERF_SEL_BE_SRCFIFO_FULL', 'CB_PERF_SEL_BLEND_CLOCK_EN', + 'CB_PERF_SEL_BLEND_COLLISION_DUE_TO_CACHE_WRITE', + 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 'CB_PERF_SEL_BLEND_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 'CB_PERF_SEL_BLEND_QUAD_COULD_HAVE_BEEN_DISCARDED', + 'CB_PERF_SEL_BLEND_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 'CB_PERF_SEL_BLEND_RAW_HAZARD_STALL', + 'CB_PERF_SEL_BLEND_STALL_AT_OUTPUT', + 'CB_PERF_SEL_BLEND_STALL_ON_CACHE_ACCESS', 'CB_PERF_SEL_BUSY', + 'CB_PERF_SEL_CCC_COLOR_RESOURCE_PANIC', + 'CB_PERF_SEL_CCC_COLOR_RESOURCE_STALL', + 'CB_PERF_SEL_CCC_FMASK_RESOURCE_PANIC', + 'CB_PERF_SEL_CCC_FMASK_RESOURCE_STALL', + 'CB_PERF_SEL_CCC_FREE_WAYS_PANIC', + 'CB_PERF_SEL_CCC_FREE_WAYS_STALL', + 'CB_PERF_SEL_CCC_IN_EVICT_HAZARD_STALL', + 'CB_PERF_SEL_CCC_SKID_FIFO_FULL', + 'CB_PERF_SEL_CCC_SKID_FIFO_STALL', + 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READY', + 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALIDB_READYB', + 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READY', + 'CB_PERF_SEL_CC_BB_BLEND_PIXEL_VALID_READYB', + 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_DIRTY_QBLOCKS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_FLUSH', + 'CB_PERF_SEL_CC_CACHE_QBLOCKS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_SECTOR_HIT', + 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CC_CACHE_STALL', + 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST', + 'CB_PERF_SEL_CC_CRW_GLX_REQ_READ_REQUEST_IN_FLIGHT', + 'CB_PERF_SEL_CC_CRW_GLX_REQ_WRITE_REQUEST', + 'CB_PERF_SEL_CC_CRW_GLX_SRC_WRITE_CYCLES', + 'CB_PERF_SEL_CC_FDCC_COMPRESS_FRAG_TIDS_IN', + 'CB_PERF_SEL_CC_FDCC_DECOMPRESS_FRAG_TIDS_OUT', + 'CB_PERF_SEL_CC_QUADFRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_QUADFRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_QUADFRAG_VALID_READY', + 'CB_PERF_SEL_CC_QUADFRAG_VALID_READYB', 'CB_PERF_SEL_CC_TAG_HIT', + 'CB_PERF_SEL_COLOR_STORE_CLOCK_EN', + 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_EXPORT_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READY', + 'CB_PERF_SEL_DB_CB_EXPORT_VALID_READYB', 'CB_PERF_SEL_DRAWN_BUSY', + 'CB_PERF_SEL_DRAWN_PIXEL', 'CB_PERF_SEL_DRAWN_QUAD', + 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', 'CB_PERF_SEL_EVENT', + 'CB_PERF_SEL_EVENTS_CLK_EN', + 'CB_PERF_SEL_EVENT_BOTTOM_OF_PIPE_TS', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 'CB_PERF_SEL_EXPORT_ADDED_1_FRAGMENT', + 'CB_PERF_SEL_EXPORT_ADDED_2_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_ADDED_3_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_ADDED_4_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_ADDED_5_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_ADDED_6_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_ADDED_7_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_BLEND_OPT_BLEND_BYPASS', + 'CB_PERF_SEL_EXPORT_BLEND_OPT_DISCARD_PIXELS', + 'CB_PERF_SEL_EXPORT_BLEND_OPT_DONT_READ_DST', + 'CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_1_FRAGMENT_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_EXPORT_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_EXPORT_KILLED_BY_COLOR_INVALID', + 'CB_PERF_SEL_EXPORT_KILLED_BY_DISCARD_PIXEL', + 'CB_PERF_SEL_EXPORT_KILLED_BY_NULL_SAMPLE_MASK', + 'CB_PERF_SEL_EXPORT_KILLED_BY_NULL_TARGET_SHADER_MASK', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_0', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_1', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_2', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_3', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_4', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_5', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_6', + 'CB_PERF_SEL_EXPORT_READS_FRAGMENT_7', + 'CB_PERF_SEL_EXPORT_REMOVED_1_FRAGMENT', + 'CB_PERF_SEL_EXPORT_REMOVED_2_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_REMOVED_3_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_REMOVED_4_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_REMOVED_5_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_REMOVED_6_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_REMOVED_7_FRAGMENTS', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_0', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_1', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_2', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_3', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_4', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_5', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_6', + 'CB_PERF_SEL_EXPORT_WRITES_FRAGMENT_7', + 'CB_PERF_SEL_FORMAT_IS_16_16_FLOAT_8PIX', + 'CB_PERF_SEL_FORMAT_IS_16_16_SIGNED_8PIX', + 'CB_PERF_SEL_FORMAT_IS_16_16_UNSIGNED_8PIX', + 'CB_PERF_SEL_FORMAT_IS_32BPP_8PIX', + 'CB_PERF_SEL_FORMAT_IS_32_ABGR', 'CB_PERF_SEL_FORMAT_IS_32_AR', + 'CB_PERF_SEL_FORMAT_IS_32_GR', 'CB_PERF_SEL_FORMAT_IS_32_R', + 'CB_PERF_SEL_FORMAT_IS_FP16_ABGR', + 'CB_PERF_SEL_FORMAT_IS_SIGNED16_ABGR', + 'CB_PERF_SEL_FORMAT_IS_UNSIGNED16_ABGR', + 'CB_PERF_SEL_FRONTEND_ADDR_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_FDCC_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_INPUT_CLOCK_EN', + 'CB_PERF_SEL_FRONTEND_SAMPLE_MASK_TRACKER_CLOCK_EN', + 'CB_PERF_SEL_GRBM_CLOCK_EN', 'CB_PERF_SEL_MEMARB_CLOCK_EN', + 'CB_PERF_SEL_PERFMON_CLOCK_EN', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 'CB_PERF_SEL_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_STATIC_CLOCK_EN', 'CB_RESERVED', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 'CENTERS_ONLY', 'CENTROIDS_AND_CENTERS', 'CENTROIDS_ONLY', + 'CHA_PERF_SEL', 'CHA_PERF_SEL_ARB_REQUESTS', 'CHA_PERF_SEL_BUSY', + 'CHA_PERF_SEL_CYCLE', 'CHA_PERF_SEL_IO_32B_WDS_CHC0', + 'CHA_PERF_SEL_IO_32B_WDS_CHC1', 'CHA_PERF_SEL_IO_32B_WDS_CHC2', + 'CHA_PERF_SEL_IO_32B_WDS_CHC3', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_IO_BURST_COUNT_CHC3', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC0', 'CHA_PERF_SEL_MEM_32B_WDS_CHC1', + 'CHA_PERF_SEL_MEM_32B_WDS_CHC2', 'CHA_PERF_SEL_MEM_32B_WDS_CHC3', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC0', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC1', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC2', + 'CHA_PERF_SEL_MEM_BURST_COUNT_CHC3', 'CHA_PERF_SEL_REQUEST_CHC0', + 'CHA_PERF_SEL_REQUEST_CHC1', 'CHA_PERF_SEL_REQUEST_CHC2', + 'CHA_PERF_SEL_REQUEST_CHC3', 'CHA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'CHA_PERF_SEL_STALL_CHC0', 'CHA_PERF_SEL_STALL_CHC1', + 'CHA_PERF_SEL_STALL_CHC2', 'CHA_PERF_SEL_STALL_CHC3', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC0', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC1', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC2', + 'CHA_PERF_SEL_STALL_RET_CONFLICT_CHC3', 'CHC_PERF_SEL', + 'CHC_PERF_SEL_ARB_RET_LEVEL', 'CHC_PERF_SEL_BUSY', + 'CHC_PERF_SEL_CYCLE', 'CHC_PERF_SEL_GL2_REQ_READ_LATENCY', + 'CHC_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'CHC_PERF_SEL_REQ', + 'CHC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'CHC_PERF_SEL_REQ_ATOMIC_WITH_RET', 'CHC_PERF_SEL_REQ_CLIENT0', + 'CHC_PERF_SEL_REQ_CLIENT1', 'CHC_PERF_SEL_REQ_CLIENT10', + 'CHC_PERF_SEL_REQ_CLIENT11', 'CHC_PERF_SEL_REQ_CLIENT12', + 'CHC_PERF_SEL_REQ_CLIENT13', 'CHC_PERF_SEL_REQ_CLIENT14', + 'CHC_PERF_SEL_REQ_CLIENT15', 'CHC_PERF_SEL_REQ_CLIENT16', + 'CHC_PERF_SEL_REQ_CLIENT17', 'CHC_PERF_SEL_REQ_CLIENT18', + 'CHC_PERF_SEL_REQ_CLIENT19', 'CHC_PERF_SEL_REQ_CLIENT2', + 'CHC_PERF_SEL_REQ_CLIENT20', 'CHC_PERF_SEL_REQ_CLIENT21', + 'CHC_PERF_SEL_REQ_CLIENT22', 'CHC_PERF_SEL_REQ_CLIENT23', + 'CHC_PERF_SEL_REQ_CLIENT3', 'CHC_PERF_SEL_REQ_CLIENT4', + 'CHC_PERF_SEL_REQ_CLIENT5', 'CHC_PERF_SEL_REQ_CLIENT6', + 'CHC_PERF_SEL_REQ_CLIENT7', 'CHC_PERF_SEL_REQ_CLIENT8', + 'CHC_PERF_SEL_REQ_CLIENT9', 'CHC_PERF_SEL_REQ_NOP_ACK', + 'CHC_PERF_SEL_REQ_NOP_RTN0', 'CHC_PERF_SEL_REQ_READ', + 'CHC_PERF_SEL_REQ_READ_128B', 'CHC_PERF_SEL_REQ_READ_32B', + 'CHC_PERF_SEL_REQ_READ_64B', 'CHC_PERF_SEL_REQ_WRITE', + 'CHC_PERF_SEL_REQ_WRITE_32B', 'CHC_PERF_SEL_REQ_WRITE_64B', + 'CHC_PERF_SEL_STALL_BUFFER_FULL', 'CHC_PERF_SEL_STALL_GL2_GL1', + 'CHC_PERF_SEL_STARVE', 'CHUNK_SIZE', 'CHUNK_SIZE_16KB', + 'CHUNK_SIZE_1KB', 'CHUNK_SIZE_2KB', 'CHUNK_SIZE_32KB', + 'CHUNK_SIZE_4KB', 'CHUNK_SIZE_64KB', 'CHUNK_SIZE_8KB', + 'CLEAR_SMU_INTR', 'CLKGATE_BASE_MODE', 'CLKGATE_SM_MODE', + 'CLOCK_BRANCH_SOFT_RESET', 'CLOCK_BRANCH_SOFT_RESET_FORCE', + 'CLOCK_BRANCH_SOFT_RESET_NOOP', 'CLOCK_GATING_DISABLE', + 'CLOCK_GATING_DISABLED', 'CLOCK_GATING_DISABLED_IN_DCO', + 'CLOCK_GATING_DISABLE_ENUM', 'CLOCK_GATING_DISABLE_ENUM_DISABLED', + 'CLOCK_GATING_DISABLE_ENUM_ENABLED', 'CLOCK_GATING_EN', + 'CLOCK_GATING_ENABLE', 'CLOCK_GATING_ENABLED', + 'CLOCK_GATING_ENABLED_IN_DCO', 'CMC_3DLUT_17CUBE', + 'CMC_3DLUT_30BIT', 'CMC_3DLUT_30BIT_ENUM', 'CMC_3DLUT_36BIT', + 'CMC_3DLUT_9CUBE', 'CMC_3DLUT_RAM_SEL', 'CMC_3DLUT_SIZE_ENUM', + 'CMC_LUT_2CFG_MEMORY_A', 'CMC_LUT_2CFG_MEMORY_B', + 'CMC_LUT_2CFG_NO_MEMORY', 'CMC_LUT_2_CONFIG_ENUM', + 'CMC_LUT_2_MODE_BYPASS', 'CMC_LUT_2_MODE_ENUM', + 'CMC_LUT_2_MODE_RAMA_LUT', 'CMC_LUT_2_MODE_RAMB_LUT', + 'CMC_LUT_NUM_SEG', 'CMC_LUT_RAM_SEL', 'CMC_RAM0_ACCESS', + 'CMC_RAM1_ACCESS', 'CMC_RAM2_ACCESS', 'CMC_RAM3_ACCESS', + 'CMC_RAMA_ACCESS', 'CMC_RAMB_ACCESS', 'CMC_SEGMENTS_1', + 'CMC_SEGMENTS_128', 'CMC_SEGMENTS_16', 'CMC_SEGMENTS_2', + 'CMC_SEGMENTS_32', 'CMC_SEGMENTS_4', 'CMC_SEGMENTS_64', + 'CMC_SEGMENTS_8', 'CMPTO', 'CM_BYPASS', 'CM_COEF_FORMAT_ENUM', + 'CM_DATA_SIGNED', 'CM_DISABLE', 'CM_EN', 'CM_ENABLE', + 'CM_GAMMA_LUT_MODE_ENUM', 'CM_GAMMA_LUT_PWL_DISABLE_ENUM', + 'CM_GAMMA_LUT_SEL_ENUM', 'CM_LUT_2_CONFIG_ENUM', + 'CM_LUT_2_MODE_ENUM', 'CM_LUT_4_CONFIG_ENUM', + 'CM_LUT_4_MODE_ENUM', 'CM_LUT_CONFIG_MODE', 'CM_LUT_NUM_SEG', + 'CM_LUT_RAM_SEL', 'CM_LUT_READ_COLOR_SEL', 'CM_LUT_READ_DBG', + 'CM_NOT_PENDING', 'CM_PENDING', 'CM_POST_CSC_MODE_ENUM', + 'CM_WRITE_BASE_ONLY', 'CM_YES_PENDING', 'CNVC_ROUND', + 'CNVC_TRUNCATE', 'COEF_POST_CSC', 'COEF_POST_CSC_B', + 'COEF_RAM_SELECT_BACK', 'COEF_RAM_SELECT_CURRENT', + 'COEF_RAM_SELECT_RD', 'COLOR_24BIT_1BIT_AND', + 'COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'COLOR_24BIT_8BIT_ALPHA_UNPREMULT', 'COLOR_64BIT_FP_PREMULT', + 'COLOR_64BIT_FP_UNPREMULT', 'COLOR_KEYER_ENABLE', + 'COLOR_KEYER_MODE', 'COLOR_KEY_DIS', 'COLOR_KEY_EN', + 'COMB_DST_MINUS_SRC', 'COMB_DST_PLUS_SRC', 'COMB_MAX_DST_SRC', + 'COMB_MIN_DST_SRC', 'COMB_SRC_MINUS_DST', + 'COMPRESSION_MODE_BYPASS_COMPRESSION', + 'COMPRESSION_MODE_BYPASS_METADATA_CACHE', + 'COMPRESSION_MODE_COMPRESSION_ENABLED', + 'COMPRESSION_MODE_READ_DECOMPRESSED', + 'COMPRESSION_MODE_READ_RAW_COMPRESSED_DATA', + 'COMPRESSION_MODE_WRITE_COMPRESSION_DISABLED', + 'CONFIG_SPACE1_END', 'CONFIG_SPACE1_START', 'CONFIG_SPACE2_END', + 'CONFIG_SPACE2_START', 'CONFIG_SPACE_END', 'CONFIG_SPACE_START', + 'CONTEXT_DONE', 'CONTEXT_SPACE_END', 'CONTEXT_SPACE_START', + 'CONTEXT_SUSPEND', 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', + 'CORB_READ_POINTER_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', 'COUNTER_RING_0', + 'COUNTER_RING_1', 'COUNTER_RING_SPLIT', 'CPC_LATENCY_STATS_SEL', + 'CPC_LATENCY_STATS_SEL_INVAL_LAST', + 'CPC_LATENCY_STATS_SEL_INVAL_MAX', + 'CPC_LATENCY_STATS_SEL_INVAL_MIN', + 'CPC_LATENCY_STATS_SEL_XACK_LAST', + 'CPC_LATENCY_STATS_SEL_XACK_MAX', + 'CPC_LATENCY_STATS_SEL_XACK_MIN', + 'CPC_LATENCY_STATS_SEL_XNACK_LAST', + 'CPC_LATENCY_STATS_SEL_XNACK_MAX', + 'CPC_LATENCY_STATS_SEL_XNACK_MIN', 'CPC_PERFCOUNT_SEL', + 'CPC_PERF_SEL_ALWAYS_COUNT', 'CPC_PERF_SEL_CPC_GCRIU_BUSY', + 'CPC_PERF_SEL_CPC_GCRIU_IDLE', 'CPC_PERF_SEL_CPC_GCRIU_STALL', + 'CPC_PERF_SEL_CPC_STAT_BUSY', 'CPC_PERF_SEL_CPC_STAT_IDLE', + 'CPC_PERF_SEL_CPC_STAT_STALL', 'CPC_PERF_SEL_CPC_TCIU_BUSY', + 'CPC_PERF_SEL_CPC_TCIU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_BUSY', + 'CPC_PERF_SEL_CPC_UTCL2IU_IDLE', 'CPC_PERF_SEL_CPC_UTCL2IU_STALL', + 'CPC_PERF_SEL_CPC_UTCL2IU_XACK', 'CPC_PERF_SEL_CPC_UTCL2IU_XNACK', + 'CPC_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPC_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME1_DC0_SPI_BUSY', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MEM_WRITE', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME2_DC1_SPI_BUSY', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MEM_WRITE', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_TCIU_READ', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_HIT', + 'CPC_PERF_SEL_MEC_INSTR_CACHE_MISS', 'CPC_PERF_SEL_MEC_THREAD0', + 'CPC_PERF_SEL_MEC_THREAD1', 'CPC_PERF_SEL_MEC_THREAD2', + 'CPC_PERF_SEL_MEC_THREAD3', 'CPC_PERF_SEL_MES_THREAD0', + 'CPC_PERF_SEL_MES_THREAD1', + 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 'CPC_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPC_TAG_RAM', + 'CPF_LATENCY_STATS_SEL', 'CPF_LATENCY_STATS_SEL_INVAL_LAST', + 'CPF_LATENCY_STATS_SEL_INVAL_MAX', + 'CPF_LATENCY_STATS_SEL_INVAL_MIN', + 'CPF_LATENCY_STATS_SEL_READ_LAST', + 'CPF_LATENCY_STATS_SEL_READ_MAX', + 'CPF_LATENCY_STATS_SEL_READ_MIN', + 'CPF_LATENCY_STATS_SEL_XACK_LAST', + 'CPF_LATENCY_STATS_SEL_XACK_MAX', + 'CPF_LATENCY_STATS_SEL_XACK_MIN', + 'CPF_LATENCY_STATS_SEL_XNACK_LAST', + 'CPF_LATENCY_STATS_SEL_XNACK_MAX', + 'CPF_LATENCY_STATS_SEL_XNACK_MIN', 'CPF_PERFCOUNTWINDOW_SEL', + 'CPF_PERFCOUNT_SEL', 'CPF_PERFWINDOW_SEL_CSF', + 'CPF_PERFWINDOW_SEL_HQD1', 'CPF_PERFWINDOW_SEL_HQD2', + 'CPF_PERFWINDOW_SEL_RDMA', 'CPF_PERFWINDOW_SEL_RWPP', + 'CPF_PERF_SEL_ALWAYS_COUNT', + 'CPF_PERF_SEL_CMP_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_CPF_GCRIU_BUSY', 'CPF_PERF_SEL_CPF_GCRIU_IDLE', + 'CPF_PERF_SEL_CPF_GCRIU_STALL', 'CPF_PERF_SEL_CPF_STAT_BUSY', + 'CPF_PERF_SEL_CPF_STAT_IDLE', 'CPF_PERF_SEL_CPF_STAT_STALL', + 'CPF_PERF_SEL_CPF_TCIU_BUSY', 'CPF_PERF_SEL_CPF_TCIU_IDLE', + 'CPF_PERF_SEL_CPF_TCIU_STALL', 'CPF_PERF_SEL_CPF_UTCL2IU_BUSY', + 'CPF_PERF_SEL_CPF_UTCL2IU_IDLE', 'CPF_PERF_SEL_CPF_UTCL2IU_STALL', + 'CPF_PERF_SEL_CPF_UTCL2IU_XACK', 'CPF_PERF_SEL_CPF_UTCL2IU_XNACK', + 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_DONE', + 'CPF_PERF_SEL_CP_SDMA_MNGR_DMA_REQ', + 'CPF_PERF_SEL_CP_SDMA_MNGR_LATENCY', + 'CPF_PERF_SEL_CP_SDMA_MNGR_SDMABUSY', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_DB', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_STATE', + 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 'CPF_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_GFX_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 'CPF_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPF_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 'CPF_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 'CPF_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 'CPF_SCRATCH_REG_ATOMIC_ADD', 'CPF_SCRATCH_REG_ATOMIC_AND', + 'CPF_SCRATCH_REG_ATOMIC_CMPSWAP', 'CPF_SCRATCH_REG_ATOMIC_MAX', + 'CPF_SCRATCH_REG_ATOMIC_MIN', 'CPF_SCRATCH_REG_ATOMIC_NOT', + 'CPF_SCRATCH_REG_ATOMIC_OP', 'CPF_SCRATCH_REG_ATOMIC_OR', + 'CPF_SCRATCH_REG_ATOMIC_SUB', 'CPF_TAG_RAM', + 'CPG_LATENCY_STATS_SEL', 'CPG_LATENCY_STATS_SEL_ATOMIC_LAST', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MAX', + 'CPG_LATENCY_STATS_SEL_ATOMIC_MIN', + 'CPG_LATENCY_STATS_SEL_INVAL_LAST', + 'CPG_LATENCY_STATS_SEL_INVAL_MAX', + 'CPG_LATENCY_STATS_SEL_INVAL_MIN', + 'CPG_LATENCY_STATS_SEL_READ_LAST', + 'CPG_LATENCY_STATS_SEL_READ_MAX', + 'CPG_LATENCY_STATS_SEL_READ_MIN', + 'CPG_LATENCY_STATS_SEL_WRITE_LAST', + 'CPG_LATENCY_STATS_SEL_WRITE_MAX', + 'CPG_LATENCY_STATS_SEL_WRITE_MIN', + 'CPG_LATENCY_STATS_SEL_XACK_LAST', + 'CPG_LATENCY_STATS_SEL_XACK_MAX', + 'CPG_LATENCY_STATS_SEL_XACK_MIN', + 'CPG_LATENCY_STATS_SEL_XNACK_LAST', + 'CPG_LATENCY_STATS_SEL_XNACK_MAX', + 'CPG_LATENCY_STATS_SEL_XNACK_MIN', 'CPG_PERFCOUNTWINDOW_SEL', + 'CPG_PERFCOUNT_SEL', 'CPG_PERFWINDOW_SEL_APPEND', + 'CPG_PERFWINDOW_SEL_CE', 'CPG_PERFWINDOW_SEL_CEDMA', + 'CPG_PERFWINDOW_SEL_CPC_IC', 'CPG_PERFWINDOW_SEL_CPG_IC', + 'CPG_PERFWINDOW_SEL_DDID', 'CPG_PERFWINDOW_SEL_DFY', + 'CPG_PERFWINDOW_SEL_DMA', 'CPG_PERFWINDOW_SEL_ME', + 'CPG_PERFWINDOW_SEL_MEC1', 'CPG_PERFWINDOW_SEL_MEC2', + 'CPG_PERFWINDOW_SEL_MEMRD', 'CPG_PERFWINDOW_SEL_MEMWR', + 'CPG_PERFWINDOW_SEL_MES', 'CPG_PERFWINDOW_SEL_PFP', + 'CPG_PERFWINDOW_SEL_PQ1', 'CPG_PERFWINDOW_SEL_PQ2', + 'CPG_PERFWINDOW_SEL_PQ3', 'CPG_PERFWINDOW_SEL_PRT_HDR_RPTR', + 'CPG_PERFWINDOW_SEL_PRT_SMP_RPTR', 'CPG_PERFWINDOW_SEL_QURD', + 'CPG_PERFWINDOW_SEL_QU_EOP', 'CPG_PERFWINDOW_SEL_QU_PIPE', + 'CPG_PERFWINDOW_SEL_QU_STRM', 'CPG_PERFWINDOW_SEL_RB', + 'CPG_PERFWINDOW_SEL_RESERVED1', 'CPG_PERFWINDOW_SEL_RESERVED2', + 'CPG_PERFWINDOW_SEL_SHADOW', 'CPG_PERFWINDOW_SEL_SR', + 'CPG_PERFWINDOW_SEL_VGT0', 'CPG_PERFWINDOW_SEL_VGT1', + 'CPG_PERF_SEL_ALL_GFX_PIPES_BUSY', 'CPG_PERF_SEL_ALWAYS_COUNT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_CE_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', 'CPG_PERF_SEL_CPG_GCRIU_BUSY', + 'CPG_PERF_SEL_CPG_GCRIU_IDLE', 'CPG_PERF_SEL_CPG_GCRIU_STALL', + 'CPG_PERF_SEL_CPG_STAT_BUSY', 'CPG_PERF_SEL_CPG_STAT_IDLE', + 'CPG_PERF_SEL_CPG_STAT_STALL', 'CPG_PERF_SEL_CPG_TCIU_BUSY', + 'CPG_PERF_SEL_CPG_TCIU_IDLE', 'CPG_PERF_SEL_CPG_TCIU_STALL', + 'CPG_PERF_SEL_CPG_UTCL2IU_BUSY', 'CPG_PERF_SEL_CPG_UTCL2IU_IDLE', + 'CPG_PERF_SEL_CPG_UTCL2IU_STALL', 'CPG_PERF_SEL_CPG_UTCL2IU_XACK', + 'CPG_PERF_SEL_CPG_UTCL2IU_XNACK', + 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_DMA_BUSY', + 'CPG_PERF_SEL_DMA_FETCHER_STALLED_ON_ROQ_FULL', + 'CPG_PERF_SEL_DMA_STALLED', 'CPG_PERF_SEL_DMA_STARVED', + 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 'CPG_PERF_SEL_GCRIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_GUS_READ_REQUEST_SENT', + 'CPG_PERF_SEL_GUS_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 'CPG_PERF_SEL_ME_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_ME_INSTR_CACHE_MISS', 'CPG_PERF_SEL_ME_PARSER_BUSY', + 'CPG_PERF_SEL_ME_PWS_STALLED0', 'CPG_PERF_SEL_ME_PWS_STALLED1', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_HIT', + 'CPG_PERF_SEL_PFP_INSTR_CACHE_MISS', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_HIT_IB2', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB1', + 'CPG_PERF_SEL_PFP_PACKET_FILTER_MISS_IB2', + 'CPG_PERF_SEL_PFP_PWS_STALLED0', 'CPG_PERF_SEL_PFP_PWS_STALLED1', + 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_DDID_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 'CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL0', + 'CPG_PERF_SEL_PFP_VGTDMA_DB_ROQ_DATA_STALL1', + 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS0', + 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_BYPASS1', + 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS0', + 'CPG_PERF_SEL_PFP_VGTDMA_INDR_STRUCT_NOT_BYPASS1', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 'CPG_PERF_SEL_TCIU_READ_REQUEST_SENT', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 'CPG_PERF_SEL_TCIU_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPG_TAG_RAM', + 'CP_ALPHA_TAG_RAM_SEL', 'CP_DDID_CNTL_MODE', 'CP_DDID_CNTL_SIZE', + 'CP_DDID_CNTL_VMID_SEL', 'CP_ME_ID', 'CP_PERFMON_ENABLE_MODE', + 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 'CP_PERFMON_ENABLE_MODE_RESERVED_1', 'CP_PERFMON_STATE', + 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'CP_PERFMON_STATE_RESERVED_3', 'CP_PERFMON_STATE_START_COUNTING', + 'CP_PERFMON_STATE_STOP_COUNTING', 'CP_PIPE_ID', 'CP_RING_ID', + 'CRC_CUR_0', 'CRC_CUR_1', 'CRC_CUR_SEL', 'CRC_INTERLACE_0', + 'CRC_INTERLACE_1', 'CRC_INTERLACE_2', 'CRC_INTERLACE_3', + 'CRC_INTERLACE_SEL', 'CRC_IN_PIX_0', 'CRC_IN_PIX_1', + 'CRC_IN_PIX_2', 'CRC_IN_PIX_3', 'CRC_IN_PIX_4', 'CRC_IN_PIX_5', + 'CRC_IN_PIX_6', 'CRC_IN_PIX_7', 'CRC_IN_PIX_SEL', 'CRC_SRC_0', + 'CRC_SRC_1', 'CRC_SRC_2', 'CRC_SRC_3', 'CRC_SRC_SEL', + 'CRC_STEREO_0', 'CRC_STEREO_1', 'CRC_STEREO_2', 'CRC_STEREO_3', + 'CRC_STEREO_SEL', 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'CROB_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'CROB_MEM_PWR_LIGHT_SLEEP_MODE', 'CROSSBAR_FOR_ALPHA', + 'CROSSBAR_FOR_CB_B', 'CROSSBAR_FOR_CR_R', 'CROSSBAR_FOR_Y_G', + 'CRS', 'CR_R_DATA_ONTO_ALPHA_PORT', 'CR_R_DATA_ONTO_CB_B_PORT', + 'CR_R_DATA_ONTO_CR_R_PORT', 'CR_R_DATA_ONTO_Y_G_PORT', + 'CSCNTL_ADDR_WIDTH', 'CSCNTL_DATA_WIDTH', 'CSCNTL_TYPE', + 'CSCNTL_TYPE_EVENT', 'CSCNTL_TYPE_PRIVATE', 'CSCNTL_TYPE_STATE', + 'CSCNTL_TYPE_TG', 'CSCNTL_TYPE_WIDTH', 'CSDATA_ADDR_WIDTH', + 'CSDATA_DATA_WIDTH', 'CSDATA_TYPE', 'CSDATA_TYPE_EVENT', + 'CSDATA_TYPE_PRIVATE', 'CSDATA_TYPE_STATE', 'CSDATA_TYPE_TG', + 'CSDATA_TYPE_WIDTH', 'CS_CONTEXT_DONE', 'CS_DONE', 'CS_NA', + 'CS_PARTIAL_FLUSH', 'CURSOR_2X_MAGNIFY', + 'CURSOR_2X_MAGNIFY_IS_DISABLE', 'CURSOR_2X_MAGNIFY_IS_ENABLE', + 'CURSOR_COLOR_24BIT_1BIT_AND', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_PREMULT', + 'CURSOR_COLOR_24BIT_8BIT_ALPHA_UNPREMULT', + 'CURSOR_COLOR_64BIT_FP_PREMULT', + 'CURSOR_COLOR_64BIT_FP_UNPREMULT', 'CURSOR_ENABLE', + 'CURSOR_IN_GUEST_PHYSICAL_ADDRESS', + 'CURSOR_IN_SYSTEM_PHYSICAL_ADDRESS', 'CURSOR_IS_DISABLE', + 'CURSOR_IS_ENABLE', 'CURSOR_IS_NOT_SNOOP', 'CURSOR_IS_SNOOP', + 'CURSOR_LINES_PER_CHUNK', 'CURSOR_LINE_PER_CHUNK_1', + 'CURSOR_LINE_PER_CHUNK_16', 'CURSOR_LINE_PER_CHUNK_2', + 'CURSOR_LINE_PER_CHUNK_4', 'CURSOR_LINE_PER_CHUNK_8', + 'CURSOR_MODE', 'CURSOR_MONO_2BIT', + 'CURSOR_PERFMON_LATENCY_MEASURE_CROB_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_EN', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_DISABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_IS_ENABLED', + 'CURSOR_PERFMON_LATENCY_MEASURE_MC_LATENCY', + 'CURSOR_PERFMON_LATENCY_MEASURE_SEL', 'CURSOR_PITCH', + 'CURSOR_PITCH_128_PIXELS', 'CURSOR_PITCH_256_PIXELS', + 'CURSOR_PITCH_64_PIXELS', 'CURSOR_REQUEST_EARLY', + 'CURSOR_REQUEST_NORMALLY', 'CURSOR_REQ_MODE', 'CURSOR_SNOOP', + 'CURSOR_STEREO_EN', 'CURSOR_STEREO_IS_DISABLED', + 'CURSOR_STEREO_IS_ENABLED', 'CURSOR_SURFACE_IS_NOT_TMZ', + 'CURSOR_SURFACE_IS_TMZ', 'CURSOR_SURFACE_TMZ', 'CURSOR_SYSTEM', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_0', + 'CURSOR_XY_POSITION_ROTATION_AND_MIRRORING_BYPASS_1', + 'CUR_CLAMP_DIS', 'CUR_CLAMP_EN', 'CUR_DIS', + 'CUR_DYNAMIC_EXPANSION', 'CUR_EN', 'CUR_ENABLE', + 'CUR_EXPAND_MODE', 'CUR_FP_NO_ROM', 'CUR_FP_USE_ROM', + 'CUR_INV_CLAMP', 'CUR_MATRIX_COEF_FORMAT_ENUM', + 'CUR_MATRIX_FIX_S2_13', 'CUR_MATRIX_FIX_S3_12', 'CUR_MODE', + 'CUR_NOT_PENDING', 'CUR_PENDING', 'CUR_ROM_EN', 'CUR_YES_PENDING', + 'CUR_ZERO_EXPANSION', 'CbYCrY10101010_422_PACKED', + 'CbYCrY12121212_422_PACKED', 'CbYCrY8888_422_PACKED', 'CombFunc', + 'CompareFrag', 'ConservativeZExport', 'CovToShaderSel', + 'CrYCbA1010102', 'CrYCbA16161616_10LSB', 'CrYCbA16161616_10MSB', + 'CrYCbA16161616_12LSB', 'CrYCbA16161616_12MSB', 'CrYCbA8888', + 'CrYCbY10101010_422_PACKED', 'CrYCbY12121212_422_PACKED', + 'CrYCbY8888_422_PACKED', 'DAC_MUX_SELECT', 'DAC_MUX_SELECT_DACA', + 'DAC_MUX_SELECT_DACB', 'DB_BYPASS', 'DB_BYPASS_WR_DISABLE', + 'DB_CACHE_FLUSH_AND_INV', 'DB_COMP_WR_DISABLE', 'DB_DEFAULT', + 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 'DB_PERF_SEL_CB_DB_rdreq_sends', + 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 'DB_PERF_SEL_CB_DB_wrreq_sends', + 'DB_PERF_SEL_DB_CB_context_dones', 'DB_PERF_SEL_DB_CB_eop_dones', + 'DB_PERF_SEL_DB_CB_export_busy', + 'DB_PERF_SEL_DB_CB_export_double_format', + 'DB_PERF_SEL_DB_CB_export_events', + 'DB_PERF_SEL_DB_CB_export_export_quads', + 'DB_PERF_SEL_DB_CB_export_fast_format', + 'DB_PERF_SEL_DB_CB_export_fmt_16_16_float_8pix', + 'DB_PERF_SEL_DB_CB_export_fmt_16_16_signed_8pix', + 'DB_PERF_SEL_DB_CB_export_fmt_16_16_unsigned_8pix', + 'DB_PERF_SEL_DB_CB_export_fmt_32bpp_8pix', + 'DB_PERF_SEL_DB_CB_export_is_event_BOTTOM_OF_PIPE_TS', + 'DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_CB_PIXEL_DATA', + 'DB_PERF_SEL_DB_CB_export_is_event_FLUSH_AND_INV_DB_DATA_TS', + 'DB_PERF_SEL_DB_CB_export_num_pixels_need_blending', + 'DB_PERF_SEL_DB_CB_export_quads', + 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x1', + 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_1x2', + 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x1', + 'DB_PERF_SEL_DB_CB_export_quads_vrs_rate_2x2', + 'DB_PERF_SEL_DB_CB_export_sends', + 'DB_PERF_SEL_DB_CB_export_slow_format', + 'DB_PERF_SEL_DB_CB_export_stalls', + 'DB_PERF_SEL_DB_CB_export_waiting_for_perfcounter_stop_event', + 'DB_PERF_SEL_DB_CB_rdret_ack', 'DB_PERF_SEL_DB_CB_rdret_nack', + 'DB_PERF_SEL_DB_CB_wrret_ack', 'DB_PERF_SEL_DB_CB_wrret_nack', + 'DB_PERF_SEL_DB_SC_c_tile_rate', 'DB_PERF_SEL_DB_SC_quad_busy', + 'DB_PERF_SEL_DB_SC_quad_conflicts', + 'DB_PERF_SEL_DB_SC_quad_double_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_noz_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 'DB_PERF_SEL_DB_SC_quad_noz_tiles', + 'DB_PERF_SEL_DB_SC_quad_num_null_1x2_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_num_null_2x1_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_num_null_2x2_coarse_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_1_pixel', + 'DB_PERF_SEL_DB_SC_quad_quads_with_2_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_3_pixels', + 'DB_PERF_SEL_DB_SC_quad_quads_with_4_pixels', + 'DB_PERF_SEL_DB_SC_quad_sends', 'DB_PERF_SEL_DB_SC_quad_stalls', + 'DB_PERF_SEL_DB_SC_quad_tiles', 'DB_PERF_SEL_DB_SC_s_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_busy', 'DB_PERF_SEL_DB_SC_tile_culled', + 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 'DB_PERF_SEL_DB_SC_tile_no_ops', 'DB_PERF_SEL_DB_SC_tile_sends', + 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 'DB_PERF_SEL_DB_SC_tile_stalls', + 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_tiles', 'DB_PERF_SEL_DB_SC_wave_busy', + 'DB_PERF_SEL_DB_SC_wave_conflict', + 'DB_PERF_SEL_DB_SC_wave_hard_conflict', + 'DB_PERF_SEL_DB_SC_wave_id_wrapped', + 'DB_PERF_SEL_DB_SC_wave_sends', 'DB_PERF_SEL_DB_SC_wave_stalls', + 'DB_PERF_SEL_DB_SC_z_tile_rate', + 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 'DB_PERF_SEL_Depth_Tile_Cache_event', + 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 'DB_PERF_SEL_MI_psd_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_quad_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_tile_req_wrack_counter_stall', + 'DB_PERF_SEL_MI_zpc_req_wrack_counter_stall', + 'DB_PERF_SEL_OREO_Events_delayed', 'DB_PERF_SEL_OREO_Events_load', + 'DB_PERF_SEL_OREO_Events_non_transition', + 'DB_PERF_SEL_OREO_Events_stalls', + 'DB_PERF_SEL_OREO_Events_transition', + 'DB_PERF_SEL_OREO_SB_evicts', 'DB_PERF_SEL_OREO_SB_hits', + 'DB_PERF_SEL_OREO_SB_misses', 'DB_PERF_SEL_OREO_SB_stalls', + 'DB_PERF_SEL_OREO_ST_load', 'DB_PERF_SEL_OREO_ST_read', + 'DB_PERF_SEL_OREO_ST_stalls', 'DB_PERF_SEL_OREO_TT_load', + 'DB_PERF_SEL_OREO_TT_read', 'DB_PERF_SEL_OREO_TT_stalls', + 'DB_PERF_SEL_OREO_WT_load', 'DB_PERF_SEL_OREO_WT_read', + 'DB_PERF_SEL_Op_Pipe_Busy', 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 'DB_PERF_SEL_Op_Pipe_Postz_Busy', 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 'DB_PERF_SEL_PERF_fg_lob_fwdr_timeout_hits', + 'DB_PERF_SEL_Plane_Cache_flushes', + 'DB_PERF_SEL_Plane_Cache_frees', 'DB_PERF_SEL_Plane_Cache_hits', + 'DB_PERF_SEL_Plane_Cache_misses', + 'DB_PERF_SEL_Plane_Cache_starves', + 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 'DB_PERF_SEL_PostZ_Samples_failing_S', + 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 'DB_PERF_SEL_PreZ_Samples_failing_S', + 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 'DB_PERF_SEL_RMI_rd_s_32byte_req', + 'DB_PERF_SEL_RMI_rd_s_32byte_ret', + 'DB_PERF_SEL_RMI_rd_tile_32byte_req', + 'DB_PERF_SEL_RMI_rd_tile_32byte_ret', + 'DB_PERF_SEL_RMI_rd_z_32byte_req', + 'DB_PERF_SEL_RMI_rd_z_32byte_ret', + 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_ack', + 'DB_PERF_SEL_RMI_wr_psdzpc_32byte_req', + 'DB_PERF_SEL_RMI_wr_s_32byte_ack', + 'DB_PERF_SEL_RMI_wr_s_32byte_req', + 'DB_PERF_SEL_RMI_wr_tile_32byte_ack', + 'DB_PERF_SEL_RMI_wr_tile_32byte_req', + 'DB_PERF_SEL_RMI_wr_z_32byte_ack', + 'DB_PERF_SEL_RMI_wr_z_32byte_req', 'DB_PERF_SEL_SC_DB_quad_busy', + 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 'DB_PERF_SEL_SC_DB_quad_pixels', 'DB_PERF_SEL_SC_DB_quad_quads', + 'DB_PERF_SEL_SC_DB_quad_quads_pipe0', + 'DB_PERF_SEL_SC_DB_quad_quads_pipe1', + 'DB_PERF_SEL_SC_DB_quad_sends', 'DB_PERF_SEL_SC_DB_quad_squads', + 'DB_PERF_SEL_SC_DB_quad_tiles', 'DB_PERF_SEL_SC_DB_quad_vrs_1x1', + 'DB_PERF_SEL_SC_DB_quad_vrs_1x2', + 'DB_PERF_SEL_SC_DB_quad_vrs_2x1', + 'DB_PERF_SEL_SC_DB_quad_vrs_2x2', + 'DB_PERF_SEL_SC_DB_quad_vrs_2x_ssaa', + 'DB_PERF_SEL_SC_DB_quad_vrs_4x_ssaa', + 'DB_PERF_SEL_SC_DB_quad_vrs_8x_ssaa', + 'DB_PERF_SEL_SC_DB_tile_backface', 'DB_PERF_SEL_SC_DB_tile_busy', + 'DB_PERF_SEL_SC_DB_tile_covered', 'DB_PERF_SEL_SC_DB_tile_events', + 'DB_PERF_SEL_SC_DB_tile_sends', 'DB_PERF_SEL_SC_DB_tile_stalls', + 'DB_PERF_SEL_SC_DB_tile_tiles', + 'DB_PERF_SEL_SC_DB_tile_tiles_pipe0', + 'DB_PERF_SEL_SC_DB_tile_tiles_pipe1', + 'DB_PERF_SEL_SC_DB_wave_busy', + 'DB_PERF_SEL_SC_DB_wave_id_wrapped', + 'DB_PERF_SEL_SC_DB_wave_quads', 'DB_PERF_SEL_SC_DB_wave_sends', + 'DB_PERF_SEL_SH_quads_outstanding_sum', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_enabled', + 'DB_PERF_SEL_SX_DB_quad_all_pixels_killed', + 'DB_PERF_SEL_SX_DB_quad_busy', + 'DB_PERF_SEL_SX_DB_quad_double_format', + 'DB_PERF_SEL_SX_DB_quad_export_quads', + 'DB_PERF_SEL_SX_DB_quad_exports', + 'DB_PERF_SEL_SX_DB_quad_fast_format', + 'DB_PERF_SEL_SX_DB_quad_need_blending_and_dst_read', + 'DB_PERF_SEL_SX_DB_quad_pixels', 'DB_PERF_SEL_SX_DB_quad_quads', + 'DB_PERF_SEL_SX_DB_quad_sends', + 'DB_PERF_SEL_SX_DB_quad_slow_format', + 'DB_PERF_SEL_SX_DB_quad_stalls', 'DB_PERF_SEL_SX_DB_quad_waves', + 'DB_PERF_SEL_Stencil_Cache_flushes', + 'DB_PERF_SEL_Stencil_Cache_frees', + 'DB_PERF_SEL_Stencil_Cache_hits', + 'DB_PERF_SEL_Stencil_Cache_misses', + 'DB_PERF_SEL_Stencil_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_flushes', 'DB_PERF_SEL_Tile_Cache_hits', + 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Tile_Cache_misses', 'DB_PERF_SEL_Tile_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_surface_stall', + 'DB_PERF_SEL_Z_Cache_frees', 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 'DB_PERF_SEL_Z_Cache_pmask_hits', + 'DB_PERF_SEL_Z_Cache_pmask_misses', + 'DB_PERF_SEL_Z_Cache_pmask_starves', + 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 'DB_PERF_SEL_clock_main_active', + 'DB_PERF_SEL_clock_mem_export_active', + 'DB_PERF_SEL_clock_reg_active', + 'DB_PERF_SEL_cs_events_pws_enable', + 'DB_PERF_SEL_depth_bounds_tile_culled', 'DB_PERF_SEL_di_dt_stall', + 'DB_PERF_SEL_dk_squad_busy', 'DB_PERF_SEL_dk_squad_sends', + 'DB_PERF_SEL_dk_squad_stalls', 'DB_PERF_SEL_dk_tile_busy', + 'DB_PERF_SEL_dk_tile_quad_starves', 'DB_PERF_SEL_dk_tile_sends', + 'DB_PERF_SEL_dk_tile_stalls', 'DB_PERF_SEL_dkg_tile_rate_tile', + 'DB_PERF_SEL_dtt_sm_clash_stall', 'DB_PERF_SEL_dtt_sm_miss_stall', + 'DB_PERF_SEL_dtt_sm_slot_stall', + 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 'DB_PERF_SEL_esr_eot_fwd_busy', 'DB_PERF_SEL_esr_eot_fwd_forward', + 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 'DB_PERF_SEL_esr_ps_lqf_busy', 'DB_PERF_SEL_esr_ps_lqf_stall', + 'DB_PERF_SEL_esr_ps_out_busy', 'DB_PERF_SEL_esr_ps_src_in_sends', + 'DB_PERF_SEL_esr_ps_src_in_squads', + 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_stall', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 'DB_PERF_SEL_esr_ps_src_out_stall', 'DB_PERF_SEL_esr_ps_vic_busy', + 'DB_PERF_SEL_esr_ps_vic_stall', + 'DB_PERF_SEL_esr_ps_woc_1squadIn_2squadOut', + 'DB_PERF_SEL_esr_ps_woc_2squadIn_1squadOut', + 'DB_PERF_SEL_esr_psi_vic_tile_rate', + 'DB_PERF_SEL_esr_sqq_zi_busy', 'DB_PERF_SEL_esr_sqq_zi_stall', + 'DB_PERF_SEL_esr_vic_footprint_match_1x2', + 'DB_PERF_SEL_esr_vic_footprint_match_2x1', + 'DB_PERF_SEL_esr_vic_footprint_match_2x2', + 'DB_PERF_SEL_esr_vic_sqq_busy', 'DB_PERF_SEL_esr_vic_sqq_stall', + 'DB_PERF_SEL_etr_out_busy', 'DB_PERF_SEL_etr_out_esr_stall', + 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 'DB_PERF_SEL_etr_out_send', 'DB_PERF_SEL_flush_10plane', + 'DB_PERF_SEL_flush_11plane', 'DB_PERF_SEL_flush_12plane', + 'DB_PERF_SEL_flush_13plane', 'DB_PERF_SEL_flush_14plane', + 'DB_PERF_SEL_flush_15plane', 'DB_PERF_SEL_flush_16plane', + 'DB_PERF_SEL_flush_1plane', 'DB_PERF_SEL_flush_2plane', + 'DB_PERF_SEL_flush_3plane', 'DB_PERF_SEL_flush_4plane', + 'DB_PERF_SEL_flush_5plane', 'DB_PERF_SEL_flush_6plane', + 'DB_PERF_SEL_flush_7plane', 'DB_PERF_SEL_flush_8plane', + 'DB_PERF_SEL_flush_9plane', 'DB_PERF_SEL_flush_compressed', + 'DB_PERF_SEL_flush_compressed_stencil', + 'DB_PERF_SEL_flush_expanded_stencil', + 'DB_PERF_SEL_flush_expanded_z', 'DB_PERF_SEL_flush_plane_le4', + 'DB_PERF_SEL_flush_single_stencil', + 'DB_PERF_SEL_hi_z_s_checker_force_coarse_vrs_1x1', + 'DB_PERF_SEL_hi_z_s_checker_force_ssaa_vrs_1x1', + 'DB_PERF_SEL_his_tile_culled', 'DB_PERF_SEL_hiz_tc_read_starved', + 'DB_PERF_SEL_hiz_tc_write_stall', 'DB_PERF_SEL_hiz_tile_culled', + 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 'DB_PERF_SEL_mi_rdreq_busy', 'DB_PERF_SEL_mi_rdreq_stall', + 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 'DB_PERF_SEL_mi_wrreq_busy', 'DB_PERF_SEL_mi_wrreq_stall', + 'DB_PERF_SEL_noz_waiting_for_postz_done', + 'DB_PERF_SEL_planes_flushed', + 'DB_PERF_SEL_postz_ps_invoked_pixel_cnt', + 'DB_PERF_SEL_postzl_full_launch', + 'DB_PERF_SEL_postzl_partial_launch', + 'DB_PERF_SEL_postzl_partial_waiting', + 'DB_PERF_SEL_postzl_se_busy', 'DB_PERF_SEL_postzl_se_stall', + 'DB_PERF_SEL_postzl_sq_pt_busy', 'DB_PERF_SEL_postzl_sq_pt_stall', + 'DB_PERF_SEL_postzl_src_in_sends', + 'DB_PERF_SEL_postzl_src_in_squads', + 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 'DB_PERF_SEL_postzl_src_in_stall', + 'DB_PERF_SEL_postzl_src_in_tile_rate', + 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_postzl_src_out_stall', + 'DB_PERF_SEL_postzl_tile_init_stall', + 'DB_PERF_SEL_postzl_tile_mem_stall', + 'DB_PERF_SEL_prez_ps_invoked_pixel_cnt', + 'DB_PERF_SEL_prezl_src_in_sends', + 'DB_PERF_SEL_prezl_src_in_squads', + 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 'DB_PERF_SEL_prezl_src_in_stall', + 'DB_PERF_SEL_prezl_src_in_tile_rate', + 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_prezl_src_out_stall', + 'DB_PERF_SEL_prezl_tile_init_stall', + 'DB_PERF_SEL_prezl_tile_mem_stall', + 'DB_PERF_SEL_ps_events_pws_enable', + 'DB_PERF_SEL_pws_liveness_stall_dtt_tag', + 'DB_PERF_SEL_pws_liveness_stall_tcp_cache_mgr', + 'DB_PERF_SEL_pws_stall', 'DB_PERF_SEL_qc_busy', + 'DB_PERF_SEL_qc_conflicts', 'DB_PERF_SEL_qc_full_stall', + 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', 'DB_PERF_SEL_qc_xfc', + 'DB_PERF_SEL_quad_rd_32byte_reqs', 'DB_PERF_SEL_quad_rd_busy', + 'DB_PERF_SEL_quad_rd_mi_stall', + 'DB_PERF_SEL_quad_rd_mi_stall_unc', 'DB_PERF_SEL_quad_rd_panic', + 'DB_PERF_SEL_quad_rd_rw_collision', 'DB_PERF_SEL_quad_rd_sends', + 'DB_PERF_SEL_quad_rd_sends_unc', 'DB_PERF_SEL_quad_rd_tag_stall', + 'DB_PERF_SEL_quad_rdret_busy', 'DB_PERF_SEL_quad_rdret_sends', + 'DB_PERF_SEL_quad_wr_acks', 'DB_PERF_SEL_quad_wr_busy', + 'DB_PERF_SEL_quad_wr_coherency_stall', + 'DB_PERF_SEL_quad_wr_mi_stall', 'DB_PERF_SEL_quad_wr_sends', + 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 'DB_PERF_SEL_sc_kick_end', 'DB_PERF_SEL_sc_kick_start', + 'DB_PERF_SEL_tcp_dispatcher_flushes', + 'DB_PERF_SEL_tcp_dispatcher_reads', + 'DB_PERF_SEL_tcp_prefetcher_flushes', + 'DB_PERF_SEL_tcp_prefetcher_reads', + 'DB_PERF_SEL_tcp_preloader_flushes', + 'DB_PERF_SEL_tcp_preloader_reads', 'DB_PERF_SEL_tile_rd_sends', + 'DB_PERF_SEL_tile_wr_acks', 'DB_PERF_SEL_tile_wr_sends', + 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 'DB_PERF_SEL_tiles_decomp_on_expclear', + 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 'DB_PERF_SEL_tiles_z_fully_summarized', 'DB_PERF_SEL_tl_busy', + 'DB_PERF_SEL_tl_dtc_read_starved', 'DB_PERF_SEL_tl_events', + 'DB_PERF_SEL_tl_expand_squads', + 'DB_PERF_SEL_tl_flush_expand_squads', + 'DB_PERF_SEL_tl_in_fast_z_stall', + 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 'DB_PERF_SEL_tl_in_xfc', 'DB_PERF_SEL_tl_out_squads', + 'DB_PERF_SEL_tl_out_xfc', 'DB_PERF_SEL_tl_postZ_noop_squads', + 'DB_PERF_SEL_tl_postZ_squads', 'DB_PERF_SEL_tl_preZ_noop_squads', + 'DB_PERF_SEL_tl_preZ_squads', + 'DB_PERF_SEL_tl_stencil_locked_stall', + 'DB_PERF_SEL_tl_stencil_stall', 'DB_PERF_SEL_tl_summarize_squads', + 'DB_PERF_SEL_tl_tile_ops', 'DB_PERF_SEL_tl_z_decompress_stall', + 'DB_PERF_SEL_tl_z_fetch_stall', + 'DB_PERF_SEL_ts_events_pws_enable', + 'DB_PERF_SEL_ts_tc_update_stall', + 'DB_PERF_SEL_tsc_insert_summarize_stall', + 'DB_PERF_SEL_unmapped_z_tile_culled', + 'DB_PERF_SEL_zf_plane_multicycle', 'DCCG_AUDIO_DTO0_SOURCE_SEL', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG0', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG1', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG2', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_OTG3', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', + 'DCCG_AUDIO_DTO2_SOURCE_SEL', 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0_DIV2', 'DCCG_AUDIO_DTO_SEL', + 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', + 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 'DCCG_AUDIO_DTO_USE_512FBR_DTO', + 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', 'DCCG_DBG_BLOCK_SEL', + 'DCCG_DBG_BLOCK_SEL_DCCG', 'DCCG_DBG_BLOCK_SEL_PMON', + 'DCCG_DBG_BLOCK_SEL_PMON2', 'DCCG_DBG_EN', 'DCCG_DBG_EN_DISABLE', + 'DCCG_DBG_EN_ENABLE', 'DCCG_DEEP_COLOR_CNTL', + 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', 'DCCG_DEEP_COLOR_DTO_DISABLE', + 'DCCG_FIFO_ERRDET_OVR_DISABLE', 'DCCG_FIFO_ERRDET_OVR_EN', + 'DCCG_FIFO_ERRDET_OVR_ENABLE', 'DCCG_FIFO_ERRDET_RESET', + 'DCCG_FIFO_ERRDET_RESET_FORCE', 'DCCG_FIFO_ERRDET_RESET_NOOP', + 'DCCG_FIFO_ERRDET_STATE', 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 'DCCG_FIFO_ERRDET_STATE_DETECTION', 'DCCG_PERF_MODE_HSYNC', + 'DCCG_PERF_MODE_HSYNC_NOOP', 'DCCG_PERF_MODE_HSYNC_START', + 'DCCG_PERF_MODE_VSYNC', 'DCCG_PERF_MODE_VSYNC_NOOP', + 'DCCG_PERF_MODE_VSYNC_START', 'DCCG_PERF_OTG_SELECT', + 'DCCG_PERF_RUN', 'DCCG_PERF_RUN_NOOP', 'DCCG_PERF_RUN_START', + 'DCCG_PERF_SEL_OTG0', 'DCCG_PERF_SEL_OTG1', 'DCCG_PERF_SEL_OTG2', + 'DCCG_PERF_SEL_OTG3', 'DCCG_PERF_SEL_RESERVED', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_2', + 'DCHUBBUB_DET_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'DCHUBBUB_DET_MEM_PWR_LIGHT_SLEEP_MODE', + 'DCHUBBUB_MEM_POWER_DIS_MODE_DISABLE', + 'DCHUBBUB_MEM_POWER_DIS_MODE_ENABLE', + 'DCHUBBUB_MEM_POWER_MODE_DEEP_SLEEP', + 'DCHUBBUB_MEM_POWER_MODE_LIGHT_SLEEP', + 'DCHUBBUB_MEM_POWER_MODE_OFF', + 'DCHUBBUB_MEM_POWER_MODE_SHUT_DOWN', 'DCHUBBUB_MEM_PWR_DIS_MODE', + 'DCHUBBUB_MEM_PWR_MODE', 'DCIOCHIP_AUX_ALL_PWR_OK', + 'DCIOCHIP_AUX_ALL_PWR_OK_0', 'DCIOCHIP_AUX_ALL_PWR_OK_1', + 'DCIOCHIP_AUX_CSEL0P9', 'DCIOCHIP_AUX_CSEL1P1', + 'DCIOCHIP_AUX_CSEL_DEC0P9', 'DCIOCHIP_AUX_CSEL_DEC1P0', + 'DCIOCHIP_AUX_CSEL_INC1P0', 'DCIOCHIP_AUX_CSEL_INC1P1', + 'DCIOCHIP_AUX_FALLSLEWSEL', 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', 'DCIOCHIP_AUX_HYS_TUNE', + 'DCIOCHIP_AUX_HYS_TUNE_0', 'DCIOCHIP_AUX_HYS_TUNE_1', + 'DCIOCHIP_AUX_HYS_TUNE_2', 'DCIOCHIP_AUX_HYS_TUNE_3', + 'DCIOCHIP_AUX_RECEIVER_SEL', 'DCIOCHIP_AUX_RECEIVER_SEL_0', + 'DCIOCHIP_AUX_RECEIVER_SEL_1', 'DCIOCHIP_AUX_RECEIVER_SEL_2', + 'DCIOCHIP_AUX_RECEIVER_SEL_3', 'DCIOCHIP_AUX_RSEL0P9', + 'DCIOCHIP_AUX_RSEL1P1', 'DCIOCHIP_AUX_RSEL_DEC0P9', + 'DCIOCHIP_AUX_RSEL_DEC1P0', 'DCIOCHIP_AUX_RSEL_INC1P0', + 'DCIOCHIP_AUX_RSEL_INC1P1', 'DCIOCHIP_AUX_SPIKESEL', + 'DCIOCHIP_AUX_SPIKESEL_10NS', 'DCIOCHIP_AUX_SPIKESEL_50NS', + 'DCIOCHIP_AUX_VOD_TUNE', 'DCIOCHIP_AUX_VOD_TUNE_0', + 'DCIOCHIP_AUX_VOD_TUNE_1', 'DCIOCHIP_AUX_VOD_TUNE_2', + 'DCIOCHIP_AUX_VOD_TUNE_3', 'DCIOCHIP_GPIO_MASK_EN', + 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', 'DCIOCHIP_HPD_SEL', + 'DCIOCHIP_HPD_SEL_ASYNC', 'DCIOCHIP_HPD_SEL_CLOCKED', + 'DCIOCHIP_I2C_COMPSEL', 'DCIOCHIP_I2C_FALLSLEWSEL', + 'DCIOCHIP_I2C_FALLSLEWSEL_00', 'DCIOCHIP_I2C_FALLSLEWSEL_01', + 'DCIOCHIP_I2C_FALLSLEWSEL_10', 'DCIOCHIP_I2C_FALLSLEWSEL_11', + 'DCIOCHIP_I2C_RECEIVER_SEL', 'DCIOCHIP_I2C_RECEIVER_SEL_0', + 'DCIOCHIP_I2C_RECEIVER_SEL_1', 'DCIOCHIP_I2C_RECEIVER_SEL_2', + 'DCIOCHIP_I2C_RECEIVER_SEL_3', 'DCIOCHIP_I2C_REC_COMPARATOR', + 'DCIOCHIP_I2C_REC_SCHMIT', 'DCIOCHIP_I2C_VPH_1V2_EN', + 'DCIOCHIP_I2C_VPH_1V2_EN_0', 'DCIOCHIP_I2C_VPH_1V2_EN_1', + 'DCIOCHIP_INVERT', 'DCIOCHIP_MASK', 'DCIOCHIP_MASK_DISABLE', + 'DCIOCHIP_MASK_ENABLE', 'DCIOCHIP_PAD_MODE', + 'DCIOCHIP_PAD_MODE_DDC', 'DCIOCHIP_PAD_MODE_DP', 'DCIOCHIP_PD_EN', + 'DCIOCHIP_PD_EN_ALLOW', 'DCIOCHIP_PD_EN_NOTALLOW', + 'DCIOCHIP_POL_INVERT', 'DCIOCHIP_POL_NON_INVERT', + 'DCIOCHIP_REF_27_SRC_SEL', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', + 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL', + 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS', + 'DCIO_DBG_ASYNC_4BIT_SEL', 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', 'DCIO_DBG_ASYNC_BLOCK_SEL', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DIO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', 'DCIO_DCRXPHY_SOFT_RESET', + 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', + 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', 'DCIO_DC_GENERICA_SEL', + 'DCIO_DC_GENERICB_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL', + 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE', + 'DCIO_DC_GPU_TIMER_READ_SELECT', + 'DCIO_DC_GPU_TIMER_START_POSITION', + 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL', + 'DCIO_DIO_EXT_VSYNC_MASK', 'DCIO_DIO_OTG_EXT_VSYNC_MUX', + 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', 'DCIO_DPCS_INTERRUPT_DISABLE', + 'DCIO_DPCS_INTERRUPT_ENABLE', 'DCIO_DPCS_INTERRUPT_MASK', + 'DCIO_DPCS_INTERRUPT_TYPE', + 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', + 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', + 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', 'DCIO_EXT_VSYNC_MASK_NONE', + 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', 'DCIO_EXT_VSYNC_MASK_PIPE0', + 'DCIO_EXT_VSYNC_MASK_PIPE1', 'DCIO_EXT_VSYNC_MASK_PIPE2', + 'DCIO_EXT_VSYNC_MASK_PIPE3', 'DCIO_EXT_VSYNC_MASK_PIPE4', + 'DCIO_EXT_VSYNC_MASK_PIPE5', 'DCIO_EXT_VSYNC_MUX_GENERICB', + 'DCIO_EXT_VSYNC_MUX_OTG0', 'DCIO_EXT_VSYNC_MUX_OTG1', + 'DCIO_EXT_VSYNC_MUX_OTG2', 'DCIO_EXT_VSYNC_MUX_OTG3', + 'DCIO_EXT_VSYNC_MUX_OTG4', 'DCIO_EXT_VSYNC_MUX_OTG5', + 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 'DCIO_GENERICA_SEL_STEREOSYNC', 'DCIO_GENERICA_SEL_SYNCEN', + 'DCIO_GENERICB_SEL_GENERICB_DCCG', 'DCIO_GENERICB_SEL_STEREOSYNC', + 'DCIO_GENERICB_SEL_SYNCEN', 'DCIO_GENLK_CLK_GSL_MASK', + 'DCIO_GENLK_CLK_GSL_MASK_NO', 'DCIO_GENLK_CLK_GSL_MASK_STEREO', + 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', + 'DCIO_GENLK_VSYNC_GSL_MASK', 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', + 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_START_0_END_27', 'DCIO_GPU_TIMER_START_10_END_37', + 'DCIO_GPU_TIMER_START_1_END_28', 'DCIO_GPU_TIMER_START_2_END_29', + 'DCIO_GPU_TIMER_START_3_END_30', 'DCIO_GPU_TIMER_START_4_END_31', + 'DCIO_GPU_TIMER_START_6_END_33', 'DCIO_GPU_TIMER_START_8_END_35', + 'DCIO_GSL_SEL', 'DCIO_GSL_SEL_GROUP_0', 'DCIO_GSL_SEL_GROUP_1', + 'DCIO_GSL_SEL_GROUP_2', 'DCIO_PHY_HPO_ENC_SRC_SEL', + 'DCIO_SWAPLOCK_A_GSL_MASK', 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', 'DCIO_SWAPLOCK_B_GSL_MASK', + 'DCIO_SWAPLOCK_B_GSL_MASK_NO', 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', 'DCIO_TEST_CLK_SEL_DISPCLK', + 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', 'DCIO_TEST_CLK_SEL_SOCCLK', + 'DCIO_UNIPHYA_FBDIV_CLK', 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYA_TEST_REFDIV_CLK', 'DCIO_UNIPHYB_FBDIV_CLK', + 'DCIO_UNIPHYB_FBDIV_SSC_CLK', 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYB_TEST_REFDIV_CLK', 'DCIO_UNIPHYC_FBDIV_CLK', + 'DCIO_UNIPHYC_FBDIV_SSC_CLK', 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYC_TEST_REFDIV_CLK', 'DCIO_UNIPHYD_FBDIV_CLK', + 'DCIO_UNIPHYD_FBDIV_SSC_CLK', 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYD_TEST_REFDIV_CLK', 'DCIO_UNIPHYE_FBDIV_CLK', + 'DCIO_UNIPHYE_FBDIV_SSC_CLK', 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYE_TEST_REFDIV_CLK', 'DCIO_UNIPHYF_FBDIV_CLK', + 'DCIO_UNIPHYF_FBDIV_SSC_CLK', 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYF_TEST_REFDIV_CLK', 'DCIO_UNIPHYG_FBDIV_CLK', + 'DCIO_UNIPHYG_FBDIV_SSC_CLK', 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYG_TEST_REFDIV_CLK', 'DCIO_UNIPHY_CHANNEL_INVERTED', + 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', 'DCIO_UNIPHY_IMPCAL_SEL', + 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', + 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT', + 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX1', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX2', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX3', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX4', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX5', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_G_AUX6', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 'DCOH_TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK0', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK1', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK2', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK3', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK4', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK5', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK6', + 'DCOH_TEST_CLOCK_MUX_SELECT_DPIASYMCLK7', + 'DCOH_TEST_CLOCK_MUX_SELECT_ENUM', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYASYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYBSYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYCSYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYDSYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYESYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYFSYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_PHYGSYMCLK', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX1', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX2', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX3', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX4', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX5', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_G_AUX6', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_P', + 'DCOH_TEST_CLOCK_MUX_SELECT_REFCLK_R', + 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM', + 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_DISABLED', + 'DCOH_TOP_CLOCK_GATING_DISABLE_ENUM_ENABLED', + 'DCOH_TOP_ENABLE_ENUM', 'DCOH_TOP_ENABLE_ENUM_DISABLED', + 'DCOH_TOP_ENABLE_ENUM_ENABLED', 'DC_DMCUB_INT_TYPE', + 'DC_DMCUB_TIMER_WINDOW', 'DC_MEM_GLOBAL_PWR_REQ_DIS', + 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 'DC_SMU_INTERRUPT_ENABLE', 'DDID_VMID_CNTL', 'DDID_VMID_PIPE', + 'DECERR', 'DENORM_TRUNCATE', 'DETILE_BUFFER_PACKER_ENABLE', + 'DETILE_BUFFER_PACKER_IS_DISABLE', + 'DETILE_BUFFER_PACKER_IS_ENABLE', 'DFQ_MIN_FREE_ENTRIES', + 'DFQ_MIN_FREE_ENTRIES_0', 'DFQ_MIN_FREE_ENTRIES_1', + 'DFQ_MIN_FREE_ENTRIES_2', 'DFQ_MIN_FREE_ENTRIES_3', + 'DFQ_MIN_FREE_ENTRIES_4', 'DFQ_MIN_FREE_ENTRIES_5', + 'DFQ_MIN_FREE_ENTRIES_6', 'DFQ_MIN_FREE_ENTRIES_7', + 'DFQ_NUM_ENTRIES', 'DFQ_NUM_ENTRIES_0', 'DFQ_NUM_ENTRIES_1', + 'DFQ_NUM_ENTRIES_2', 'DFQ_NUM_ENTRIES_3', 'DFQ_NUM_ENTRIES_4', + 'DFQ_NUM_ENTRIES_5', 'DFQ_NUM_ENTRIES_6', 'DFQ_NUM_ENTRIES_7', + 'DFQ_NUM_ENTRIES_8', 'DFQ_SIZE', 'DFQ_SIZE_0', 'DFQ_SIZE_1', + 'DFQ_SIZE_2', 'DFQ_SIZE_3', 'DFQ_SIZE_4', 'DFQ_SIZE_5', + 'DFQ_SIZE_6', 'DFQ_SIZE_7', 'DIFFERENT_RGB', + 'DIG_10BIT_TEST_PATTERN', 'DIG_ALTERNATING_TEST_PATTERN', + 'DIG_BE_CNTL_HPD1', 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', + 'DIG_BE_CNTL_HPD4', 'DIG_BE_CNTL_HPD_SELECT', 'DIG_BE_CNTL_MODE', + 'DIG_BE_CNTL_NO_HPD', 'DIG_BE_DP_MST_MODE', 'DIG_BE_DP_SST_MODE', + 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', 'DIG_BE_RESERVED3', + 'DIG_BE_RESERVED4', 'DIG_BE_TMDS_DVI_MODE', + 'DIG_BE_TMDS_HDMI_MODE', 'DIG_DIGITAL_BYPASS_ENABLE', + 'DIG_DIGITAL_BYPASS_OFF', 'DIG_DIGITAL_BYPASS_ON', + 'DIG_DIGITAL_BYPASS_SEL', 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_12BPC_LSB', + 'DIG_DIGITAL_BYPASS_SEL_36BPP', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_LSB', + 'DIG_DIGITAL_BYPASS_SEL_48BPP_MSB', + 'DIG_DIGITAL_BYPASS_SEL_ALPHA', 'DIG_DIGITAL_BYPASS_SEL_BYPASS', + 'DIG_FE_CNTL_SOURCE_SELECT', 'DIG_FE_CNTL_STEREOSYNC_SELECT', + 'DIG_FE_SOURCE_FROM_OTG0', 'DIG_FE_SOURCE_FROM_OTG1', + 'DIG_FE_SOURCE_FROM_OTG2', 'DIG_FE_SOURCE_FROM_OTG3', + 'DIG_FE_SOURCE_RESERVED', 'DIG_FE_STEREOSYNC_FROM_OTG0', + 'DIG_FE_STEREOSYNC_FROM_OTG1', 'DIG_FE_STEREOSYNC_FROM_OTG2', + 'DIG_FE_STEREOSYNC_FROM_OTG3', 'DIG_FE_STEREOSYNC_RESERVED', + 'DIG_FIFO_1_PIX_PER_CYCLE', 'DIG_FIFO_2_PIX_PER_CYCLE', + 'DIG_FIFO_4_PIX_PER_CYCLE', 'DIG_FIFO_8_PIX_PER_CYCLE', + 'DIG_FIFO_CTRL_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_CTRL_USE_OVERWRITE_LEVEL', + 'DIG_FIFO_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', + 'DIG_FIFO_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', 'DIG_FIFO_NO_ERROR_OCCURRED', + 'DIG_FIFO_OUTPUT_PIXEL_PER_CYCLE', 'DIG_FIFO_OVERFLOW_OCCURRED', + 'DIG_FIFO_OVERFLOW_UNDERFLOW_ERROR', 'DIG_FIFO_READ_CLOCK_SRC', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', + 'DIG_FIFO_UNDERFLOW_OCCURRED', 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', + 'DIG_FIFO_USE_OVERWRITE_LEVEL', 'DIG_IN_DEBUG_MODE', + 'DIG_IN_NORMAL_OPERATION', 'DIG_MODE', + 'DIG_OUTPUT_CRC_CNTL_LINK_SEL', 'DIG_OUTPUT_CRC_DATA_SEL', + 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', 'DIG_OUTPUT_CRC_FOR_AUDIO', + 'DIG_OUTPUT_CRC_FOR_FULLFRAME', 'DIG_OUTPUT_CRC_FOR_VBI', + 'DIG_OUTPUT_CRC_ON_LINK0', 'DIG_OUTPUT_CRC_ON_LINK1', + 'DIG_RANDOM_PATTERN_ENABLED', 'DIG_RANDOM_PATTERN_RESETED', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', + 'DIG_STREAM_MAPPER_DIG_STREAM_LINK_TARGET', + 'DIG_STREAM_MAPPER_LINK0', 'DIG_STREAM_MAPPER_LINK1', + 'DIG_STREAM_MAPPER_LINK2', 'DIG_STREAM_MAPPER_LINK3', + 'DIG_STREAM_MAPPER_LINK6', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL', + 'DIG_TEST_PATTERN_NORMAL', 'DIG_TEST_PATTERN_RANDOM', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET', + 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN', 'DIG_UPDATE_EYE_SEL_BOTH', + 'DIG_UPDATE_EYE_SEL_LEFT', 'DIG_UPDATE_EYE_SEL_RIGHT', + 'DIG_UPDATE_FIELD_SEL_BOTH', 'DIG_UPDATE_FIELD_SEL_BOTTOM', + 'DIG_UPDATE_FIELD_SEL_RESERVED', 'DIG_UPDATE_FIELD_SEL_TOP', + 'DIOMEM_DISABLE_MEM_PWR_CTRL', 'DIOMEM_DYNAMIC_DEEP_SLEEP_EN', + 'DIOMEM_DYNAMIC_DEEP_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_EN', + 'DIOMEM_DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DIOMEM_DYNAMIC_SHUT_DOWN_ENABLE', 'DIOMEM_ENABLE_MEM_PWR_CTRL', + 'DIOMEM_FORCE_DEEP_SLEEP_REQUEST', 'DIOMEM_FORCE_LIGHT_SLEEP_REQ', + 'DIOMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', 'DIOMEM_NO_FORCE_REQ', + 'DIOMEM_NO_FORCE_REQUEST', 'DIOMEM_PWR_DIS_CTRL', + 'DIOMEM_PWR_FORCE_CTRL', 'DIOMEM_PWR_FORCE_CTRL2', + 'DIOMEM_PWR_SEL_CTRL', 'DIOMEM_PWR_SEL_CTRL2', + 'DIO_CLOCK_GATING_DIS', 'DIO_CLOCK_GATING_DISABLE', + 'DIO_CLOCK_GATING_EN', 'DIO_DBG_BLOCK_SEL', + 'DIO_DBG_BLOCK_SEL_AUX0', 'DIO_DBG_BLOCK_SEL_AUX1', + 'DIO_DBG_BLOCK_SEL_AUX2', 'DIO_DBG_BLOCK_SEL_AUX3', + 'DIO_DBG_BLOCK_SEL_DIGA', 'DIO_DBG_BLOCK_SEL_DIGB', + 'DIO_DBG_BLOCK_SEL_DIGC', 'DIO_DBG_BLOCK_SEL_DIGD', + 'DIO_DBG_BLOCK_SEL_DIGFE_A', 'DIO_DBG_BLOCK_SEL_DIGFE_B', + 'DIO_DBG_BLOCK_SEL_DIGFE_C', 'DIO_DBG_BLOCK_SEL_DIGFE_D', + 'DIO_DBG_BLOCK_SEL_DIO', 'DIO_DBG_BLOCK_SEL_DPA', + 'DIO_DBG_BLOCK_SEL_DPB', 'DIO_DBG_BLOCK_SEL_DPC', + 'DIO_DBG_BLOCK_SEL_DPD', 'DIO_DBG_BLOCK_SEL_DPFE_A', + 'DIO_DBG_BLOCK_SEL_DPFE_B', 'DIO_DBG_BLOCK_SEL_DPFE_C', + 'DIO_DBG_BLOCK_SEL_DPFE_D', 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', + 'DIO_DBG_BLOCK_SEL_RESERVED', 'DIO_FIFO_ERROR', + 'DIO_FIFO_ERROR_00', 'DIO_FIFO_ERROR_01', 'DIO_FIFO_ERROR_10', + 'DIO_FIFO_ERROR_11', + 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', 'DISABLE_CLOCK_GATING', + 'DISABLE_CLOCK_GATING_IN_DCO', 'DISABLE_DEBUG', + 'DISABLE_JITTER_REMOVAL', 'DISABLE_MEM_PWR_CTRL', 'DISABLE_PWL', + 'DISABLE_TF0_OPT', 'DISABLE_TF1_OPT', 'DISABLE_THE_FEATURE', + 'DISABLE_THE_INTERRUPT', 'DISPCLK_CHG_FWD_CORR_DISABLE', + 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', + 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 'DISPCLK_FREQ_RAMP_COMPLETED', 'DISPCLK_FREQ_RAMP_DONE', + 'DISPCLK_FREQ_RAMP_IN_PROGRESS', 'DIVISOR_BY1', + 'DIVISOR_BY2_RESERVED', 'DIVISOR_BY3', 'DIVISOR_BY4_RESERVED', + 'DIVISOR_BY5_RESERVED', 'DIVISOR_BY6_RESERVED', + 'DIVISOR_BY7_RESERVED', 'DIVISOR_BY8_RESERVED', 'DIV_2', 'DIV_4', + 'DIV_8', 'DI_INDEX_SIZE_16_BIT', 'DI_INDEX_SIZE_32_BIT', + 'DI_INDEX_SIZE_8_BIT', 'DI_PT_2D_RECTANGLE', 'DI_PT_LINELIST', + 'DI_PT_LINELIST_ADJ', 'DI_PT_LINELOOP', 'DI_PT_LINESTRIP', + 'DI_PT_LINESTRIP_ADJ', 'DI_PT_NONE', 'DI_PT_PATCH', + 'DI_PT_POINTLIST', 'DI_PT_POLYGON', 'DI_PT_QUADLIST', + 'DI_PT_QUADSTRIP', 'DI_PT_RECTLIST', 'DI_PT_TRIFAN', + 'DI_PT_TRILIST', 'DI_PT_TRILIST_ADJ', 'DI_PT_TRISTRIP', + 'DI_PT_TRISTRIP_ADJ', 'DI_PT_UNUSED_1', 'DI_PT_UNUSED_3', + 'DI_PT_UNUSED_4', 'DI_PT_UNUSED_5', 'DI_SRC_SEL_AUTO_INDEX', + 'DI_SRC_SEL_DMA', 'DI_SRC_SEL_IMMEDIATE', 'DI_SRC_SEL_RESERVED', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', + 'DMDATA_CLEAR_UNDERFLOW_STATUS', 'DMDATA_DONE', + 'DMDATA_DONT_CLEAR', 'DMDATA_HARDWARE_UPDATE_MODE', 'DMDATA_MODE', + 'DMDATA_NOT_SENT_TO_DIG', 'DMDATA_NOT_UNDERFLOW', + 'DMDATA_NOT_UPDATED', 'DMDATA_QOS_LEVEL_FROM_SOFTWARE', + 'DMDATA_QOS_LEVEL_FROM_TTU', 'DMDATA_QOS_MODE', 'DMDATA_REPEAT', + 'DMDATA_SENT_TO_DIG', 'DMDATA_SOFTWARE_UPDATE_MODE', + 'DMDATA_UNDERFLOW', 'DMDATA_UNDERFLOWED', + 'DMDATA_UNDERFLOW_CLEAR', 'DMDATA_UPDATED', + 'DMDATA_USE_FOR_CURRENT_AND_FUTURE_FRAMES', + 'DMDATA_USE_FOR_CURRENT_FRAME_ONLY', 'DMDATA_VM_DONE', + 'DMDATA_VM_IS_DONE', 'DMDATA_VM_IS_NOT_DONE', + 'DMDATA_WAS_UPDATED', 'DME_MEM_DISABLE_MEM_PWR_CTRL', + 'DME_MEM_ENABLE_MEM_PWR_CTRL', 'DME_MEM_FORCE_DEEP_SLEEP_REQUEST', + 'DME_MEM_FORCE_LIGHT_SLEEP_REQUEST', + 'DME_MEM_FORCE_SHUT_DOWN_REQUEST', 'DME_MEM_NO_FORCE_REQUEST', + 'DME_MEM_POWER_STATE_ENUM', 'DME_MEM_POWER_STATE_ENUM_DS', + 'DME_MEM_POWER_STATE_ENUM_LS', 'DME_MEM_POWER_STATE_ENUM_ON', + 'DME_MEM_POWER_STATE_ENUM_SD', 'DME_MEM_PWR_DIS_CTRL', + 'DME_MEM_PWR_FORCE_CTRL', 'DMU_CLOCK_ON', 'DMU_CLOCK_STATUS_OFF', + 'DMU_CLOCK_STATUS_ON', 'DMU_DC_GPU_TIMER_READ_SELECT', + 'DMU_DC_GPU_TIMER_START_POSITION', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_48', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_FLIP_AWAY_76', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VREADY_36', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM_24', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_STARTUP_12', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_0', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE_NO_LOCK_64', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_50', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_FLIP_AWAY_78', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VREADY_38', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM_26', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_STARTUP_14', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_2', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE_NO_LOCK_66', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_52', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_FLIP_AWAY_80', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VREADY_40', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM_28', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_STARTUP_16', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_4', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE_NO_LOCK_68', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_54', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_FLIP_AWAY_82', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VREADY_42', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM_30', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_STARTUP_18', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_6', + 'DMU_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE_NO_LOCK_70', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_49', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_FLIP_AWAY_77', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VREADY_37', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM_25', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_STARTUP_13', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_1', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE_NO_LOCK_65', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_51', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_FLIP_AWAY_79', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VREADY_39', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM_27', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_STARTUP_15', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_3', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE_NO_LOCK_67', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_53', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_FLIP_AWAY_81', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VREADY_41', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM_29', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_STARTUP_17', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_5', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE_NO_LOCK_69', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_55', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_FLIP_AWAY_83', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VREADY_43', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM_31', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_STARTUP_19', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_7', + 'DMU_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE_NO_LOCK_71', + 'DMU_GPU_TIMER_START_0_END_27', 'DMU_GPU_TIMER_START_10_END_37', + 'DMU_GPU_TIMER_START_1_END_28', 'DMU_GPU_TIMER_START_2_END_29', + 'DMU_GPU_TIMER_START_3_END_30', 'DMU_GPU_TIMER_START_4_END_31', + 'DMU_GPU_TIMER_START_6_END_33', 'DMU_GPU_TIMER_START_8_END_35', + 'DONUTS', 'DOUT_I2C_ACK', 'DOUT_I2C_ACK_TO_CLEAN', + 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_ABORT_XFER', + 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', + 'DOUT_I2C_CONTROL_DBG_REF_SEL', 'DOUT_I2C_CONTROL_DDC_SELECT', + 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', 'DOUT_I2C_CONTROL_GO', + 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_SELECT_DDC1', 'DOUT_I2C_CONTROL_SELECT_DDC2', + 'DOUT_I2C_CONTROL_SELECT_DDC3', 'DOUT_I2C_CONTROL_SELECT_DDC4', + 'DOUT_I2C_CONTROL_SELECT_DDCVGA', 'DOUT_I2C_CONTROL_SEND_RESET', + 'DOUT_I2C_CONTROL_SEND_RESET_LENGTH', + 'DOUT_I2C_CONTROL_SOFT_RESET', 'DOUT_I2C_CONTROL_START_TRANSFER', + 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 'DOUT_I2C_CONTROL_SW_STATUS_RESET', 'DOUT_I2C_CONTROL_TRANS0', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', + 'DOUT_I2C_CONTROL_TRANSACTION_COUNT', + 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_10', + 'DOUT_I2C_CONTROL__SEND_RESET_LENGTH_9', + 'DOUT_I2C_DATA_INDEX_WRITE', 'DOUT_I2C_DATA__INDEX_WRITE', + 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', + 'DOUT_I2C_DDC_SPEED_THRESHOLD', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', + 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET', + 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_NO_ACK', 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', + 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DPHY_8B10B_CUR_DISP', + 'DPHY_8B10B_CUR_DISP_ONE', 'DPHY_8B10B_CUR_DISP_ZERO', + 'DPHY_8B10B_NOT_RESET', 'DPHY_8B10B_OUTPUT', 'DPHY_8B10B_RESET', + 'DPHY_8B10B_RESETET', 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 'DPHY_ATEST_LANE0_REG_PATTERN', 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 'DPHY_ATEST_LANE1_REG_PATTERN', 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 'DPHY_ATEST_LANE2_REG_PATTERN', 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 'DPHY_ATEST_LANE3_REG_PATTERN', 'DPHY_ATEST_SEL_LANE0', + 'DPHY_ATEST_SEL_LANE1', 'DPHY_ATEST_SEL_LANE2', + 'DPHY_ATEST_SEL_LANE3', 'DPHY_BYPASS', 'DPHY_CRC_CONTINUOUS', + 'DPHY_CRC_CONT_EN', 'DPHY_CRC_DISABLED', 'DPHY_CRC_EN', + 'DPHY_CRC_ENABLED', 'DPHY_CRC_FIELD', 'DPHY_CRC_LANE0_SELECTED', + 'DPHY_CRC_LANE1_SELECTED', 'DPHY_CRC_LANE2_SELECTED', + 'DPHY_CRC_LANE3_SELECTED', 'DPHY_CRC_MST_PHASE_ERROR_ACK', + 'DPHY_CRC_MST_PHASE_ERROR_ACKED', + 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', 'DPHY_CRC_ONE_SHOT', + 'DPHY_CRC_SEL', 'DPHY_CRC_START_FROM_BOTTOM_FIELD', + 'DPHY_CRC_START_FROM_TOP_FIELD', 'DPHY_DBG_OUTPUT', + 'DPHY_FAST_TRAINING_CAPABLE', 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 'DPHY_FEC_ACTIVE', 'DPHY_FEC_DISABLED', 'DPHY_FEC_ENABLE', + 'DPHY_FEC_ENABLED', 'DPHY_FEC_NOT_ACTIVE', 'DPHY_FEC_READY', + 'DPHY_FEC_READY_DIS', 'DPHY_FEC_READY_EN', + 'DPHY_LOAD_BS_COUNT_NOT_STARTED', 'DPHY_LOAD_BS_COUNT_START', + 'DPHY_LOAD_BS_COUNT_STARTED', 'DPHY_NO_SKEW', + 'DPHY_PRBS11_SELECTED', 'DPHY_PRBS23_SELECTED', + 'DPHY_PRBS7_SELECTED', 'DPHY_PRBS_DISABLE', 'DPHY_PRBS_EN', + 'DPHY_PRBS_ENABLE', 'DPHY_PRBS_SEL', + 'DPHY_RX_FAST_TRAINING_CAPABLE', 'DPHY_SKEW_BYPASS', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_ENUM', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_NOT_RESET', + 'DPHY_STREAM_RESET_DURING_FAST_TRAINING_RESET', + 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 'DPHY_SW_FAST_TRAINING_START', 'DPHY_SW_FAST_TRAINING_STARTED', + 'DPHY_TRAINING_PATTERN_1', 'DPHY_TRAINING_PATTERN_2', + 'DPHY_TRAINING_PATTERN_3', 'DPHY_TRAINING_PATTERN_4', + 'DPHY_TRAINING_PATTERN_SEL', 'DPHY_WITH_SKEW', 'DPREFCLK_SRC_SEL', + 'DPREFCLK_SRC_SEL_CK', 'DPREFCLK_SRC_SEL_P0PLL', + 'DPREFCLK_SRC_SEL_P1PLL', 'DPREFCLK_SRC_SEL_P2PLL', + 'DPTE_GROUP_SIZE', 'DPTE_GROUP_SIZE_1024B', + 'DPTE_GROUP_SIZE_128B', 'DPTE_GROUP_SIZE_2048B', + 'DPTE_GROUP_SIZE_256B', 'DPTE_GROUP_SIZE_512B', + 'DPTE_GROUP_SIZE_64B', 'DP_AUX_ARB_CONTROL_ARB_PRIORITY', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', 'DP_AUX_ARB_STATUS', + 'DP_AUX_CONTROL_HPD1_SELECTED', 'DP_AUX_CONTROL_HPD2_SELECTED', + 'DP_AUX_CONTROL_HPD3_SELECTED', 'DP_AUX_CONTROL_HPD4_SELECTED', + 'DP_AUX_CONTROL_HPD_SEL', 'DP_AUX_CONTROL_NO_HPD_SELECTED', + 'DP_AUX_CONTROL_TEST_MODE', 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 'DP_AUX_CONTROL_TEST_MODE_ENABLE', + 'DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', + 'DP_AUX_ERR_OCCURRED_ACK', 'DP_AUX_ERR_OCCURRED__ACK', + 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 'DP_AUX_IDLE', 'DP_AUX_INT_ACK', 'DP_AUX_INT_LS_UPDATE_ACK', + 'DP_AUX_INT_LS_UPDATE_NOT_ACK', 'DP_AUX_INT__ACK', + 'DP_AUX_INT__NOT_ACK', 'DP_AUX_IN_USE_GTC', 'DP_AUX_IN_USE_LS', + 'DP_AUX_IN_USE_PHYWAKE', 'DP_AUX_IN_USE_SW', + 'DP_AUX_LS_UPDATE_ACK', 'DP_AUX_PHY_WAKE_HIGH_PRIORITY', + 'DP_AUX_PHY_WAKE_LOW_PRIORITY', 'DP_AUX_PHY_WAKE_PRIORITY', + 'DP_AUX_POTENTIAL_ERR_REACHED_ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', 'DP_AUX_RESET', + 'DP_AUX_RESET_ASSERTED', 'DP_AUX_RESET_DEASSERTED', + 'DP_AUX_RESET_DONE', 'DP_AUX_RESET_SEQUENCE_DONE', + 'DP_AUX_RESET_SEQUENCE_NOT_DONE', 'DP_AUX_RX_TIMEOUT_LEN_MUL', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_2', 'DP_AUX_RX_TIMEOUT_LEN_MUL_4', + 'DP_AUX_RX_TIMEOUT_LEN_MUL_8', 'DP_AUX_RX_TIMEOUT_LEN_NO_MUL', + 'DP_AUX_SW_CONTROL_LS_READ_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__TRIG', 'DP_AUX_SW_CONTROL_SW_GO', + 'DP_AUX_SW_CONTROL_SW__GO', 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 'DP_AUX_TX_PRECHARGE_LEN_MUL', 'DP_AUX_TX_PRECHARGE_LEN_MUL_2', + 'DP_AUX_TX_PRECHARGE_LEN_MUL_4', 'DP_AUX_TX_PRECHARGE_LEN_MUL_8', + 'DP_AUX_TX_PRECHARGE_LEN_NO_MUL', 'DP_COMPONENT_DEPTH', + 'DP_COMPONENT_DEPTH_10BPC', 'DP_COMPONENT_DEPTH_12BPC', + 'DP_COMPONENT_DEPTH_16BPC', 'DP_COMPONENT_DEPTH_6BPC', + 'DP_COMPONENT_DEPTH_8BPC', 'DP_COMPRESSED_PIXEL_FORMAT', + 'DP_DPHY_8B10B_EXT_DISP', 'DP_DPHY_8B10B_EXT_DISP_ONE', + 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', + 'DP_DPHY_HBR2_PASS_THROUGH', 'DP_DPHY_HBR2_PATTERN_1', + 'DP_DPHY_HBR2_PATTERN_2_NEG', 'DP_DPHY_HBR2_PATTERN_2_POS', + 'DP_DPHY_HBR2_PATTERN_3', 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE', + 'DP_DPHY_SYM32_1LANE', 'DP_DPHY_SYM32_2LANE', + 'DP_DPHY_SYM32_4LANE', 'DP_DPHY_SYM32_ACTIVE', + 'DP_DPHY_SYM32_CRC_END_LLCP', 'DP_DPHY_SYM32_CRC_END_PS_ANY', + 'DP_DPHY_SYM32_CRC_END_PS_LT_SR', 'DP_DPHY_SYM32_CRC_END_PS_ONLY', + 'DP_DPHY_SYM32_CRC_START_LLCP', + 'DP_DPHY_SYM32_CRC_START_PS_LT_SR', + 'DP_DPHY_SYM32_CRC_START_PS_ONLY', + 'DP_DPHY_SYM32_CRC_START_PS_POST_LT_SR', + 'DP_DPHY_SYM32_CRC_START_TP_START', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SCHEDULER', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_SYMBOL_HANDLER', + 'DP_DPHY_SYM32_CRC_TAP_SOURCE_TP_GEN_MUX', + 'DP_DPHY_SYM32_CRC_USE_END_EVENT', + 'DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', 'DP_DPHY_SYM32_DISABLE', + 'DP_DPHY_SYM32_ENABLE', 'DP_DPHY_SYM32_LT_TPS1', + 'DP_DPHY_SYM32_LT_TPS2', 'DP_DPHY_SYM32_NOT_RESET', + 'DP_DPHY_SYM32_NO_RATE_UPDATE_PENDING', + 'DP_DPHY_SYM32_OUTPUT_DPIA', 'DP_DPHY_SYM32_OUTPUT_PHY', + 'DP_DPHY_SYM32_RATE_UPDATE_PENDING', 'DP_DPHY_SYM32_RESERVED', + 'DP_DPHY_SYM32_RESET', 'DP_DPHY_SYM32_RESET_STATUS_ASSERTED', + 'DP_DPHY_SYM32_RESET_STATUS_DEASSERTED', + 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE', + 'DP_DPHY_SYM32_SAT_NOTRIGGER_UPDATE_PENDING', + 'DP_DPHY_SYM32_SAT_NO_UPDATE', + 'DP_DPHY_SYM32_SAT_NO_UPDATE_PENDING', + 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE', + 'DP_DPHY_SYM32_SAT_TRIGGER_UPDATE_PENDING', + 'DP_DPHY_SYM32_SCHEDULER_ASLEEP', 'DP_DPHY_SYM32_SCHEDULER_AWAKE', + 'DP_DPHY_SYM32_SCHEDULER_OFF', 'DP_DPHY_SYM32_STATUS_ENABLED', + 'DP_DPHY_SYM32_STATUS_IDLE', 'DP_DPHY_SYM32_STREAM_OVR_ALWAYS', + 'DP_DPHY_SYM32_STREAM_OVR_NONE', + 'DP_DPHY_SYM32_STREAM_OVR_REPLACE', + 'DP_DPHY_SYM32_STREAM_OVR_TYPE_CONTROL', + 'DP_DPHY_SYM32_STREAM_OVR_TYPE_DATA', 'DP_DPHY_SYM32_TEST', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS11', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS15', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS23', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS31', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS7', + 'DP_DPHY_SYM32_TP_PRBS_SEL_PRBS9', + 'DP_DPHY_SYM32_TP_SELECT_CUSTOM', 'DP_DPHY_SYM32_TP_SELECT_PRBS', + 'DP_DPHY_SYM32_TP_SELECT_SQUARE', 'DP_DPHY_SYM32_TP_SELECT_TPS1', + 'DP_DPHY_SYM32_TP_SELECT_TPS2', 'DP_DSC_444_S422', + 'DP_DSC_N422_N420', 'DP_DTO_DESPREAD_DISABLE', + 'DP_DTO_DESPREAD_ENABLE', 'DP_DTO_DS_DISABLE', + 'DP_LINK_TRAINING_ALREADY_COMPLETE', 'DP_LINK_TRAINING_COMPLETE', + 'DP_LINK_TRAINING_NOT_COMPLETE', 'DP_LINK_TRAINING_SWITCH_MODE', + 'DP_LINK_TRAINING_SWITCH_TO_IDLE', + 'DP_LINK_TRAINING_SWITCH_TO_VIDEO', 'DP_ML_PHY_SEQ_IMMEDIATE', + 'DP_ML_PHY_SEQ_LINE_NUM', 'DP_ML_PHY_SEQ_MODE', + 'DP_MSA_V_TIMING_OVERRIDE_EN', 'DP_MSE_BLANK_CODE', + 'DP_MSE_BLANK_CODE_SF_FILLED', 'DP_MSE_BLANK_CODE_ZERO_FILLED', + 'DP_MSE_LINK_LINE', 'DP_MSE_LINK_LINE_128_MTP_LONG', + 'DP_MSE_LINK_LINE_256_MTP_LONG', 'DP_MSE_LINK_LINE_32_MTP_LONG', + 'DP_MSE_LINK_LINE_64_MTP_LONG', 'DP_MSE_NOT_ZERO_FE_ENCODER', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', 'DP_MSE_TIMESTAMP_MODE', + 'DP_MSE_ZERO_ENCODER', 'DP_MSE_ZERO_FE_ENCODER', + 'DP_MSO_FOUR_SSTLINK', 'DP_MSO_NUM_OF_SST_LINKS', + 'DP_MSO_ONE_SSTLINK', 'DP_MSO_TWO_SSTLINK', 'DP_MST_MODE', + 'DP_PIXEL_ENCODING', 'DP_PIXEL_ENCODING_COMPRESSED', + 'DP_PIXEL_ENCODING_RGB_YCBCR444', 'DP_PIXEL_ENCODING_TYPE', + 'DP_PIXEL_ENCODING_UNCOMPRESSED', 'DP_PIXEL_ENCODING_YCBCR420', + 'DP_PIXEL_ENCODING_YCBCR422', 'DP_PIXEL_ENCODING_Y_ONLY', + 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'DP_SEC_ASP_HIGH_PRIORITY', 'DP_SEC_ASP_LOW_PRIORITY', + 'DP_SEC_ASP_PRIORITY', 'DP_SEC_AUDIO_MUTE', + 'DP_SEC_AUDIO_MUTE_HW_CTRL', 'DP_SEC_AUDIO_MUTE_SW_CTRL', + 'DP_SEC_COLLISION_ACK', 'DP_SEC_COLLISION_ACK_CLR_FLAG', + 'DP_SEC_COLLISION_ACK_NO_EFFECT', 'DP_SEC_GSP0_PRIORITY', + 'DP_SEC_GSP_SEND', 'DP_SEC_GSP_SEND_ANY_LINE', + 'DP_SEC_GSP_SEND_PPS', 'DP_SEC_LINE_REFERENCE', + 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', 'DP_SEC_TIMESTAMP_MODE', + 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', 'DP_SST_MODE', + 'DP_STEER_1_PIX_PER_CYCLE', 'DP_STEER_2_PIX_PER_CYCLE', + 'DP_STEER_4_PIX_PER_CYCLE', 'DP_STEER_8_PIX_PER_CYCLE', + 'DP_STEER_OUTPUT_PIXEL_PER_CYCLE', 'DP_STEER_OVERFLOW_ACK', + 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', 'DP_STEER_OVERFLOW_MASK', + 'DP_STEER_OVERFLOW_MASKED', 'DP_STEER_OVERFLOW_UNMASK', + 'DP_STREAM_ENC_DCCG', 'DP_STREAM_ENC_DISPLAY_PIPE', + 'DP_STREAM_ENC_HARDWARE', 'DP_STREAM_ENC_NOT_RESET', + 'DP_STREAM_ENC_NO_ERROR_OCCURRED', + 'DP_STREAM_ENC_OVERFLOW_OCCURRED', + 'DP_STREAM_ENC_OVERFLOW_UNDERFLOW_ERROR', + 'DP_STREAM_ENC_OVERWRITE_LEVEL_SELECT', + 'DP_STREAM_ENC_PROGRAMMABLE', 'DP_STREAM_ENC_READ_CLOCK_CONTROL', + 'DP_STREAM_ENC_RESET', 'DP_STREAM_ENC_RESET_CONTROL', + 'DP_STREAM_ENC_STREAM_ACTIVE', 'DP_STREAM_ENC_UNDERFLOW_OCCURRED', + 'DP_STREAM_ENC_VIDEO_STREAM_ACTIVE', + 'DP_STREAM_ENC_VIDEO_STREAM_NOT_ACTIVE', + 'DP_STREAM_MAPPER_DP_STREAM_LINK_TARGET', + 'DP_STREAM_MAPPER_LINK0', 'DP_STREAM_MAPPER_LINK1', + 'DP_STREAM_MAPPER_LINK2', 'DP_STREAM_MAPPER_LINK3', + 'DP_STREAM_MAPPER_RESERVED', 'DP_SYM32_ENC_COMPONENT_DEPTH_10BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_12BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_6BPC', + 'DP_SYM32_ENC_COMPONENT_DEPTH_8BPC', + 'DP_SYM32_ENC_COMPRESSED_FORMAT', 'DP_SYM32_ENC_CONTINUOUS_MODE', + 'DP_SYM32_ENC_CRC_NOT_VALID', 'DP_SYM32_ENC_CRC_VALID', + 'DP_SYM32_ENC_DISABLE', 'DP_SYM32_ENC_DP_SOF', + 'DP_SYM32_ENC_ENABLE', 'DP_SYM32_ENC_GSP_DEADLINE_MISSED', + 'DP_SYM32_ENC_GSP_DEADLINE_NOT_MISSED', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_128', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_32', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED0', + 'DP_SYM32_ENC_GSP_PAYLOAD_SIZE_RESERVED1', + 'DP_SYM32_ENC_GSP_SEND_AT_EARLIEST_TIME', + 'DP_SYM32_ENC_GSP_SEND_AT_LINE_NUMBER', + 'DP_SYM32_ENC_GSP_TRIGGER_NOT_PENDING', + 'DP_SYM32_ENC_GSP_TRIGGER_PENDING', + 'DP_SYM32_ENC_MEM_PWR_FORCE_DEEP_SLEEP_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_FORCE_LIGHT_SLEEP_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_FORCE_SHUT_DOWN_REQUEST', + 'DP_SYM32_ENC_MEM_PWR_NO_FORCE_REQUEST', + 'DP_SYM32_ENC_NOT_PENDING', 'DP_SYM32_ENC_NOT_RESET', + 'DP_SYM32_ENC_NO_OVERFLOW_OCCURRED', 'DP_SYM32_ENC_ONE_SHOT_MODE', + 'DP_SYM32_ENC_OTG_SOF', 'DP_SYM32_ENC_OVERFLOW_OCCURRED', + 'DP_SYM32_ENC_PENDING', + 'DP_SYM32_ENC_PIXEL_ENCODING_RGB_YCBCR444', + 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR420', + 'DP_SYM32_ENC_PIXEL_ENCODING_YCBCR422', + 'DP_SYM32_ENC_PIXEL_ENCODING_Y_ONLY', + 'DP_SYM32_ENC_POWER_STATE_ENUM_DS', + 'DP_SYM32_ENC_POWER_STATE_ENUM_LS', + 'DP_SYM32_ENC_POWER_STATE_ENUM_ON', + 'DP_SYM32_ENC_POWER_STATE_ENUM_SD', 'DP_SYM32_ENC_RESET', + 'DP_SYM32_ENC_SDP_AUDIO_MUTE_FORCED', + 'DP_SYM32_ENC_SDP_AUDIO_MUTE_NOT_FORCED', + 'DP_SYM32_ENC_SDP_HIGH_PRIORITY', 'DP_SYM32_ENC_SDP_LOW_PRIORITY', + 'DP_SYM32_ENC_UNCOMPRESSED_FORMAT', + 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_HBLANK', + 'DP_SYM32_ENC_VID_STREAM_DEFER_TO_VBLANK', + 'DP_SYM32_ENC_VID_STREAM_NO_DEFER', 'DP_SYNC_POLARITY', + 'DP_SYNC_POLARITY_ACTIVE_HIGH', 'DP_SYNC_POLARITY_ACTIVE_LOW', + 'DP_TU_OVERFLOW_ACK', 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_TU_OVERFLOW_ACK_NO_EFFECT', 'DP_UDI_1_LANE', 'DP_UDI_2_LANES', + 'DP_UDI_4_LANES', 'DP_UDI_LANES', 'DP_UDI_LANES_RESERVED', + 'DP_VID_1X_Nvid', 'DP_VID_2X_Nvid', 'DP_VID_4X_Nvid', + 'DP_VID_8X_Nvid', 'DP_VID_ENHANCED_FRAME_MODE', + 'DP_VID_M_N_CALC_AUTO', + 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', + 'DP_VID_M_N_DOUBLE_BUFFER_MODE', 'DP_VID_M_N_GEN_EN', + 'DP_VID_M_N_PROGRAMMED_VIA_REG', 'DP_VID_N_INTERVAL', + 'DP_VID_STREAM_DISABLE_ACK', 'DP_VID_STREAM_DISABLE_MASK', + 'DP_VID_STREAM_DIS_DEFER', 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', 'DP_VID_STREAM_DIS_NO_DEFER', + 'DP_VID_VBID_FIELD_POL', 'DP_VID_VBID_FIELD_POL_INV', + 'DP_VID_VBID_FIELD_POL_NORMAL', 'DRAW_DONE', + 'DSCCIF_BITS_PER_COMPONENT_ENUM', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCCIF_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCCIF_ENABLE_ENUM', 'DSCCIF_ENABLE_ENUM_DISABLED', + 'DSCCIF_ENABLE_ENUM_ENABLED', 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_420', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_NATIVE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_RGB', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_SIMPLE_YCBCR_422', + 'DSCCIF_INPUT_PIXEL_FORMAT_ENUM_YCBCR_444', + 'DSCC_BITS_PER_COMPONENT_ENUM', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_10_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_12_BIT', + 'DSCC_BITS_PER_COMPONENT_ENUM_BITS_PER_COMPONENT_8_BIT', + 'DSCC_DSC_VERSION_MAJOR_ENUM', + 'DSCC_DSC_VERSION_MAJOR_ENUM_DSC_1_X_MAJOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_1_MINOR_VERSION', + 'DSCC_DSC_VERSION_MINOR_ENUM_DSC_X_2_MINOR_VERSION', + 'DSCC_ENABLE_ENUM', 'DSCC_ENABLE_ENUM_DISABLED', + 'DSCC_ENABLE_ENUM_ENABLED', 'DSCC_ICH_RESET_ENUM', + 'DSCC_ICH_RESET_ENUM_SLICE0_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE1_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE2_ICH_RESET', + 'DSCC_ICH_RESET_ENUM_SLICE3_ICH_RESET', 'DSCC_LINEBUF_DEPTH_ENUM', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_10_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_11_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_12_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_13_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_8_BIT', + 'DSCC_LINEBUF_DEPTH_ENUM_LINEBUF_DEPTH_9_BIT', + 'DSCC_MEM_PWR_DIS_ENUM', 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_DIS', + 'DSCC_MEM_PWR_DIS_ENUM_REQUEST_EN', 'DSCC_MEM_PWR_FORCE_ENUM', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_DEEP_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_LIGHT_SLEEP_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_FORCE_SHUT_DOWN_REQUEST', + 'DSCC_MEM_PWR_FORCE_ENUM_NO_FORCE_REQUEST', + 'DSCL_MODE_CHROMA_SCALING_BYPASS', 'DSCL_MODE_DSCL_BYPASS', + 'DSCL_MODE_LUMA_SCALING_BYPASS', 'DSCL_MODE_SCALING_444_BYPASS', + 'DSCL_MODE_SCALING_444_RGB_ENABLE', + 'DSCL_MODE_SCALING_444_YCBCR_ENABLE', + 'DSCL_MODE_SCALING_YCBCR_ENABLE', 'DSCL_MODE_SEL', + 'DS_HW_CAL_DIS', 'DS_HW_CAL_EN', 'DS_HW_CAL_ENABLE', + 'DS_REF_IS_EXT_GENLOCK', 'DS_REF_IS_PCIE', 'DS_REF_IS_XTALIN', + 'DS_REF_SRC', 'DVO_ENABLE_RST', 'DVO_ENABLE_RST_DISABLE', + 'DVO_ENABLE_RST_ENABLE', 'DWB_CRC_CONT_EN_CONT', + 'DWB_CRC_CONT_EN_ENUM', 'DWB_CRC_CONT_EN_ONE_SHOT', + 'DWB_CRC_SRC_SEL_DWB_IN', 'DWB_CRC_SRC_SEL_DWB_OUT', + 'DWB_CRC_SRC_SEL_ENUM', 'DWB_CRC_SRC_SEL_OGAM_OUT', + 'DWB_DATA_OVERFLOW_INT_TYPE_0', 'DWB_DATA_OVERFLOW_INT_TYPE_1', + 'DWB_DATA_OVERFLOW_INT_TYPE_ENUM', + 'DWB_DATA_OVERFLOW_TYPE_BUFFER', 'DWB_DATA_OVERFLOW_TYPE_ENUM', + 'DWB_DATA_OVERFLOW_TYPE_NO_OVERFLOW', + 'DWB_DATA_OVERFLOW_TYPE_VREADY', 'DWB_DATA_OVERFLOW_TYPE_VUPDATE', + 'DWB_DEBUG_SEL_DWBCP', 'DWB_DEBUG_SEL_ENUM', 'DWB_DEBUG_SEL_FC', + 'DWB_DEBUG_SEL_PERFMON', 'DWB_DEBUG_SEL_RESERVED', + 'DWB_GAMUT_REMAP_COEF_FORMAT_ENUM', + 'DWB_GAMUT_REMAP_COEF_FORMAT_S2_13', + 'DWB_GAMUT_REMAP_COEF_FORMAT_S3_12', + 'DWB_GAMUT_REMAP_MODE_BYPASS', 'DWB_GAMUT_REMAP_MODE_COEF_A', + 'DWB_GAMUT_REMAP_MODE_COEF_B', 'DWB_GAMUT_REMAP_MODE_ENUM', + 'DWB_GAMUT_REMAP_MODE_RESERVED', 'DWB_LUT_NUM_SEG', + 'DWB_MEM_PWR_FORCE_DIS', 'DWB_MEM_PWR_FORCE_DS', + 'DWB_MEM_PWR_FORCE_ENUM', 'DWB_MEM_PWR_FORCE_LS', + 'DWB_MEM_PWR_FORCE_SD', 'DWB_MEM_PWR_STATE_DS', + 'DWB_MEM_PWR_STATE_ENUM', 'DWB_MEM_PWR_STATE_LS', + 'DWB_MEM_PWR_STATE_ON', 'DWB_MEM_PWR_STATE_SD', + 'DWB_OGAM_LUT_CONFIG_MODE_DIFF', 'DWB_OGAM_LUT_CONFIG_MODE_ENUM', + 'DWB_OGAM_LUT_CONFIG_MODE_SAME', 'DWB_OGAM_LUT_HOST_SEL_ENUM', + 'DWB_OGAM_LUT_HOST_SEL_RAMA', 'DWB_OGAM_LUT_HOST_SEL_RAMB', + 'DWB_OGAM_LUT_READ_COLOR_SEL_B', + 'DWB_OGAM_LUT_READ_COLOR_SEL_ENUM', + 'DWB_OGAM_LUT_READ_COLOR_SEL_G', 'DWB_OGAM_LUT_READ_COLOR_SEL_R', + 'DWB_OGAM_LUT_READ_COLOR_SEL_RESERVED', + 'DWB_OGAM_LUT_READ_DBG_DISABLE', 'DWB_OGAM_LUT_READ_DBG_ENABLE', + 'DWB_OGAM_LUT_READ_DBG_ENUM', 'DWB_OGAM_MODE_BYPASS', + 'DWB_OGAM_MODE_ENUM', 'DWB_OGAM_MODE_RAM_LUT_ENABLED', + 'DWB_OGAM_MODE_RESERVED', 'DWB_OGAM_PWL_DISABLE_ENUM', + 'DWB_OGAM_PWL_DISABLE_FALSE', 'DWB_OGAM_PWL_DISABLE_TRUE', + 'DWB_OGAM_SELECT_A', 'DWB_OGAM_SELECT_B', 'DWB_OGAM_SELECT_ENUM', + 'DWB_SEGMENTS_1', 'DWB_SEGMENTS_128', 'DWB_SEGMENTS_16', + 'DWB_SEGMENTS_2', 'DWB_SEGMENTS_32', 'DWB_SEGMENTS_4', + 'DWB_SEGMENTS_64', 'DWB_SEGMENTS_8', 'DWB_TEST_CLK_SEL_ENUM', + 'DWB_TEST_CLK_SEL_G', 'DWB_TEST_CLK_SEL_P', 'DWB_TEST_CLK_SEL_R', + 'DYNAMIC_DEEP_SLEEP_EN', 'DYNAMIC_DEEP_SLEEP_ENABLE', + 'DYNAMIC_LIGHT_SLEEP_EN', 'DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DYNAMIC_SHUT_DOWN_ENABLE', 'DbMemArbWatermarks', + 'DbPRTFaultBehavior', 'DbPSLControl', 'EARLY', + 'EARLY_Z_THEN_LATE_Z', 'EARLY_Z_THEN_RE_Z', + 'EFC_ACrYCb16161616_10LSB', 'EFC_ACrYCb16161616_10MSB', + 'EFC_ACrYCb16161616_12LSB', 'EFC_ACrYCb16161616_12MSB', + 'EFC_ACrYCb2101010', 'EFC_ACrYCb8888', 'EFC_ARGB1555', + 'EFC_ARGB16161616_10LSB', 'EFC_ARGB16161616_10MSB', + 'EFC_ARGB16161616_12LSB', 'EFC_ARGB16161616_12MSB', + 'EFC_ARGB16161616_FLOAT', 'EFC_ARGB16161616_SNORM', + 'EFC_ARGB16161616_UNORM', 'EFC_ARGB2101010', 'EFC_ARGB4444', + 'EFC_ARGB8888', 'EFC_AYCrCb16161616_10LSB', + 'EFC_AYCrCb16161616_10MSB', 'EFC_AYCrCb16161616_12LSB', + 'EFC_AYCrCb16161616_12MSB', 'EFC_AYCrCb8888', 'EFC_BGR101111_FIX', + 'EFC_BGR101111_FLOAT', 'EFC_BGR565', + 'EFC_CbYCrY10101010_422_PACKED', 'EFC_CbYCrY12121212_422_PACKED', + 'EFC_CbYCrY8888_422_PACKED', 'EFC_CrYCbA1010102', + 'EFC_CrYCbA16161616_10LSB', 'EFC_CrYCbA16161616_10MSB', + 'EFC_CrYCbA16161616_12LSB', 'EFC_CrYCbA16161616_12MSB', + 'EFC_CrYCbA8888', 'EFC_CrYCbY10101010_422_PACKED', + 'EFC_CrYCbY12121212_422_PACKED', 'EFC_CrYCbY8888_422_PACKED', + 'EFC_MONO_10LSB', 'EFC_MONO_10MSB', 'EFC_MONO_12LSB', + 'EFC_MONO_12MSB', 'EFC_MONO_16', 'EFC_MONO_8', + 'EFC_RGB111110_FIX', 'EFC_RGB111110_FLOAT', 'EFC_RGB565', + 'EFC_RGBA1010102', 'EFC_RGBA16161616_10LSB', + 'EFC_RGBA16161616_10MSB', 'EFC_RGBA16161616_12LSB', + 'EFC_RGBA16161616_12MSB', 'EFC_RGBA16161616_FLOAT', + 'EFC_RGBA16161616_SNORM', 'EFC_RGBA16161616_UNORM', + 'EFC_RGBA4444', 'EFC_RGBA5551', 'EFC_RGBA8888', + 'EFC_SURFACE_PIXEL_FORMAT', 'EFC_Y10_CbCr1010_420_PLANAR', + 'EFC_Y10_CrCb1010_420_PLANAR', 'EFC_Y12_CbCr1212_420_PLANAR', + 'EFC_Y12_CrCb1212_420_PLANAR', 'EFC_Y8_CbCr88_420_PLANAR', + 'EFC_Y8_CrCb88_420_PLANAR', 'EFC_YCbYCr10101010_422_PACKED', + 'EFC_YCbYCr12121212_422_PACKED', 'EFC_YCbYCr8888_422_PACKED', + 'EFC_YCrCbA16161616_10LSB', 'EFC_YCrCbA16161616_10MSB', + 'EFC_YCrCbA16161616_12LSB', 'EFC_YCrCbA16161616_12MSB', + 'EFC_YCrCbA8888', 'EFC_YCrYCb10101010_422_PACKED', + 'EFC_YCrYCb12121212_422_PACKED', 'EFC_YCrYCb8888_422_PACKED', + 'ENABLE', 'ENABLE_AMCLK0', 'ENABLE_AMCLK1', 'ENABLE_CLOCK', + 'ENABLE_DEBUG', 'ENABLE_ENUM', 'ENABLE_ENUM_DISABLED', + 'ENABLE_ENUM_ENABLED', 'ENABLE_JITTER_REMOVAL', + 'ENABLE_MEM_PWR_CTRL', 'ENABLE_NGG_PIPELINE', + 'ENABLE_PIPELINE_NOT_USED', 'ENABLE_PWL', 'ENABLE_TF0_OPT', + 'ENABLE_TF1_OPT', 'ENABLE_THE_FEATURE', 'ENABLE_THE_FUNC_CLOCK', + 'ENABLE_THE_INTERRUPT', 'ENABLE_THE_REFCLK', 'END_OF_PIPE_IB_END', + 'END_OF_PIPE_INCR_DE', 'END_OF_ROW_MODE', 'ENUM_DCN_ACTIVE', + 'ENUM_DCN_NOT_ACTIVE', 'ENUM_DIO_DCN_ACTIVE_STATUS', + 'ENUM_DPG_BIT_DEPTH', 'ENUM_DPG_BIT_DEPTH_10BPC', + 'ENUM_DPG_BIT_DEPTH_12BPC', 'ENUM_DPG_BIT_DEPTH_6BPC', + 'ENUM_DPG_BIT_DEPTH_8BPC', 'ENUM_DPG_DISABLE', + 'ENUM_DPG_DYNAMIC_RANGE', 'ENUM_DPG_DYNAMIC_RANGE_CEA', + 'ENUM_DPG_DYNAMIC_RANGE_VESA', 'ENUM_DPG_EN', 'ENUM_DPG_ENABLE', + 'ENUM_DPG_FIELD_POLARITY', + 'ENUM_DPG_FIELD_POLARITY_TOP_EVEN_BOTTOM_ODD', + 'ENUM_DPG_FIELD_POLARITY_TOP_ODD_BOTTOM_EVEN', 'ENUM_DPG_MODE', + 'ENUM_DPG_MODE_HORIZONTAL_BAR', 'ENUM_DPG_MODE_RGB_COLOUR_BLOCK', + 'ENUM_DPG_MODE_RGB_DUAL_RAMP', 'ENUM_DPG_MODE_RGB_SINGLE_RAMP', + 'ENUM_DPG_MODE_RGB_XR_BIAS', 'ENUM_DPG_MODE_VERTICAL_BAR', + 'ENUM_DPG_MODE_YCBCR_601_COLOUR_BLOCK', + 'ENUM_DPG_MODE_YCBCR_709_COLOUR_BLOCK', + 'ENUM_DP_DPHY_SYM32_CRC_END_EVENT', + 'ENUM_DP_DPHY_SYM32_CRC_START_EVENT', + 'ENUM_DP_DPHY_SYM32_CRC_TAP_SOURCE', + 'ENUM_DP_DPHY_SYM32_CRC_USE_NUM_SYMBOLS', + 'ENUM_DP_DPHY_SYM32_ENABLE', 'ENUM_DP_DPHY_SYM32_MODE', + 'ENUM_DP_DPHY_SYM32_NUM_LANES', 'ENUM_DP_DPHY_SYM32_OUTPUT_MODE', + 'ENUM_DP_DPHY_SYM32_RATE_UPDATE_PENDING', + 'ENUM_DP_DPHY_SYM32_RESET', 'ENUM_DP_DPHY_SYM32_RESET_STATUS', + 'ENUM_DP_DPHY_SYM32_SAT_UPDATE', + 'ENUM_DP_DPHY_SYM32_SAT_UPDATE_PENDING', + 'ENUM_DP_DPHY_SYM32_SCHEDULER_STATUS', + 'ENUM_DP_DPHY_SYM32_STATUS', + 'ENUM_DP_DPHY_SYM32_STREAM_OVR_ENABLE', + 'ENUM_DP_DPHY_SYM32_STREAM_OVR_TYPE', + 'ENUM_DP_DPHY_SYM32_TP_PRBS_SEL', 'ENUM_DP_DPHY_SYM32_TP_SELECT', + 'ENUM_DP_SYM32_ENC_AUDIO_MUTE', + 'ENUM_DP_SYM32_ENC_CONTINUOUS_MODE', + 'ENUM_DP_SYM32_ENC_CRC_VALID', + 'ENUM_DP_SYM32_ENC_DP_COMPONENT_DEPTH', + 'ENUM_DP_SYM32_ENC_ENABLE', + 'ENUM_DP_SYM32_ENC_GSP_DEADLINE_MISSED', + 'ENUM_DP_SYM32_ENC_GSP_ONE_SHOT_TRIGGER_POSITION', + 'ENUM_DP_SYM32_ENC_GSP_PAYLOAD_SIZE', + 'ENUM_DP_SYM32_ENC_GSP_TRIGGER_PENDING', + 'ENUM_DP_SYM32_ENC_MEM_PWR_FORCE_ENUM', + 'ENUM_DP_SYM32_ENC_OVERFLOW_STATUS', 'ENUM_DP_SYM32_ENC_PENDING', + 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING', + 'ENUM_DP_SYM32_ENC_PIXEL_ENCODING_TYPE', + 'ENUM_DP_SYM32_ENC_POWER_STATE_ENUM', 'ENUM_DP_SYM32_ENC_RESET', + 'ENUM_DP_SYM32_ENC_SDP_PRIORITY', + 'ENUM_DP_SYM32_ENC_SOF_REFERENCE', + 'ENUM_DP_SYM32_ENC_VID_STREAM_DEFER', 'ENUM_NUM_SIMD_PER_CU', + 'EVENT_STATE_CHANGE', 'EXOKAY', 'EXPANSION_MODE', + 'EXPANSION_MODE_CONSERVATIVE', 'EXPANSION_MODE_OPTIMAL', + 'EXPANSION_MODE_ZERO', 'EXPORT_ANY_Z', 'EXPORT_GREATER_THAN_Z', + 'EXPORT_LESS_THAN_Z', 'EXPORT_RESERVED', 'FAULT_FAIL', + 'FAULT_ONE', 'FAULT_PASS', 'FAULT_ZERO', 'FC_EYE_SELECTION_ENUM', + 'FC_EYE_SELECTION_LEFT_EYE', 'FC_EYE_SELECTION_RIGHT_EYE', + 'FC_EYE_SELECTION_STEREO_DIS', 'FC_FRAME_CAPTURE_RATE_ENUM', + 'FC_FRAME_CAPTURE_RATE_FULL', 'FC_FRAME_CAPTURE_RATE_HALF', + 'FC_FRAME_CAPTURE_RATE_QUARTER', 'FC_FRAME_CAPTURE_RATE_THIRD', + 'FC_STEREO_EYE_POLARITY_ENUM', 'FC_STEREO_EYE_POLARITY_LEFT', + 'FC_STEREO_EYE_POLARITY_RIGHT', 'FEC_ACTIVE_STATUS', 'FIX_S2_13', + 'FIX_S3_12', 'FLIP_ANY_FRAME', 'FLIP_LEFT_EYE', 'FLIP_RATE', + 'FLIP_RATE_0', 'FLIP_RATE_1', 'FLIP_RATE_2', 'FLIP_RATE_3', + 'FLIP_RATE_4', 'FLIP_RATE_5', 'FLIP_RATE_6', 'FLIP_RATE_7', + 'FLIP_RIGHT_EYE', 'FLUSH_AND_INV_CB_DATA_TS', + 'FLUSH_AND_INV_CB_META', 'FLUSH_AND_INV_CB_PIXEL_DATA', + 'FLUSH_AND_INV_DB_DATA_TS', 'FLUSH_AND_INV_DB_META', + 'FLUSH_CONTROL_FLUSH_NOT_STARTED', 'FLUSH_CONTROL_FLUSH_STARTED', + 'FLUSH_DFSM', 'FLUSH_ES_OUTPUT', 'FLUSH_HS_OUTPUT', 'FLUSH_SX_TS', + 'FMTMEM_DISABLE_MEM_PWR_CTRL', 'FMTMEM_ENABLE_MEM_PWR_CTRL', + 'FMTMEM_FORCE_DEEP_SLEEP_REQUEST', + 'FMTMEM_FORCE_LIGHT_SLEEP_REQUEST', + 'FMTMEM_FORCE_SHUT_DOWN_REQUEST', 'FMTMEM_NO_FORCE_REQUEST', + 'FMTMEM_PWR_DIS_CTRL', 'FMTMEM_PWR_FORCE_CTRL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 'FMT_CLAMP_CNTL_COLOR_FORMAT', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', + 'FMT_CONTROL_PIXEL_ENCODING', + 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', + 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 'FMT_CONTROL_SUBSAMPLING_MODE', + 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', + 'FMT_CONTROL_SUBSAMPLING_ORDER', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', + 'FMT_DEBUG_CNTL_COLOR_SELECT', 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', 'FMT_DYNAMIC_EXP_MODE', + 'FMT_DYNAMIC_EXP_MODE_10to12', 'FMT_DYNAMIC_EXP_MODE_8to12', + 'FMT_FRAME_RANDOM_ENABLE_CONTROL', + 'FMT_FRAME_RANDOM_ENABLE_RESET_EACH_FRAME', + 'FMT_FRAME_RANDOM_ENABLE_RESET_ONCE', 'FMT_POWER_STATE_ENUM', + 'FMT_POWER_STATE_ENUM_DS', 'FMT_POWER_STATE_ENUM_LS', + 'FMT_POWER_STATE_ENUM_ON', 'FMT_POWER_STATE_ENUM_SD', + 'FMT_RGB_RANDOM_ENABLE_CONTROL', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_DISABLE', + 'FMT_RGB_RANDOM_ENABLE_CONTROL_ENABLE', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_1', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_2', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_CONTROL', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_NO_SWAP', + 'FMT_SPATIAL_DITHER_FRAME_COUNTER_BIT_SWAP_RESERVED', + 'FMT_SPATIAL_DITHER_MODE', 'FMT_SPATIAL_DITHER_MODE_0', + 'FMT_SPATIAL_DITHER_MODE_1', 'FMT_SPATIAL_DITHER_MODE_2', + 'FMT_SPATIAL_DITHER_MODE_3', 'FMT_STEREOSYNC_OVERRIDE_CONTROL', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_0', + 'FMT_STEREOSYNC_OVERRIDE_CONTROL_1', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', 'FORCE_00', + 'FORCE_BINNING_ON', 'FORCE_DEEP_SLEEP_REQUEST', 'FORCE_DISABLE', + 'FORCE_DISABLE_CLOCK', 'FORCE_EARLY_Z', 'FORCE_ENABLE', + 'FORCE_FF', 'FORCE_LATE_Z', 'FORCE_LIGHT_SLEEP_REQ', + 'FORCE_LIGHT_SLEEP_REQUEST', 'FORCE_OFF', + 'FORCE_ONE_ROW_FOR_FRAME', 'FORCE_ONE_ROW_FOR_FRAME_0', + 'FORCE_ONE_ROW_FOR_FRAME_1', 'FORCE_OPT_AUTO', + 'FORCE_OPT_DISABLE', 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 'FORCE_OPT_ENABLE_IF_SRC_A_1', 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', 'FORCE_RESERVED', 'FORCE_RE_Z', + 'FORCE_SENT', 'FORCE_SHUT_DOWN_REQUEST', 'FORCE_SUMM_BOTH', + 'FORCE_SUMM_MAXZ', 'FORCE_SUMM_MINZ', 'FORCE_SUMM_OFF', + 'FORCE_THE_CLOCK_DISABLED', 'FORMAT_CROSSBAR', + 'FORMAT_CROSSBAR_B', 'FORMAT_CROSSBAR_G', 'FORMAT_CROSSBAR_R', + 'FRAG_ALWAYS', 'FRAG_EQUAL', 'FRAG_GEQUAL', 'FRAG_GREATER', + 'FRAG_LEQUAL', 'FRAG_LESS', 'FRAG_NEVER', 'FRAG_NOTEQUAL', + 'ForceControl', 'GATCL1RequestType', 'GATCL1_TYPE_BYPASS', + 'GATCL1_TYPE_NORMAL', 'GATCL1_TYPE_SHOOTDOWN', 'GCRPerfSel', + 'GCR_PERF_SEL_ALL_REQ', + 'GCR_PERF_SEL_CLK_FOR_ALL_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_PHY_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CLK_FOR_VIRT_OUTSTANDING_REQ', + 'GCR_PERF_SEL_CPC_ALL_REQ', 'GCR_PERF_SEL_CPC_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL1_RANGE_REQ', + 'GCR_PERF_SEL_CPC_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPC_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPC_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPC_METADATA_REQ', + 'GCR_PERF_SEL_CPC_SQC_DATA_REQ', 'GCR_PERF_SEL_CPC_SQC_INST_REQ', + 'GCR_PERF_SEL_CPC_TCP_REQ', 'GCR_PERF_SEL_CPF_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL1_RANGE_REQ', + 'GCR_PERF_SEL_CPF_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPF_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPF_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPF_METADATA_REQ', + 'GCR_PERF_SEL_CPF_SQC_DATA_REQ', 'GCR_PERF_SEL_CPF_SQC_INST_REQ', + 'GCR_PERF_SEL_CPF_TCP_REQ', 'GCR_PERF_SEL_CPG_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL1_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL1_RANGE_REQ', + 'GCR_PERF_SEL_CPG_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_CPG_GL2_ALL_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_CPG_GL2_RANGE_REQ', 'GCR_PERF_SEL_CPG_METADATA_REQ', + 'GCR_PERF_SEL_CPG_SQC_DATA_REQ', 'GCR_PERF_SEL_CPG_SQC_INST_REQ', + 'GCR_PERF_SEL_CPG_TCP_REQ', 'GCR_PERF_SEL_NONE', + 'GCR_PERF_SEL_PHY_REQ', 'GCR_PERF_SEL_PIO_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL1_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PIO_GL1_RANGE_REQ', + 'GCR_PERF_SEL_PIO_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_PIO_GL2_ALL_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PIO_GL2_RANGE_REQ', 'GCR_PERF_SEL_PIO_METADATA_REQ', + 'GCR_PERF_SEL_PIO_SQC_DATA_REQ', 'GCR_PERF_SEL_PIO_SQC_INST_REQ', + 'GCR_PERF_SEL_PIO_TCP_REQ', + 'GCR_PERF_SEL_PMM_ABIT_FLUSH_INTERRUPT', + 'GCR_PERF_SEL_PMM_ABIT_FLUSH_ONGOING', + 'GCR_PERF_SEL_PMM_ABIT_FORCE_FLUSH', + 'GCR_PERF_SEL_PMM_ABIT_NUM_FLUSH', + 'GCR_PERF_SEL_PMM_ABIT_TIMER_FLUSH', + 'GCR_PERF_SEL_PMM_ALOG_INTERRUPT', + 'GCR_PERF_SEL_PMM_INTERRUPT_READY_TO_SEND', + 'GCR_PERF_SEL_PMM_MAM_FLUSH_REQ', + 'GCR_PERF_SEL_PMM_MAM_FLUSH_RESP', + 'GCR_PERF_SEL_PMM_NUM_INTERRUPT', 'GCR_PERF_SEL_PMM_RLC_CGCG_REQ', + 'GCR_PERF_SEL_PMM_RLC_CGCG_RESP', + 'GCR_PERF_SEL_PMM_STALL_PMM_IH_CREDITS', + 'GCR_PERF_SEL_PM_ALL_REQ', 'GCR_PERF_SEL_PM_GL1_ALL_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PM_GL1_RANGE_REQ', + 'GCR_PERF_SEL_PM_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_PM_GL2_ALL_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_PM_GL2_RANGE_REQ', 'GCR_PERF_SEL_PM_METADATA_REQ', + 'GCR_PERF_SEL_PM_SQC_DATA_REQ', 'GCR_PERF_SEL_PM_SQC_INST_REQ', + 'GCR_PERF_SEL_PM_TCP_REQ', 'GCR_PERF_SEL_RLC_ALL_REQ', + 'GCR_PERF_SEL_RLC_GL1_ALL_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_RLC_GL1_RANGE_REQ', + 'GCR_PERF_SEL_RLC_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_RLC_GL2_ALL_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_RLC_GL2_RANGE_REQ', 'GCR_PERF_SEL_RLC_METADATA_REQ', + 'GCR_PERF_SEL_RLC_SQC_DATA_REQ', 'GCR_PERF_SEL_RLC_SQC_INST_REQ', + 'GCR_PERF_SEL_RLC_TCP_REQ', 'GCR_PERF_SEL_SDMA0_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA0_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA0_METADATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA0_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA0_TCP_REQ', + 'GCR_PERF_SEL_SDMA1_ALL_REQ', 'GCR_PERF_SEL_SDMA1_GL1_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_GL1_TLB_SHOOTDOWN_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_ALL_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_GT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_LT16K_REQ', + 'GCR_PERF_SEL_SDMA1_GL2_RANGE_REQ', + 'GCR_PERF_SEL_SDMA1_METADATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_DATA_REQ', + 'GCR_PERF_SEL_SDMA1_SQC_INST_REQ', 'GCR_PERF_SEL_SDMA1_TCP_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_HEAVY_REQ', + 'GCR_PERF_SEL_TLB_SHOOTDOWN_LIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_FILTERED_RET', + 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', + 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', + 'GCR_PERF_SEL_UTCL2_REQ', 'GCR_PERF_SEL_UTCL2_RET', + 'GCR_PERF_SEL_VIRT_REQ', 'GCUTCL2_PERF_SEL', + 'GCUTCL2_PERF_SEL_EVENT_0', 'GCUTCL2_PERF_SEL_EVENT_1', + 'GCUTCL2_PERF_SEL_EVENT_10', 'GCUTCL2_PERF_SEL_EVENT_11', + 'GCUTCL2_PERF_SEL_EVENT_12', 'GCUTCL2_PERF_SEL_EVENT_13', + 'GCUTCL2_PERF_SEL_EVENT_14', 'GCUTCL2_PERF_SEL_EVENT_15', + 'GCUTCL2_PERF_SEL_EVENT_16', 'GCUTCL2_PERF_SEL_EVENT_17', + 'GCUTCL2_PERF_SEL_EVENT_18', 'GCUTCL2_PERF_SEL_EVENT_19', + 'GCUTCL2_PERF_SEL_EVENT_2', 'GCUTCL2_PERF_SEL_EVENT_20', + 'GCUTCL2_PERF_SEL_EVENT_21', 'GCUTCL2_PERF_SEL_EVENT_22', + 'GCUTCL2_PERF_SEL_EVENT_23', 'GCUTCL2_PERF_SEL_EVENT_24', + 'GCUTCL2_PERF_SEL_EVENT_25', 'GCUTCL2_PERF_SEL_EVENT_26', + 'GCUTCL2_PERF_SEL_EVENT_27', 'GCUTCL2_PERF_SEL_EVENT_28', + 'GCUTCL2_PERF_SEL_EVENT_29', 'GCUTCL2_PERF_SEL_EVENT_3', + 'GCUTCL2_PERF_SEL_EVENT_30', 'GCUTCL2_PERF_SEL_EVENT_31', + 'GCUTCL2_PERF_SEL_EVENT_32', 'GCUTCL2_PERF_SEL_EVENT_33', + 'GCUTCL2_PERF_SEL_EVENT_34', 'GCUTCL2_PERF_SEL_EVENT_35', + 'GCUTCL2_PERF_SEL_EVENT_36', 'GCUTCL2_PERF_SEL_EVENT_4', + 'GCUTCL2_PERF_SEL_EVENT_5', 'GCUTCL2_PERF_SEL_EVENT_6', + 'GCUTCL2_PERF_SEL_EVENT_7', 'GCUTCL2_PERF_SEL_EVENT_8', + 'GCUTCL2_PERF_SEL_EVENT_9', 'GCVML2_PERF_SEL', + 'GCVML2_PERF_SEL_EVENT_0', 'GCVML2_PERF_SEL_EVENT_1', + 'GCVML2_PERF_SEL_EVENT_10', 'GCVML2_PERF_SEL_EVENT_11', + 'GCVML2_PERF_SEL_EVENT_12', 'GCVML2_PERF_SEL_EVENT_13', + 'GCVML2_PERF_SEL_EVENT_14', 'GCVML2_PERF_SEL_EVENT_15', + 'GCVML2_PERF_SEL_EVENT_16', 'GCVML2_PERF_SEL_EVENT_17', + 'GCVML2_PERF_SEL_EVENT_18', 'GCVML2_PERF_SEL_EVENT_19', + 'GCVML2_PERF_SEL_EVENT_2', 'GCVML2_PERF_SEL_EVENT_20', + 'GCVML2_PERF_SEL_EVENT_21', 'GCVML2_PERF_SEL_EVENT_22', + 'GCVML2_PERF_SEL_EVENT_23', 'GCVML2_PERF_SEL_EVENT_24', + 'GCVML2_PERF_SEL_EVENT_25', 'GCVML2_PERF_SEL_EVENT_26', + 'GCVML2_PERF_SEL_EVENT_27', 'GCVML2_PERF_SEL_EVENT_28', + 'GCVML2_PERF_SEL_EVENT_29', 'GCVML2_PERF_SEL_EVENT_3', + 'GCVML2_PERF_SEL_EVENT_30', 'GCVML2_PERF_SEL_EVENT_31', + 'GCVML2_PERF_SEL_EVENT_32', 'GCVML2_PERF_SEL_EVENT_33', + 'GCVML2_PERF_SEL_EVENT_34', 'GCVML2_PERF_SEL_EVENT_35', + 'GCVML2_PERF_SEL_EVENT_36', 'GCVML2_PERF_SEL_EVENT_37', + 'GCVML2_PERF_SEL_EVENT_38', 'GCVML2_PERF_SEL_EVENT_39', + 'GCVML2_PERF_SEL_EVENT_4', 'GCVML2_PERF_SEL_EVENT_40', + 'GCVML2_PERF_SEL_EVENT_41', 'GCVML2_PERF_SEL_EVENT_42', + 'GCVML2_PERF_SEL_EVENT_43', 'GCVML2_PERF_SEL_EVENT_44', + 'GCVML2_PERF_SEL_EVENT_45', 'GCVML2_PERF_SEL_EVENT_46', + 'GCVML2_PERF_SEL_EVENT_47', 'GCVML2_PERF_SEL_EVENT_48', + 'GCVML2_PERF_SEL_EVENT_49', 'GCVML2_PERF_SEL_EVENT_5', + 'GCVML2_PERF_SEL_EVENT_50', 'GCVML2_PERF_SEL_EVENT_51', + 'GCVML2_PERF_SEL_EVENT_52', 'GCVML2_PERF_SEL_EVENT_53', + 'GCVML2_PERF_SEL_EVENT_54', 'GCVML2_PERF_SEL_EVENT_55', + 'GCVML2_PERF_SEL_EVENT_56', 'GCVML2_PERF_SEL_EVENT_57', + 'GCVML2_PERF_SEL_EVENT_58', 'GCVML2_PERF_SEL_EVENT_59', + 'GCVML2_PERF_SEL_EVENT_6', 'GCVML2_PERF_SEL_EVENT_60', + 'GCVML2_PERF_SEL_EVENT_61', 'GCVML2_PERF_SEL_EVENT_62', + 'GCVML2_PERF_SEL_EVENT_63', 'GCVML2_PERF_SEL_EVENT_64', + 'GCVML2_PERF_SEL_EVENT_65', 'GCVML2_PERF_SEL_EVENT_66', + 'GCVML2_PERF_SEL_EVENT_67', 'GCVML2_PERF_SEL_EVENT_68', + 'GCVML2_PERF_SEL_EVENT_69', 'GCVML2_PERF_SEL_EVENT_7', + 'GCVML2_PERF_SEL_EVENT_70', 'GCVML2_PERF_SEL_EVENT_71', + 'GCVML2_PERF_SEL_EVENT_72', 'GCVML2_PERF_SEL_EVENT_73', + 'GCVML2_PERF_SEL_EVENT_74', 'GCVML2_PERF_SEL_EVENT_75', + 'GCVML2_PERF_SEL_EVENT_76', 'GCVML2_PERF_SEL_EVENT_77', + 'GCVML2_PERF_SEL_EVENT_78', 'GCVML2_PERF_SEL_EVENT_79', + 'GCVML2_PERF_SEL_EVENT_8', 'GCVML2_PERF_SEL_EVENT_80', + 'GCVML2_PERF_SEL_EVENT_81', 'GCVML2_PERF_SEL_EVENT_82', + 'GCVML2_PERF_SEL_EVENT_83', 'GCVML2_PERF_SEL_EVENT_84', + 'GCVML2_PERF_SEL_EVENT_85', 'GCVML2_PERF_SEL_EVENT_86', + 'GCVML2_PERF_SEL_EVENT_87', 'GCVML2_PERF_SEL_EVENT_88', + 'GCVML2_PERF_SEL_EVENT_89', 'GCVML2_PERF_SEL_EVENT_9', + 'GCVML2_PERF_SEL_EVENT_90', 'GCVML2_SPM_PERF_SEL', + 'GCVML2_SPM_PERF_SEL_EVENT_0', 'GCVML2_SPM_PERF_SEL_EVENT_1', + 'GCVML2_SPM_PERF_SEL_EVENT_10', 'GCVML2_SPM_PERF_SEL_EVENT_11', + 'GCVML2_SPM_PERF_SEL_EVENT_12', 'GCVML2_SPM_PERF_SEL_EVENT_13', + 'GCVML2_SPM_PERF_SEL_EVENT_14', 'GCVML2_SPM_PERF_SEL_EVENT_15', + 'GCVML2_SPM_PERF_SEL_EVENT_16', 'GCVML2_SPM_PERF_SEL_EVENT_17', + 'GCVML2_SPM_PERF_SEL_EVENT_18', 'GCVML2_SPM_PERF_SEL_EVENT_19', + 'GCVML2_SPM_PERF_SEL_EVENT_2', 'GCVML2_SPM_PERF_SEL_EVENT_20', + 'GCVML2_SPM_PERF_SEL_EVENT_21', 'GCVML2_SPM_PERF_SEL_EVENT_22', + 'GCVML2_SPM_PERF_SEL_EVENT_23', 'GCVML2_SPM_PERF_SEL_EVENT_24', + 'GCVML2_SPM_PERF_SEL_EVENT_25', 'GCVML2_SPM_PERF_SEL_EVENT_26', + 'GCVML2_SPM_PERF_SEL_EVENT_27', 'GCVML2_SPM_PERF_SEL_EVENT_28', + 'GCVML2_SPM_PERF_SEL_EVENT_29', 'GCVML2_SPM_PERF_SEL_EVENT_3', + 'GCVML2_SPM_PERF_SEL_EVENT_30', 'GCVML2_SPM_PERF_SEL_EVENT_31', + 'GCVML2_SPM_PERF_SEL_EVENT_32', 'GCVML2_SPM_PERF_SEL_EVENT_33', + 'GCVML2_SPM_PERF_SEL_EVENT_34', 'GCVML2_SPM_PERF_SEL_EVENT_35', + 'GCVML2_SPM_PERF_SEL_EVENT_36', 'GCVML2_SPM_PERF_SEL_EVENT_37', + 'GCVML2_SPM_PERF_SEL_EVENT_38', 'GCVML2_SPM_PERF_SEL_EVENT_39', + 'GCVML2_SPM_PERF_SEL_EVENT_4', 'GCVML2_SPM_PERF_SEL_EVENT_40', + 'GCVML2_SPM_PERF_SEL_EVENT_41', 'GCVML2_SPM_PERF_SEL_EVENT_42', + 'GCVML2_SPM_PERF_SEL_EVENT_43', 'GCVML2_SPM_PERF_SEL_EVENT_44', + 'GCVML2_SPM_PERF_SEL_EVENT_45', 'GCVML2_SPM_PERF_SEL_EVENT_46', + 'GCVML2_SPM_PERF_SEL_EVENT_47', 'GCVML2_SPM_PERF_SEL_EVENT_48', + 'GCVML2_SPM_PERF_SEL_EVENT_49', 'GCVML2_SPM_PERF_SEL_EVENT_5', + 'GCVML2_SPM_PERF_SEL_EVENT_50', 'GCVML2_SPM_PERF_SEL_EVENT_51', + 'GCVML2_SPM_PERF_SEL_EVENT_52', 'GCVML2_SPM_PERF_SEL_EVENT_53', + 'GCVML2_SPM_PERF_SEL_EVENT_54', 'GCVML2_SPM_PERF_SEL_EVENT_55', + 'GCVML2_SPM_PERF_SEL_EVENT_56', 'GCVML2_SPM_PERF_SEL_EVENT_57', + 'GCVML2_SPM_PERF_SEL_EVENT_58', 'GCVML2_SPM_PERF_SEL_EVENT_59', + 'GCVML2_SPM_PERF_SEL_EVENT_6', 'GCVML2_SPM_PERF_SEL_EVENT_60', + 'GCVML2_SPM_PERF_SEL_EVENT_61', 'GCVML2_SPM_PERF_SEL_EVENT_62', + 'GCVML2_SPM_PERF_SEL_EVENT_63', 'GCVML2_SPM_PERF_SEL_EVENT_64', + 'GCVML2_SPM_PERF_SEL_EVENT_65', 'GCVML2_SPM_PERF_SEL_EVENT_66', + 'GCVML2_SPM_PERF_SEL_EVENT_67', 'GCVML2_SPM_PERF_SEL_EVENT_68', + 'GCVML2_SPM_PERF_SEL_EVENT_69', 'GCVML2_SPM_PERF_SEL_EVENT_7', + 'GCVML2_SPM_PERF_SEL_EVENT_70', 'GCVML2_SPM_PERF_SEL_EVENT_71', + 'GCVML2_SPM_PERF_SEL_EVENT_72', 'GCVML2_SPM_PERF_SEL_EVENT_73', + 'GCVML2_SPM_PERF_SEL_EVENT_74', 'GCVML2_SPM_PERF_SEL_EVENT_75', + 'GCVML2_SPM_PERF_SEL_EVENT_76', 'GCVML2_SPM_PERF_SEL_EVENT_77', + 'GCVML2_SPM_PERF_SEL_EVENT_78', 'GCVML2_SPM_PERF_SEL_EVENT_79', + 'GCVML2_SPM_PERF_SEL_EVENT_8', 'GCVML2_SPM_PERF_SEL_EVENT_80', + 'GCVML2_SPM_PERF_SEL_EVENT_81', 'GCVML2_SPM_PERF_SEL_EVENT_82', + 'GCVML2_SPM_PERF_SEL_EVENT_83', 'GCVML2_SPM_PERF_SEL_EVENT_84', + 'GCVML2_SPM_PERF_SEL_EVENT_85', 'GCVML2_SPM_PERF_SEL_EVENT_86', + 'GCVML2_SPM_PERF_SEL_EVENT_87', 'GCVML2_SPM_PERF_SEL_EVENT_88', + 'GCVML2_SPM_PERF_SEL_EVENT_89', 'GCVML2_SPM_PERF_SEL_EVENT_9', + 'GCVML2_SPM_PERF_SEL_EVENT_90', 'GC_EA_CPWD_PERFCOUNT_SEL', + 'GC_EA_CPWD_PERF_SEL_ALWAYS_COUNT', + 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_COMPLETED', + 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT', + 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED', + 'GC_EA_CPWD_PERF_SEL_MAM_AFLUSH_ONGOING', + 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT', + 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_HIT_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_FA_LRU_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_ARAM_REQ_VLD', + 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT', + 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_HIT_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_FA_LRU_EVICT', + 'GC_EA_CPWD_PERF_SEL_MAM_DBIT_REQ_VLD', + 'GC_EA_CPWD_PERF_SEL_MAM_DQRY_ONGOING', + 'GC_EA_CPWD_PERF_SEL_MAM_FLUSH_REQ', + 'GC_EA_CPWD_PERF_SEL_MAM_FLUSH_RESP', + 'GC_EA_CPWD_PERF_SEL_MAM_NUM_DQRY', 'GC_EA_CPWD_PERF_SEL_PRB_REQ', + 'GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_CPWD_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_RDRAM_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_RDRAM_NUM_BANKS_VLD', + 'GC_EA_CPWD_PERF_SEL_RDRAM_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_RDRAM_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_CPWD_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR', + 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_RGMI_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_RGMI_NUM_BANKS_VLD', + 'GC_EA_CPWD_PERF_SEL_RGMI_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_RGMI_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RIO_GRP0_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RIO_GRP1_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RIO_GRP2_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RIO_GRP3_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_RIO_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_RIO_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_RIO_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_RRET_VLD', 'GC_EA_CPWD_PERF_SEL_SARB_BUSY', + 'GC_EA_CPWD_PERF_SEL_SARB_COHERENT_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_REQ_PER_VC', + 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_RW_TURN_AROUND', + 'GC_EA_CPWD_PERF_SEL_SARB_DRAM_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_SARB_GMI_REQ_PER_VC', + 'GC_EA_CPWD_PERF_SEL_SARB_GMI_RW_TURN_AROUND', + 'GC_EA_CPWD_PERF_SEL_SARB_GMI_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_SARB_IDLE', + 'GC_EA_CPWD_PERF_SEL_SARB_IO_REQ_PER_VC', + 'GC_EA_CPWD_PERF_SEL_SARB_IO_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_SARB_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_SARB_REQ_PER_VC', + 'GC_EA_CPWD_PERF_SEL_SARB_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_SARB_STALLED', + 'GC_EA_CPWD_PERF_SEL_SARB_STARVING', + 'GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_CPWD_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_WDRAM_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_WDRAM_NUM_BANKS_VLD', + 'GC_EA_CPWD_PERF_SEL_WDRAM_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WDRAM_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_CPWD_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_WGMI_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_WGMI_NUM_BANKS_VLD', + 'GC_EA_CPWD_PERF_SEL_WGMI_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WGMI_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WIO_GRP0_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WIO_GRP1_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WIO_GRP2_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WIO_GRP3_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END0', + 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_END1', + 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START0', + 'GC_EA_CPWD_PERF_SEL_WIO_LATENCY_START1', + 'GC_EA_CPWD_PERF_SEL_WIO_REQ_PER_CLIGRP', + 'GC_EA_CPWD_PERF_SEL_WIO_SIZE_REQ', + 'GC_EA_CPWD_PERF_SEL_WRET_VLD', 'GC_EA_SE_PERFCOUNT_SEL', + 'GC_EA_SE_PERF_SEL_ALWAYS_COUNT', + 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_COMPLETED', + 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT', + 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_INTERRUPT_STALLED', + 'GC_EA_SE_PERF_SEL_MAM_AFLUSH_ONGOING', + 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT', + 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_HIT_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_ARAM_FA_LRU_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_ARAM_REQ_VLD', + 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT', + 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_HIT_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_DBIT_FA_LRU_EVICT', + 'GC_EA_SE_PERF_SEL_MAM_DBIT_REQ_VLD', + 'GC_EA_SE_PERF_SEL_MAM_DQRY_ONGOING', + 'GC_EA_SE_PERF_SEL_MAM_FLUSH_REQ', + 'GC_EA_SE_PERF_SEL_MAM_FLUSH_RESP', + 'GC_EA_SE_PERF_SEL_MAM_NUM_DQRY', 'GC_EA_SE_PERF_SEL_PRB_REQ', + 'GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_SE_PERF_SEL_RDRAM_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_RDRAM_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_RDRAM_NUM_BANKS_VLD', + 'GC_EA_SE_PERF_SEL_RDRAM_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_RDRAM_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_SE_PERF_SEL_RGMI_CHAINED_REQ_PER_CLIGR', + 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_RGMI_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_RGMI_NUM_BANKS_VLD', + 'GC_EA_SE_PERF_SEL_RGMI_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_RGMI_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RIO_GRP0_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RIO_GRP1_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RIO_GRP2_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RIO_GRP3_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_RIO_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_RIO_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_RIO_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_RIO_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_RIO_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_RIO_SIZE_REQ', 'GC_EA_SE_PERF_SEL_RRET_VLD', + 'GC_EA_SE_PERF_SEL_SARB_BUSY', + 'GC_EA_SE_PERF_SEL_SARB_COHERENT_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_SARB_DRAM_REQ_PER_VC', + 'GC_EA_SE_PERF_SEL_SARB_DRAM_RW_TURN_AROUND', + 'GC_EA_SE_PERF_SEL_SARB_DRAM_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_SARB_GMI_REQ_PER_VC', + 'GC_EA_SE_PERF_SEL_SARB_GMI_RW_TURN_AROUND', + 'GC_EA_SE_PERF_SEL_SARB_GMI_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_SARB_IDLE', + 'GC_EA_SE_PERF_SEL_SARB_IO_REQ_PER_VC', + 'GC_EA_SE_PERF_SEL_SARB_IO_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_SARB_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_SARB_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_SARB_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_SARB_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_SARB_REQ_PER_VC', + 'GC_EA_SE_PERF_SEL_SARB_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_SARB_STALLED', + 'GC_EA_SE_PERF_SEL_SARB_STARVING', + 'GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_SE_PERF_SEL_WDRAM_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_WDRAM_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_WDRAM_NUM_BANKS_VLD', + 'GC_EA_SE_PERF_SEL_WDRAM_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WDRAM_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_BURSTS_LENGTH', + 'GC_EA_SE_PERF_SEL_WGMI_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_WGMI_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_WGMI_NUM_BANKS_VLD', + 'GC_EA_SE_PERF_SEL_WGMI_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WGMI_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WIO_CHAINED_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WIO_GRP0_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WIO_GRP1_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WIO_GRP2_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WIO_GRP3_SIZE_REQ', + 'GC_EA_SE_PERF_SEL_WIO_LATENCY_END0', + 'GC_EA_SE_PERF_SEL_WIO_LATENCY_END1', + 'GC_EA_SE_PERF_SEL_WIO_LATENCY_START0', + 'GC_EA_SE_PERF_SEL_WIO_LATENCY_START1', + 'GC_EA_SE_PERF_SEL_WIO_REQ_PER_CLIGRP', + 'GC_EA_SE_PERF_SEL_WIO_SIZE_REQ', 'GC_EA_SE_PERF_SEL_WRET_VLD', + 'GE1_PERFCOUNT_SELECT', 'GE2_DIST_PERFCOUNT_SELECT', + 'GE2_SE_PERFCOUNT_SELECT', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', + 'GENERIC_STEREOSYNC_SEL', 'GENERIC_STEREOSYNC_SEL_D1', + 'GENERIC_STEREOSYNC_SEL_D2', 'GENERIC_STEREOSYNC_SEL_D3', + 'GENERIC_STEREOSYNC_SEL_D4', 'GENERIC_STEREOSYNC_SEL_RESERVED', + 'GL0V_CACHE_POLICIES', 'GL0V_CACHE_POLICY_HIT_EVICT', + 'GL0V_CACHE_POLICY_HIT_LRU', 'GL0V_CACHE_POLICY_MISS_EVICT', + 'GL0V_CACHE_POLICY_MISS_INVAL', 'GL0V_CACHE_POLICY_MISS_LRU', + 'GL1A_PERF_SEL', 'GL1A_PERF_SEL_ARB_REQUESTS', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C0', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C1', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C2', + 'GL1A_PERF_SEL_BURST_COUNT_GL1C3', 'GL1A_PERF_SEL_BUSY', + 'GL1A_PERF_SEL_CYCLE', 'GL1A_PERF_SEL_REQUEST_GL1C0', + 'GL1A_PERF_SEL_REQUEST_GL1C1', 'GL1A_PERF_SEL_REQUEST_GL1C2', + 'GL1A_PERF_SEL_REQUEST_GL1C3', 'GL1A_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'GL1A_PERF_SEL_STALL_GL1C0', 'GL1A_PERF_SEL_STALL_GL1C1', + 'GL1A_PERF_SEL_STALL_GL1C2', 'GL1A_PERF_SEL_STALL_GL1C3', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C0', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C1', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C2', + 'GL1A_PERF_SEL_STALL_RET_CONFLICT_GL1C3', + 'GL1A_PERF_SEL_WDS_32B_GL1C0', 'GL1A_PERF_SEL_WDS_32B_GL1C1', + 'GL1A_PERF_SEL_WDS_32B_GL1C2', 'GL1A_PERF_SEL_WDS_32B_GL1C3', + 'GL1C_PERF_SEL', 'GL1C_PERF_SEL_ARB_RET_LEVEL', + 'GL1C_PERF_SEL_BUSY', 'GL1C_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 'GL1C_PERF_SEL_CYCLE', 'GL1C_PERF_SEL_GL2_REQ_READ_LATENCY', + 'GL1C_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'GL1C_PERF_SEL_REQ', + 'GL1C_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'GL1C_PERF_SEL_REQ_ATOMIC_WITH_RET', 'GL1C_PERF_SEL_REQ_CLIENT0', + 'GL1C_PERF_SEL_REQ_CLIENT1', 'GL1C_PERF_SEL_REQ_CLIENT10', + 'GL1C_PERF_SEL_REQ_CLIENT11', 'GL1C_PERF_SEL_REQ_CLIENT12', + 'GL1C_PERF_SEL_REQ_CLIENT13', 'GL1C_PERF_SEL_REQ_CLIENT14', + 'GL1C_PERF_SEL_REQ_CLIENT15', 'GL1C_PERF_SEL_REQ_CLIENT16', + 'GL1C_PERF_SEL_REQ_CLIENT17', 'GL1C_PERF_SEL_REQ_CLIENT18', + 'GL1C_PERF_SEL_REQ_CLIENT19', 'GL1C_PERF_SEL_REQ_CLIENT2', + 'GL1C_PERF_SEL_REQ_CLIENT20', 'GL1C_PERF_SEL_REQ_CLIENT21', + 'GL1C_PERF_SEL_REQ_CLIENT22', 'GL1C_PERF_SEL_REQ_CLIENT23', + 'GL1C_PERF_SEL_REQ_CLIENT24', 'GL1C_PERF_SEL_REQ_CLIENT25', + 'GL1C_PERF_SEL_REQ_CLIENT26', 'GL1C_PERF_SEL_REQ_CLIENT27', + 'GL1C_PERF_SEL_REQ_CLIENT3', 'GL1C_PERF_SEL_REQ_CLIENT4', + 'GL1C_PERF_SEL_REQ_CLIENT5', 'GL1C_PERF_SEL_REQ_CLIENT6', + 'GL1C_PERF_SEL_REQ_CLIENT7', 'GL1C_PERF_SEL_REQ_CLIENT8', + 'GL1C_PERF_SEL_REQ_CLIENT9', 'GL1C_PERF_SEL_REQ_NOP_ACK', + 'GL1C_PERF_SEL_REQ_NOP_RTN0', 'GL1C_PERF_SEL_REQ_READ', + 'GL1C_PERF_SEL_REQ_READ_128B', 'GL1C_PERF_SEL_REQ_READ_32B', + 'GL1C_PERF_SEL_REQ_READ_64B', 'GL1C_PERF_SEL_REQ_WRITE', + 'GL1C_PERF_SEL_REQ_WRITE_32B', 'GL1C_PERF_SEL_REQ_WRITE_64B', + 'GL1C_PERF_SEL_STALL_BUFFER_FULL', 'GL1C_PERF_SEL_STALL_GL2_GL1', + 'GL1C_PERF_SEL_STALL_VM', 'GL1C_PERF_SEL_STARVE', + 'GL1C_PERF_SEL_UTCL0_GPA3_REQUEST', + 'GL1C_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 'GL1C_PERF_SEL_UTCL0_LFIFO_FULL', + 'GL1C_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 'GL1C_PERF_SEL_UTCL0_PERMISSION_MISS', + 'GL1C_PERF_SEL_UTCL0_REQUEST', + 'GL1C_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 'GL1C_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 'GL1C_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 'GL1C_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 'GL1C_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 'GL1C_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'GL1C_PERF_SEL_UTCL0_TRANSLATION_HIT', + 'GL1C_PERF_SEL_UTCL0_TRANSLATION_MISS', + 'GL1C_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 'GL1C_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', 'GL1XA_PERF_SEL', + 'GL1XA_PERF_SEL_ARB_REQUESTS', + 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC0', + 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC1', + 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC2', + 'GL1XA_PERF_SEL_BURST_COUNT_GL1XC3', 'GL1XA_PERF_SEL_BUSY', + 'GL1XA_PERF_SEL_CYCLE', 'GL1XA_PERF_SEL_REQUEST_GL1XC0', + 'GL1XA_PERF_SEL_REQUEST_GL1XC1', 'GL1XA_PERF_SEL_REQUEST_GL1XC2', + 'GL1XA_PERF_SEL_REQUEST_GL1XC3', + 'GL1XA_PERF_SEL_REQ_INFLIGHT_LEVEL', + 'GL1XA_PERF_SEL_STALL_GL1XC0', 'GL1XA_PERF_SEL_STALL_GL1XC1', + 'GL1XA_PERF_SEL_STALL_GL1XC2', 'GL1XA_PERF_SEL_STALL_GL1XC3', + 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC0', + 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC1', + 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC2', + 'GL1XA_PERF_SEL_STALL_RET_CONFLICT_GL1XC3', + 'GL1XA_PERF_SEL_WDS_32B_GL1XC0', 'GL1XA_PERF_SEL_WDS_32B_GL1XC1', + 'GL1XA_PERF_SEL_WDS_32B_GL1XC2', 'GL1XA_PERF_SEL_WDS_32B_GL1XC3', + 'GL1XC_PERF_SEL', 'GL1XC_PERF_SEL_ARB_RET_LEVEL', + 'GL1XC_PERF_SEL_BUSY', 'GL1XC_PERF_SEL_CLIENT_UTCL0_INFLIGHT', + 'GL1XC_PERF_SEL_CYCLE', 'GL1XC_PERF_SEL_GL2_REQ_READ_LATENCY', + 'GL1XC_PERF_SEL_GL2_REQ_WRITE_LATENCY', 'GL1XC_PERF_SEL_REQ', + 'GL1XC_PERF_SEL_REQ_ATOMIC_WITHOUT_RET', + 'GL1XC_PERF_SEL_REQ_ATOMIC_WITH_RET', + 'GL1XC_PERF_SEL_REQ_CLIENT0', 'GL1XC_PERF_SEL_REQ_CLIENT1', + 'GL1XC_PERF_SEL_REQ_CLIENT10', 'GL1XC_PERF_SEL_REQ_CLIENT11', + 'GL1XC_PERF_SEL_REQ_CLIENT12', 'GL1XC_PERF_SEL_REQ_CLIENT13', + 'GL1XC_PERF_SEL_REQ_CLIENT14', 'GL1XC_PERF_SEL_REQ_CLIENT15', + 'GL1XC_PERF_SEL_REQ_CLIENT16', 'GL1XC_PERF_SEL_REQ_CLIENT17', + 'GL1XC_PERF_SEL_REQ_CLIENT18', 'GL1XC_PERF_SEL_REQ_CLIENT19', + 'GL1XC_PERF_SEL_REQ_CLIENT2', 'GL1XC_PERF_SEL_REQ_CLIENT20', + 'GL1XC_PERF_SEL_REQ_CLIENT21', 'GL1XC_PERF_SEL_REQ_CLIENT22', + 'GL1XC_PERF_SEL_REQ_CLIENT23', 'GL1XC_PERF_SEL_REQ_CLIENT24', + 'GL1XC_PERF_SEL_REQ_CLIENT25', 'GL1XC_PERF_SEL_REQ_CLIENT26', + 'GL1XC_PERF_SEL_REQ_CLIENT27', 'GL1XC_PERF_SEL_REQ_CLIENT3', + 'GL1XC_PERF_SEL_REQ_CLIENT4', 'GL1XC_PERF_SEL_REQ_CLIENT5', + 'GL1XC_PERF_SEL_REQ_CLIENT6', 'GL1XC_PERF_SEL_REQ_CLIENT7', + 'GL1XC_PERF_SEL_REQ_CLIENT8', 'GL1XC_PERF_SEL_REQ_CLIENT9', + 'GL1XC_PERF_SEL_REQ_NOP_ACK', 'GL1XC_PERF_SEL_REQ_NOP_RTN0', + 'GL1XC_PERF_SEL_REQ_READ', 'GL1XC_PERF_SEL_REQ_READ_128B', + 'GL1XC_PERF_SEL_REQ_READ_32B', 'GL1XC_PERF_SEL_REQ_READ_64B', + 'GL1XC_PERF_SEL_REQ_WRITE', 'GL1XC_PERF_SEL_REQ_WRITE_32B', + 'GL1XC_PERF_SEL_REQ_WRITE_64B', + 'GL1XC_PERF_SEL_STALL_BUFFER_FULL', + 'GL1XC_PERF_SEL_STALL_GL2_GL1', 'GL1XC_PERF_SEL_STALL_VM', + 'GL1XC_PERF_SEL_STARVE', 'GL1XC_PERF_SEL_UTCL0_GPA3_REQUEST', + 'GL1XC_PERF_SEL_UTCL0_INTERNAL_RETRY_REQ', + 'GL1XC_PERF_SEL_UTCL0_LFIFO_FULL', + 'GL1XC_PERF_SEL_UTCL0_MISS_UNDER_MISS', + 'GL1XC_PERF_SEL_UTCL0_PERMISSION_MISS', + 'GL1XC_PERF_SEL_UTCL0_REQUEST', + 'GL1XC_PERF_SEL_UTCL0_STALL_INFLIGHT_MAX', + 'GL1XC_PERF_SEL_UTCL0_STALL_LFIFO_NOT_RES', + 'GL1XC_PERF_SEL_UTCL0_STALL_LRU_INFLIGHT', + 'GL1XC_PERF_SEL_UTCL0_STALL_MISSFIFO_FULL', + 'GL1XC_PERF_SEL_UTCL0_STALL_MULTI_MISS', + 'GL1XC_PERF_SEL_UTCL0_STALL_UTCL1_REQ_OUT_OF_CREDITS', + 'GL1XC_PERF_SEL_UTCL0_TRANSLATION_HIT', + 'GL1XC_PERF_SEL_UTCL0_TRANSLATION_MISS', + 'GL1XC_PERF_SEL_UTCL0_UTCL1_INFLIGHT', + 'GL1XC_PERF_SEL_UTCL0_UTCL1_PERM_FAULT', + 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_NO_RETRY_FAULT', + 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_PRT_FAULT', + 'GL1XC_PERF_SEL_UTCL0_UTCL1_XNACK_RETRY_FAULT', + 'GL1_CACHE_POLICIES', 'GL1_CACHE_POLICY_HIT_EVICT', + 'GL1_CACHE_POLICY_HIT_LRU', 'GL1_CACHE_POLICY_MISS_EVICT', + 'GL1_CACHE_POLICY_MISS_LRU', 'GL1_CACHE_STORE_POLICIES', + 'GL1_CACHE_STORE_POLICY_BYPASS', 'GL2A_PERF_SEL', + 'GL2A_PERF_SEL_BUSY', 'GL2A_PERF_SEL_CYCLE', 'GL2A_PERF_SEL_NONE', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT0', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT1', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT10', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT11', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT12', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT13', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT14', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT15', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT2', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT3', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT4', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT5', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT6', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT7', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT8', + 'GL2A_PERF_SEL_REQ_BURST_CLIENT9', + 'GL2A_PERF_SEL_REQ_BURST_GL2C0', 'GL2A_PERF_SEL_REQ_BURST_GL2C1', + 'GL2A_PERF_SEL_REQ_BURST_GL2C2', 'GL2A_PERF_SEL_REQ_BURST_GL2C3', + 'GL2A_PERF_SEL_REQ_BURST_GL2C4', 'GL2A_PERF_SEL_REQ_BURST_GL2C5', + 'GL2A_PERF_SEL_REQ_BURST_GL2C6', 'GL2A_PERF_SEL_REQ_BURST_GL2C7', + 'GL2A_PERF_SEL_REQ_GL2C0', 'GL2A_PERF_SEL_REQ_GL2C1', + 'GL2A_PERF_SEL_REQ_GL2C2', 'GL2A_PERF_SEL_REQ_GL2C3', + 'GL2A_PERF_SEL_REQ_GL2C4', 'GL2A_PERF_SEL_REQ_GL2C5', + 'GL2A_PERF_SEL_REQ_GL2C6', 'GL2A_PERF_SEL_REQ_GL2C7', + 'GL2A_PERF_SEL_REQ_STALL_GL2C0', 'GL2A_PERF_SEL_REQ_STALL_GL2C1', + 'GL2A_PERF_SEL_REQ_STALL_GL2C2', 'GL2A_PERF_SEL_REQ_STALL_GL2C3', + 'GL2A_PERF_SEL_REQ_STALL_GL2C4', 'GL2A_PERF_SEL_REQ_STALL_GL2C5', + 'GL2A_PERF_SEL_REQ_STALL_GL2C6', 'GL2A_PERF_SEL_REQ_STALL_GL2C7', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT0', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT1', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT10', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT11', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT12', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT13', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT14', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT15', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT2', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT3', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT4', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT5', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT6', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT7', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT8', + 'GL2A_PERF_SEL_RTN_ARB_COLLISION_CLIENT9', + 'GL2A_PERF_SEL_RTN_CLIENT0', 'GL2A_PERF_SEL_RTN_CLIENT1', + 'GL2A_PERF_SEL_RTN_CLIENT10', 'GL2A_PERF_SEL_RTN_CLIENT11', + 'GL2A_PERF_SEL_RTN_CLIENT12', 'GL2A_PERF_SEL_RTN_CLIENT13', + 'GL2A_PERF_SEL_RTN_CLIENT14', 'GL2A_PERF_SEL_RTN_CLIENT15', + 'GL2A_PERF_SEL_RTN_CLIENT2', 'GL2A_PERF_SEL_RTN_CLIENT3', + 'GL2A_PERF_SEL_RTN_CLIENT4', 'GL2A_PERF_SEL_RTN_CLIENT5', + 'GL2A_PERF_SEL_RTN_CLIENT6', 'GL2A_PERF_SEL_RTN_CLIENT7', + 'GL2A_PERF_SEL_RTN_CLIENT8', 'GL2A_PERF_SEL_RTN_CLIENT9', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT0', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT1', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT10', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT11', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT12', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT13', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT14', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT15', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT2', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT3', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT4', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT5', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT6', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT7', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT8', + 'GL2A_PERF_SEL_RTN_CREDIT_STALL_CLIENT9', + 'GL2A_PERF_SEL_RTN_STALL_GL2C0', 'GL2A_PERF_SEL_RTN_STALL_GL2C1', + 'GL2A_PERF_SEL_RTN_STALL_GL2C2', 'GL2A_PERF_SEL_RTN_STALL_GL2C3', + 'GL2A_PERF_SEL_RTN_STALL_GL2C4', 'GL2A_PERF_SEL_RTN_STALL_GL2C5', + 'GL2A_PERF_SEL_RTN_STALL_GL2C6', 'GL2A_PERF_SEL_RTN_STALL_GL2C7', + 'GL2C_PERF_SEL', 'GL2C_PERF_SEL_ALL_GCR_INV_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_INV_VOL_EVICT', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_OR_INV_VOL_CYCLE', + 'GL2C_PERF_SEL_ALL_GCR_WB_WRITEBACK', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 'GL2C_PERF_SEL_ALL_TC_OP_WB_OR_INV_VOL_START', + 'GL2C_PERF_SEL_ATOMIC', 'GL2C_PERF_SEL_BUBBLE', + 'GL2C_PERF_SEL_BUSY', 'GL2C_PERF_SEL_BYPASS_REQ', + 'GL2C_PERF_SEL_CLIENT0_REQ', 'GL2C_PERF_SEL_CLIENT10_REQ', + 'GL2C_PERF_SEL_CLIENT11_REQ', 'GL2C_PERF_SEL_CLIENT12_REQ', + 'GL2C_PERF_SEL_CLIENT13_REQ', 'GL2C_PERF_SEL_CLIENT14_REQ', + 'GL2C_PERF_SEL_CLIENT15_REQ', 'GL2C_PERF_SEL_CLIENT1_REQ', + 'GL2C_PERF_SEL_CLIENT2_REQ', 'GL2C_PERF_SEL_CLIENT3_REQ', + 'GL2C_PERF_SEL_CLIENT4_REQ', 'GL2C_PERF_SEL_CLIENT5_REQ', + 'GL2C_PERF_SEL_CLIENT6_REQ', 'GL2C_PERF_SEL_CLIENT7_REQ', + 'GL2C_PERF_SEL_CLIENT8_REQ', 'GL2C_PERF_SEL_CLIENT9_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_0_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_128_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_32_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_64_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_96_REQ', + 'GL2C_PERF_SEL_COMPRESSED_READ_REQ', 'GL2C_PERF_SEL_CYCLE', + 'GL2C_PERF_SEL_C_RO_S_REQ', 'GL2C_PERF_SEL_C_RO_US_REQ', + 'GL2C_PERF_SEL_C_RW_S_REQ', 'GL2C_PERF_SEL_C_RW_US_REQ', + 'GL2C_PERF_SEL_DEWRITE_ALLOCATE_HIT', 'GL2C_PERF_SEL_EA_ATOMIC', + 'GL2C_PERF_SEL_EA_ATOMIC_LEVEL', 'GL2C_PERF_SEL_EA_OUTSTANDING', + 'GL2C_PERF_SEL_EA_RDREQ_128B', 'GL2C_PERF_SEL_EA_RDREQ_32B', + 'GL2C_PERF_SEL_EA_RDREQ_64B', 'GL2C_PERF_SEL_EA_RDREQ_96B', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM', 'GL2C_PERF_SEL_EA_RDREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_RDREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_RDREQ_SNOOP', 'GL2C_PERF_SEL_EA_RDREQ_SPLIT', + 'GL2C_PERF_SEL_EA_RDRET_NACK', + 'GL2C_PERF_SEL_EA_RD_COMPRESSED_32B', + 'GL2C_PERF_SEL_EA_RD_UNCACHED_32B', 'GL2C_PERF_SEL_EA_WRREQ_64B', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM', 'GL2C_PERF_SEL_EA_WRREQ_DRAM_32B', + 'GL2C_PERF_SEL_EA_WRREQ_DRAM_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_GMI_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_IO_CREDIT_STALL', + 'GL2C_PERF_SEL_EA_WRREQ_SNOOP', 'GL2C_PERF_SEL_EA_WRRET_NACK', + 'GL2C_PERF_SEL_EA_WR_UNCACHED_32B', 'GL2C_PERF_SEL_EVICT', + 'GL2C_PERF_SEL_FULLY_WRITTEN_HIT', 'GL2C_PERF_SEL_FULL_HIT', + 'GL2C_PERF_SEL_GARLIC_READ', 'GL2C_PERF_SEL_GARLIC_WRITE', + 'GL2C_PERF_SEL_GCR_ALL', 'GL2C_PERF_SEL_GCR_DISCARD', + 'GL2C_PERF_SEL_GCR_GL2_INV_ALL', + 'GL2C_PERF_SEL_GCR_GL2_INV_RANGE', 'GL2C_PERF_SEL_GCR_GL2_WB_ALL', + 'GL2C_PERF_SEL_GCR_GL2_WB_INV_RANGE', + 'GL2C_PERF_SEL_GCR_GL2_WB_RANGE', 'GL2C_PERF_SEL_GCR_INV', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_EVICT', + 'GL2C_PERF_SEL_GCR_INVL2_VOL_START', 'GL2C_PERF_SEL_GCR_RANGE', + 'GL2C_PERF_SEL_GCR_UNSHARED', 'GL2C_PERF_SEL_GCR_VOL', + 'GL2C_PERF_SEL_GCR_WB', 'GL2C_PERF_SEL_GCR_WBINVL2_CYCLE', + 'GL2C_PERF_SEL_GCR_WBINVL2_EVICT', + 'GL2C_PERF_SEL_GCR_WBINVL2_START', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_CYCLE', + 'GL2C_PERF_SEL_GCR_WBL2_VOL_START', 'GL2C_PERF_SEL_GL2A_LEVEL', + 'GL2C_PERF_SEL_HIGH_PRIORITY_REQ', 'GL2C_PERF_SEL_HIT', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT0', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT1', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT10', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT11', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT12', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT13', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT14', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT15', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT16', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT17', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT18', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT19', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT2', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT3', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT4', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT5', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT6', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT7', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT8', + 'GL2C_PERF_SEL_HIT_PASS_MISS_IN_CLIENT9', 'GL2C_PERF_SEL_IB_REQ', + 'GL2C_PERF_SEL_IB_STALL', 'GL2C_PERF_SEL_IB_TAG_STALL', + 'GL2C_PERF_SEL_IO_READ', 'GL2C_PERF_SEL_IO_WRITE', + 'GL2C_PERF_SEL_LATENCY_FIFO_FULL', 'GL2C_PERF_SEL_LRU_REQ', + 'GL2C_PERF_SEL_MC_RDREQ', 'GL2C_PERF_SEL_MC_RDREQ_LEVEL', + 'GL2C_PERF_SEL_MC_WRREQ', 'GL2C_PERF_SEL_MC_WRREQ_LEVEL', + 'GL2C_PERF_SEL_MC_WRREQ_STALL', 'GL2C_PERF_SEL_METADATA_READ_REQ', + 'GL2C_PERF_SEL_MISS', 'GL2C_PERF_SEL_NOA_REQ', + 'GL2C_PERF_SEL_NONE', 'GL2C_PERF_SEL_NOP_ACK', + 'GL2C_PERF_SEL_NOP_RTN0', 'GL2C_PERF_SEL_NORMAL_EVICT', + 'GL2C_PERF_SEL_NORMAL_WRITEBACK', 'GL2C_PERF_SEL_ONION_READ', + 'GL2C_PERF_SEL_ONION_WRITE', 'GL2C_PERF_SEL_PARTIAL_32B_HIT', + 'GL2C_PERF_SEL_PARTIAL_64B_HIT', 'GL2C_PERF_SEL_PARTIAL_96B_HIT', + 'GL2C_PERF_SEL_READ', 'GL2C_PERF_SEL_READ_128_REQ', + 'GL2C_PERF_SEL_READ_32_REQ', 'GL2C_PERF_SEL_READ_64_REQ', + 'GL2C_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 'GL2C_PERF_SEL_READ_RETURN_TIMEOUT', 'GL2C_PERF_SEL_REQ', + 'GL2C_PERF_SEL_REQ_TO_MISS_QUEUE', 'GL2C_PERF_SEL_RETURN_ACK', + 'GL2C_PERF_SEL_RETURN_DATA', 'GL2C_PERF_SEL_SHARED_REQ', + 'GL2C_PERF_SEL_SRC_FIFO_FULL', 'GL2C_PERF_SEL_STREAM_REQ', + 'GL2C_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 'GL2C_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 'GL2C_PERF_SEL_TAG_READ_DST_STALL', 'GL2C_PERF_SEL_TAG_STALL', + 'GL2C_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 'GL2C_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', 'GL2C_PERF_SEL_UC_REQ', + 'GL2C_PERF_SEL_UNCACHED_WRITE', 'GL2C_PERF_SEL_VOL_REQ', + 'GL2C_PERF_SEL_WRITE', 'GL2C_PERF_SEL_WRITEBACK', + 'GL2C_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 'GL2C_PERF_SEL_WRITE_32_REQ', 'GL2C_PERF_SEL_WRITE_64_REQ', + 'GL2_CACHE_POLICIES', 'GL2_CACHE_POLICY_BYPASS', + 'GL2_CACHE_POLICY_LRU', 'GL2_CACHE_POLICY_NOA', + 'GL2_CACHE_POLICY_STREAM', 'GL2_NACKS', 'GL2_NACK_DATA_ERROR', + 'GL2_NACK_NO_FAULT', 'GL2_NACK_PAGE_FAULT', + 'GL2_NACK_PROTECTION_FAULT', 'GL2_OP', 'GL2_OP_ATOMIC_ADD_32', + 'GL2_OP_ATOMIC_ADD_64', 'GL2_OP_ATOMIC_ADD_RTN_32', + 'GL2_OP_ATOMIC_ADD_RTN_64', 'GL2_OP_ATOMIC_AND_32', + 'GL2_OP_ATOMIC_AND_64', 'GL2_OP_ATOMIC_AND_RTN_32', + 'GL2_OP_ATOMIC_AND_RTN_64', 'GL2_OP_ATOMIC_CLAMP_SUB_RTN_32', + 'GL2_OP_ATOMIC_CMPSWAP_32', 'GL2_OP_ATOMIC_CMPSWAP_64', + 'GL2_OP_ATOMIC_CMPSWAP_RTN_32', 'GL2_OP_ATOMIC_CMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_COND_SUB_RTN_32', 'GL2_OP_ATOMIC_DEC_32', + 'GL2_OP_ATOMIC_DEC_64', 'GL2_OP_ATOMIC_DEC_RTN_32', + 'GL2_OP_ATOMIC_DEC_RTN_64', 'GL2_OP_ATOMIC_FADD_32', + 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FADD_RTN_32', 'GL2_OP_ATOMIC_FCMPSWAP_32', + 'GL2_OP_ATOMIC_FCMPSWAP_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FCMPSWAP_RTN_32', 'GL2_OP_ATOMIC_FCMPSWAP_RTN_64', + 'GL2_OP_ATOMIC_FMAX_32', 'GL2_OP_ATOMIC_FMAX_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMAX_RTN_32', 'GL2_OP_ATOMIC_FMAX_RTN_64', + 'GL2_OP_ATOMIC_FMIN_32', 'GL2_OP_ATOMIC_FMIN_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'GL2_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'GL2_OP_ATOMIC_FMIN_RTN_32', 'GL2_OP_ATOMIC_FMIN_RTN_64', + 'GL2_OP_ATOMIC_INC_32', 'GL2_OP_ATOMIC_INC_64', + 'GL2_OP_ATOMIC_INC_RTN_32', 'GL2_OP_ATOMIC_INC_RTN_64', + 'GL2_OP_ATOMIC_OR_32', 'GL2_OP_ATOMIC_OR_64', + 'GL2_OP_ATOMIC_OR_RTN_32', 'GL2_OP_ATOMIC_OR_RTN_64', + 'GL2_OP_ATOMIC_PK_ADD_BF16', 'GL2_OP_ATOMIC_PK_ADD_BF16_RTN', + 'GL2_OP_ATOMIC_PK_ADD_FP16', 'GL2_OP_ATOMIC_PK_ADD_FP16_RTN', + 'GL2_OP_ATOMIC_SMAX_32', 'GL2_OP_ATOMIC_SMAX_64', + 'GL2_OP_ATOMIC_SMAX_RTN_32', 'GL2_OP_ATOMIC_SMAX_RTN_64', + 'GL2_OP_ATOMIC_SMIN_32', 'GL2_OP_ATOMIC_SMIN_64', + 'GL2_OP_ATOMIC_SMIN_RTN_32', 'GL2_OP_ATOMIC_SMIN_RTN_64', + 'GL2_OP_ATOMIC_STORE_COND_RTN', 'GL2_OP_ATOMIC_SUB_32', + 'GL2_OP_ATOMIC_SUB_64', 'GL2_OP_ATOMIC_SUB_RTN_32', + 'GL2_OP_ATOMIC_SUB_RTN_64', 'GL2_OP_ATOMIC_SWAP_32', + 'GL2_OP_ATOMIC_SWAP_64', 'GL2_OP_ATOMIC_SWAP_RTN_32', + 'GL2_OP_ATOMIC_SWAP_RTN_64', 'GL2_OP_ATOMIC_UMAX_32', + 'GL2_OP_ATOMIC_UMAX_64', 'GL2_OP_ATOMIC_UMAX_8', + 'GL2_OP_ATOMIC_UMAX_RTN_32', 'GL2_OP_ATOMIC_UMAX_RTN_64', + 'GL2_OP_ATOMIC_UMIN_32', 'GL2_OP_ATOMIC_UMIN_64', + 'GL2_OP_ATOMIC_UMIN_8', 'GL2_OP_ATOMIC_UMIN_RTN_32', + 'GL2_OP_ATOMIC_UMIN_RTN_64', 'GL2_OP_ATOMIC_XOR_32', + 'GL2_OP_ATOMIC_XOR_64', 'GL2_OP_ATOMIC_XOR_RTN_32', + 'GL2_OP_ATOMIC_XOR_RTN_64', + 'GL2_OP_FORCE_EXISTING_DATA_TO_DECOMPRESS', 'GL2_OP_GL1_INV', + 'GL2_OP_GL2_INV', 'GL2_OP_GL2_WB', 'GL2_OP_GL2_WBINV', + 'GL2_OP_LOAD_RESERVE', 'GL2_OP_MASKS', 'GL2_OP_MASK_64', + 'GL2_OP_MASK_FLUSH_DENROM', 'GL2_OP_MASK_NO_RTN', + 'GL2_OP_NOP_ACK', 'GL2_OP_NOP_RTN0', 'GL2_OP_PROBE_FILTER', + 'GL2_OP_READ', 'GL2_OP_READ_COMPRESSION_KEY', + 'GL2_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', 'GL2_OP_UTC_PROBE', + 'GL2_OP_WRITE', 'GL2_OP_WRITE_ZERO_SIZE', 'GLCompressionMode', + 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE', + 'GLOBAL_CONTROL_CONTROLLER_RESET', 'GLOBAL_CONTROL_FLUSH_CONTROL', + 'GLOBAL_STATUS_FLUSH_STATUS', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 'GL__CONSTANT_ALPHA', 'GL__CONSTANT_COLOR', 'GL__DST_ALPHA', + 'GL__DST_COLOR', 'GL__ONE', 'GL__ONE_MINUS_CONSTANT_ALPHA', + 'GL__ONE_MINUS_CONSTANT_COLOR', 'GL__ONE_MINUS_DST_ALPHA', + 'GL__ONE_MINUS_DST_COLOR', 'GL__ONE_MINUS_SRC_ALPHA', + 'GL__ONE_MINUS_SRC_COLOR', 'GL__SRC_ALPHA', + 'GL__SRC_ALPHA_SATURATE', 'GL__SRC_COLOR', 'GL__ZERO', + 'GRBMH_PERF_SEL', 'GRBMH_PERF_SEL_BCI_BUSY', + 'GRBMH_PERF_SEL_CB_BUSY', 'GRBMH_PERF_SEL_CB_CLEAN', + 'GRBMH_PERF_SEL_COUNT', 'GRBMH_PERF_SEL_DB_BUSY', + 'GRBMH_PERF_SEL_DB_CLEAN', 'GRBMH_PERF_SEL_EA_BUSY', + 'GRBMH_PERF_SEL_EA_LINK_BUSY', 'GRBMH_PERF_SEL_GE_BUSY', + 'GRBMH_PERF_SEL_GL1A_BUSY', 'GRBMH_PERF_SEL_GL1CC_BUSY', + 'GRBMH_PERF_SEL_GL1XCC_BUSY', 'GRBMH_PERF_SEL_GL2A_BUSY', + 'GRBMH_PERF_SEL_GL2C_BUSY', 'GRBMH_PERF_SEL_PA_BUSY', + 'GRBMH_PERF_SEL_PC_BUSY', 'GRBMH_PERF_SEL_RLC_BUSY', + 'GRBMH_PERF_SEL_SC_BUSY', 'GRBMH_PERF_SEL_SC_CLEAN', + 'GRBMH_PERF_SEL_SPI_BUSY', 'GRBMH_PERF_SEL_SX_BUSY', + 'GRBMH_PERF_SEL_TA_BUSY', 'GRBMH_PERF_SEL_TCP_BUSY', + 'GRBMH_PERF_SEL_USER_DEFINED', 'GRBMH_PERF_SEL_UTCL1_BUSY', + 'GRBM_PERF_SEL', 'GRBM_PERF_SEL_ANY_ACTIVE_F_BUSY', + 'GRBM_PERF_SEL_BCI_BUSY', 'GRBM_PERF_SEL_CB_BUSY', + 'GRBM_PERF_SEL_CB_CLEAN', 'GRBM_PERF_SEL_CH_BUSY', + 'GRBM_PERF_SEL_COUNT', 'GRBM_PERF_SEL_CPC_BUSY', + 'GRBM_PERF_SEL_CPF_BUSY', 'GRBM_PERF_SEL_CPG_BUSY', + 'GRBM_PERF_SEL_CP_BUSY', 'GRBM_PERF_SEL_CP_COHER_BUSY', + 'GRBM_PERF_SEL_CP_DMA_BUSY', 'GRBM_PERF_SEL_DB_BUSY', + 'GRBM_PERF_SEL_DB_CLEAN', 'GRBM_PERF_SEL_EA_BUSY', + 'GRBM_PERF_SEL_GE_BUSY', 'GRBM_PERF_SEL_GE_NO_DMA_BUSY', + 'GRBM_PERF_SEL_GL1CC_BUSY', 'GRBM_PERF_SEL_GL1XCC_BUSY', + 'GRBM_PERF_SEL_GL2CC_BUSY', 'GRBM_PERF_SEL_GUI_ACTIVE', + 'GRBM_PERF_SEL_GUS_BUSY', 'GRBM_PERF_SEL_PA_BUSY', + 'GRBM_PERF_SEL_PC_BUSY', 'GRBM_PERF_SEL_PMM_BUSY', + 'GRBM_PERF_SEL_RLC_BUSY', 'GRBM_PERF_SEL_SC_BUSY', + 'GRBM_PERF_SEL_SDMA_BUSY', 'GRBM_PERF_SEL_SPI_BUSY', + 'GRBM_PERF_SEL_SX_BUSY', 'GRBM_PERF_SEL_TA_BUSY', + 'GRBM_PERF_SEL_TCP_BUSY', 'GRBM_PERF_SEL_USER_DEFINED', + 'GRBM_PERF_SEL_UTCL1_BUSY', 'GRBM_PERF_SEL_UTCL2_BUSY', + 'GREEN_LUT', 'GSTHREADID_SIZE', 'GS_OFF', 'GS_SCENARIO_A', + 'GS_SCENARIO_B', 'GS_SCENARIO_C', 'GS_SCENARIO_G', 'GS_STAGE_OFF', + 'GS_STAGE_ON', 'HDMICHARCLK_SRC_SEL', + 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', 'HDMICHARCLK_SRC_SEL_UNIPHYA', + 'HDMICHARCLK_SRC_SEL_UNIPHYB', 'HDMICHARCLK_SRC_SEL_UNIPHYC', + 'HDMICHARCLK_SRC_SEL_UNIPHYD', 'HDMISTREAMCLK_SRC_SEL', + 'HDMI_ACP_NOT_SEND', 'HDMI_ACP_PKT_SEND', 'HDMI_ACP_SEND', + 'HDMI_ACR_0_MULTIPLE_RESERVED', 'HDMI_ACR_1_MULTIPLE', + 'HDMI_ACR_2_MULTIPLE', 'HDMI_ACR_3_MULTIPLE_RESERVED', + 'HDMI_ACR_4_MULTIPLE', 'HDMI_ACR_5_MULTIPLE_RESERVED', + 'HDMI_ACR_6_MULTIPLE_RESERVED', 'HDMI_ACR_7_MULTIPLE_RESERVED', + 'HDMI_ACR_AUDIO_PRIORITY', 'HDMI_ACR_CONT', + 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', + 'HDMI_ACR_NOT_SEND', 'HDMI_ACR_N_MULTIPLE', + 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 'HDMI_ACR_PKT_SEND', 'HDMI_ACR_SELECT', 'HDMI_ACR_SELECT_32K', + 'HDMI_ACR_SELECT_44K', 'HDMI_ACR_SELECT_48K', + 'HDMI_ACR_SELECT_HW', 'HDMI_ACR_SEND', 'HDMI_ACR_SOURCE', + 'HDMI_ACR_SOURCE_HW', 'HDMI_ACR_SOURCE_SW', + 'HDMI_AUDIO_DELAY_56CLK', 'HDMI_AUDIO_DELAY_58CLK', + 'HDMI_AUDIO_DELAY_DISABLE', 'HDMI_AUDIO_DELAY_EN', + 'HDMI_AUDIO_DELAY_RESERVED', 'HDMI_AUDIO_INFO_CONT', + 'HDMI_AUDIO_INFO_CONT_DISABLE', 'HDMI_AUDIO_INFO_CONT_ENABLE', + 'HDMI_AUDIO_INFO_NOT_SEND', 'HDMI_AUDIO_INFO_PKT_SEND', + 'HDMI_AUDIO_INFO_SEND', + 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', + 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_RATE', 'HDMI_DATA_SCRAMBLE_DISABLE', + 'HDMI_DATA_SCRAMBLE_EN', 'HDMI_DATA_SCRAMBLE_ENABLE', + 'HDMI_DEEP_COLOR_DEPTH', 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 'HDMI_DEEP_COLOR_DEPTH_30BPP', 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 'HDMI_DEEP_COLOR_DEPTH_48BPP', 'HDMI_DEFAULT_PAHSE', + 'HDMI_DEFAULT_PHASE_IS_0', 'HDMI_DEFAULT_PHASE_IS_1', + 'HDMI_ERROR_ACK', 'HDMI_ERROR_ACK_INT', 'HDMI_ERROR_MASK', + 'HDMI_ERROR_MASK_INT', 'HDMI_ERROR_NOT_ACK', + 'HDMI_ERROR_NOT_MASK', 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', + 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', 'HDMI_GC_AVMUTE', + 'HDMI_GC_AVMUTE_CONT', 'HDMI_GC_AVMUTE_CONT_DISABLE', + 'HDMI_GC_AVMUTE_CONT_ENABLE', 'HDMI_GC_AVMUTE_SET', + 'HDMI_GC_AVMUTE_UNSET', 'HDMI_GC_CONT', 'HDMI_GC_CONT_DISABLE', + 'HDMI_GC_CONT_ENABLE', 'HDMI_GC_NOT_SEND', 'HDMI_GC_PKT_SEND', + 'HDMI_GC_SEND', 'HDMI_GENERIC_CONT', 'HDMI_GENERIC_CONT_DISABLE', + 'HDMI_GENERIC_CONT_ENABLE', 'HDMI_GENERIC_NOT_SEND', + 'HDMI_GENERIC_PKT_SEND', 'HDMI_GENERIC_SEND', 'HDMI_ISRC_CONT', + 'HDMI_ISRC_CONT_DISABLE', 'HDMI_ISRC_CONT_ENABLE', + 'HDMI_ISRC_NOT_SEND', 'HDMI_ISRC_PKT_SEND', 'HDMI_ISRC_SEND', + 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', 'HDMI_KEEPOUT_MODE', + 'HDMI_METADATA_ENABLE', 'HDMI_METADATA_NOT_SEND', + 'HDMI_METADATA_PKT_SEND', 'HDMI_MPEG_INFO_CONT', + 'HDMI_MPEG_INFO_CONT_DISABLE', 'HDMI_MPEG_INFO_CONT_ENABLE', + 'HDMI_MPEG_INFO_NOT_SEND', 'HDMI_MPEG_INFO_PKT_SEND', + 'HDMI_MPEG_INFO_SEND', 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 'HDMI_NO_EXTRA_NULL_PACKET_FILLED', 'HDMI_NULL_NOT_SEND', + 'HDMI_NULL_PKT_SEND', 'HDMI_NULL_SEND', 'HDMI_PACKET_GEN_VERSION', + 'HDMI_PACKET_GEN_VERSION_NEW', 'HDMI_PACKET_GEN_VERSION_OLD', + 'HDMI_PACKET_LINE_REFERENCE', 'HDMI_PACKING_PHASE_OVERRIDE', + 'HDMI_PACKING_PHASE_SET_BY_HW', 'HDMI_PACKING_PHASE_SET_BY_SW', + 'HDMI_PKT_LINE_REF_OTGSOF', 'HDMI_PKT_LINE_REF_VSYNC', + 'HDMI_SEND_MAX_AUDIO_PACKETS', 'HDP_ENDIAN_8IN16', + 'HDP_ENDIAN_8IN32', 'HDP_ENDIAN_8IN64', 'HDP_ENDIAN_NONE', + 'HPD_INT_CONTROL_ACK', 'HPD_INT_CONTROL_ACK_0', + 'HPD_INT_CONTROL_ACK_1', 'HPD_INT_CONTROL_GEN_INT_ON_CON', + 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', 'HPD_INT_CONTROL_POLARITY', + 'HPD_INT_CONTROL_RX_INT_ACK', 'HPD_INT_CONTROL_RX_INT_ACK_0', + 'HPD_INT_CONTROL_RX_INT_ACK_1', 'HPO_SRC0', 'HPO_SRC_RESERVED', + 'HPO_TOP_CLOCK_GATING_DIS', 'HPO_TOP_CLOCK_GATING_DISABLE', + 'HPO_TOP_CLOCK_GATING_EN', + 'HPO_TOP_FEATURE_GATED_DISPCLK_IN_HDMISTREAMENC0', + 'HPO_TOP_FEATURE_GATED_HDMICHARCLK0', + 'HPO_TOP_FEATURE_GATED_HDMISTREAMCLK0', + 'HPO_TOP_FEATURE_GATED_SOCCLK_IN_HDMISTREAMENC0', + 'HPO_TOP_PERMANENT_DISPCLK', 'HPO_TOP_PERMANENT_HDMICHARCLK0', + 'HPO_TOP_PERMANENT_HDMISTREAMCLK0', 'HPO_TOP_PERMANENT_SOCCLK', + 'HPO_TOP_REGISTER_GATED_DISPCLK', + 'HPO_TOP_REGISTER_GATED_HDMICHARCLK0', + 'HPO_TOP_REGISTER_GATED_HDMISTREAMCLK0', 'HPO_TOP_TEST_CLK_SEL', + 'HPO_TOP_TEST_CLOCK_RESERVED', 'HS_GS', 'HS_STAGE_OFF', + 'HS_STAGE_ON', 'HUBP_3DLUT_ADDRESSING_MODE', + 'HUBP_3DLUT_SIMPLE_LINEAR', 'HUBP_3DLUT_SW_LINEAR', + 'HUBP_BLANK_EN', 'HUBP_BLANK_SW_ASSERT', 'HUBP_BLANK_SW_DEASSERT', + 'HUBP_IN_ACTIVE', 'HUBP_IN_BLANK', 'HUBP_IN_VBLANK', + 'HUBP_MEASURE_WIN_MODE_DCFCLK', 'HUBP_MEASURE_WIN_MODE_DCFCLK_0', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_1', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_2', + 'HUBP_MEASURE_WIN_MODE_DCFCLK_3', 'HUBP_NO_OUTSTANDING_REQ', + 'HUBP_SOFT_RESET', 'HUBP_SOFT_RESET_OFF', 'HUBP_SOFT_RESET_ON', + 'HUBP_TTU_DISABLE', 'HUBP_TTU_DISABLED', 'HUBP_TTU_ENABLED', + 'HUBP_VREADY_AT_OR_AFTER_VSYNC', 'HUBP_VTG_SEL', + 'HW_MIRRORING_DISABLE', 'HW_MIRRORING_ENABLE', 'H_MIRROR_EN', + 'Hdp_SurfaceEndian', 'ID_STREAM_DISABLE_ACKED', + 'ID_STREAM_DISABLE_NO_ACK', 'IHC_INTERRUPT_DEST', + 'IHC_INTERRUPT_LINE_STATUS', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 'INPUT_COVERAGE', 'INPUT_DEPTH_COVERAGE', 'INPUT_INNER_COVERAGE', + 'INST_ID_ECC_INTERRUPT_MSG', 'INST_ID_HOST_REG_TRAP_MSG', + 'INST_ID_HW_TRAP', 'INST_ID_HW_TRAP_GET_TBA', 'INST_ID_KILL_SEQ', + 'INST_ID_PRIV_START', 'INST_ID_SPI_WREXEC', + 'INST_ID_TTRACE_NEW_PC_MSG', 'INTERRUPT_LINE_ASSERTED', + 'INTERRUPT_LINE_NOT_ASSERTED', 'INTERRUPT_SENT_TO_DMCUB', + 'INTERRUPT_SENT_TO_IH', 'INT_DISABLED', 'INT_ENABLED', + 'INT_LEVEL', 'INT_MASK', 'INT_PULSE', 'INVALID_REG_ACCESS_TYPE', + 'IQ_DEQUEUE_RETRY', 'IQ_INTR_TYPE_IB', 'IQ_INTR_TYPE_MQD', + 'IQ_INTR_TYPE_PQ', 'IQ_OFFLOAD_RETRY', 'IQ_QUEUE_SLEEP', + 'IQ_SCH_WAVE_MSG', 'ISHARP_FMT_MODE_0', 'ISHARP_FMT_MODE_1', + 'ISHARP_FMT_MODE_ENUM', 'ISHARP_LBA_MODE_0', 'ISHARP_LBA_MODE_1', + 'ISHARP_LBA_MODE_ENUM', 'ISHARP_NOISEDET_MODE_0', + 'ISHARP_NOISEDET_MODE_1', 'ISHARP_NOISEDET_MODE_2', + 'ISHARP_NOISEDET_MODE_3', 'ISHARP_NOISEDET_MODE_ENUM', + 'JITTER_REMOVE_DISABLE', 'LATE_Z', 'LB_ALPHA_DISABLE', + 'LB_ALPHA_EN', 'LB_ALPHA_ENABLE', 'LB_INTERLEAVE_DISABLE', + 'LB_INTERLEAVE_EN', 'LB_INTERLEAVE_ENABLE', 'LB_MEMORY_CONFIG', + 'LB_MEMORY_CONFIG_0', 'LB_MEMORY_CONFIG_1', 'LB_MEMORY_CONFIG_2', + 'LB_MEMORY_CONFIG_3', 'LEGACY_PIPE_INTERLEAVE', + 'LEGACY_PIPE_INTERLEAVE_256B', 'LEGACY_PIPE_INTERLEAVE_512B', + 'LINESTRIP', 'LSDMA_PERF_SEL', 'LSDMA_PERF_SEL_ATCL2_FREE', + 'LSDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 'LSDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 'LSDMA_PERF_SEL_ATCL2_RET_ACK', 'LSDMA_PERF_SEL_ATCL2_RET_XNACK', + 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_REQ', + 'LSDMA_PERF_SEL_ATOMIC_MMHUB_WR_RET', + 'LSDMA_PERF_SEL_CE_AFIFO_FULL', 'LSDMA_PERF_SEL_CE_BUSY', + 'LSDMA_PERF_SEL_CE_BUSY_END', 'LSDMA_PERF_SEL_CE_BUSY_START', + 'LSDMA_PERF_SEL_CE_DST_IDLE', 'LSDMA_PERF_SEL_CE_INFO1_FULL', + 'LSDMA_PERF_SEL_CE_INFO_FULL', 'LSDMA_PERF_SEL_CE_IN_IDLE', + 'LSDMA_PERF_SEL_CE_L1_STALL', 'LSDMA_PERF_SEL_CE_L1_WR_VLD', + 'LSDMA_PERF_SEL_CE_MMHUB_RDREQ_SEND', + 'LSDMA_PERF_SEL_CE_MMHUB_WRREQ_SEND', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_RD_RET', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_REQ', + 'LSDMA_PERF_SEL_CE_OR_F32_MMHUB_WR_RET', + 'LSDMA_PERF_SEL_CE_OUT_IDLE', 'LSDMA_PERF_SEL_CE_RD_STALL', + 'LSDMA_PERF_SEL_CE_RREQ_IDLE', 'LSDMA_PERF_SEL_CE_SPLIT_IDLE', + 'LSDMA_PERF_SEL_CE_WREQ_IDLE', 'LSDMA_PERF_SEL_CE_WR_IDLE', + 'LSDMA_PERF_SEL_CE_WR_STALL', 'LSDMA_PERF_SEL_CMD_OP_END', + 'LSDMA_PERF_SEL_CMD_OP_MATCH', 'LSDMA_PERF_SEL_CMD_OP_START', + 'LSDMA_PERF_SEL_CTX_CHANGE', + 'LSDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'LSDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'LSDMA_PERF_SEL_CYCLE', + 'LSDMA_PERF_SEL_DMA_L1_RD_SEND', 'LSDMA_PERF_SEL_DMA_L1_WR_SEND', + 'LSDMA_PERF_SEL_DMA_MC_RD_SEND', 'LSDMA_PERF_SEL_DMA_MC_WR_SEND', + 'LSDMA_PERF_SEL_DOORBELL', 'LSDMA_PERF_SEL_DRAM_ECC', + 'LSDMA_PERF_SEL_DUMMY_0', 'LSDMA_PERF_SEL_DUMMY_1', + 'LSDMA_PERF_SEL_EX_IDLE', + 'LSDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'LSDMA_PERF_SEL_F32_L1_WR_VLD', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_END', + 'LSDMA_PERF_SEL_F32_PERFCNT_TRIGGER_START', + 'LSDMA_PERF_SEL_GFX_SELECT', 'LSDMA_PERF_SEL_IB_CMD_FULL', + 'LSDMA_PERF_SEL_IB_CMD_IDLE', 'LSDMA_PERF_SEL_IB_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_IB_MMHUB_RD_RET', 'LSDMA_PERF_SEL_IDLE', + 'LSDMA_PERF_SEL_INT_IDLE', 'LSDMA_PERF_SEL_INT_REQ_COUNT', + 'LSDMA_PERF_SEL_INT_REQ_STALL', + 'LSDMA_PERF_SEL_INT_RESP_ACCEPTED', + 'LSDMA_PERF_SEL_INT_RESP_RETRY', + 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 'LSDMA_PERF_SEL_IS_INVREQ_ADDR_WR', + 'LSDMA_PERF_SEL_L1_INV_MIDDLE', 'LSDMA_PERF_SEL_L1_RDL2_IDLE', + 'LSDMA_PERF_SEL_L1_RDMC_IDLE', 'LSDMA_PERF_SEL_L1_RD_FIFO_IDLE', + 'LSDMA_PERF_SEL_L1_RD_INV_EN', 'LSDMA_PERF_SEL_L1_RD_INV_IDLE', + 'LSDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 'LSDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', + 'LSDMA_PERF_SEL_L1_WRL2_IDLE', 'LSDMA_PERF_SEL_L1_WRMC_IDLE', + 'LSDMA_PERF_SEL_L1_WR_FIFO_IDLE', 'LSDMA_PERF_SEL_L1_WR_INV_EN', + 'LSDMA_PERF_SEL_L1_WR_INV_IDLE', + 'LSDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 'LSDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', + 'LSDMA_PERF_SEL_MC_RD_COUNT', 'LSDMA_PERF_SEL_MC_RD_IDLE', + 'LSDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'LSDMA_PERF_SEL_MC_RD_RET_STALL', 'LSDMA_PERF_SEL_MC_WR_COUNT', + 'LSDMA_PERF_SEL_MC_WR_IDLE', + 'LSDMA_PERF_SEL_MMHUB_CE_RDRET_VALID', + 'LSDMA_PERF_SEL_MMHUB_CE_WRRET_VALID', + 'LSDMA_PERF_SEL_NACK_GEN_ERR', 'LSDMA_PERF_SEL_NUM_PACKET', + 'LSDMA_PERF_SEL_PAGE_SELECT', 'LSDMA_PERF_SEL_RB_CMD_FULL', + 'LSDMA_PERF_SEL_RB_CMD_IDLE', 'LSDMA_PERF_SEL_RB_EMPTY', + 'LSDMA_PERF_SEL_RB_FULL', 'LSDMA_PERF_SEL_RB_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_RB_MMHUB_RD_RET', 'LSDMA_PERF_SEL_RB_RPTR_WB', + 'LSDMA_PERF_SEL_RB_RPTR_WRAP', 'LSDMA_PERF_SEL_RB_WPTR_POLL_READ', + 'LSDMA_PERF_SEL_RB_WPTR_WRAP', 'LSDMA_PERF_SEL_RD_BA_RTR', + 'LSDMA_PERF_SEL_REG_IDLE', 'LSDMA_PERF_SEL_RLC0_SELECT', + 'LSDMA_PERF_SEL_RLC1_SELECT', 'LSDMA_PERF_SEL_SDMA_ATCL2_SEND', + 'LSDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 'LSDMA_PERF_SEL_SDMA_INVACK_NFLUSH', 'LSDMA_PERF_SEL_SEM_IDLE', + 'LSDMA_PERF_SEL_SEM_REQ_COUNT', 'LSDMA_PERF_SEL_SEM_REQ_STALL', + 'LSDMA_PERF_SEL_SEM_RESP_FAIL', + 'LSDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'LSDMA_PERF_SEL_SEM_RESP_PASS', 'LSDMA_PERF_SEL_SRBM_REG_SEND', + 'LSDMA_PERF_SEL_UTCL1_UTCL2_REQ', + 'LSDMA_PERF_SEL_UTCL1_UTCL2_RET', + 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_REQ', + 'LSDMA_PERF_SEL_WPTR_MMHUB_RD_RET', 'LSDMA_PERF_SEL_WR_BA_RTR', + 'LUMA_KEYER_ENABLE', 'LUMA_KEY_DIS', 'LUMA_KEY_EN', + 'LUT_2CFG_MEMORY_A', 'LUT_2CFG_MEMORY_B', 'LUT_2CFG_NO_MEMORY', + 'LUT_2_MODE_BYPASS', 'LUT_2_MODE_RAMA_LUT', 'LUT_2_MODE_RAMB_LUT', + 'LUT_4CFG_MEMORY_A', 'LUT_4CFG_MEMORY_B', 'LUT_4CFG_NO_MEMORY', + 'LUT_4CFG_ROM_A', 'LUT_4CFG_ROM_B', 'LUT_4_MODE_BYPASS', + 'LUT_4_MODE_RAMA_LUT', 'LUT_4_MODE_RAMB_LUT', + 'LUT_4_MODE_ROMA_LUT', 'LUT_4_MODE_ROMB_LUT', + 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', + 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT', + 'MASTER_UPDATE_LOCK_DB_FIELD_BOTH', + 'MASTER_UPDATE_LOCK_DB_FIELD_BOTTOM', + 'MASTER_UPDATE_LOCK_DB_FIELD_RESERVED', + 'MASTER_UPDATE_LOCK_DB_FIELD_TOP', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_BOTH', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_LEFT', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RESERVED', + 'MASTER_UPDATE_LOCK_DB_STEREO_SEL_RIGHT', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_LOCK_SEL', 'MASTER_UPDATE_LOCK_SEL_0', + 'MASTER_UPDATE_LOCK_SEL_1', 'MASTER_UPDATE_LOCK_SEL_2', + 'MASTER_UPDATE_LOCK_SEL_3', 'MASTER_UPDATE_LOCK_SEL_RESERVED4', + 'MASTER_UPDATE_LOCK_SEL_RESERVED5', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', + 'MATRIX_MODE_0', 'MATRIX_MODE_1', 'MATRIX_MODE_ENUM', + 'MEM_ARB_MODE_AGE', 'MEM_ARB_MODE_BOTH', 'MEM_ARB_MODE_FIXED', + 'MEM_ARB_MODE_WEIGHT', 'MEM_POWER_DIS_MODE_DISABLE', + 'MEM_POWER_DIS_MODE_ENABLE', 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', + 'MEM_POWER_FORCE_MODE_LIGHT_SLEEP', 'MEM_POWER_FORCE_MODE_OFF', + 'MEM_POWER_FORCE_MODE_SHUT_DOWN', 'MEM_POWER_STATUS_DEEP_SLEEP', + 'MEM_POWER_STATUS_LIGHT_SLEEP', 'MEM_POWER_STATUS_ON', + 'MEM_POWER_STATUS_SHUT_DOWN', 'MEM_PWR_DIS_CTRL', + 'MEM_PWR_DIS_MODE', 'MEM_PWR_FORCE_CTRL', 'MEM_PWR_FORCE_CTRL2', + 'MEM_PWR_FORCE_MODE', 'MEM_PWR_SEL_CTRL', 'MEM_PWR_SEL_CTRL2', + 'MEM_PWR_STATUS', 'METADATA_HUBP_SEL', 'METADATA_HUBP_SEL_0', + 'METADATA_HUBP_SEL_1', 'METADATA_HUBP_SEL_2', + 'METADATA_HUBP_SEL_3', 'METADATA_HUBP_SEL_RESERVED', + 'METADATA_STREAM_DP', 'METADATA_STREAM_DVE', + 'METADATA_STREAM_TYPE_SEL', 'META_CHUNK_SIZE', + 'META_CHUNK_SIZE_1KB', 'META_CHUNK_SIZE_2KB', + 'META_CHUNK_SIZE_4KB', 'META_CHUNK_SIZE_8KB', 'META_LINEAR', + 'META_SURF_LINEAR', 'META_SURF_TILED', 'ME_ID0', 'ME_ID1', + 'ME_ID2', 'ME_ID3', 'MICROSECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL', + 'MILLISECOND_TIME_BASE_CLOCK_IS_DCCGREFCLK', + 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL', 'MIN_CHUNK_SIZE', + 'MIN_CHUNK_SIZE_1024B', 'MIN_CHUNK_SIZE_256B', + 'MIN_CHUNK_SIZE_512B', 'MIN_META_CHUNK_SIZE', + 'MIN_META_CHUNK_SIZE_128B', 'MIN_META_CHUNK_SIZE_256B', + 'MIN_META_CHUNK_SIZE_64B', 'MONO_10LSB', 'MONO_10MSB', + 'MONO_12LSB', 'MONO_12MSB', 'MONO_16', 'MONO_2BIT', 'MONO_8', + 'MPCC_BG_COLOR_BPC', 'MPCC_BG_COLOR_BPC_10bit', + 'MPCC_BG_COLOR_BPC_11bit', 'MPCC_BG_COLOR_BPC_12bit', + 'MPCC_BG_COLOR_BPC_8bit', 'MPCC_BG_COLOR_BPC_9bit', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', + 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_GLOBAL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_PER_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE_UNUSED', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_FALSE', + 'MPCC_CONTROL_MPCC_ALPHA_MULTIPLIED_MODE_TRUE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_0', + 'MPCC_CONTROL_MPCC_BOT_GAIN_MODE_1', 'MPCC_CONTROL_MPCC_MODE', + 'MPCC_CONTROL_MPCC_MODE_BYPASS', + 'MPCC_CONTROL_MPCC_MODE_TOP_BOT_BLENDING', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_ONLY', + 'MPCC_CONTROL_MPCC_MODE_TOP_LAYER_PASSTHROUGH', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_ENUM', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_S2_13', + 'MPCC_GAMUT_REMAP_COEF_FORMAT_S3_12', 'MPCC_GAMUT_REMAP_MODE_0', + 'MPCC_GAMUT_REMAP_MODE_1', 'MPCC_GAMUT_REMAP_MODE_2', + 'MPCC_GAMUT_REMAP_MODE_ENUM', 'MPCC_GAMUT_REMAP_MODE_RSV', + 'MPCC_MCM_3DLUT_17CUBE', 'MPCC_MCM_3DLUT_30BIT', + 'MPCC_MCM_3DLUT_30BIT_ENUM', 'MPCC_MCM_3DLUT_36BIT', + 'MPCC_MCM_3DLUT_9CUBE', 'MPCC_MCM_3DLUT_RAM_SEL', + 'MPCC_MCM_3DLUT_SIZE_ENUM', 'MPCC_MCM_GAMMA_LUT_BYPASS', + 'MPCC_MCM_GAMMA_LUT_DISABLE_PWL', 'MPCC_MCM_GAMMA_LUT_ENABLE_PWL', + 'MPCC_MCM_GAMMA_LUT_MODE_ENUM', + 'MPCC_MCM_GAMMA_LUT_PWL_DISABLE_ENUM', 'MPCC_MCM_GAMMA_LUT_RAMA', + 'MPCC_MCM_GAMMA_LUT_RAMB', 'MPCC_MCM_GAMMA_LUT_RAM_LUT', + 'MPCC_MCM_GAMMA_LUT_RESERVED_1', 'MPCC_MCM_GAMMA_LUT_RESERVED_3', + 'MPCC_MCM_GAMMA_LUT_SEL_ENUM', + 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_ENUM', + 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S2_13', + 'MPCC_MCM_GAMUT_REMAP_COEF_FORMAT_S3_12', + 'MPCC_MCM_GAMUT_REMAP_MODE_0', 'MPCC_MCM_GAMUT_REMAP_MODE_1', + 'MPCC_MCM_GAMUT_REMAP_MODE_2', 'MPCC_MCM_GAMUT_REMAP_MODE_ENUM', + 'MPCC_MCM_GAMUT_REMAP_MODE_RSV', 'MPCC_MCM_LUT_2_MODE_BYPASS', + 'MPCC_MCM_LUT_2_MODE_ENUM', 'MPCC_MCM_LUT_2_MODE_RAMA_LUT', + 'MPCC_MCM_LUT_2_MODE_RAMB_LUT', 'MPCC_MCM_LUT_ALL_USE_R', + 'MPCC_MCM_LUT_BLUE_LUT', 'MPCC_MCM_LUT_CONFIG_MODE', + 'MPCC_MCM_LUT_DIFFERENT_RGB', 'MPCC_MCM_LUT_DISABLE_DEBUG', + 'MPCC_MCM_LUT_ENABLE_DEBUG', 'MPCC_MCM_LUT_GREEN_LUT', + 'MPCC_MCM_LUT_NUM_SEG', 'MPCC_MCM_LUT_RAMA_ACCESS', + 'MPCC_MCM_LUT_RAMB_ACCESS', 'MPCC_MCM_LUT_RAM_SEL', + 'MPCC_MCM_LUT_READ_COLOR_SEL', 'MPCC_MCM_LUT_READ_DBG', + 'MPCC_MCM_LUT_RED_LUT', 'MPCC_MCM_LUT_SEGMENTS_1', + 'MPCC_MCM_LUT_SEGMENTS_128', 'MPCC_MCM_LUT_SEGMENTS_16', + 'MPCC_MCM_LUT_SEGMENTS_2', 'MPCC_MCM_LUT_SEGMENTS_32', + 'MPCC_MCM_LUT_SEGMENTS_4', 'MPCC_MCM_LUT_SEGMENTS_64', + 'MPCC_MCM_LUT_SEGMENTS_8', 'MPCC_MCM_MEM_PWR_FORCE_DIS', + 'MPCC_MCM_MEM_PWR_FORCE_DS', 'MPCC_MCM_MEM_PWR_FORCE_ENUM', + 'MPCC_MCM_MEM_PWR_FORCE_LS', 'MPCC_MCM_MEM_PWR_FORCE_SD', + 'MPCC_MCM_MEM_PWR_STATE_DS', 'MPCC_MCM_MEM_PWR_STATE_ENUM', + 'MPCC_MCM_MEM_PWR_STATE_LS', 'MPCC_MCM_MEM_PWR_STATE_ON', + 'MPCC_MCM_MEM_PWR_STATE_SD', 'MPCC_MCM_RAM0_ACCESS', + 'MPCC_MCM_RAM1_ACCESS', 'MPCC_MCM_RAM2_ACCESS', + 'MPCC_MCM_RAM3_ACCESS', 'MPCC_OGAM_ALL_USE_R', + 'MPCC_OGAM_BLUE_LUT', 'MPCC_OGAM_DIFFERENT_RGB', + 'MPCC_OGAM_DISABLE_DEBUG', 'MPCC_OGAM_DISABLE_PWL', + 'MPCC_OGAM_ENABLE_DEBUG', 'MPCC_OGAM_ENABLE_PWL', + 'MPCC_OGAM_GREEN_LUT', 'MPCC_OGAM_LUT_2CFG_MEMORY_A', + 'MPCC_OGAM_LUT_2CFG_MEMORY_B', 'MPCC_OGAM_LUT_2CFG_NO_MEMORY', + 'MPCC_OGAM_LUT_2_CONFIG_ENUM', 'MPCC_OGAM_LUT_CONFIG_MODE', + 'MPCC_OGAM_LUT_PWL_DISABLE_ENUM', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMA', + 'MPCC_OGAM_LUT_RAM_CONTROL_MPCC_OGAM_LUT_RAM_SEL_RAMB', + 'MPCC_OGAM_LUT_RAM_SEL', 'MPCC_OGAM_LUT_READ_COLOR_SEL', + 'MPCC_OGAM_LUT_READ_DBG', 'MPCC_OGAM_LUT_SEL_ENUM', + 'MPCC_OGAM_MODE_0', 'MPCC_OGAM_MODE_2', + 'MPCC_OGAM_MODE_MPCC_OGAM_MODE_ENUM', 'MPCC_OGAM_MODE_RSV', + 'MPCC_OGAM_MODE_RSV1', 'MPCC_OGAM_NUM_SEG', 'MPCC_OGAM_RAMA', + 'MPCC_OGAM_RAMA_ACCESS', 'MPCC_OGAM_RAMB', + 'MPCC_OGAM_RAMB_ACCESS', 'MPCC_OGAM_RED_LUT', + 'MPCC_OGAM_SEGMENTS_1', 'MPCC_OGAM_SEGMENTS_128', + 'MPCC_OGAM_SEGMENTS_16', 'MPCC_OGAM_SEGMENTS_2', + 'MPCC_OGAM_SEGMENTS_32', 'MPCC_OGAM_SEGMENTS_4', + 'MPCC_OGAM_SEGMENTS_64', 'MPCC_OGAM_SEGMENTS_8', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_FALSE', + 'MPCC_OGAM_TEST_DEBUG_INDEX_MPCC_OGAM_TEST_DEBUG_WRITE_EN_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_EN', 'MPCC_SM_CONTROL_MPCC_SM_EN_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_EN_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FIELD_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 'MPCC_SM_CONTROL_MPCC_SM_FORCE_NEXT_TOP_POL_RESERVED', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_FALSE', + 'MPCC_SM_CONTROL_MPCC_SM_FRAME_ALT_TRUE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_CHECKERBOARD_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_COLUMN_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_ROW_SUBSAMPLING', + 'MPCC_SM_CONTROL_MPCC_SM_MODE_SINGLE_PLANE', + 'MPC_CFG_3DLUT_FL_FORMAT', 'MPC_CFG_3DLUT_FL_FORMAT_0', + 'MPC_CFG_3DLUT_FL_FORMAT_1', 'MPC_CFG_3DLUT_FL_FORMAT_2', + 'MPC_CFG_3DLUT_FL_MODE', 'MPC_CFG_3DLUT_FL_MODE_0', + 'MPC_CFG_3DLUT_FL_MODE_1', 'MPC_CFG_3DLUT_FL_MODE_2', + 'MPC_CFG_3DLUT_FL_MODE_3', 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_CUR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_ADR_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CFG_VUPDATE_LOCK_SET_TRUE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_FALSE', + 'MPC_CFG_CUR_VUPDATE_LOCK_SET_TRUE', 'MPC_CFG_MPC_TEST_CLK_SEL', + 'MPC_CFG_MPC_TEST_CLK_SEL_0', 'MPC_CFG_MPC_TEST_CLK_SEL_1', + 'MPC_CFG_MPC_TEST_CLK_SEL_2', 'MPC_CFG_MPC_TEST_CLK_SEL_3', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_FALSE', + 'MPC_CFG_TEST_DEBUG_INDEX_MPC_CFG_TEST_DEBUG_WRITE_EN_TRUE', + 'MPC_CRC_CALC_INTERLACE_MODE', 'MPC_CRC_CALC_MODE', + 'MPC_CRC_CALC_STEREO_MODE', 'MPC_CRC_CONTINUOUS_MODE', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_BOTTOM', + 'MPC_CRC_INTERLACE_MODE_BOTH_RESET_EACH', + 'MPC_CRC_INTERLACE_MODE_BOTTOM', 'MPC_CRC_INTERLACE_MODE_TOP', + 'MPC_CRC_ONE_SHOT_MODE', 'MPC_CRC_SOURCE_SELECT', + 'MPC_CRC_SOURCE_SEL_DPP', 'MPC_CRC_SOURCE_SEL_DWB', + 'MPC_CRC_SOURCE_SEL_OPP', 'MPC_CRC_SOURCE_SEL_OTHER', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_EACH', + 'MPC_CRC_STEREO_MODE_BOTH_RESET_RIGHT', + 'MPC_CRC_STEREO_MODE_LEFT', 'MPC_CRC_STEREO_MODE_RIGHT', + 'MPC_OCSC_COEF_FORMAT', 'MPC_OCSC_COEF_FORMAT_S2_13', + 'MPC_OCSC_COEF_FORMAT_S3_12', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_FALSE', + 'MPC_OCSC_TEST_DEBUG_INDEX_MPC_OCSC_TEST_DEBUG_WRITE_EN_TRUE', + 'MPC_OUT_CSC_MODE', 'MPC_OUT_CSC_MODE_0', 'MPC_OUT_CSC_MODE_1', + 'MPC_OUT_CSC_MODE_2', 'MPC_OUT_CSC_MODE_RSV', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_10BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_11BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_12BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_6BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_8BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_9BITS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_BYPASS', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_MODE', + 'MPC_OUT_DENORM_CONTROL_MPC_OUT_DENORM_PASSTHROUGH', + 'MPC_OUT_RATE_CONTROL_DISABLE_SET', + 'MPC_OUT_RATE_CONTROL_SET_DISABLE', + 'MPC_OUT_RATE_CONTROL_SET_ENABLE', + 'MSA_V_TIMING_OVERRIDE_DISABLED', 'MSA_V_TIMING_OVERRIDE_ENABLED', + 'MTYPE', 'MTYPE_CC', 'MTYPE_C_RO_S', 'MTYPE_C_RO_US', + 'MTYPE_C_RW_S', 'MTYPE_C_RW_US', 'MTYPE_NC', 'MTYPE_RESERVED_1', + 'MTYPE_RESERVED_5', 'MTYPE_RESERVED_7', 'MTYPE_UC', 'MTYPE_WC', + 'MULTIPLE_BY1', 'MULTIPLE_BY2', 'MULTIPLE_BY3_RESERVED', + 'MULTIPLE_BY4', 'MULTIPLE_RESERVED', 'MULT_16', 'MULT_8', + 'MemArbMode', 'NON_BYPASS', 'NOT_FORCE_THE_CLOCK_DISABLED', + 'NOT_SENT', 'NO_DIST', 'NO_DIV', 'NO_FORCE', 'NO_FORCE_REQ', + 'NO_FORCE_REQUEST', 'NO_MIN_CHUNK_SIZE', 'NO_MIN_META_CHUNK_SIZE', + 'NO_OUTSTANDING_REQ', 'NUM_SIMD_PER_CU', 'OBUF_BYPASS_DIS', + 'OBUF_BYPASS_EN', 'OBUF_BYPASS_SEL', 'OBUF_FULL', + 'OBUF_FULL_RECOUT', 'OBUF_HALF_RECOUT', + 'OBUF_IS_HALF_RECOUT_WIDTH_SEL', 'OBUF_RECOUT', + 'OBUF_USE_FULL_BUFFER_SEL', 'OFFCHIP_HS_DEALLOC', 'OFF_SEQ', + 'OKAY', 'OKAY_NODATA', 'OMODE_BLEND', 'OMODE_O_THEN_B', + 'OMODE_P_THEN_O_THEN_B', 'OMODE_RESERVED_3', 'ON_SEQ', + 'OPPBUF_DISPLAY_SEGMENTATION', + 'OPPBUF_DISPLAY_SEGMENTATION_1_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_2_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_LEFT', + 'OPPBUF_DISPLAY_SEGMENTATION_4_SEGMENT_SPLIT_RIGHT', + 'OPP_PIPE_CLOCK_DISABLE', 'OPP_PIPE_CLOCK_ENABLE', + 'OPP_PIPE_CLOCK_ENABLE_CONTROL', 'OPP_PIPE_CRC_CONT_EN', + 'OPP_PIPE_CRC_DISABLE', 'OPP_PIPE_CRC_EN', 'OPP_PIPE_CRC_ENABLE', + 'OPP_PIPE_CRC_INTERLACE_EN', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_INTERLACED', + 'OPP_PIPE_CRC_INTERLACE_EN_INTERPRET_AS_PROGRESSIVE', + 'OPP_PIPE_CRC_INTERLACE_MODE', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_BOTTOM_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTH_RESET_AFTER_EACH_FIELD', + 'OPP_PIPE_CRC_INTERLACE_MODE_BOTTOM', + 'OPP_PIPE_CRC_INTERLACE_MODE_TOP', 'OPP_PIPE_CRC_MODE_CONTINUOUS', + 'OPP_PIPE_CRC_MODE_ONE_SHOT', 'OPP_PIPE_CRC_ONE_SHOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_NOT_PENDING', + 'OPP_PIPE_CRC_ONE_SHOT_PENDING_PENDING', + 'OPP_PIPE_CRC_PIXEL_SELECT', + 'OPP_PIPE_CRC_PIXEL_SELECT_ALL_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_EVEN_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_ODD_PIXELS', + 'OPP_PIPE_CRC_PIXEL_SELECT_RESERVED', + 'OPP_PIPE_CRC_SOURCE_SELECT', 'OPP_PIPE_CRC_SOURCE_SELECT_FMT', + 'OPP_PIPE_CRC_SOURCE_SELECT_SFT', 'OPP_PIPE_CRC_STEREO_EN', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_NON_STEREO', + 'OPP_PIPE_CRC_STEREO_EN_INTERPRET_AS_STEREO', + 'OPP_PIPE_CRC_STEREO_MODE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_EACH_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_BOTH_RESET_AFTER_RIGHT_EYE', + 'OPP_PIPE_CRC_STEREO_MODE_LEFT', 'OPP_PIPE_CRC_STEREO_MODE_RIGHT', + 'OPP_PIPE_DIGTIAL_BYPASS_CONTROL', + 'OPP_PIPE_DIGTIAL_BYPASS_DISABLE', + 'OPP_PIPE_DIGTIAL_BYPASS_ENABLE', 'OPP_TEST_CLK_SEL_CONTROL', + 'OPP_TEST_CLK_SEL_DISPCLK_ABM0', 'OPP_TEST_CLK_SEL_DISPCLK_ABM1', + 'OPP_TEST_CLK_SEL_DISPCLK_ABM2', 'OPP_TEST_CLK_SEL_DISPCLK_ABM3', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP0', 'OPP_TEST_CLK_SEL_DISPCLK_OPP1', + 'OPP_TEST_CLK_SEL_DISPCLK_OPP2', 'OPP_TEST_CLK_SEL_DISPCLK_OPP3', + 'OPP_TEST_CLK_SEL_DISPCLK_P', 'OPP_TEST_CLK_SEL_DISPCLK_R', + 'OPP_TEST_CLK_SEL_RESERVED0', 'OPP_TEST_CLK_SEL_RESERVED1', + 'OPP_TEST_CLK_SEL_RESERVED2', 'OPP_TEST_CLK_SEL_RESERVED3', + 'OPP_TOP_CLOCK_DISABLED_STATUS', 'OPP_TOP_CLOCK_ENABLED_STATUS', + 'OPP_TOP_CLOCK_ENABLE_STATUS', 'OPP_TOP_CLOCK_GATING_CONTROL', + 'OPP_TOP_CLOCK_GATING_DISABLED', 'OPP_TOP_CLOCK_GATING_ENABLED', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG0', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG1', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG2', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_OTG3', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED4', + 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5', + 'OPT_COMB_ADD', 'OPT_COMB_BLEND_DISABLED', 'OPT_COMB_MAX', + 'OPT_COMB_MIN', 'OPT_COMB_NONE', 'OPT_COMB_REVSUBTRACT', + 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', + 'OTG_ADD_PIXEL', 'OTG_ADD_PIXEL_FORCE', 'OTG_ADD_PIXEL_NOOP', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_FIRST', + 'OTG_CONTROL_OTG_DISABLE_POINT_CNTL_DISABLE_VUPDATE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_DP', + 'OTG_CONTROL_OTG_FIELD_NUMBER_CNTL_NORMAL', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_FALSE', + 'OTG_CONTROL_OTG_FIELD_NUMBER_POLARITY_TRUE', + 'OTG_CONTROL_OTG_MASTER_EN', 'OTG_CONTROL_OTG_MASTER_EN_FALSE', + 'OTG_CONTROL_OTG_MASTER_EN_TRUE', 'OTG_CONTROL_OTG_OUT_MUX', + 'OTG_CONTROL_OTG_OUT_MUX_0', 'OTG_CONTROL_OTG_OUT_MUX_1', + 'OTG_CONTROL_OTG_OUT_MUX_2', 'OTG_CONTROL_OTG_START_POINT_CNTL', + 'OTG_CONTROL_OTG_START_POINT_CNTL_DP', + 'OTG_CONTROL_OTG_START_POINT_CNTL_NORMAL', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_FALSE', + 'OTG_COUNT_CONTROL_OTG_HORZ_COUNT_BY2_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC1_EN', 'OTG_CRC_CNTL_OTG_CRC1_EN_FALSE', + 'OTG_CRC_CNTL_OTG_CRC1_EN_TRUE', 'OTG_CRC_CNTL_OTG_CRC_CONT_EN', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_NORESET', + 'OTG_CRC_CNTL_OTG_CRC_CONT_MODE_RESET', 'OTG_CRC_CNTL_OTG_CRC_EN', + 'OTG_CRC_CNTL_OTG_CRC_EN_FALSE', 'OTG_CRC_CNTL_OTG_CRC_EN_TRUE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTH_FIELD', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_BOTTOM', + 'OTG_CRC_CNTL_OTG_CRC_INTERLACE_MODE_TOP', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_EYES', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_BOTH_FIELDS', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_LEFT', + 'OTG_CRC_CNTL_OTG_CRC_STEREO_MODE_RIGHT', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 'OTG_CRC_CNTL_OTG_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC0_SELECT_U_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_IA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_I_A_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UAB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_UA_B', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_AB', + 'OTG_CRC_CNTL_OTG_OTG_CRC1_SELECT_U_A_B', + 'OTG_DIG_UPDATE_VCOUNT_0', 'OTG_DIG_UPDATE_VCOUNT_1', + 'OTG_DIG_UPDATE_VCOUNT_MODE', 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE', + 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE_0', + 'OTG_DLPC_CONTROL_OTG_RESYNC_MODE_1', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_0', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_1', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_2', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_DRR_TIMING_DBUF_UPDATE_MODE_3', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_FALSE', + 'OTG_DOUBLE_BUFFER_CONTROL_OTG_UPDATE_INSTANTLY_TRUE', + 'OTG_DROP_PIXEL', 'OTG_DROP_PIXEL_FORCE', 'OTG_DROP_PIXEL_NOOP', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_1FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_2FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_4FRAME', + 'OTG_DRR_CONTROL_OTG_DRR_AVERAGE_FRAME_8FRAME', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_FALSE', + 'OTG_DTMTEST_CNTL_OTG_DTMTEST_OTG_EN_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_GRANULARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_FALSE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_POLARITY_TRUE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_CLK', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_GENLK_VSYNC', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_RESERVED', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKA', + 'OTG_FLOW_CONTROL_OTG_FLOW_CONTROL_SOURCE_SELECT_SWAPLOCKB', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CHECK_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_CLEAR_TRUE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_DISABLE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_MODE_RESERVED', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 'OTG_FORCE_COUNT_NOW_CNTL_OTG_FORCE_COUNT_NOW_TRIG_SEL_TRUE', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG0', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG1', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG2', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_OTG3', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED4', + 'OTG_GLOBAL_CONTROL2_MANUAL_FLOW_CONTROL_SEL_RESERVED5', + 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_EYE_SEL', + 'OTG_GLOBAL_CONTROL3_DIG_UPDATE_FIELD_SEL', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_FIELD', + 'OTG_GLOBAL_CONTROL3_MASTER_UPDATE_LOCK_DB_STEREO_SEL', + 'OTG_GLOBAL_UPDATE_LOCK_DISABLE', 'OTG_GLOBAL_UPDATE_LOCK_EN', + 'OTG_GLOBAL_UPDATE_LOCK_ENABLE', 'OTG_GSL_MASTER_MODE', + 'OTG_GSL_MASTER_MODE_0', 'OTG_GSL_MASTER_MODE_1', + 'OTG_GSL_MASTER_MODE_2', 'OTG_GSL_MASTER_MODE_3', + 'OTG_HORZ_REPETITION_COUNT', 'OTG_HORZ_REPETITION_COUNT_0', + 'OTG_HORZ_REPETITION_COUNT_1', 'OTG_HORZ_REPETITION_COUNT_10', + 'OTG_HORZ_REPETITION_COUNT_11', 'OTG_HORZ_REPETITION_COUNT_12', + 'OTG_HORZ_REPETITION_COUNT_13', 'OTG_HORZ_REPETITION_COUNT_14', + 'OTG_HORZ_REPETITION_COUNT_15', 'OTG_HORZ_REPETITION_COUNT_2', + 'OTG_HORZ_REPETITION_COUNT_3', 'OTG_HORZ_REPETITION_COUNT_4', + 'OTG_HORZ_REPETITION_COUNT_5', 'OTG_HORZ_REPETITION_COUNT_6', + 'OTG_HORZ_REPETITION_COUNT_7', 'OTG_HORZ_REPETITION_COUNT_8', + 'OTG_HORZ_REPETITION_COUNT_9', 'OTG_H_SYNC_A_POL', + 'OTG_H_SYNC_A_POL_HIGH', 'OTG_H_SYNC_A_POL_LOW', + 'OTG_H_TIMING_DIV_MODE', 'OTG_H_TIMING_DIV_MODE_AUTO', + 'OTG_H_TIMING_DIV_MODE_DIV_BY2', 'OTG_H_TIMING_DIV_MODE_DIV_BY4', + 'OTG_H_TIMING_DIV_MODE_MANUAL', 'OTG_H_TIMING_DIV_MODE_NOAUTO', + 'OTG_H_TIMING_DIV_MODE_NO_DIV', 'OTG_H_TIMING_DIV_MODE_RESERVED', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_FALSE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_ENABLE_TRUE', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_BOTTOM', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_NOT2', + 'OTG_INTERLACE_CONTROL_OTG_INTERLACE_FORCE_NEXT_FIELD_TOP', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_COUNT_NOW_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_GSL_VSYNC_GAP_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_SNAPSHOT_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGA_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_TRIGB_INT_TYPE_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_MSK_TRUE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_FALSE', + 'OTG_INTERRUPT_CONTROL_OTG_VSYNC_NOM_INT_TYPE_TRUE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 'OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_OTG_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', + 'OTG_MASTER_UPDATE_LOCK_DB_EN', 'OTG_MASTER_UPDATE_LOCK_DISABLE', + 'OTG_MASTER_UPDATE_LOCK_ENABLE', 'OTG_MASTER_UPDATE_LOCK_GSL_EN', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_FALSE', + 'OTG_MASTER_UPDATE_LOCK_GSL_EN_TRUE', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_0', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_1', + 'OTG_MASTER_UPDATE_LOCK_VCOUNT_MODE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 'OTG_SNAPSHOT_CONTROL_OTG_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_FALSE', + 'OTG_SNAPSHOT_STATUS_OTG_SNAPSHOT_CLEAR_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_CLEAR_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_ENABLE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_CPU_SS_INT_TYPE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_FALSE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_TRUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 'OTG_STATIC_SCREEN_CONTROL_OTG_STATIC_SCREEN_OVERRIDE_VALUE_ON', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_FALSE', + 'OTG_STEREO_CONTROL_OTG_FIELD_NUM_SEL_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EN_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_EYE_FLAG_POLARITY_TRUE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 'OTG_STEREO_CONTROL_OTG_STEREO_SYNC_OUTPUT_POLARITY_TRUE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_LEFT', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_NO', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RESERVED', + 'OTG_STEREO_FORCE_NEXT_EYE_OTG_STEREO_FORCE_NEXT_EYE_RIGHT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_CLEAR_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICB', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_GENERICD', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED4', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_PIPE_SELECT_RESERVED5', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HPD2', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_HSYNC', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_RESERVED14', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGA_CNTL_OTG_TRIGA_SOURCE_SELECT_VSYNC', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGA_FREQUENCY_SELECT', 'OTG_TRIGA_FREQUENCY_SELECT_0', + 'OTG_TRIGA_FREQUENCY_SELECT_1', 'OTG_TRIGA_FREQUENCY_SELECT_2', + 'OTG_TRIGA_FREQUENCY_SELECT_3', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGA_RISING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_CLEAR_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICB', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_GENERICD', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_HSYNCA', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_INTERLACE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_POLARITY_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_FALSE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_RESYNC_BYPASS_EN_TRUE', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_OTG3', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED4', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_PIPE_SELECT_RESERVED5', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_BLON_Y_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_FLIP_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICD_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICE_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENERICF_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_CLK_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GENLK_VSYNC_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_GSL_ALLOW_FLIP', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HPD2', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_HSYNC', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC0', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_LOGIC1', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_MANUAL_FLOW_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_SOF', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_OTG_TRIG_MANUAL_CONTROL', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_RESERVED14', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKA_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_SWAPLOCKB_PIN', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_LOCK', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_UPDATE_PENDING', + 'OTG_TRIGB_CNTL_OTG_TRIGB_SOURCE_SELECT_VSYNC', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_FALLING_EDGE_DETECT_CNTL_3', + 'OTG_TRIGB_FREQUENCY_SELECT', 'OTG_TRIGB_FREQUENCY_SELECT_0', + 'OTG_TRIGB_FREQUENCY_SELECT_1', 'OTG_TRIGB_FREQUENCY_SELECT_2', + 'OTG_TRIGB_FREQUENCY_SELECT_3', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_0', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_1', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_2', + 'OTG_TRIGB_RISING_EDGE_DETECT_CNTL_3', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_FALSE', + 'OTG_UPDATE_LOCK_OTG_UPDATE_LOCK_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 'OTG_VERTICAL_INTERRUPT0_CONTROL_OTG_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT1_CONTROL_OTG_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_CLEAR_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 'OTG_VERTICAL_INTERRUPT2_CONTROL_OTG_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_DISABLE', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_RESERVED', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 'OTG_VERT_SYNC_CONTROL_OTG_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 'OTG_VERT_SYNC_CONTROL_OTG_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_FALSE', + 'OTG_VSYNC_NOM_INT_STATUS_OTG_VSYNC_NOM_INT_CLEAR_TRUE', + 'OTG_VUPDATE_BLOCK_DISABLE', 'OTG_VUPDATE_BLOCK_DISABLE_OFF', + 'OTG_VUPDATE_BLOCK_DISABLE_ON', 'OTG_V_SYNC_A_POL', + 'OTG_V_SYNC_A_POL_HIGH', 'OTG_V_SYNC_A_POL_LOW', + 'OTG_V_SYNC_MODE', 'OTG_V_SYNC_MODE_HBLANK', + 'OTG_V_SYNC_MODE_HSYNC', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_0', + 'OTG_V_TOTAL_CONTROL_OTG_DRR_EVENT_ACTIVE_PERIOD_1', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_ON_EVENT_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 'OTG_V_TOTAL_CONTROL_OTG_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MAX_SEL_TRUE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_FALSE', + 'OTG_V_TOTAL_CONTROL_OTG_V_TOTAL_MIN_SEL_TRUE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_FALSE', + 'OTG_V_TOTAL_INT_STATUS_OTG_SET_V_TOTAL_MIN_EVENT_OCCURRED_ACK_TRUE', + 'OUTPUT_LINE', 'OUTPUT_POINT', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'OUTPUT_TRIANGLE_CCW', 'OUTPUT_TRIANGLE_CW', 'OUTSTANDING_REQ', + 'OVERRUN', 'OreoMode', 'PART_FRAC_EVEN', 'PART_FRAC_ODD', + 'PART_INTEGER', 'PART_POW2', 'PATCHES', 'PC_PERFCNT_SEL', + 'PC_PERF_GE_GSDONE', 'PC_PERF_GL1_RTN_CNT_GT512', + 'PC_PERF_GL1_RTN_CNT_GT768', 'PC_PERF_GL1_RTN_CNT_GTE1', + 'PC_PERF_GRBM_BUSY', 'PC_PERF_LWC0_PC_MEM_READ_STALL', + 'PC_PERF_LWC0_PKR2_SA_BDRY_CROSSING', + 'PC_PERF_LWC0_PKR3_SA_BDRY_CROSSING', + 'PC_PERF_LWC0_PROBE_ORDER_STALL', + 'PC_PERF_LWC1_PC_MEM_READ_STALL', + 'PC_PERF_LWC1_PKR0_SA_BDRY_CROSSING', + 'PC_PERF_LWC1_PKR1_SA_BDRY_CROSSING', + 'PC_PERF_LWC1_PROBE_ORDER_STALL', + 'PC_PERF_MW_CACHE_CNTL_FULL_STALL', 'PC_PERF_MW_CACHE_HIT', + 'PC_PERF_MW_CACHE_MISS', 'PC_PERF_MW_CACHE_REUSE', + 'PC_PERF_MW_DEALLOC_HIT', 'PC_PERF_MW_DLINE_ALLOC', + 'PC_PERF_MW_DLINE_DEALLOC', 'PC_PERF_MW_GL1H_NUM_REQS', + 'PC_PERF_MW_GL1H_REQ_FREEZE', 'PC_PERF_MW_PHY_DLINE_FULL_STALL', + 'PC_PERF_MW_PROBE_CNT_FREEZE', 'PC_PERF_MW_RTN_ADDR_FREEZE', + 'PC_PERF_MW_STAMP_LIMIT_STALL', 'PC_PERF_MW_TAGLINE_ALLOC', + 'PC_PERF_MW_TAGLINE_DEALLOC', 'PC_PERF_NUM_PSWAVE', + 'PC_PERF_PC_LDS_CNTL_VALID0', 'PC_PERF_PC_LDS_CNTL_VALID1', + 'PC_PERF_PC_LDS_VERTEX_REUSE0', 'PC_PERF_PC_LDS_VERTEX_REUSE1', + 'PC_PERF_PC_MEM_BANK_CONF0', 'PC_PERF_PC_MEM_BANK_CONF1', + 'PC_PERF_PC_SPI_PROBE_FREEZE', + 'PC_PERF_PC_SPI_PROBE_OUT_OF_CREDIT', 'PC_PERF_PKR0_FPOSG_EQ1', + 'PC_PERF_PKR0_FPOSG_GT1', 'PC_PERF_PKR0_FPOSG_GT128', + 'PC_PERF_PKR0_FPOSG_GT16', 'PC_PERF_PKR0_FPOSG_GT64', + 'PC_PERF_PKR0_FPOSG_OUT_OF_WAVE', + 'PC_PERF_PKR0_GSDONE_WHILE_IDLE', 'PC_PERF_PKR0_NUM_PROBES', + 'PC_PERF_PKR0_NUM_WAVES', 'PC_PERF_PKR0_PRIMS_PER_PROBE_EQ1', + 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT1', + 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT2', + 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT4', + 'PC_PERF_PKR0_PRIMS_PER_PROBE_GT8', + 'PC_PERF_PKR0_PRIMS_PER_WAVE_EQ1', + 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT1', + 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT2', + 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT4', + 'PC_PERF_PKR0_PRIMS_PER_WAVE_GT8', 'PC_PERF_PKR0_PRIMS_REUSE', + 'PC_PERF_PKR0_PROBES_PER_WAVE_EQ1', + 'PC_PERF_PKR0_PROBES_PER_WAVE_GT1', + 'PC_PERF_PKR0_PROBES_PER_WAVE_GT2', + 'PC_PERF_PKR0_PROBES_PER_WAVE_GT4', + 'PC_PERF_PKR0_PROBES_PER_WAVE_GT8', 'PC_PERF_PKR1_FPOSG_EQ1', + 'PC_PERF_PKR1_FPOSG_GT1', 'PC_PERF_PKR1_FPOSG_GT128', + 'PC_PERF_PKR1_FPOSG_GT16', 'PC_PERF_PKR1_FPOSG_GT64', + 'PC_PERF_PKR1_FPOSG_OUT_OF_WAVE', + 'PC_PERF_PKR1_GSDONE_WHILE_IDLE', 'PC_PERF_PKR1_NUM_PROBES', + 'PC_PERF_PKR1_NUM_WAVES', 'PC_PERF_PKR1_PRIMS_PER_PROBE_EQ1', + 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT1', + 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT2', + 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT4', + 'PC_PERF_PKR1_PRIMS_PER_PROBE_GT8', + 'PC_PERF_PKR1_PRIMS_PER_WAVE_EQ1', + 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT1', + 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT2', + 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT4', + 'PC_PERF_PKR1_PRIMS_PER_WAVE_GT8', 'PC_PERF_PKR1_PRIMS_REUSE', + 'PC_PERF_PKR1_PROBES_PER_WAVE_EQ1', + 'PC_PERF_PKR1_PROBES_PER_WAVE_GT1', + 'PC_PERF_PKR1_PROBES_PER_WAVE_GT2', + 'PC_PERF_PKR1_PROBES_PER_WAVE_GT4', + 'PC_PERF_PKR1_PROBES_PER_WAVE_GT8', 'PC_PERF_PKR2_FPOSG_EQ1', + 'PC_PERF_PKR2_FPOSG_GT1', 'PC_PERF_PKR2_FPOSG_GT128', + 'PC_PERF_PKR2_FPOSG_GT16', 'PC_PERF_PKR2_FPOSG_GT64', + 'PC_PERF_PKR2_FPOSG_OUT_OF_WAVE', + 'PC_PERF_PKR2_GSDONE_WHILE_IDLE', 'PC_PERF_PKR2_NUM_PROBES', + 'PC_PERF_PKR2_NUM_WAVES', 'PC_PERF_PKR2_PRIMS_PER_PROBE_EQ1', + 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT1', + 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT2', + 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT4', + 'PC_PERF_PKR2_PRIMS_PER_PROBE_GT8', + 'PC_PERF_PKR2_PRIMS_PER_WAVE_EQ1', + 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT1', + 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT2', + 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT4', + 'PC_PERF_PKR2_PRIMS_PER_WAVE_GT8', 'PC_PERF_PKR2_PRIMS_REUSE', + 'PC_PERF_PKR2_PROBES_PER_WAVE_EQ1', + 'PC_PERF_PKR2_PROBES_PER_WAVE_GT1', + 'PC_PERF_PKR2_PROBES_PER_WAVE_GT2', + 'PC_PERF_PKR2_PROBES_PER_WAVE_GT4', + 'PC_PERF_PKR2_PROBES_PER_WAVE_GT8', 'PC_PERF_PKR3_FPOSG_EQ1', + 'PC_PERF_PKR3_FPOSG_GT1', 'PC_PERF_PKR3_FPOSG_GT128', + 'PC_PERF_PKR3_FPOSG_GT16', 'PC_PERF_PKR3_FPOSG_GT64', + 'PC_PERF_PKR3_FPOSG_OUT_OF_WAVE', + 'PC_PERF_PKR3_GSDONE_WHILE_IDLE', 'PC_PERF_PKR3_NUM_PROBES', + 'PC_PERF_PKR3_NUM_WAVES', 'PC_PERF_PKR3_PRIMS_PER_PROBE_EQ1', + 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT1', + 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT2', + 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT4', + 'PC_PERF_PKR3_PRIMS_PER_PROBE_GT8', + 'PC_PERF_PKR3_PRIMS_PER_WAVE_EQ1', + 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT1', + 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT2', + 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT4', + 'PC_PERF_PKR3_PRIMS_PER_WAVE_GT8', 'PC_PERF_PKR3_PRIMS_REUSE', + 'PC_PERF_PKR3_PROBES_PER_WAVE_EQ1', + 'PC_PERF_PKR3_PROBES_PER_WAVE_GT1', + 'PC_PERF_PKR3_PROBES_PER_WAVE_GT2', + 'PC_PERF_PKR3_PROBES_PER_WAVE_GT4', + 'PC_PERF_PKR3_PROBES_PER_WAVE_GT8', 'PC_PERF_SC_FPOSG0', + 'PC_PERF_SC_FPOSG1', 'PC_PERF_SC_FPOSG2', 'PC_PERF_SC_FPOSG3', + 'PC_PERF_SC_FPOSG_WAIT0', 'PC_PERF_SC_FPOSG_WAIT1', + 'PC_PERF_SC_FPOSG_WAIT2', 'PC_PERF_SC_FPOSG_WAIT3', + 'PC_PERF_SC_MW_FREEZE', 'PC_PERF_SC_NUM_PROBES', + 'PC_PERF_SC_NUM_SPLIT_WAVES', 'PC_PERF_SC_NUM_WAVES', + 'PC_PERF_SC_PC_PTR_SEND0', 'PC_PERF_SC_PC_PTR_SEND1', + 'PC_PERF_SC_PC_PTR_SEND2', 'PC_PERF_SC_PC_PTR_SEND3', + 'PC_PERF_SC_PC_PTR_VALID0', 'PC_PERF_SC_PC_PTR_VALID1', + 'PC_PERF_SC_PC_PTR_VALID2', 'PC_PERF_SC_PC_PTR_VALID3', + 'PC_PERF_SC_PQ_FREEZE0', 'PC_PERF_SC_PQ_FREEZE1', + 'PC_PERF_SC_PQ_FREEZE2', 'PC_PERF_SC_PQ_FREEZE3', + 'PC_PERF_SC_WAIT_SYNC0', 'PC_PERF_SC_WAIT_SYNC1', + 'PC_PERF_SC_WAIT_SYNC2', 'PC_PERF_SC_WAIT_SYNC3', + 'PERFCOUNTER_ACTIVE', 'PERFCOUNTER_CNT0_STATE', + 'PERFCOUNTER_CNT0_STATE_FREEZE', 'PERFCOUNTER_CNT0_STATE_HW', + 'PERFCOUNTER_CNT0_STATE_RESET', 'PERFCOUNTER_CNT0_STATE_START', + 'PERFCOUNTER_CNT1_STATE', 'PERFCOUNTER_CNT1_STATE_FREEZE', + 'PERFCOUNTER_CNT1_STATE_HW', 'PERFCOUNTER_CNT1_STATE_RESET', + 'PERFCOUNTER_CNT1_STATE_START', 'PERFCOUNTER_CNT2_STATE', + 'PERFCOUNTER_CNT2_STATE_FREEZE', 'PERFCOUNTER_CNT2_STATE_HW', + 'PERFCOUNTER_CNT2_STATE_RESET', 'PERFCOUNTER_CNT2_STATE_START', + 'PERFCOUNTER_CNT3_STATE', 'PERFCOUNTER_CNT3_STATE_FREEZE', + 'PERFCOUNTER_CNT3_STATE_HW', 'PERFCOUNTER_CNT3_STATE_RESET', + 'PERFCOUNTER_CNT3_STATE_START', 'PERFCOUNTER_CNT4_STATE', + 'PERFCOUNTER_CNT4_STATE_FREEZE', 'PERFCOUNTER_CNT4_STATE_HW', + 'PERFCOUNTER_CNT4_STATE_RESET', 'PERFCOUNTER_CNT4_STATE_START', + 'PERFCOUNTER_CNT5_STATE', 'PERFCOUNTER_CNT5_STATE_FREEZE', + 'PERFCOUNTER_CNT5_STATE_HW', 'PERFCOUNTER_CNT5_STATE_RESET', + 'PERFCOUNTER_CNT5_STATE_START', 'PERFCOUNTER_CNT6_STATE', + 'PERFCOUNTER_CNT6_STATE_FREEZE', 'PERFCOUNTER_CNT6_STATE_HW', + 'PERFCOUNTER_CNT6_STATE_RESET', 'PERFCOUNTER_CNT6_STATE_START', + 'PERFCOUNTER_CNT7_STATE', 'PERFCOUNTER_CNT7_STATE_FREEZE', + 'PERFCOUNTER_CNT7_STATE_HW', 'PERFCOUNTER_CNT7_STATE_RESET', + 'PERFCOUNTER_CNT7_STATE_START', 'PERFCOUNTER_CNTL_SEL', + 'PERFCOUNTER_CNTL_SEL_0', 'PERFCOUNTER_CNTL_SEL_1', + 'PERFCOUNTER_CNTL_SEL_2', 'PERFCOUNTER_CNTL_SEL_3', + 'PERFCOUNTER_CNTL_SEL_4', 'PERFCOUNTER_CNTL_SEL_5', + 'PERFCOUNTER_CNTL_SEL_6', 'PERFCOUNTER_CNTL_SEL_7', + 'PERFCOUNTER_CNTOFF_START_DIS', + 'PERFCOUNTER_CNTOFF_START_DISABLE', + 'PERFCOUNTER_CNTOFF_START_ENABLE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', 'PERFCOUNTER_CVALUE_SEL', + 'PERFCOUNTER_CVALUE_SEL_11_0', 'PERFCOUNTER_CVALUE_SEL_15_0', + 'PERFCOUNTER_CVALUE_SEL_23_12', 'PERFCOUNTER_CVALUE_SEL_31_16', + 'PERFCOUNTER_CVALUE_SEL_35_24', 'PERFCOUNTER_CVALUE_SEL_47_0', + 'PERFCOUNTER_CVALUE_SEL_47_32', 'PERFCOUNTER_CVALUE_SEL_47_36', + 'PERFCOUNTER_HW_CNTL_SEL', 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', + 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', 'PERFCOUNTER_HW_STOP1_0', + 'PERFCOUNTER_HW_STOP1_1', 'PERFCOUNTER_HW_STOP1_SEL', + 'PERFCOUNTER_HW_STOP2_0', 'PERFCOUNTER_HW_STOP2_1', + 'PERFCOUNTER_HW_STOP2_SEL', 'PERFCOUNTER_INC_MODE', + 'PERFCOUNTER_INC_MODE_BOTH_EDGE', 'PERFCOUNTER_INC_MODE_LSB', + 'PERFCOUNTER_INC_MODE_MULTI_BIT', 'PERFCOUNTER_INC_MODE_NEG_EDGE', + 'PERFCOUNTER_INC_MODE_POS_EDGE', 'PERFCOUNTER_INT_DISABLE', + 'PERFCOUNTER_INT_EN', 'PERFCOUNTER_INT_ENABLE', + 'PERFCOUNTER_INT_TYPE', 'PERFCOUNTER_INT_TYPE_LEVEL', + 'PERFCOUNTER_INT_TYPE_PULSE', 'PERFCOUNTER_IS_ACTIVE', + 'PERFCOUNTER_IS_IDLE', 'PERFCOUNTER_OFF_MASK', + 'PERFCOUNTER_OFF_MASK_DISABLE', 'PERFCOUNTER_OFF_MASK_ENABLE', + 'PERFCOUNTER_RESTART_DISABLE', 'PERFCOUNTER_RESTART_EN', + 'PERFCOUNTER_RESTART_ENABLE', 'PERFCOUNTER_RUNEN_MODE', + 'PERFCOUNTER_RUNEN_MODE_EDGE', 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 'PERFCOUNTER_SAMPLE', 'PERFCOUNTER_START', + 'PERFCOUNTER_STATE_SEL0', 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 'PERFCOUNTER_STATE_SEL0_LOCAL', 'PERFCOUNTER_STATE_SEL1', + 'PERFCOUNTER_STATE_SEL1_GLOBAL', 'PERFCOUNTER_STATE_SEL1_LOCAL', + 'PERFCOUNTER_STATE_SEL2', 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 'PERFCOUNTER_STATE_SEL2_LOCAL', 'PERFCOUNTER_STATE_SEL3', + 'PERFCOUNTER_STATE_SEL3_GLOBAL', 'PERFCOUNTER_STATE_SEL3_LOCAL', + 'PERFCOUNTER_STATE_SEL4', 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 'PERFCOUNTER_STATE_SEL4_LOCAL', 'PERFCOUNTER_STATE_SEL5', + 'PERFCOUNTER_STATE_SEL5_GLOBAL', 'PERFCOUNTER_STATE_SEL5_LOCAL', + 'PERFCOUNTER_STATE_SEL6', 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 'PERFCOUNTER_STATE_SEL6_LOCAL', 'PERFCOUNTER_STATE_SEL7', + 'PERFCOUNTER_STATE_SEL7_GLOBAL', 'PERFCOUNTER_STATE_SEL7_LOCAL', + 'PERFCOUNTER_STOP', 'PERFMON_CNTOFF_AND', 'PERFMON_CNTOFF_AND_OR', + 'PERFMON_CNTOFF_INT_DISABLE', 'PERFMON_CNTOFF_INT_EN', + 'PERFMON_CNTOFF_INT_ENABLE', 'PERFMON_CNTOFF_INT_TYPE', + 'PERFMON_CNTOFF_INT_TYPE_LEVEL', 'PERFMON_CNTOFF_INT_TYPE_PULSE', + 'PERFMON_CNTOFF_OR', 'PERFMON_COUNTER_MODE', + 'PERFMON_COUNTER_MODE_ACCUM', + 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 'PERFMON_COUNTER_MODE_DIRTY', + 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_MAX', 'PERFMON_COUNTER_MODE_RESERVED', + 'PERFMON_COUNTER_MODE_SAMPLE', 'PERFMON_SPM_MODE', + 'PERFMON_SPM_MODE_16BIT_CLAMP', 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_32BIT_CLAMP', 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_OFF', 'PERFMON_SPM_MODE_RESERVED_5', + 'PERFMON_SPM_MODE_RESERVED_6', 'PERFMON_SPM_MODE_RESERVED_7', + 'PERFMON_SPM_MODE_TEST_MODE_0', 'PERFMON_SPM_MODE_TEST_MODE_1', + 'PERFMON_SPM_MODE_TEST_MODE_2', 'PERFMON_STATE', + 'PERFMON_STATE_FREEZE', 'PERFMON_STATE_HW', 'PERFMON_STATE_RESET', + 'PERFMON_STATE_START', 'PERF_CLIPSM_CULL_PRIMS_CNT', + 'PERF_CLPR_BACK_PRIM', 'PERF_CLPR_CLIP_PLANE_CNT_9_PLUS', + 'PERF_CLPR_INPUT_END_OF_PACKET', 'PERF_CLPR_INPUT_EVENT', + 'PERF_CLPR_INPUT_EXTENDED_EVENT', + 'PERF_CLPR_INPUT_FIRST_OF_SUBGROUP', 'PERF_CLPR_INPUT_NULL_PRIM', + 'PERF_CLPR_INPUT_PRIM', 'PERF_CLPR_INPUT_SEND', 'PERF_ENGG_BUSY', + 'PERF_ENGG_CSB_GE_INPUT_FIFO_FULL', + 'PERF_ENGG_CSB_GE_INPUT_FIFO_POP_BIT', + 'PERF_ENGG_CSB_GE_MEMORY_EMPTY', 'PERF_ENGG_CSB_GE_MEMORY_FULL', + 'PERF_ENGG_CSB_GE_SENDING_SUBGROUP', + 'PERF_ENGG_CSB_MACHINE_IS_STARVED', + 'PERF_ENGG_CSB_MACHINE_STALLED_BY_CSB_MEMORY', + 'PERF_ENGG_CSB_MACHINE_STALLED_BY_SPI', + 'PERF_ENGG_CSB_NULL_SUBGROUP', + 'PERF_ENGG_CSB_PAYLOAD_INPUT_FIFO_FULL', + 'PERF_ENGG_CSB_PRIM_COUNT_EQ0', 'PERF_ENGG_CSB_SPI_MEMORY_EMPTY', + 'PERF_ENGG_CSB_SPI_MEMORY_FULL', + 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_NO_WRITE', + 'PERF_ENGG_INDEX_PRIM_IF_FETCH_TO_PRIMIC_P_FIFO_WRITE', + 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_P_FIFO', + 'PERF_ENGG_INDEX_PRIM_IF_STALLED_BY_FULL_FETCH_TO_PRIMIC_S_FIFO', + 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_CSB', + 'PERF_ENGG_INDEX_PRIM_IF_STARVED_BY_NO_PRIM', + 'PERF_ENGG_INDEX_REQ_BUSY_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_REQ_IDLE_AND_STALLED_BY_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_REQ_NULL_REQUEST', + 'PERF_ENGG_INDEX_REQ_STALLED_BY_SX_CREDITS', + 'PERF_ENGG_INDEX_REQ_STARVED', 'PERF_ENGG_INDEX_RET0_NEW_VERTS', + 'PERF_ENGG_INDEX_RET10_NEW_VERTS', + 'PERF_ENGG_INDEX_RET11_NEW_VERTS', + 'PERF_ENGG_INDEX_RET12_NEW_VERTS', + 'PERF_ENGG_INDEX_RET1_NEW_VERTS', + 'PERF_ENGG_INDEX_RET2_NEW_VERTS', + 'PERF_ENGG_INDEX_RET3_NEW_VERTS', + 'PERF_ENGG_INDEX_RET4_NEW_VERTS', + 'PERF_ENGG_INDEX_RET5_NEW_VERTS', + 'PERF_ENGG_INDEX_RET6_NEW_VERTS', + 'PERF_ENGG_INDEX_RET7_NEW_VERTS', + 'PERF_ENGG_INDEX_RET8_NEW_VERTS', + 'PERF_ENGG_INDEX_RET9_NEW_VERTS', + 'PERF_ENGG_INDEX_RET_0_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_RET_1_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_RET_2_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_RET_3_NEW_VERTS_THIS_PRIM', + 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_EMPTY', + 'PERF_ENGG_INDEX_RET_REQ2RTN_FIFO_FULL', + 'PERF_ENGG_INDEX_RET_SXRX_NULL_DROPPER_STALLED_BY_FULL_PRIM_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_READING_EVENT', + 'PERF_ENGG_INDEX_RET_SXRX_READING_NULL_SUBGROUP', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_0_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_1_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_2_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_3_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_NOPL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_QDWORD_4_VALID_PRIMS_PL', + 'PERF_ENGG_INDEX_RET_SXRX_READING_SUBGROUP_PRIMCOUNT_EQ0', + 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_CSB_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_STALLED_BY_PRIM_INDICES_FIFO', + 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_CSB', + 'PERF_ENGG_INDEX_RET_SXRX_STARVED_BY_PRIMS', + 'PERF_ENGG_INDEX_RET_SX_RECEIVE_FIFO_FULL', + 'PERF_ENGG_POS_REQ_STARVED', 'PERF_OUTPUT_PRIM_1_SC', + 'PERF_OUTPUT_PRIM_2_SC', 'PERF_OUTPUT_PRIM_3_SC', + 'PERF_OUTPUT_PRIM_4_SC', 'PERF_OUTPUT_PRIM_5_SC', + 'PERF_OUTPUT_PRIM_6_SC', 'PERF_PAPC_CCGSM_BUSY', + 'PERF_PAPC_CCGSM_IDLE', 'PERF_PAPC_CCGSM_STALLED', + 'PERF_PAPC_CLIPGA_BUSY', 'PERF_PAPC_CLIPGA_IDLE', + 'PERF_PAPC_CLIPGA_STALLED', 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', 'PERF_PAPC_CLIPSM_BUSY', + 'PERF_PAPC_CLIPSM_IDLE', 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', 'PERF_PAPC_CLIP_BUSY', + 'PERF_PAPC_CLIP_IDLE', 'PERF_PAPC_CLPRIM_BUSY', + 'PERF_PAPC_CLPRIM_IDLE', 'PERF_PAPC_CLPRIM_STALLED', + 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', 'PERF_PAPC_CLPR_CULL_PRIM', + 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 'PERF_PAPC_CLPR_VV_CULL_PRIM', 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', 'PERF_PAPC_CLSM_NULL_PRIM', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_PLUS', + 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 'PERF_PAPC_CL_DYN_SCLK_VLD', 'PERF_PAPC_PASX_REC_BUSY', + 'PERF_PAPC_PASX_REC_IDLE', 'PERF_PAPC_PASX_REC_STALLED', + 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 'PERF_PAPC_PASX_REC_STARVED_SX', 'PERF_PAPC_PASX_REQ', + 'PERF_PAPC_PASX_REQ_BUSY', 'PERF_PAPC_PASX_REQ_IDLE', + 'PERF_PAPC_PASX_REQ_STALLED', 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 'PERF_PAPC_PASX_VTX_NAN_DISCARD', 'PERF_PAPC_PA_REG_SCLK_VLD', + 'PERF_PAPC_SU_ALL_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_ALL_OUTPUT_PRIM', 'PERF_PAPC_SU_ALL_STALLED_SC', + 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', 'PERF_PAPC_SU_BUSY', + 'PERF_PAPC_SU_CULLED_PRIM', 'PERF_PAPC_SU_DYN_SCLK_VLD', + 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', 'PERF_PAPC_SU_IDLE', + 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_INPUT_NULL_PRIM', 'PERF_PAPC_SU_INPUT_PRIM', + 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', 'PERF_PAPC_SU_OUTPUT_EOPG', + 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', 'PERF_PAPC_SU_OUTPUT_PRIM', + 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE0_STALLED_SC', + 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE1_STALLED_SC', + 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE2_STALLED_SC', + 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE3_STALLED_SC', + 'PERF_PAPC_SU_SE4_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE4_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE4_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE4_STALLED_SC', + 'PERF_PAPC_SU_SE5_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE5_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE5_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE5_STALLED_SC', 'PERF_PAPC_SU_STALLED_SC', + 'PERF_PAPC_SU_STARVED_CLIP', 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 'PERF_PASX_CCDIST0_VECTOR', 'PERF_PASX_CCDIST1_VECTOR', + 'PERF_PASX_MISC_VECTOR', 'PERF_PASX_POS_VECTOR', + 'PERF_PASX_STEREO_POS_VECTOR', 'PERF_PA_BUSY', + 'PERF_PA_FETCH_TO_PRIMIC_P_FIFO_FULL', + 'PERF_PA_PRIMIC_TO_CLPRIM_FIFO_FULL', 'PERF_PA_VERTEX_FIFO_FULL', + 'PERF_PH_SEND_1_SC', 'PERF_PH_SEND_2_SC', 'PERF_PH_SEND_3_SC', + 'PERF_PH_SEND_4_SC', 'PERF_PH_SEND_5_SC', 'PERF_PH_SEND_6_SC', + 'PERF_SC0_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC0_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC1_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC2_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_BUSY_EVENT', + 'PERF_SC3_QUALIFIED_SEND_NOT_BUSY_EVENT', + 'PERF_SMALL_PRIM_CULL_PRIM_1X1', 'PERF_SMALL_PRIM_CULL_PRIM_1X2', + 'PERF_SMALL_PRIM_CULL_PRIM_1X3', 'PERF_SMALL_PRIM_CULL_PRIM_1XN', + 'PERF_SMALL_PRIM_CULL_PRIM_2X1', 'PERF_SMALL_PRIM_CULL_PRIM_2X2', + 'PERF_SMALL_PRIM_CULL_PRIM_2X3', 'PERF_SMALL_PRIM_CULL_PRIM_2XN', + 'PERF_SMALL_PRIM_CULL_PRIM_3X1', 'PERF_SMALL_PRIM_CULL_PRIM_3X2', + 'PERF_SMALL_PRIM_CULL_PRIM_NX1', 'PERF_SMALL_PRIM_CULL_PRIM_NX2', + 'PERF_SU_INPUT_SEND', 'PERF_SU_OUTPUT_SEND', + 'PERF_SU_SMALL_PRIM_FILTER_CULL_CNT', 'PERSISTENT_SPACE_END', + 'PERSISTENT_SPACE_START', 'PFVF_SQDEC_BEGIN', 'PFVF_SQDEC_END', + 'PHYSYMCLK_FORCE_EN', 'PHYSYMCLK_FORCE_EN_DISABLE', + 'PHYSYMCLK_FORCE_EN_ENABLE', 'PHYSYMCLK_FORCE_SRC_PHYD18CLK', + 'PHYSYMCLK_FORCE_SRC_PHYD32CLK', 'PHYSYMCLK_FORCE_SRC_SEL', + 'PHYSYMCLK_FORCE_SRC_SYMCLK', 'PHY_MUX_ENABLE_ENUM', + 'PHY_MUX_ENABLE_ENUM_DISABLED', 'PHY_MUX_ENABLE_ENUM_ENABLED', + 'PH_PERFCNT_SEL', 'PH_PERF_SC0_FIFO_STATUS_0', + 'PH_PERF_SC0_FIFO_STATUS_1', 'PH_PERF_SC0_FIFO_STATUS_2', + 'PH_PERF_SC0_FIFO_STATUS_3', 'PH_PERF_SC1_FIFO_STATUS_0', + 'PH_PERF_SC1_FIFO_STATUS_1', 'PH_PERF_SC1_FIFO_STATUS_2', + 'PH_PERF_SC1_FIFO_STATUS_3', 'PH_PERF_SC2_FIFO_STATUS_0', + 'PH_PERF_SC2_FIFO_STATUS_1', 'PH_PERF_SC2_FIFO_STATUS_2', + 'PH_PERF_SC2_FIFO_STATUS_3', 'PH_PERF_SC3_FIFO_STATUS_0', + 'PH_PERF_SC3_FIFO_STATUS_1', 'PH_PERF_SC3_FIFO_STATUS_2', + 'PH_PERF_SC3_FIFO_STATUS_3', 'PH_PERF_SC4_FIFO_STATUS_0', + 'PH_PERF_SC4_FIFO_STATUS_1', 'PH_PERF_SC4_FIFO_STATUS_2', + 'PH_PERF_SC4_FIFO_STATUS_3', 'PH_PERF_SC5_FIFO_STATUS_0', + 'PH_PERF_SC5_FIFO_STATUS_1', 'PH_PERF_SC5_FIFO_STATUS_2', + 'PH_PERF_SC5_FIFO_STATUS_3', 'PH_PERF_SC6_FIFO_STATUS_0', + 'PH_PERF_SC6_FIFO_STATUS_1', 'PH_PERF_SC6_FIFO_STATUS_2', + 'PH_PERF_SC6_FIFO_STATUS_3', 'PH_PERF_SC7_FIFO_STATUS_0', + 'PH_PERF_SC7_FIFO_STATUS_1', 'PH_PERF_SC7_FIFO_STATUS_2', + 'PH_PERF_SC7_FIFO_STATUS_3', + 'PH_PERF_SEL_1_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_1_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_2_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_2_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_3_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_3_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_4_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_4_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_5_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_5_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_6_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_6_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_7_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_7_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_8_SC_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_8_SC_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC0_ARB_BUSY', + 'PH_PERF_SEL_SC0_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC0_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC0_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC0_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC0_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC0_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC0_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC0_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC0_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC0_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC0_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC0_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC0_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC0_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC0_GFX_PIPE_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA0_EOPG_WE', + 'PH_PERF_SEL_SC0_PA0_EOP_WE', 'PH_PERF_SEL_SC0_PA0_EVENT_WE', + 'PH_PERF_SEL_SC0_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA0_FPOP_WE', 'PH_PERF_SEL_SC0_PA0_FPOV_WE', + 'PH_PERF_SEL_SC0_PA0_NULL_WE', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA1_EOPG_WE', + 'PH_PERF_SEL_SC0_PA1_EOP_WE', 'PH_PERF_SEL_SC0_PA1_EVENT_WE', + 'PH_PERF_SEL_SC0_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA1_FPOP_WE', 'PH_PERF_SEL_SC0_PA1_FPOV_WE', + 'PH_PERF_SEL_SC0_PA1_NULL_WE', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA2_EOPG_WE', + 'PH_PERF_SEL_SC0_PA2_EOP_WE', 'PH_PERF_SEL_SC0_PA2_EVENT_WE', + 'PH_PERF_SEL_SC0_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA2_FPOP_WE', 'PH_PERF_SEL_SC0_PA2_FPOV_WE', + 'PH_PERF_SEL_SC0_PA2_NULL_WE', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA3_EOPG_WE', + 'PH_PERF_SEL_SC0_PA3_EOP_WE', 'PH_PERF_SEL_SC0_PA3_EVENT_WE', + 'PH_PERF_SEL_SC0_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA3_FPOP_WE', 'PH_PERF_SEL_SC0_PA3_FPOV_WE', + 'PH_PERF_SEL_SC0_PA3_NULL_WE', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA4_EOPG_WE', + 'PH_PERF_SEL_SC0_PA4_EOP_WE', 'PH_PERF_SEL_SC0_PA4_EVENT_WE', + 'PH_PERF_SEL_SC0_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA4_FPOP_WE', 'PH_PERF_SEL_SC0_PA4_FPOV_WE', + 'PH_PERF_SEL_SC0_PA4_NULL_WE', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA5_EOPG_WE', + 'PH_PERF_SEL_SC0_PA5_EOP_WE', 'PH_PERF_SEL_SC0_PA5_EVENT_WE', + 'PH_PERF_SEL_SC0_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA5_FPOP_WE', 'PH_PERF_SEL_SC0_PA5_FPOV_WE', + 'PH_PERF_SEL_SC0_PA5_NULL_WE', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA6_EOPG_WE', + 'PH_PERF_SEL_SC0_PA6_EOP_WE', 'PH_PERF_SEL_SC0_PA6_EVENT_WE', + 'PH_PERF_SEL_SC0_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA6_FPOP_WE', 'PH_PERF_SEL_SC0_PA6_FPOV_WE', + 'PH_PERF_SEL_SC0_PA6_NULL_WE', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC0_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC0_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC0_PA7_EOPG_WE', + 'PH_PERF_SEL_SC0_PA7_EOP_WE', 'PH_PERF_SEL_SC0_PA7_EVENT_WE', + 'PH_PERF_SEL_SC0_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC0_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC0_PA7_FPOP_WE', 'PH_PERF_SEL_SC0_PA7_FPOV_WE', + 'PH_PERF_SEL_SC0_PA7_NULL_WE', + 'PH_PERF_SEL_SC0_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC0_SEND', 'PH_PERF_SEL_SC0_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC1_ARB_BUSY', + 'PH_PERF_SEL_SC1_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC1_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC1_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC1_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC1_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC1_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC1_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC1_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC1_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC1_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC1_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC1_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC1_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC1_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC1_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA0_EOPG_WE', + 'PH_PERF_SEL_SC1_PA0_EOP_WE', 'PH_PERF_SEL_SC1_PA0_EVENT_WE', + 'PH_PERF_SEL_SC1_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA0_FPOP_WE', 'PH_PERF_SEL_SC1_PA0_FPOV_WE', + 'PH_PERF_SEL_SC1_PA0_NULL_WE', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA1_EOPG_WE', + 'PH_PERF_SEL_SC1_PA1_EOP_WE', 'PH_PERF_SEL_SC1_PA1_EVENT_WE', + 'PH_PERF_SEL_SC1_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA1_FPOP_WE', 'PH_PERF_SEL_SC1_PA1_FPOV_WE', + 'PH_PERF_SEL_SC1_PA1_NULL_WE', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA2_EOPG_WE', + 'PH_PERF_SEL_SC1_PA2_EOP_WE', 'PH_PERF_SEL_SC1_PA2_EVENT_WE', + 'PH_PERF_SEL_SC1_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA2_FPOP_WE', 'PH_PERF_SEL_SC1_PA2_FPOV_WE', + 'PH_PERF_SEL_SC1_PA2_NULL_WE', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA3_EOPG_WE', + 'PH_PERF_SEL_SC1_PA3_EOP_WE', 'PH_PERF_SEL_SC1_PA3_EVENT_WE', + 'PH_PERF_SEL_SC1_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA3_FPOP_WE', 'PH_PERF_SEL_SC1_PA3_FPOV_WE', + 'PH_PERF_SEL_SC1_PA3_NULL_WE', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA4_EOPG_WE', + 'PH_PERF_SEL_SC1_PA4_EOP_WE', 'PH_PERF_SEL_SC1_PA4_EVENT_WE', + 'PH_PERF_SEL_SC1_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA4_FPOP_WE', 'PH_PERF_SEL_SC1_PA4_FPOV_WE', + 'PH_PERF_SEL_SC1_PA4_NULL_WE', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA5_EOPG_WE', + 'PH_PERF_SEL_SC1_PA5_EOP_WE', 'PH_PERF_SEL_SC1_PA5_EVENT_WE', + 'PH_PERF_SEL_SC1_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA5_FPOP_WE', 'PH_PERF_SEL_SC1_PA5_FPOV_WE', + 'PH_PERF_SEL_SC1_PA5_NULL_WE', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA6_EOPG_WE', + 'PH_PERF_SEL_SC1_PA6_EOP_WE', 'PH_PERF_SEL_SC1_PA6_EVENT_WE', + 'PH_PERF_SEL_SC1_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA6_FPOP_WE', 'PH_PERF_SEL_SC1_PA6_FPOV_WE', + 'PH_PERF_SEL_SC1_PA6_NULL_WE', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC1_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC1_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC1_PA7_EOPG_WE', + 'PH_PERF_SEL_SC1_PA7_EOP_WE', 'PH_PERF_SEL_SC1_PA7_EVENT_WE', + 'PH_PERF_SEL_SC1_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC1_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC1_PA7_FPOP_WE', 'PH_PERF_SEL_SC1_PA7_FPOV_WE', + 'PH_PERF_SEL_SC1_PA7_NULL_WE', + 'PH_PERF_SEL_SC1_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC1_SEND', 'PH_PERF_SEL_SC1_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC2_ARB_BUSY', + 'PH_PERF_SEL_SC2_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC2_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC2_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC2_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC2_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC2_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC2_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC2_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC2_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC2_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC2_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC2_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC2_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC2_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC2_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA0_EOPG_WE', + 'PH_PERF_SEL_SC2_PA0_EOP_WE', 'PH_PERF_SEL_SC2_PA0_EVENT_WE', + 'PH_PERF_SEL_SC2_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA0_FPOP_WE', 'PH_PERF_SEL_SC2_PA0_FPOV_WE', + 'PH_PERF_SEL_SC2_PA0_NULL_WE', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA1_EOPG_WE', + 'PH_PERF_SEL_SC2_PA1_EOP_WE', 'PH_PERF_SEL_SC2_PA1_EVENT_WE', + 'PH_PERF_SEL_SC2_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA1_FPOP_WE', 'PH_PERF_SEL_SC2_PA1_FPOV_WE', + 'PH_PERF_SEL_SC2_PA1_NULL_WE', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA2_EOPG_WE', + 'PH_PERF_SEL_SC2_PA2_EOP_WE', 'PH_PERF_SEL_SC2_PA2_EVENT_WE', + 'PH_PERF_SEL_SC2_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA2_FPOP_WE', 'PH_PERF_SEL_SC2_PA2_FPOV_WE', + 'PH_PERF_SEL_SC2_PA2_NULL_WE', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA3_EOPG_WE', + 'PH_PERF_SEL_SC2_PA3_EOP_WE', 'PH_PERF_SEL_SC2_PA3_EVENT_WE', + 'PH_PERF_SEL_SC2_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA3_FPOP_WE', 'PH_PERF_SEL_SC2_PA3_FPOV_WE', + 'PH_PERF_SEL_SC2_PA3_NULL_WE', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA4_EOPG_WE', + 'PH_PERF_SEL_SC2_PA4_EOP_WE', 'PH_PERF_SEL_SC2_PA4_EVENT_WE', + 'PH_PERF_SEL_SC2_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA4_FPOP_WE', 'PH_PERF_SEL_SC2_PA4_FPOV_WE', + 'PH_PERF_SEL_SC2_PA4_NULL_WE', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA5_EOPG_WE', + 'PH_PERF_SEL_SC2_PA5_EOP_WE', 'PH_PERF_SEL_SC2_PA5_EVENT_WE', + 'PH_PERF_SEL_SC2_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA5_FPOP_WE', 'PH_PERF_SEL_SC2_PA5_FPOV_WE', + 'PH_PERF_SEL_SC2_PA5_NULL_WE', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA6_EOPG_WE', + 'PH_PERF_SEL_SC2_PA6_EOP_WE', 'PH_PERF_SEL_SC2_PA6_EVENT_WE', + 'PH_PERF_SEL_SC2_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA6_FPOP_WE', 'PH_PERF_SEL_SC2_PA6_FPOV_WE', + 'PH_PERF_SEL_SC2_PA6_NULL_WE', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC2_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC2_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC2_PA7_EOPG_WE', + 'PH_PERF_SEL_SC2_PA7_EOP_WE', 'PH_PERF_SEL_SC2_PA7_EVENT_WE', + 'PH_PERF_SEL_SC2_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC2_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC2_PA7_FPOP_WE', 'PH_PERF_SEL_SC2_PA7_FPOV_WE', + 'PH_PERF_SEL_SC2_PA7_NULL_WE', + 'PH_PERF_SEL_SC2_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC2_SEND', 'PH_PERF_SEL_SC2_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC3_ARB_BUSY', + 'PH_PERF_SEL_SC3_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC3_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC3_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC3_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC3_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC3_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC3_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC3_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC3_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC3_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC3_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC3_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC3_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC3_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC3_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA0_EOPG_WE', + 'PH_PERF_SEL_SC3_PA0_EOP_WE', 'PH_PERF_SEL_SC3_PA0_EVENT_WE', + 'PH_PERF_SEL_SC3_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA0_FPOP_WE', 'PH_PERF_SEL_SC3_PA0_FPOV_WE', + 'PH_PERF_SEL_SC3_PA0_NULL_WE', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA1_EOPG_WE', + 'PH_PERF_SEL_SC3_PA1_EOP_WE', 'PH_PERF_SEL_SC3_PA1_EVENT_WE', + 'PH_PERF_SEL_SC3_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA1_FPOP_WE', 'PH_PERF_SEL_SC3_PA1_FPOV_WE', + 'PH_PERF_SEL_SC3_PA1_NULL_WE', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA2_EOPG_WE', + 'PH_PERF_SEL_SC3_PA2_EOP_WE', 'PH_PERF_SEL_SC3_PA2_EVENT_WE', + 'PH_PERF_SEL_SC3_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA2_FPOP_WE', 'PH_PERF_SEL_SC3_PA2_FPOV_WE', + 'PH_PERF_SEL_SC3_PA2_NULL_WE', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA3_EOPG_WE', + 'PH_PERF_SEL_SC3_PA3_EOP_WE', 'PH_PERF_SEL_SC3_PA3_EVENT_WE', + 'PH_PERF_SEL_SC3_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA3_FPOP_WE', 'PH_PERF_SEL_SC3_PA3_FPOV_WE', + 'PH_PERF_SEL_SC3_PA3_NULL_WE', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA4_EOPG_WE', + 'PH_PERF_SEL_SC3_PA4_EOP_WE', 'PH_PERF_SEL_SC3_PA4_EVENT_WE', + 'PH_PERF_SEL_SC3_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA4_FPOP_WE', 'PH_PERF_SEL_SC3_PA4_FPOV_WE', + 'PH_PERF_SEL_SC3_PA4_NULL_WE', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA5_EOPG_WE', + 'PH_PERF_SEL_SC3_PA5_EOP_WE', 'PH_PERF_SEL_SC3_PA5_EVENT_WE', + 'PH_PERF_SEL_SC3_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA5_FPOP_WE', 'PH_PERF_SEL_SC3_PA5_FPOV_WE', + 'PH_PERF_SEL_SC3_PA5_NULL_WE', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA6_EOPG_WE', + 'PH_PERF_SEL_SC3_PA6_EOP_WE', 'PH_PERF_SEL_SC3_PA6_EVENT_WE', + 'PH_PERF_SEL_SC3_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA6_FPOP_WE', 'PH_PERF_SEL_SC3_PA6_FPOV_WE', + 'PH_PERF_SEL_SC3_PA6_NULL_WE', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC3_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC3_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC3_PA7_EOPG_WE', + 'PH_PERF_SEL_SC3_PA7_EOP_WE', 'PH_PERF_SEL_SC3_PA7_EVENT_WE', + 'PH_PERF_SEL_SC3_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC3_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC3_PA7_FPOP_WE', 'PH_PERF_SEL_SC3_PA7_FPOV_WE', + 'PH_PERF_SEL_SC3_PA7_NULL_WE', + 'PH_PERF_SEL_SC3_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC3_SEND', 'PH_PERF_SEL_SC3_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC4_ARB_BUSY', + 'PH_PERF_SEL_SC4_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC4_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC4_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC4_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC4_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC4_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC4_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC4_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC4_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC4_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC4_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC4_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC4_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC4_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC4_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA0_EOPG_WE', + 'PH_PERF_SEL_SC4_PA0_EOP_WE', 'PH_PERF_SEL_SC4_PA0_EVENT_WE', + 'PH_PERF_SEL_SC4_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA0_FPOP_WE', 'PH_PERF_SEL_SC4_PA0_FPOV_WE', + 'PH_PERF_SEL_SC4_PA0_NULL_WE', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA1_EOPG_WE', + 'PH_PERF_SEL_SC4_PA1_EOP_WE', 'PH_PERF_SEL_SC4_PA1_EVENT_WE', + 'PH_PERF_SEL_SC4_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA1_FPOP_WE', 'PH_PERF_SEL_SC4_PA1_FPOV_WE', + 'PH_PERF_SEL_SC4_PA1_NULL_WE', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA2_EOPG_WE', + 'PH_PERF_SEL_SC4_PA2_EOP_WE', 'PH_PERF_SEL_SC4_PA2_EVENT_WE', + 'PH_PERF_SEL_SC4_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA2_FPOP_WE', 'PH_PERF_SEL_SC4_PA2_FPOV_WE', + 'PH_PERF_SEL_SC4_PA2_NULL_WE', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA3_EOPG_WE', + 'PH_PERF_SEL_SC4_PA3_EOP_WE', 'PH_PERF_SEL_SC4_PA3_EVENT_WE', + 'PH_PERF_SEL_SC4_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA3_FPOP_WE', 'PH_PERF_SEL_SC4_PA3_FPOV_WE', + 'PH_PERF_SEL_SC4_PA3_NULL_WE', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA4_EOPG_WE', + 'PH_PERF_SEL_SC4_PA4_EOP_WE', 'PH_PERF_SEL_SC4_PA4_EVENT_WE', + 'PH_PERF_SEL_SC4_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA4_FPOP_WE', 'PH_PERF_SEL_SC4_PA4_FPOV_WE', + 'PH_PERF_SEL_SC4_PA4_NULL_WE', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA5_EOPG_WE', + 'PH_PERF_SEL_SC4_PA5_EOP_WE', 'PH_PERF_SEL_SC4_PA5_EVENT_WE', + 'PH_PERF_SEL_SC4_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA5_FPOP_WE', 'PH_PERF_SEL_SC4_PA5_FPOV_WE', + 'PH_PERF_SEL_SC4_PA5_NULL_WE', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA6_EOPG_WE', + 'PH_PERF_SEL_SC4_PA6_EOP_WE', 'PH_PERF_SEL_SC4_PA6_EVENT_WE', + 'PH_PERF_SEL_SC4_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA6_FPOP_WE', 'PH_PERF_SEL_SC4_PA6_FPOV_WE', + 'PH_PERF_SEL_SC4_PA6_NULL_WE', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC4_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC4_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC4_PA7_EOPG_WE', + 'PH_PERF_SEL_SC4_PA7_EOP_WE', 'PH_PERF_SEL_SC4_PA7_EVENT_WE', + 'PH_PERF_SEL_SC4_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC4_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC4_PA7_FPOP_WE', 'PH_PERF_SEL_SC4_PA7_FPOV_WE', + 'PH_PERF_SEL_SC4_PA7_NULL_WE', + 'PH_PERF_SEL_SC4_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC4_SEND', 'PH_PERF_SEL_SC4_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC5_ARB_BUSY', + 'PH_PERF_SEL_SC5_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC5_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC5_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC5_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC5_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC5_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC5_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC5_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC5_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC5_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC5_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC5_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC5_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC5_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC5_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA0_EOPG_WE', + 'PH_PERF_SEL_SC5_PA0_EOP_WE', 'PH_PERF_SEL_SC5_PA0_EVENT_WE', + 'PH_PERF_SEL_SC5_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA0_FPOP_WE', 'PH_PERF_SEL_SC5_PA0_FPOV_WE', + 'PH_PERF_SEL_SC5_PA0_NULL_WE', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA1_EOPG_WE', + 'PH_PERF_SEL_SC5_PA1_EOP_WE', 'PH_PERF_SEL_SC5_PA1_EVENT_WE', + 'PH_PERF_SEL_SC5_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA1_FPOP_WE', 'PH_PERF_SEL_SC5_PA1_FPOV_WE', + 'PH_PERF_SEL_SC5_PA1_NULL_WE', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA2_EOPG_WE', + 'PH_PERF_SEL_SC5_PA2_EOP_WE', 'PH_PERF_SEL_SC5_PA2_EVENT_WE', + 'PH_PERF_SEL_SC5_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA2_FPOP_WE', 'PH_PERF_SEL_SC5_PA2_FPOV_WE', + 'PH_PERF_SEL_SC5_PA2_NULL_WE', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA3_EOPG_WE', + 'PH_PERF_SEL_SC5_PA3_EOP_WE', 'PH_PERF_SEL_SC5_PA3_EVENT_WE', + 'PH_PERF_SEL_SC5_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA3_FPOP_WE', 'PH_PERF_SEL_SC5_PA3_FPOV_WE', + 'PH_PERF_SEL_SC5_PA3_NULL_WE', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA4_EOPG_WE', + 'PH_PERF_SEL_SC5_PA4_EOP_WE', 'PH_PERF_SEL_SC5_PA4_EVENT_WE', + 'PH_PERF_SEL_SC5_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA4_FPOP_WE', 'PH_PERF_SEL_SC5_PA4_FPOV_WE', + 'PH_PERF_SEL_SC5_PA4_NULL_WE', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA5_EOPG_WE', + 'PH_PERF_SEL_SC5_PA5_EOP_WE', 'PH_PERF_SEL_SC5_PA5_EVENT_WE', + 'PH_PERF_SEL_SC5_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA5_FPOP_WE', 'PH_PERF_SEL_SC5_PA5_FPOV_WE', + 'PH_PERF_SEL_SC5_PA5_NULL_WE', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA6_EOPG_WE', + 'PH_PERF_SEL_SC5_PA6_EOP_WE', 'PH_PERF_SEL_SC5_PA6_EVENT_WE', + 'PH_PERF_SEL_SC5_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA6_FPOP_WE', 'PH_PERF_SEL_SC5_PA6_FPOV_WE', + 'PH_PERF_SEL_SC5_PA6_NULL_WE', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC5_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC5_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC5_PA7_EOPG_WE', + 'PH_PERF_SEL_SC5_PA7_EOP_WE', 'PH_PERF_SEL_SC5_PA7_EVENT_WE', + 'PH_PERF_SEL_SC5_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC5_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC5_PA7_FPOP_WE', 'PH_PERF_SEL_SC5_PA7_FPOV_WE', + 'PH_PERF_SEL_SC5_PA7_NULL_WE', + 'PH_PERF_SEL_SC5_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC5_SEND', 'PH_PERF_SEL_SC5_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC6_ARB_BUSY', + 'PH_PERF_SEL_SC6_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC6_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC6_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC6_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC6_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC6_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC6_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC6_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC6_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC6_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC6_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC6_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC6_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC6_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC6_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA0_EOPG_WE', + 'PH_PERF_SEL_SC6_PA0_EOP_WE', 'PH_PERF_SEL_SC6_PA0_EVENT_WE', + 'PH_PERF_SEL_SC6_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA0_FPOP_WE', 'PH_PERF_SEL_SC6_PA0_FPOV_WE', + 'PH_PERF_SEL_SC6_PA0_NULL_WE', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA1_EOPG_WE', + 'PH_PERF_SEL_SC6_PA1_EOP_WE', 'PH_PERF_SEL_SC6_PA1_EVENT_WE', + 'PH_PERF_SEL_SC6_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA1_FPOP_WE', 'PH_PERF_SEL_SC6_PA1_FPOV_WE', + 'PH_PERF_SEL_SC6_PA1_NULL_WE', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA2_EOPG_WE', + 'PH_PERF_SEL_SC6_PA2_EOP_WE', 'PH_PERF_SEL_SC6_PA2_EVENT_WE', + 'PH_PERF_SEL_SC6_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA2_FPOP_WE', 'PH_PERF_SEL_SC6_PA2_FPOV_WE', + 'PH_PERF_SEL_SC6_PA2_NULL_WE', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA3_EOPG_WE', + 'PH_PERF_SEL_SC6_PA3_EOP_WE', 'PH_PERF_SEL_SC6_PA3_EVENT_WE', + 'PH_PERF_SEL_SC6_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA3_FPOP_WE', 'PH_PERF_SEL_SC6_PA3_FPOV_WE', + 'PH_PERF_SEL_SC6_PA3_NULL_WE', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA4_EOPG_WE', + 'PH_PERF_SEL_SC6_PA4_EOP_WE', 'PH_PERF_SEL_SC6_PA4_EVENT_WE', + 'PH_PERF_SEL_SC6_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA4_FPOP_WE', 'PH_PERF_SEL_SC6_PA4_FPOV_WE', + 'PH_PERF_SEL_SC6_PA4_NULL_WE', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA5_EOPG_WE', + 'PH_PERF_SEL_SC6_PA5_EOP_WE', 'PH_PERF_SEL_SC6_PA5_EVENT_WE', + 'PH_PERF_SEL_SC6_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA5_FPOP_WE', 'PH_PERF_SEL_SC6_PA5_FPOV_WE', + 'PH_PERF_SEL_SC6_PA5_NULL_WE', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA6_EOPG_WE', + 'PH_PERF_SEL_SC6_PA6_EOP_WE', 'PH_PERF_SEL_SC6_PA6_EVENT_WE', + 'PH_PERF_SEL_SC6_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA6_FPOP_WE', 'PH_PERF_SEL_SC6_PA6_FPOV_WE', + 'PH_PERF_SEL_SC6_PA6_NULL_WE', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC6_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC6_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC6_PA7_EOPG_WE', + 'PH_PERF_SEL_SC6_PA7_EOP_WE', 'PH_PERF_SEL_SC6_PA7_EVENT_WE', + 'PH_PERF_SEL_SC6_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC6_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC6_PA7_FPOP_WE', 'PH_PERF_SEL_SC6_PA7_FPOV_WE', + 'PH_PERF_SEL_SC6_PA7_NULL_WE', + 'PH_PERF_SEL_SC6_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC6_SEND', 'PH_PERF_SEL_SC6_SRPS_WINDOW_VALID', + 'PH_PERF_SEL_SC7_ARB_BUSY', + 'PH_PERF_SEL_SC7_ARB_EOP_POP_SYNC_POP', + 'PH_PERF_SEL_SC7_ARB_EVENT_SYNC_POP', + 'PH_PERF_SEL_SC7_ARB_PA_BUSY_SOP', + 'PH_PERF_SEL_SC7_ARB_STALLED_FROM_BELOW', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_FULL', + 'PH_PERF_SEL_SC7_ARB_STARVED_FROM_ABOVE_WITH_UNSELECTED_FIFO_NOT_EMPTY', + 'PH_PERF_SEL_SC7_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'PH_PERF_SEL_SC7_ARB_XFC_ONLY_PRIM_CYCLES', + 'PH_PERF_SEL_SC7_BUSY_CNT_NOT_ZERO', + 'PH_PERF_SEL_SC7_BUSY_PROCESSING_MULTICYCLE_PRIM', + 'PH_PERF_SEL_SC7_CREDIT_AT_MAX', + 'PH_PERF_SEL_SC7_CREDIT_AT_MAX_NO_PENDING_SEND', + 'PH_PERF_SEL_SC7_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'PH_PERF_SEL_SC7_EOP_SYNC_WINDOW', + 'PH_PERF_SEL_SC7_GFX_PIPE0_TO_1_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE1_TO_0_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE_EOP_PRIM_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC7_GFX_PIPE_EVENT_PROVOKED_TRANSITION', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA0_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA0_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA0_EOPG_WE', + 'PH_PERF_SEL_SC7_PA0_EOP_WE', 'PH_PERF_SEL_SC7_PA0_EVENT_WE', + 'PH_PERF_SEL_SC7_PA0_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA0_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA0_FPOP_WE', 'PH_PERF_SEL_SC7_PA0_FPOV_WE', + 'PH_PERF_SEL_SC7_PA0_NULL_WE', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA1_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA1_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA1_EOPG_WE', + 'PH_PERF_SEL_SC7_PA1_EOP_WE', 'PH_PERF_SEL_SC7_PA1_EVENT_WE', + 'PH_PERF_SEL_SC7_PA1_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA1_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA1_FPOP_WE', 'PH_PERF_SEL_SC7_PA1_FPOV_WE', + 'PH_PERF_SEL_SC7_PA1_NULL_WE', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA2_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA2_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA2_EOPG_WE', + 'PH_PERF_SEL_SC7_PA2_EOP_WE', 'PH_PERF_SEL_SC7_PA2_EVENT_WE', + 'PH_PERF_SEL_SC7_PA2_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA2_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA2_FPOP_WE', 'PH_PERF_SEL_SC7_PA2_FPOV_WE', + 'PH_PERF_SEL_SC7_PA2_NULL_WE', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA3_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA3_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA3_EOPG_WE', + 'PH_PERF_SEL_SC7_PA3_EOP_WE', 'PH_PERF_SEL_SC7_PA3_EVENT_WE', + 'PH_PERF_SEL_SC7_PA3_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA3_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA3_FPOP_WE', 'PH_PERF_SEL_SC7_PA3_FPOV_WE', + 'PH_PERF_SEL_SC7_PA3_NULL_WE', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA4_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA4_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA4_EOPG_WE', + 'PH_PERF_SEL_SC7_PA4_EOP_WE', 'PH_PERF_SEL_SC7_PA4_EVENT_WE', + 'PH_PERF_SEL_SC7_PA4_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA4_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA4_FPOP_WE', 'PH_PERF_SEL_SC7_PA4_FPOV_WE', + 'PH_PERF_SEL_SC7_PA4_NULL_WE', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA5_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA5_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA5_EOPG_WE', + 'PH_PERF_SEL_SC7_PA5_EOP_WE', 'PH_PERF_SEL_SC7_PA5_EVENT_WE', + 'PH_PERF_SEL_SC7_PA5_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA5_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA5_FPOP_WE', 'PH_PERF_SEL_SC7_PA5_FPOV_WE', + 'PH_PERF_SEL_SC7_PA5_NULL_WE', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA6_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA6_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA6_EOPG_WE', + 'PH_PERF_SEL_SC7_PA6_EOP_WE', 'PH_PERF_SEL_SC7_PA6_EVENT_WE', + 'PH_PERF_SEL_SC7_PA6_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA6_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA6_FPOP_WE', 'PH_PERF_SEL_SC7_PA6_FPOV_WE', + 'PH_PERF_SEL_SC7_PA6_NULL_WE', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_EOP_RD', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_RD', + 'PH_PERF_SEL_SC7_PA7_DATA_FIFO_WE', + 'PH_PERF_SEL_SC7_PA7_DEALLOC_WE', 'PH_PERF_SEL_SC7_PA7_EOPG_WE', + 'PH_PERF_SEL_SC7_PA7_EOP_WE', 'PH_PERF_SEL_SC7_PA7_EVENT_WE', + 'PH_PERF_SEL_SC7_PA7_FIFO_EMPTY', 'PH_PERF_SEL_SC7_PA7_FIFO_FULL', + 'PH_PERF_SEL_SC7_PA7_FPOP_WE', 'PH_PERF_SEL_SC7_PA7_FPOV_WE', + 'PH_PERF_SEL_SC7_PA7_NULL_WE', + 'PH_PERF_SEL_SC7_PS_ENG_MULTICYCLE_BUBBLE', + 'PH_PERF_SEL_SC7_SEND', 'PH_PERF_SEL_SC7_SRPS_WINDOW_VALID', + 'PH_SPI_MODE_ARBITER_SELECTED_PA_PH_FIFO_COUNT', + 'PH_SPI_MODE_DISABLED', 'PH_SPI_MODE_LARGEST_PA_PH_FIFO_COUNT', + 'PIPELINESTAT_START', 'PIPELINESTAT_STOP', 'PIPE_ALIGNED', + 'PIPE_ALIGNED_SURF', 'PIPE_ID0', 'PIPE_ID1', 'PIPE_ID2', + 'PIPE_ID3', 'PIPE_INT_MASK_MODE', 'PIPE_INT_MASK_MODE_DISABLE', + 'PIPE_INT_MASK_MODE_ENABLE', 'PIPE_INT_TYPE_MODE', + 'PIPE_INT_TYPE_MODE_DISABLE', 'PIPE_INT_TYPE_MODE_ENABLE', + 'PIPE_IN_FLUSH_URGENT', 'PIPE_IN_FLUSH_URGENT_DISABLE', + 'PIPE_IN_FLUSH_URGENT_ENABLE', 'PIPE_PHYPLL_PIXEL_RATE_SOURCE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_RESERVED', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 'PIPE_PIXEL_RATE_PLL_SOURCE', + 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', + 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', 'PIPE_PIXEL_RATE_SOURCE', + 'PIPE_PIXEL_RATE_SOURCE_P0PLL', 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 'PIPE_PIXEL_RATE_SOURCE_P2PLL', 'PIPE_UNALIGNED_SURF', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_1', + 'PIXCDC_MEM_POWER_LIGHT_SLEEP_MODE_OFF', + 'PIXCDC_MEM_PWR_LIGHT_SLEEP_MODE', 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 'PIXEL_PIPE_OCCLUSION_COUNT_1', 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 'PIXEL_PIPE_OCCLUSION_COUNT_3', 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', 'PIXEL_PIPE_STAT_CONTROL', + 'PIXEL_PIPE_STAT_DUMP', 'PIXEL_PIPE_STAT_RESET', + 'PIXEL_PIPE_STRIDE_128_BITS', 'PIXEL_PIPE_STRIDE_256_BITS', + 'PIXEL_PIPE_STRIDE_32_BITS', 'PIXEL_PIPE_STRIDE_64_BITS', + 'PIX_DYNAMIC_EXPANSION', 'PIX_EXPAND_MODE', 'PIX_ZERO_EXPANSION', + 'PLL_CFG_IF_SOFT_RESET', 'PLL_CFG_IF_SOFT_RESET_FORCE', + 'PLL_CFG_IF_SOFT_RESET_NOOP', 'PM_ASSERT_RESET', + 'PM_ASSERT_RESET_0', 'PM_ASSERT_RESET_1', 'POINTLIST', + 'POWER_STATE_ENUM', 'POWER_STATE_ENUM_DS', 'POWER_STATE_ENUM_LS', + 'POWER_STATE_ENUM_ON', 'POWER_STATE_ENUM_SD', 'PRE_CSC_BYPASS', + 'PRE_CSC_MODE_ENUM', 'PRE_CSC_SET_A', 'PRE_CSC_SET_B', + 'PRE_DEGAM_BT2020', 'PRE_DEGAM_BT2100HLG', 'PRE_DEGAM_BT2100PQ', + 'PRE_DEGAM_BYPASS', 'PRE_DEGAM_ENABLE', 'PRE_DEGAM_GAMMA_22', + 'PRE_DEGAM_GAMMA_24', 'PRE_DEGAM_GAMMA_26', 'PRE_DEGAM_MODE', + 'PRE_DEGAM_SELECT', 'PRE_DEGAM_SRGB', 'PROG_SEQ', 'PROTVIOL', + 'PRQ_MRQ_FLUSH_URGENT', 'PRQ_MRQ_FLUSH_URGENT_DISABLE', + 'PRQ_MRQ_FLUSH_URGENT_ENABLE', 'PS', 'PSLC_ASAP', 'PSLC_AUTO', + 'PSLC_COUNTDOWN', 'PSLC_ON_HANG_ONLY', 'PS_DONE', + 'PS_PARTIAL_FLUSH', 'PTE_BUFFER_MODE', 'PTE_BUFFER_MODE_0', + 'PTE_BUFFER_MODE_1', 'PTE_ROW_HEIGHT_LINEAR', + 'PTE_ROW_HEIGHT_LINEAR_1024L', 'PTE_ROW_HEIGHT_LINEAR_128L', + 'PTE_ROW_HEIGHT_LINEAR_16L', 'PTE_ROW_HEIGHT_LINEAR_256L', + 'PTE_ROW_HEIGHT_LINEAR_32L', 'PTE_ROW_HEIGHT_LINEAR_512L', + 'PTE_ROW_HEIGHT_LINEAR_64L', 'PTE_ROW_HEIGHT_LINEAR_8L', + 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'PWRSEQ_BL_PWM_CNTL2_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN', + 'PWRSEQ_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT', + 'PWRSEQ_BL_PWM_CNTL_BL_PWM_EN', + 'PWRSEQ_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN', + 'PWRSEQ_BL_PWM_DISABLE', 'PWRSEQ_BL_PWM_ENABLE', + 'PWRSEQ_BL_PWM_FRACTIONAL_DISABLE', + 'PWRSEQ_BL_PWM_FRACTIONAL_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN', + 'PWRSEQ_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', + 'PWRSEQ_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_REG_LOCK_ENABLE', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 'PWRSEQ_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_NORMAL', + 'PWRSEQ_BL_PWM_OVERRIDE_PANEL_PWRSEQ_EN_PWM', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', + 'PWRSEQ_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 'PWRSEQ_GPIO_MASK_EN', 'PWRSEQ_GPIO_MASK_EN_HARDWARE', + 'PWRSEQ_GPIO_MASK_EN_SOFTWARE', 'PWRSEQ_PANEL_BLON_OFF', + 'PWRSEQ_PANEL_BLON_ON', 'PWRSEQ_PANEL_BLON_POL_INVERT', + 'PWRSEQ_PANEL_BLON_POL_NON_INVERT', 'PWRSEQ_PANEL_DIGON_OFF', + 'PWRSEQ_PANEL_DIGON_ON', 'PWRSEQ_PANEL_DIGON_POL_INVERT', + 'PWRSEQ_PANEL_DIGON_POL_NON_INVERT', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_BLON_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_DIGON_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_PANEL_SYNCEN_POL', + 'PWRSEQ_PANEL_PWRSEQ_CNTL_TARGET_STATE', + 'PWRSEQ_PANEL_PWRSEQ_DELAY2_PANEL_VARY_BL_OVERRIDE_EN', + 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_OFF', + 'PWRSEQ_PANEL_PWRSEQ_TARGET_STATE_LCD_ON', + 'PWRSEQ_PANEL_SYNCEN_POL_INVERT', + 'PWRSEQ_PANEL_SYNCEN_POL_NON_INVERT', + 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_BLON', + 'PWRSEQ_PANEL_VARY_BL_OVERRIDE_EN_SEPARATE', 'PerfCounter_Vals', + 'PhSPIstatusMode', 'PixelPipeCounterId', 'PixelPipeStride', + 'PkrMap', 'PkrXsel', 'PkrXsel2', 'PkrYsel', 'RAMA', 'RAMA_ACCESS', + 'RAMB', 'RAMB_ACCESS', 'RAM_LUT', 'RANGE_00', 'RANGE_FF', + 'RASTER_CONFIG_PKR_MAP_0', 'RASTER_CONFIG_PKR_MAP_1', + 'RASTER_CONFIG_PKR_MAP_2', 'RASTER_CONFIG_PKR_MAP_3', + 'RASTER_CONFIG_PKR_XSEL2_0', 'RASTER_CONFIG_PKR_XSEL2_1', + 'RASTER_CONFIG_PKR_XSEL2_2', 'RASTER_CONFIG_PKR_XSEL2_3', + 'RASTER_CONFIG_PKR_XSEL_0', 'RASTER_CONFIG_PKR_XSEL_1', + 'RASTER_CONFIG_PKR_XSEL_2', 'RASTER_CONFIG_PKR_XSEL_3', + 'RASTER_CONFIG_PKR_YSEL_0', 'RASTER_CONFIG_PKR_YSEL_1', + 'RASTER_CONFIG_PKR_YSEL_2', 'RASTER_CONFIG_PKR_YSEL_3', + 'RASTER_CONFIG_RB_MAP_0', 'RASTER_CONFIG_RB_MAP_1', + 'RASTER_CONFIG_RB_MAP_2', 'RASTER_CONFIG_RB_MAP_3', + 'RASTER_CONFIG_RB_XSEL2_0', 'RASTER_CONFIG_RB_XSEL2_1', + 'RASTER_CONFIG_RB_XSEL2_2', 'RASTER_CONFIG_RB_XSEL2_3', + 'RASTER_CONFIG_RB_XSEL_0', 'RASTER_CONFIG_RB_XSEL_1', + 'RASTER_CONFIG_RB_YSEL_0', 'RASTER_CONFIG_RB_YSEL_1', + 'RASTER_CONFIG_SC_MAP_0', 'RASTER_CONFIG_SC_MAP_1', + 'RASTER_CONFIG_SC_MAP_2', 'RASTER_CONFIG_SC_MAP_3', + 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', 'RASTER_CONFIG_SE_MAP_0', + 'RASTER_CONFIG_SE_MAP_1', 'RASTER_CONFIG_SE_MAP_2', + 'RASTER_CONFIG_SE_MAP_3', 'RASTER_CONFIG_SE_PAIR_MAP_0', + 'RASTER_CONFIG_SE_PAIR_MAP_1', 'RASTER_CONFIG_SE_PAIR_MAP_2', + 'RASTER_CONFIG_SE_PAIR_MAP_3', + 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', 'RAW', + 'RDPCSTX_CLOCK_CNTL_RDPCS_EXT_REFCLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_CLOCK_ON', + 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_OCLACLK_GATE_DIS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_CLOCK_ON', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_GATE_DIS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_SRAMCLK_PASS', + 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_CLOCK_ON', + 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_EN', + 'RDPCSTX_CLOCK_CNTL_RDPCS_TX_CLK_GATE_DIS', + 'RDPCSTX_CLOCK_CNTL_TX_CLK_EN', + 'RDPCSTX_CNTL_RDPCS_CBUS_SOFT_RESET', + 'RDPCSTX_CNTL_RDPCS_SRAM_SOFT_RESET', + 'RDPCSTX_CNTL_RDPCS_TX_FIFO_EN', + 'RDPCSTX_CNTL_RDPCS_TX_FIFO_LANE_EN', + 'RDPCSTX_CNTL_RDPCS_TX_SOFT_RESET', 'RDPCSTX_FIFO_EMPTY', + 'RDPCSTX_FIFO_FULL', 'RDPCSTX_FIFO_IS_EMPTY', + 'RDPCSTX_FIFO_IS_FULL', 'RDPCSTX_FIFO_NOT_EMPTY', + 'RDPCSTX_FIFO_NOT_FULL', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_4LANE_TOGGLE_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_DPALT_DISABLE_TOGGLE_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_REG_FIFO_ERROR_MASK', + 'RDPCSTX_INTERRUPT_CONTROL_RDPCS_TX_FIFO_ERROR_MASK', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_MUX_SEL', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_CR_PARA_SEL', + 'RDPCSTX_PHY_CNTL0_RDPCS_PHY_REF_RANGE', + 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_EXT_LD_DONE', + 'RDPCSTX_PHY_CNTL0_RDPCS_SRAM_INIT_DONE', + 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_DP_REF_CLK_MPLLB_DIV', + 'RDPCSTX_PHY_CNTL11_RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV', + 'RDPCSTX_PHY_CNTL12_RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCSTX_PHY_CNTL4_RDPCS_PHY_DP_TX_TERM_CTRL', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_DETRX_RESULT', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_RATE', + 'RDPCSTX_PHY_CNTL_RDPCS_PHY_DP_TX_WIDTH', + 'RDPCSTX_PHY_CNTL_RRDPCS_PHY_DP_TX_PSTATE', + 'RDPCSTX_PHY_REF_ALT_CLK_EN', 'RDPCSTX_TX_FIFO_DISABLED_MASK', + 'RDPCSTX_TX_FIFO_DISABLED_MASK_DISABLE', + 'RDPCSTX_TX_FIFO_DISABLED_MASK_ENABLE', + 'RDPCS_CBUS_SOFT_RESET_DISABLE', 'RDPCS_CBUS_SOFT_RESET_ENABLE', + 'RDPCS_DBG_OCLA_SEL', 'RDPCS_DBG_OCLA_SEL_MON_OUT_15_8', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_23_16', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_31_24', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_39_32', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_47_40', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_55_48', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_63_56', + 'RDPCS_DBG_OCLA_SEL_MON_OUT_7_0', + 'RDPCS_DPALT_4LANE_TOGGLE_2LANE', + 'RDPCS_DPALT_4LANE_TOGGLE_4LANE', + 'RDPCS_DPALT_4LANE_TOGGLE_MASK_DISABLE', + 'RDPCS_DPALT_4LANE_TOGGLE_MASK_ENABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_DISABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_ENABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_DISABLE', + 'RDPCS_DPALT_DISABLE_TOGGLE_MASK_ENABLE', + 'RDPCS_EXT_REFCLK_DISABLE', 'RDPCS_EXT_REFCLK_ENABLE', + 'RDPCS_EXT_REFCLK_EN_DISABLE', 'RDPCS_EXT_REFCLK_EN_ENABLE', + 'RDPCS_LANE_BIT_ORDER_REVERSE_DISABLE', + 'RDPCS_LANE_BIT_ORDER_REVERSE_ENABLE', + 'RDPCS_LANE_PACK_FROM_MSB_DISABLE', + 'RDPCS_LANE_PACK_FROM_MSB_ENABLE', 'RDPCS_MEM_PWR_DEEP_SLEEP', + 'RDPCS_MEM_PWR_LIGHT_SLEEP', 'RDPCS_MEM_PWR_NO_FORCE', + 'RDPCS_MEM_PWR_PWR_STATE_DEEP_SLEEP', + 'RDPCS_MEM_PWR_PWR_STATE_LIGHT_SLEEP', + 'RDPCS_MEM_PWR_PWR_STATE_ON', 'RDPCS_MEM_PWR_PWR_STATE_SHUT_DOWN', + 'RDPCS_MEM_PWR_SHUT_DOWN', 'RDPCS_OCLACLK_CLOCK_OFF', + 'RDPCS_OCLACLK_CLOCK_ON', 'RDPCS_OCLACLK_DISABLE', + 'RDPCS_OCLACLK_ENABLE', 'RDPCS_OCLACLK_GATE_DISABLE', + 'RDPCS_OCLACLK_GATE_ENABLE', 'RDPCS_PHY_CR_MUX_SEL_FOR_DC', + 'RDPCS_PHY_CR_MUX_SEL_FOR_USB', 'RDPCS_PHY_CR_PARA_SEL_CR', + 'RDPCS_PHY_CR_PARA_SEL_JTAG', 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV10', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV2', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV3', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV4', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV5', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV6', + 'RDPCS_PHY_DP_MPLLB_TX_CLK_DIV8', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV1', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV16', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV2', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV3', + 'RDPCS_PHY_DP_REF_CLK_MPLLB_DIV8', + 'RDPCS_PHY_DP_TX_DETRX_RESULT_DETECT', + 'RDPCS_PHY_DP_TX_DETRX_RESULT_NO_DETECT', 'RDPCS_PHY_DP_TX_RATE', + 'RDPCS_PHY_DP_TX_RATE_DIV2', 'RDPCS_PHY_DP_TX_RATE_DIV4', + 'RDPCS_PHY_DP_TX_TERM_CTRL_40', 'RDPCS_PHY_DP_TX_TERM_CTRL_42', + 'RDPCS_PHY_DP_TX_TERM_CTRL_44', 'RDPCS_PHY_DP_TX_TERM_CTRL_46', + 'RDPCS_PHY_DP_TX_TERM_CTRL_48', 'RDPCS_PHY_DP_TX_TERM_CTRL_50', + 'RDPCS_PHY_DP_TX_TERM_CTRL_52', 'RDPCS_PHY_DP_TX_TERM_CTRL_54', + 'RDPCS_PHY_DP_TX_WIDTH_10', 'RDPCS_PHY_DP_TX_WIDTH_16', + 'RDPCS_PHY_DP_TX_WIDTH_20', 'RDPCS_PHY_DP_TX_WIDTH_8', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_0', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_1', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_2', + 'RDPCS_PHY_HDMI_MPLLB_HDMI_PIXEL_CLK_DIV_3', + 'RDPCS_PHY_REF_ALT_CLK_DISABLE', 'RDPCS_PHY_REF_ALT_CLK_ENABLE', + 'RDPCS_PHY_REF_RANGE_0', 'RDPCS_PHY_REF_RANGE_1', + 'RDPCS_PHY_REF_RANGE_2', 'RDPCS_PHY_REF_RANGE_3', + 'RDPCS_PHY_REF_RANGE_4', 'RDPCS_PHY_REF_RANGE_5', + 'RDPCS_PHY_REF_RANGE_6', 'RDPCS_PHY_REF_RANGE_7', + 'RDPCS_REG_FIFO_ERROR_MASK_DISABLE', + 'RDPCS_REG_FIFO_ERROR_MASK_ENABLE', 'RDPCS_SRAMCLK_DISABLE', + 'RDPCS_SRAMCLK_ENABLE', 'RDPCS_SRAMCLK_GATE_DISABLE', + 'RDPCS_SRAMCLK_GATE_ENABLE', 'RDPCS_SRAMCLK_NOT_PASS', + 'RDPCS_SRAMCLK_PASS', 'RDPCS_SRAM_EXT_LD_DONE', + 'RDPCS_SRAM_EXT_LD_NOT_DONE', 'RDPCS_SRAM_INIT_DONE', + 'RDPCS_SRAM_INIT_NOT_DONE', 'RDPCS_SRAM_SRAM_RESET_DISABLE', + 'RDPCS_SRAM_SRAM_RESET_ENABLE', 'RDPCS_SYMCLK_SRAMCLK_CLOCK_OFF', + 'RDPCS_SYMCLK_SRAMCLK_CLOCK_ON', 'RDPCS_TEST_CLK_SEL', + 'RDPCS_TEST_CLK_SEL_CFGCLK', + 'RDPCS_TEST_CLK_SEL_DP_MPLLB_DIV_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX0_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX1_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX2_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_DP_TX3_WORD_CLK', + 'RDPCS_TEST_CLK_SEL_EXT_CR_CLK', + 'RDPCS_TEST_CLK_SEL_HDMI_MPLLB_HDMI_PIXEL_CLK', + 'RDPCS_TEST_CLK_SEL_NONE', 'RDPCS_TEST_CLK_SEL_PHY_REF_DIG_CLK', + 'RDPCS_TEST_CLK_SEL_REF_DIG_FR_clk', 'RDPCS_TEST_CLK_SEL_SRAMCLK', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_LDPCS_DIV4', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS', + 'RDPCS_TEST_CLK_SEL_SYMCLK_DIV2_RDPCS_DIV4', + 'RDPCS_TEST_CLK_SEL_dtb_out0', 'RDPCS_TEST_CLK_SEL_dtb_out1', + 'RDPCS_TX_CLK_CLOCK_OFF', 'RDPCS_TX_CLK_CLOCK_ON', + 'RDPCS_TX_CLK_DISABLE', 'RDPCS_TX_CLK_ENABLE', + 'RDPCS_TX_CLK_GATE_DISABLE', 'RDPCS_TX_CLK_GATE_ENABLE', + 'RDPCS_TX_CNTL_TX_LANE_PACK_FROM_MSB', 'RDPCS_TX_FIFO_DISABLE', + 'RDPCS_TX_FIFO_ENABLE', 'RDPCS_TX_FIFO_ERROR_MASK_DISABLE', + 'RDPCS_TX_FIFO_ERROR_MASK_ENABLE', 'RDPCS_TX_FIFO_LANE_DISABLE', + 'RDPCS_TX_FIFO_LANE_ENABLE', 'RDPCS_TX_SOFT_RESET_DISABLE', + 'RDPCS_TX_SOFT_RESET_ENABLE', + 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_FORCE', + 'RDPCS_TX_SRAM_CNTL_RDPCS_MEM_PWR_PWR_STATE', + 'READ_COMPRESSION_MODE', 'READ_SEQ', 'RECTLIST', 'RECT_2D', + 'RED_LUT', 'REFER_TO_DP_SOF', 'REFER_TO_OTG_SOF', + 'REG_SECURE_VIOLATE_READ', 'REG_SECURE_VIOLATE_WRITE', + 'REG_UNALLOCATED_ADDR_READ', 'REG_UNALLOCATED_ADDR_WRITE', + 'REG_VIRTUAL_READ', 'REG_VIRTUAL_WRITE', 'RESERVED1', 'RESERVED2', + 'RESERVED3', 'RESERVED4', 'RESERVED_1', 'RESERVED_10', + 'RESERVED_11', 'RESERVED_20', 'RESERVED_21', 'RESERVED_22', + 'RESERVED_23', 'RESERVED_3', 'RESERVED_32', 'RESERVED_33', + 'RESERVED_34', 'RESERVED_35', 'RESERVED_44', 'RESERVED_45', + 'RESERVED_46', 'RESERVED_47', 'RESERVED_56', 'RESERVED_57', + 'RESERVED_58', 'RESERVED_59', 'RESERVED_60', 'RESERVED_61', + 'RESERVED_62', 'RESERVED_63', 'RESERVED_72', 'RESERVED_73', + 'RESERVED_74', 'RESERVED_75', 'RESERVED_8', 'RESERVED_84', + 'RESERVED_85', 'RESERVED_86', 'RESERVED_87', 'RESERVED_88', + 'RESERVED_89', 'RESERVED_9', 'RESERVED_90', 'RESERVED_91', + 'RESERVED_RDPOLICY', 'RESET_TO_LOWEST_VGT', 'RESET_VTX_CNT', + 'RESPONSE_STATUS', 'RE_Z', 'RGB111110_FIX', 'RGB111110_FLOAT', + 'RGB565', 'RGBA1010102', 'RGBA16161616_10LSB', + 'RGBA16161616_10MSB', 'RGBA16161616_12LSB', 'RGBA16161616_12MSB', + 'RGBA16161616_FLOAT', 'RGBA16161616_SNORM', 'RGBA16161616_UNORM', + 'RGBA4444', 'RGBA5551', 'RGBA8888', 'RGBE', 'RINGID0', 'RINGID1', + 'RINGID2', 'RINGID3', 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RLC_DOORBELL_MODE', 'RLC_DOORBELL_MODE_DISABLE', + 'RLC_DOORBELL_MODE_ENABLE', 'RLC_DOORBELL_MODE_ENABLE_PF', + 'RLC_DOORBELL_MODE_ENABLE_PF_VF', 'RLC_PERFCOUNTER_SEL', + 'RLC_PERFMON_STATE', 'RLC_PERFMON_STATE_DISABLE', + 'RLC_PERFMON_STATE_ENABLE', 'RLC_PERFMON_STATE_RESERVED_3', + 'RLC_PERFMON_STATE_RESERVED_4', 'RLC_PERFMON_STATE_RESERVED_5', + 'RLC_PERFMON_STATE_RESERVED_6', 'RLC_PERFMON_STATE_RESET', + 'RLC_PERFMON_STATE_ROLLOVER', 'RLC_PERF_SEL_CP_INTERRUPT', + 'RLC_PERF_SEL_GRBM_INTERRUPT', 'RLC_PERF_SEL_IH_INTERRUPT', + 'RLC_PERF_SEL_POWER_FEATURE_0', 'RLC_PERF_SEL_POWER_FEATURE_1', + 'RLC_PERF_SEL_SERDES_COMMAND_WRITE', 'RLC_PERF_SEL_SPM_INTERRUPT', + 'RMIPerfSel', 'RMI_PERF_SEL_BUSY', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_CB_RTS_RTR', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_DB_RTS_RTR', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_IN0_RTS_RTR', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_IN1_RTS_RTR', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_READ_RTS_RTR', + 'RMI_PERF_SEL_CONSUMER_PROBEGEN_WRITE_RTS_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 'RMI_PERF_SEL_DYN_CLK_RB_VLD', 'RMI_PERF_SEL_EVENT_SEND', + 'RMI_PERF_SEL_NONE', 'RMI_PERF_SEL_PERF_WINDOW', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_32BWRREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 'RMI_PERF_SEL_RB_RMI_RDREQ_TO_RDRET_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_FIFO_EMPTY', + 'RMI_PERF_SEL_RB_RMI_RD_FIFO_MAX', 'RMI_PERF_SEL_RB_RMI_RD_IDLE', + 'RMI_PERF_SEL_RB_RMI_RD_INTF_BUSY', + 'RMI_PERF_SEL_RB_RMI_RD_STALL', 'RMI_PERF_SEL_RB_RMI_RD_STARVE', + 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 'RMI_PERF_SEL_RB_RMI_WRREQ_TO_WRRET_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_FIFO_EMPTY', + 'RMI_PERF_SEL_RB_RMI_WR_FIFO_MAX', 'RMI_PERF_SEL_RB_RMI_WR_IDLE', + 'RMI_PERF_SEL_RB_RMI_WR_INTF_BUSY', + 'RMI_PERF_SEL_RB_RMI_WR_STALL', 'RMI_PERF_SEL_RB_RMI_WR_STARVE', + 'RMI_PERF_SEL_REG_CLK_VLD', 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_TC_64BRDREQ_ALL_ORONE_CID', + 'RMI_PERF_SEL_RMI_TC_64BWRREQ_ALL_ORONE_CID', + 'RMI_PERF_SEL_RMI_TC_CREDIT_FULL_NO_PENDING_SEND', + 'RMI_PERF_SEL_RMI_TC_CREDIT_ZERO_PENDING_SEND', + 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 'RMI_PERF_SEL_RMI_TC_STALL_ALLREQ', + 'RMI_PERF_SEL_RMI_TC_STALL_RDREQ', + 'RMI_PERF_SEL_RMI_TC_STALL_WRREQ', + 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_TCIW_BUSY', 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 'RMI_PERF_SEL_TCIW_REQ', + 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', 'ROM_SIGNATURE', + 'ROTATE_0_DEGREES', 'ROTATE_180_DEGREES', 'ROTATE_270_DEGREES', + 'ROTATE_90_DEGREES', 'ROTATION_ANGLE', 'ROW_TTU_MODE', + 'RPDCSTX_CNTL_TX_LANE_BIT_ORDER_REVERSE_BEFORE_PACK', + 'RRDPCS_PHY_DP_TX_PSTATE_HOLD', + 'RRDPCS_PHY_DP_TX_PSTATE_HOLD_OFF', + 'RRDPCS_PHY_DP_TX_PSTATE_POWER_DOWN', + 'RRDPCS_PHY_DP_TX_PSTATE_POWER_UP', 'RSPM_CMD', + 'RSPM_CMD_CALIBRATE', 'RSPM_CMD_FORCE_SAMPLE', 'RSPM_CMD_IDLE', + 'RSPM_CMD_INVALID', 'RSPM_CMD_PERF_RESET', 'RSPM_CMD_PERF_SAMPLE', + 'RSPM_CMD_PROF_START', 'RSPM_CMD_PROF_STOP', 'RSPM_CMD_SPM_RESET', + 'RSPM_CMD_SPM_START', 'RSPM_CMD_SPM_STOP', 'RST_PIX_CNT', + 'RSV_TAG_RAM', 'RbMap', 'RbXsel', 'RbXsel2', 'RbYsel', + 'ReadPolicy', 'Reserved_0x00', 'RingCounterControl', + 'SAMPLE_PIPELINESTAT', 'SAMPLE_STREAMOUTSTATS', + 'SAMPLE_STREAMOUTSTATS1', 'SAMPLE_STREAMOUTSTATS2', + 'SAMPLE_STREAMOUTSTATS3', 'SCL_2TAP_HARDCODE', 'SCL_ALPHA_COEF', + 'SCL_ALPHA_COEF_FIRST', 'SCL_ALPHA_COEF_SECOND', + 'SCL_AUTOCAL_MODE', 'SCL_BOUNDARY', 'SCL_BOUNDARY_BLACK', + 'SCL_BOUNDARY_EDGE', 'SCL_CHROMA_COEF', 'SCL_CHROMA_COEF_FIRST', + 'SCL_CHROMA_COEF_SECOND', 'SCL_COEF_2TAP_HARDCODE_OFF', + 'SCL_COEF_2TAP_HARDCODE_ON', 'SCL_COEF_CHROMA_HORZ_FILTER', + 'SCL_COEF_CHROMA_VERT_FILTER', 'SCL_COEF_FILTER_TYPE_SEL', + 'SCL_COEF_LUMA_HORZ_FILTER', 'SCL_COEF_LUMA_VERT_FILTER', + 'SCL_COEF_RAM_SEL', 'SCL_COEF_RAM_SEL_0', 'SCL_COEF_RAM_SEL_1', + 'SCL_COEF_SC_HORZ_FILTER', 'SCL_COEF_SC_VERT_FILTER', + 'SCL_SHARP_DISABLE', 'SCL_SHARP_EN', 'SCL_SHARP_ENABLE', 'SCOPE', + 'SCOPE_CU', 'SCOPE_DEV', 'SCOPE_SE', 'SCOPE_SYS', + 'SC_BACKEND_BUSY', 'SC_BACKEND_PRIM_FIFO_FULL', 'SC_BB_DISCARD', + 'SC_BCI_CREDIT_AT_MAX', 'SC_BCI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_BCI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_BCI_SEND', + 'SC_BE_VRS_FB_RET', 'SC_BE_VRS_FB_RET_HIT', + 'SC_BE_VRS_FB_RET_STALLED', 'SC_BE_VRS_RD_REQ', + 'SC_BE_VRS_RD_REQ_HIT', 'SC_BE_VRS_RD_REQ_STALLED', + 'SC_BE_VRS_RD_RET', 'SC_BE_VRS_RD_RET_STALLED', + 'SC_BM_BE0_STALLED', 'SC_BM_BE1_STALLED', 'SC_BM_BE2_STALLED', + 'SC_BM_BE3_STALLED', 'SC_BM_BUSY', + 'SC_BM_MULTI_ACCUM_1_BE_STALLED', + 'SC_BM_MULTI_ACCUM_2_BE_STALLED', + 'SC_BM_MULTI_ACCUM_3_BE_STALLED', + 'SC_BM_MULTI_ACCUM_4_BE_STALLED', 'SC_BUSY_CNT_NOT_ZERO', + 'SC_DB0_QUAD_INTF_BUSY', 'SC_DB0_QUAD_INTF_CREDIT_AT_MAX', + 'SC_DB0_QUAD_INTF_IDLE', 'SC_DB0_QUAD_INTF_SEND', + 'SC_DB0_QUAD_INTF_STALLED_BY_DB', 'SC_DB0_TILE_INTERFACE_BUSY', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_MAX_WITH_NO_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_CREDIT_AT_ZERO_WITH_PENDING_SEND', + 'SC_DB0_TILE_INTERFACE_SEND', 'SC_DB0_TILE_INTERFACE_SEND_EVENT', + 'SC_DB0_TILE_MASK_FIFO_FULL', + 'SC_DB0_WE_STALLED_BY_RSLT_FIFO_FULL', + 'SC_DB0_WE_TILE_MASK_RETURN_FIFO_FULL_WITH_WE_RSLT_FIFO_STALL', + 'SC_EARLYZ_QUAD_COUNT', 'SC_EARLYZ_QUAD_WITH_1_PIX', + 'SC_EARLYZ_QUAD_WITH_2_PIX', 'SC_EARLYZ_QUAD_WITH_3_PIX', + 'SC_EARLYZ_QUAD_WITH_4_PIX', 'SC_GL1X_BUSY', + 'SC_GRP0_DYN_SCLK_BUSY', 'SC_GRP1_DYN_SCLK_BUSY', + 'SC_GRP2_DYN_SCLK_BUSY', 'SC_GRP3_DYN_SCLK_BUSY', + 'SC_GRP4_DYN_SCLK_BUSY', 'SC_GRP5_DYN_SCLK_BUSY', + 'SC_GRP6_DYN_SCLK_BUSY', 'SC_GRP7_DYN_SCLK_BUSY', + 'SC_GRP8_DYN_SCLK_BUSY', 'SC_GRP9_DYN_SCLK_BUSY', 'SC_HALF_LSB', + 'SC_LSB_ONE_SIDED', 'SC_LSB_TWO_SIDED', 'SC_P0_DETAIL_QUAD_COUNT', + 'SC_P0_DETAIL_QUAD_WITH_1_PIX', 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 'SC_P0_DETAIL_QUAD_WITH_3_PIX', 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 'SC_P0_HIZ_QUAD_COUNT', 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 'SC_P0_HIZ_QUAD_PER_TILE_H1', 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 'SC_P0_HIZ_QUAD_PER_TILE_H11', 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 'SC_P0_HIZ_QUAD_PER_TILE_H13', 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 'SC_P0_HIZ_QUAD_PER_TILE_H15', 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 'SC_P0_HIZ_QUAD_PER_TILE_H2', 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 'SC_P0_HIZ_QUAD_PER_TILE_H4', 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 'SC_P0_HIZ_QUAD_PER_TILE_H6', 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 'SC_P0_HIZ_QUAD_PER_TILE_H8', 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 'SC_P0_HIZ_TILE_COUNT', 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 'SC_PA0_SC_DATA_FIFO_RD', 'SC_PA0_SC_DATA_FIFO_WE', + 'SC_PA0_SC_DEALLOC_2_0_RD', 'SC_PA0_SC_EOP_WE', + 'SC_PA0_SC_EVENT_WE', 'SC_PA0_SC_NULL_DEALLOC_WE', + 'SC_PA0_SC_NULL_WE', 'SC_PA_SC_DEALLOC_2_0_WE', + 'SC_PA_SC_FPOV_WE', 'SC_PA_TO_PBB_SCLK_GATE_STALL_STALL', + 'SC_PBB_BATCH_BREAK_DUE_TO_BINNING_MODE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_DEBUG_DATA_PER_DRAW_DISPATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_GFX_PIPE_CHANGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_NEW_SC_MODE', + 'SC_PBB_BATCH_BREAK_DUE_TO_NONBINNED_BATCH', + 'SC_PBB_BATCH_BREAK_DUE_TO_NULL_PRIM_BREAK_BATCH_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_CONTEXT', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_FPOV', + 'SC_PBB_BATCH_BREAK_DUE_TO_OVERRIDE_REGISTER_PERSISTENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPELINE_EVENT_COUNT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PIPE_RESET', + 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 'SC_PBB_BATCH_BREAK_DUE_TO_TIMEOUT_COUNTER', + 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BIN_HIST_NUM_PRIMS', 'SC_PBB_BUSY', + 'SC_PBB_BUSY_AND_NO_SENDS', + 'SC_PBB_EMPTY_INPUT_CYCLE_WHEN_BATCH_OPEN', 'SC_PBB_END_OF_BATCH', + 'SC_PBB_END_OF_BIN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 'SC_PBB_NONBINNED_PRIM', 'SC_PBB_NUM_BINS', + 'SC_PBB_PRIMBIN_PROCESSED', 'SC_PBB_PRIM_ADDED_TO_BATCH', + 'SC_PBB_READ_DEALLOC_4_0', 'SC_PBB_READ_DEALLOC_7_5', + 'SC_PBB_READ_FPOG_4_0', 'SC_PBB_READ_FPOG_7_5', 'SC_PBB_READ_PH0', + 'SC_PBB_RESERVED', 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', 'SC_PERFCNT_SEL', + 'SC_PERF_SEL_RESERVED_108', 'SC_PERF_SEL_RESERVED_109', + 'SC_PERF_SEL_RESERVED_110', 'SC_PERF_SEL_RESERVED_111', + 'SC_PERF_SEL_RESERVED_112', 'SC_PERF_SEL_RESERVED_113', + 'SC_PERF_SEL_RESERVED_114', 'SC_PERF_SEL_RESERVED_115', + 'SC_PERF_SEL_RESERVED_116', 'SC_PERF_SEL_RESERVED_117', + 'SC_PERF_SEL_RESERVED_118', 'SC_PERF_SEL_RESERVED_119', + 'SC_PERF_SEL_RESERVED_120', 'SC_PERF_SEL_RESERVED_121', + 'SC_PERF_SEL_RESERVED_122', 'SC_PERF_SEL_RESERVED_123', + 'SC_PERF_SEL_RESERVED_124', 'SC_PERF_SEL_RESERVED_125', + 'SC_PERF_SEL_RESERVED_126', 'SC_PERF_SEL_RESERVED_127', + 'SC_PERF_SEL_RESERVED_128', 'SC_PERF_SEL_RESERVED_129', + 'SC_PERF_SEL_RESERVED_130', 'SC_PERF_SEL_RESERVED_131', + 'SC_PERF_SEL_RESERVED_132', 'SC_PERF_SEL_RESERVED_133', + 'SC_PERF_SEL_RESERVED_134', 'SC_PERF_SEL_RESERVED_135', + 'SC_PERF_SEL_RESERVED_136', 'SC_PERF_SEL_RESERVED_137', + 'SC_PERF_SEL_RESERVED_138', 'SC_PERF_SEL_RESERVED_139', + 'SC_PERF_SEL_RESERVED_140', 'SC_PERF_SEL_RESERVED_141', + 'SC_PERF_SEL_RESERVED_142', 'SC_PERF_SEL_RESERVED_143', + 'SC_PERF_SEL_RESERVED_144', 'SC_PERF_SEL_RESERVED_145', + 'SC_PERF_SEL_RESERVED_146', 'SC_PERF_SEL_RESERVED_147', + 'SC_PERF_SEL_RESERVED_148', 'SC_PERF_SEL_RESERVED_149', + 'SC_PERF_SEL_RESERVED_150', 'SC_PERF_SEL_RESERVED_151', + 'SC_PERF_SEL_RESERVED_152', 'SC_PERF_SEL_RESERVED_153', + 'SC_PERF_SEL_RESERVED_154', 'SC_PERF_SEL_RESERVED_155', + 'SC_PERF_SEL_RESERVED_156', 'SC_PERF_SEL_RESERVED_157', + 'SC_PERF_SEL_RESERVED_158', 'SC_PERF_SEL_RESERVED_160', + 'SC_PERF_SEL_RESERVED_161', 'SC_PERF_SEL_RESERVED_162', + 'SC_PERF_SEL_RESERVED_164', 'SC_PERF_SEL_RESERVED_165', + 'SC_PERF_SEL_RESERVED_166', 'SC_PERF_SEL_RESERVED_184', + 'SC_PERF_SEL_RESERVED_185', 'SC_PERF_SEL_RESERVED_186', + 'SC_PERF_SEL_RESERVED_187', 'SC_PERF_SEL_RESERVED_188', + 'SC_PERF_SEL_RESERVED_189', 'SC_PERF_SEL_RESERVED_190', + 'SC_PERF_SEL_RESERVED_191', 'SC_PERF_SEL_RESERVED_192', + 'SC_PERF_SEL_RESERVED_193', 'SC_PERF_SEL_RESERVED_194', + 'SC_PERF_SEL_RESERVED_195', 'SC_PERF_SEL_RESERVED_196', + 'SC_PERF_SEL_RESERVED_197', 'SC_PERF_SEL_RESERVED_198', + 'SC_PERF_SEL_RESERVED_199', 'SC_PERF_SEL_RESERVED_200', + 'SC_PERF_SEL_RESERVED_201', 'SC_PERF_SEL_RESERVED_202', + 'SC_PERF_SEL_RESERVED_203', 'SC_PERF_SEL_RESERVED_204', + 'SC_PERF_SEL_RESERVED_205', 'SC_PERF_SEL_RESERVED_206', + 'SC_PERF_SEL_RESERVED_207', 'SC_PERF_SEL_RESERVED_208', + 'SC_PERF_SEL_RESERVED_209', 'SC_PERF_SEL_RESERVED_210', + 'SC_PERF_SEL_RESERVED_211', 'SC_PERF_SEL_RESERVED_212', + 'SC_PERF_SEL_RESERVED_213', 'SC_PERF_SEL_RESERVED_214', + 'SC_PERF_SEL_RESERVED_215', 'SC_PERF_SEL_RESERVED_216', + 'SC_PERF_SEL_RESERVED_217', 'SC_PERF_SEL_RESERVED_218', + 'SC_PERF_SEL_RESERVED_219', 'SC_PERF_SEL_RESERVED_220', + 'SC_PERF_SEL_RESERVED_221', 'SC_PERF_SEL_RESERVED_222', + 'SC_PERF_SEL_RESERVED_223', 'SC_PERF_SEL_RESERVED_224', + 'SC_PERF_SEL_RESERVED_225', 'SC_PERF_SEL_RESERVED_226', + 'SC_PERF_SEL_RESERVED_227', 'SC_PERF_SEL_RESERVED_228', + 'SC_PERF_SEL_RESERVED_229', 'SC_PERF_SEL_RESERVED_230', + 'SC_PERF_SEL_RESERVED_231', 'SC_PERF_SEL_RESERVED_232', + 'SC_PERF_SEL_RESERVED_233', 'SC_PERF_SEL_RESERVED_234', + 'SC_PERF_SEL_RESERVED_236', 'SC_PERF_SEL_RESERVED_237', + 'SC_PERF_SEL_RESERVED_238', 'SC_PERF_SEL_RESERVED_240', + 'SC_PERF_SEL_RESERVED_241', 'SC_PERF_SEL_RESERVED_242', + 'SC_PERF_SEL_RESERVED_247', 'SC_PERF_SEL_RESERVED_248', + 'SC_PERF_SEL_RESERVED_249', 'SC_PERF_SEL_RESERVED_250', + 'SC_PERF_SEL_RESERVED_251', 'SC_PERF_SEL_RESERVED_252', + 'SC_PERF_SEL_RESERVED_253', 'SC_PERF_SEL_RESERVED_254', + 'SC_PERF_SEL_RESERVED_255', 'SC_PERF_SEL_RESERVED_256', + 'SC_PERF_SEL_RESERVED_257', 'SC_PERF_SEL_RESERVED_258', + 'SC_PERF_SEL_RESERVED_279', 'SC_PERF_SEL_RESERVED_280', + 'SC_PERF_SEL_RESERVED_288', 'SC_PERF_SEL_RESERVED_289', + 'SC_PERF_SEL_RESERVED_290', 'SC_PERF_SEL_RESERVED_291', + 'SC_PERF_SEL_RESERVED_293', 'SC_PERF_SEL_RESERVED_294', + 'SC_PERF_SEL_RESERVED_295', 'SC_PERF_SEL_RESERVED_296', + 'SC_PERF_SEL_RESERVED_297', 'SC_PERF_SEL_RESERVED_298', + 'SC_PERF_SEL_RESERVED_299', 'SC_PERF_SEL_RESERVED_301', + 'SC_PERF_SEL_RESERVED_303', 'SC_PERF_SEL_RESERVED_304', + 'SC_PERF_SEL_RESERVED_305', 'SC_PERF_SEL_RESERVED_306', + 'SC_PERF_SEL_RESERVED_307', 'SC_PERF_SEL_RESERVED_308', + 'SC_PERF_SEL_RESERVED_309', 'SC_PERF_SEL_RESERVED_310', + 'SC_PERF_SEL_RESERVED_311', 'SC_PERF_SEL_RESERVED_312', + 'SC_PERF_SEL_RESERVED_313', 'SC_PERF_SEL_RESERVED_314', + 'SC_PERF_SEL_RESERVED_315', 'SC_PERF_SEL_RESERVED_316', + 'SC_PERF_SEL_RESERVED_317', 'SC_PERF_SEL_RESERVED_319', + 'SC_PERF_SEL_RESERVED_320', 'SC_PERF_SEL_RESERVED_321', + 'SC_PERF_SEL_RESERVED_322', 'SC_PERF_SEL_RESERVED_323', + 'SC_PERF_SEL_RESERVED_324', 'SC_PERF_SEL_RESERVED_325', + 'SC_PERF_SEL_RESERVED_328', 'SC_PERF_SEL_RESERVED_329', + 'SC_PERF_SEL_RESERVED_330', 'SC_PERF_SEL_RESERVED_331', + 'SC_PERF_SEL_RESERVED_332', 'SC_PERF_SEL_RESERVED_333', + 'SC_PERF_SEL_RESERVED_334', 'SC_PERF_SEL_RESERVED_335', + 'SC_PERF_SEL_RESERVED_336', 'SC_PERF_SEL_RESERVED_337', + 'SC_PERF_SEL_RESERVED_340', 'SC_PERF_SEL_RESERVED_341', + 'SC_PERF_SEL_RESERVED_347', 'SC_PERF_SEL_RESERVED_348', + 'SC_PERF_SEL_RESERVED_351', 'SC_PERF_SEL_RESERVED_354', + 'SC_PERF_SEL_RESERVED_355', 'SC_PERF_SEL_RESERVED_356', + 'SC_PERF_SEL_RESERVED_357', 'SC_PERF_SEL_RESERVED_358', + 'SC_PERF_SEL_RESERVED_359', 'SC_PERF_SEL_RESERVED_360', + 'SC_PERF_SEL_RESERVED_361', 'SC_PERF_SEL_RESERVED_362', + 'SC_PERF_SEL_RESERVED_363', 'SC_PERF_SEL_RESERVED_364', + 'SC_PERF_SEL_RESERVED_365', 'SC_PERF_SEL_RESERVED_366', + 'SC_PERF_SEL_RESERVED_367', 'SC_PERF_SEL_RESERVED_368', + 'SC_PERF_SEL_RESERVED_369', 'SC_PERF_SEL_RESERVED_370', + 'SC_PERF_SEL_RESERVED_371', 'SC_PERF_SEL_RESERVED_372', + 'SC_PERF_SEL_RESERVED_375', 'SC_PERF_SEL_RESERVED_376', + 'SC_PERF_SEL_RESERVED_377', 'SC_PERF_SEL_RESERVED_378', + 'SC_PERF_SEL_RESERVED_379', 'SC_PERF_SEL_RESERVED_380', + 'SC_PERF_SEL_RESERVED_381', 'SC_PERF_SEL_RESERVED_382', + 'SC_PERF_SEL_RESERVED_383', 'SC_PERF_SEL_RESERVED_384', + 'SC_PERF_SEL_RESERVED_385', 'SC_PERF_SEL_RESERVED_423', + 'SC_PERF_SEL_RESERVED_424', 'SC_PERF_SEL_RESERVED_425', + 'SC_PERF_SEL_RESERVED_426', 'SC_PERF_SEL_RESERVED_427', + 'SC_PERF_SEL_RESERVED_428', 'SC_PERF_SEL_RESERVED_429', + 'SC_PERF_SEL_RESERVED_430', 'SC_PERF_SEL_RESERVED_431', + 'SC_PERF_SEL_RESERVED_432', 'SC_PERF_SEL_RESERVED_433', + 'SC_PERF_SEL_RESERVED_434', 'SC_PERF_SEL_RESERVED_435', + 'SC_PERF_SEL_RESERVED_436', 'SC_PERF_SEL_RESERVED_478', + 'SC_PERF_SEL_RESERVED_479', 'SC_PERF_SEL_RESERVED_483', + 'SC_PERF_SEL_RESERVED_484', 'SC_PERF_SEL_RESERVED_485', + 'SC_PERF_SEL_RESERVED_486', 'SC_PERF_SEL_RESERVED_487', + 'SC_PERF_SEL_RESERVED_488', 'SC_PERF_SEL_RESERVED_489', + 'SC_PERF_SEL_RESERVED_490', 'SC_PERF_SEL_RESERVED_509', + 'SC_PERF_SEL_RESERVED_510', 'SC_PERF_SEL_RESERVED_511', + 'SC_PERF_SEL_RESERVED_512', 'SC_PERF_SEL_RESERVED_513', + 'SC_PERF_SEL_RESERVED_514', 'SC_PERF_SEL_RESERVED_523', + 'SC_PERF_SEL_RESERVED_524', 'SC_PERF_SEL_RESERVED_525', + 'SC_PERF_SEL_RESERVED_532', 'SC_PERF_SEL_RESERVED_533', + 'SC_PERF_SEL_RESERVED_534', 'SC_PERF_SEL_RESERVED_539', + 'SC_PERF_SEL_RESERVED_568', 'SC_PERF_SEL_RESERVED_76', + 'SC_PERF_SEL_RESERVED_77', 'SC_PERF_SEL_RESERVED_78', + 'SC_PERF_SEL_RESERVED_80', 'SC_PERF_SEL_RESERVED_81', + 'SC_PERF_SEL_RESERVED_82', 'SC_PERF_SEL_RESERVED_84', + 'SC_PERF_SEL_RESERVED_85', 'SC_PERF_SEL_RESERVED_86', + 'SC_PERF_SEL_RESERVED_88', 'SC_PERF_SEL_RESERVED_89', + 'SC_PERF_SEL_RESERVED_90', 'SC_PKR_4X2_FILL_QUAD', + 'SC_PKR_4X2_QUAD_SPLIT', 'SC_PKR_BCI_QUAD_NEW_PRIM', + 'SC_PKR_CONTROL_XFER', 'SC_PKR_DBHANG_FORCE_EOV', + 'SC_PKR_DB_OREO_WAVE_QUAD_COUNT', 'SC_PKR_DB_WAVE_STALL', + 'SC_PKR_END_OF_VECTOR', + 'SC_PKR_OREO_STALLED_BY_NO_VALID_WAIVE_ID', + 'SC_PKR_PC_NO_CREDITS', 'SC_PKR_PC_SEND', 'SC_PKR_PC_SEND_EOV', + 'SC_PKR_PC_SEND_EVENT', 'SC_PKR_PC_SEND_PRIM_VALID_0', + 'SC_PKR_PC_SEND_PRIM_VALID_1', 'SC_PKR_PC_SEND_TRUE_PRIM', + 'SC_PKR_PC_STALLED', 'SC_PKR_PSINVOC_SEDC_FIFO_FULL', + 'SC_PKR_QUAD_PER_ROW_H1', 'SC_PKR_QUAD_PER_ROW_H2', + 'SC_PKR_SPI_QUAD_COUNT', 'SC_PKR_WAVE_BREAK_FULL_TILE', + 'SC_PKR_WAVE_BREAK_OUTSIDE_REGION', 'SC_PK_BUSY', + 'SC_PK_DEALLOC_WAVE_BREAK', 'SC_PK_MAX_DEALLOC_FORCE_EOV', + 'SC_PK_PM_4X2_SPLIT_WAVE_BRK_1H', + 'SC_PK_PM_AE_CONFLICT_WAVE_BRK_1H', + 'SC_PK_PM_AVOID_DEALLOC_ADD_WAVE_BRK_1H', + 'SC_PK_PM_CTL_ONLY_CMD_WAVE_BRK_1H', + 'SC_PK_PM_END_OF_VECTOR_WAVE_BRK_1H', + 'SC_PK_PM_EOP_OR_LAD_WAVE_BRK_1H', + 'SC_PK_PM_FD_CONFLICT_WAVE_BRK_1H', + 'SC_PK_PM_FORCE_PARTIAL_FOR_DEALLOC_WAVE_BRK_1H', + 'SC_PK_PM_FULL_TILE_WAVE_BRK_1H', + 'SC_PK_PM_MAX_CLK_CNT_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_MAX_DEALLOC_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_MAX_REZ_CNT_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_OREO_CONFLICT_QUAD_FORCE_EOV_WAVE_BRK_1H', + 'SC_PK_PM_PKR_FILL_4X2_WAVE_BRK_1H', + 'SC_PK_PM_SPLIT_OR_FILL_4X2_WAVE_BRK_1H', + 'SC_PK_PM_VRS_RATE_X_00_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_00_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_01_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_10_Y_11_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_00_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_01_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_10_QUAD', + 'SC_PK_PM_VRS_RATE_X_11_Y_11_QUAD', + 'SC_PK_PM_WAVE_BREAK_OUTSIDE_REGION_WAVE_BRK_1H', + 'SC_PSSW_WINDOW_VALID', 'SC_PSSW_WINDOW_VALID_BUSY', + 'SC_PS_ARB_PA_SC_BUSY', 'SC_PS_ARB_SC_BUSY', + 'SC_PS_ARB_STALLED_FROM_BELOW', 'SC_PS_ARB_STARVED_FROM_ABOVE', + 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', 'SC_PS_CTX_DONE_FIFO_POP', + 'SC_PS_CTX_DONE_FIFO_PUSH', 'SC_PS_PA0_SC_FIFO_EMPTY', + 'SC_PS_PA0_SC_FIFO_FULL', 'SC_PS_PM_PBB_TO_PSE_FIFO_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PBB_TO_PSE_FIFO_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_PFF_PW_FULL', + 'SC_PS_PM_PBB_TO_PSE_FIFO_WE_STALL_BY_ZFF_PW_FULL', + 'SC_PS_PM_PFF_PW_FULL', 'SC_PS_PM_ZFF_PW_FULL', + 'SC_PS_TO_BE_SCLK_GATE_STALL', 'SC_PS_TS_EVENT_FIFO_POP', + 'SC_PS_TS_EVENT_FIFO_PUSH', 'SC_PWS_CS_EVENTS_PWS_ENABLE', + 'SC_PWS_P0_CS_SYNC_COMPLETE', 'SC_PWS_P0_PS_SYNC_COMPLETE', + 'SC_PWS_P0_TS_SYNC_COMPLETE', 'SC_PWS_P1_CS_SYNC_COMPLETE', + 'SC_PWS_P1_PS_SYNC_COMPLETE', 'SC_PWS_P1_TS_SYNC_COMPLETE', + 'SC_PWS_PS_EVENTS_PWS_ENABLE', 'SC_PWS_STALLED', + 'SC_PWS_TS_EVENTS_PWS_ENABLE', 'SC_PW_BM_PASS_EMPTY_PRIM', + 'SC_QZ0_QUAD_COUNT', 'SC_QZ0_QUAD_PER_TILE_H0', + 'SC_QZ0_QUAD_PER_TILE_H1', 'SC_QZ0_QUAD_PER_TILE_H10', + 'SC_QZ0_QUAD_PER_TILE_H11', 'SC_QZ0_QUAD_PER_TILE_H12', + 'SC_QZ0_QUAD_PER_TILE_H13', 'SC_QZ0_QUAD_PER_TILE_H14', + 'SC_QZ0_QUAD_PER_TILE_H15', 'SC_QZ0_QUAD_PER_TILE_H16', + 'SC_QZ0_QUAD_PER_TILE_H2', 'SC_QZ0_QUAD_PER_TILE_H3', + 'SC_QZ0_QUAD_PER_TILE_H4', 'SC_QZ0_QUAD_PER_TILE_H5', + 'SC_QZ0_QUAD_PER_TILE_H6', 'SC_QZ0_QUAD_PER_TILE_H7', + 'SC_QZ0_QUAD_PER_TILE_H8', 'SC_QZ0_QUAD_PER_TILE_H9', + 'SC_QZ0_TILE_COUNT', 'SC_QZ0_TILE_COVERED_COUNT', + 'SC_QZ0_TILE_NOT_COVERED_COUNT', 'SC_QZQP_WINDOW_VALID', + 'SC_QZQP_WINDOW_VALID_BUSY', 'SC_REG_SCLK_BUSY', 'SC_RESERVED_60', + 'SC_SCB_BUSY', 'SC_SCF_SCB_INTERFACE_BUSY', 'SC_SCISSOR_DISCARD', + 'SC_SEND_DB_VPZ', 'SC_SPIBC_FULL_FREEZE', 'SC_SPI_CREDIT_AT_MAX', + 'SC_SPI_CREDIT_AT_MAX_NO_PENDING_SEND', + 'SC_SPI_CREDIT_AT_ZERO_WITH_PENDING_SEND', 'SC_SPI_DEALLOC_4_0', + 'SC_SPI_DEALLOC_7_5', 'SC_SPI_EVENT', 'SC_SPI_FPOV_4_0', + 'SC_SPI_FPOV_7_5', 'SC_SPI_SEND', 'SC_SPI_WAVE_STALLED_BY_SPI', + 'SC_SRPS_WINDOW_VALID', 'SC_SRPS_WINDOW_VALID_BUSY', + 'SC_STALLED_BY_BCI', 'SC_STALLED_BY_DB0_TILEFIFO', + 'SC_STALLED_BY_DB_QUAD', 'SC_STALLED_BY_DB_TILE', + 'SC_STALLED_BY_PRIMFIFO', 'SC_STALLED_BY_QUADFIFO', + 'SC_STALLED_BY_SPI', 'SC_STALLED_BY_TILEFIFO', + 'SC_STALLED_BY_TILEORDERFIFO', 'SC_STARVED_BY_DB_QUAD', + 'SC_STARVED_BY_DB_TILE', 'SC_STARVED_BY_PA', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 'SC_SUPERTILE_COUNT', + 'SC_SUPERTILE_COUNT_EXCLUDE_PASS_EMPTY_PRIM', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H0', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H10', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H12', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H14', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H16', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H3', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H5', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H7', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_EXCLUDE_PASS_EMPTY_PRIM_H9', + 'SC_SUPERTILE_PER_PRIM_H0', 'SC_SUPERTILE_PER_PRIM_H1', + 'SC_SUPERTILE_PER_PRIM_H10', 'SC_SUPERTILE_PER_PRIM_H11', + 'SC_SUPERTILE_PER_PRIM_H12', 'SC_SUPERTILE_PER_PRIM_H13', + 'SC_SUPERTILE_PER_PRIM_H14', 'SC_SUPERTILE_PER_PRIM_H15', + 'SC_SUPERTILE_PER_PRIM_H16', 'SC_SUPERTILE_PER_PRIM_H2', + 'SC_SUPERTILE_PER_PRIM_H3', 'SC_SUPERTILE_PER_PRIM_H4', + 'SC_SUPERTILE_PER_PRIM_H5', 'SC_SUPERTILE_PER_PRIM_H6', + 'SC_SUPERTILE_PER_PRIM_H7', 'SC_SUPERTILE_PER_PRIM_H8', + 'SC_SUPERTILE_PER_PRIM_H9', 'SC_TILE_PER_PRIM_H0', + 'SC_TILE_PER_PRIM_H1', 'SC_TILE_PER_PRIM_H10', + 'SC_TILE_PER_PRIM_H11', 'SC_TILE_PER_PRIM_H12', + 'SC_TILE_PER_PRIM_H13', 'SC_TILE_PER_PRIM_H14', + 'SC_TILE_PER_PRIM_H15', 'SC_TILE_PER_PRIM_H16', + 'SC_TILE_PER_PRIM_H2', 'SC_TILE_PER_PRIM_H3', + 'SC_TILE_PER_PRIM_H4', 'SC_TILE_PER_PRIM_H5', + 'SC_TILE_PER_PRIM_H6', 'SC_TILE_PER_PRIM_H7', + 'SC_TILE_PER_PRIM_H8', 'SC_TILE_PER_PRIM_H9', + 'SC_TILE_PER_SUPERTILE_H0', 'SC_TILE_PER_SUPERTILE_H1', + 'SC_TILE_PER_SUPERTILE_H10', 'SC_TILE_PER_SUPERTILE_H11', + 'SC_TILE_PER_SUPERTILE_H12', 'SC_TILE_PER_SUPERTILE_H13', + 'SC_TILE_PER_SUPERTILE_H14', 'SC_TILE_PER_SUPERTILE_H15', + 'SC_TILE_PER_SUPERTILE_H16', 'SC_TILE_PER_SUPERTILE_H2', + 'SC_TILE_PER_SUPERTILE_H3', 'SC_TILE_PER_SUPERTILE_H4', + 'SC_TILE_PER_SUPERTILE_H5', 'SC_TILE_PER_SUPERTILE_H6', + 'SC_TILE_PER_SUPERTILE_H7', 'SC_TILE_PER_SUPERTILE_H8', + 'SC_TILE_PER_SUPERTILE_H9', 'SC_TILE_PICKED_H1', + 'SC_TPQZ_WINDOW_VALID', 'SC_TPQZ_WINDOW_VALID_BUSY', + 'SC_TRPK_WINDOW_VALID', 'SC_TRPK_WINDOW_VALID_BUSY', 'SC_UR_1X', + 'SC_UR_2X', 'SC_UR_4X', 'SC_UR_8X', 'SC_VRC_ACK_OUTPUT_STALL', + 'SC_VRC_BUSY', 'SC_VRC_DIRTY_SECTORS_FLUSHED', + 'SC_VRC_EVICT_NONZERO_INFLIGHT_STALL', 'SC_VRC_FLUSH', + 'SC_VRC_FLUSH_DONE_STALL', 'SC_VRC_FLUSH_EVICT_STALL', + 'SC_VRC_FLUSH_FIP_HIT_STALL', 'SC_VRC_FLUSH_REFLUSH_STALL', + 'SC_VRC_FLUSH_STALL', 'SC_VRC_FLUSH_WRREQ_DRAIN_STALL', + 'SC_VRC_GL1X_RD_REQ', 'SC_VRC_GL1X_RD_RET', + 'SC_VRC_GL1X_RD_XNACK', 'SC_VRC_GL1X_REQ_STALLED', + 'SC_VRC_GL1X_SRC_STALLED', 'SC_VRC_GL1X_SRC_XFR', + 'SC_VRC_GL1X_WR_ACK', 'SC_VRC_GL1X_WR_REQ', + 'SC_VRC_GL1X_WR_XNACK', 'SC_VRC_HINTMEM_RE_CNT', + 'SC_VRC_HINTMEM_WE_CNT', 'SC_VRC_HPF_EVENT', 'SC_VRC_HPF_REQ', + 'SC_VRC_HPF_STALLED', 'SC_VRC_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'SC_VRC_LRU_EVICT_PENDING_EVICT_STALL', + 'SC_VRC_LRU_EVICT_SCHEDULED_EVICT_STALL', + 'SC_VRC_LRU_EVICT_STALL', 'SC_VRC_PROBE_ACK_TILES', + 'SC_VRC_RATEMEM_RE_CNT', 'SC_VRC_RATEMEM_WE_CNT', + 'SC_VRC_READ_OUTPUT_STALL', 'SC_VRC_REEVICTION_STALL', + 'SC_VRC_REPLACE_FLUSH_IN_PROGRESS_STALL', + 'SC_VRC_REPLACE_PENDING_EVICT_STALL', + 'SC_VRC_REPLACE_SCHEDULED_EVICT_STALL', 'SC_VRC_SECTORS_FLUSHED', + 'SC_VRC_SECTOR_HIT', 'SC_VRC_SECTOR_MISS', 'SC_VRC_STALL', + 'SC_VRC_TAGS_FLUSHED', 'SC_VRC_TAG_MISS', + 'SC_VRC_WRITE_OUTPUT_STALL', 'SC_VRS_BE_BUSY', + 'SC_VRS_COMB_MODE_MAX', 'SC_VRS_COMB_MODE_MIN', + 'SC_VRS_COMB_MODE_OVERRIDE', 'SC_VRS_COMB_MODE_PASSTHRU', + 'SC_VRS_COMB_MODE_SATURATE', 'SDMA_PERFMON_SEL', + 'SDMA_PERFMON_SEL_CE_AFIFO_FULL', 'SDMA_PERFMON_SEL_CE_DST_IDLE', + 'SDMA_PERFMON_SEL_CE_INFO1_FULL', 'SDMA_PERFMON_SEL_CE_INFO_FULL', + 'SDMA_PERFMON_SEL_CE_IN_IDLE', 'SDMA_PERFMON_SEL_CE_L1_WR_VLD', + 'SDMA_PERFMON_SEL_CE_OUT_IDLE', 'SDMA_PERFMON_SEL_CE_RD_STALL', + 'SDMA_PERFMON_SEL_CE_RREQ_IDLE', 'SDMA_PERFMON_SEL_CE_SPLIT_IDLE', + 'SDMA_PERFMON_SEL_CE_WREQ_IDLE', 'SDMA_PERFMON_SEL_CE_WR_IDLE', + 'SDMA_PERFMON_SEL_CE_WR_STALL', + 'SDMA_PERFMON_SEL_CPF_SDMA_INVREQ', 'SDMA_PERFMON_SEL_CTX_CHANGE', + 'SDMA_PERFMON_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERFMON_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERFMON_SEL_CYCLE', + 'SDMA_PERFMON_SEL_DMA_L1_RD_SEND', + 'SDMA_PERFMON_SEL_DMA_L1_WR_SEND', + 'SDMA_PERFMON_SEL_DMA_MC_RD_SEND', + 'SDMA_PERFMON_SEL_DMA_MC_WR_SEND', 'SDMA_PERFMON_SEL_DOORBELL', + 'SDMA_PERFMON_SEL_DUMMY_0', 'SDMA_PERFMON_SEL_DUMMY_1', + 'SDMA_PERFMON_SEL_EX_IDLE', + 'SDMA_PERFMON_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERFMON_SEL_GCR_RTN', 'SDMA_PERFMON_SEL_GCR_SEND', + 'SDMA_PERFMON_SEL_GPUVM_INV_HIGH', + 'SDMA_PERFMON_SEL_GPUVM_INV_LOW', 'SDMA_PERFMON_SEL_IB_CMD_FULL', + 'SDMA_PERFMON_SEL_IB_CMD_IDLE', 'SDMA_PERFMON_SEL_IDLE', + 'SDMA_PERFMON_SEL_INT_IDLE', 'SDMA_PERFMON_SEL_INT_REQ_COUNT', + 'SDMA_PERFMON_SEL_INT_REQ_STALL', + 'SDMA_PERFMON_SEL_INT_RESP_ACCEPTED', + 'SDMA_PERFMON_SEL_INT_RESP_RETRY', + 'SDMA_PERFMON_SEL_L1_RDL2_IDLE', 'SDMA_PERFMON_SEL_L1_RDMC_IDLE', + 'SDMA_PERFMON_SEL_L1_RD_INV_IDLE', + 'SDMA_PERFMON_SEL_L1_WRL2_IDLE', 'SDMA_PERFMON_SEL_L1_WRMC_IDLE', + 'SDMA_PERFMON_SEL_L1_WR_INV_IDLE', + 'SDMA_PERFMON_SEL_L2_META_RET_VLD', + 'SDMA_PERFMON_SEL_MCU_L1_WR_VLD', 'SDMA_PERFMON_SEL_MC_RD_COUNT', + 'SDMA_PERFMON_SEL_MC_RD_IDLE', + 'SDMA_PERFMON_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERFMON_SEL_MC_RD_RET_STALL', + 'SDMA_PERFMON_SEL_MC_WR_COUNT', 'SDMA_PERFMON_SEL_MC_WR_IDLE', + 'SDMA_PERFMON_SEL_META_L2_REQ_SEND', + 'SDMA_PERFMON_SEL_META_REQ_SEND', 'SDMA_PERFMON_SEL_META_RTN_VLD', + 'SDMA_PERFMON_SEL_MMHUB_TAG_DELAY_COUNTER', + 'SDMA_PERFMON_SEL_NUM_PACKET', 'SDMA_PERFMON_SEL_QUEUE0_SELECT', + 'SDMA_PERFMON_SEL_QUEUE1_SELECT', + 'SDMA_PERFMON_SEL_QUEUE2_SELECT', + 'SDMA_PERFMON_SEL_QUEUE3_SELECT', 'SDMA_PERFMON_SEL_RB_CMD_FULL', + 'SDMA_PERFMON_SEL_RB_CMD_IDLE', 'SDMA_PERFMON_SEL_RB_EMPTY', + 'SDMA_PERFMON_SEL_RB_FULL', 'SDMA_PERFMON_SEL_RB_RPTR_WB', + 'SDMA_PERFMON_SEL_RB_RPTR_WRAP', + 'SDMA_PERFMON_SEL_RB_WPTR_POLL_READ', + 'SDMA_PERFMON_SEL_RB_WPTR_WRAP', 'SDMA_PERFMON_SEL_RD_BA_RTR', + 'SDMA_PERFMON_SEL_REG_IDLE', 'SDMA_PERFMON_SEL_SDMA_CPF_INVACK', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_INVACK_ALL', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_RD_SEND', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_SEND', + 'SDMA_PERFMON_SEL_SDMA_UTCL2_WR_SEND', + 'SDMA_PERFMON_SEL_SEM_IDLE', 'SDMA_PERFMON_SEL_SEM_REQ_COUNT', + 'SDMA_PERFMON_SEL_SEM_REQ_STALL', + 'SDMA_PERFMON_SEL_SEM_RESP_FAIL', + 'SDMA_PERFMON_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERFMON_SEL_SEM_RESP_PASS', + 'SDMA_PERFMON_SEL_SRBM_REG_SEND', 'SDMA_PERFMON_SEL_TLBI_RTN', + 'SDMA_PERFMON_SEL_TLBI_SEND', + 'SDMA_PERFMON_SEL_UTCL1_TAG_DELAY_COUNTER', + 'SDMA_PERFMON_SEL_UTCL2_FREE', 'SDMA_PERFMON_SEL_UTCL2_RET_ACK', + 'SDMA_PERFMON_SEL_UTCL2_RET_XNACK', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_INVREQ_ALL', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_RD_RTN', + 'SDMA_PERFMON_SEL_UTCL2_SDMA_WR_RTN', + 'SDMA_PERFMON_SEL_WR_BA_RTR', 'SDMA_PERF_SEL', + 'SDMA_PERF_SEL_CE_AFIFO_FULL', 'SDMA_PERF_SEL_CE_BUSY', + 'SDMA_PERF_SEL_CE_BUSY_END', 'SDMA_PERF_SEL_CE_BUSY_START', + 'SDMA_PERF_SEL_CE_CH_RDREQ_SEND', + 'SDMA_PERF_SEL_CE_CH_WRREQ_SEND', 'SDMA_PERF_SEL_CE_CH_WR_REQ', + 'SDMA_PERF_SEL_CE_CH_WR_RET', 'SDMA_PERF_SEL_CE_DST_IDLE', + 'SDMA_PERF_SEL_CE_INFO1_FULL', 'SDMA_PERF_SEL_CE_INFO_FULL', + 'SDMA_PERF_SEL_CE_IN_IDLE', 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 'SDMA_PERF_SEL_CE_OR_MCU_CH_RD_REQ', + 'SDMA_PERF_SEL_CE_OR_MCU_CH_RD_RET', 'SDMA_PERF_SEL_CE_OUT_IDLE', + 'SDMA_PERF_SEL_CE_RD_STALL', 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 'SDMA_PERF_SEL_CE_SPLIT_IDLE', 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 'SDMA_PERF_SEL_CE_WR_IDLE', 'SDMA_PERF_SEL_CE_WR_STALL', + 'SDMA_PERF_SEL_CGCG_FENCE', 'SDMA_PERF_SEL_CH_CE_RDRET_VALID', + 'SDMA_PERF_SEL_CH_CE_WRRET_VALID', 'SDMA_PERF_SEL_CMD_OP_END', + 'SDMA_PERF_SEL_CMD_OP_MATCH', 'SDMA_PERF_SEL_CMD_OP_START', + 'SDMA_PERF_SEL_CPF_SDMA_INVREQ', 'SDMA_PERF_SEL_CTX_CHANGE', + 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERF_SEL_CYCLE', + 'SDMA_PERF_SEL_DMA_L1_RD_SEND', 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 'SDMA_PERF_SEL_DMA_MC_RD_SEND', 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 'SDMA_PERF_SEL_DOORBELL', 'SDMA_PERF_SEL_DUMMY_0', + 'SDMA_PERF_SEL_DUMMY_1', 'SDMA_PERF_SEL_EX_IDLE', + 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERF_SEL_GCR_RTN', 'SDMA_PERF_SEL_GCR_SEND', + 'SDMA_PERF_SEL_GPUVM_INV_HIGH', 'SDMA_PERF_SEL_GPUVM_INV_LOW', + 'SDMA_PERF_SEL_IB_CH_RD_REQ', 'SDMA_PERF_SEL_IB_CH_RD_RET', + 'SDMA_PERF_SEL_IB_CMD_FULL', 'SDMA_PERF_SEL_IB_CMD_IDLE', + 'SDMA_PERF_SEL_IDLE', 'SDMA_PERF_SEL_INT_IDLE', + 'SDMA_PERF_SEL_INT_REQ_COUNT', 'SDMA_PERF_SEL_INT_REQ_STALL', + 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', 'SDMA_PERF_SEL_INT_RESP_RETRY', + 'SDMA_PERF_SEL_L1_RDL2_IDLE', 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 'SDMA_PERF_SEL_L1_RD_INV_IDLE', 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 'SDMA_PERF_SEL_L1_WRMC_IDLE', 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 'SDMA_PERF_SEL_L2_META_RET_VLD', 'SDMA_PERF_SEL_MCU_CH_WR_REQ', + 'SDMA_PERF_SEL_MCU_CH_WR_RET', 'SDMA_PERF_SEL_MCU_L1_WR_VLD', + 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER', + 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_END', + 'SDMA_PERF_SEL_MCU_PERFCNT_TRIGGER_START', + 'SDMA_PERF_SEL_MC_RD_COUNT', 'SDMA_PERF_SEL_MC_RD_IDLE', + 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERF_SEL_MC_RD_RET_STALL', 'SDMA_PERF_SEL_MC_WR_COUNT', + 'SDMA_PERF_SEL_MC_WR_IDLE', 'SDMA_PERF_SEL_META_L2_REQ_SEND', + 'SDMA_PERF_SEL_META_REQ_SEND', 'SDMA_PERF_SEL_META_RTN_VLD', + 'SDMA_PERF_SEL_NUM_PACKET', 'SDMA_PERF_SEL_QUEUE0_SELECT', + 'SDMA_PERF_SEL_QUEUE1_SELECT', 'SDMA_PERF_SEL_QUEUE2_SELECT', + 'SDMA_PERF_SEL_QUEUE3_SELECT', 'SDMA_PERF_SEL_QUEUE4_SELECT', + 'SDMA_PERF_SEL_QUEUE5_SELECT', 'SDMA_PERF_SEL_QUEUE6_SELECT', + 'SDMA_PERF_SEL_QUEUE7_SELECT', 'SDMA_PERF_SEL_RB_CH_RD_REQ', + 'SDMA_PERF_SEL_RB_CH_RD_RET', 'SDMA_PERF_SEL_RB_CMD_FULL', + 'SDMA_PERF_SEL_RB_CMD_IDLE', 'SDMA_PERF_SEL_RB_EMPTY', + 'SDMA_PERF_SEL_RB_FULL', 'SDMA_PERF_SEL_RB_RPTR_WB', + 'SDMA_PERF_SEL_RB_RPTR_WRAP', 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', + 'SDMA_PERF_SEL_RB_WPTR_WRAP', 'SDMA_PERF_SEL_RD_BA_RTR', + 'SDMA_PERF_SEL_REG_IDLE', 'SDMA_PERF_SEL_SDMA_CPF_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK', + 'SDMA_PERF_SEL_SDMA_UTCL2_INVACK_ALL', + 'SDMA_PERF_SEL_SDMA_UTCL2_RD_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_SEND', + 'SDMA_PERF_SEL_SDMA_UTCL2_WR_SEND', 'SDMA_PERF_SEL_SEM_IDLE', + 'SDMA_PERF_SEL_SEM_REQ_COUNT', 'SDMA_PERF_SEL_SEM_REQ_STALL', + 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERF_SEL_SEM_RESP_PASS', 'SDMA_PERF_SEL_SRBM_REG_SEND', + 'SDMA_PERF_SEL_TLBI_RTN', 'SDMA_PERF_SEL_TLBI_SEND', + 'SDMA_PERF_SEL_UTCL1_UTCL2_REQ', 'SDMA_PERF_SEL_UTCL1_UTCL2_RET', + 'SDMA_PERF_SEL_UTCL2_FREE', 'SDMA_PERF_SEL_UTCL2_RET_ACK', + 'SDMA_PERF_SEL_UTCL2_RET_XNACK', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ', + 'SDMA_PERF_SEL_UTCL2_SDMA_INVREQ_ALL', + 'SDMA_PERF_SEL_UTCL2_SDMA_RD_RTN', + 'SDMA_PERF_SEL_UTCL2_SDMA_WR_RTN', 'SDMA_PERF_SEL_WPTR_CH_RD_REQ', + 'SDMA_PERF_SEL_WPTR_CH_RD_RET', 'SDMA_PERF_SEL_WR_BA_RTR', + 'SEC_GSP0_PRIORITY_HIGH', 'SEC_GSP0_PRIORITY_LOW', 'SEGMENTS_1', + 'SEGMENTS_128', 'SEGMENTS_16', 'SEGMENTS_2', 'SEGMENTS_32', + 'SEGMENTS_4', 'SEGMENTS_64', 'SEGMENTS_8', 'SEL_DTBCLK_P0', + 'SEL_DTBCLK_P1', 'SEL_DTBCLK_P2', 'SEL_DTBCLK_P3', + 'SEND_AT_EARLIEST_TIME', 'SEND_AT_LINK_NUMBER', + 'SEND_NORMAL_PACKET', 'SEND_PPS_PACKET', 'SET_SMU_MSG_INTR', + 'SH_MEM_ADDRESS_MODE', 'SH_MEM_ADDRESS_MODE_32', + 'SH_MEM_ADDRESS_MODE_64', 'SH_MEM_ALIGNMENT_MODE', + 'SH_MEM_ALIGNMENT_MODE_DWORD', + 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 'SH_MEM_ALIGNMENT_MODE_STRICT', 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', + 'SIGNED', 'SIMM16_WAITCNT_DEPCTR_HOLD_CNT_SIZE', + 'SIMM16_WAITCNT_DEPCTR_HOLD_CNT_START', + 'SIMM16_WAITCNT_DEPCTR_SA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_SA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SDST_START', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_SSRC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VCC_START', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VA_VDST_START', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_SIZE', + 'SIMM16_WAITCNT_DEPCTR_VM_VSRC_START', + 'SIMM16_WAITCNT_EXP_CNT_SIZE', 'SIMM16_WAITCNT_EXP_CNT_START', + 'SIMM16_WAITCNT_LGKM_CNT_SIZE', 'SIMM16_WAITCNT_LGKM_CNT_START', + 'SIMM16_WAITCNT_VM_CNT_SIZE', 'SIMM16_WAITCNT_VM_CNT_START', + 'SIMM16_WAIT_EVENT_EXP_RDY_SIZE', + 'SIMM16_WAIT_EVENT_EXP_RDY_START', 'SIZE_16K', 'SIZE_8K', + 'SLVERR', 'SMU_INTR', 'SMU_INTR_STATUS_CLEAR', + 'SMU_INTR_STATUS_NOOP', 'SMU_MSG_INTR_NOOP', 'SM_MODE_RESERVED', + 'SOFT_RESET', 'SOFT_RESET_0', 'SOFT_RESET_1', + 'SO_VGTSTREAMOUT_FLUSH', 'SPI_FOG_EXP', 'SPI_FOG_EXP2', + 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', 'SPI_FOG_NONE', + 'SPI_LB_WAVES_RSVD', 'SPI_LB_WAVES_SELECT', 'SPI_PERFCNT_SEL', + 'SPI_PERF_ALL_PS_WAVE', 'SPI_PERF_ALL_PS_WAVE_IN_FLIGHT', + 'SPI_PERF_ALL_WAVE', 'SPI_PERF_ALL_WAVE_IN_FLIGHT', + 'SPI_PERF_ALL_WAVE_ITEMS', 'SPI_PERF_ALL_WAVE_ITEMS_W32', + 'SPI_PERF_ALL_WAVE_ITEMS_W64', 'SPI_PERF_ALL_WAVE_RESTORED', + 'SPI_PERF_ALL_WAVE_SAVED', 'SPI_PERF_ALL_WAVE_W32', + 'SPI_PERF_ALL_WAVE_W64', 'SPI_PERF_BUSY', 'SPI_PERF_CSGN_BUSY', + 'SPI_PERF_CSGN_CRAWLER_STALL', 'SPI_PERF_CSGN_EVENT_WAVE', + 'SPI_PERF_CSGN_NUM_THREADGROUPS', 'SPI_PERF_CSGN_PWS_STALL', + 'SPI_PERF_CSGN_WAVE', 'SPI_PERF_CSGN_WAVE_IN_FLIGHT', + 'SPI_PERF_CSGN_WINDOW_VALID', 'SPI_PERF_CSG_TEMP_ALLOC_LEVEL', + 'SPI_PERF_CSN_BUSY', 'SPI_PERF_CSN_CRAWLER_STALL', + 'SPI_PERF_CSN_EVENT_WAVE', 'SPI_PERF_CSN_NUM_THREADGROUPS', + 'SPI_PERF_CSN_TEMP_ALLOC_LEVEL', 'SPI_PERF_CSN_WAVE', + 'SPI_PERF_CSN_WAVE_IN_FLIGHT', 'SPI_PERF_CSN_WINDOW_VALID', + 'SPI_PERF_EXPORT_DB0_STALL', 'SPI_PERF_EXPORT_DB1_STALL', + 'SPI_PERF_EXPORT_DB2_STALL', 'SPI_PERF_EXPORT_DB3_STALL', + 'SPI_PERF_EXPORT_DB4_STALL', 'SPI_PERF_EXPORT_DB5_STALL', + 'SPI_PERF_EXPORT_DB6_STALL', 'SPI_PERF_EXPORT_DB7_STALL', + 'SPI_PERF_EXPORT_SCB0_STALL', 'SPI_PERF_EXPORT_SCB1_STALL', + 'SPI_PERF_EXPORT_SCB2_STALL', 'SPI_PERF_EXPORT_SCB3_STALL', + 'SPI_PERF_EXP_ARB_COL_CNT', 'SPI_PERF_EXP_ARB_GDS_CNT', + 'SPI_PERF_EXP_ARB_IDX_CNT', 'SPI_PERF_EXP_ARB_POS_CNT', + 'SPI_PERF_EXP_THROT_CAUSALITY_DETECTED', + 'SPI_PERF_EXP_THROT_DOWNSTEP', 'SPI_PERF_EXP_THROT_UPSTEP', + 'SPI_PERF_EXP_WITH_CONFLICT', 'SPI_PERF_EXP_WITH_CONFLICT_CLEAR', + 'SPI_PERF_GFX_TEMP_ALLOC_LEVEL', 'SPI_PERF_GS_ALLOC_IDX', + 'SPI_PERF_GS_ALLOC_POS', 'SPI_PERF_GS_BUSY', + 'SPI_PERF_GS_CRAWLER_STALL', 'SPI_PERF_GS_EVENT_WAVE', + 'SPI_PERF_GS_EXP_DONE', 'SPI_PERF_GS_FIRST_SUBGRP', + 'SPI_PERF_GS_GRP_LIFETIME', 'SPI_PERF_GS_GRP_LIFETIME_SAMPLE', + 'SPI_PERF_GS_HS_DEALLOC', 'SPI_PERF_GS_INDX0_STALL', + 'SPI_PERF_GS_INDX1_STALL', 'SPI_PERF_GS_NGG_SE_LATE_ALLOC_LIMIT', + 'SPI_PERF_GS_NGG_SE_SEND_GS_ALLOC', + 'SPI_PERF_GS_NGG_STALL_MSG_VAL', 'SPI_PERF_GS_PERS_UPD_FULL0', + 'SPI_PERF_GS_PERS_UPD_FULL1', 'SPI_PERF_GS_POS0_STALL', + 'SPI_PERF_GS_POS1_STALL', 'SPI_PERF_GS_PWS_STALL', + 'SPI_PERF_GS_SCBD_IDX_CLEANUP', 'SPI_PERF_GS_SCBD_POS_CLEANUP', + 'SPI_PERF_GS_WAVE', 'SPI_PERF_GS_WAVE_IN_FLIGHT', + 'SPI_PERF_GS_WINDOW_VALID', 'SPI_PERF_HS_BUSY', + 'SPI_PERF_HS_CRAWLER_STALL', 'SPI_PERF_HS_EVENT_WAVE', + 'SPI_PERF_HS_FIRST_WAVE', 'SPI_PERF_HS_PERS_UPD_FULL0', + 'SPI_PERF_HS_PERS_UPD_FULL1', 'SPI_PERF_HS_PWS_STALL', + 'SPI_PERF_HS_WAVE', 'SPI_PERF_HS_WAVE_IN_FLIGHT', + 'SPI_PERF_HS_WINDOW_VALID', 'SPI_PERF_LDS_ALLOC_LEVEL', + 'SPI_PERF_NUM_EXPGRANT_EXPORTS', + 'SPI_PERF_NUM_GDS_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_GDS_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_GDS_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_GDS_SA1SQ1_EXPORTS', + 'SPI_PERF_NUM_POS_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_POS_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_POS_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_POS_SA1SQ1_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA0SQ0_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA0SQ1_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA1SQ0_EXPORTS', + 'SPI_PERF_NUM_PS_COL_SA1SQ1_EXPORTS', + 'SPI_PERF_PIX_ALLOC_PEND_CNT', 'SPI_PERF_PS0_2_WAVE_GROUPS', + 'SPI_PERF_PS0_ACTIVE', 'SPI_PERF_PS0_BUSY', + 'SPI_PERF_PS0_CRAWLER_STALL', 'SPI_PERF_PS0_DEALLOC', + 'SPI_PERF_PS0_DEALLOC_FULL', 'SPI_PERF_PS0_EVENT_WAVE', + 'SPI_PERF_PS0_EXP_ALLOC_WITH_CONFLICT', + 'SPI_PERF_PS0_LDS_DONE_FULL', 'SPI_PERF_PS0_OPT_WAVE', + 'SPI_PERF_PS0_PRIM_BIN0', 'SPI_PERF_PS0_PRIM_BIN1', + 'SPI_PERF_PS0_WAVE', 'SPI_PERF_PS0_WAVEID_STARVED', + 'SPI_PERF_PS0_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS0_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS0_WAVE_IN_FLIGHT', + 'SPI_PERF_PS0_WINDOW_VALID', 'SPI_PERF_PS1_2_WAVE_GROUPS', + 'SPI_PERF_PS1_ACTIVE', 'SPI_PERF_PS1_BUSY', + 'SPI_PERF_PS1_CRAWLER_STALL', 'SPI_PERF_PS1_DEALLOC', + 'SPI_PERF_PS1_DEALLOC_FULL', 'SPI_PERF_PS1_EVENT_WAVE', + 'SPI_PERF_PS1_EXP_ALLOC_WITH_CONFLICT', + 'SPI_PERF_PS1_LDS_DONE_FULL', 'SPI_PERF_PS1_OPT_WAVE', + 'SPI_PERF_PS1_PRIM_BIN0', 'SPI_PERF_PS1_PRIM_BIN1', + 'SPI_PERF_PS1_WAVE', 'SPI_PERF_PS1_WAVEID_STARVED', + 'SPI_PERF_PS1_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS1_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS1_WAVE_IN_FLIGHT', + 'SPI_PERF_PS1_WINDOW_VALID', 'SPI_PERF_PS2_2_WAVE_GROUPS', + 'SPI_PERF_PS2_ACTIVE', 'SPI_PERF_PS2_BUSY', + 'SPI_PERF_PS2_CRAWLER_STALL', 'SPI_PERF_PS2_DEALLOC', + 'SPI_PERF_PS2_DEALLOC_FULL', 'SPI_PERF_PS2_EVENT_WAVE', + 'SPI_PERF_PS2_EXP_ALLOC_WITH_CONFLICT', + 'SPI_PERF_PS2_LDS_DONE_FULL', 'SPI_PERF_PS2_OPT_WAVE', + 'SPI_PERF_PS2_PRIM_BIN0', 'SPI_PERF_PS2_PRIM_BIN1', + 'SPI_PERF_PS2_WAVE', 'SPI_PERF_PS2_WAVEID_STARVED', + 'SPI_PERF_PS2_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS2_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS2_WAVE_IN_FLIGHT', + 'SPI_PERF_PS2_WINDOW_VALID', 'SPI_PERF_PS3_2_WAVE_GROUPS', + 'SPI_PERF_PS3_ACTIVE', 'SPI_PERF_PS3_BUSY', + 'SPI_PERF_PS3_CRAWLER_STALL', 'SPI_PERF_PS3_DEALLOC', + 'SPI_PERF_PS3_DEALLOC_FULL', 'SPI_PERF_PS3_EVENT_WAVE', + 'SPI_PERF_PS3_EXP_ALLOC_WITH_CONFLICT', + 'SPI_PERF_PS3_LDS_DONE_FULL', 'SPI_PERF_PS3_OPT_WAVE', + 'SPI_PERF_PS3_PRIM_BIN0', 'SPI_PERF_PS3_PRIM_BIN1', + 'SPI_PERF_PS3_WAVE', 'SPI_PERF_PS3_WAVEID_STARVED', + 'SPI_PERF_PS3_WAVE_GROUP_CLOCK_DELAY', + 'SPI_PERF_PS3_WAVE_GROUP_TIMEOUTS', 'SPI_PERF_PS3_WAVE_IN_FLIGHT', + 'SPI_PERF_PS3_WINDOW_VALID', 'SPI_PERF_PS_EXP_ALLOC', + 'SPI_PERF_PS_EXP_ARB_CONFLICT', 'SPI_PERF_PS_EXP_DONE', + 'SPI_PERF_PS_PERS_UPD_FULL0', 'SPI_PERF_PS_PERS_UPD_FULL1', + 'SPI_PERF_PS_PWS_STALL', 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM0_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM1_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM2_SIMD_FULL_PS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSG', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_CSN', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_GS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_HS', + 'SPI_PERF_RA_ACCUM3_SIMD_FULL_PS', 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 'SPI_PERF_RA_BAR_CU_FULL_CSN', 'SPI_PERF_RA_BAR_CU_FULL_GS', + 'SPI_PERF_RA_BAR_CU_FULL_HS', 'SPI_PERF_RA_BAR_CU_FULL_PS', + 'SPI_PERF_RA_BULKY_CU_FULL_CSG', 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 'SPI_PERF_RA_CSC_UNDER_TUNNEL', 'SPI_PERF_RA_CSG_LOCK', + 'SPI_PERF_RA_CSN_LOCK', 'SPI_PERF_RA_GFX_UNDER_TUNNEL', + 'SPI_PERF_RA_GS_LDS_OCCUPANCY', 'SPI_PERF_RA_GS_LOCK', + 'SPI_PERF_RA_GS_VGPR_OCCUPANCY', 'SPI_PERF_RA_HS_LOCK', + 'SPI_PERF_RA_LDS_CU_FULL_CSG', 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 'SPI_PERF_RA_LDS_CU_FULL_GS', 'SPI_PERF_RA_LDS_CU_FULL_HS', + 'SPI_PERF_RA_LDS_CU_FULL_PS', 'SPI_PERF_RA_PC_PROBE_STALL_PS', + 'SPI_PERF_RA_PC_PSWAVE_STALL_PS', 'SPI_PERF_RA_PH_THROTTLE', + 'SPI_PERF_RA_PIPE_REQ_BIN2', 'SPI_PERF_RA_PRE_ALLOC_STALL', + 'SPI_PERF_RA_PS_LDS_OCCUPANCY', 'SPI_PERF_RA_PS_VGPR_OCCUPANCY', + 'SPI_PERF_RA_REQ_ALLOC', + 'SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_CU_LEVEL', + 'SPI_PERF_RA_REQ_ALLOC_DYN_VGPR_STALL', + 'SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_LEVEL', + 'SPI_PERF_RA_REQ_ALLOC_WGP_TAKEOVER_STALL', + 'SPI_PERF_RA_REQ_NO_ALLOC', 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 'SPI_PERF_RA_REQ_NO_ALLOC_HS', 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 'SPI_PERF_RA_RES_STALL_CSG', 'SPI_PERF_RA_RES_STALL_CSN', + 'SPI_PERF_RA_RES_STALL_GS', 'SPI_PERF_RA_RES_STALL_HS', + 'SPI_PERF_RA_RES_STALL_PS', 'SPI_PERF_RA_RSV_UPD', + 'SPI_PERF_RA_SPI_THROTTLE', 'SPI_PERF_RA_TASK_REQ_BIN3', + 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 'SPI_PERF_RA_TMP_STALL_CSG', 'SPI_PERF_RA_TMP_STALL_CSN', + 'SPI_PERF_RA_TMP_STALL_GS', 'SPI_PERF_RA_TMP_STALL_HS', + 'SPI_PERF_RA_TMP_STALL_PS', 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 'SPI_PERF_RA_WR_CTL_FULL', 'SPI_PERF_RA_WVALLOC_STALL', + 'SPI_PERF_RA_WVLIM_STALL_CSG', 'SPI_PERF_RA_WVLIM_STALL_CSN', + 'SPI_PERF_RA_WVLIM_STALL_GS', 'SPI_PERF_RA_WVLIM_STALL_HS', + 'SPI_PERF_RA_WVLIM_STALL_PS', 'SPI_PERF_SGPR_INIT', + 'SPI_PERF_SWC_CSGN_WR', 'SPI_PERF_SWC_CSN_WR', + 'SPI_PERF_SWC_GS_WR', 'SPI_PERF_SWC_HS_WR', 'SPI_PERF_SWC_PS_WR', + 'SPI_PERF_VGPR_ALLOC_LEVEL', 'SPI_PERF_VGPR_INIT', + 'SPI_PERF_VWC_CSGN_WR', 'SPI_PERF_VWC_CSN_WR', + 'SPI_PERF_VWC_ES_WR', 'SPI_PERF_VWC_GS_WR', 'SPI_PERF_VWC_HS_WR', + 'SPI_PERF_VWC_LS_WR', 'SPI_PERF_VWC_PS_WR', + 'SPI_PNT_SPRITE_OVERRIDE', 'SPI_PNT_SPRITE_SEL_0', + 'SPI_PNT_SPRITE_SEL_1', 'SPI_PNT_SPRITE_SEL_NONE', + 'SPI_PNT_SPRITE_SEL_S', 'SPI_PNT_SPRITE_SEL_T', + 'SPI_PS_LDS_GROUP_1', 'SPI_PS_LDS_GROUP_2', 'SPI_PS_LDS_GROUP_4', + 'SPI_PS_LDS_GROUP_SIZE', 'SPI_SAMPLE_CNTL', 'SPI_SHADER_1COMP', + 'SPI_SHADER_2COMP', 'SPI_SHADER_32_ABGR', 'SPI_SHADER_32_AR', + 'SPI_SHADER_32_GR', 'SPI_SHADER_32_R', 'SPI_SHADER_4COMP', + 'SPI_SHADER_4COMPRESS', 'SPI_SHADER_EX_FORMAT', + 'SPI_SHADER_FORMAT', 'SPI_SHADER_FP16_ABGR', 'SPI_SHADER_NONE', + 'SPI_SHADER_SINT16_ABGR', 'SPI_SHADER_SNORM16_ABGR', + 'SPI_SHADER_UINT16_ABGR', 'SPI_SHADER_UNORM16_ABGR', + 'SPI_SHADER_ZERO', 'SPM_PERFMON_STATE', 'SPRITE_EN', + 'SP_PERF_SEL_DST_BUF_ALLOC_STALL', + 'SP_PERF_SEL_DST_BUF_EVEN_DIRTY', 'SP_PERF_SEL_DST_BUF_ODD_DIRTY', + 'SP_PERF_SEL_DST_BUF_WB_CONF_W_SPI', + 'SP_PERF_SEL_DST_BUF_WB_CONF_W_TD_LDS', 'SP_PERF_SEL_DUMMY_LAST', + 'SP_PERF_SEL_SRC_CACHE_HIT_B0', 'SP_PERF_SEL_SRC_CACHE_HIT_B1', + 'SP_PERF_SEL_SRC_CACHE_HIT_B2', 'SP_PERF_SEL_SRC_CACHE_HIT_B3', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B0', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B1', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B2', + 'SP_PERF_SEL_SRC_CACHE_PROBE_B3', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B0', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B1', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B2', + 'SP_PERF_SEL_SRC_CACHE_PROBE_SUCCESS_B3', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B0', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B1', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B2', + 'SP_PERF_SEL_SRC_CACHE_RECYCLE_HIT_B3', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B0', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B1', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B2', + 'SP_PERF_SEL_SRC_CACHE_VGPR_RD_B3', + 'SP_PERF_SEL_VALU_COEXEC_WITH_TRANS', + 'SP_PERF_SEL_VALU_EXEC_MASK_CHANGE', + 'SP_PERF_SEL_VALU_FAST_OP_STALL_VGPR_NOT_READY', + 'SP_PERF_SEL_VALU_OPERAND', + 'SP_PERF_SEL_VALU_OPERAND_FROM_DST_BUF', + 'SP_PERF_SEL_VALU_PENDING_QUEUE_STALL', + 'SP_PERF_SEL_VALU_SGPR_FWD_BUF_FULL', 'SP_PERF_SEL_VALU_STALL', + 'SP_PERF_SEL_VALU_STALL_DST_STALL', + 'SP_PERF_SEL_VALU_STALL_SDST_FWD', + 'SP_PERF_SEL_VALU_STALL_SGPR_NOT_READY', + 'SP_PERF_SEL_VALU_STALL_VDST_FWD', + 'SP_PERF_SEL_VALU_STALL_VGPR_NOT_READY', + 'SP_PERF_SEL_VALU_VGPR_OPERAND', + 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_EXP', + 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_LDS', + 'SP_PERF_SEL_VALU_VGPR_RD_CONFLICT_TEX', + 'SP_PERF_SEL_VGPR_EXP_RD', 'SP_PERF_SEL_VGPR_RD', + 'SP_PERF_SEL_VGPR_SPI_WR', 'SP_PERF_SEL_VGPR_TDLDS_DATA_WR', + 'SP_PERF_SEL_VGPR_VMEM_RD', 'SP_PERF_SEL_VGPR_WR', + 'SP_PERF_SEL_VGPR_WR_KILL', 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_DCACHE_FLAT_REQ', 'SQC_PERF_SEL_DCACHE_GCR', + 'SQC_PERF_SEL_DCACHE_GCR_HITS', + 'SQC_PERF_SEL_DCACHE_GCR_INVALIDATE', 'SQC_PERF_SEL_DCACHE_HITS', + 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_DCACHE_INVAL_INST', 'SQC_PERF_SEL_DCACHE_MISSES', + 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 'SQC_PERF_SEL_DCACHE_PREFETCH_MISSES', + 'SQC_PERF_SEL_DCACHE_PREFETCH_REQ_CACHELINES', + 'SQC_PERF_SEL_DCACHE_REQ', 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 'SQC_PERF_SEL_DCACHE_SPI_RETURN_STALL', + 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DUMMY_LAST', 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_GCR', 'SQC_PERF_SEL_ICACHE_GCR_HITS', + 'SQC_PERF_SEL_ICACHE_GCR_INVALIDATE', 'SQC_PERF_SEL_ICACHE_HITS', + 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_ICACHE_INVAL_INST', 'SQC_PERF_SEL_ICACHE_MISSES', + 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 'SQC_PERF_SEL_ICACHE_PREFETCH_MISSES', + 'SQC_PERF_SEL_ICACHE_PREFETCH_REQ_CACHELINES', + 'SQC_PERF_SEL_ICACHE_REQ', + 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_LDS_ACTIVE_ATOMIC_CNT', + 'SQC_PERF_SEL_LDS_ACTIVE_LOAD_CNT', + 'SQC_PERF_SEL_LDS_ACTIVE_STORE_CNT', + 'SQC_PERF_SEL_LDS_ADDR_ACTIVE', 'SQC_PERF_SEL_LDS_ADDR_CONFLICT', + 'SQC_PERF_SEL_LDS_ADDR_STALL', 'SQC_PERF_SEL_LDS_ATOMIC_DWORDS', + 'SQC_PERF_SEL_LDS_ATOMIC_RETURN', + 'SQC_PERF_SEL_LDS_BANKCONF_ATOMIC_CNT', + 'SQC_PERF_SEL_LDS_BANKCONF_LOAD_CNT', + 'SQC_PERF_SEL_LDS_BANKCONF_STORE_CNT', + 'SQC_PERF_SEL_LDS_BANK_CONFLICT', + 'SQC_PERF_SEL_LDS_FP_ADD_CYCLES', 'SQC_PERF_SEL_LDS_IDX_ACTIVE', + 'SQC_PERF_SEL_LDS_LDS_EXECUTION_STALL', + 'SQC_PERF_SEL_LDS_LDS_VGPR_WRITE_STALL', + 'SQC_PERF_SEL_LDS_LOAD_DWORDS', 'SQC_PERF_SEL_LDS_MEM_VIOLATIONS', + 'SQC_PERF_SEL_LDS_PC_LDS_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_SPI_VGPR_WRITE_STALL_TD', + 'SQC_PERF_SEL_LDS_STORE_DWORDS', + 'SQC_PERF_SEL_LDS_TD_VGPR_CONF_STALL', + 'SQC_PERF_SEL_LDS_UNALIGNED_STALL', 'SQC_PERF_SEL_LDS_VGPR_BUSY', + 'SQC_PERF_SEL_SQ_DCACHE_REQS', 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', 'SQC_PERF_SEL_TC_INST_REQ', + 'SQC_PERF_SEL_TC_REQ', 'SQC_PERF_SEL_TC_STALL', + 'SQC_PERF_SEL_TC_STARVE', 'SQC_PERF_SEL_TD_VGPR_BUSY', + 'SQDEC_BEGIN', 'SQDEC_END', 'SQGFXUDEC_BEGIN', 'SQGFXUDEC_END', + 'SQG_PERF_SEL', 'SQG_PERF_SEL_ACCUM_PREV', + 'SQG_PERF_SEL_BUSY_CYCLES', 'SQG_PERF_SEL_CYCLES', + 'SQG_PERF_SEL_DUMMY_LAST', 'SQG_PERF_SEL_EVENTS', + 'SQG_PERF_SEL_EXP_BUS0_BUSY', 'SQG_PERF_SEL_EXP_BUS1_BUSY', + 'SQG_PERF_SEL_EXP_REQ0_BUS_BUSY', + 'SQG_PERF_SEL_EXP_REQ1_BUS_BUSY', 'SQG_PERF_SEL_ITEMS', + 'SQG_PERF_SEL_ITEMS_CS', 'SQG_PERF_SEL_ITEMS_GS', + 'SQG_PERF_SEL_ITEMS_HS', 'SQG_PERF_SEL_ITEMS_PS', + 'SQG_PERF_SEL_LEVEL_WAVES', 'SQG_PERF_SEL_LEVEL_WGP_ACTIVE', + 'SQG_PERF_SEL_MSG', 'SQG_PERF_SEL_MSG_BUS_BUSY', + 'SQG_PERF_SEL_MSG_INTERRUPT', 'SQG_PERF_SEL_NONE', + 'SQG_PERF_SEL_PS_QUADS', 'SQG_PERF_SEL_REFCLKS', + 'SQG_PERF_SEL_TTRACE_LOST_PACKETS', 'SQG_PERF_SEL_TTRACE_STALL', + 'SQG_PERF_SEL_TTRACE_WRITE_DATA', 'SQG_PERF_SEL_WAVE32_ITEMS', + 'SQG_PERF_SEL_WAVE64_ITEMS', 'SQG_PERF_SEL_WAVES', + 'SQG_PERF_SEL_WAVES_32', 'SQG_PERF_SEL_WAVES_64', + 'SQG_PERF_SEL_WAVES_CS_VEC32', 'SQG_PERF_SEL_WAVES_DYN_VGPR', + 'SQG_PERF_SEL_WAVES_EQ_32', 'SQG_PERF_SEL_WAVES_EQ_64', + 'SQG_PERF_SEL_WAVES_GS_VEC32', 'SQG_PERF_SEL_WAVES_HS_VEC32', + 'SQG_PERF_SEL_WAVES_INITIAL_PREFETCH', 'SQG_PERF_SEL_WAVES_LT_16', + 'SQG_PERF_SEL_WAVES_LT_32', 'SQG_PERF_SEL_WAVES_LT_48', + 'SQG_PERF_SEL_WAVES_LT_64', 'SQG_PERF_SEL_WAVES_PS_VEC32', + 'SQG_PERF_SEL_WAVES_RESTORED', 'SQG_PERF_SEL_WAVES_SAVED', + 'SQG_PERF_SEL_WAVES_VEC32', 'SQG_PERF_SEL_WAVES_WGP_TAKEOVER', + 'SQG_PERF_SEL_WAVE_CYCLES', 'SQIND_GLOBAL_REGS_OFFSET', + 'SQIND_GLOBAL_REGS_SIZE', 'SQIND_LOCAL_REGS_OFFSET', + 'SQIND_LOCAL_REGS_SIZE', 'SQIND_WAVE_HOST_REGS_OFFSET', + 'SQIND_WAVE_HOST_REGS_SIZE', 'SQIND_WAVE_HW_REGS_OFFSET', + 'SQIND_WAVE_HW_REGS_SIZE', 'SQIND_WAVE_SGPRS_OFFSET', + 'SQIND_WAVE_SGPRS_SIZE', 'SQIND_WAVE_VGPRS_OFFSET', + 'SQIND_WAVE_VGPRS_SIZE', 'SQPERFDDEC_BEGIN', 'SQPERFDDEC_END', + 'SQPERFSDEC_BEGIN', 'SQPERFSDEC_END', 'SQPWRDEC_BEGIN', + 'SQPWRDEC_END', 'SQ_ARB_STATE_ISSUED_BRMSG', + 'SQ_ARB_STATE_ISSUED_EXPORT', 'SQ_ARB_STATE_ISSUED_LDS', + 'SQ_ARB_STATE_ISSUED_LDS_DIRECT', 'SQ_ARB_STATE_ISSUED_SCALAR', + 'SQ_ARB_STATE_ISSUED_TEX', 'SQ_ARB_STATE_ISSUED_VALU', + 'SQ_ARB_STATE_STALLED_BRMSG', 'SQ_ARB_STATE_STALLED_EXPORT', + 'SQ_ARB_STATE_STALLED_LDS', 'SQ_ARB_STATE_STALLED_LDS_DIRECT', + 'SQ_ARB_STATE_STALLED_SCALAR', 'SQ_ARB_STATE_STALLED_TEX', + 'SQ_ARB_STATE_STALLED_VALU', 'SQ_CAC_POWER_ALU_BUSY', + 'SQ_CAC_POWER_GPR_RD', 'SQ_CAC_POWER_GPR_WR', + 'SQ_CAC_POWER_LDS_BUSY', 'SQ_CAC_POWER_SEL', + 'SQ_CAC_POWER_TEX_BUSY', 'SQ_CAC_POWER_VALU', + 'SQ_CAC_POWER_VALU0', 'SQ_CAC_POWER_VALU1', 'SQ_CAC_POWER_VALU2', + 'SQ_DISPATCHER_GFX_CNT_PER_RING', 'SQ_DISPATCHER_GFX_MIN', + 'SQ_EDC_INFO_SOURCE', 'SQ_EDC_INFO_SOURCE_GDS', + 'SQ_EDC_INFO_SOURCE_INST', 'SQ_EDC_INFO_SOURCE_INVALID', + 'SQ_EDC_INFO_SOURCE_LDS', 'SQ_EDC_INFO_SOURCE_SGPR', + 'SQ_EDC_INFO_SOURCE_TA', 'SQ_EDC_INFO_SOURCE_VGPR', + 'SQ_EX_EXCP_ADDR_WATCH', 'SQ_EX_EXCP_ALU_FLOAT_DIV0', + 'SQ_EX_EXCP_ALU_INEXACT', 'SQ_EX_EXCP_ALU_INPUT_DENORM', + 'SQ_EX_EXCP_ALU_INT_DIV0', 'SQ_EX_EXCP_ALU_INVALID', + 'SQ_EX_EXCP_ALU_OVERFLOW', 'SQ_EX_EXCP_ALU_UNDERFLOW', + 'SQ_EX_EXCP_VALU_BASE', 'SQ_EX_EXCP_VALU_SIZE', 'SQ_FLAT', + 'SQ_GFXDEC_BEGIN', 'SQ_GFXDEC_END', 'SQ_GFXDEC_STATE_ID_SHIFT', + 'SQ_GLOBAL', 'SQ_IBUF_IB_DRET', 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 'SQ_IBUF_IB_EMPTY_WAIT_GNT', 'SQ_IBUF_IB_IDLE', + 'SQ_IBUF_IB_INI_WAIT_DRET', 'SQ_IBUF_IB_INI_WAIT_GNT', + 'SQ_IBUF_IB_LE_4DW', 'SQ_IBUF_IB_WAIT_DRET', 'SQ_IBUF_ST', + 'SQ_IMG_FILTER_MODE_BLEND', 'SQ_IMG_FILTER_MODE_MAX', + 'SQ_IMG_FILTER_MODE_MIN', 'SQ_IMG_FILTER_TYPE', 'SQ_IND_CMD_CMD', + 'SQ_IND_CMD_CMD_KILL', 'SQ_IND_CMD_CMD_NULL', + 'SQ_IND_CMD_CMD_SAVECTX', 'SQ_IND_CMD_CMD_SETFATALHALT', + 'SQ_IND_CMD_CMD_SETHALT', 'SQ_IND_CMD_CMD_SET_SYS_PRIO', + 'SQ_IND_CMD_CMD_SINGLE_STEP', 'SQ_IND_CMD_CMD_TRAP', + 'SQ_IND_CMD_CMD_TRAP_AFTER_INST', 'SQ_IND_CMD_MODE', + 'SQ_IND_CMD_MODE_BROADCAST', 'SQ_IND_CMD_MODE_BROADCAST_ME', + 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', 'SQ_IND_CMD_MODE_SINGLE', + 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', 'SQ_INST_STR_IB_WAVE_NORML', + 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', 'SQ_INST_STR_ST', + 'SQ_INST_TYPE', 'SQ_INST_TYPE_BARRIER', + 'SQ_INST_TYPE_BRANCH_NOT_TAKEN', 'SQ_INST_TYPE_BRANCH_TAKEN', + 'SQ_INST_TYPE_DUAL_VALU', 'SQ_INST_TYPE_EXP', 'SQ_INST_TYPE_FLAT', + 'SQ_INST_TYPE_JUMP', 'SQ_INST_TYPE_LDS', + 'SQ_INST_TYPE_LDS_DIRECT', 'SQ_INST_TYPE_MSG', + 'SQ_INST_TYPE_NONE', 'SQ_INST_TYPE_OTHER', 'SQ_INST_TYPE_SCALAR', + 'SQ_INST_TYPE_TEX', 'SQ_INST_TYPE_VALU', + 'SQ_INST_TYPE_VALU_MATRIX', 'SQ_LLC_0', 'SQ_LLC_1', + 'SQ_LLC_BYPASS', 'SQ_LLC_CTL', 'SQ_LLC_RSVD_2', + 'SQ_MAX_PGM_SGPRS', 'SQ_MAX_PGM_VGPRS', 'SQ_NON_EVENT', + 'SQ_NO_INST_ISSUE', 'SQ_NO_INST_ISSUE_ALU_DEP', + 'SQ_NO_INST_ISSUE_BARRIER_WAIT', 'SQ_NO_INST_ISSUE_INTERNAL', + 'SQ_NO_INST_ISSUE_NO_ARB_WIN', 'SQ_NO_INST_ISSUE_NO_INSTS', + 'SQ_NO_INST_ISSUE_OTHER', 'SQ_NO_INST_ISSUE_SLEEP_WAIT', + 'SQ_NO_INST_ISSUE_S_WAITCNT', 'SQ_OOB_COMPLETE', + 'SQ_OOB_INDEX_AND_OFFSET', 'SQ_OOB_INDEX_ONLY', + 'SQ_OOB_NUM_RECORDS_0', 'SQ_OOB_SELECT', 'SQ_PERF_SEL', + 'SQ_PERF_SEL_ACCUM_PREV', 'SQ_PERF_SEL_BUSY_CYCLES', + 'SQ_PERF_SEL_CYCLES', 'SQ_PERF_SEL_DUMMY_END', + 'SQ_PERF_SEL_DUMMY_LAST', 'SQ_PERF_SEL_EVENTS', + 'SQ_PERF_SEL_EXP_BUS0_BUSY', 'SQ_PERF_SEL_EXP_BUS1_BUSY', + 'SQ_PERF_SEL_EXP_REQ0_BUS_BUSY', 'SQ_PERF_SEL_EXP_REQ1_BUS_BUSY', + 'SQ_PERF_SEL_EXP_REQ_BUS_STALL', 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 'SQ_PERF_SEL_IFETCH_LEVEL', 'SQ_PERF_SEL_IFETCH_REQS', + 'SQ_PERF_SEL_INSTS_ALL', 'SQ_PERF_SEL_INSTS_BARRIER_LOCK', + 'SQ_PERF_SEL_INSTS_BRANCH', 'SQ_PERF_SEL_INSTS_CBRANCH_NOT_TAKEN', + 'SQ_PERF_SEL_INSTS_CBRANCH_TAKEN', 'SQ_PERF_SEL_INSTS_DELAY_ALU', + 'SQ_PERF_SEL_INSTS_DELAY_ALU_COISSUE', + 'SQ_PERF_SEL_INSTS_DUAL_VALU_WAVE32', 'SQ_PERF_SEL_INSTS_EXP', + 'SQ_PERF_SEL_INSTS_EXP_MRT', 'SQ_PERF_SEL_INSTS_EXP_Z', + 'SQ_PERF_SEL_INSTS_FLAT', 'SQ_PERF_SEL_INSTS_FLAT_ATOMIC', + 'SQ_PERF_SEL_INSTS_FLAT_LOAD', 'SQ_PERF_SEL_INSTS_FLAT_STORE', + 'SQ_PERF_SEL_INSTS_GLOBAL_SCRATCH', 'SQ_PERF_SEL_INSTS_INTERNAL', + 'SQ_PERF_SEL_INSTS_LDS', 'SQ_PERF_SEL_INSTS_LDS_DIRECT_LOAD', + 'SQ_PERF_SEL_INSTS_LDS_PARAM_LOAD', 'SQ_PERF_SEL_INSTS_LOCK', + 'SQ_PERF_SEL_INSTS_NON_VALU_EXEC_SKIPPED', + 'SQ_PERF_SEL_INSTS_SALU', 'SQ_PERF_SEL_INSTS_SALU_CS', + 'SQ_PERF_SEL_INSTS_SALU_FLOAT', 'SQ_PERF_SEL_INSTS_SALU_GS', + 'SQ_PERF_SEL_INSTS_SALU_HS', 'SQ_PERF_SEL_INSTS_SALU_PS', + 'SQ_PERF_SEL_INSTS_SENDMSG', 'SQ_PERF_SEL_INSTS_SMEM', + 'SQ_PERF_SEL_INSTS_SMEM_CS', 'SQ_PERF_SEL_INSTS_SMEM_GS', + 'SQ_PERF_SEL_INSTS_SMEM_HS', 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 'SQ_PERF_SEL_INSTS_SMEM_PS', 'SQ_PERF_SEL_INSTS_TEX', + 'SQ_PERF_SEL_INSTS_TEX_ATOMIC_NORTN', + 'SQ_PERF_SEL_INSTS_TEX_ATOMIC_RTN', + 'SQ_PERF_SEL_INSTS_TEX_BLOCK_LOAD', + 'SQ_PERF_SEL_INSTS_TEX_BLOCK_STORE', 'SQ_PERF_SEL_INSTS_TEX_LOAD', + 'SQ_PERF_SEL_INSTS_TEX_SAMPLE', 'SQ_PERF_SEL_INSTS_TEX_STORE', + 'SQ_PERF_SEL_INSTS_VALU', 'SQ_PERF_SEL_INSTS_VALU_1_PASS', + 'SQ_PERF_SEL_INSTS_VALU_2_PASS', 'SQ_PERF_SEL_INSTS_VALU_4_PASS', + 'SQ_PERF_SEL_INSTS_VALU_COISSUE', 'SQ_PERF_SEL_INSTS_VALU_DP', + 'SQ_PERF_SEL_INSTS_VALU_EXEC_SKIPPED', + 'SQ_PERF_SEL_INSTS_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64', + 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_16BIT', + 'SQ_PERF_SEL_INSTS_VALU_ONE_CYCLE_WAVE64_32BIT', + 'SQ_PERF_SEL_INSTS_VALU_TRANS', 'SQ_PERF_SEL_INSTS_VALU_TRANS32', + 'SQ_PERF_SEL_INSTS_VALU_VINTERP', 'SQ_PERF_SEL_INSTS_VEC32', + 'SQ_PERF_SEL_INSTS_VEC32_FLAT', + 'SQ_PERF_SEL_INSTS_VEC32_FLAT_ATOMIC', + 'SQ_PERF_SEL_INSTS_VEC32_FLAT_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_FLAT_STORE', + 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH', + 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_ATOMIC', + 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_GLOBAL_SCRATCH_STORE', + 'SQ_PERF_SEL_INSTS_VEC32_LDS', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_NORTN', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_ATOMIC_RTN', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_OTHER', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_PARAM_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_LDS_STORE', + 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS', + 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_LEVEL_LDS_STORE', + 'SQ_PERF_SEL_INSTS_VEC32_TEX', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_ATOMIC', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_CS', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_GS', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_HS', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_LOAD', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_PS', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_SAMPLE', + 'SQ_PERF_SEL_INSTS_VEC32_TEX_STORE', + 'SQ_PERF_SEL_INSTS_VEC32_VALU', 'SQ_PERF_SEL_INSTS_VEC32_VALU_CS', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_GS', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_HS', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_PS', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_TRANS32', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_VINTERP', + 'SQ_PERF_SEL_INSTS_VEC32_VALU_WMMA', + 'SQ_PERF_SEL_INSTS_VGPR_ALLOC', + 'SQ_PERF_SEL_INSTS_VGPR_ALLOC_FAIL', 'SQ_PERF_SEL_INSTS_WAKEUP', + 'SQ_PERF_SEL_INSTS_WMMA_LOAD', 'SQ_PERF_SEL_INST_BARRIER_STALL', + 'SQ_PERF_SEL_INST_CACHE_REQ_STALL', 'SQ_PERF_SEL_INST_CYCLES_EXP', + 'SQ_PERF_SEL_INST_CYCLES_FLAT', 'SQ_PERF_SEL_INST_CYCLES_LDS', + 'SQ_PERF_SEL_INST_CYCLES_TEX', 'SQ_PERF_SEL_INST_CYCLES_VALU', + 'SQ_PERF_SEL_INST_CYCLES_VALU_NO_COEXEC', + 'SQ_PERF_SEL_INST_CYCLES_VALU_TRANS32', + 'SQ_PERF_SEL_INST_CYCLES_VMEM', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_ATOMIC', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_LOAD', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_STORE', + 'SQ_PERF_SEL_INST_ISSUE_ALL_STALL', + 'SQ_PERF_SEL_INST_ISSUE_EXP_STALL', + 'SQ_PERF_SEL_INST_ISSUE_LDS_STALL', + 'SQ_PERF_SEL_INST_ISSUE_SALU_STALL', + 'SQ_PERF_SEL_INST_ISSUE_SMEM_STALL', + 'SQ_PERF_SEL_INST_ISSUE_TEX_STALL', + 'SQ_PERF_SEL_INST_ISSUE_VALU_STALL', 'SQ_PERF_SEL_INST_LEVEL_EXP', + 'SQ_PERF_SEL_INST_LEVEL_LDS', 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 'SQ_PERF_SEL_INST_LEVEL_TEX_LOAD', + 'SQ_PERF_SEL_INST_LEVEL_TEX_STORE', + 'SQ_PERF_SEL_INST_WAITCNT_STALL', 'SQ_PERF_SEL_IS_CACHE_DUP_MISS', + 'SQ_PERF_SEL_IS_CACHE_MISS', 'SQ_PERF_SEL_IS_CACHE_REQ', + 'SQ_PERF_SEL_ITEMS', 'SQ_PERF_SEL_ITEMS_MAX_VALU', + 'SQ_PERF_SEL_ITEMS_VALU', 'SQ_PERF_SEL_ITEM_CYCLES_VALU', + 'SQ_PERF_SEL_ITEM_CYCLES_VMEM', + 'SQ_PERF_SEL_LDS_DIRECT_CMD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_LEVEL_WAVES', 'SQ_PERF_SEL_MSG', + 'SQ_PERF_SEL_MSG_BUS_BUSY', 'SQ_PERF_SEL_MSG_FIFO_FULL_STALL', + 'SQ_PERF_SEL_MSG_INTERRUPT', 'SQ_PERF_SEL_NONE', + 'SQ_PERF_SEL_NONE2', 'SQ_PERF_SEL_OVERFLOW_PREV', + 'SQ_PERF_SEL_PS_QUADS', 'SQ_PERF_SEL_SALU_GATHER_FULL_STALL', + 'SQ_PERF_SEL_SALU_PIPE_STALL', 'SQ_PERF_SEL_SALU_SGATHER_STALL', + 'SQ_PERF_SEL_SALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_SMEM_DCACHE_RETURN_CYCLES', + 'SQ_PERF_SEL_SP_CONST_CYCLES', + 'SQ_PERF_SEL_SP_CONST_STALL_CYCLES', 'SQ_PERF_SEL_USER0', + 'SQ_PERF_SEL_USER1', 'SQ_PERF_SEL_USER10', 'SQ_PERF_SEL_USER11', + 'SQ_PERF_SEL_USER12', 'SQ_PERF_SEL_USER13', 'SQ_PERF_SEL_USER14', + 'SQ_PERF_SEL_USER15', 'SQ_PERF_SEL_USER2', 'SQ_PERF_SEL_USER3', + 'SQ_PERF_SEL_USER4', 'SQ_PERF_SEL_USER5', 'SQ_PERF_SEL_USER6', + 'SQ_PERF_SEL_USER7', 'SQ_PERF_SEL_USER8', 'SQ_PERF_SEL_USER9', + 'SQ_PERF_SEL_USER_LEVEL0', 'SQ_PERF_SEL_USER_LEVEL1', + 'SQ_PERF_SEL_USER_LEVEL10', 'SQ_PERF_SEL_USER_LEVEL11', + 'SQ_PERF_SEL_USER_LEVEL12', 'SQ_PERF_SEL_USER_LEVEL13', + 'SQ_PERF_SEL_USER_LEVEL14', 'SQ_PERF_SEL_USER_LEVEL15', + 'SQ_PERF_SEL_USER_LEVEL2', 'SQ_PERF_SEL_USER_LEVEL3', + 'SQ_PERF_SEL_USER_LEVEL4', 'SQ_PERF_SEL_USER_LEVEL5', + 'SQ_PERF_SEL_USER_LEVEL6', 'SQ_PERF_SEL_USER_LEVEL7', + 'SQ_PERF_SEL_USER_LEVEL8', 'SQ_PERF_SEL_USER_LEVEL9', + 'SQ_PERF_SEL_VALU_FWD_BUFFER_FULL_STALL', + 'SQ_PERF_SEL_VALU_READWRITELANE_CYCLES', + 'SQ_PERF_SEL_VALU_RETURN_SDST', + 'SQ_PERF_SEL_VALU_SGATHER_FULL_STALL', + 'SQ_PERF_SEL_VALU_SGATHER_STALL', + 'SQ_PERF_SEL_VALU_SGPR_RD_FIFO_FULL_STALL', + 'SQ_PERF_SEL_VALU_STARVE', 'SQ_PERF_SEL_VEC32_INSTS_EXP', + 'SQ_PERF_SEL_VMEM_ARB_FIFO_FULL', 'SQ_PERF_SEL_VMEM_BUS_ACTIVE', + 'SQ_PERF_SEL_VMEM_BUS_STALL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_LDS_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_BUS_STALL_TA_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_STARVE_LDS_ADDR_EMPTY', + 'SQ_PERF_SEL_VMEM_STARVE_TA_ADDR_EMPTY', + 'SQ_PERF_SEL_VMEM_VGPR_READ_STALLED_BY_EXPORT', + 'SQ_PERF_SEL_WAIT_ANY', 'SQ_PERF_SEL_WAIT_BARRIER', + 'SQ_PERF_SEL_WAIT_CNT_ANY', 'SQ_PERF_SEL_WAIT_CNT_DS', + 'SQ_PERF_SEL_WAIT_CNT_EXP', 'SQ_PERF_SEL_WAIT_CNT_KM', + 'SQ_PERF_SEL_WAIT_CNT_LOAD', 'SQ_PERF_SEL_WAIT_CNT_SAMPLE', + 'SQ_PERF_SEL_WAIT_CNT_STORE', 'SQ_PERF_SEL_WAIT_DELAY_ALU', + 'SQ_PERF_SEL_WAIT_DEPCTR', 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 'SQ_PERF_SEL_WAIT_IFETCH', 'SQ_PERF_SEL_WAIT_INST_ANY', + 'SQ_PERF_SEL_WAIT_OTHER', 'SQ_PERF_SEL_WAIT_SLEEP', + 'SQ_PERF_SEL_WAIT_TTRACE', 'SQ_PERF_SEL_WAVE32_INSTS', + 'SQ_PERF_SEL_WAVE32_ITEMS', 'SQ_PERF_SEL_WAVE64_HALF_SKIP', + 'SQ_PERF_SEL_WAVE64_INSTS', 'SQ_PERF_SEL_WAVE64_ITEMS', + 'SQ_PERF_SEL_WAVES', 'SQ_PERF_SEL_WAVES_32', + 'SQ_PERF_SEL_WAVES_64', 'SQ_PERF_SEL_WAVES_EQ_32', + 'SQ_PERF_SEL_WAVES_EQ_64', 'SQ_PERF_SEL_WAVES_INITIAL_PREFETCH', + 'SQ_PERF_SEL_WAVES_LT_16', 'SQ_PERF_SEL_WAVES_LT_32', + 'SQ_PERF_SEL_WAVES_LT_48', 'SQ_PERF_SEL_WAVES_LT_64', + 'SQ_PERF_SEL_WAVES_RESTORED', 'SQ_PERF_SEL_WAVES_SAVED', + 'SQ_PERF_SEL_WAVE_CYCLES', 'SQ_PERF_SEL_WAVE_READY', + 'SQ_ROUND_MINUS_INFINITY', 'SQ_ROUND_MODE', + 'SQ_ROUND_NEAREST_EVEN', 'SQ_ROUND_PLUS_INFINITY', + 'SQ_ROUND_TO_ZERO', 'SQ_RSRC_BUF', 'SQ_RSRC_BUF_RSVD_1', + 'SQ_RSRC_BUF_RSVD_2', 'SQ_RSRC_BUF_RSVD_3', 'SQ_RSRC_BUF_TYPE', + 'SQ_RSRC_FLAT', 'SQ_RSRC_FLAT_RSVD_0', 'SQ_RSRC_FLAT_RSVD_2', + 'SQ_RSRC_FLAT_RSVD_3', 'SQ_RSRC_FLAT_TYPE', 'SQ_RSRC_IMG_1D', + 'SQ_RSRC_IMG_1D_ARRAY', 'SQ_RSRC_IMG_2D', 'SQ_RSRC_IMG_2D_ARRAY', + 'SQ_RSRC_IMG_2D_MSAA', 'SQ_RSRC_IMG_2D_MSAA_ARRAY', + 'SQ_RSRC_IMG_3D', 'SQ_RSRC_IMG_CUBE', 'SQ_RSRC_IMG_RSVD_0', + 'SQ_RSRC_IMG_RSVD_1', 'SQ_RSRC_IMG_RSVD_2', 'SQ_RSRC_IMG_RSVD_3', + 'SQ_RSRC_IMG_RSVD_4', 'SQ_RSRC_IMG_RSVD_5', 'SQ_RSRC_IMG_RSVD_6', + 'SQ_RSRC_IMG_RSVD_7', 'SQ_RSRC_IMG_TYPE', 'SQ_SCRATCH', + 'SQ_SEL_0', 'SQ_SEL_1', 'SQ_SEL_N_BC_1', 'SQ_SEL_RESERVED_1', + 'SQ_SEL_W', 'SQ_SEL_X', 'SQ_SEL_XYZW01', 'SQ_SEL_Y', 'SQ_SEL_Z', + 'SQ_TEX_ANISO_RATIO', 'SQ_TEX_ANISO_RATIO_1', + 'SQ_TEX_ANISO_RATIO_16', 'SQ_TEX_ANISO_RATIO_2', + 'SQ_TEX_ANISO_RATIO_4', 'SQ_TEX_ANISO_RATIO_8', + 'SQ_TEX_BORDER_COLOR', 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 'SQ_TEX_BORDER_COLOR_REGISTER', 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 'SQ_TEX_CLAMP', 'SQ_TEX_CLAMP_BORDER', 'SQ_TEX_CLAMP_HALF_BORDER', + 'SQ_TEX_CLAMP_LAST_TEXEL', 'SQ_TEX_DEPTH_COMPARE', + 'SQ_TEX_DEPTH_COMPARE_ALWAYS', 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 'SQ_TEX_DEPTH_COMPARE_GREATER', + 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', 'SQ_TEX_DEPTH_COMPARE_LESS', + 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', 'SQ_TEX_DEPTH_COMPARE_NEVER', + 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', 'SQ_TEX_MIP_FILTER', + 'SQ_TEX_MIP_FILTER_LINEAR', 'SQ_TEX_MIP_FILTER_NONE', + 'SQ_TEX_MIP_FILTER_POINT', 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', + 'SQ_TEX_MIRROR', 'SQ_TEX_MIRROR_ONCE_BORDER', + 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 'SQ_TEX_WRAP', 'SQ_TEX_XY_FILTER', + 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', 'SQ_TEX_XY_FILTER_ANISO_POINT', + 'SQ_TEX_XY_FILTER_BILINEAR', 'SQ_TEX_XY_FILTER_POINT', + 'SQ_TEX_Z_FILTER', 'SQ_TEX_Z_FILTER_LINEAR', + 'SQ_TEX_Z_FILTER_NONE', 'SQ_TEX_Z_FILTER_POINT', 'SQ_WATCH_MODES', + 'SQ_WATCH_MODE_ALL', 'SQ_WATCH_MODE_ATOMIC', + 'SQ_WATCH_MODE_NONREAD', 'SQ_WATCH_MODE_READ', + 'SQ_WAVE_FWD_PROG_INTERVAL', 'SQ_WAVE_FWD_PROG_INTERVAL_1024', + 'SQ_WAVE_FWD_PROG_INTERVAL_256', 'SQ_WAVE_FWD_PROG_INTERVAL_4096', + 'SQ_WAVE_FWD_PROG_INTERVAL_NEVER', 'SQ_WAVE_IB_DEP_HOLD_CNT_SIZE', + 'SQ_WAVE_IB_DEP_LDS_DIR_SIZE', 'SQ_WAVE_IB_DEP_SA_EXEC_SIZE', + 'SQ_WAVE_IB_DEP_SA_M0_SIZE', 'SQ_WAVE_IB_DEP_SA_SDST_SIZE', + 'SQ_WAVE_IB_DEP_VA_EXEC_SIZE', 'SQ_WAVE_IB_DEP_VA_SDST_SIZE', + 'SQ_WAVE_IB_DEP_VA_SSRC_SIZE', 'SQ_WAVE_IB_DEP_VA_VCC_SIZE', + 'SQ_WAVE_IB_DEP_VA_VDST_SIZE', 'SQ_WAVE_IB_DEP_VM_VSRC_SIZE', + 'SQ_WAVE_SCHED_MODES', + 'SQ_WAVE_SCHED_MODE_DISABLE_VA_VDST_VM_VSRC', + 'SQ_WAVE_SCHED_MODE_EXPERT', 'SQ_WAVE_SCHED_MODE_NORMAL', + 'SQ_WAVE_TYPE', 'SQ_WAVE_TYPE_CS', 'SQ_WAVE_TYPE_GS', + 'SQ_WAVE_TYPE_HS', 'SQ_WAVE_TYPE_PS', 'SQ_WAVE_TYPE_PS0', + 'SQ_WAVE_TYPE_PS1', 'SQ_WAVE_TYPE_PS2', 'SQ_WAVE_TYPE_PS3', + 'SQ_WAVE_TYPE_RSVD0', 'SQ_WAVE_TYPE_RSVD1', 'SQ_WAVE_TYPE_RSVD2', + 'STALL', 'STENCIL_ADD_CLAMP', 'STENCIL_ADD_WRAP', 'STENCIL_AND', + 'STENCIL_INVERT', 'STENCIL_KEEP', 'STENCIL_NAND', 'STENCIL_NOR', + 'STENCIL_ONES', 'STENCIL_OR', 'STENCIL_REPLACE_OP', + 'STENCIL_REPLACE_TEST', 'STENCIL_SUB_CLAMP', 'STENCIL_SUB_WRAP', + 'STENCIL_XNOR', 'STENCIL_XOR', 'STENCIL_ZERO', + 'STREAM_0_SYNCHRONIZATION', + 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_10_SYNCHRONIZATION', + 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION', + 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION', + 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION', + 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION', + 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION', + 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_1_SYNCHRONIZATION', + 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_2_SYNCHRONIZATION', + 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_3_SYNCHRONIZATION', + 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_4_SYNCHRONIZATION', + 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_5_SYNCHRONIZATION', + 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION', + 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION', + 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION', + 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION', + 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'STRM_PERFMON_STATE_RESERVED_3', + 'STRM_PERFMON_STATE_START_COUNTING', + 'STRM_PERFMON_STATE_STOP_COUNTING', 'SURFACE_DCC', + 'SURFACE_DCC_BLOCK_IS_IND_128B', 'SURFACE_DCC_BLOCK_IS_IND_64B', + 'SURFACE_DCC_BLOCK_IS_IND_64B_NO_128BCL', + 'SURFACE_DCC_BLOCK_IS_UNCONSTRAINED', 'SURFACE_DCC_IND_128B', + 'SURFACE_DCC_IND_64B', 'SURFACE_DCC_IND_BLK', + 'SURFACE_DCC_IS_IND_128B', 'SURFACE_DCC_IS_IND_64B', + 'SURFACE_DCC_IS_NOT_IND_128B', 'SURFACE_DCC_IS_NOT_IND_64B', + 'SURFACE_FLIP_AWAY_INT_LEVEL', 'SURFACE_FLIP_AWAY_INT_PULSE', + 'SURFACE_FLIP_AWAY_INT_TYPE', 'SURFACE_FLIP_EXEC_DEBUG_MODE', + 'SURFACE_FLIP_EXEC_DEBUG_MODE_ENABLE', + 'SURFACE_FLIP_EXEC_NORMAL_MODE', 'SURFACE_FLIP_INT_LEVEL', + 'SURFACE_FLIP_INT_PULSE', 'SURFACE_FLIP_INT_TYPE', + 'SURFACE_FLIP_IN_STEREOSYNC', 'SURFACE_FLIP_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC', + 'SURFACE_FLIP_MODE_FOR_STEREOSYNC_RESERVED', + 'SURFACE_FLIP_NOT_IN_STEREOSYNC_MODE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLE', + 'SURFACE_FLIP_STEREO_SELECT_DISABLED', + 'SURFACE_FLIP_STEREO_SELECT_ENABLED', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_INVERT', + 'SURFACE_FLIP_STEREO_SELECT_POLARITY_NOT_INVERT', + 'SURFACE_FLIP_TYPE', 'SURFACE_FLIP_VUPDATE_SKIP_NUM', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_0', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_1', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_10', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_11', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_12', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_13', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_14', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_15', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_2', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_3', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_4', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_5', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_6', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_7', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_8', + 'SURFACE_FLIP_VUPDATE_SKIP_NUM_9', 'SURFACE_INUSE_IS_LATCHED', + 'SURFACE_INUSE_IS_NOT_LATCHED', 'SURFACE_INUSE_RAED_NO_LATCH', + 'SURFACE_IS_DCC', 'SURFACE_IS_NOT_DCC', 'SURFACE_IS_NOT_TMZ', + 'SURFACE_IS_TMZ', 'SURFACE_I_FLIP', 'SURFACE_PIXEL_FORMAT', + 'SURFACE_TMZ', 'SURFACE_UPDATE_IS_LOCKED', + 'SURFACE_UPDATE_IS_UNLOCKED', 'SURFACE_UPDATE_LOCK', + 'SURFACE_V_FLIP', 'SU_PERFCNT_SEL', 'SWATH_HEIGHT', + 'SWATH_HEIGHT_16L', 'SWATH_HEIGHT_1L', 'SWATH_HEIGHT_2L', + 'SWATH_HEIGHT_4L', 'SWATH_HEIGHT_8L', 'SX_BLEND_OPT', + 'SX_CB_RAT_ACK_REQUEST', 'SX_DOWNCONVERT_FORMAT', + 'SX_OPT_COMB_FCN', 'SX_PERFCOUNTER_VALS', 'SX_PERF_SEL_CLOCK', + 'SX_PERF_SEL_CLOCK_DROP_STALL', 'SX_PERF_SEL_COL_BUSY', + 'SX_PERF_SEL_DB0_4X2_DISCARD', 'SX_PERF_SEL_DB0_END_OF_WAVE', + 'SX_PERF_SEL_DB0_HALF_QUADS', 'SX_PERF_SEL_DB0_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB0_PIXELS', + 'SX_PERF_SEL_DB0_PIXEL_IDLE', 'SX_PERF_SEL_DB0_PIXEL_STALL', + 'SX_PERF_SEL_DB0_PRED_PIXELS', 'SX_PERF_SEL_DB0_SIZE', + 'SX_PERF_SEL_DB1_4X2_DISCARD', 'SX_PERF_SEL_DB1_END_OF_WAVE', + 'SX_PERF_SEL_DB1_HALF_QUADS', 'SX_PERF_SEL_DB1_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB1_PIXELS', + 'SX_PERF_SEL_DB1_PIXEL_IDLE', 'SX_PERF_SEL_DB1_PIXEL_STALL', + 'SX_PERF_SEL_DB1_PRED_PIXELS', 'SX_PERF_SEL_DB1_SIZE', + 'SX_PERF_SEL_DB2_4X2_DISCARD', 'SX_PERF_SEL_DB2_END_OF_WAVE', + 'SX_PERF_SEL_DB2_HALF_QUADS', 'SX_PERF_SEL_DB2_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB2_PIXELS', + 'SX_PERF_SEL_DB2_PIXEL_IDLE', 'SX_PERF_SEL_DB2_PIXEL_STALL', + 'SX_PERF_SEL_DB2_PRED_PIXELS', 'SX_PERF_SEL_DB2_SIZE', + 'SX_PERF_SEL_DB3_4X2_DISCARD', 'SX_PERF_SEL_DB3_END_OF_WAVE', + 'SX_PERF_SEL_DB3_HALF_QUADS', 'SX_PERF_SEL_DB3_MRT_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT_SINGLE_QUADS', 'SX_PERF_SEL_DB3_PIXELS', + 'SX_PERF_SEL_DB3_PIXEL_IDLE', 'SX_PERF_SEL_DB3_PIXEL_STALL', + 'SX_PERF_SEL_DB3_PRED_PIXELS', 'SX_PERF_SEL_DB3_SIZE', + 'SX_PERF_SEL_GATE_EN1', 'SX_PERF_SEL_GATE_EN2', + 'SX_PERF_SEL_GATE_EN3', 'SX_PERF_SEL_GATE_EN4', + 'SX_PERF_SEL_GATE_EN5', 'SX_PERF_SEL_GATE_EN6', + 'SX_PERF_SEL_GATE_EN7', 'SX_PERF_SEL_GATE_EN8', + 'SX_PERF_SEL_IDX_BUSY', 'SX_PERF_SEL_IDX_IDLE_CYCLES', + 'SX_PERF_SEL_IDX_REQ', 'SX_PERF_SEL_IDX_REQ_LATENCY', + 'SX_PERF_SEL_IDX_RET', 'SX_PERF_SEL_IDX_SCBD_STALL', + 'SX_PERF_SEL_IDX_STALL_CYCLES', 'SX_PERF_SEL_PA_IDLE_CYCLES', + 'SX_PERF_SEL_PA_POS', 'SX_PERF_SEL_PA_POS_BANK_CONF', + 'SX_PERF_SEL_PA_REQ', 'SX_PERF_SEL_PA_REQ_LATENCY', + 'SX_PERF_SEL_POS_BUSY', 'SX_PERF_SEL_POS_SCBD_STALL', + 'SX_PERF_SEL_SH_COLOR_STALL', 'SX_PERF_SEL_SH_COLOR_STARVE', + 'SX_PERF_SEL_SH_IDX_STARVE', 'SX_PERF_SEL_SH_POS_STALL', + 'SX_PERF_SEL_SH_POS_STARVE', 'SX_RT_EXPORT_10_11_11', + 'SX_RT_EXPORT_16_16_AR', 'SX_RT_EXPORT_16_16_GR', + 'SX_RT_EXPORT_1_5_5_5', 'SX_RT_EXPORT_2_10_10_10', + 'SX_RT_EXPORT_2_10_10_10_6E4', 'SX_RT_EXPORT_2_10_10_10_7E3', + 'SX_RT_EXPORT_32_A', 'SX_RT_EXPORT_32_R', 'SX_RT_EXPORT_4_4_4_4', + 'SX_RT_EXPORT_5_6_5', 'SX_RT_EXPORT_8_8_8_8', + 'SX_RT_EXPORT_9_9_9_E5', 'SX_RT_EXPORT_NO_CONVERSION', + 'SYMCLK_FE_SRC', 'SYMCLK_FE_SRC_RESERVED', + 'SYMCLK_FE_SRC_UNIPHYA', 'SYMCLK_FE_SRC_UNIPHYB', + 'SYMCLK_FE_SRC_UNIPHYC', 'SYMCLK_FE_SRC_UNIPHYD', 'ScMap', + 'ScUncertaintyRegionMode', 'ScUncertaintyRegionMult', 'ScXsel', + 'ScYsel', 'SeMap', 'SePairMap', 'SePairXsel', 'SePairYsel', + 'SeXsel', 'SeYsel', 'StencilOp', 'TA_PERFCOUNT_SEL', + 'TA_PERF_SEL_NULL', 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 'TA_PERF_SEL_addresser_busy', 'TA_PERF_SEL_addresser_fifo_busy', + 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 'TA_PERF_SEL_addresser_stalled_cycles', + 'TA_PERF_SEL_aligner_busy', + 'TA_PERF_SEL_aligner_clk_valid_cycles', + 'TA_PERF_SEL_aligner_cycles', 'TA_PERF_SEL_aniso_10_cycle_quads', + 'TA_PERF_SEL_aniso_12_cycle_quads', + 'TA_PERF_SEL_aniso_14_cycle_quads', + 'TA_PERF_SEL_aniso_16_cycle_quads', + 'TA_PERF_SEL_aniso_1_cycle_quads', + 'TA_PERF_SEL_aniso_2_cycle_quads', + 'TA_PERF_SEL_aniso_4_cycle_quads', + 'TA_PERF_SEL_aniso_6_cycle_quads', + 'TA_PERF_SEL_aniso_8_cycle_quads', + 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 'TA_PERF_SEL_aniso_stalled_cycles', + 'TA_PERF_SEL_atomic_2_write_data_vgpr_instructions', + 'TA_PERF_SEL_atomic_4_write_data_vgpr_instructions', + 'TA_PERF_SEL_atomic_write_data_input_cycles', + 'TA_PERF_SEL_atomic_write_data_output_cycles', + 'TA_PERF_SEL_bf_busy', + 'TA_PERF_SEL_boundary_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_boundary_non_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_buffer_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_buffer_2_address_input_vgpr_instructions', + 'TA_PERF_SEL_buffer_atomic_wavefronts', + 'TA_PERF_SEL_buffer_flat_1_op_burst', + 'TA_PERF_SEL_buffer_flat_2to3_op_burst', + 'TA_PERF_SEL_buffer_flat_4to31_op_burst', + 'TA_PERF_SEL_buffer_flat_clk_valid_cycles', + 'TA_PERF_SEL_buffer_flat_ge32_op_burst', + 'TA_PERF_SEL_buffer_has_index_instructions', + 'TA_PERF_SEL_buffer_has_offset_instructions', + 'TA_PERF_SEL_buffer_load_wavefronts', + 'TA_PERF_SEL_buffer_store_wavefronts', + 'TA_PERF_SEL_buffer_total_cycles', + 'TA_PERF_SEL_buffer_wavefronts', + 'TA_PERF_SEL_color_1_cycle_quads', + 'TA_PERF_SEL_color_2_cycle_quads', + 'TA_PERF_SEL_color_3_cycle_quads', + 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 'TA_PERF_SEL_deriv_stalled_cycles', + 'TA_PERF_SEL_flat_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_flat_2_address_input_vgpr_instructions', + 'TA_PERF_SEL_flat_atomic_wavefronts', + 'TA_PERF_SEL_flat_load_wavefronts', + 'TA_PERF_SEL_flat_store_wavefronts', + 'TA_PERF_SEL_flat_total_cycles', 'TA_PERF_SEL_flat_wavefronts', + 'TA_PERF_SEL_gradient_busy', + 'TA_PERF_SEL_gradient_clk_valid_cycles', + 'TA_PERF_SEL_gradient_cycles', 'TA_PERF_SEL_gradient_fifo_busy', + 'TA_PERF_SEL_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_ibubble_16to31_cycle_burst', + 'TA_PERF_SEL_ibubble_1_cycle_burst', + 'TA_PERF_SEL_ibubble_2to3_cycle_burst', + 'TA_PERF_SEL_ibubble_32to63_cycle_burst', + 'TA_PERF_SEL_ibubble_4to15_cycle_burst', + 'TA_PERF_SEL_ibubble_ge64_cycle_burst', + 'TA_PERF_SEL_image_atomic_wavefronts', + 'TA_PERF_SEL_image_linked_1_op_burst', + 'TA_PERF_SEL_image_linked_2to3_op_burst', + 'TA_PERF_SEL_image_linked_4to7_op_burst', + 'TA_PERF_SEL_image_linked_ge8_op_burst', + 'TA_PERF_SEL_image_nosampler_1_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_1_op_burst', + 'TA_PERF_SEL_image_nosampler_2_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_2to3_op_burst', + 'TA_PERF_SEL_image_nosampler_3_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_4_address_input_vgpr_instructions', + 'TA_PERF_SEL_image_nosampler_4to31_op_burst', + 'TA_PERF_SEL_image_nosampler_ge32_op_burst', + 'TA_PERF_SEL_image_nosampler_has_q_instructions', + 'TA_PERF_SEL_image_nosampler_has_r_instructions', + 'TA_PERF_SEL_image_nosampler_has_t_instructions', + 'TA_PERF_SEL_image_nosampler_total_cycles', + 'TA_PERF_SEL_image_read_wavefronts', + 'TA_PERF_SEL_image_sampler_10_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_11_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_12_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_1_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_1_op_burst', + 'TA_PERF_SEL_image_sampler_2_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_2to3_op_burst', + 'TA_PERF_SEL_image_sampler_3_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_4_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_4to7_op_burst', + 'TA_PERF_SEL_image_sampler_5_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_6_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_7_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_8_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_9_input_vgpr_instructions', + 'TA_PERF_SEL_image_sampler_ge8_op_burst', + 'TA_PERF_SEL_image_sampler_has_bias_instructions', + 'TA_PERF_SEL_image_sampler_has_dr_instructions', + 'TA_PERF_SEL_image_sampler_has_ds_instructions', + 'TA_PERF_SEL_image_sampler_has_dt_instructions', + 'TA_PERF_SEL_image_sampler_has_offset_instructions', + 'TA_PERF_SEL_image_sampler_has_q_instructions', + 'TA_PERF_SEL_image_sampler_has_r_instructions', + 'TA_PERF_SEL_image_sampler_has_reference_instructions', + 'TA_PERF_SEL_image_sampler_has_t_instructions', + 'TA_PERF_SEL_image_sampler_total_cycles', + 'TA_PERF_SEL_image_sampler_wavefronts', + 'TA_PERF_SEL_image_store_wavefronts', + 'TA_PERF_SEL_image_wavefronts', 'TA_PERF_SEL_in_addr_cycles', + 'TA_PERF_SEL_in_busy', 'TA_PERF_SEL_in_cfifo_busy', + 'TA_PERF_SEL_in_data_cycles', 'TA_PERF_SEL_in_fifos_busy', + 'TA_PERF_SEL_in_qfifo_busy', 'TA_PERF_SEL_in_rfifo_busy', + 'TA_PERF_SEL_in_waiting_on_req_cycles', + 'TA_PERF_SEL_in_wfifo_busy', + 'TA_PERF_SEL_lod_aniso_clk_valid_cycles', 'TA_PERF_SEL_lod_busy', + 'TA_PERF_SEL_lod_fifo_busy', 'TA_PERF_SEL_mip_1_cycle_quads', + 'TA_PERF_SEL_mip_2_cycle_quads', + 'TA_PERF_SEL_mipmap_invalid_samples', + 'TA_PERF_SEL_mipmap_lod_0_samples', + 'TA_PERF_SEL_mipmap_lod_10_samples', + 'TA_PERF_SEL_mipmap_lod_11_samples', + 'TA_PERF_SEL_mipmap_lod_12_samples', + 'TA_PERF_SEL_mipmap_lod_13_samples', + 'TA_PERF_SEL_mipmap_lod_14_samples', + 'TA_PERF_SEL_mipmap_lod_15_samples', + 'TA_PERF_SEL_mipmap_lod_16_samples', + 'TA_PERF_SEL_mipmap_lod_1_samples', + 'TA_PERF_SEL_mipmap_lod_2_samples', + 'TA_PERF_SEL_mipmap_lod_3_samples', + 'TA_PERF_SEL_mipmap_lod_4_samples', + 'TA_PERF_SEL_mipmap_lod_5_samples', + 'TA_PERF_SEL_mipmap_lod_6_samples', + 'TA_PERF_SEL_mipmap_lod_7_samples', + 'TA_PERF_SEL_mipmap_lod_8_samples', + 'TA_PERF_SEL_mipmap_lod_9_samples', + 'TA_PERF_SEL_non_harvestable_clk_enabled_cycles', + 'TA_PERF_SEL_nonsampler_clk_valid_cycles', 'TA_PERF_SEL_ns_busy', + 'TA_PERF_SEL_num_nodes_invalidated_due_to_bad_input', + 'TA_PERF_SEL_num_nodes_invalidated_due_to_oob', + 'TA_PERF_SEL_num_unlit_nodes_ta_opt', + 'TA_PERF_SEL_point_sampled_quads', + 'TA_PERF_SEL_register_clk_valid_cycles', + 'TA_PERF_SEL_sampler_addressing_clk_valid_cycles', + 'TA_PERF_SEL_sampler_clk_valid_cycles', + 'TA_PERF_SEL_sampler_op_quads', 'TA_PERF_SEL_smp_busy_ns_idle', + 'TA_PERF_SEL_smp_idle_ns_busy', + 'TA_PERF_SEL_store_2_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_3_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_4_write_data_vgpr_instructions', + 'TA_PERF_SEL_store_has_w_instructions', + 'TA_PERF_SEL_store_has_x_instructions', + 'TA_PERF_SEL_store_has_y_instructions', + 'TA_PERF_SEL_store_has_z_instructions', + 'TA_PERF_SEL_store_write_data_input_cycles', + 'TA_PERF_SEL_store_write_data_output_cycles', + 'TA_PERF_SEL_sync_nonsampler_fifo_clk_valid_cycles', + 'TA_PERF_SEL_sync_sampler_cstate_fifo_clk_valid_cycles', + 'TA_PERF_SEL_sync_sampler_sstate_fifo_clk_valid_cycles', + 'TA_PERF_SEL_ta_busy', 'TA_PERF_SEL_tcreq_clk_valid_cycles', + 'TA_PERF_SEL_total_wavefronts', 'TA_PERF_SEL_vmemcmd_cycles', + 'TA_PERF_SEL_vmemreq_cycles', 'TA_PERF_SEL_vol_1_cycle_quads', + 'TA_PERF_SEL_vol_2_cycle_quads', 'TA_PERF_SEL_walker_cycles', + 'TA_PERF_SEL_write_1_op_burst', 'TA_PERF_SEL_write_2to3_op_burst', + 'TA_PERF_SEL_write_4to31_op_burst', + 'TA_PERF_SEL_write_data_clk_valid_cycles', + 'TA_PERF_SEL_write_ge32_op_burst', 'TA_PERF_SEL_write_path_busy', + 'TA_TC_ADDR_MODES', 'TA_TC_ADDR_MODE_BORDER_COLOR', + 'TA_TC_ADDR_MODE_COMP0', 'TA_TC_ADDR_MODE_COMP1', + 'TA_TC_ADDR_MODE_COMP2', 'TA_TC_ADDR_MODE_COMP3', + 'TA_TC_ADDR_MODE_DEFAULT', 'TA_TC_ADDR_MODE_UNALIGNED', + 'TA_TC_REQ_MODES', 'TA_TC_REQ_MODE_BORDER', 'TA_TC_REQ_MODE_BYTE', + 'TA_TC_REQ_MODE_BYTE_NV', 'TA_TC_REQ_MODE_DWORD', + 'TA_TC_REQ_MODE_NORMAL', 'TA_TC_REQ_MODE_TEX0', + 'TA_TC_REQ_MODE_TEX1', 'TA_TC_REQ_MODE_TEX2', 'TCC_MTYPE', + 'TCP_CACHE_POLICIES', 'TCP_CACHE_POLICY_HIT_EVICT', + 'TCP_CACHE_POLICY_HIT_LRU', 'TCP_CACHE_POLICY_MISS_EVICT', + 'TCP_CACHE_POLICY_MISS_LRU', 'TCP_CACHE_STORE_POLICIES', + 'TCP_CACHE_STORE_POLICY_WT_EVICT', + 'TCP_CACHE_STORE_POLICY_WT_LRU', 'TCP_COMPRESSION_BYPASS', + 'TCP_COMPRESSION_BYPASS_DIS', 'TCP_COMPRESSION_BYPASS_EN', + 'TCP_COMPRESSION_OVERRIDE', 'TCP_COMPRESSION_OVERRIDE_DIS', + 'TCP_COMPRESSION_OVERRIDE_EN', 'TCP_OPCODE_ATOMIC', + 'TCP_OPCODE_ATOMIC_CMPSWAP', 'TCP_OPCODE_GATHERH', + 'TCP_OPCODE_INV', 'TCP_OPCODE_LOAD', 'TCP_OPCODE_READ', + 'TCP_OPCODE_SAMPLER', 'TCP_OPCODE_TYPE', 'TCP_OPCODE_WRITE', + 'TCP_PERFCOUNT_SELECT', 'TCP_PERF_SEL_ALLOC_STALL', + 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL', + 'TCP_PERF_SEL_BURST_BIN_READHIT_0', + 'TCP_PERF_SEL_BURST_BIN_READHIT_1', + 'TCP_PERF_SEL_BURST_BIN_READHIT_2to4', + 'TCP_PERF_SEL_BURST_BIN_READHIT_5to8', + 'TCP_PERF_SEL_BURST_BIN_READHIT_9to16', + 'TCP_PERF_SEL_BURST_BIN_READHIT_gt16', + 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_0', + 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_1to2', + 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_3to4', + 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_5to8', + 'TCP_PERF_SEL_BURST_BIN_WRITECOMBINE_9to16', + 'TCP_PERF_SEL_COMP_TEX_LOAD_STALL', + 'TCP_PERF_SEL_DATA_FIFO_STALL', 'TCP_PERF_SEL_GATE_EN1', + 'TCP_PERF_SEL_GATE_EN2', 'TCP_PERF_SEL_GL1_GRANT_READ_STALL', + 'TCP_PERF_SEL_GL1_PENDING_STALL', 'TCP_PERF_SEL_GL1_READ_LATENCY', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_GL1_REQ_ATOMIC_WITH_RET', 'TCP_PERF_SEL_GL1_REQ_LU', + 'TCP_PERF_SEL_GL1_REQ_READ', 'TCP_PERF_SEL_GL1_REQ_READ_128B', + 'TCP_PERF_SEL_GL1_REQ_READ_64B', 'TCP_PERF_SEL_GL1_REQ_WRITE', + 'TCP_PERF_SEL_GL1_TCP_BACK_PRESSURE', + 'TCP_PERF_SEL_GL1_TCP_RDRET_STALL', + 'TCP_PERF_SEL_GL1_WRITE_LATENCY', 'TCP_PERF_SEL_LFIFO_STALL', + 'TCP_PERF_SEL_LOD_STALL', 'TCP_PERF_SEL_MEM_REQ_FIFO_STALL', + 'TCP_PERF_SEL_POWER_STALL', + 'TCP_PERF_SEL_READ_DATACONFLICT_STALL', + 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL', 'TCP_PERF_SEL_REQ', + 'TCP_PERF_SEL_REQ_MISS', 'TCP_PERF_SEL_REQ_MISS_TAGBANK0', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK1', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK2', + 'TCP_PERF_SEL_REQ_MISS_TAGBANK3', 'TCP_PERF_SEL_REQ_NON_READ', + 'TCP_PERF_SEL_REQ_READ', 'TCP_PERF_SEL_REQ_READ_HIT_LRU', + 'TCP_PERF_SEL_REQ_READ_MISS_EVICT', + 'TCP_PERF_SEL_REQ_TAGBANK0_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK0_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK1_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK1_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK2_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK2_SET1', + 'TCP_PERF_SEL_REQ_TAGBANK3_SET0', + 'TCP_PERF_SEL_REQ_TAGBANK3_SET1', + 'TCP_PERF_SEL_REQ_TAG_MATCH_AND_LU_INVALIDATE', + 'TCP_PERF_SEL_REQ_TAG_MATCH_AND_NOT_VALID', + 'TCP_PERF_SEL_REQ_WRITE', 'TCP_PERF_SEL_REQ_WRITE_MISS_EVICT', + 'TCP_PERF_SEL_TAGFAKE_EOW', 'TCP_PERF_SEL_TA_REQ', + 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_TA_REQ_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_TA_REQ_BUFFERNOP', 'TCP_PERF_SEL_TA_REQ_GL0_INV', + 'TCP_PERF_SEL_TA_REQ_READ', 'TCP_PERF_SEL_TA_REQ_STATE_READ', + 'TCP_PERF_SEL_TA_REQ_WRITE', 'TCP_PERF_SEL_TA_TCP_REQ_STARVE', + 'TCP_PERF_SEL_TA_TC_REQ_EN_SUM', 'TCP_PERF_SEL_TCP_LATENCY', + 'TCP_PERF_SEL_TCP_TA_REQ_STALL', + 'TCP_PERF_SEL_TD_DATA_CYCLE_STALL', 'TCP_PERF_SEL_TD_TCP_STALL', + 'TCP_PERF_SEL_WRITECOMBINE_ENDCLAUSE', + 'TCP_PERF_SEL_WRITE_DATACONFLICT_STALL', + 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL', 'TCP_WATCH_MODES', + 'TCP_WATCH_MODE_ALL', 'TCP_WATCH_MODE_ATOMIC', + 'TCP_WATCH_MODE_NONREAD', 'TCP_WATCH_MODE_READ', + 'TCP_WRITE_COMPRESSION_DISABLE', + 'TCP_WRITE_COMPRESSION_DISABLE_DIS', + 'TCP_WRITE_COMPRESSION_DISABLE_EN', 'TC_EA_CID', 'TC_EA_CID_CPF', + 'TC_EA_CID_CPG', 'TC_EA_CID_DCC', 'TC_EA_CID_FMASK', + 'TC_EA_CID_HTILE', 'TC_EA_CID_IA', 'TC_EA_CID_MISC', + 'TC_EA_CID_PA', 'TC_EA_CID_RT', 'TC_EA_CID_SQC', + 'TC_EA_CID_STENCIL', 'TC_EA_CID_TCP', 'TC_EA_CID_TCPMETA', + 'TC_EA_CID_UTCL2_TPI', 'TC_EA_CID_WD', 'TC_EA_CID_Z', 'TC_NACKS', + 'TC_NACK_DATA_ERROR', 'TC_NACK_NO_FAULT', 'TC_NACK_PAGE_FAULT', + 'TC_NACK_PROTECTION_FAULT', 'TC_OP', 'TC_OP_ATOMIC_ADD_32', + 'TC_OP_ATOMIC_ADD_64', 'TC_OP_ATOMIC_ADD_RTN_32', + 'TC_OP_ATOMIC_ADD_RTN_64', 'TC_OP_ATOMIC_AND_32', + 'TC_OP_ATOMIC_AND_64', 'TC_OP_ATOMIC_AND_RTN_32', + 'TC_OP_ATOMIC_AND_RTN_64', 'TC_OP_ATOMIC_CMPSWAP_32', + 'TC_OP_ATOMIC_CMPSWAP_64', 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 'TC_OP_ATOMIC_CMPSWAP_RTN_64', 'TC_OP_ATOMIC_DEC_32', + 'TC_OP_ATOMIC_DEC_64', 'TC_OP_ATOMIC_DEC_RTN_32', + 'TC_OP_ATOMIC_DEC_RTN_64', 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FADD_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_32', 'TC_OP_ATOMIC_FCMPSWAP_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 'TC_OP_ATOMIC_FMAX_32', 'TC_OP_ATOMIC_FMAX_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMAX_RTN_32', 'TC_OP_ATOMIC_FMAX_RTN_64', + 'TC_OP_ATOMIC_FMIN_32', 'TC_OP_ATOMIC_FMIN_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMIN_RTN_32', 'TC_OP_ATOMIC_FMIN_RTN_64', + 'TC_OP_ATOMIC_INC_32', 'TC_OP_ATOMIC_INC_64', + 'TC_OP_ATOMIC_INC_RTN_32', 'TC_OP_ATOMIC_INC_RTN_64', + 'TC_OP_ATOMIC_OR_32', 'TC_OP_ATOMIC_OR_64', + 'TC_OP_ATOMIC_OR_RTN_32', 'TC_OP_ATOMIC_OR_RTN_64', + 'TC_OP_ATOMIC_SMAX_32', 'TC_OP_ATOMIC_SMAX_64', + 'TC_OP_ATOMIC_SMAX_RTN_32', 'TC_OP_ATOMIC_SMAX_RTN_64', + 'TC_OP_ATOMIC_SMIN_32', 'TC_OP_ATOMIC_SMIN_64', + 'TC_OP_ATOMIC_SMIN_RTN_32', 'TC_OP_ATOMIC_SMIN_RTN_64', + 'TC_OP_ATOMIC_SUB_32', 'TC_OP_ATOMIC_SUB_64', + 'TC_OP_ATOMIC_SUB_RTN_32', 'TC_OP_ATOMIC_SUB_RTN_64', + 'TC_OP_ATOMIC_SWAP_32', 'TC_OP_ATOMIC_SWAP_64', + 'TC_OP_ATOMIC_SWAP_RTN_32', 'TC_OP_ATOMIC_SWAP_RTN_64', + 'TC_OP_ATOMIC_UMAX_32', 'TC_OP_ATOMIC_UMAX_64', + 'TC_OP_ATOMIC_UMAX_RTN_32', 'TC_OP_ATOMIC_UMAX_RTN_64', + 'TC_OP_ATOMIC_UMIN_32', 'TC_OP_ATOMIC_UMIN_64', + 'TC_OP_ATOMIC_UMIN_RTN_32', 'TC_OP_ATOMIC_UMIN_RTN_64', + 'TC_OP_ATOMIC_XOR_32', 'TC_OP_ATOMIC_XOR_64', + 'TC_OP_ATOMIC_XOR_RTN_32', 'TC_OP_ATOMIC_XOR_RTN_64', + 'TC_OP_INVL2_NC', 'TC_OP_INV_METADATA', 'TC_OP_MASKS', + 'TC_OP_MASK_64', 'TC_OP_MASK_FLUSH_DENROM', 'TC_OP_MASK_NO_RTN', + 'TC_OP_NOP_ACK', 'TC_OP_NOP_RTN0', 'TC_OP_PROBE_FILTER', + 'TC_OP_READ', 'TC_OP_RESERVED_FADD_32', + 'TC_OP_RESERVED_FADD_RTN_32', 'TC_OP_RESERVED_FOP_32_0', + 'TC_OP_RESERVED_FOP_32_2', 'TC_OP_RESERVED_FOP_64_0', + 'TC_OP_RESERVED_FOP_64_1', 'TC_OP_RESERVED_FOP_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_32_0', 'TC_OP_RESERVED_FOP_RTN_32_2', + 'TC_OP_RESERVED_FOP_RTN_64_0', 'TC_OP_RESERVED_FOP_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_64_2', 'TC_OP_RESERVED_NON_FLOAT_32_1', + 'TC_OP_RESERVED_NON_FLOAT_32_2', 'TC_OP_RESERVED_NON_FLOAT_32_3', + 'TC_OP_RESERVED_NON_FLOAT_32_4', 'TC_OP_RESERVED_NON_FLOAT_64_1', + 'TC_OP_RESERVED_NON_FLOAT_64_2', 'TC_OP_RESERVED_NON_FLOAT_64_3', + 'TC_OP_RESERVED_NON_FLOAT_64_4', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', 'TC_OP_WBINVL1', + 'TC_OP_WBINVL1_SD', 'TC_OP_WBINVL1_VOL', 'TC_OP_WBINVL2', + 'TC_OP_WBINVL2_NC', 'TC_OP_WBINVL2_SD', 'TC_OP_WBL2_NC', + 'TC_OP_WBL2_WC', 'TC_OP_WRITE', 'TD_PERFCOUNT_SEL', + 'TD_PERF_SEL_2x_sampler_op_with_1_unlit_quad', + 'TD_PERF_SEL_2x_sampler_op_with_both_quads_unlit', + 'TD_PERF_SEL_all_pipes_sclk_on_at_same_time', + 'TD_PERF_SEL_blend_prt_with_prt_default_0', + 'TD_PERF_SEL_box_non_opaque_culled', + 'TD_PERF_SEL_box_opaque_culled', + 'TD_PERF_SEL_box_with_procedural_children_only_culled', + 'TD_PERF_SEL_box_with_triangle_children_only_culled', + 'TD_PERF_SEL_bubble_bin_lds_stall_1to3', + 'TD_PERF_SEL_bubble_bin_lds_stall_4to7', + 'TD_PERF_SEL_bubble_bin_lds_stall_8to15', + 'TD_PERF_SEL_bubble_bin_lds_stall_gt15', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_0', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_1', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_128to511', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_2to31', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_32to127', + 'TD_PERF_SEL_bubble_bin_ta_waiting_for_tc_data_gt511', + 'TD_PERF_SEL_burst_bin_gather_1', + 'TD_PERF_SEL_burst_bin_gather_2to8', + 'TD_PERF_SEL_burst_bin_gather_9to16', + 'TD_PERF_SEL_burst_bin_gather_gt16', + 'TD_PERF_SEL_burst_bin_nofilter_1', + 'TD_PERF_SEL_burst_bin_nofilter_2to4', + 'TD_PERF_SEL_burst_bin_nofilter_5to7', + 'TD_PERF_SEL_burst_bin_nofilter_8to16', + 'TD_PERF_SEL_burst_bin_nofilter_gt16', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_1', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_2to4', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_5to7', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_8to16', + 'TD_PERF_SEL_burst_bin_preempting_nofilter_gt16', + 'TD_PERF_SEL_burst_bin_sampler_1', + 'TD_PERF_SEL_burst_bin_sampler_2to8', + 'TD_PERF_SEL_burst_bin_sampler_9to16', + 'TD_PERF_SEL_burst_bin_sampler_gt16', + 'TD_PERF_SEL_bypassLerp_instr', + 'TD_PERF_SEL_core_state_ram_max_cnt', + 'TD_PERF_SEL_core_state_rams_read', 'TD_PERF_SEL_d16_en_instr', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_lds', + 'TD_PERF_SEL_done_scoreboard_bp_due_to_ooo', + 'TD_PERF_SEL_done_scoreboard_is_full', + 'TD_PERF_SEL_done_scoreboard_max_stored_cnt', + 'TD_PERF_SEL_done_scoreboard_max_waiting_cnt', + 'TD_PERF_SEL_done_scoreboard_not_empty', + 'TD_PERF_SEL_four_comp_return_instr', + 'TD_PERF_SEL_gather4_2x_instr', 'TD_PERF_SEL_gather4_instr', + 'TD_PERF_SEL_gather4h_2x_instr', 'TD_PERF_SEL_gather4h_instr', + 'TD_PERF_SEL_getlod_2x_instr', 'TD_PERF_SEL_getlod_instr', + 'TD_PERF_SEL_input_bp_due_to_done_scoreboard_full', + 'TD_PERF_SEL_input_busy', 'TD_PERF_SEL_input_state_fifo_full', + 'TD_PERF_SEL_instance_mask_culled', + 'TD_PERF_SEL_instruction_dest_is_lds', 'TD_PERF_SEL_lds_stall', + 'TD_PERF_SEL_load_instr', 'TD_PERF_SEL_lod_warn_from_ta', + 'TD_PERF_SEL_min_max_filter_instr', 'TD_PERF_SEL_mixmode_instr', + 'TD_PERF_SEL_mixmode_resource', 'TD_PERF_SEL_msaa_load_instr', + 'TD_PERF_SEL_nofilter_busy', + 'TD_PERF_SEL_nofilter_byte_cycling_16cycles', + 'TD_PERF_SEL_nofilter_byte_cycling_4cycles', + 'TD_PERF_SEL_nofilter_byte_cycling_8cycles', + 'TD_PERF_SEL_nofilter_d16_sclk_en', + 'TD_PERF_SEL_nofilter_d32_sclk_en', + 'TD_PERF_SEL_nofilter_dword_cycling_2cycles', + 'TD_PERF_SEL_nofilter_dword_cycling_4cycles', + 'TD_PERF_SEL_nofilter_formatters_turned_on', + 'TD_PERF_SEL_nofilter_insert_extra_comps', + 'TD_PERF_SEL_nofilter_pkr_full', + 'TD_PERF_SEL_nofilter_pkr_full_due_to_arb', + 'TD_PERF_SEL_nofilter_popcount_dmask_gt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_popcount_dmask_lt_num_comp_of_fmt', + 'TD_PERF_SEL_nofilter_sclk_en', + 'TD_PERF_SEL_nofilter_sclk_on_sampler_sclk_off', + 'TD_PERF_SEL_nofilter_total_num_comps_to_lds', 'TD_PERF_SEL_none', + 'TD_PERF_SEL_one_comp_return_instr', + 'TD_PERF_SEL_opaque_black_border', + 'TD_PERF_SEL_out_of_order_instr', + 'TD_PERF_SEL_preempting_nofilter_max_cnt', + 'TD_PERF_SEL_prt_ack_instr', 'TD_PERF_SEL_ps_load_instr', + 'TD_PERF_SEL_reference_data_rams_read', + 'TD_PERF_SEL_resmap_2x_instr', 'TD_PERF_SEL_resmap_instr', + 'TD_PERF_SEL_resmap_with_aniso_filtering', + 'TD_PERF_SEL_resmap_with_cubemap_corner', + 'TD_PERF_SEL_resmap_with_no_more_filtering', + 'TD_PERF_SEL_resmap_with_volume_filtering', + 'TD_PERF_SEL_sample_2x_instr', 'TD_PERF_SEL_sample_c_instr', + 'TD_PERF_SEL_sample_instr', 'TD_PERF_SEL_sampler_accum_sclk_en', + 'TD_PERF_SEL_sampler_bilerp_sclk_en', + 'TD_PERF_SEL_sampler_bypass_sclk_en', + 'TD_PERF_SEL_sampler_core_sclk_en', + 'TD_PERF_SEL_sampler_format_flt_sclk_en', + 'TD_PERF_SEL_sampler_format_fxdpt_sclk_en', + 'TD_PERF_SEL_sampler_lerp0_active', + 'TD_PERF_SEL_sampler_lerp1_active', + 'TD_PERF_SEL_sampler_lerp2_active', + 'TD_PERF_SEL_sampler_lerp3_active', + 'TD_PERF_SEL_sampler_lerp4_active', + 'TD_PERF_SEL_sampler_lerp5_active', + 'TD_PERF_SEL_sampler_lerp6_active', + 'TD_PERF_SEL_sampler_lerp7_active', + 'TD_PERF_SEL_sampler_lerp_busy', + 'TD_PERF_SEL_sampler_minmax_sclk_en', + 'TD_PERF_SEL_sampler_out_busy', 'TD_PERF_SEL_sampler_out_sclk_en', + 'TD_PERF_SEL_sampler_pkr_full', + 'TD_PERF_SEL_sampler_pkr_full_due_to_arb', + 'TD_PERF_SEL_sampler_preformatter_sclk_en', + 'TD_PERF_SEL_sampler_sclk_on_nofilter_sclk_off', + 'TD_PERF_SEL_status_packet', 'TD_PERF_SEL_store_preempts_a_load', + 'TD_PERF_SEL_ta_data_stall', + 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_2cycles', + 'TD_PERF_SEL_tc_cycling_of_nofilter_instr_4cycles', + 'TD_PERF_SEL_tc_data_stall', 'TD_PERF_SEL_tc_ram_stall', + 'TD_PERF_SEL_tc_td_data_fifo_full', + 'TD_PERF_SEL_tc_td_ram_fifo_full', + 'TD_PERF_SEL_tc_td_ram_fifo_max_cnt', 'TD_PERF_SEL_td_busy', + 'TD_PERF_SEL_td_cycling_of_nofilter_instr_2cycles', + 'TD_PERF_SEL_td_cycling_of_nofilter_instr_4cycles', + 'TD_PERF_SEL_three_comp_return_instr', + 'TD_PERF_SEL_total_num_instr', + 'TD_PERF_SEL_total_num_instr_with_perf_wdw', + 'TD_PERF_SEL_total_num_nofilter_instr', + 'TD_PERF_SEL_total_num_nofilter_instr_with_perf_wdw', + 'TD_PERF_SEL_total_num_sampler_instr', + 'TD_PERF_SEL_total_num_sampler_instr_with_perf_wdw', + 'TD_PERF_SEL_tri_proc_node_override_slot0', + 'TD_PERF_SEL_tri_proc_node_override_slot1', + 'TD_PERF_SEL_tri_run_ahs_slot0', 'TD_PERF_SEL_tri_run_ahs_slot1', + 'TD_PERF_SEL_tri_run_intersect_ahs_slot0', + 'TD_PERF_SEL_tri_run_intersect_ahs_slot1', + 'TD_PERF_SEL_triangle_back_facing_culled', + 'TD_PERF_SEL_triangle_front_facing_culled', + 'TD_PERF_SEL_triangle_non_opaque_culled', + 'TD_PERF_SEL_triangle_opaque_culled', + 'TD_PERF_SEL_two_comp_return_instr', + 'TD_PERF_SEL_user_defined_border', + 'TD_PERF_SEL_weight_data_rams_read', 'TD_PERF_SEL_white_border', + 'TD_PERF_SEL_write_ack_instr', 'TESS_ISOLINE', 'TESS_QUAD', + 'TESS_TRIANGLE', 'TEST_CLK_DIV_SEL', 'TEST_CLK_SEL', + 'TEST_CLK_SEL_0', 'TEST_CLK_SEL_1', 'TEST_CLK_SEL_2', + 'TEST_CLK_SEL_3', 'TEST_CLK_SEL_4', 'TEST_CLK_SEL_5', + 'TEST_CLK_SEL_6', 'TEST_CLK_SEL_7', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_G', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_P', + 'TEST_CLOCK_MUX_SELECT_DISPCLK_R', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_D', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_G', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_P', + 'TEST_CLOCK_MUX_SELECT_DSCCLK_R', 'TEST_CLOCK_MUX_SELECT_ENUM', + 'TEX_BC_SWIZZLE', 'TEX_BC_Swizzle_WXYZ', 'TEX_BC_Swizzle_WZYX', + 'TEX_BC_Swizzle_XWYZ', 'TEX_BC_Swizzle_XYZW', + 'TEX_BC_Swizzle_YXWZ', 'TEX_BC_Swizzle_ZYXW', + 'TEX_BORDER_COLOR_TYPE', 'TEX_BorderColor_OpaqueBlack', + 'TEX_BorderColor_OpaqueWhite', 'TEX_BorderColor_Register', + 'TEX_BorderColor_TransparentBlack', 'TEX_CHROMA_KEY', 'TEX_CLAMP', + 'TEX_COORD_TYPE', 'TEX_ChromaKey_Blend', 'TEX_ChromaKey_Disabled', + 'TEX_ChromaKey_Kill', 'TEX_ChromaKey_RESERVED_3', + 'TEX_Clamp_ClampHalfToBorder', 'TEX_Clamp_ClampToBorder', + 'TEX_Clamp_ClampToLast', 'TEX_Clamp_Mirror', + 'TEX_Clamp_MirrorOnceHalfToBorder', + 'TEX_Clamp_MirrorOnceToBorder', 'TEX_Clamp_MirrorOnceToLast', + 'TEX_Clamp_Repeat', 'TEX_CoordType_Normalized', + 'TEX_CoordType_Unnormalized', 'TEX_DEPTH_COMPARE_FUNCTION', + 'TEX_DepthCompareFunction_Always', + 'TEX_DepthCompareFunction_Equal', + 'TEX_DepthCompareFunction_Greater', + 'TEX_DepthCompareFunction_GreaterEqual', + 'TEX_DepthCompareFunction_Less', + 'TEX_DepthCompareFunction_LessEqual', + 'TEX_DepthCompareFunction_Never', + 'TEX_DepthCompareFunction_NotEqual', 'TEX_FORMAT_COMP', + 'TEX_FormatComp_RESERVED_3', 'TEX_FormatComp_Signed', + 'TEX_FormatComp_Unsigned', 'TEX_FormatComp_UnsignedBiased', + 'TEX_MAX_ANISO_RATIO', 'TEX_MIP_FILTER', + 'TEX_MaxAnisoRatio_16to1', 'TEX_MaxAnisoRatio_1to1', + 'TEX_MaxAnisoRatio_2to1', 'TEX_MaxAnisoRatio_4to1', + 'TEX_MaxAnisoRatio_8to1', 'TEX_MaxAnisoRatio_RESERVED_5', + 'TEX_MaxAnisoRatio_RESERVED_6', 'TEX_MaxAnisoRatio_RESERVED_7', + 'TEX_MipFilter_Linear', 'TEX_MipFilter_None', + 'TEX_MipFilter_Point', 'TEX_MipFilter_Point_Aniso_Adj', + 'TEX_REQUEST_SIZE', 'TEX_RequestSize_128B', + 'TEX_RequestSize_2X64B', 'TEX_RequestSize_32B', + 'TEX_RequestSize_64B', 'TEX_SAMPLER_TYPE', + 'TEX_SamplerType_Invalid', 'TEX_SamplerType_Valid', + 'TEX_XYFilter_AnisoLinear', 'TEX_XYFilter_AnisoPoint', + 'TEX_XYFilter_Linear', 'TEX_XYFilter_Point', 'TEX_XY_FILTER', + 'TEX_ZFilter_Linear', 'TEX_ZFilter_None', 'TEX_ZFilter_Point', + 'TEX_ZFilter_RESERVED_3', 'TEX_Z_FILTER', 'TGID_ROLLOVER', + 'THREAD_TRACE_DRAW', 'THREAD_TRACE_FINISH', 'THREAD_TRACE_MARKER', + 'THREAD_TRACE_START', 'THREAD_TRACE_STOP', 'TMDS_COLOR_FORMAT', + 'TMDS_COLOR_FORMAT_DUAL30BPP', 'TMDS_COLOR_FORMAT_RESERVED', + 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 'TMDS_CTL0_DATA_INVERT', 'TMDS_CTL0_DATA_INVERT_EN', + 'TMDS_CTL0_DATA_MODULATION', 'TMDS_CTL0_DATA_MODULATION_BIT0', + 'TMDS_CTL0_DATA_MODULATION_BIT1', + 'TMDS_CTL0_DATA_MODULATION_BIT2', + 'TMDS_CTL0_DATA_MODULATION_DISABLE', 'TMDS_CTL0_DATA_NORMAL', + 'TMDS_CTL0_DATA_SEL', 'TMDS_CTL0_DATA_SEL0_RESERVED', + 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL0_DATA_SEL2_VSYNC', + 'TMDS_CTL0_DATA_SEL3_RESERVED', 'TMDS_CTL0_DATA_SEL4_HSYNC', + 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', + 'TMDS_CTL0_PATTERN_OUT_DISABLE', 'TMDS_CTL0_PATTERN_OUT_EN', + 'TMDS_CTL0_PATTERN_OUT_ENABLE', 'TMDS_CTL1_DATA_INVERT', + 'TMDS_CTL1_DATA_INVERT_EN', 'TMDS_CTL1_DATA_MODULATION', + 'TMDS_CTL1_DATA_MODULATION_BIT0', + 'TMDS_CTL1_DATA_MODULATION_BIT1', + 'TMDS_CTL1_DATA_MODULATION_BIT2', + 'TMDS_CTL1_DATA_MODULATION_DISABLE', 'TMDS_CTL1_DATA_NORMAL', + 'TMDS_CTL1_DATA_SEL', 'TMDS_CTL1_DATA_SEL0_RESERVED', + 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL1_DATA_SEL2_VSYNC', + 'TMDS_CTL1_DATA_SEL3_RESERVED', 'TMDS_CTL1_DATA_SEL4_HSYNC', + 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL1_PATTERN_OUT_DISABLE', 'TMDS_CTL1_PATTERN_OUT_EN', + 'TMDS_CTL1_PATTERN_OUT_ENABLE', 'TMDS_CTL2_DATA_INVERT', + 'TMDS_CTL2_DATA_INVERT_EN', 'TMDS_CTL2_DATA_MODULATION', + 'TMDS_CTL2_DATA_MODULATION_BIT0', + 'TMDS_CTL2_DATA_MODULATION_BIT1', + 'TMDS_CTL2_DATA_MODULATION_BIT2', + 'TMDS_CTL2_DATA_MODULATION_DISABLE', 'TMDS_CTL2_DATA_NORMAL', + 'TMDS_CTL2_DATA_SEL', 'TMDS_CTL2_DATA_SEL0_RESERVED', + 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL2_DATA_SEL2_VSYNC', + 'TMDS_CTL2_DATA_SEL3_RESERVED', 'TMDS_CTL2_DATA_SEL4_HSYNC', + 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL2_PATTERN_OUT_DISABLE', 'TMDS_CTL2_PATTERN_OUT_EN', + 'TMDS_CTL2_PATTERN_OUT_ENABLE', 'TMDS_CTL3_DATA_INVERT', + 'TMDS_CTL3_DATA_INVERT_EN', 'TMDS_CTL3_DATA_MODULATION', + 'TMDS_CTL3_DATA_MODULATION_BIT0', + 'TMDS_CTL3_DATA_MODULATION_BIT1', + 'TMDS_CTL3_DATA_MODULATION_BIT2', + 'TMDS_CTL3_DATA_MODULATION_DISABLE', 'TMDS_CTL3_DATA_NORMAL', + 'TMDS_CTL3_DATA_SEL', 'TMDS_CTL3_DATA_SEL0_RESERVED', + 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL3_DATA_SEL2_VSYNC', + 'TMDS_CTL3_DATA_SEL3_RESERVED', 'TMDS_CTL3_DATA_SEL4_HSYNC', + 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL3_PATTERN_OUT_DISABLE', 'TMDS_CTL3_PATTERN_OUT_EN', + 'TMDS_CTL3_PATTERN_OUT_ENABLE', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', 'TMDS_DVI_MODE', + 'TMDS_HDMI_MODE', 'TMDS_MUX_SELECT', 'TMDS_MUX_SELECT_B', + 'TMDS_MUX_SELECT_G', 'TMDS_MUX_SELECT_R', + 'TMDS_MUX_SELECT_RESERVED', 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 'TMDS_PIXEL_ENCODING', 'TMDS_PIXEL_ENCODING_422', + 'TMDS_PIXEL_ENCODING_444_OR_420', 'TMDS_REG_TEST_OUTPUTA_CNTLA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 'TMDS_REG_TEST_OUTPUTB_CNTLB', 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', 'TMDS_STEREOSYNC_CTL0', + 'TMDS_STEREOSYNC_CTL1', 'TMDS_STEREOSYNC_CTL2', + 'TMDS_STEREOSYNC_CTL3', 'TMDS_STEREOSYNC_CTL_SEL_REG', + 'TMDS_SYNC_PHASE', 'TMDS_SYNC_PHASE_ON_FRAME_START', + 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB', + 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK', + 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', + 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', + 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', + 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', 'TRANSERR', + 'TRANSFERRED_1024_BYTES', 'TRANSFERRED_128_BYTES', + 'TRANSFERRED_2048_BYTES', 'TRANSFERRED_256_BYTES', + 'TRANSFERRED_4096_BYTES', 'TRANSFERRED_512_BYTES', + 'TRANSFERRED_64_BYTES', 'TRANSFERRED_8192_BYTES', 'TRAPEZOIDS', + 'TRISTRIP', 'TVX_TYPE', 'TVX_Type_InvalidTextureResource', + 'TVX_Type_InvalidVertexBuffer', 'TVX_Type_ValidTextureResource', + 'TVX_Type_ValidVertexBuffer', 'UCONFIG_SPACE_END', + 'UCONFIG_SPACE_START', 'UNDEF', 'UNSIGNED', 'UTCL0FaultType', + 'UTCL0RequestType', 'UTCL0_TYPE_BYPASS', 'UTCL0_TYPE_NORMAL', + 'UTCL0_TYPE_SHOOTDOWN', 'UTCL0_XNACK_NO_RETRY', 'UTCL0_XNACK_PRT', + 'UTCL0_XNACK_RETRY', 'UTCL0_XNACK_SUCCESS', 'UTCL1FaultType', + 'UTCL1PerfSel', 'UTCL1RequestType', + 'UTCL1_PERF_SEL_ALOG_CACHE_HIT', 'UTCL1_PERF_SEL_ALOG_CACHE_REQ', + 'UTCL1_PERF_SEL_ALOG_INTERRUPT', + 'UTCL1_PERF_SEL_ALOG_INTERRUPT_DROPPED', + 'UTCL1_PERF_SEL_ALOG_STALL_PMM_CREDITS', + 'UTCL1_PERF_SEL_AVG_INV_LATENCY', 'UTCL1_PERF_SEL_BYPASS_REQS', + 'UTCL1_PERF_SEL_CP_INVREQS', 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC0', + 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC1', + 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC2', + 'UTCL1_PERF_SEL_EVICTIONS_NUM_CC3', 'UTCL1_PERF_SEL_HITS', + 'UTCL1_PERF_SEL_HITS_PG_SIZE_1', 'UTCL1_PERF_SEL_HITS_PG_SIZE_2', + 'UTCL1_PERF_SEL_HITS_PG_SIZE_3', 'UTCL1_PERF_SEL_HITS_PG_SIZE_4', + 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', + 'UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS', + 'UTCL1_PERF_SEL_MH_DUPLICATE_DETECT', + 'UTCL1_PERF_SEL_MH_RECENT_BUF_HIT', 'UTCL1_PERF_SEL_MISSES', + 'UTCL1_PERF_SEL_NONE', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC0', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC1', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC2', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_RQ_EXISTS_TO_CC3', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC0', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC1', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC2', + 'UTCL1_PERF_SEL_NUM_OF_CYCLES_W_COLLISION_CC3', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_16M_32M', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_1M_2M', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_256K_512K', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_2M_4M', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_32M_INF', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4K_64K', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_4M_8M', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_512K_1M', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_64K_256K', + 'UTCL1_PERF_SEL_NUM_UTCL2_RTN_SIZE_8M_16M', + 'UTCL1_PERF_SEL_RANGE_INVREQS', 'UTCL1_PERF_SEL_REQS', + 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_0', + 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_1', + 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_2', + 'UTCL1_PERF_SEL_REQ_NUM_CACHE_CORE_3', + 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_0', + 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_1', + 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_2', + 'UTCL1_PERF_SEL_REQ_TO_MISS_HNDLR_3', 'UTCL1_PERF_SEL_RTNS', + 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_0', + 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_1', + 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_2', + 'UTCL1_PERF_SEL_STALL_CYCLES_CACHE_CORE_3', + 'UTCL1_PERF_SEL_STALL_MH_FULL', + 'UTCL1_PERF_SEL_STALL_UTCL2_CREDITS', + 'UTCL1_PERF_SEL_UTCL0_UTCL1_INVACKS', + 'UTCL1_PERF_SEL_UTCL1_UTCL2_INVACKS', 'UTCL1_PERF_SEL_UTCL2_REQS', + 'UTCL1_PERF_SEL_UTCL2_REQS_OUTSTANDING_ACCUM', + 'UTCL1_PERF_SEL_UTCL2_REQ_SQUASHED_NUM', + 'UTCL1_PERF_SEL_UTCL2_RET_CNT', 'UTCL1_PERF_SEL_UTCL2_RET_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_PERM_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_PRT_FAULT', + 'UTCL1_PERF_SEL_UTCL2_RET_XNACK_RETRY', + 'UTCL1_PERF_SEL_UTCL2_UTCL1_INVREQS', + 'UTCL1_PERF_SEL_XLAT_REQ_BUSY', 'UTCL1_TYPE_BYPASS', + 'UTCL1_TYPE_NORMAL', 'UTCL1_TYPE_SHOOTDOWN', + 'UTCL1_XNACK_NO_RETRY', 'UTCL1_XNACK_PRT', 'UTCL1_XNACK_RETRY', + 'UTCL1_XNACK_SUCCESS', 'VGT_DETECT_ONE', 'VGT_DETECT_ZERO', + 'VGT_DIST_MODE', 'VGT_DI_INDEX_SIZE', 'VGT_DI_PRIM_TYPE', + 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', 'VGT_DMA_BUF_RING', + 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', 'VGT_DMA_PTR_UPDATE', + 'VGT_DMA_SWAP_16_BIT', 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', + 'VGT_DMA_SWAP_NONE', 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', + 'VGT_FLUSH', 'VGT_GROUP_CONV_SEL', 'VGT_GRP_AUTO_PRIM', + 'VGT_GRP_FIX_1_23_TO_FLOAT', 'VGT_GRP_FLOAT_32', + 'VGT_GRP_INDEX_16', 'VGT_GRP_INDEX_32', 'VGT_GRP_SINT_16', + 'VGT_GRP_SINT_32', 'VGT_GRP_UINT_16', 'VGT_GRP_UINT_32', + 'VGT_GS_MODE_TYPE', 'VGT_GS_OUTPRIM_TYPE', 'VGT_INDEX_16', + 'VGT_INDEX_32', 'VGT_INDEX_8', 'VGT_INDEX_TYPE_MODE', + 'VGT_OUTPATH_GS_BLOCK', 'VGT_OUTPATH_HS_BLOCK', + 'VGT_OUTPATH_PRIM_GEN', 'VGT_OUTPATH_SELECT', + 'VGT_OUTPATH_TE_GS_BLOCK', 'VGT_OUTPATH_TE_OUTPUT', + 'VGT_OUTPATH_TE_PRIM_GEN', 'VGT_OUTPATH_VTX_REUSE', + 'VGT_OUT_2D_RECT', 'VGT_OUT_DUMMY_1', 'VGT_OUT_DUMMY_2', + 'VGT_OUT_DUMMY_3', 'VGT_OUT_LINE', 'VGT_OUT_LINE_ADJ', + 'VGT_OUT_PATCH', 'VGT_OUT_POINT', 'VGT_OUT_PRIM_TYPE', + 'VGT_OUT_RECT_V0', 'VGT_OUT_TRI', 'VGT_OUT_TRI_ADJ', + 'VGT_POLICY_BYPASS', 'VGT_POLICY_LRU', 'VGT_POLICY_STREAM', + 'VGT_RDREQ_POLICY', 'VGT_SPEC_DATA_READ', + 'VGT_SPEC_DATA_READ_AUTO', 'VGT_SPEC_DATA_READ_FORCE_OFF', + 'VGT_SPEC_DATA_READ_FORCE_ON', 'VGT_STAGES_GS_EN', + 'VGT_STAGES_HS_EN', 'VGT_STREAMOUT_RESET', 'VGT_STREAMOUT_SYNC', + 'VGT_TEMPORAL', 'VGT_TEMPORAL_DISCARD', + 'VGT_TEMPORAL_HIGH_PRIORITY', 'VGT_TEMPORAL_NORMAL', + 'VGT_TEMPORAL_STREAM', 'VGT_TESS_PARTITION', 'VGT_TESS_TOPOLOGY', + 'VGT_TESS_TYPE', 'VID_ENHANCED_MODE', 'VID_NORMAL_FRAME_MODE', + 'VID_STREAM_DISABLE_MASKED', 'VID_STREAM_DISABLE_UNMASK', + 'VMID_SZ', 'VMPG_SIZE', 'VMPG_SIZE_4KB', 'VMPG_SIZE_64KB', + 'VM_GROUP_SIZE', 'VM_GROUP_SIZE_1024B', 'VM_GROUP_SIZE_128B', + 'VM_GROUP_SIZE_2048B', 'VM_GROUP_SIZE_256B', 'VM_GROUP_SIZE_512B', + 'VM_GROUP_SIZE_64B', 'VM_PG_SIZE_128KB', 'VM_PG_SIZE_128MB', + 'VM_PG_SIZE_16KB', 'VM_PG_SIZE_16MB', 'VM_PG_SIZE_1MB', + 'VM_PG_SIZE_256KB', 'VM_PG_SIZE_2MB', 'VM_PG_SIZE_32KB', + 'VM_PG_SIZE_32MB', 'VM_PG_SIZE_4KB', 'VM_PG_SIZE_4MB', + 'VM_PG_SIZE_512KB', 'VM_PG_SIZE_64KB', 'VM_PG_SIZE_64MB', + 'VM_PG_SIZE_8KB', 'VM_PG_SIZE_8MB', + 'VPG_MEM_DISABLE_MEM_PWR_CTRL', 'VPG_MEM_ENABLE_MEM_PWR_CTRL', + 'VPG_MEM_FORCE_LIGHT_SLEEP_REQ', 'VPG_MEM_NO_FORCE_REQ', + 'VPG_MEM_PWR_DIS_CTRL', 'VPG_MEM_PWR_FORCE_CTRL', + 'VREADY_AT_OR_AFTER_VSYNC', 'VREADY_BEFORE_VSYNC', + 'VRSCombinerModeSC', 'VRS_SHADING_RATE_16X_SSAA', + 'VRS_SHADING_RATE_1X1', 'VRS_SHADING_RATE_1X2', + 'VRS_SHADING_RATE_2X1', 'VRS_SHADING_RATE_2X2', + 'VRS_SHADING_RATE_2X4', 'VRS_SHADING_RATE_2X_SSAA', + 'VRS_SHADING_RATE_4X2', 'VRS_SHADING_RATE_4X4', + 'VRS_SHADING_RATE_4X_SSAA', 'VRS_SHADING_RATE_8X_SSAA', + 'VRS_SHADING_RATE_UNDEFINED0', 'VRS_SHADING_RATE_UNDEFINED1', + 'VRS_SHADING_RATE_UNDEFINED2', 'VRS_SHADING_RATE_UNDEFINED3', + 'VRS_SHADING_RATE_UNDEFINED4', 'VRSrate', 'VSYNC_CNT_LATCH_MASK', + 'VSYNC_CNT_LATCH_MASK_0', 'VSYNC_CNT_LATCH_MASK_1', + 'VSYNC_CNT_RESET_SEL', 'VSYNC_CNT_RESET_SEL_0', + 'VSYNC_CNT_RESET_SEL_1', 'VS_PARTIAL_FLUSH', 'VTG_SEL_0', + 'VTG_SEL_1', 'VTG_SEL_2', 'VTG_SEL_3', 'VTG_SEL_4', 'VTG_SEL_5', + 'WAIT_SYNC', 'WATERMARK_MODE', 'WD_IA_DRAW_REG_XFER', + 'WD_IA_DRAW_REG_XFER_FL_MS_EXP_ALLOC', + 'WD_IA_DRAW_REG_XFER_FL_MS_TG_SIZE', + 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM', + 'WD_IA_DRAW_REG_XFER_FL_MS_WG_DIM_1', + 'WD_IA_DRAW_REG_XFER_GE_CNTL', + 'WD_IA_DRAW_REG_XFER_GE_GS_THROTTLE', + 'WD_IA_DRAW_REG_XFER_GE_PC_ALLOC', + 'WD_IA_DRAW_REG_XFER_GE_STEREO_CNTL', + 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR1', + 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR2', + 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR3', + 'WD_IA_DRAW_REG_XFER_GE_USER_VGPR_EN', + 'WD_IA_DRAW_REG_XFER_GE_VRS_RATE', + 'WD_IA_DRAW_REG_XFER_GFX_PIPE_CONTROL', + 'WD_IA_DRAW_REG_XFER_SPI_SHADER_GS_OUT_CONFIG_PS', + 'WD_IA_DRAW_REG_XFER_VGT_DRAW_PAYLOAD_CNTL', + 'WD_IA_DRAW_REG_XFER_VGT_GS_OUT_PRIM_TYPE', + 'WD_IA_DRAW_REG_XFER_VGT_INSTANCE_BASE_ID', + 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_EN', + 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVEID_RESET', + 'WD_IA_DRAW_REG_XFER_VGT_PRIMITIVE_TYPE', 'WD_IA_DRAW_SOURCE', + 'WD_IA_DRAW_SOURCE_AUTO', 'WD_IA_DRAW_SOURCE_DMA', + 'WD_IA_DRAW_SOURCE_IMMD', 'WD_IA_DRAW_SOURCE_OPAQ', + 'WD_IA_DRAW_TYPE', 'WD_IA_DRAW_TYPE_DI_MM0', + 'WD_IA_DRAW_TYPE_EVENT_ADDR', 'WD_IA_DRAW_TYPE_EVENT_INIT', + 'WD_IA_DRAW_TYPE_IMM_DATA', 'WD_IA_DRAW_TYPE_INDX_OFF', + 'WD_IA_DRAW_TYPE_MAX_INDX', 'WD_IA_DRAW_TYPE_MIN_INDX', + 'WD_IA_DRAW_TYPE_REG_XFER', 'WRITE_BASE_ONLY', 'WRITE_BOTH', + 'WRITE_COMPRESSION_MODE', 'WritePolicy', 'XNORM', 'XNORM_A', + 'XNORM_B', 'XTAL_REF_CLOCK_SOURCE_SEL', + 'XTAL_REF_CLOCK_SOURCE_SEL_DCCGREFCLK', + 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', 'XTAL_REF_SEL', + 'XTAL_REF_SEL_1X', 'XTAL_REF_SEL_2X', 'Y10_CbCr1010_420_PLANAR', + 'Y10_CrCb1010_420_PLANAR', 'Y12_CbCr1212_420_PLANAR', + 'Y12_CrCb1212_420_PLANAR', 'Y8_CbCr88_420_PLANAR', + 'Y8_CrCb88_420_PLANAR', 'YCbYCr10101010_422_PACKED', + 'YCbYCr12121212_422_PACKED', 'YCbYCr8888_422_PACKED', + 'YCrCbA16161616_10LSB', 'YCrCbA16161616_10MSB', + 'YCrCbA16161616_12LSB', 'YCrCbA16161616_12MSB', 'YCrCbA8888', + 'YCrYCb10101010_422_PACKED', 'YCrYCb12121212_422_PACKED', + 'YCrYCb8888_422_PACKED', 'Y_G_DATA_ONTO_ALPHA_PORT', + 'Y_G_DATA_ONTO_CB_B_PORT', 'Y_G_DATA_ONTO_CR_R_PORT', + 'Y_G_DATA_ONTO_Y_G_PORT', 'ZLimitSumm', 'ZModeForce', 'ZOrder', + 'ZSamplePosition', 'Z_SAMPLE_CENTER', 'Z_SAMPLE_CENTROID', + '_soc24_ENUM_HEADER', 'ge1_assembler_busy', + 'ge1_assembler_dma_starved', 'ge1_assembler_stalled', + 'ge1_dma_busy', 'ge1_dma_lat_bin_0', 'ge1_dma_lat_bin_1', + 'ge1_dma_lat_bin_2', 'ge1_dma_lat_bin_3', 'ge1_dma_lat_bin_4', + 'ge1_dma_lat_bin_5', 'ge1_dma_lat_bin_6', 'ge1_dma_lat_bin_7', + 'ge1_dma_return_cl0', 'ge1_dma_return_cl1', + 'ge1_dma_return_size_cl0', 'ge1_dma_return_size_cl1', + 'ge1_dma_utcl1_consecutive_retry_event', + 'ge1_dma_utcl1_request_event', 'ge1_dma_utcl1_retry_event', + 'ge1_dma_utcl1_stall_event', 'ge1_dma_utcl1_stall_utcl2_event', + 'ge1_dma_utcl1_translation_hit_event', + 'ge1_dma_utcl1_translation_miss_event', 'ge1_pipe0_to_pipe1', + 'ge1_pipe1_to_pipe0', 'ge1_prim_group_limit_hit', + 'ge1_rbiu_di_fifo_stalled_p0', 'ge1_rbiu_di_fifo_stalled_p1', + 'ge1_rbiu_di_fifo_starved_p0', 'ge1_rbiu_di_fifo_starved_p1', + 'ge1_rbiu_dr_fifo_stalled_p0', 'ge1_rbiu_dr_fifo_stalled_p1', + 'ge1_rbiu_dr_fifo_starved_p0', 'ge1_rbiu_dr_fifo_starved_p1', + 'ge1_sclk_input_vld', 'ge1_sclk_reg_vld', + 'ge1_small_draws_one_instance', 'ge1_stat_busy', + 'ge1_stat_no_dma_busy', 'ge1_unopt_multi_instance_draws', + 'ge_agm_gcr_combine', 'ge_agm_gcr_crd_stall', + 'ge_agm_gcr_latency', 'ge_agm_gcr_req', 'ge_agm_gcr_req_amount', + 'ge_agm_gcr_req_outstanding', 'ge_agm_gcr_stall', + 'ge_agm_gcr_tag_stall', 'ge_all_tf2', 'ge_all_tf3', 'ge_all_tf4', + 'ge_all_tf5', 'ge_all_tf6', 'ge_all_tf_eq', 'ge_csb_spi_bp', + 'ge_dist_distributer_busy', 'ge_dist_hs_done', + 'ge_dist_hs_done_latency', 'ge_dist_hs_done_latency_se0', + 'ge_dist_hs_done_latency_se1', 'ge_dist_hs_done_latency_se2', + 'ge_dist_hs_done_latency_se3', 'ge_dist_hs_done_latency_se4', + 'ge_dist_hs_done_latency_se5', 'ge_dist_hs_done_latency_se6', + 'ge_dist_hs_done_latency_se7', 'ge_dist_hs_done_se0', + 'ge_dist_hs_done_se1', 'ge_dist_hs_done_se2', + 'ge_dist_hs_done_se3', 'ge_dist_hs_done_se4', + 'ge_dist_hs_done_se5', 'ge_dist_hs_done_se6', + 'ge_dist_hs_done_se7', 'ge_dist_indx_fifos_full_and_empty', + 'ge_dist_inside_tf_bin_0', 'ge_dist_inside_tf_bin_1', + 'ge_dist_inside_tf_bin_2', 'ge_dist_inside_tf_bin_3', + 'ge_dist_inside_tf_bin_4', 'ge_dist_inside_tf_bin_5', + 'ge_dist_inside_tf_bin_6', 'ge_dist_inside_tf_bin_7', + 'ge_dist_inside_tf_bin_8', 'ge_dist_null_patch', + 'ge_dist_op_fifo_full_starve', 'ge_dist_pc_feorder_fifo_full', + 'ge_dist_pc_ge_manager_busy', 'ge_dist_sclk_core_vld', + 'ge_dist_sclk_input_vld', 'ge_dist_sclk_wd_te11_vld', + 'ge_dist_switch_mode_stall', 'ge_dist_te11_starved', + 'ge_dist_tfreq_lat_bin_0', 'ge_dist_tfreq_lat_bin_1', + 'ge_dist_tfreq_lat_bin_2', 'ge_dist_tfreq_lat_bin_3', + 'ge_dist_tfreq_lat_bin_4', 'ge_dist_tfreq_lat_bin_5', + 'ge_dist_tfreq_lat_bin_6', 'ge_dist_tfreq_lat_bin_7', + 'ge_dist_tfreq_utcl1_consecutive_retry_event', + 'ge_dist_tfreq_utcl1_request_event', + 'ge_dist_tfreq_utcl1_retry_event', + 'ge_dist_tfreq_utcl1_stall_event', + 'ge_dist_tfreq_utcl1_stall_utcl2_event', + 'ge_dist_tfreq_utcl1_translation_hit_event', + 'ge_dist_tfreq_utcl1_translation_miss_event', + 'ge_dist_wd_te11_busy', 'ge_distclk_vld', 'ge_esvert_send', + 'ge_gs_issue_rtr_stalled', 'ge_gsprim_send', + 'ge_gsprim_stalled_esvert', 'ge_gsthread_stalled', + 'ge_hs_done_all_tf0_se0', 'ge_hs_done_all_tf0_se1', + 'ge_hs_done_all_tf0_se2', 'ge_hs_done_all_tf0_se3', + 'ge_hs_done_all_tf0_se4', 'ge_hs_done_all_tf0_se5', + 'ge_hs_done_all_tf0_se6', 'ge_hs_done_all_tf0_se7', + 'ge_hs_done_all_tf1_se0', 'ge_hs_done_all_tf1_se1', + 'ge_hs_done_all_tf1_se2', 'ge_hs_done_all_tf1_se3', + 'ge_hs_done_all_tf1_se4', 'ge_hs_done_all_tf1_se5', + 'ge_hs_done_all_tf1_se6', 'ge_hs_done_all_tf1_se7', + 'ge_hs_stall_tfmm_fifo_full', 'ge_hs_tif_stall', + 'ge_merge_gsgrp_rdy_pending_verts', + 'ge_merge_hsgrp_rdy_pending_verts', 'ge_merge_hsgs_fifo_blocked', + 'ge_merge_hsgs_grp_switch', 'ge_merge_hsgs_vert_switch', + 'ge_merge_lses_fifo_blocked', 'ge_merge_lses_vert_switch', + 'ge_merged_hsgs_grp_stalled', 'ge_merged_hsgs_vert_stalled', + 'ge_merged_lses_vert_stalled', 'ge_ngg_agm_req_stall', + 'ge_ngg_attr_discard_alloc', 'ge_ngg_attr_grp_alloc', + 'ge_ngg_attr_grp_latency', 'ge_ngg_attr_grp_wasted', + 'ge_ngg_attr_null_dealloc', 'ge_ngg_busy_base', + 'ge_ngg_indx_bus_stall', 'ge_ngg_ord_id_req_stall', + 'ge_ngg_pc_space_not_avail', 'ge_ngg_reuse_prim_limit_hit', + 'ge_ngg_reuse_vert_limit_hit', 'ge_ngg_spi_esvert_partial_eov', + 'ge_ngg_spi_gsprim_partial_eov', 'ge_ngg_stall_tess_off_tess_on', + 'ge_ngg_stall_tess_on_tess_off', 'ge_ngg_starved_after_work', + 'ge_ngg_starved_idle', 'ge_ngg_starving_for_wave_id', + 'ge_ngg_subgrp_fifo_stall', 'ge_num_of_donut_dist_patches', + 'ge_num_of_hs_dealloc_events', 'ge_num_of_no_dist_patches', + 'ge_num_of_patch_dist_patches', + 'ge_num_of_se_switches_due_to_donut', + 'ge_num_of_se_switches_due_to_patch_accum', + 'ge_num_of_se_switches_due_to_trap', 'ge_pa0_csb_eop', + 'ge_se0_te11_starved_on_hs_done', + 'ge_se1_te11_starved_on_hs_done', + 'ge_se2_te11_starved_on_hs_done', + 'ge_se3_te11_starved_on_hs_done', + 'ge_se4_te11_starved_on_hs_done', + 'ge_se5_te11_starved_on_hs_done', + 'ge_se6_te11_starved_on_hs_done', + 'ge_se7_te11_starved_on_hs_done', 'ge_se_api_ds_verts', + 'ge_se_api_vs_verts', 'ge_se_combined_busy', + 'ge_se_ds_cache_hits', 'ge_se_ds_prims', 'ge_se_es_thread_groups', + 'ge_se_esvert_stalled_gsprim', 'ge_se_hs_input_stall', + 'ge_se_hs_tfm_stall', 'ge_se_hs_tgs_active_high_water_mark', + 'ge_se_hs_thread_groups', 'ge_se_reused_es_indices', + 'ge_se_sclk_input_vld', 'ge_se_sclk_ngg_vld', + 'ge_se_sclk_te11_vld', 'ge_se_sending_vert_or_prim', + 'ge_se_spi_esvert_eov', 'ge_se_spi_esvert_stalled', + 'ge_se_spi_esvert_starved_busy', 'ge_se_spi_esvert_valid', + 'ge_se_spi_gsprim_cont', 'ge_se_spi_gsprim_eov', + 'ge_se_spi_gsprim_stalled', 'ge_se_spi_gsprim_starved_busy', + 'ge_se_spi_gsprim_valid', + 'ge_se_spi_gssubgrp_event_window_active', + 'ge_se_spi_gssubgrp_is_event', 'ge_se_spi_gssubgrp_send', + 'ge_se_spi_hsgrp_is_event', 'ge_se_spi_hsgrp_send', + 'ge_se_spi_hsvert_eov', 'ge_se_spi_hsvert_fifo_full_stall', + 'ge_se_spi_hsvert_stalled', 'ge_se_spi_hsvert_starved_busy', + 'ge_se_spi_hsvert_valid', 'ge_se_spi_lsvert_eov', + 'ge_se_spi_lsvert_stalled', 'ge_se_spi_lsvert_starved_busy', + 'ge_se_spi_lsvert_valid', 'ge_se_spi_tgrp_fifo_stall', + 'ge_spi_gsgrp_valid', 'ge_spi_gssubgrp_stalled', + 'ge_spi_hsgrp_spi_stall', 'ge_spi_hsvert_send', + 'ge_spi_hswave_fifo_full_stall', 'ge_spi_lsvert_send', + 'ge_spi_lswave_fifo_full_stall', 'ge_te11_compactor_starved', + 'ge_te11_con_stall', 'ge_tf_ret_data_stalling_hs_done'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/am/vega10.py b/tinygrad_repo/tinygrad/runtime/autogen/am/vega10.py new file mode 100644 index 0000000000..510fbe6a03 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/am/vega10.py @@ -0,0 +1,36196 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + + + +_vega10_ENUM_HEADER = True # macro +ENUMS_GDS_PERFCOUNT_SELECT_H = True # macro +SQ_WAVE_TYPE_PS0 = 0x00000000 # macro +SQIND_GLOBAL_REGS_OFFSET = 0x00000000 # macro +SQIND_GLOBAL_REGS_SIZE = 0x00000008 # macro +SQIND_LOCAL_REGS_OFFSET = 0x00000008 # macro +SQIND_LOCAL_REGS_SIZE = 0x00000008 # macro +SQIND_WAVE_HWREGS_OFFSET = 0x00000010 # macro +SQIND_WAVE_HWREGS_SIZE = 0x000001f0 # macro +SQIND_WAVE_SGPRS_OFFSET = 0x00000200 # macro +SQIND_WAVE_SGPRS_SIZE = 0x00000200 # macro +SQIND_WAVE_VGPRS_OFFSET = 0x00000400 # macro +SQIND_WAVE_VGPRS_SIZE = 0x00000100 # macro +SQ_GFXDEC_BEGIN = 0x0000a000 # macro +SQ_GFXDEC_END = 0x0000c000 # macro +SQ_GFXDEC_STATE_ID_SHIFT = 0x0000000a # macro +SQDEC_BEGIN = 0x00002300 # macro +SQDEC_END = 0x000023ff # macro +SQPERFSDEC_BEGIN = 0x0000d9c0 # macro +SQPERFSDEC_END = 0x0000da40 # macro +SQPERFDDEC_BEGIN = 0x0000d1c0 # macro +SQPERFDDEC_END = 0x0000d240 # macro +SQGFXUDEC_BEGIN = 0x0000c330 # macro +SQGFXUDEC_END = 0x0000c380 # macro +SQPWRDEC_BEGIN = 0x0000f08c # macro +SQPWRDEC_END = 0x0000f094 # macro +SQ_DISPATCHER_GFX_MIN = 0x00000010 # macro +SQ_DISPATCHER_GFX_CNT_PER_RING = 0x00000008 # macro +SQ_MAX_PGM_SGPRS = 0x00000068 # macro +SQ_MAX_PGM_VGPRS = 0x00000100 # macro +SQ_THREAD_TRACE_TIME_UNIT = 0x00000004 # macro +SQ_EX_MODE_EXCP_VALU_BASE = 0x00000000 # macro +SQ_EX_MODE_EXCP_VALU_SIZE = 0x00000007 # macro +SQ_EX_MODE_EXCP_INVALID = 0x00000000 # macro +SQ_EX_MODE_EXCP_INPUT_DENORM = 0x00000001 # macro +SQ_EX_MODE_EXCP_DIV0 = 0x00000002 # macro +SQ_EX_MODE_EXCP_OVERFLOW = 0x00000003 # macro +SQ_EX_MODE_EXCP_UNDERFLOW = 0x00000004 # macro +SQ_EX_MODE_EXCP_INEXACT = 0x00000005 # macro +SQ_EX_MODE_EXCP_INT_DIV0 = 0x00000006 # macro +SQ_EX_MODE_EXCP_ADDR_WATCH0 = 0x00000007 # macro +SQ_EX_MODE_EXCP_MEM_VIOL = 0x00000008 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH1 = 0x00000000 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH2 = 0x00000001 # macro +SQ_EX_MODE_EXCP_HI_ADDR_WATCH3 = 0x00000002 # macro +INST_ID_PRIV_START = 0x80000000 # macro +INST_ID_ECC_INTERRUPT_MSG = 0xfffffff0 # macro +INST_ID_TTRACE_NEW_PC_MSG = 0xfffffff1 # macro +INST_ID_HW_TRAP = 0xfffffff2 # macro +INST_ID_KILL_SEQ = 0xfffffff3 # macro +INST_ID_SPI_WREXEC = 0xfffffff4 # macro +INST_ID_HOST_REG_TRAP_MSG = 0xfffffffe # macro +SIMM16_WAITCNT_VM_CNT_START = 0x00000000 # macro +SIMM16_WAITCNT_VM_CNT_SIZE = 0x00000004 # macro +SIMM16_WAITCNT_EXP_CNT_START = 0x00000004 # macro +SIMM16_WAITCNT_EXP_CNT_SIZE = 0x00000003 # macro +SIMM16_WAITCNT_LGKM_CNT_START = 0x00000008 # macro +SIMM16_WAITCNT_LGKM_CNT_SIZE = 0x00000004 # macro +SIMM16_WAITCNT_VM_CNT_HI_START = 0x0000000e # macro +SIMM16_WAITCNT_VM_CNT_HI_SIZE = 0x00000002 # macro +SQ_EDC_FUE_CNTL_SQ = 0x00000000 # macro +SQ_EDC_FUE_CNTL_LDS = 0x00000001 # macro +SQ_EDC_FUE_CNTL_SIMD0 = 0x00000002 # macro +SQ_EDC_FUE_CNTL_SIMD1 = 0x00000003 # macro +SQ_EDC_FUE_CNTL_SIMD2 = 0x00000004 # macro +SQ_EDC_FUE_CNTL_SIMD3 = 0x00000005 # macro +SQ_EDC_FUE_CNTL_TA = 0x00000006 # macro +SQ_EDC_FUE_CNTL_TD = 0x00000007 # macro +SQ_EDC_FUE_CNTL_TCP = 0x00000008 # macro +CSDATA_TYPE_WIDTH = 0x00000002 # macro +CSDATA_ADDR_WIDTH = 0x00000007 # macro +CSDATA_DATA_WIDTH = 0x00000020 # macro +GSTHREADID_SIZE = 0x00000002 # macro +GB_TILING_CONFIG_TABLE_SIZE = 0x00000020 # macro +GB_TILING_CONFIG_MACROTABLE_SIZE = 0x00000010 # macro +SEM_ECC_ERROR = 0x00000000 # macro +SEM_TRANS_ERROR = 0x00000001 # macro +SEM_FAILED = 0x00000002 # macro +SEM_PASSED = 0x00000003 # macro +IQ_QUEUE_SLEEP = 0x00000000 # macro +IQ_OFFLOAD_RETRY = 0x00000001 # macro +IQ_SCH_WAVE_MSG = 0x00000002 # macro +IQ_SEM_REARM = 0x00000003 # macro +IQ_DEQUEUE_RETRY = 0x00000004 # macro +IQ_INTR_TYPE_PQ = 0x00000000 # macro +IQ_INTR_TYPE_IB = 0x00000001 # macro +IQ_INTR_TYPE_MQD = 0x00000002 # macro +VMID_SZ = 0x00000004 # macro +CONFIG_SPACE_START = 0x00002000 # macro +CONFIG_SPACE_END = 0x00009fff # macro +CONFIG_SPACE1_START = 0x00002000 # macro +CONFIG_SPACE1_END = 0x00002bff # macro +CONFIG_SPACE2_START = 0x00003000 # macro +CONFIG_SPACE2_END = 0x00009fff # macro +UCONFIG_SPACE_START = 0x0000c000 # macro +UCONFIG_SPACE_END = 0x0000ffff # macro +PERSISTENT_SPACE_START = 0x00002c00 # macro +PERSISTENT_SPACE_END = 0x00002fff # macro +CONTEXT_SPACE_START = 0x0000a000 # macro +CONTEXT_SPACE_END = 0x0000bfff # macro +SQ_ENC_SOP1_BITS = 0xbe800000 # macro +SQ_ENC_SOP1_MASK = 0xff800000 # macro +SQ_ENC_SOP1_FIELD = 0x0000017d # macro +SQ_ENC_SOPC_BITS = 0xbf000000 # macro +SQ_ENC_SOPC_MASK = 0xff800000 # macro +SQ_ENC_SOPC_FIELD = 0x0000017e # macro +SQ_ENC_SOPP_BITS = 0xbf800000 # macro +SQ_ENC_SOPP_MASK = 0xff800000 # macro +SQ_ENC_SOPP_FIELD = 0x0000017f # macro +SQ_ENC_SOPK_BITS = 0xb0000000 # macro +SQ_ENC_SOPK_MASK = 0xf0000000 # macro +SQ_ENC_SOPK_FIELD = 0x0000000b # macro +SQ_ENC_SOP2_BITS = 0x80000000 # macro +SQ_ENC_SOP2_MASK = 0xc0000000 # macro +SQ_ENC_SOP2_FIELD = 0x00000002 # macro +SQ_ENC_SMEM_BITS = 0xc0000000 # macro +SQ_ENC_SMEM_MASK = 0xfc000000 # macro +SQ_ENC_SMEM_FIELD = 0x00000030 # macro +SQ_ENC_VOP1_BITS = 0x7e000000 # macro +SQ_ENC_VOP1_MASK = 0xfe000000 # macro +SQ_ENC_VOP1_FIELD = 0x0000003f # macro +SQ_ENC_VOPC_BITS = 0x7c000000 # macro +SQ_ENC_VOPC_MASK = 0xfe000000 # macro +SQ_ENC_VOPC_FIELD = 0x0000003e # macro +SQ_ENC_VOP2_BITS = 0x00000000 # macro +SQ_ENC_VOP2_MASK = 0x80000000 # macro +SQ_ENC_VOP2_FIELD = 0x00000000 # macro +SQ_ENC_VINTRP_BITS = 0xd4000000 # macro +SQ_ENC_VINTRP_MASK = 0xfc000000 # macro +SQ_ENC_VINTRP_FIELD = 0x00000035 # macro +SQ_ENC_VOP3P_BITS = 0xd3800000 # macro +SQ_ENC_VOP3P_MASK = 0xff800000 # macro +SQ_ENC_VOP3P_FIELD = 0x000001a7 # macro +SQ_ENC_VOP3_BITS = 0xd0000000 # macro +SQ_ENC_VOP3_MASK = 0xfc000000 # macro +SQ_ENC_VOP3_FIELD = 0x00000034 # macro +SQ_ENC_DS_BITS = 0xd8000000 # macro +SQ_ENC_DS_MASK = 0xfc000000 # macro +SQ_ENC_DS_FIELD = 0x00000036 # macro +SQ_ENC_MUBUF_BITS = 0xe0000000 # macro +SQ_ENC_MUBUF_MASK = 0xfc000000 # macro +SQ_ENC_MUBUF_FIELD = 0x00000038 # macro +SQ_ENC_MTBUF_BITS = 0xe8000000 # macro +SQ_ENC_MTBUF_MASK = 0xfc000000 # macro +SQ_ENC_MTBUF_FIELD = 0x0000003a # macro +SQ_ENC_MIMG_BITS = 0xf0000000 # macro +SQ_ENC_MIMG_MASK = 0xfc000000 # macro +SQ_ENC_MIMG_FIELD = 0x0000003c # macro +SQ_ENC_EXP_BITS = 0xc4000000 # macro +SQ_ENC_EXP_MASK = 0xfc000000 # macro +SQ_ENC_EXP_FIELD = 0x00000031 # macro +SQ_ENC_FLAT_BITS = 0xdc000000 # macro +SQ_ENC_FLAT_MASK = 0xfc000000 # macro +SQ_ENC_FLAT_FIELD = 0x00000037 # macro +SQ_V_OP3_INTRP_COUNT = 0x0000000c # macro +SQ_SENDMSG_SYSTEM_SIZE = 0x00000003 # macro +SQ_HWREG_ID_SIZE = 0x00000006 # macro +SQ_V_OPC_COUNT = 0x00000100 # macro +SQ_NUM_VGPR = 0x00000100 # macro +SQ_WAITCNT_LGKM_SHIFT = 0x00000008 # macro +SQ_HWREG_ID_SHIFT = 0x00000000 # macro +SQ_EXP_NUM_POS = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VOPC_OFFSET = 0x00000000 # macro +SQ_V_OP3_2IN_OFFSET = 0x00000280 # macro +SQ_XLATE_VOP3_TO_VOP2_OFFSET = 0x00000100 # macro +SQ_EXP_NUM_MRT = 0x00000008 # macro +SQ_NUM_TTMP = 0x00000010 # macro +SQ_SENDMSG_STREAMID_SHIFT = 0x00000008 # macro +SQ_V_OP1_COUNT = 0x00000080 # macro +SQ_WAITCNT_LGKM_SIZE = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VOPC_COUNT = 0x00000100 # macro +SQ_SENDMSG_MSG_SHIFT = 0x00000000 # macro +SQ_V_OP3_3IN_OFFSET = 0x000001c0 # macro +SQ_HWREG_OFFSET_SHIFT = 0x00000006 # macro +SQ_HWREG_SIZE_SHIFT = 0x0000000b # macro +SQ_HWREG_OFFSET_SIZE = 0x00000005 # macro +SQ_V_OP3_3IN_COUNT = 0x000000b0 # macro +SQ_SENDMSG_MSG_SIZE = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VOP1_COUNT = 0x00000080 # macro +SQ_EXP_NUM_GDS = 0x00000005 # macro +SQ_V_OP2_COUNT = 0x00000040 # macro +SQ_SENDMSG_GSOP_SIZE = 0x00000002 # macro +SQ_WAITCNT_VM_SHIFT = 0x00000000 # macro +SQ_XLATE_VOP3_TO_VOP3P_COUNT = 0x00000080 # macro +SQ_V_OP3_2IN_COUNT = 0x00000080 # macro +SQ_SENDMSG_SYSTEM_SHIFT = 0x00000004 # macro +SQ_WAITCNT_VM_SIZE = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VOP3P_OFFSET = 0x00000380 # macro +SQ_WAITCNT_EXP_SHIFT = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VOP2_COUNT = 0x00000040 # macro +SQ_EXP_NUM_PARAM = 0x00000020 # macro +SQ_HWREG_SIZE_SIZE = 0x00000005 # macro +SQ_WAITCNT_EXP_SIZE = 0x00000003 # macro +SQ_V_OP3_INTRP_OFFSET = 0x00000274 # macro +SQ_SENDMSG_GSOP_SHIFT = 0x00000004 # macro +SQ_XLATE_VOP3_TO_VINTRP_OFFSET = 0x00000270 # macro +SQ_NUM_ATTR = 0x00000021 # macro +SQ_NUM_SGPR = 0x00000066 # macro +SQ_SRC_VGPR_BIT = 0x00000100 # macro +SQ_V_INTRP_COUNT = 0x00000004 # macro +SQ_SENDMSG_STREAMID_SIZE = 0x00000002 # macro +SQ_V_OP3P_COUNT = 0x00000080 # macro +SQ_XLATE_VOP3_TO_VOP1_OFFSET = 0x00000140 # macro +SQ_XLATE_VOP3_TO_VINTRP_COUNT = 0x00000004 # macro +SQ_SRC_DPP = 0x000000fa # macro +SQ_TBUFFER_LOAD_FORMAT_X = 0x00000000 # macro +SQ_TBUFFER_LOAD_FORMAT_XY = 0x00000001 # macro +SQ_TBUFFER_LOAD_FORMAT_XYZ = 0x00000002 # macro +SQ_TBUFFER_LOAD_FORMAT_XYZW = 0x00000003 # macro +SQ_TBUFFER_STORE_FORMAT_X = 0x00000004 # macro +SQ_TBUFFER_STORE_FORMAT_XY = 0x00000005 # macro +SQ_TBUFFER_STORE_FORMAT_XYZ = 0x00000006 # macro +SQ_TBUFFER_STORE_FORMAT_XYZW = 0x00000007 # macro +SQ_TBUFFER_LOAD_FORMAT_D16_X = 0x00000008 # macro +SQ_TBUFFER_LOAD_FORMAT_D16_XY = 0x00000009 # macro +SQ_TBUFFER_LOAD_FORMAT_D16_XYZ = 0x0000000a # macro +SQ_TBUFFER_LOAD_FORMAT_D16_XYZW = 0x0000000b # macro +SQ_TBUFFER_STORE_FORMAT_D16_X = 0x0000000c # macro +SQ_TBUFFER_STORE_FORMAT_D16_XY = 0x0000000d # macro +SQ_TBUFFER_STORE_FORMAT_D16_XYZ = 0x0000000e # macro +SQ_TBUFFER_STORE_FORMAT_D16_XYZW = 0x0000000f # macro +SQ_GLOBAL_LOAD_UBYTE = 0x00000010 # macro +SQ_GLOBAL_LOAD_SBYTE = 0x00000011 # macro +SQ_GLOBAL_LOAD_USHORT = 0x00000012 # macro +SQ_GLOBAL_LOAD_SSHORT = 0x00000013 # macro +SQ_GLOBAL_LOAD_DWORD = 0x00000014 # macro +SQ_GLOBAL_LOAD_DWORDX2 = 0x00000015 # macro +SQ_GLOBAL_LOAD_DWORDX3 = 0x00000016 # macro +SQ_GLOBAL_LOAD_DWORDX4 = 0x00000017 # macro +SQ_GLOBAL_STORE_BYTE = 0x00000018 # macro +SQ_GLOBAL_STORE_SHORT = 0x0000001a # macro +SQ_GLOBAL_STORE_DWORD = 0x0000001c # macro +SQ_GLOBAL_STORE_DWORDX2 = 0x0000001d # macro +SQ_GLOBAL_STORE_DWORDX3 = 0x0000001e # macro +SQ_GLOBAL_STORE_DWORDX4 = 0x0000001f # macro +SQ_GLOBAL_ATOMIC_SWAP = 0x00000040 # macro +SQ_GLOBAL_ATOMIC_CMPSWAP = 0x00000041 # macro +SQ_GLOBAL_ATOMIC_ADD = 0x00000042 # macro +SQ_GLOBAL_ATOMIC_SUB = 0x00000043 # macro +SQ_GLOBAL_ATOMIC_SMIN = 0x00000044 # macro +SQ_GLOBAL_ATOMIC_UMIN = 0x00000045 # macro +SQ_GLOBAL_ATOMIC_SMAX = 0x00000046 # macro +SQ_GLOBAL_ATOMIC_UMAX = 0x00000047 # macro +SQ_GLOBAL_ATOMIC_AND = 0x00000048 # macro +SQ_GLOBAL_ATOMIC_OR = 0x00000049 # macro +SQ_GLOBAL_ATOMIC_XOR = 0x0000004a # macro +SQ_GLOBAL_ATOMIC_INC = 0x0000004b # macro +SQ_GLOBAL_ATOMIC_DEC = 0x0000004c # macro +SQ_GLOBAL_ATOMIC_SWAP_X2 = 0x00000060 # macro +SQ_GLOBAL_ATOMIC_CMPSWAP_X2 = 0x00000061 # macro +SQ_GLOBAL_ATOMIC_ADD_X2 = 0x00000062 # macro +SQ_GLOBAL_ATOMIC_SUB_X2 = 0x00000063 # macro +SQ_GLOBAL_ATOMIC_SMIN_X2 = 0x00000064 # macro +SQ_GLOBAL_ATOMIC_UMIN_X2 = 0x00000065 # macro +SQ_GLOBAL_ATOMIC_SMAX_X2 = 0x00000066 # macro +SQ_GLOBAL_ATOMIC_UMAX_X2 = 0x00000067 # macro +SQ_GLOBAL_ATOMIC_AND_X2 = 0x00000068 # macro +SQ_GLOBAL_ATOMIC_OR_X2 = 0x00000069 # macro +SQ_GLOBAL_ATOMIC_XOR_X2 = 0x0000006a # macro +SQ_GLOBAL_ATOMIC_INC_X2 = 0x0000006b # macro +SQ_GLOBAL_ATOMIC_DEC_X2 = 0x0000006c # macro +SQ_VGPR0 = 0x00000000 # macro +SQ_SCRATCH_LOAD_UBYTE = 0x00000010 # macro +SQ_SCRATCH_LOAD_SBYTE = 0x00000011 # macro +SQ_SCRATCH_LOAD_USHORT = 0x00000012 # macro +SQ_SCRATCH_LOAD_SSHORT = 0x00000013 # macro +SQ_SCRATCH_LOAD_DWORD = 0x00000014 # macro +SQ_SCRATCH_LOAD_DWORDX2 = 0x00000015 # macro +SQ_SCRATCH_LOAD_DWORDX3 = 0x00000016 # macro +SQ_SCRATCH_LOAD_DWORDX4 = 0x00000017 # macro +SQ_SCRATCH_STORE_BYTE = 0x00000018 # macro +SQ_SCRATCH_STORE_SHORT = 0x0000001a # macro +SQ_SCRATCH_STORE_DWORD = 0x0000001c # macro +SQ_SCRATCH_STORE_DWORDX2 = 0x0000001d # macro +SQ_SCRATCH_STORE_DWORDX3 = 0x0000001e # macro +SQ_SCRATCH_STORE_DWORDX4 = 0x0000001f # macro +SQ_VCC_ALL = 0x00000000 # macro +SQ_SRC_0 = 0x00000080 # macro +SQ_SRC_1_INT = 0x00000081 # macro +SQ_SRC_2_INT = 0x00000082 # macro +SQ_SRC_3_INT = 0x00000083 # macro +SQ_SRC_4_INT = 0x00000084 # macro +SQ_SRC_5_INT = 0x00000085 # macro +SQ_SRC_6_INT = 0x00000086 # macro +SQ_SRC_7_INT = 0x00000087 # macro +SQ_SRC_8_INT = 0x00000088 # macro +SQ_SRC_9_INT = 0x00000089 # macro +SQ_SRC_10_INT = 0x0000008a # macro +SQ_SRC_11_INT = 0x0000008b # macro +SQ_SRC_12_INT = 0x0000008c # macro +SQ_SRC_13_INT = 0x0000008d # macro +SQ_SRC_14_INT = 0x0000008e # macro +SQ_SRC_15_INT = 0x0000008f # macro +SQ_SRC_16_INT = 0x00000090 # macro +SQ_SRC_17_INT = 0x00000091 # macro +SQ_SRC_18_INT = 0x00000092 # macro +SQ_SRC_19_INT = 0x00000093 # macro +SQ_SRC_20_INT = 0x00000094 # macro +SQ_SRC_21_INT = 0x00000095 # macro +SQ_SRC_22_INT = 0x00000096 # macro +SQ_SRC_23_INT = 0x00000097 # macro +SQ_SRC_24_INT = 0x00000098 # macro +SQ_SRC_25_INT = 0x00000099 # macro +SQ_SRC_26_INT = 0x0000009a # macro +SQ_SRC_27_INT = 0x0000009b # macro +SQ_SRC_28_INT = 0x0000009c # macro +SQ_SRC_29_INT = 0x0000009d # macro +SQ_SRC_30_INT = 0x0000009e # macro +SQ_SRC_31_INT = 0x0000009f # macro +SQ_SRC_32_INT = 0x000000a0 # macro +SQ_SRC_33_INT = 0x000000a1 # macro +SQ_SRC_34_INT = 0x000000a2 # macro +SQ_SRC_35_INT = 0x000000a3 # macro +SQ_SRC_36_INT = 0x000000a4 # macro +SQ_SRC_37_INT = 0x000000a5 # macro +SQ_SRC_38_INT = 0x000000a6 # macro +SQ_SRC_39_INT = 0x000000a7 # macro +SQ_SRC_40_INT = 0x000000a8 # macro +SQ_SRC_41_INT = 0x000000a9 # macro +SQ_SRC_42_INT = 0x000000aa # macro +SQ_SRC_43_INT = 0x000000ab # macro +SQ_SRC_44_INT = 0x000000ac # macro +SQ_SRC_45_INT = 0x000000ad # macro +SQ_SRC_46_INT = 0x000000ae # macro +SQ_SRC_47_INT = 0x000000af # macro +SQ_SRC_48_INT = 0x000000b0 # macro +SQ_SRC_49_INT = 0x000000b1 # macro +SQ_SRC_50_INT = 0x000000b2 # macro +SQ_SRC_51_INT = 0x000000b3 # macro +SQ_SRC_52_INT = 0x000000b4 # macro +SQ_SRC_53_INT = 0x000000b5 # macro +SQ_SRC_54_INT = 0x000000b6 # macro +SQ_SRC_55_INT = 0x000000b7 # macro +SQ_SRC_56_INT = 0x000000b8 # macro +SQ_SRC_57_INT = 0x000000b9 # macro +SQ_SRC_58_INT = 0x000000ba # macro +SQ_SRC_59_INT = 0x000000bb # macro +SQ_SRC_60_INT = 0x000000bc # macro +SQ_SRC_61_INT = 0x000000bd # macro +SQ_SRC_62_INT = 0x000000be # macro +SQ_SRC_63_INT = 0x000000bf # macro +SQ_IMAGE_LOAD = 0x00000000 # macro +SQ_IMAGE_LOAD_MIP = 0x00000001 # macro +SQ_IMAGE_LOAD_PCK = 0x00000002 # macro +SQ_IMAGE_LOAD_PCK_SGN = 0x00000003 # macro +SQ_IMAGE_LOAD_MIP_PCK = 0x00000004 # macro +SQ_IMAGE_LOAD_MIP_PCK_SGN = 0x00000005 # macro +SQ_IMAGE_STORE = 0x00000008 # macro +SQ_IMAGE_STORE_MIP = 0x00000009 # macro +SQ_IMAGE_STORE_PCK = 0x0000000a # macro +SQ_IMAGE_STORE_MIP_PCK = 0x0000000b # macro +SQ_IMAGE_GET_RESINFO = 0x0000000e # macro +SQ_IMAGE_ATOMIC_SWAP = 0x00000010 # macro +SQ_IMAGE_ATOMIC_CMPSWAP = 0x00000011 # macro +SQ_IMAGE_ATOMIC_ADD = 0x00000012 # macro +SQ_IMAGE_ATOMIC_SUB = 0x00000013 # macro +SQ_IMAGE_ATOMIC_SMIN = 0x00000014 # macro +SQ_IMAGE_ATOMIC_UMIN = 0x00000015 # macro +SQ_IMAGE_ATOMIC_SMAX = 0x00000016 # macro +SQ_IMAGE_ATOMIC_UMAX = 0x00000017 # macro +SQ_IMAGE_ATOMIC_AND = 0x00000018 # macro +SQ_IMAGE_ATOMIC_OR = 0x00000019 # macro +SQ_IMAGE_ATOMIC_XOR = 0x0000001a # macro +SQ_IMAGE_ATOMIC_INC = 0x0000001b # macro +SQ_IMAGE_ATOMIC_DEC = 0x0000001c # macro +SQ_IMAGE_SAMPLE = 0x00000020 # macro +SQ_IMAGE_SAMPLE_CL = 0x00000021 # macro +SQ_IMAGE_SAMPLE_D = 0x00000022 # macro +SQ_IMAGE_SAMPLE_D_CL = 0x00000023 # macro +SQ_IMAGE_SAMPLE_L = 0x00000024 # macro +SQ_IMAGE_SAMPLE_B = 0x00000025 # macro +SQ_IMAGE_SAMPLE_B_CL = 0x00000026 # macro +SQ_IMAGE_SAMPLE_LZ = 0x00000027 # macro +SQ_IMAGE_SAMPLE_C = 0x00000028 # macro +SQ_IMAGE_SAMPLE_C_CL = 0x00000029 # macro +SQ_IMAGE_SAMPLE_C_D = 0x0000002a # macro +SQ_IMAGE_SAMPLE_C_D_CL = 0x0000002b # macro +SQ_IMAGE_SAMPLE_C_L = 0x0000002c # macro +SQ_IMAGE_SAMPLE_C_B = 0x0000002d # macro +SQ_IMAGE_SAMPLE_C_B_CL = 0x0000002e # macro +SQ_IMAGE_SAMPLE_C_LZ = 0x0000002f # macro +SQ_IMAGE_SAMPLE_O = 0x00000030 # macro +SQ_IMAGE_SAMPLE_CL_O = 0x00000031 # macro +SQ_IMAGE_SAMPLE_D_O = 0x00000032 # macro +SQ_IMAGE_SAMPLE_D_CL_O = 0x00000033 # macro +SQ_IMAGE_SAMPLE_L_O = 0x00000034 # macro +SQ_IMAGE_SAMPLE_B_O = 0x00000035 # macro +SQ_IMAGE_SAMPLE_B_CL_O = 0x00000036 # macro +SQ_IMAGE_SAMPLE_LZ_O = 0x00000037 # macro +SQ_IMAGE_SAMPLE_C_O = 0x00000038 # macro +SQ_IMAGE_SAMPLE_C_CL_O = 0x00000039 # macro +SQ_IMAGE_SAMPLE_C_D_O = 0x0000003a # macro +SQ_IMAGE_SAMPLE_C_D_CL_O = 0x0000003b # macro +SQ_IMAGE_SAMPLE_C_L_O = 0x0000003c # macro +SQ_IMAGE_SAMPLE_C_B_O = 0x0000003d # macro +SQ_IMAGE_SAMPLE_C_B_CL_O = 0x0000003e # macro +SQ_IMAGE_SAMPLE_C_LZ_O = 0x0000003f # macro +SQ_IMAGE_GATHER4 = 0x00000040 # macro +SQ_IMAGE_GATHER4_CL = 0x00000041 # macro +SQ_IMAGE_GATHER4H = 0x00000042 # macro +SQ_IMAGE_GATHER4_L = 0x00000044 # macro +SQ_IMAGE_GATHER4_B = 0x00000045 # macro +SQ_IMAGE_GATHER4_B_CL = 0x00000046 # macro +SQ_IMAGE_GATHER4_LZ = 0x00000047 # macro +SQ_IMAGE_GATHER4_C = 0x00000048 # macro +SQ_IMAGE_GATHER4_C_CL = 0x00000049 # macro +SQ_IMAGE_GATHER4H_PCK = 0x0000004a # macro +SQ_IMAGE_GATHER8H_PCK = 0x0000004b # macro +SQ_IMAGE_GATHER4_C_L = 0x0000004c # macro +SQ_IMAGE_GATHER4_C_B = 0x0000004d # macro +SQ_IMAGE_GATHER4_C_B_CL = 0x0000004e # macro +SQ_IMAGE_GATHER4_C_LZ = 0x0000004f # macro +SQ_IMAGE_GATHER4_O = 0x00000050 # macro +SQ_IMAGE_GATHER4_CL_O = 0x00000051 # macro +SQ_IMAGE_GATHER4_L_O = 0x00000054 # macro +SQ_IMAGE_GATHER4_B_O = 0x00000055 # macro +SQ_IMAGE_GATHER4_B_CL_O = 0x00000056 # macro +SQ_IMAGE_GATHER4_LZ_O = 0x00000057 # macro +SQ_IMAGE_GATHER4_C_O = 0x00000058 # macro +SQ_IMAGE_GATHER4_C_CL_O = 0x00000059 # macro +SQ_IMAGE_GATHER4_C_L_O = 0x0000005c # macro +SQ_IMAGE_GATHER4_C_B_O = 0x0000005d # macro +SQ_IMAGE_GATHER4_C_B_CL_O = 0x0000005e # macro +SQ_IMAGE_GATHER4_C_LZ_O = 0x0000005f # macro +SQ_IMAGE_GET_LOD = 0x00000060 # macro +SQ_IMAGE_SAMPLE_CD = 0x00000068 # macro +SQ_IMAGE_SAMPLE_CD_CL = 0x00000069 # macro +SQ_IMAGE_SAMPLE_C_CD = 0x0000006a # macro +SQ_IMAGE_SAMPLE_C_CD_CL = 0x0000006b # macro +SQ_IMAGE_SAMPLE_CD_O = 0x0000006c # macro +SQ_IMAGE_SAMPLE_CD_CL_O = 0x0000006d # macro +SQ_IMAGE_SAMPLE_C_CD_O = 0x0000006e # macro +SQ_IMAGE_SAMPLE_C_CD_CL_O = 0x0000006f # macro +SQ_IMAGE_RSRC256 = 0x0000007e # macro +SQ_IMAGE_SAMPLER = 0x0000007f # macro +SQ_HW_REG_MODE = 0x00000001 # macro +SQ_HW_REG_STATUS = 0x00000002 # macro +SQ_HW_REG_TRAPSTS = 0x00000003 # macro +SQ_HW_REG_HW_ID = 0x00000004 # macro +SQ_HW_REG_GPR_ALLOC = 0x00000005 # macro +SQ_HW_REG_LDS_ALLOC = 0x00000006 # macro +SQ_HW_REG_IB_STS = 0x00000007 # macro +SQ_HW_REG_PC_LO = 0x00000008 # macro +SQ_HW_REG_PC_HI = 0x00000009 # macro +SQ_HW_REG_INST_DW0 = 0x0000000a # macro +SQ_HW_REG_INST_DW1 = 0x0000000b # macro +SQ_HW_REG_IB_DBG0 = 0x0000000c # macro +SQ_HW_REG_IB_DBG1 = 0x0000000d # macro +SQ_HW_REG_FLUSH_IB = 0x0000000e # macro +SQ_HW_REG_SH_MEM_BASES = 0x0000000f # macro +SQ_HW_REG_SQ_SHADER_TBA_LO = 0x00000010 # macro +SQ_HW_REG_SQ_SHADER_TBA_HI = 0x00000011 # macro +SQ_HW_REG_SQ_SHADER_TMA_LO = 0x00000012 # macro +SQ_HW_REG_SQ_SHADER_TMA_HI = 0x00000013 # macro +SQ_S_MOV_B32 = 0x00000000 # macro +SQ_S_MOV_B64 = 0x00000001 # macro +SQ_S_CMOV_B32 = 0x00000002 # macro +SQ_S_CMOV_B64 = 0x00000003 # macro +SQ_S_NOT_B32 = 0x00000004 # macro +SQ_S_NOT_B64 = 0x00000005 # macro +SQ_S_WQM_B32 = 0x00000006 # macro +SQ_S_WQM_B64 = 0x00000007 # macro +SQ_S_BREV_B32 = 0x00000008 # macro +SQ_S_BREV_B64 = 0x00000009 # macro +SQ_S_BCNT0_I32_B32 = 0x0000000a # macro +SQ_S_BCNT0_I32_B64 = 0x0000000b # macro +SQ_S_BCNT1_I32_B32 = 0x0000000c # macro +SQ_S_BCNT1_I32_B64 = 0x0000000d # macro +SQ_S_FF0_I32_B32 = 0x0000000e # macro +SQ_S_FF0_I32_B64 = 0x0000000f # macro +SQ_S_FF1_I32_B32 = 0x00000010 # macro +SQ_S_FF1_I32_B64 = 0x00000011 # macro +SQ_S_FLBIT_I32_B32 = 0x00000012 # macro +SQ_S_FLBIT_I32_B64 = 0x00000013 # macro +SQ_S_FLBIT_I32 = 0x00000014 # macro +SQ_S_FLBIT_I32_I64 = 0x00000015 # macro +SQ_S_SEXT_I32_I8 = 0x00000016 # macro +SQ_S_SEXT_I32_I16 = 0x00000017 # macro +SQ_S_BITSET0_B32 = 0x00000018 # macro +SQ_S_BITSET0_B64 = 0x00000019 # macro +SQ_S_BITSET1_B32 = 0x0000001a # macro +SQ_S_BITSET1_B64 = 0x0000001b # macro +SQ_S_GETPC_B64 = 0x0000001c # macro +SQ_S_SETPC_B64 = 0x0000001d # macro +SQ_S_SWAPPC_B64 = 0x0000001e # macro +SQ_S_RFE_B64 = 0x0000001f # macro +SQ_S_AND_SAVEEXEC_B64 = 0x00000020 # macro +SQ_S_OR_SAVEEXEC_B64 = 0x00000021 # macro +SQ_S_XOR_SAVEEXEC_B64 = 0x00000022 # macro +SQ_S_ANDN2_SAVEEXEC_B64 = 0x00000023 # macro +SQ_S_ORN2_SAVEEXEC_B64 = 0x00000024 # macro +SQ_S_NAND_SAVEEXEC_B64 = 0x00000025 # macro +SQ_S_NOR_SAVEEXEC_B64 = 0x00000026 # macro +SQ_S_XNOR_SAVEEXEC_B64 = 0x00000027 # macro +SQ_S_QUADMASK_B32 = 0x00000028 # macro +SQ_S_QUADMASK_B64 = 0x00000029 # macro +SQ_S_MOVRELS_B32 = 0x0000002a # macro +SQ_S_MOVRELS_B64 = 0x0000002b # macro +SQ_S_MOVRELD_B32 = 0x0000002c # macro +SQ_S_MOVRELD_B64 = 0x0000002d # macro +SQ_S_CBRANCH_JOIN = 0x0000002e # macro +SQ_S_MOV_REGRD_B32 = 0x0000002f # macro +SQ_S_ABS_I32 = 0x00000030 # macro +SQ_S_MOV_FED_B32 = 0x00000031 # macro +SQ_S_SET_GPR_IDX_IDX = 0x00000032 # macro +SQ_S_ANDN1_SAVEEXEC_B64 = 0x00000033 # macro +SQ_S_ORN1_SAVEEXEC_B64 = 0x00000034 # macro +SQ_S_ANDN1_WREXEC_B64 = 0x00000035 # macro +SQ_S_ANDN2_WREXEC_B64 = 0x00000036 # macro +SQ_S_BITREPLICATE_B64_B32 = 0x00000037 # macro +SQ_CNT1 = 0x00000000 # macro +SQ_CNT2 = 0x00000001 # macro +SQ_CNT3 = 0x00000002 # macro +SQ_CNT4 = 0x00000003 # macro +SQ_V_MAD_LEGACY_F32 = 0x000001c0 # macro +SQ_V_MAD_F32 = 0x000001c1 # macro +SQ_V_MAD_I32_I24 = 0x000001c2 # macro +SQ_V_MAD_U32_U24 = 0x000001c3 # macro +SQ_V_CUBEID_F32 = 0x000001c4 # macro +SQ_V_CUBESC_F32 = 0x000001c5 # macro +SQ_V_CUBETC_F32 = 0x000001c6 # macro +SQ_V_CUBEMA_F32 = 0x000001c7 # macro +SQ_V_BFE_U32 = 0x000001c8 # macro +SQ_V_BFE_I32 = 0x000001c9 # macro +SQ_V_BFI_B32 = 0x000001ca # macro +SQ_V_FMA_F32 = 0x000001cb # macro +SQ_V_FMA_F64 = 0x000001cc # macro +SQ_V_LERP_U8 = 0x000001cd # macro +SQ_V_ALIGNBIT_B32 = 0x000001ce # macro +SQ_V_ALIGNBYTE_B32 = 0x000001cf # macro +SQ_V_MIN3_F32 = 0x000001d0 # macro +SQ_V_MIN3_I32 = 0x000001d1 # macro +SQ_V_MIN3_U32 = 0x000001d2 # macro +SQ_V_MAX3_F32 = 0x000001d3 # macro +SQ_V_MAX3_I32 = 0x000001d4 # macro +SQ_V_MAX3_U32 = 0x000001d5 # macro +SQ_V_MED3_F32 = 0x000001d6 # macro +SQ_V_MED3_I32 = 0x000001d7 # macro +SQ_V_MED3_U32 = 0x000001d8 # macro +SQ_V_SAD_U8 = 0x000001d9 # macro +SQ_V_SAD_HI_U8 = 0x000001da # macro +SQ_V_SAD_U16 = 0x000001db # macro +SQ_V_SAD_U32 = 0x000001dc # macro +SQ_V_CVT_PK_U8_F32 = 0x000001dd # macro +SQ_V_DIV_FIXUP_F32 = 0x000001de # macro +SQ_V_DIV_FIXUP_F64 = 0x000001df # macro +SQ_V_DIV_SCALE_F32 = 0x000001e0 # macro +SQ_V_DIV_SCALE_F64 = 0x000001e1 # macro +SQ_V_DIV_FMAS_F32 = 0x000001e2 # macro +SQ_V_DIV_FMAS_F64 = 0x000001e3 # macro +SQ_V_MSAD_U8 = 0x000001e4 # macro +SQ_V_QSAD_PK_U16_U8 = 0x000001e5 # macro +SQ_V_MQSAD_PK_U16_U8 = 0x000001e6 # macro +SQ_V_MQSAD_U32_U8 = 0x000001e7 # macro +SQ_V_MAD_U64_U32 = 0x000001e8 # macro +SQ_V_MAD_I64_I32 = 0x000001e9 # macro +SQ_V_MAD_LEGACY_F16 = 0x000001ea # macro +SQ_V_MAD_LEGACY_U16 = 0x000001eb # macro +SQ_V_MAD_LEGACY_I16 = 0x000001ec # macro +SQ_V_PERM_B32 = 0x000001ed # macro +SQ_V_FMA_LEGACY_F16 = 0x000001ee # macro +SQ_V_DIV_FIXUP_LEGACY_F16 = 0x000001ef # macro +SQ_V_CVT_PKACCUM_U8_F32 = 0x000001f0 # macro +SQ_V_MAD_U32_U16 = 0x000001f1 # macro +SQ_V_MAD_I32_I16 = 0x000001f2 # macro +SQ_V_XAD_U32 = 0x000001f3 # macro +SQ_V_MIN3_F16 = 0x000001f4 # macro +SQ_V_MIN3_I16 = 0x000001f5 # macro +SQ_V_MIN3_U16 = 0x000001f6 # macro +SQ_V_MAX3_F16 = 0x000001f7 # macro +SQ_V_MAX3_I16 = 0x000001f8 # macro +SQ_V_MAX3_U16 = 0x000001f9 # macro +SQ_V_MED3_F16 = 0x000001fa # macro +SQ_V_MED3_I16 = 0x000001fb # macro +SQ_V_MED3_U16 = 0x000001fc # macro +SQ_V_LSHL_ADD_U32 = 0x000001fd # macro +SQ_V_ADD_LSHL_U32 = 0x000001fe # macro +SQ_V_ADD3_U32 = 0x000001ff # macro +SQ_V_LSHL_OR_B32 = 0x00000200 # macro +SQ_V_AND_OR_B32 = 0x00000201 # macro +SQ_V_OR3_B32 = 0x00000202 # macro +SQ_V_MAD_F16 = 0x00000203 # macro +SQ_V_MAD_U16 = 0x00000204 # macro +SQ_V_MAD_I16 = 0x00000205 # macro +SQ_V_FMA_F16 = 0x00000206 # macro +SQ_V_DIV_FIXUP_F16 = 0x00000207 # macro +SQ_V_INTERP_P1LL_F16 = 0x00000274 # macro +SQ_V_INTERP_P1LV_F16 = 0x00000275 # macro +SQ_V_INTERP_P2_LEGACY_F16 = 0x00000276 # macro +SQ_V_INTERP_P2_F16 = 0x00000277 # macro +SQ_V_ADD_F64 = 0x00000280 # macro +SQ_V_MUL_F64 = 0x00000281 # macro +SQ_V_MIN_F64 = 0x00000282 # macro +SQ_V_MAX_F64 = 0x00000283 # macro +SQ_V_LDEXP_F64 = 0x00000284 # macro +SQ_V_MUL_LO_U32 = 0x00000285 # macro +SQ_V_MUL_HI_U32 = 0x00000286 # macro +SQ_V_MUL_HI_I32 = 0x00000287 # macro +SQ_V_LDEXP_F32 = 0x00000288 # macro +SQ_V_READLANE_B32 = 0x00000289 # macro +SQ_V_WRITELANE_B32 = 0x0000028a # macro +SQ_V_BCNT_U32_B32 = 0x0000028b # macro +SQ_V_MBCNT_LO_U32_B32 = 0x0000028c # macro +SQ_V_MBCNT_HI_U32_B32 = 0x0000028d # macro +SQ_V_MAC_LEGACY_F32 = 0x0000028e # macro +SQ_V_LSHLREV_B64 = 0x0000028f # macro +SQ_V_LSHRREV_B64 = 0x00000290 # macro +SQ_V_ASHRREV_I64 = 0x00000291 # macro +SQ_V_TRIG_PREOP_F64 = 0x00000292 # macro +SQ_V_BFM_B32 = 0x00000293 # macro +SQ_V_CVT_PKNORM_I16_F32 = 0x00000294 # macro +SQ_V_CVT_PKNORM_U16_F32 = 0x00000295 # macro +SQ_V_CVT_PKRTZ_F16_F32 = 0x00000296 # macro +SQ_V_CVT_PK_U16_U32 = 0x00000297 # macro +SQ_V_CVT_PK_I16_I32 = 0x00000298 # macro +SQ_V_CVT_PKNORM_I16_F16 = 0x00000299 # macro +SQ_V_CVT_PKNORM_U16_F16 = 0x0000029a # macro +SQ_V_READLANE_REGRD_B32 = 0x0000029b # macro +SQ_V_ADD_I32 = 0x0000029c # macro +SQ_V_SUB_I32 = 0x0000029d # macro +SQ_V_ADD_I16 = 0x0000029e # macro +SQ_V_SUB_I16 = 0x0000029f # macro +SQ_V_PACK_B32_F16 = 0x000002a0 # macro +SQ_SRC_LITERAL = 0x000000ff # macro +SQ_DPP_QUAD_PERM = 0x00000000 # macro +SQ_DPP_ROW_SL1 = 0x00000101 # macro +SQ_DPP_ROW_SL2 = 0x00000102 # macro +SQ_DPP_ROW_SL3 = 0x00000103 # macro +SQ_DPP_ROW_SL4 = 0x00000104 # macro +SQ_DPP_ROW_SL5 = 0x00000105 # macro +SQ_DPP_ROW_SL6 = 0x00000106 # macro +SQ_DPP_ROW_SL7 = 0x00000107 # macro +SQ_DPP_ROW_SL8 = 0x00000108 # macro +SQ_DPP_ROW_SL9 = 0x00000109 # macro +SQ_DPP_ROW_SL10 = 0x0000010a # macro +SQ_DPP_ROW_SL11 = 0x0000010b # macro +SQ_DPP_ROW_SL12 = 0x0000010c # macro +SQ_DPP_ROW_SL13 = 0x0000010d # macro +SQ_DPP_ROW_SL14 = 0x0000010e # macro +SQ_DPP_ROW_SL15 = 0x0000010f # macro +SQ_DPP_ROW_SR1 = 0x00000111 # macro +SQ_DPP_ROW_SR2 = 0x00000112 # macro +SQ_DPP_ROW_SR3 = 0x00000113 # macro +SQ_DPP_ROW_SR4 = 0x00000114 # macro +SQ_DPP_ROW_SR5 = 0x00000115 # macro +SQ_DPP_ROW_SR6 = 0x00000116 # macro +SQ_DPP_ROW_SR7 = 0x00000117 # macro +SQ_DPP_ROW_SR8 = 0x00000118 # macro +SQ_DPP_ROW_SR9 = 0x00000119 # macro +SQ_DPP_ROW_SR10 = 0x0000011a # macro +SQ_DPP_ROW_SR11 = 0x0000011b # macro +SQ_DPP_ROW_SR12 = 0x0000011c # macro +SQ_DPP_ROW_SR13 = 0x0000011d # macro +SQ_DPP_ROW_SR14 = 0x0000011e # macro +SQ_DPP_ROW_SR15 = 0x0000011f # macro +SQ_DPP_ROW_RR1 = 0x00000121 # macro +SQ_DPP_ROW_RR2 = 0x00000122 # macro +SQ_DPP_ROW_RR3 = 0x00000123 # macro +SQ_DPP_ROW_RR4 = 0x00000124 # macro +SQ_DPP_ROW_RR5 = 0x00000125 # macro +SQ_DPP_ROW_RR6 = 0x00000126 # macro +SQ_DPP_ROW_RR7 = 0x00000127 # macro +SQ_DPP_ROW_RR8 = 0x00000128 # macro +SQ_DPP_ROW_RR9 = 0x00000129 # macro +SQ_DPP_ROW_RR10 = 0x0000012a # macro +SQ_DPP_ROW_RR11 = 0x0000012b # macro +SQ_DPP_ROW_RR12 = 0x0000012c # macro +SQ_DPP_ROW_RR13 = 0x0000012d # macro +SQ_DPP_ROW_RR14 = 0x0000012e # macro +SQ_DPP_ROW_RR15 = 0x0000012f # macro +SQ_DPP_WF_SL1 = 0x00000130 # macro +SQ_DPP_WF_RL1 = 0x00000134 # macro +SQ_DPP_WF_SR1 = 0x00000138 # macro +SQ_DPP_WF_RR1 = 0x0000013c # macro +SQ_DPP_ROW_MIRROR = 0x00000140 # macro +SQ_DPP_ROW_HALF_MIRROR = 0x00000141 # macro +SQ_DPP_ROW_BCAST15 = 0x00000142 # macro +SQ_DPP_ROW_BCAST31 = 0x00000143 # macro +SQ_FLAT_SCRATCH_LO = 0x00000066 # macro +SQ_FLAT_SCRATCH_HI = 0x00000067 # macro +SQ_V_NOP = 0x00000000 # macro +SQ_V_MOV_B32 = 0x00000001 # macro +SQ_V_READFIRSTLANE_B32 = 0x00000002 # macro +SQ_V_CVT_I32_F64 = 0x00000003 # macro +SQ_V_CVT_F64_I32 = 0x00000004 # macro +SQ_V_CVT_F32_I32 = 0x00000005 # macro +SQ_V_CVT_F32_U32 = 0x00000006 # macro +SQ_V_CVT_U32_F32 = 0x00000007 # macro +SQ_V_CVT_I32_F32 = 0x00000008 # macro +SQ_V_MOV_FED_B32 = 0x00000009 # macro +SQ_V_CVT_F16_F32 = 0x0000000a # macro +SQ_V_CVT_F32_F16 = 0x0000000b # macro +SQ_V_CVT_RPI_I32_F32 = 0x0000000c # macro +SQ_V_CVT_FLR_I32_F32 = 0x0000000d # macro +SQ_V_CVT_OFF_F32_I4 = 0x0000000e # macro +SQ_V_CVT_F32_F64 = 0x0000000f # macro +SQ_V_CVT_F64_F32 = 0x00000010 # macro +SQ_V_CVT_F32_UBYTE0 = 0x00000011 # macro +SQ_V_CVT_F32_UBYTE1 = 0x00000012 # macro +SQ_V_CVT_F32_UBYTE2 = 0x00000013 # macro +SQ_V_CVT_F32_UBYTE3 = 0x00000014 # macro +SQ_V_CVT_U32_F64 = 0x00000015 # macro +SQ_V_CVT_F64_U32 = 0x00000016 # macro +SQ_V_TRUNC_F64 = 0x00000017 # macro +SQ_V_CEIL_F64 = 0x00000018 # macro +SQ_V_RNDNE_F64 = 0x00000019 # macro +SQ_V_FLOOR_F64 = 0x0000001a # macro +SQ_V_FRACT_F32 = 0x0000001b # macro +SQ_V_TRUNC_F32 = 0x0000001c # macro +SQ_V_CEIL_F32 = 0x0000001d # macro +SQ_V_RNDNE_F32 = 0x0000001e # macro +SQ_V_FLOOR_F32 = 0x0000001f # macro +SQ_V_EXP_F32 = 0x00000020 # macro +SQ_V_LOG_F32 = 0x00000021 # macro +SQ_V_RCP_F32 = 0x00000022 # macro +SQ_V_RCP_IFLAG_F32 = 0x00000023 # macro +SQ_V_RSQ_F32 = 0x00000024 # macro +SQ_V_RCP_F64 = 0x00000025 # macro +SQ_V_RSQ_F64 = 0x00000026 # macro +SQ_V_SQRT_F32 = 0x00000027 # macro +SQ_V_SQRT_F64 = 0x00000028 # macro +SQ_V_SIN_F32 = 0x00000029 # macro +SQ_V_COS_F32 = 0x0000002a # macro +SQ_V_NOT_B32 = 0x0000002b # macro +SQ_V_BFREV_B32 = 0x0000002c # macro +SQ_V_FFBH_U32 = 0x0000002d # macro +SQ_V_FFBL_B32 = 0x0000002e # macro +SQ_V_FFBH_I32 = 0x0000002f # macro +SQ_V_FREXP_EXP_I32_F64 = 0x00000030 # macro +SQ_V_FREXP_MANT_F64 = 0x00000031 # macro +SQ_V_FRACT_F64 = 0x00000032 # macro +SQ_V_FREXP_EXP_I32_F32 = 0x00000033 # macro +SQ_V_FREXP_MANT_F32 = 0x00000034 # macro +SQ_V_CLREXCP = 0x00000035 # macro +SQ_V_MOV_PRSV_B32 = 0x00000036 # macro +SQ_V_CVT_F16_U16 = 0x00000039 # macro +SQ_V_CVT_F16_I16 = 0x0000003a # macro +SQ_V_CVT_U16_F16 = 0x0000003b # macro +SQ_V_CVT_I16_F16 = 0x0000003c # macro +SQ_V_RCP_F16 = 0x0000003d # macro +SQ_V_SQRT_F16 = 0x0000003e # macro +SQ_V_RSQ_F16 = 0x0000003f # macro +SQ_V_LOG_F16 = 0x00000040 # macro +SQ_V_EXP_F16 = 0x00000041 # macro +SQ_V_FREXP_MANT_F16 = 0x00000042 # macro +SQ_V_FREXP_EXP_I16_F16 = 0x00000043 # macro +SQ_V_FLOOR_F16 = 0x00000044 # macro +SQ_V_CEIL_F16 = 0x00000045 # macro +SQ_V_TRUNC_F16 = 0x00000046 # macro +SQ_V_RNDNE_F16 = 0x00000047 # macro +SQ_V_FRACT_F16 = 0x00000048 # macro +SQ_V_SIN_F16 = 0x00000049 # macro +SQ_V_COS_F16 = 0x0000004a # macro +SQ_V_EXP_LEGACY_F32 = 0x0000004b # macro +SQ_V_LOG_LEGACY_F32 = 0x0000004c # macro +SQ_V_CVT_NORM_I16_F16 = 0x0000004d # macro +SQ_V_CVT_NORM_U16_F16 = 0x0000004e # macro +SQ_V_SAT_PK_U8_I16 = 0x0000004f # macro +SQ_V_WRITELANE_IMM32 = 0x00000050 # macro +SQ_V_SWAP_B32 = 0x00000051 # macro +SQ_FLAT_LOAD_UBYTE = 0x00000010 # macro +SQ_FLAT_LOAD_SBYTE = 0x00000011 # macro +SQ_FLAT_LOAD_USHORT = 0x00000012 # macro +SQ_FLAT_LOAD_SSHORT = 0x00000013 # macro +SQ_FLAT_LOAD_DWORD = 0x00000014 # macro +SQ_FLAT_LOAD_DWORDX2 = 0x00000015 # macro +SQ_FLAT_LOAD_DWORDX3 = 0x00000016 # macro +SQ_FLAT_LOAD_DWORDX4 = 0x00000017 # macro +SQ_FLAT_STORE_BYTE = 0x00000018 # macro +SQ_FLAT_STORE_SHORT = 0x0000001a # macro +SQ_FLAT_STORE_DWORD = 0x0000001c # macro +SQ_FLAT_STORE_DWORDX2 = 0x0000001d # macro +SQ_FLAT_STORE_DWORDX3 = 0x0000001e # macro +SQ_FLAT_STORE_DWORDX4 = 0x0000001f # macro +SQ_FLAT_ATOMIC_SWAP = 0x00000040 # macro +SQ_FLAT_ATOMIC_CMPSWAP = 0x00000041 # macro +SQ_FLAT_ATOMIC_ADD = 0x00000042 # macro +SQ_FLAT_ATOMIC_SUB = 0x00000043 # macro +SQ_FLAT_ATOMIC_SMIN = 0x00000044 # macro +SQ_FLAT_ATOMIC_UMIN = 0x00000045 # macro +SQ_FLAT_ATOMIC_SMAX = 0x00000046 # macro +SQ_FLAT_ATOMIC_UMAX = 0x00000047 # macro +SQ_FLAT_ATOMIC_AND = 0x00000048 # macro +SQ_FLAT_ATOMIC_OR = 0x00000049 # macro +SQ_FLAT_ATOMIC_XOR = 0x0000004a # macro +SQ_FLAT_ATOMIC_INC = 0x0000004b # macro +SQ_FLAT_ATOMIC_DEC = 0x0000004c # macro +SQ_FLAT_ATOMIC_SWAP_X2 = 0x00000060 # macro +SQ_FLAT_ATOMIC_CMPSWAP_X2 = 0x00000061 # macro +SQ_FLAT_ATOMIC_ADD_X2 = 0x00000062 # macro +SQ_FLAT_ATOMIC_SUB_X2 = 0x00000063 # macro +SQ_FLAT_ATOMIC_SMIN_X2 = 0x00000064 # macro +SQ_FLAT_ATOMIC_UMIN_X2 = 0x00000065 # macro +SQ_FLAT_ATOMIC_SMAX_X2 = 0x00000066 # macro +SQ_FLAT_ATOMIC_UMAX_X2 = 0x00000067 # macro +SQ_FLAT_ATOMIC_AND_X2 = 0x00000068 # macro +SQ_FLAT_ATOMIC_OR_X2 = 0x00000069 # macro +SQ_FLAT_ATOMIC_XOR_X2 = 0x0000006a # macro +SQ_FLAT_ATOMIC_INC_X2 = 0x0000006b # macro +SQ_FLAT_ATOMIC_DEC_X2 = 0x0000006c # macro +SQ_DS_ADD_U32 = 0x00000000 # macro +SQ_DS_SUB_U32 = 0x00000001 # macro +SQ_DS_RSUB_U32 = 0x00000002 # macro +SQ_DS_INC_U32 = 0x00000003 # macro +SQ_DS_DEC_U32 = 0x00000004 # macro +SQ_DS_MIN_I32 = 0x00000005 # macro +SQ_DS_MAX_I32 = 0x00000006 # macro +SQ_DS_MIN_U32 = 0x00000007 # macro +SQ_DS_MAX_U32 = 0x00000008 # macro +SQ_DS_AND_B32 = 0x00000009 # macro +SQ_DS_OR_B32 = 0x0000000a # macro +SQ_DS_XOR_B32 = 0x0000000b # macro +SQ_DS_MSKOR_B32 = 0x0000000c # macro +SQ_DS_WRITE_B32 = 0x0000000d # macro +SQ_DS_WRITE2_B32 = 0x0000000e # macro +SQ_DS_WRITE2ST64_B32 = 0x0000000f # macro +SQ_DS_CMPST_B32 = 0x00000010 # macro +SQ_DS_CMPST_F32 = 0x00000011 # macro +SQ_DS_MIN_F32 = 0x00000012 # macro +SQ_DS_MAX_F32 = 0x00000013 # macro +SQ_DS_NOP = 0x00000014 # macro +SQ_DS_ADD_F32 = 0x00000015 # macro +SQ_DS_WRITE_ADDTID_B32 = 0x0000001d # macro +SQ_DS_WRITE_B8 = 0x0000001e # macro +SQ_DS_WRITE_B16 = 0x0000001f # macro +SQ_DS_ADD_RTN_U32 = 0x00000020 # macro +SQ_DS_SUB_RTN_U32 = 0x00000021 # macro +SQ_DS_RSUB_RTN_U32 = 0x00000022 # macro +SQ_DS_INC_RTN_U32 = 0x00000023 # macro +SQ_DS_DEC_RTN_U32 = 0x00000024 # macro +SQ_DS_MIN_RTN_I32 = 0x00000025 # macro +SQ_DS_MAX_RTN_I32 = 0x00000026 # macro +SQ_DS_MIN_RTN_U32 = 0x00000027 # macro +SQ_DS_MAX_RTN_U32 = 0x00000028 # macro +SQ_DS_AND_RTN_B32 = 0x00000029 # macro +SQ_DS_OR_RTN_B32 = 0x0000002a # macro +SQ_DS_XOR_RTN_B32 = 0x0000002b # macro +SQ_DS_MSKOR_RTN_B32 = 0x0000002c # macro +SQ_DS_WRXCHG_RTN_B32 = 0x0000002d # macro +SQ_DS_WRXCHG2_RTN_B32 = 0x0000002e # macro +SQ_DS_WRXCHG2ST64_RTN_B32 = 0x0000002f # macro +SQ_DS_CMPST_RTN_B32 = 0x00000030 # macro +SQ_DS_CMPST_RTN_F32 = 0x00000031 # macro +SQ_DS_MIN_RTN_F32 = 0x00000032 # macro +SQ_DS_MAX_RTN_F32 = 0x00000033 # macro +SQ_DS_WRAP_RTN_B32 = 0x00000034 # macro +SQ_DS_ADD_RTN_F32 = 0x00000035 # macro +SQ_DS_READ_B32 = 0x00000036 # macro +SQ_DS_READ2_B32 = 0x00000037 # macro +SQ_DS_READ2ST64_B32 = 0x00000038 # macro +SQ_DS_READ_I8 = 0x00000039 # macro +SQ_DS_READ_U8 = 0x0000003a # macro +SQ_DS_READ_I16 = 0x0000003b # macro +SQ_DS_READ_U16 = 0x0000003c # macro +SQ_DS_SWIZZLE_B32 = 0x0000003d # macro +SQ_DS_PERMUTE_B32 = 0x0000003e # macro +SQ_DS_BPERMUTE_B32 = 0x0000003f # macro +SQ_DS_ADD_U64 = 0x00000040 # macro +SQ_DS_SUB_U64 = 0x00000041 # macro +SQ_DS_RSUB_U64 = 0x00000042 # macro +SQ_DS_INC_U64 = 0x00000043 # macro +SQ_DS_DEC_U64 = 0x00000044 # macro +SQ_DS_MIN_I64 = 0x00000045 # macro +SQ_DS_MAX_I64 = 0x00000046 # macro +SQ_DS_MIN_U64 = 0x00000047 # macro +SQ_DS_MAX_U64 = 0x00000048 # macro +SQ_DS_AND_B64 = 0x00000049 # macro +SQ_DS_OR_B64 = 0x0000004a # macro +SQ_DS_XOR_B64 = 0x0000004b # macro +SQ_DS_MSKOR_B64 = 0x0000004c # macro +SQ_DS_WRITE_B64 = 0x0000004d # macro +SQ_DS_WRITE2_B64 = 0x0000004e # macro +SQ_DS_WRITE2ST64_B64 = 0x0000004f # macro +SQ_DS_CMPST_B64 = 0x00000050 # macro +SQ_DS_CMPST_F64 = 0x00000051 # macro +SQ_DS_MIN_F64 = 0x00000052 # macro +SQ_DS_MAX_F64 = 0x00000053 # macro +SQ_DS_ADD_RTN_U64 = 0x00000060 # macro +SQ_DS_SUB_RTN_U64 = 0x00000061 # macro +SQ_DS_RSUB_RTN_U64 = 0x00000062 # macro +SQ_DS_INC_RTN_U64 = 0x00000063 # macro +SQ_DS_DEC_RTN_U64 = 0x00000064 # macro +SQ_DS_MIN_RTN_I64 = 0x00000065 # macro +SQ_DS_MAX_RTN_I64 = 0x00000066 # macro +SQ_DS_MIN_RTN_U64 = 0x00000067 # macro +SQ_DS_MAX_RTN_U64 = 0x00000068 # macro +SQ_DS_AND_RTN_B64 = 0x00000069 # macro +SQ_DS_OR_RTN_B64 = 0x0000006a # macro +SQ_DS_XOR_RTN_B64 = 0x0000006b # macro +SQ_DS_MSKOR_RTN_B64 = 0x0000006c # macro +SQ_DS_WRXCHG_RTN_B64 = 0x0000006d # macro +SQ_DS_WRXCHG2_RTN_B64 = 0x0000006e # macro +SQ_DS_WRXCHG2ST64_RTN_B64 = 0x0000006f # macro +SQ_DS_CMPST_RTN_B64 = 0x00000070 # macro +SQ_DS_CMPST_RTN_F64 = 0x00000071 # macro +SQ_DS_MIN_RTN_F64 = 0x00000072 # macro +SQ_DS_MAX_RTN_F64 = 0x00000073 # macro +SQ_DS_READ_B64 = 0x00000076 # macro +SQ_DS_READ2_B64 = 0x00000077 # macro +SQ_DS_READ2ST64_B64 = 0x00000078 # macro +SQ_DS_CONDXCHG32_RTN_B64 = 0x0000007e # macro +SQ_DS_ADD_SRC2_U32 = 0x00000080 # macro +SQ_DS_SUB_SRC2_U32 = 0x00000081 # macro +SQ_DS_RSUB_SRC2_U32 = 0x00000082 # macro +SQ_DS_INC_SRC2_U32 = 0x00000083 # macro +SQ_DS_DEC_SRC2_U32 = 0x00000084 # macro +SQ_DS_MIN_SRC2_I32 = 0x00000085 # macro +SQ_DS_MAX_SRC2_I32 = 0x00000086 # macro +SQ_DS_MIN_SRC2_U32 = 0x00000087 # macro +SQ_DS_MAX_SRC2_U32 = 0x00000088 # macro +SQ_DS_AND_SRC2_B32 = 0x00000089 # macro +SQ_DS_OR_SRC2_B32 = 0x0000008a # macro +SQ_DS_XOR_SRC2_B32 = 0x0000008b # macro +SQ_DS_WRITE_SRC2_B32 = 0x0000008d # macro +SQ_DS_MIN_SRC2_F32 = 0x00000092 # macro +SQ_DS_MAX_SRC2_F32 = 0x00000093 # macro +SQ_DS_ADD_SRC2_F32 = 0x00000095 # macro +SQ_DS_GWS_SEMA_RELEASE_ALL = 0x00000098 # macro +SQ_DS_GWS_INIT = 0x00000099 # macro +SQ_DS_GWS_SEMA_V = 0x0000009a # macro +SQ_DS_GWS_SEMA_BR = 0x0000009b # macro +SQ_DS_GWS_SEMA_P = 0x0000009c # macro +SQ_DS_GWS_BARRIER = 0x0000009d # macro +SQ_DS_READ_ADDTID_B32 = 0x000000b6 # macro +SQ_DS_CONSUME = 0x000000bd # macro +SQ_DS_APPEND = 0x000000be # macro +SQ_DS_ORDERED_COUNT = 0x000000bf # macro +SQ_DS_ADD_SRC2_U64 = 0x000000c0 # macro +SQ_DS_SUB_SRC2_U64 = 0x000000c1 # macro +SQ_DS_RSUB_SRC2_U64 = 0x000000c2 # macro +SQ_DS_INC_SRC2_U64 = 0x000000c3 # macro +SQ_DS_DEC_SRC2_U64 = 0x000000c4 # macro +SQ_DS_MIN_SRC2_I64 = 0x000000c5 # macro +SQ_DS_MAX_SRC2_I64 = 0x000000c6 # macro +SQ_DS_MIN_SRC2_U64 = 0x000000c7 # macro +SQ_DS_MAX_SRC2_U64 = 0x000000c8 # macro +SQ_DS_AND_SRC2_B64 = 0x000000c9 # macro +SQ_DS_OR_SRC2_B64 = 0x000000ca # macro +SQ_DS_XOR_SRC2_B64 = 0x000000cb # macro +SQ_DS_WRITE_SRC2_B64 = 0x000000cd # macro +SQ_DS_MIN_SRC2_F64 = 0x000000d2 # macro +SQ_DS_MAX_SRC2_F64 = 0x000000d3 # macro +SQ_DS_WRITE_B96 = 0x000000de # macro +SQ_DS_WRITE_B128 = 0x000000df # macro +SQ_DS_CONDXCHG32_RTN_B128 = 0x000000fd # macro +SQ_DS_READ_B96 = 0x000000fe # macro +SQ_DS_READ_B128 = 0x000000ff # macro +SQ_S_LOAD_DWORD = 0x00000000 # macro +SQ_S_LOAD_DWORDX2 = 0x00000001 # macro +SQ_S_LOAD_DWORDX4 = 0x00000002 # macro +SQ_S_LOAD_DWORDX8 = 0x00000003 # macro +SQ_S_LOAD_DWORDX16 = 0x00000004 # macro +SQ_S_SCRATCH_LOAD_DWORD = 0x00000005 # macro +SQ_S_SCRATCH_LOAD_DWORDX2 = 0x00000006 # macro +SQ_S_SCRATCH_LOAD_DWORDX4 = 0x00000007 # macro +SQ_S_BUFFER_LOAD_DWORD = 0x00000008 # macro +SQ_S_BUFFER_LOAD_DWORDX2 = 0x00000009 # macro +SQ_S_BUFFER_LOAD_DWORDX4 = 0x0000000a # macro +SQ_S_BUFFER_LOAD_DWORDX8 = 0x0000000b # macro +SQ_S_BUFFER_LOAD_DWORDX16 = 0x0000000c # macro +SQ_S_STORE_DWORD = 0x00000010 # macro +SQ_S_STORE_DWORDX2 = 0x00000011 # macro +SQ_S_STORE_DWORDX4 = 0x00000012 # macro +SQ_S_SCRATCH_STORE_DWORD = 0x00000015 # macro +SQ_S_SCRATCH_STORE_DWORDX2 = 0x00000016 # macro +SQ_S_SCRATCH_STORE_DWORDX4 = 0x00000017 # macro +SQ_S_BUFFER_STORE_DWORD = 0x00000018 # macro +SQ_S_BUFFER_STORE_DWORDX2 = 0x00000019 # macro +SQ_S_BUFFER_STORE_DWORDX4 = 0x0000001a # macro +SQ_S_DCACHE_INV = 0x00000020 # macro +SQ_S_DCACHE_WB = 0x00000021 # macro +SQ_S_DCACHE_INV_VOL = 0x00000022 # macro +SQ_S_DCACHE_WB_VOL = 0x00000023 # macro +SQ_S_MEMTIME = 0x00000024 # macro +SQ_S_MEMREALTIME = 0x00000025 # macro +SQ_S_ATC_PROBE = 0x00000026 # macro +SQ_S_ATC_PROBE_BUFFER = 0x00000027 # macro +SQ_S_BUFFER_ATOMIC_SWAP = 0x00000040 # macro +SQ_S_BUFFER_ATOMIC_CMPSWAP = 0x00000041 # macro +SQ_S_BUFFER_ATOMIC_ADD = 0x00000042 # macro +SQ_S_BUFFER_ATOMIC_SUB = 0x00000043 # macro +SQ_S_BUFFER_ATOMIC_SMIN = 0x00000044 # macro +SQ_S_BUFFER_ATOMIC_UMIN = 0x00000045 # macro +SQ_S_BUFFER_ATOMIC_SMAX = 0x00000046 # macro +SQ_S_BUFFER_ATOMIC_UMAX = 0x00000047 # macro +SQ_S_BUFFER_ATOMIC_AND = 0x00000048 # macro +SQ_S_BUFFER_ATOMIC_OR = 0x00000049 # macro +SQ_S_BUFFER_ATOMIC_XOR = 0x0000004a # macro +SQ_S_BUFFER_ATOMIC_INC = 0x0000004b # macro +SQ_S_BUFFER_ATOMIC_DEC = 0x0000004c # macro +SQ_S_BUFFER_ATOMIC_SWAP_X2 = 0x00000060 # macro +SQ_S_BUFFER_ATOMIC_CMPSWAP_X2 = 0x00000061 # macro +SQ_S_BUFFER_ATOMIC_ADD_X2 = 0x00000062 # macro +SQ_S_BUFFER_ATOMIC_SUB_X2 = 0x00000063 # macro +SQ_S_BUFFER_ATOMIC_SMIN_X2 = 0x00000064 # macro +SQ_S_BUFFER_ATOMIC_UMIN_X2 = 0x00000065 # macro +SQ_S_BUFFER_ATOMIC_SMAX_X2 = 0x00000066 # macro +SQ_S_BUFFER_ATOMIC_UMAX_X2 = 0x00000067 # macro +SQ_S_BUFFER_ATOMIC_AND_X2 = 0x00000068 # macro +SQ_S_BUFFER_ATOMIC_OR_X2 = 0x00000069 # macro +SQ_S_BUFFER_ATOMIC_XOR_X2 = 0x0000006a # macro +SQ_S_BUFFER_ATOMIC_INC_X2 = 0x0000006b # macro +SQ_S_BUFFER_ATOMIC_DEC_X2 = 0x0000006c # macro +SQ_S_ATOMIC_SWAP = 0x00000080 # macro +SQ_S_ATOMIC_CMPSWAP = 0x00000081 # macro +SQ_S_ATOMIC_ADD = 0x00000082 # macro +SQ_S_ATOMIC_SUB = 0x00000083 # macro +SQ_S_ATOMIC_SMIN = 0x00000084 # macro +SQ_S_ATOMIC_UMIN = 0x00000085 # macro +SQ_S_ATOMIC_SMAX = 0x00000086 # macro +SQ_S_ATOMIC_UMAX = 0x00000087 # macro +SQ_S_ATOMIC_AND = 0x00000088 # macro +SQ_S_ATOMIC_OR = 0x00000089 # macro +SQ_S_ATOMIC_XOR = 0x0000008a # macro +SQ_S_ATOMIC_INC = 0x0000008b # macro +SQ_S_ATOMIC_DEC = 0x0000008c # macro +SQ_S_ATOMIC_SWAP_X2 = 0x000000a0 # macro +SQ_S_ATOMIC_CMPSWAP_X2 = 0x000000a1 # macro +SQ_S_ATOMIC_ADD_X2 = 0x000000a2 # macro +SQ_S_ATOMIC_SUB_X2 = 0x000000a3 # macro +SQ_S_ATOMIC_SMIN_X2 = 0x000000a4 # macro +SQ_S_ATOMIC_UMIN_X2 = 0x000000a5 # macro +SQ_S_ATOMIC_SMAX_X2 = 0x000000a6 # macro +SQ_S_ATOMIC_UMAX_X2 = 0x000000a7 # macro +SQ_S_ATOMIC_AND_X2 = 0x000000a8 # macro +SQ_S_ATOMIC_OR_X2 = 0x000000a9 # macro +SQ_S_ATOMIC_XOR_X2 = 0x000000aa # macro +SQ_S_ATOMIC_INC_X2 = 0x000000ab # macro +SQ_S_ATOMIC_DEC_X2 = 0x000000ac # macro +SQ_V_CNDMASK_B32 = 0x00000000 # macro +SQ_V_ADD_F32 = 0x00000001 # macro +SQ_V_SUB_F32 = 0x00000002 # macro +SQ_V_SUBREV_F32 = 0x00000003 # macro +SQ_V_MUL_LEGACY_F32 = 0x00000004 # macro +SQ_V_MUL_F32 = 0x00000005 # macro +SQ_V_MUL_I32_I24 = 0x00000006 # macro +SQ_V_MUL_HI_I32_I24 = 0x00000007 # macro +SQ_V_MUL_U32_U24 = 0x00000008 # macro +SQ_V_MUL_HI_U32_U24 = 0x00000009 # macro +SQ_V_MIN_F32 = 0x0000000a # macro +SQ_V_MAX_F32 = 0x0000000b # macro +SQ_V_MIN_I32 = 0x0000000c # macro +SQ_V_MAX_I32 = 0x0000000d # macro +SQ_V_MIN_U32 = 0x0000000e # macro +SQ_V_MAX_U32 = 0x0000000f # macro +SQ_V_LSHRREV_B32 = 0x00000010 # macro +SQ_V_ASHRREV_I32 = 0x00000011 # macro +SQ_V_LSHLREV_B32 = 0x00000012 # macro +SQ_V_AND_B32 = 0x00000013 # macro +SQ_V_OR_B32 = 0x00000014 # macro +SQ_V_XOR_B32 = 0x00000015 # macro +SQ_V_MAC_F32 = 0x00000016 # macro +SQ_V_MADMK_F32 = 0x00000017 # macro +SQ_V_MADAK_F32 = 0x00000018 # macro +SQ_V_ADD_CO_U32 = 0x00000019 # macro +SQ_V_SUB_CO_U32 = 0x0000001a # macro +SQ_V_SUBREV_CO_U32 = 0x0000001b # macro +SQ_V_ADDC_CO_U32 = 0x0000001c # macro +SQ_V_SUBB_CO_U32 = 0x0000001d # macro +SQ_V_SUBBREV_CO_U32 = 0x0000001e # macro +SQ_V_ADD_F16 = 0x0000001f # macro +SQ_V_SUB_F16 = 0x00000020 # macro +SQ_V_SUBREV_F16 = 0x00000021 # macro +SQ_V_MUL_F16 = 0x00000022 # macro +SQ_V_MAC_F16 = 0x00000023 # macro +SQ_V_MADMK_F16 = 0x00000024 # macro +SQ_V_MADAK_F16 = 0x00000025 # macro +SQ_V_ADD_U16 = 0x00000026 # macro +SQ_V_SUB_U16 = 0x00000027 # macro +SQ_V_SUBREV_U16 = 0x00000028 # macro +SQ_V_MUL_LO_U16 = 0x00000029 # macro +SQ_V_LSHLREV_B16 = 0x0000002a # macro +SQ_V_LSHRREV_B16 = 0x0000002b # macro +SQ_V_ASHRREV_I16 = 0x0000002c # macro +SQ_V_MAX_F16 = 0x0000002d # macro +SQ_V_MIN_F16 = 0x0000002e # macro +SQ_V_MAX_U16 = 0x0000002f # macro +SQ_V_MAX_I16 = 0x00000030 # macro +SQ_V_MIN_U16 = 0x00000031 # macro +SQ_V_MIN_I16 = 0x00000032 # macro +SQ_V_LDEXP_F16 = 0x00000033 # macro +SQ_V_ADD_U32 = 0x00000034 # macro +SQ_V_SUB_U32 = 0x00000035 # macro +SQ_V_SUBREV_U32 = 0x00000036 # macro +SQ_SYSMSG_OP_ECC_ERR_INTERRUPT = 0x00000001 # macro +SQ_SYSMSG_OP_REG_RD = 0x00000002 # macro +SQ_SYSMSG_OP_HOST_TRAP_ACK = 0x00000003 # macro +SQ_SYSMSG_OP_TTRACE_PC = 0x00000004 # macro +SQ_SYSMSG_OP_ILLEGAL_INST_INTERRUPT = 0x00000005 # macro +SQ_SYSMSG_OP_MEMVIOL_INTERRUPT = 0x00000006 # macro +SQ_SRC_VCCZ = 0x000000fb # macro +SQ_CHAN_X = 0x00000000 # macro +SQ_CHAN_Y = 0x00000001 # macro +SQ_CHAN_Z = 0x00000002 # macro +SQ_CHAN_W = 0x00000003 # macro +SQ_S_MOVK_I32 = 0x00000000 # macro +SQ_S_CMOVK_I32 = 0x00000001 # macro +SQ_S_CMPK_EQ_I32 = 0x00000002 # macro +SQ_S_CMPK_LG_I32 = 0x00000003 # macro +SQ_S_CMPK_GT_I32 = 0x00000004 # macro +SQ_S_CMPK_GE_I32 = 0x00000005 # macro +SQ_S_CMPK_LT_I32 = 0x00000006 # macro +SQ_S_CMPK_LE_I32 = 0x00000007 # macro +SQ_S_CMPK_EQ_U32 = 0x00000008 # macro +SQ_S_CMPK_LG_U32 = 0x00000009 # macro +SQ_S_CMPK_GT_U32 = 0x0000000a # macro +SQ_S_CMPK_GE_U32 = 0x0000000b # macro +SQ_S_CMPK_LT_U32 = 0x0000000c # macro +SQ_S_CMPK_LE_U32 = 0x0000000d # macro +SQ_S_ADDK_I32 = 0x0000000e # macro +SQ_S_MULK_I32 = 0x0000000f # macro +SQ_S_CBRANCH_I_FORK = 0x00000010 # macro +SQ_S_GETREG_B32 = 0x00000011 # macro +SQ_S_SETREG_B32 = 0x00000012 # macro +SQ_S_GETREG_REGRD_B32 = 0x00000013 # macro +SQ_S_SETREG_IMM32_B32 = 0x00000014 # macro +SQ_S_CALL_B64 = 0x00000015 # macro +SQ_L1 = 0x00000001 # macro +SQ_L2 = 0x00000002 # macro +SQ_L3 = 0x00000003 # macro +SQ_L4 = 0x00000004 # macro +SQ_L5 = 0x00000005 # macro +SQ_L6 = 0x00000006 # macro +SQ_L7 = 0x00000007 # macro +SQ_L8 = 0x00000008 # macro +SQ_L9 = 0x00000009 # macro +SQ_L10 = 0x0000000a # macro +SQ_L11 = 0x0000000b # macro +SQ_L12 = 0x0000000c # macro +SQ_L13 = 0x0000000d # macro +SQ_L14 = 0x0000000e # macro +SQ_L15 = 0x0000000f # macro +SQ_SGPR0 = 0x00000000 # macro +SQ_V_PK_MAD_I16 = 0x00000000 # macro +SQ_V_PK_MUL_LO_U16 = 0x00000001 # macro +SQ_V_PK_ADD_I16 = 0x00000002 # macro +SQ_V_PK_SUB_I16 = 0x00000003 # macro +SQ_V_PK_LSHLREV_B16 = 0x00000004 # macro +SQ_V_PK_LSHRREV_B16 = 0x00000005 # macro +SQ_V_PK_ASHRREV_I16 = 0x00000006 # macro +SQ_V_PK_MAX_I16 = 0x00000007 # macro +SQ_V_PK_MIN_I16 = 0x00000008 # macro +SQ_V_PK_MAD_U16 = 0x00000009 # macro +SQ_V_PK_ADD_U16 = 0x0000000a # macro +SQ_V_PK_SUB_U16 = 0x0000000b # macro +SQ_V_PK_MAX_U16 = 0x0000000c # macro +SQ_V_PK_MIN_U16 = 0x0000000d # macro +SQ_V_PK_MAD_F16 = 0x0000000e # macro +SQ_V_PK_ADD_F16 = 0x0000000f # macro +SQ_V_PK_MUL_F16 = 0x00000010 # macro +SQ_V_PK_MIN_F16 = 0x00000011 # macro +SQ_V_PK_MAX_F16 = 0x00000012 # macro +SQ_V_MAD_MIX_F32 = 0x00000020 # macro +SQ_V_MAD_MIXLO_F16 = 0x00000021 # macro +SQ_V_MAD_MIXHI_F16 = 0x00000022 # macro +SQ_V_INTERP_P1_F32 = 0x00000000 # macro +SQ_V_INTERP_P2_F32 = 0x00000001 # macro +SQ_V_INTERP_MOV_F32 = 0x00000002 # macro +SQ_R1 = 0x00000001 # macro +SQ_R2 = 0x00000002 # macro +SQ_R3 = 0x00000003 # macro +SQ_R4 = 0x00000004 # macro +SQ_R5 = 0x00000005 # macro +SQ_R6 = 0x00000006 # macro +SQ_R7 = 0x00000007 # macro +SQ_R8 = 0x00000008 # macro +SQ_R9 = 0x00000009 # macro +SQ_R10 = 0x0000000a # macro +SQ_R11 = 0x0000000b # macro +SQ_R12 = 0x0000000c # macro +SQ_R13 = 0x0000000d # macro +SQ_R14 = 0x0000000e # macro +SQ_R15 = 0x0000000f # macro +SQ_S_ADD_U32 = 0x00000000 # macro +SQ_S_SUB_U32 = 0x00000001 # macro +SQ_S_ADD_I32 = 0x00000002 # macro +SQ_S_SUB_I32 = 0x00000003 # macro +SQ_S_ADDC_U32 = 0x00000004 # macro +SQ_S_SUBB_U32 = 0x00000005 # macro +SQ_S_MIN_I32 = 0x00000006 # macro +SQ_S_MIN_U32 = 0x00000007 # macro +SQ_S_MAX_I32 = 0x00000008 # macro +SQ_S_MAX_U32 = 0x00000009 # macro +SQ_S_CSELECT_B32 = 0x0000000a # macro +SQ_S_CSELECT_B64 = 0x0000000b # macro +SQ_S_AND_B32 = 0x0000000c # macro +SQ_S_AND_B64 = 0x0000000d # macro +SQ_S_OR_B32 = 0x0000000e # macro +SQ_S_OR_B64 = 0x0000000f # macro +SQ_S_XOR_B32 = 0x00000010 # macro +SQ_S_XOR_B64 = 0x00000011 # macro +SQ_S_ANDN2_B32 = 0x00000012 # macro +SQ_S_ANDN2_B64 = 0x00000013 # macro +SQ_S_ORN2_B32 = 0x00000014 # macro +SQ_S_ORN2_B64 = 0x00000015 # macro +SQ_S_NAND_B32 = 0x00000016 # macro +SQ_S_NAND_B64 = 0x00000017 # macro +SQ_S_NOR_B32 = 0x00000018 # macro +SQ_S_NOR_B64 = 0x00000019 # macro +SQ_S_XNOR_B32 = 0x0000001a # macro +SQ_S_XNOR_B64 = 0x0000001b # macro +SQ_S_LSHL_B32 = 0x0000001c # macro +SQ_S_LSHL_B64 = 0x0000001d # macro +SQ_S_LSHR_B32 = 0x0000001e # macro +SQ_S_LSHR_B64 = 0x0000001f # macro +SQ_S_ASHR_I32 = 0x00000020 # macro +SQ_S_ASHR_I64 = 0x00000021 # macro +SQ_S_BFM_B32 = 0x00000022 # macro +SQ_S_BFM_B64 = 0x00000023 # macro +SQ_S_MUL_I32 = 0x00000024 # macro +SQ_S_BFE_U32 = 0x00000025 # macro +SQ_S_BFE_I32 = 0x00000026 # macro +SQ_S_BFE_U64 = 0x00000027 # macro +SQ_S_BFE_I64 = 0x00000028 # macro +SQ_S_CBRANCH_G_FORK = 0x00000029 # macro +SQ_S_ABSDIFF_I32 = 0x0000002a # macro +SQ_S_RFE_RESTORE_B64 = 0x0000002b # macro +SQ_S_MUL_HI_U32 = 0x0000002c # macro +SQ_S_MUL_HI_I32 = 0x0000002d # macro +SQ_S_LSHL1_ADD_U32 = 0x0000002e # macro +SQ_S_LSHL2_ADD_U32 = 0x0000002f # macro +SQ_S_LSHL3_ADD_U32 = 0x00000030 # macro +SQ_S_LSHL4_ADD_U32 = 0x00000031 # macro +SQ_S_PACK_LL_B32_B16 = 0x00000032 # macro +SQ_S_PACK_LH_B32_B16 = 0x00000033 # macro +SQ_S_PACK_HH_B32_B16 = 0x00000034 # macro +SQ_FLAT = 0x00000000 # macro +SQ_SCRATCH = 0x00000001 # macro +SQ_GLOBAL = 0x00000002 # macro +SQ_EXEC_LO = 0x0000007e # macro +SQ_EXEC_HI = 0x0000007f # macro +SQ_SRC_64_INT = 0x000000c0 # macro +SQ_SRC_M_1_INT = 0x000000c1 # macro +SQ_SRC_M_2_INT = 0x000000c2 # macro +SQ_SRC_M_3_INT = 0x000000c3 # macro +SQ_SRC_M_4_INT = 0x000000c4 # macro +SQ_SRC_M_5_INT = 0x000000c5 # macro +SQ_SRC_M_6_INT = 0x000000c6 # macro +SQ_SRC_M_7_INT = 0x000000c7 # macro +SQ_SRC_M_8_INT = 0x000000c8 # macro +SQ_SRC_M_9_INT = 0x000000c9 # macro +SQ_SRC_M_10_INT = 0x000000ca # macro +SQ_SRC_M_11_INT = 0x000000cb # macro +SQ_SRC_M_12_INT = 0x000000cc # macro +SQ_SRC_M_13_INT = 0x000000cd # macro +SQ_SRC_M_14_INT = 0x000000ce # macro +SQ_SRC_M_15_INT = 0x000000cf # macro +SQ_SRC_M_16_INT = 0x000000d0 # macro +SQ_SRC_0_5 = 0x000000f0 # macro +SQ_SRC_M_0_5 = 0x000000f1 # macro +SQ_SRC_1 = 0x000000f2 # macro +SQ_SRC_M_1 = 0x000000f3 # macro +SQ_SRC_2 = 0x000000f4 # macro +SQ_SRC_M_2 = 0x000000f5 # macro +SQ_SRC_4 = 0x000000f6 # macro +SQ_SRC_M_4 = 0x000000f7 # macro +SQ_SRC_INV_2PI = 0x000000f8 # macro +SQ_VCC_LO = 0x0000006a # macro +SQ_VCC_HI = 0x0000006b # macro +SQ_EXP_MRT0 = 0x00000000 # macro +SQ_EXP_MRTZ = 0x00000008 # macro +SQ_EXP_NULL = 0x00000009 # macro +SQ_EXP_POS0 = 0x0000000c # macro +SQ_EXP_PARAM0 = 0x00000020 # macro +SQ_S_NOP = 0x00000000 # macro +SQ_S_ENDPGM = 0x00000001 # macro +SQ_S_BRANCH = 0x00000002 # macro +SQ_S_WAKEUP = 0x00000003 # macro +SQ_S_CBRANCH_SCC0 = 0x00000004 # macro +SQ_S_CBRANCH_SCC1 = 0x00000005 # macro +SQ_S_CBRANCH_VCCZ = 0x00000006 # macro +SQ_S_CBRANCH_VCCNZ = 0x00000007 # macro +SQ_S_CBRANCH_EXECZ = 0x00000008 # macro +SQ_S_CBRANCH_EXECNZ = 0x00000009 # macro +SQ_S_BARRIER = 0x0000000a # macro +SQ_S_SETKILL = 0x0000000b # macro +SQ_S_WAITCNT = 0x0000000c # macro +SQ_S_SETHALT = 0x0000000d # macro +SQ_S_SLEEP = 0x0000000e # macro +SQ_S_SETPRIO = 0x0000000f # macro +SQ_S_SENDMSG = 0x00000010 # macro +SQ_S_SENDMSGHALT = 0x00000011 # macro +SQ_S_TRAP = 0x00000012 # macro +SQ_S_ICACHE_INV = 0x00000013 # macro +SQ_S_INCPERFLEVEL = 0x00000014 # macro +SQ_S_DECPERFLEVEL = 0x00000015 # macro +SQ_S_TTRACEDATA = 0x00000016 # macro +SQ_S_CBRANCH_CDBGSYS = 0x00000017 # macro +SQ_S_CBRANCH_CDBGUSER = 0x00000018 # macro +SQ_S_CBRANCH_CDBGSYS_OR_USER = 0x00000019 # macro +SQ_S_CBRANCH_CDBGSYS_AND_USER = 0x0000001a # macro +SQ_S_ENDPGM_SAVED = 0x0000001b # macro +SQ_S_SET_GPR_IDX_OFF = 0x0000001c # macro +SQ_S_SET_GPR_IDX_MODE = 0x0000001d # macro +SQ_S_ENDPGM_ORDERED_PS_DONE = 0x0000001e # macro +SQ_EXP = 0x00000000 # macro +SQ_SRC_POPS_EXITING_WAVE_ID = 0x000000ef # macro +SQ_XNACK_MASK_LO = 0x00000068 # macro +SQ_XNACK_MASK_HI = 0x00000069 # macro +SQ_OMOD_OFF = 0x00000000 # macro +SQ_OMOD_M2 = 0x00000001 # macro +SQ_OMOD_M4 = 0x00000002 # macro +SQ_OMOD_D2 = 0x00000003 # macro +SQ_SRC_EXECZ = 0x000000fc # macro +SQ_F = 0x00000000 # macro +SQ_LT = 0x00000001 # macro +SQ_EQ = 0x00000002 # macro +SQ_LE = 0x00000003 # macro +SQ_GT = 0x00000004 # macro +SQ_NE = 0x00000005 # macro +SQ_GE = 0x00000006 # macro +SQ_T = 0x00000007 # macro +SQ_DPP_BOUND_OFF = 0x00000000 # macro +SQ_DPP_BOUND_ZERO = 0x00000001 # macro +SQ_M0 = 0x0000007c # macro +SQ_MSG_INTERRUPT = 0x00000001 # macro +SQ_MSG_GS = 0x00000002 # macro +SQ_MSG_GS_DONE = 0x00000003 # macro +SQ_MSG_SAVEWAVE = 0x00000004 # macro +SQ_MSG_STALL_WAVE_GEN = 0x00000005 # macro +SQ_MSG_HALT_WAVES = 0x00000006 # macro +SQ_MSG_ORDERED_PS_DONE = 0x00000007 # macro +SQ_MSG_EARLY_PRIM_DEALLOC = 0x00000008 # macro +SQ_MSG_GS_ALLOC_REQ = 0x00000009 # macro +SQ_MSG_SYSMSG = 0x0000000f # macro +SQ_PARAM_P10 = 0x00000000 # macro +SQ_PARAM_P20 = 0x00000001 # macro +SQ_PARAM_P0 = 0x00000002 # macro +SQ_V_OPC_OFFSET = 0x00000000 # macro +SQ_V_OP2_OFFSET = 0x00000100 # macro +SQ_V_OP1_OFFSET = 0x00000140 # macro +SQ_V_INTRP_OFFSET = 0x00000270 # macro +SQ_V_OP3P_OFFSET = 0x00000380 # macro +SQ_SRC_SDWA = 0x000000f9 # macro +SQ_SRC_SHARED_BASE = 0x000000eb # macro +SQ_SRC_SHARED_LIMIT = 0x000000ec # macro +SQ_SRC_PRIVATE_BASE = 0x000000ed # macro +SQ_SRC_PRIVATE_LIMIT = 0x000000ee # macro +SQ_LG = 0x00000005 # macro +SQ_O = 0x00000007 # macro +SQ_U = 0x00000008 # macro +SQ_NGE = 0x00000009 # macro +SQ_NLG = 0x0000000a # macro +SQ_NGT = 0x0000000b # macro +SQ_NLE = 0x0000000c # macro +SQ_NEQ = 0x0000000d # macro +SQ_NLT = 0x0000000e # macro +SQ_TRU = 0x0000000f # macro +SQ_SDWA_UNUSED_PAD = 0x00000000 # macro +SQ_SDWA_UNUSED_SEXT = 0x00000001 # macro +SQ_SDWA_UNUSED_PRESERVE = 0x00000002 # macro +SQ_SRC_SCC = 0x000000fd # macro +SQ_V_CMP_CLASS_F32 = 0x00000010 # macro +SQ_V_CMPX_CLASS_F32 = 0x00000011 # macro +SQ_V_CMP_CLASS_F64 = 0x00000012 # macro +SQ_V_CMPX_CLASS_F64 = 0x00000013 # macro +SQ_V_CMP_CLASS_F16 = 0x00000014 # macro +SQ_V_CMPX_CLASS_F16 = 0x00000015 # macro +SQ_V_CMP_F_F16 = 0x00000020 # macro +SQ_V_CMP_LT_F16 = 0x00000021 # macro +SQ_V_CMP_EQ_F16 = 0x00000022 # macro +SQ_V_CMP_LE_F16 = 0x00000023 # macro +SQ_V_CMP_GT_F16 = 0x00000024 # macro +SQ_V_CMP_LG_F16 = 0x00000025 # macro +SQ_V_CMP_GE_F16 = 0x00000026 # macro +SQ_V_CMP_O_F16 = 0x00000027 # macro +SQ_V_CMP_U_F16 = 0x00000028 # macro +SQ_V_CMP_NGE_F16 = 0x00000029 # macro +SQ_V_CMP_NLG_F16 = 0x0000002a # macro +SQ_V_CMP_NGT_F16 = 0x0000002b # macro +SQ_V_CMP_NLE_F16 = 0x0000002c # macro +SQ_V_CMP_NEQ_F16 = 0x0000002d # macro +SQ_V_CMP_NLT_F16 = 0x0000002e # macro +SQ_V_CMP_TRU_F16 = 0x0000002f # macro +SQ_V_CMPX_F_F16 = 0x00000030 # macro +SQ_V_CMPX_LT_F16 = 0x00000031 # macro +SQ_V_CMPX_EQ_F16 = 0x00000032 # macro +SQ_V_CMPX_LE_F16 = 0x00000033 # macro +SQ_V_CMPX_GT_F16 = 0x00000034 # macro +SQ_V_CMPX_LG_F16 = 0x00000035 # macro +SQ_V_CMPX_GE_F16 = 0x00000036 # macro +SQ_V_CMPX_O_F16 = 0x00000037 # macro +SQ_V_CMPX_U_F16 = 0x00000038 # macro +SQ_V_CMPX_NGE_F16 = 0x00000039 # macro +SQ_V_CMPX_NLG_F16 = 0x0000003a # macro +SQ_V_CMPX_NGT_F16 = 0x0000003b # macro +SQ_V_CMPX_NLE_F16 = 0x0000003c # macro +SQ_V_CMPX_NEQ_F16 = 0x0000003d # macro +SQ_V_CMPX_NLT_F16 = 0x0000003e # macro +SQ_V_CMPX_TRU_F16 = 0x0000003f # macro +SQ_V_CMP_F_F32 = 0x00000040 # macro +SQ_V_CMP_LT_F32 = 0x00000041 # macro +SQ_V_CMP_EQ_F32 = 0x00000042 # macro +SQ_V_CMP_LE_F32 = 0x00000043 # macro +SQ_V_CMP_GT_F32 = 0x00000044 # macro +SQ_V_CMP_LG_F32 = 0x00000045 # macro +SQ_V_CMP_GE_F32 = 0x00000046 # macro +SQ_V_CMP_O_F32 = 0x00000047 # macro +SQ_V_CMP_U_F32 = 0x00000048 # macro +SQ_V_CMP_NGE_F32 = 0x00000049 # macro +SQ_V_CMP_NLG_F32 = 0x0000004a # macro +SQ_V_CMP_NGT_F32 = 0x0000004b # macro +SQ_V_CMP_NLE_F32 = 0x0000004c # macro +SQ_V_CMP_NEQ_F32 = 0x0000004d # macro +SQ_V_CMP_NLT_F32 = 0x0000004e # macro +SQ_V_CMP_TRU_F32 = 0x0000004f # macro +SQ_V_CMPX_F_F32 = 0x00000050 # macro +SQ_V_CMPX_LT_F32 = 0x00000051 # macro +SQ_V_CMPX_EQ_F32 = 0x00000052 # macro +SQ_V_CMPX_LE_F32 = 0x00000053 # macro +SQ_V_CMPX_GT_F32 = 0x00000054 # macro +SQ_V_CMPX_LG_F32 = 0x00000055 # macro +SQ_V_CMPX_GE_F32 = 0x00000056 # macro +SQ_V_CMPX_O_F32 = 0x00000057 # macro +SQ_V_CMPX_U_F32 = 0x00000058 # macro +SQ_V_CMPX_NGE_F32 = 0x00000059 # macro +SQ_V_CMPX_NLG_F32 = 0x0000005a # macro +SQ_V_CMPX_NGT_F32 = 0x0000005b # macro +SQ_V_CMPX_NLE_F32 = 0x0000005c # macro +SQ_V_CMPX_NEQ_F32 = 0x0000005d # macro +SQ_V_CMPX_NLT_F32 = 0x0000005e # macro +SQ_V_CMPX_TRU_F32 = 0x0000005f # macro +SQ_V_CMP_F_F64 = 0x00000060 # macro +SQ_V_CMP_LT_F64 = 0x00000061 # macro +SQ_V_CMP_EQ_F64 = 0x00000062 # macro +SQ_V_CMP_LE_F64 = 0x00000063 # macro +SQ_V_CMP_GT_F64 = 0x00000064 # macro +SQ_V_CMP_LG_F64 = 0x00000065 # macro +SQ_V_CMP_GE_F64 = 0x00000066 # macro +SQ_V_CMP_O_F64 = 0x00000067 # macro +SQ_V_CMP_U_F64 = 0x00000068 # macro +SQ_V_CMP_NGE_F64 = 0x00000069 # macro +SQ_V_CMP_NLG_F64 = 0x0000006a # macro +SQ_V_CMP_NGT_F64 = 0x0000006b # macro +SQ_V_CMP_NLE_F64 = 0x0000006c # macro +SQ_V_CMP_NEQ_F64 = 0x0000006d # macro +SQ_V_CMP_NLT_F64 = 0x0000006e # macro +SQ_V_CMP_TRU_F64 = 0x0000006f # macro +SQ_V_CMPX_F_F64 = 0x00000070 # macro +SQ_V_CMPX_LT_F64 = 0x00000071 # macro +SQ_V_CMPX_EQ_F64 = 0x00000072 # macro +SQ_V_CMPX_LE_F64 = 0x00000073 # macro +SQ_V_CMPX_GT_F64 = 0x00000074 # macro +SQ_V_CMPX_LG_F64 = 0x00000075 # macro +SQ_V_CMPX_GE_F64 = 0x00000076 # macro +SQ_V_CMPX_O_F64 = 0x00000077 # macro +SQ_V_CMPX_U_F64 = 0x00000078 # macro +SQ_V_CMPX_NGE_F64 = 0x00000079 # macro +SQ_V_CMPX_NLG_F64 = 0x0000007a # macro +SQ_V_CMPX_NGT_F64 = 0x0000007b # macro +SQ_V_CMPX_NLE_F64 = 0x0000007c # macro +SQ_V_CMPX_NEQ_F64 = 0x0000007d # macro +SQ_V_CMPX_NLT_F64 = 0x0000007e # macro +SQ_V_CMPX_TRU_F64 = 0x0000007f # macro +SQ_V_CMP_F_I16 = 0x000000a0 # macro +SQ_V_CMP_LT_I16 = 0x000000a1 # macro +SQ_V_CMP_EQ_I16 = 0x000000a2 # macro +SQ_V_CMP_LE_I16 = 0x000000a3 # macro +SQ_V_CMP_GT_I16 = 0x000000a4 # macro +SQ_V_CMP_NE_I16 = 0x000000a5 # macro +SQ_V_CMP_GE_I16 = 0x000000a6 # macro +SQ_V_CMP_T_I16 = 0x000000a7 # macro +SQ_V_CMP_F_U16 = 0x000000a8 # macro +SQ_V_CMP_LT_U16 = 0x000000a9 # macro +SQ_V_CMP_EQ_U16 = 0x000000aa # macro +SQ_V_CMP_LE_U16 = 0x000000ab # macro +SQ_V_CMP_GT_U16 = 0x000000ac # macro +SQ_V_CMP_NE_U16 = 0x000000ad # macro +SQ_V_CMP_GE_U16 = 0x000000ae # macro +SQ_V_CMP_T_U16 = 0x000000af # macro +SQ_V_CMPX_F_I16 = 0x000000b0 # macro +SQ_V_CMPX_LT_I16 = 0x000000b1 # macro +SQ_V_CMPX_EQ_I16 = 0x000000b2 # macro +SQ_V_CMPX_LE_I16 = 0x000000b3 # macro +SQ_V_CMPX_GT_I16 = 0x000000b4 # macro +SQ_V_CMPX_NE_I16 = 0x000000b5 # macro +SQ_V_CMPX_GE_I16 = 0x000000b6 # macro +SQ_V_CMPX_T_I16 = 0x000000b7 # macro +SQ_V_CMPX_F_U16 = 0x000000b8 # macro +SQ_V_CMPX_LT_U16 = 0x000000b9 # macro +SQ_V_CMPX_EQ_U16 = 0x000000ba # macro +SQ_V_CMPX_LE_U16 = 0x000000bb # macro +SQ_V_CMPX_GT_U16 = 0x000000bc # macro +SQ_V_CMPX_NE_U16 = 0x000000bd # macro +SQ_V_CMPX_GE_U16 = 0x000000be # macro +SQ_V_CMPX_T_U16 = 0x000000bf # macro +SQ_V_CMP_F_I32 = 0x000000c0 # macro +SQ_V_CMP_LT_I32 = 0x000000c1 # macro +SQ_V_CMP_EQ_I32 = 0x000000c2 # macro +SQ_V_CMP_LE_I32 = 0x000000c3 # macro +SQ_V_CMP_GT_I32 = 0x000000c4 # macro +SQ_V_CMP_NE_I32 = 0x000000c5 # macro +SQ_V_CMP_GE_I32 = 0x000000c6 # macro +SQ_V_CMP_T_I32 = 0x000000c7 # macro +SQ_V_CMP_F_U32 = 0x000000c8 # macro +SQ_V_CMP_LT_U32 = 0x000000c9 # macro +SQ_V_CMP_EQ_U32 = 0x000000ca # macro +SQ_V_CMP_LE_U32 = 0x000000cb # macro +SQ_V_CMP_GT_U32 = 0x000000cc # macro +SQ_V_CMP_NE_U32 = 0x000000cd # macro +SQ_V_CMP_GE_U32 = 0x000000ce # macro +SQ_V_CMP_T_U32 = 0x000000cf # macro +SQ_V_CMPX_F_I32 = 0x000000d0 # macro +SQ_V_CMPX_LT_I32 = 0x000000d1 # macro +SQ_V_CMPX_EQ_I32 = 0x000000d2 # macro +SQ_V_CMPX_LE_I32 = 0x000000d3 # macro +SQ_V_CMPX_GT_I32 = 0x000000d4 # macro +SQ_V_CMPX_NE_I32 = 0x000000d5 # macro +SQ_V_CMPX_GE_I32 = 0x000000d6 # macro +SQ_V_CMPX_T_I32 = 0x000000d7 # macro +SQ_V_CMPX_F_U32 = 0x000000d8 # macro +SQ_V_CMPX_LT_U32 = 0x000000d9 # macro +SQ_V_CMPX_EQ_U32 = 0x000000da # macro +SQ_V_CMPX_LE_U32 = 0x000000db # macro +SQ_V_CMPX_GT_U32 = 0x000000dc # macro +SQ_V_CMPX_NE_U32 = 0x000000dd # macro +SQ_V_CMPX_GE_U32 = 0x000000de # macro +SQ_V_CMPX_T_U32 = 0x000000df # macro +SQ_V_CMP_F_I64 = 0x000000e0 # macro +SQ_V_CMP_LT_I64 = 0x000000e1 # macro +SQ_V_CMP_EQ_I64 = 0x000000e2 # macro +SQ_V_CMP_LE_I64 = 0x000000e3 # macro +SQ_V_CMP_GT_I64 = 0x000000e4 # macro +SQ_V_CMP_NE_I64 = 0x000000e5 # macro +SQ_V_CMP_GE_I64 = 0x000000e6 # macro +SQ_V_CMP_T_I64 = 0x000000e7 # macro +SQ_V_CMP_F_U64 = 0x000000e8 # macro +SQ_V_CMP_LT_U64 = 0x000000e9 # macro +SQ_V_CMP_EQ_U64 = 0x000000ea # macro +SQ_V_CMP_LE_U64 = 0x000000eb # macro +SQ_V_CMP_GT_U64 = 0x000000ec # macro +SQ_V_CMP_NE_U64 = 0x000000ed # macro +SQ_V_CMP_GE_U64 = 0x000000ee # macro +SQ_V_CMP_T_U64 = 0x000000ef # macro +SQ_V_CMPX_F_I64 = 0x000000f0 # macro +SQ_V_CMPX_LT_I64 = 0x000000f1 # macro +SQ_V_CMPX_EQ_I64 = 0x000000f2 # macro +SQ_V_CMPX_LE_I64 = 0x000000f3 # macro +SQ_V_CMPX_GT_I64 = 0x000000f4 # macro +SQ_V_CMPX_NE_I64 = 0x000000f5 # macro +SQ_V_CMPX_GE_I64 = 0x000000f6 # macro +SQ_V_CMPX_T_I64 = 0x000000f7 # macro +SQ_V_CMPX_F_U64 = 0x000000f8 # macro +SQ_V_CMPX_LT_U64 = 0x000000f9 # macro +SQ_V_CMPX_EQ_U64 = 0x000000fa # macro +SQ_V_CMPX_LE_U64 = 0x000000fb # macro +SQ_V_CMPX_GT_U64 = 0x000000fc # macro +SQ_V_CMPX_NE_U64 = 0x000000fd # macro +SQ_V_CMPX_GE_U64 = 0x000000fe # macro +SQ_V_CMPX_T_U64 = 0x000000ff # macro +SQ_GS_OP_NOP = 0x00000000 # macro +SQ_GS_OP_CUT = 0x00000001 # macro +SQ_GS_OP_EMIT = 0x00000002 # macro +SQ_GS_OP_EMIT_CUT = 0x00000003 # macro +SQ_SRC_LDS_DIRECT = 0x000000fe # macro +SQ_ATTR0 = 0x00000000 # macro +SQ_EXP_GDS0 = 0x00000018 # macro +SQ_S_CMP_EQ_I32 = 0x00000000 # macro +SQ_S_CMP_LG_I32 = 0x00000001 # macro +SQ_S_CMP_GT_I32 = 0x00000002 # macro +SQ_S_CMP_GE_I32 = 0x00000003 # macro +SQ_S_CMP_LT_I32 = 0x00000004 # macro +SQ_S_CMP_LE_I32 = 0x00000005 # macro +SQ_S_CMP_EQ_U32 = 0x00000006 # macro +SQ_S_CMP_LG_U32 = 0x00000007 # macro +SQ_S_CMP_GT_U32 = 0x00000008 # macro +SQ_S_CMP_GE_U32 = 0x00000009 # macro +SQ_S_CMP_LT_U32 = 0x0000000a # macro +SQ_S_CMP_LE_U32 = 0x0000000b # macro +SQ_S_BITCMP0_B32 = 0x0000000c # macro +SQ_S_BITCMP1_B32 = 0x0000000d # macro +SQ_S_BITCMP0_B64 = 0x0000000e # macro +SQ_S_BITCMP1_B64 = 0x0000000f # macro +SQ_S_SETVSKIP = 0x00000010 # macro +SQ_S_SET_GPR_IDX_ON = 0x00000011 # macro +SQ_S_CMP_EQ_U64 = 0x00000012 # macro +SQ_S_CMP_LG_U64 = 0x00000013 # macro +SQ_TTMP0 = 0x0000006c # macro +SQ_TTMP1 = 0x0000006d # macro +SQ_TTMP2 = 0x0000006e # macro +SQ_TTMP3 = 0x0000006f # macro +SQ_TTMP4 = 0x00000070 # macro +SQ_TTMP5 = 0x00000071 # macro +SQ_TTMP6 = 0x00000072 # macro +SQ_TTMP7 = 0x00000073 # macro +SQ_TTMP8 = 0x00000074 # macro +SQ_TTMP9 = 0x00000075 # macro +SQ_TTMP10 = 0x00000076 # macro +SQ_TTMP11 = 0x00000077 # macro +SQ_TTMP12 = 0x00000078 # macro +SQ_TTMP13 = 0x00000079 # macro +SQ_TTMP14 = 0x0000007a # macro +SQ_TTMP15 = 0x0000007b # macro +SQ_SRC_VGPR0 = 0x00000100 # macro +SQ_BUFFER_LOAD_FORMAT_X = 0x00000000 # macro +SQ_BUFFER_LOAD_FORMAT_XY = 0x00000001 # macro +SQ_BUFFER_LOAD_FORMAT_XYZ = 0x00000002 # macro +SQ_BUFFER_LOAD_FORMAT_XYZW = 0x00000003 # macro +SQ_BUFFER_STORE_FORMAT_X = 0x00000004 # macro +SQ_BUFFER_STORE_FORMAT_XY = 0x00000005 # macro +SQ_BUFFER_STORE_FORMAT_XYZ = 0x00000006 # macro +SQ_BUFFER_STORE_FORMAT_XYZW = 0x00000007 # macro +SQ_BUFFER_LOAD_FORMAT_D16_X = 0x00000008 # macro +SQ_BUFFER_LOAD_FORMAT_D16_XY = 0x00000009 # macro +SQ_BUFFER_LOAD_FORMAT_D16_XYZ = 0x0000000a # macro +SQ_BUFFER_LOAD_FORMAT_D16_XYZW = 0x0000000b # macro +SQ_BUFFER_STORE_FORMAT_D16_X = 0x0000000c # macro +SQ_BUFFER_STORE_FORMAT_D16_XY = 0x0000000d # macro +SQ_BUFFER_STORE_FORMAT_D16_XYZ = 0x0000000e # macro +SQ_BUFFER_STORE_FORMAT_D16_XYZW = 0x0000000f # macro +SQ_BUFFER_LOAD_UBYTE = 0x00000010 # macro +SQ_BUFFER_LOAD_SBYTE = 0x00000011 # macro +SQ_BUFFER_LOAD_USHORT = 0x00000012 # macro +SQ_BUFFER_LOAD_SSHORT = 0x00000013 # macro +SQ_BUFFER_LOAD_DWORD = 0x00000014 # macro +SQ_BUFFER_LOAD_DWORDX2 = 0x00000015 # macro +SQ_BUFFER_LOAD_DWORDX3 = 0x00000016 # macro +SQ_BUFFER_LOAD_DWORDX4 = 0x00000017 # macro +SQ_BUFFER_STORE_BYTE = 0x00000018 # macro +SQ_BUFFER_STORE_SHORT = 0x0000001a # macro +SQ_BUFFER_STORE_DWORD = 0x0000001c # macro +SQ_BUFFER_STORE_DWORDX2 = 0x0000001d # macro +SQ_BUFFER_STORE_DWORDX3 = 0x0000001e # macro +SQ_BUFFER_STORE_DWORDX4 = 0x0000001f # macro +SQ_BUFFER_STORE_LDS_DWORD = 0x0000003d # macro +SQ_BUFFER_WBINVL1 = 0x0000003e # macro +SQ_BUFFER_WBINVL1_VOL = 0x0000003f # macro +SQ_BUFFER_ATOMIC_SWAP = 0x00000040 # macro +SQ_BUFFER_ATOMIC_CMPSWAP = 0x00000041 # macro +SQ_BUFFER_ATOMIC_ADD = 0x00000042 # macro +SQ_BUFFER_ATOMIC_SUB = 0x00000043 # macro +SQ_BUFFER_ATOMIC_SMIN = 0x00000044 # macro +SQ_BUFFER_ATOMIC_UMIN = 0x00000045 # macro +SQ_BUFFER_ATOMIC_SMAX = 0x00000046 # macro +SQ_BUFFER_ATOMIC_UMAX = 0x00000047 # macro +SQ_BUFFER_ATOMIC_AND = 0x00000048 # macro +SQ_BUFFER_ATOMIC_OR = 0x00000049 # macro +SQ_BUFFER_ATOMIC_XOR = 0x0000004a # macro +SQ_BUFFER_ATOMIC_INC = 0x0000004b # macro +SQ_BUFFER_ATOMIC_DEC = 0x0000004c # macro +SQ_BUFFER_ATOMIC_SWAP_X2 = 0x00000060 # macro +SQ_BUFFER_ATOMIC_CMPSWAP_X2 = 0x00000061 # macro +SQ_BUFFER_ATOMIC_ADD_X2 = 0x00000062 # macro +SQ_BUFFER_ATOMIC_SUB_X2 = 0x00000063 # macro +SQ_BUFFER_ATOMIC_SMIN_X2 = 0x00000064 # macro +SQ_BUFFER_ATOMIC_UMIN_X2 = 0x00000065 # macro +SQ_BUFFER_ATOMIC_SMAX_X2 = 0x00000066 # macro +SQ_BUFFER_ATOMIC_UMAX_X2 = 0x00000067 # macro +SQ_BUFFER_ATOMIC_AND_X2 = 0x00000068 # macro +SQ_BUFFER_ATOMIC_OR_X2 = 0x00000069 # macro +SQ_BUFFER_ATOMIC_XOR_X2 = 0x0000006a # macro +SQ_BUFFER_ATOMIC_INC_X2 = 0x0000006b # macro +SQ_BUFFER_ATOMIC_DEC_X2 = 0x0000006c # macro +SQ_SDWA_BYTE_0 = 0x00000000 # macro +SQ_SDWA_BYTE_1 = 0x00000001 # macro +SQ_SDWA_BYTE_2 = 0x00000002 # macro +SQ_SDWA_BYTE_3 = 0x00000003 # macro +SQ_SDWA_WORD_0 = 0x00000004 # macro +SQ_SDWA_WORD_1 = 0x00000005 # macro +SQ_SDWA_DWORD = 0x00000006 # macro +ROM_SIGNATURE = 0x0000aa55 # macro + +# values for enumeration 'GDS_PERFCOUNT_SELECT' +GDS_PERFCOUNT_SELECT__enumvalues = { + 0: 'GDS_PERF_SEL_DS_ADDR_CONFL', + 1: 'GDS_PERF_SEL_DS_BANK_CONFL', + 2: 'GDS_PERF_SEL_WBUF_FLUSH', + 3: 'GDS_PERF_SEL_WR_COMP', + 4: 'GDS_PERF_SEL_WBUF_WR', + 5: 'GDS_PERF_SEL_RBUF_HIT', + 6: 'GDS_PERF_SEL_RBUF_MISS', + 7: 'GDS_PERF_SEL_SE0_SH0_NORET', + 8: 'GDS_PERF_SEL_SE0_SH0_RET', + 9: 'GDS_PERF_SEL_SE0_SH0_ORD_CNT', + 10: 'GDS_PERF_SEL_SE0_SH0_2COMP_REQ', + 11: 'GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID', + 12: 'GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID', + 13: 'GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD', + 14: 'GDS_PERF_SEL_SE0_SH0_GDS_WR_OP', + 15: 'GDS_PERF_SEL_SE0_SH0_GDS_RD_OP', + 16: 'GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP', + 17: 'GDS_PERF_SEL_SE0_SH0_GDS_REL_OP', + 18: 'GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP', + 19: 'GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP', + 20: 'GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP', + 21: 'GDS_PERF_SEL_SE0_SH1_NORET', + 22: 'GDS_PERF_SEL_SE0_SH1_RET', + 23: 'GDS_PERF_SEL_SE0_SH1_ORD_CNT', + 24: 'GDS_PERF_SEL_SE0_SH1_2COMP_REQ', + 25: 'GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID', + 26: 'GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID', + 27: 'GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD', + 28: 'GDS_PERF_SEL_SE0_SH1_GDS_WR_OP', + 29: 'GDS_PERF_SEL_SE0_SH1_GDS_RD_OP', + 30: 'GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP', + 31: 'GDS_PERF_SEL_SE0_SH1_GDS_REL_OP', + 32: 'GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP', + 33: 'GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP', + 34: 'GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP', + 35: 'GDS_PERF_SEL_SE1_SH0_NORET', + 36: 'GDS_PERF_SEL_SE1_SH0_RET', + 37: 'GDS_PERF_SEL_SE1_SH0_ORD_CNT', + 38: 'GDS_PERF_SEL_SE1_SH0_2COMP_REQ', + 39: 'GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID', + 40: 'GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID', + 41: 'GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD', + 42: 'GDS_PERF_SEL_SE1_SH0_GDS_WR_OP', + 43: 'GDS_PERF_SEL_SE1_SH0_GDS_RD_OP', + 44: 'GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP', + 45: 'GDS_PERF_SEL_SE1_SH0_GDS_REL_OP', + 46: 'GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP', + 47: 'GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP', + 48: 'GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP', + 49: 'GDS_PERF_SEL_SE1_SH1_NORET', + 50: 'GDS_PERF_SEL_SE1_SH1_RET', + 51: 'GDS_PERF_SEL_SE1_SH1_ORD_CNT', + 52: 'GDS_PERF_SEL_SE1_SH1_2COMP_REQ', + 53: 'GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID', + 54: 'GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID', + 55: 'GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD', + 56: 'GDS_PERF_SEL_SE1_SH1_GDS_WR_OP', + 57: 'GDS_PERF_SEL_SE1_SH1_GDS_RD_OP', + 58: 'GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP', + 59: 'GDS_PERF_SEL_SE1_SH1_GDS_REL_OP', + 60: 'GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP', + 61: 'GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP', + 62: 'GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP', + 63: 'GDS_PERF_SEL_SE2_SH0_NORET', + 64: 'GDS_PERF_SEL_SE2_SH0_RET', + 65: 'GDS_PERF_SEL_SE2_SH0_ORD_CNT', + 66: 'GDS_PERF_SEL_SE2_SH0_2COMP_REQ', + 67: 'GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID', + 68: 'GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID', + 69: 'GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD', + 70: 'GDS_PERF_SEL_SE2_SH0_GDS_WR_OP', + 71: 'GDS_PERF_SEL_SE2_SH0_GDS_RD_OP', + 72: 'GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP', + 73: 'GDS_PERF_SEL_SE2_SH0_GDS_REL_OP', + 74: 'GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP', + 75: 'GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP', + 76: 'GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP', + 77: 'GDS_PERF_SEL_SE2_SH1_NORET', + 78: 'GDS_PERF_SEL_SE2_SH1_RET', + 79: 'GDS_PERF_SEL_SE2_SH1_ORD_CNT', + 80: 'GDS_PERF_SEL_SE2_SH1_2COMP_REQ', + 81: 'GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID', + 82: 'GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID', + 83: 'GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD', + 84: 'GDS_PERF_SEL_SE2_SH1_GDS_WR_OP', + 85: 'GDS_PERF_SEL_SE2_SH1_GDS_RD_OP', + 86: 'GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP', + 87: 'GDS_PERF_SEL_SE2_SH1_GDS_REL_OP', + 88: 'GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP', + 89: 'GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP', + 90: 'GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP', + 91: 'GDS_PERF_SEL_SE3_SH0_NORET', + 92: 'GDS_PERF_SEL_SE3_SH0_RET', + 93: 'GDS_PERF_SEL_SE3_SH0_ORD_CNT', + 94: 'GDS_PERF_SEL_SE3_SH0_2COMP_REQ', + 95: 'GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID', + 96: 'GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID', + 97: 'GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD', + 98: 'GDS_PERF_SEL_SE3_SH0_GDS_WR_OP', + 99: 'GDS_PERF_SEL_SE3_SH0_GDS_RD_OP', + 100: 'GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP', + 101: 'GDS_PERF_SEL_SE3_SH0_GDS_REL_OP', + 102: 'GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP', + 103: 'GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP', + 104: 'GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP', + 105: 'GDS_PERF_SEL_SE3_SH1_NORET', + 106: 'GDS_PERF_SEL_SE3_SH1_RET', + 107: 'GDS_PERF_SEL_SE3_SH1_ORD_CNT', + 108: 'GDS_PERF_SEL_SE3_SH1_2COMP_REQ', + 109: 'GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID', + 110: 'GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID', + 111: 'GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD', + 112: 'GDS_PERF_SEL_SE3_SH1_GDS_WR_OP', + 113: 'GDS_PERF_SEL_SE3_SH1_GDS_RD_OP', + 114: 'GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP', + 115: 'GDS_PERF_SEL_SE3_SH1_GDS_REL_OP', + 116: 'GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP', + 117: 'GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP', + 118: 'GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP', + 119: 'GDS_PERF_SEL_GWS_RELEASED', + 120: 'GDS_PERF_SEL_GWS_BYPASS', +} +GDS_PERF_SEL_DS_ADDR_CONFL = 0 +GDS_PERF_SEL_DS_BANK_CONFL = 1 +GDS_PERF_SEL_WBUF_FLUSH = 2 +GDS_PERF_SEL_WR_COMP = 3 +GDS_PERF_SEL_WBUF_WR = 4 +GDS_PERF_SEL_RBUF_HIT = 5 +GDS_PERF_SEL_RBUF_MISS = 6 +GDS_PERF_SEL_SE0_SH0_NORET = 7 +GDS_PERF_SEL_SE0_SH0_RET = 8 +GDS_PERF_SEL_SE0_SH0_ORD_CNT = 9 +GDS_PERF_SEL_SE0_SH0_2COMP_REQ = 10 +GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID = 11 +GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID = 12 +GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD = 13 +GDS_PERF_SEL_SE0_SH0_GDS_WR_OP = 14 +GDS_PERF_SEL_SE0_SH0_GDS_RD_OP = 15 +GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP = 16 +GDS_PERF_SEL_SE0_SH0_GDS_REL_OP = 17 +GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP = 18 +GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP = 19 +GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP = 20 +GDS_PERF_SEL_SE0_SH1_NORET = 21 +GDS_PERF_SEL_SE0_SH1_RET = 22 +GDS_PERF_SEL_SE0_SH1_ORD_CNT = 23 +GDS_PERF_SEL_SE0_SH1_2COMP_REQ = 24 +GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID = 25 +GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID = 26 +GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD = 27 +GDS_PERF_SEL_SE0_SH1_GDS_WR_OP = 28 +GDS_PERF_SEL_SE0_SH1_GDS_RD_OP = 29 +GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP = 30 +GDS_PERF_SEL_SE0_SH1_GDS_REL_OP = 31 +GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP = 32 +GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP = 33 +GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP = 34 +GDS_PERF_SEL_SE1_SH0_NORET = 35 +GDS_PERF_SEL_SE1_SH0_RET = 36 +GDS_PERF_SEL_SE1_SH0_ORD_CNT = 37 +GDS_PERF_SEL_SE1_SH0_2COMP_REQ = 38 +GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID = 39 +GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID = 40 +GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD = 41 +GDS_PERF_SEL_SE1_SH0_GDS_WR_OP = 42 +GDS_PERF_SEL_SE1_SH0_GDS_RD_OP = 43 +GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP = 44 +GDS_PERF_SEL_SE1_SH0_GDS_REL_OP = 45 +GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP = 46 +GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP = 47 +GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP = 48 +GDS_PERF_SEL_SE1_SH1_NORET = 49 +GDS_PERF_SEL_SE1_SH1_RET = 50 +GDS_PERF_SEL_SE1_SH1_ORD_CNT = 51 +GDS_PERF_SEL_SE1_SH1_2COMP_REQ = 52 +GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID = 53 +GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID = 54 +GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD = 55 +GDS_PERF_SEL_SE1_SH1_GDS_WR_OP = 56 +GDS_PERF_SEL_SE1_SH1_GDS_RD_OP = 57 +GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP = 58 +GDS_PERF_SEL_SE1_SH1_GDS_REL_OP = 59 +GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP = 60 +GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP = 61 +GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP = 62 +GDS_PERF_SEL_SE2_SH0_NORET = 63 +GDS_PERF_SEL_SE2_SH0_RET = 64 +GDS_PERF_SEL_SE2_SH0_ORD_CNT = 65 +GDS_PERF_SEL_SE2_SH0_2COMP_REQ = 66 +GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID = 67 +GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID = 68 +GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD = 69 +GDS_PERF_SEL_SE2_SH0_GDS_WR_OP = 70 +GDS_PERF_SEL_SE2_SH0_GDS_RD_OP = 71 +GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP = 72 +GDS_PERF_SEL_SE2_SH0_GDS_REL_OP = 73 +GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP = 74 +GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP = 75 +GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP = 76 +GDS_PERF_SEL_SE2_SH1_NORET = 77 +GDS_PERF_SEL_SE2_SH1_RET = 78 +GDS_PERF_SEL_SE2_SH1_ORD_CNT = 79 +GDS_PERF_SEL_SE2_SH1_2COMP_REQ = 80 +GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID = 81 +GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID = 82 +GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD = 83 +GDS_PERF_SEL_SE2_SH1_GDS_WR_OP = 84 +GDS_PERF_SEL_SE2_SH1_GDS_RD_OP = 85 +GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP = 86 +GDS_PERF_SEL_SE2_SH1_GDS_REL_OP = 87 +GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP = 88 +GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP = 89 +GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP = 90 +GDS_PERF_SEL_SE3_SH0_NORET = 91 +GDS_PERF_SEL_SE3_SH0_RET = 92 +GDS_PERF_SEL_SE3_SH0_ORD_CNT = 93 +GDS_PERF_SEL_SE3_SH0_2COMP_REQ = 94 +GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID = 95 +GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID = 96 +GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD = 97 +GDS_PERF_SEL_SE3_SH0_GDS_WR_OP = 98 +GDS_PERF_SEL_SE3_SH0_GDS_RD_OP = 99 +GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP = 100 +GDS_PERF_SEL_SE3_SH0_GDS_REL_OP = 101 +GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP = 102 +GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP = 103 +GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP = 104 +GDS_PERF_SEL_SE3_SH1_NORET = 105 +GDS_PERF_SEL_SE3_SH1_RET = 106 +GDS_PERF_SEL_SE3_SH1_ORD_CNT = 107 +GDS_PERF_SEL_SE3_SH1_2COMP_REQ = 108 +GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID = 109 +GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID = 110 +GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD = 111 +GDS_PERF_SEL_SE3_SH1_GDS_WR_OP = 112 +GDS_PERF_SEL_SE3_SH1_GDS_RD_OP = 113 +GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP = 114 +GDS_PERF_SEL_SE3_SH1_GDS_REL_OP = 115 +GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP = 116 +GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP = 117 +GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP = 118 +GDS_PERF_SEL_GWS_RELEASED = 119 +GDS_PERF_SEL_GWS_BYPASS = 120 +GDS_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL' +MEM_PWR_FORCE_CTRL__enumvalues = { + 0: 'NO_FORCE_REQUEST', + 1: 'FORCE_LIGHT_SLEEP_REQUEST', + 2: 'FORCE_DEEP_SLEEP_REQUEST', + 3: 'FORCE_SHUT_DOWN_REQUEST', +} +NO_FORCE_REQUEST = 0 +FORCE_LIGHT_SLEEP_REQUEST = 1 +FORCE_DEEP_SLEEP_REQUEST = 2 +FORCE_SHUT_DOWN_REQUEST = 3 +MEM_PWR_FORCE_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_FORCE_CTRL2' +MEM_PWR_FORCE_CTRL2__enumvalues = { + 0: 'NO_FORCE_REQ', + 1: 'FORCE_LIGHT_SLEEP_REQ', +} +NO_FORCE_REQ = 0 +FORCE_LIGHT_SLEEP_REQ = 1 +MEM_PWR_FORCE_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_DIS_CTRL' +MEM_PWR_DIS_CTRL__enumvalues = { + 0: 'ENABLE_MEM_PWR_CTRL', + 1: 'DISABLE_MEM_PWR_CTRL', +} +ENABLE_MEM_PWR_CTRL = 0 +DISABLE_MEM_PWR_CTRL = 1 +MEM_PWR_DIS_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL' +MEM_PWR_SEL_CTRL__enumvalues = { + 0: 'DYNAMIC_SHUT_DOWN_ENABLE', + 1: 'DYNAMIC_DEEP_SLEEP_ENABLE', + 2: 'DYNAMIC_LIGHT_SLEEP_ENABLE', +} +DYNAMIC_SHUT_DOWN_ENABLE = 0 +DYNAMIC_DEEP_SLEEP_ENABLE = 1 +DYNAMIC_LIGHT_SLEEP_ENABLE = 2 +MEM_PWR_SEL_CTRL = ctypes.c_uint32 # enum + +# values for enumeration 'MEM_PWR_SEL_CTRL2' +MEM_PWR_SEL_CTRL2__enumvalues = { + 0: 'DYNAMIC_DEEP_SLEEP_EN', + 1: 'DYNAMIC_LIGHT_SLEEP_EN', +} +DYNAMIC_DEEP_SLEEP_EN = 0 +DYNAMIC_LIGHT_SLEEP_EN = 1 +MEM_PWR_SEL_CTRL2 = ctypes.c_uint32 # enum + +# values for enumeration 'RowSize' +RowSize__enumvalues = { + 0: 'ADDR_CONFIG_1KB_ROW', + 1: 'ADDR_CONFIG_2KB_ROW', + 2: 'ADDR_CONFIG_4KB_ROW', +} +ADDR_CONFIG_1KB_ROW = 0 +ADDR_CONFIG_2KB_ROW = 1 +ADDR_CONFIG_4KB_ROW = 2 +RowSize = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceEndian' +SurfaceEndian__enumvalues = { + 0: 'ENDIAN_NONE', + 1: 'ENDIAN_8IN16', + 2: 'ENDIAN_8IN32', + 3: 'ENDIAN_8IN64', +} +ENDIAN_NONE = 0 +ENDIAN_8IN16 = 1 +ENDIAN_8IN32 = 2 +ENDIAN_8IN64 = 3 +SurfaceEndian = ctypes.c_uint32 # enum + +# values for enumeration 'ArrayMode' +ArrayMode__enumvalues = { + 0: 'ARRAY_LINEAR_GENERAL', + 1: 'ARRAY_LINEAR_ALIGNED', + 2: 'ARRAY_1D_TILED_THIN1', + 3: 'ARRAY_1D_TILED_THICK', + 4: 'ARRAY_2D_TILED_THIN1', + 5: 'ARRAY_PRT_TILED_THIN1', + 6: 'ARRAY_PRT_2D_TILED_THIN1', + 7: 'ARRAY_2D_TILED_THICK', + 8: 'ARRAY_2D_TILED_XTHICK', + 9: 'ARRAY_PRT_TILED_THICK', + 10: 'ARRAY_PRT_2D_TILED_THICK', + 11: 'ARRAY_PRT_3D_TILED_THIN1', + 12: 'ARRAY_3D_TILED_THIN1', + 13: 'ARRAY_3D_TILED_THICK', + 14: 'ARRAY_3D_TILED_XTHICK', + 15: 'ARRAY_PRT_3D_TILED_THICK', +} +ARRAY_LINEAR_GENERAL = 0 +ARRAY_LINEAR_ALIGNED = 1 +ARRAY_1D_TILED_THIN1 = 2 +ARRAY_1D_TILED_THICK = 3 +ARRAY_2D_TILED_THIN1 = 4 +ARRAY_PRT_TILED_THIN1 = 5 +ARRAY_PRT_2D_TILED_THIN1 = 6 +ARRAY_2D_TILED_THICK = 7 +ARRAY_2D_TILED_XTHICK = 8 +ARRAY_PRT_TILED_THICK = 9 +ARRAY_PRT_2D_TILED_THICK = 10 +ARRAY_PRT_3D_TILED_THIN1 = 11 +ARRAY_3D_TILED_THIN1 = 12 +ARRAY_3D_TILED_THICK = 13 +ARRAY_3D_TILED_XTHICK = 14 +ARRAY_PRT_3D_TILED_THICK = 15 +ArrayMode = ctypes.c_uint32 # enum + +# values for enumeration 'NumPipes' +NumPipes__enumvalues = { + 0: 'ADDR_CONFIG_1_PIPE', + 1: 'ADDR_CONFIG_2_PIPE', + 2: 'ADDR_CONFIG_4_PIPE', + 3: 'ADDR_CONFIG_8_PIPE', + 4: 'ADDR_CONFIG_16_PIPE', + 5: 'ADDR_CONFIG_32_PIPE', +} +ADDR_CONFIG_1_PIPE = 0 +ADDR_CONFIG_2_PIPE = 1 +ADDR_CONFIG_4_PIPE = 2 +ADDR_CONFIG_8_PIPE = 3 +ADDR_CONFIG_16_PIPE = 4 +ADDR_CONFIG_32_PIPE = 5 +NumPipes = ctypes.c_uint32 # enum + +# values for enumeration 'NumBanksConfig' +NumBanksConfig__enumvalues = { + 0: 'ADDR_CONFIG_1_BANK', + 1: 'ADDR_CONFIG_2_BANK', + 2: 'ADDR_CONFIG_4_BANK', + 3: 'ADDR_CONFIG_8_BANK', + 4: 'ADDR_CONFIG_16_BANK', +} +ADDR_CONFIG_1_BANK = 0 +ADDR_CONFIG_2_BANK = 1 +ADDR_CONFIG_4_BANK = 2 +ADDR_CONFIG_8_BANK = 3 +ADDR_CONFIG_16_BANK = 4 +NumBanksConfig = ctypes.c_uint32 # enum + +# values for enumeration 'PipeInterleaveSize' +PipeInterleaveSize__enumvalues = { + 0: 'ADDR_CONFIG_PIPE_INTERLEAVE_256B', + 1: 'ADDR_CONFIG_PIPE_INTERLEAVE_512B', + 2: 'ADDR_CONFIG_PIPE_INTERLEAVE_1KB', + 3: 'ADDR_CONFIG_PIPE_INTERLEAVE_2KB', +} +ADDR_CONFIG_PIPE_INTERLEAVE_256B = 0 +ADDR_CONFIG_PIPE_INTERLEAVE_512B = 1 +ADDR_CONFIG_PIPE_INTERLEAVE_1KB = 2 +ADDR_CONFIG_PIPE_INTERLEAVE_2KB = 3 +PipeInterleaveSize = ctypes.c_uint32 # enum + +# values for enumeration 'BankInterleaveSize' +BankInterleaveSize__enumvalues = { + 0: 'ADDR_CONFIG_BANK_INTERLEAVE_1', + 1: 'ADDR_CONFIG_BANK_INTERLEAVE_2', + 2: 'ADDR_CONFIG_BANK_INTERLEAVE_4', + 3: 'ADDR_CONFIG_BANK_INTERLEAVE_8', +} +ADDR_CONFIG_BANK_INTERLEAVE_1 = 0 +ADDR_CONFIG_BANK_INTERLEAVE_2 = 1 +ADDR_CONFIG_BANK_INTERLEAVE_4 = 2 +ADDR_CONFIG_BANK_INTERLEAVE_8 = 3 +BankInterleaveSize = ctypes.c_uint32 # enum + +# values for enumeration 'NumShaderEngines' +NumShaderEngines__enumvalues = { + 0: 'ADDR_CONFIG_1_SHADER_ENGINE', + 1: 'ADDR_CONFIG_2_SHADER_ENGINE', + 2: 'ADDR_CONFIG_4_SHADER_ENGINE', + 3: 'ADDR_CONFIG_8_SHADER_ENGINE', +} +ADDR_CONFIG_1_SHADER_ENGINE = 0 +ADDR_CONFIG_2_SHADER_ENGINE = 1 +ADDR_CONFIG_4_SHADER_ENGINE = 2 +ADDR_CONFIG_8_SHADER_ENGINE = 3 +NumShaderEngines = ctypes.c_uint32 # enum + +# values for enumeration 'NumRbPerShaderEngine' +NumRbPerShaderEngine__enumvalues = { + 0: 'ADDR_CONFIG_1_RB_PER_SHADER_ENGINE', + 1: 'ADDR_CONFIG_2_RB_PER_SHADER_ENGINE', + 2: 'ADDR_CONFIG_4_RB_PER_SHADER_ENGINE', +} +ADDR_CONFIG_1_RB_PER_SHADER_ENGINE = 0 +ADDR_CONFIG_2_RB_PER_SHADER_ENGINE = 1 +ADDR_CONFIG_4_RB_PER_SHADER_ENGINE = 2 +NumRbPerShaderEngine = ctypes.c_uint32 # enum + +# values for enumeration 'NumGPUs' +NumGPUs__enumvalues = { + 0: 'ADDR_CONFIG_1_GPU', + 1: 'ADDR_CONFIG_2_GPU', + 2: 'ADDR_CONFIG_4_GPU', + 3: 'ADDR_CONFIG_8_GPU', +} +ADDR_CONFIG_1_GPU = 0 +ADDR_CONFIG_2_GPU = 1 +ADDR_CONFIG_4_GPU = 2 +ADDR_CONFIG_8_GPU = 3 +NumGPUs = ctypes.c_uint32 # enum + +# values for enumeration 'NumMaxCompressedFragments' +NumMaxCompressedFragments__enumvalues = { + 0: 'ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS', + 1: 'ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS', + 2: 'ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS', + 3: 'ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS', +} +ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS = 0 +ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS = 1 +ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS = 2 +ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS = 3 +NumMaxCompressedFragments = ctypes.c_uint32 # enum + +# values for enumeration 'ShaderEngineTileSize' +ShaderEngineTileSize__enumvalues = { + 0: 'ADDR_CONFIG_SE_TILE_16', + 1: 'ADDR_CONFIG_SE_TILE_32', +} +ADDR_CONFIG_SE_TILE_16 = 0 +ADDR_CONFIG_SE_TILE_32 = 1 +ShaderEngineTileSize = ctypes.c_uint32 # enum + +# values for enumeration 'MultiGPUTileSize' +MultiGPUTileSize__enumvalues = { + 0: 'ADDR_CONFIG_GPU_TILE_16', + 1: 'ADDR_CONFIG_GPU_TILE_32', + 2: 'ADDR_CONFIG_GPU_TILE_64', + 3: 'ADDR_CONFIG_GPU_TILE_128', +} +ADDR_CONFIG_GPU_TILE_16 = 0 +ADDR_CONFIG_GPU_TILE_32 = 1 +ADDR_CONFIG_GPU_TILE_64 = 2 +ADDR_CONFIG_GPU_TILE_128 = 3 +MultiGPUTileSize = ctypes.c_uint32 # enum + +# values for enumeration 'NumLowerPipes' +NumLowerPipes__enumvalues = { + 0: 'ADDR_CONFIG_1_LOWER_PIPES', + 1: 'ADDR_CONFIG_2_LOWER_PIPES', +} +ADDR_CONFIG_1_LOWER_PIPES = 0 +ADDR_CONFIG_2_LOWER_PIPES = 1 +NumLowerPipes = ctypes.c_uint32 # enum + +# values for enumeration 'ColorTransform' +ColorTransform__enumvalues = { + 0: 'DCC_CT_AUTO', + 1: 'DCC_CT_NONE', + 2: 'ABGR_TO_A_BG_G_RB', + 3: 'BGRA_TO_BG_G_RB_A', +} +DCC_CT_AUTO = 0 +DCC_CT_NONE = 1 +ABGR_TO_A_BG_G_RB = 2 +BGRA_TO_BG_G_RB_A = 3 +ColorTransform = ctypes.c_uint32 # enum + +# values for enumeration 'CompareRef' +CompareRef__enumvalues = { + 0: 'REF_NEVER', + 1: 'REF_LESS', + 2: 'REF_EQUAL', + 3: 'REF_LEQUAL', + 4: 'REF_GREATER', + 5: 'REF_NOTEQUAL', + 6: 'REF_GEQUAL', + 7: 'REF_ALWAYS', +} +REF_NEVER = 0 +REF_LESS = 1 +REF_EQUAL = 2 +REF_LEQUAL = 3 +REF_GREATER = 4 +REF_NOTEQUAL = 5 +REF_GEQUAL = 6 +REF_ALWAYS = 7 +CompareRef = ctypes.c_uint32 # enum + +# values for enumeration 'ReadSize' +ReadSize__enumvalues = { + 0: 'READ_256_BITS', + 1: 'READ_512_BITS', +} +READ_256_BITS = 0 +READ_512_BITS = 1 +ReadSize = ctypes.c_uint32 # enum + +# values for enumeration 'DepthFormat' +DepthFormat__enumvalues = { + 0: 'DEPTH_INVALID', + 1: 'DEPTH_16', + 2: 'DEPTH_X8_24', + 3: 'DEPTH_8_24', + 4: 'DEPTH_X8_24_FLOAT', + 5: 'DEPTH_8_24_FLOAT', + 6: 'DEPTH_32_FLOAT', + 7: 'DEPTH_X24_8_32_FLOAT', +} +DEPTH_INVALID = 0 +DEPTH_16 = 1 +DEPTH_X8_24 = 2 +DEPTH_8_24 = 3 +DEPTH_X8_24_FLOAT = 4 +DEPTH_8_24_FLOAT = 5 +DEPTH_32_FLOAT = 6 +DEPTH_X24_8_32_FLOAT = 7 +DepthFormat = ctypes.c_uint32 # enum + +# values for enumeration 'ZFormat' +ZFormat__enumvalues = { + 0: 'Z_INVALID', + 1: 'Z_16', + 2: 'Z_24', + 3: 'Z_32_FLOAT', +} +Z_INVALID = 0 +Z_16 = 1 +Z_24 = 2 +Z_32_FLOAT = 3 +ZFormat = ctypes.c_uint32 # enum + +# values for enumeration 'StencilFormat' +StencilFormat__enumvalues = { + 0: 'STENCIL_INVALID', + 1: 'STENCIL_8', +} +STENCIL_INVALID = 0 +STENCIL_8 = 1 +StencilFormat = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskMode' +CmaskMode__enumvalues = { + 0: 'CMASK_CLEAR_NONE', + 1: 'CMASK_CLEAR_ONE', + 2: 'CMASK_CLEAR_ALL', + 3: 'CMASK_ANY_EXPANDED', + 4: 'CMASK_ALPHA0_FRAG1', + 5: 'CMASK_ALPHA0_FRAG2', + 6: 'CMASK_ALPHA0_FRAG4', + 7: 'CMASK_ALPHA0_FRAGS', + 8: 'CMASK_ALPHA1_FRAG1', + 9: 'CMASK_ALPHA1_FRAG2', + 10: 'CMASK_ALPHA1_FRAG4', + 11: 'CMASK_ALPHA1_FRAGS', + 12: 'CMASK_ALPHAX_FRAG1', + 13: 'CMASK_ALPHAX_FRAG2', + 14: 'CMASK_ALPHAX_FRAG4', + 15: 'CMASK_ALPHAX_FRAGS', +} +CMASK_CLEAR_NONE = 0 +CMASK_CLEAR_ONE = 1 +CMASK_CLEAR_ALL = 2 +CMASK_ANY_EXPANDED = 3 +CMASK_ALPHA0_FRAG1 = 4 +CMASK_ALPHA0_FRAG2 = 5 +CMASK_ALPHA0_FRAG4 = 6 +CMASK_ALPHA0_FRAGS = 7 +CMASK_ALPHA1_FRAG1 = 8 +CMASK_ALPHA1_FRAG2 = 9 +CMASK_ALPHA1_FRAG4 = 10 +CMASK_ALPHA1_FRAGS = 11 +CMASK_ALPHAX_FRAG1 = 12 +CMASK_ALPHAX_FRAG2 = 13 +CMASK_ALPHAX_FRAG4 = 14 +CMASK_ALPHAX_FRAGS = 15 +CmaskMode = ctypes.c_uint32 # enum + +# values for enumeration 'QuadExportFormat' +QuadExportFormat__enumvalues = { + 0: 'EXPORT_UNUSED', + 1: 'EXPORT_32_R', + 2: 'EXPORT_32_GR', + 3: 'EXPORT_32_AR', + 4: 'EXPORT_FP16_ABGR', + 5: 'EXPORT_UNSIGNED16_ABGR', + 6: 'EXPORT_SIGNED16_ABGR', + 7: 'EXPORT_32_ABGR', + 8: 'EXPORT_32BPP_8PIX', + 9: 'EXPORT_16_16_UNSIGNED_8PIX', + 10: 'EXPORT_16_16_SIGNED_8PIX', + 11: 'EXPORT_16_16_FLOAT_8PIX', +} +EXPORT_UNUSED = 0 +EXPORT_32_R = 1 +EXPORT_32_GR = 2 +EXPORT_32_AR = 3 +EXPORT_FP16_ABGR = 4 +EXPORT_UNSIGNED16_ABGR = 5 +EXPORT_SIGNED16_ABGR = 6 +EXPORT_32_ABGR = 7 +EXPORT_32BPP_8PIX = 8 +EXPORT_16_16_UNSIGNED_8PIX = 9 +EXPORT_16_16_SIGNED_8PIX = 10 +EXPORT_16_16_FLOAT_8PIX = 11 +QuadExportFormat = ctypes.c_uint32 # enum + +# values for enumeration 'QuadExportFormatOld' +QuadExportFormatOld__enumvalues = { + 0: 'EXPORT_4P_32BPC_ABGR', + 1: 'EXPORT_4P_16BPC_ABGR', + 2: 'EXPORT_4P_32BPC_GR', + 3: 'EXPORT_4P_32BPC_AR', + 4: 'EXPORT_2P_32BPC_ABGR', + 5: 'EXPORT_8P_32BPC_R', +} +EXPORT_4P_32BPC_ABGR = 0 +EXPORT_4P_16BPC_ABGR = 1 +EXPORT_4P_32BPC_GR = 2 +EXPORT_4P_32BPC_AR = 3 +EXPORT_2P_32BPC_ABGR = 4 +EXPORT_8P_32BPC_R = 5 +QuadExportFormatOld = ctypes.c_uint32 # enum + +# values for enumeration 'ColorFormat' +ColorFormat__enumvalues = { + 0: 'COLOR_INVALID', + 1: 'COLOR_8', + 2: 'COLOR_16', + 3: 'COLOR_8_8', + 4: 'COLOR_32', + 5: 'COLOR_16_16', + 6: 'COLOR_10_11_11', + 7: 'COLOR_11_11_10', + 8: 'COLOR_10_10_10_2', + 9: 'COLOR_2_10_10_10', + 10: 'COLOR_8_8_8_8', + 11: 'COLOR_32_32', + 12: 'COLOR_16_16_16_16', + 13: 'COLOR_RESERVED_13', + 14: 'COLOR_32_32_32_32', + 15: 'COLOR_RESERVED_15', + 16: 'COLOR_5_6_5', + 17: 'COLOR_1_5_5_5', + 18: 'COLOR_5_5_5_1', + 19: 'COLOR_4_4_4_4', + 20: 'COLOR_8_24', + 21: 'COLOR_24_8', + 22: 'COLOR_X24_8_32_FLOAT', + 23: 'COLOR_RESERVED_23', + 24: 'COLOR_RESERVED_24', + 25: 'COLOR_RESERVED_25', + 26: 'COLOR_RESERVED_26', + 27: 'COLOR_RESERVED_27', + 28: 'COLOR_RESERVED_28', + 29: 'COLOR_RESERVED_29', + 30: 'COLOR_RESERVED_30', + 31: 'COLOR_2_10_10_10_6E4', +} +COLOR_INVALID = 0 +COLOR_8 = 1 +COLOR_16 = 2 +COLOR_8_8 = 3 +COLOR_32 = 4 +COLOR_16_16 = 5 +COLOR_10_11_11 = 6 +COLOR_11_11_10 = 7 +COLOR_10_10_10_2 = 8 +COLOR_2_10_10_10 = 9 +COLOR_8_8_8_8 = 10 +COLOR_32_32 = 11 +COLOR_16_16_16_16 = 12 +COLOR_RESERVED_13 = 13 +COLOR_32_32_32_32 = 14 +COLOR_RESERVED_15 = 15 +COLOR_5_6_5 = 16 +COLOR_1_5_5_5 = 17 +COLOR_5_5_5_1 = 18 +COLOR_4_4_4_4 = 19 +COLOR_8_24 = 20 +COLOR_24_8 = 21 +COLOR_X24_8_32_FLOAT = 22 +COLOR_RESERVED_23 = 23 +COLOR_RESERVED_24 = 24 +COLOR_RESERVED_25 = 25 +COLOR_RESERVED_26 = 26 +COLOR_RESERVED_27 = 27 +COLOR_RESERVED_28 = 28 +COLOR_RESERVED_29 = 29 +COLOR_RESERVED_30 = 30 +COLOR_2_10_10_10_6E4 = 31 +ColorFormat = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceFormat' +SurfaceFormat__enumvalues = { + 0: 'FMT_INVALID', + 1: 'FMT_8', + 2: 'FMT_16', + 3: 'FMT_8_8', + 4: 'FMT_32', + 5: 'FMT_16_16', + 6: 'FMT_10_11_11', + 7: 'FMT_11_11_10', + 8: 'FMT_10_10_10_2', + 9: 'FMT_2_10_10_10', + 10: 'FMT_8_8_8_8', + 11: 'FMT_32_32', + 12: 'FMT_16_16_16_16', + 13: 'FMT_32_32_32', + 14: 'FMT_32_32_32_32', + 15: 'FMT_RESERVED_4', + 16: 'FMT_5_6_5', + 17: 'FMT_1_5_5_5', + 18: 'FMT_5_5_5_1', + 19: 'FMT_4_4_4_4', + 20: 'FMT_8_24', + 21: 'FMT_24_8', + 22: 'FMT_X24_8_32_FLOAT', + 23: 'FMT_RESERVED_33', + 24: 'FMT_11_11_10_FLOAT', + 25: 'FMT_16_FLOAT', + 26: 'FMT_32_FLOAT', + 27: 'FMT_16_16_FLOAT', + 28: 'FMT_8_24_FLOAT', + 29: 'FMT_24_8_FLOAT', + 30: 'FMT_32_32_FLOAT', + 31: 'FMT_10_11_11_FLOAT', + 32: 'FMT_16_16_16_16_FLOAT', + 33: 'FMT_3_3_2', + 34: 'FMT_6_5_5', + 35: 'FMT_32_32_32_32_FLOAT', + 36: 'FMT_RESERVED_36', + 37: 'FMT_1', + 38: 'FMT_1_REVERSED', + 39: 'FMT_GB_GR', + 40: 'FMT_BG_RG', + 41: 'FMT_32_AS_8', + 42: 'FMT_32_AS_8_8', + 43: 'FMT_5_9_9_9_SHAREDEXP', + 44: 'FMT_8_8_8', + 45: 'FMT_16_16_16', + 46: 'FMT_16_16_16_FLOAT', + 47: 'FMT_4_4', + 48: 'FMT_32_32_32_FLOAT', + 49: 'FMT_BC1', + 50: 'FMT_BC2', + 51: 'FMT_BC3', + 52: 'FMT_BC4', + 53: 'FMT_BC5', + 54: 'FMT_BC6', + 55: 'FMT_BC7', + 56: 'FMT_32_AS_32_32_32_32', + 57: 'FMT_APC3', + 58: 'FMT_APC4', + 59: 'FMT_APC5', + 60: 'FMT_APC6', + 61: 'FMT_APC7', + 62: 'FMT_CTX1', + 63: 'FMT_RESERVED_63', +} +FMT_INVALID = 0 +FMT_8 = 1 +FMT_16 = 2 +FMT_8_8 = 3 +FMT_32 = 4 +FMT_16_16 = 5 +FMT_10_11_11 = 6 +FMT_11_11_10 = 7 +FMT_10_10_10_2 = 8 +FMT_2_10_10_10 = 9 +FMT_8_8_8_8 = 10 +FMT_32_32 = 11 +FMT_16_16_16_16 = 12 +FMT_32_32_32 = 13 +FMT_32_32_32_32 = 14 +FMT_RESERVED_4 = 15 +FMT_5_6_5 = 16 +FMT_1_5_5_5 = 17 +FMT_5_5_5_1 = 18 +FMT_4_4_4_4 = 19 +FMT_8_24 = 20 +FMT_24_8 = 21 +FMT_X24_8_32_FLOAT = 22 +FMT_RESERVED_33 = 23 +FMT_11_11_10_FLOAT = 24 +FMT_16_FLOAT = 25 +FMT_32_FLOAT = 26 +FMT_16_16_FLOAT = 27 +FMT_8_24_FLOAT = 28 +FMT_24_8_FLOAT = 29 +FMT_32_32_FLOAT = 30 +FMT_10_11_11_FLOAT = 31 +FMT_16_16_16_16_FLOAT = 32 +FMT_3_3_2 = 33 +FMT_6_5_5 = 34 +FMT_32_32_32_32_FLOAT = 35 +FMT_RESERVED_36 = 36 +FMT_1 = 37 +FMT_1_REVERSED = 38 +FMT_GB_GR = 39 +FMT_BG_RG = 40 +FMT_32_AS_8 = 41 +FMT_32_AS_8_8 = 42 +FMT_5_9_9_9_SHAREDEXP = 43 +FMT_8_8_8 = 44 +FMT_16_16_16 = 45 +FMT_16_16_16_FLOAT = 46 +FMT_4_4 = 47 +FMT_32_32_32_FLOAT = 48 +FMT_BC1 = 49 +FMT_BC2 = 50 +FMT_BC3 = 51 +FMT_BC4 = 52 +FMT_BC5 = 53 +FMT_BC6 = 54 +FMT_BC7 = 55 +FMT_32_AS_32_32_32_32 = 56 +FMT_APC3 = 57 +FMT_APC4 = 58 +FMT_APC5 = 59 +FMT_APC6 = 60 +FMT_APC7 = 61 +FMT_CTX1 = 62 +FMT_RESERVED_63 = 63 +SurfaceFormat = ctypes.c_uint32 # enum + +# values for enumeration 'BUF_DATA_FORMAT' +BUF_DATA_FORMAT__enumvalues = { + 0: 'BUF_DATA_FORMAT_INVALID', + 1: 'BUF_DATA_FORMAT_8', + 2: 'BUF_DATA_FORMAT_16', + 3: 'BUF_DATA_FORMAT_8_8', + 4: 'BUF_DATA_FORMAT_32', + 5: 'BUF_DATA_FORMAT_16_16', + 6: 'BUF_DATA_FORMAT_10_11_11', + 7: 'BUF_DATA_FORMAT_11_11_10', + 8: 'BUF_DATA_FORMAT_10_10_10_2', + 9: 'BUF_DATA_FORMAT_2_10_10_10', + 10: 'BUF_DATA_FORMAT_8_8_8_8', + 11: 'BUF_DATA_FORMAT_32_32', + 12: 'BUF_DATA_FORMAT_16_16_16_16', + 13: 'BUF_DATA_FORMAT_32_32_32', + 14: 'BUF_DATA_FORMAT_32_32_32_32', + 15: 'BUF_DATA_FORMAT_RESERVED_15', +} +BUF_DATA_FORMAT_INVALID = 0 +BUF_DATA_FORMAT_8 = 1 +BUF_DATA_FORMAT_16 = 2 +BUF_DATA_FORMAT_8_8 = 3 +BUF_DATA_FORMAT_32 = 4 +BUF_DATA_FORMAT_16_16 = 5 +BUF_DATA_FORMAT_10_11_11 = 6 +BUF_DATA_FORMAT_11_11_10 = 7 +BUF_DATA_FORMAT_10_10_10_2 = 8 +BUF_DATA_FORMAT_2_10_10_10 = 9 +BUF_DATA_FORMAT_8_8_8_8 = 10 +BUF_DATA_FORMAT_32_32 = 11 +BUF_DATA_FORMAT_16_16_16_16 = 12 +BUF_DATA_FORMAT_32_32_32 = 13 +BUF_DATA_FORMAT_32_32_32_32 = 14 +BUF_DATA_FORMAT_RESERVED_15 = 15 +BUF_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_DATA_FORMAT' +IMG_DATA_FORMAT__enumvalues = { + 0: 'IMG_DATA_FORMAT_INVALID', + 1: 'IMG_DATA_FORMAT_8', + 2: 'IMG_DATA_FORMAT_16', + 3: 'IMG_DATA_FORMAT_8_8', + 4: 'IMG_DATA_FORMAT_32', + 5: 'IMG_DATA_FORMAT_16_16', + 6: 'IMG_DATA_FORMAT_10_11_11', + 7: 'IMG_DATA_FORMAT_11_11_10', + 8: 'IMG_DATA_FORMAT_10_10_10_2', + 9: 'IMG_DATA_FORMAT_2_10_10_10', + 10: 'IMG_DATA_FORMAT_8_8_8_8', + 11: 'IMG_DATA_FORMAT_32_32', + 12: 'IMG_DATA_FORMAT_16_16_16_16', + 13: 'IMG_DATA_FORMAT_32_32_32', + 14: 'IMG_DATA_FORMAT_32_32_32_32', + 15: 'IMG_DATA_FORMAT_RESERVED_15', + 16: 'IMG_DATA_FORMAT_5_6_5', + 17: 'IMG_DATA_FORMAT_1_5_5_5', + 18: 'IMG_DATA_FORMAT_5_5_5_1', + 19: 'IMG_DATA_FORMAT_4_4_4_4', + 20: 'IMG_DATA_FORMAT_8_24', + 21: 'IMG_DATA_FORMAT_24_8', + 22: 'IMG_DATA_FORMAT_X24_8_32', + 23: 'IMG_DATA_FORMAT_8_AS_8_8_8_8', + 24: 'IMG_DATA_FORMAT_ETC2_RGB', + 25: 'IMG_DATA_FORMAT_ETC2_RGBA', + 26: 'IMG_DATA_FORMAT_ETC2_R', + 27: 'IMG_DATA_FORMAT_ETC2_RG', + 28: 'IMG_DATA_FORMAT_ETC2_RGBA1', + 29: 'IMG_DATA_FORMAT_RESERVED_29', + 30: 'IMG_DATA_FORMAT_RESERVED_30', + 31: 'IMG_DATA_FORMAT_6E4', + 32: 'IMG_DATA_FORMAT_GB_GR', + 33: 'IMG_DATA_FORMAT_BG_RG', + 34: 'IMG_DATA_FORMAT_5_9_9_9', + 35: 'IMG_DATA_FORMAT_BC1', + 36: 'IMG_DATA_FORMAT_BC2', + 37: 'IMG_DATA_FORMAT_BC3', + 38: 'IMG_DATA_FORMAT_BC4', + 39: 'IMG_DATA_FORMAT_BC5', + 40: 'IMG_DATA_FORMAT_BC6', + 41: 'IMG_DATA_FORMAT_BC7', + 42: 'IMG_DATA_FORMAT_16_AS_32_32', + 43: 'IMG_DATA_FORMAT_16_AS_16_16_16_16', + 44: 'IMG_DATA_FORMAT_16_AS_32_32_32_32', + 45: 'IMG_DATA_FORMAT_FMASK', + 46: 'IMG_DATA_FORMAT_ASTC_2D_LDR', + 47: 'IMG_DATA_FORMAT_ASTC_2D_HDR', + 48: 'IMG_DATA_FORMAT_ASTC_2D_LDR_SRGB', + 49: 'IMG_DATA_FORMAT_ASTC_3D_LDR', + 50: 'IMG_DATA_FORMAT_ASTC_3D_HDR', + 51: 'IMG_DATA_FORMAT_ASTC_3D_LDR_SRGB', + 52: 'IMG_DATA_FORMAT_N_IN_16', + 53: 'IMG_DATA_FORMAT_N_IN_16_16', + 54: 'IMG_DATA_FORMAT_N_IN_16_16_16_16', + 55: 'IMG_DATA_FORMAT_N_IN_16_AS_16_16_16_16', + 56: 'IMG_DATA_FORMAT_RESERVED_56', + 57: 'IMG_DATA_FORMAT_4_4', + 58: 'IMG_DATA_FORMAT_6_5_5', + 59: 'IMG_DATA_FORMAT_RESERVED_59', + 60: 'IMG_DATA_FORMAT_RESERVED_60', + 61: 'IMG_DATA_FORMAT_8_AS_32', + 62: 'IMG_DATA_FORMAT_8_AS_32_32', + 63: 'IMG_DATA_FORMAT_32_AS_32_32_32_32', +} +IMG_DATA_FORMAT_INVALID = 0 +IMG_DATA_FORMAT_8 = 1 +IMG_DATA_FORMAT_16 = 2 +IMG_DATA_FORMAT_8_8 = 3 +IMG_DATA_FORMAT_32 = 4 +IMG_DATA_FORMAT_16_16 = 5 +IMG_DATA_FORMAT_10_11_11 = 6 +IMG_DATA_FORMAT_11_11_10 = 7 +IMG_DATA_FORMAT_10_10_10_2 = 8 +IMG_DATA_FORMAT_2_10_10_10 = 9 +IMG_DATA_FORMAT_8_8_8_8 = 10 +IMG_DATA_FORMAT_32_32 = 11 +IMG_DATA_FORMAT_16_16_16_16 = 12 +IMG_DATA_FORMAT_32_32_32 = 13 +IMG_DATA_FORMAT_32_32_32_32 = 14 +IMG_DATA_FORMAT_RESERVED_15 = 15 +IMG_DATA_FORMAT_5_6_5 = 16 +IMG_DATA_FORMAT_1_5_5_5 = 17 +IMG_DATA_FORMAT_5_5_5_1 = 18 +IMG_DATA_FORMAT_4_4_4_4 = 19 +IMG_DATA_FORMAT_8_24 = 20 +IMG_DATA_FORMAT_24_8 = 21 +IMG_DATA_FORMAT_X24_8_32 = 22 +IMG_DATA_FORMAT_8_AS_8_8_8_8 = 23 +IMG_DATA_FORMAT_ETC2_RGB = 24 +IMG_DATA_FORMAT_ETC2_RGBA = 25 +IMG_DATA_FORMAT_ETC2_R = 26 +IMG_DATA_FORMAT_ETC2_RG = 27 +IMG_DATA_FORMAT_ETC2_RGBA1 = 28 +IMG_DATA_FORMAT_RESERVED_29 = 29 +IMG_DATA_FORMAT_RESERVED_30 = 30 +IMG_DATA_FORMAT_6E4 = 31 +IMG_DATA_FORMAT_GB_GR = 32 +IMG_DATA_FORMAT_BG_RG = 33 +IMG_DATA_FORMAT_5_9_9_9 = 34 +IMG_DATA_FORMAT_BC1 = 35 +IMG_DATA_FORMAT_BC2 = 36 +IMG_DATA_FORMAT_BC3 = 37 +IMG_DATA_FORMAT_BC4 = 38 +IMG_DATA_FORMAT_BC5 = 39 +IMG_DATA_FORMAT_BC6 = 40 +IMG_DATA_FORMAT_BC7 = 41 +IMG_DATA_FORMAT_16_AS_32_32 = 42 +IMG_DATA_FORMAT_16_AS_16_16_16_16 = 43 +IMG_DATA_FORMAT_16_AS_32_32_32_32 = 44 +IMG_DATA_FORMAT_FMASK = 45 +IMG_DATA_FORMAT_ASTC_2D_LDR = 46 +IMG_DATA_FORMAT_ASTC_2D_HDR = 47 +IMG_DATA_FORMAT_ASTC_2D_LDR_SRGB = 48 +IMG_DATA_FORMAT_ASTC_3D_LDR = 49 +IMG_DATA_FORMAT_ASTC_3D_HDR = 50 +IMG_DATA_FORMAT_ASTC_3D_LDR_SRGB = 51 +IMG_DATA_FORMAT_N_IN_16 = 52 +IMG_DATA_FORMAT_N_IN_16_16 = 53 +IMG_DATA_FORMAT_N_IN_16_16_16_16 = 54 +IMG_DATA_FORMAT_N_IN_16_AS_16_16_16_16 = 55 +IMG_DATA_FORMAT_RESERVED_56 = 56 +IMG_DATA_FORMAT_4_4 = 57 +IMG_DATA_FORMAT_6_5_5 = 58 +IMG_DATA_FORMAT_RESERVED_59 = 59 +IMG_DATA_FORMAT_RESERVED_60 = 60 +IMG_DATA_FORMAT_8_AS_32 = 61 +IMG_DATA_FORMAT_8_AS_32_32 = 62 +IMG_DATA_FORMAT_32_AS_32_32_32_32 = 63 +IMG_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'BUF_NUM_FORMAT' +BUF_NUM_FORMAT__enumvalues = { + 0: 'BUF_NUM_FORMAT_UNORM', + 1: 'BUF_NUM_FORMAT_SNORM', + 2: 'BUF_NUM_FORMAT_USCALED', + 3: 'BUF_NUM_FORMAT_SSCALED', + 4: 'BUF_NUM_FORMAT_UINT', + 5: 'BUF_NUM_FORMAT_SINT', + 6: 'BUF_NUM_FORMAT_UNORM_UINT', + 7: 'BUF_NUM_FORMAT_FLOAT', +} +BUF_NUM_FORMAT_UNORM = 0 +BUF_NUM_FORMAT_SNORM = 1 +BUF_NUM_FORMAT_USCALED = 2 +BUF_NUM_FORMAT_SSCALED = 3 +BUF_NUM_FORMAT_UINT = 4 +BUF_NUM_FORMAT_SINT = 5 +BUF_NUM_FORMAT_UNORM_UINT = 6 +BUF_NUM_FORMAT_FLOAT = 7 +BUF_NUM_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT' +IMG_NUM_FORMAT__enumvalues = { + 0: 'IMG_NUM_FORMAT_UNORM', + 1: 'IMG_NUM_FORMAT_SNORM', + 2: 'IMG_NUM_FORMAT_USCALED', + 3: 'IMG_NUM_FORMAT_SSCALED', + 4: 'IMG_NUM_FORMAT_UINT', + 5: 'IMG_NUM_FORMAT_SINT', + 6: 'IMG_NUM_FORMAT_UNORM_UINT', + 7: 'IMG_NUM_FORMAT_FLOAT', + 8: 'IMG_NUM_FORMAT_RESERVED_8', + 9: 'IMG_NUM_FORMAT_SRGB', + 10: 'IMG_NUM_FORMAT_RESERVED_10', + 11: 'IMG_NUM_FORMAT_RESERVED_11', + 12: 'IMG_NUM_FORMAT_RESERVED_12', + 13: 'IMG_NUM_FORMAT_RESERVED_13', + 14: 'IMG_NUM_FORMAT_RESERVED_14', + 15: 'IMG_NUM_FORMAT_RESERVED_15', +} +IMG_NUM_FORMAT_UNORM = 0 +IMG_NUM_FORMAT_SNORM = 1 +IMG_NUM_FORMAT_USCALED = 2 +IMG_NUM_FORMAT_SSCALED = 3 +IMG_NUM_FORMAT_UINT = 4 +IMG_NUM_FORMAT_SINT = 5 +IMG_NUM_FORMAT_UNORM_UINT = 6 +IMG_NUM_FORMAT_FLOAT = 7 +IMG_NUM_FORMAT_RESERVED_8 = 8 +IMG_NUM_FORMAT_SRGB = 9 +IMG_NUM_FORMAT_RESERVED_10 = 10 +IMG_NUM_FORMAT_RESERVED_11 = 11 +IMG_NUM_FORMAT_RESERVED_12 = 12 +IMG_NUM_FORMAT_RESERVED_13 = 13 +IMG_NUM_FORMAT_RESERVED_14 = 14 +IMG_NUM_FORMAT_RESERVED_15 = 15 +IMG_NUM_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_FMASK' +IMG_NUM_FORMAT_FMASK__enumvalues = { + 0: 'IMG_NUM_FORMAT_FMASK_8_2_1', + 1: 'IMG_NUM_FORMAT_FMASK_8_4_1', + 2: 'IMG_NUM_FORMAT_FMASK_8_8_1', + 3: 'IMG_NUM_FORMAT_FMASK_8_2_2', + 4: 'IMG_NUM_FORMAT_FMASK_8_4_2', + 5: 'IMG_NUM_FORMAT_FMASK_8_4_4', + 6: 'IMG_NUM_FORMAT_FMASK_16_16_1', + 7: 'IMG_NUM_FORMAT_FMASK_16_8_2', + 8: 'IMG_NUM_FORMAT_FMASK_32_16_2', + 9: 'IMG_NUM_FORMAT_FMASK_32_8_4', + 10: 'IMG_NUM_FORMAT_FMASK_32_8_8', + 11: 'IMG_NUM_FORMAT_FMASK_64_16_4', + 12: 'IMG_NUM_FORMAT_FMASK_64_16_8', + 13: 'IMG_NUM_FORMAT_FMASK_RESERVED_13', + 14: 'IMG_NUM_FORMAT_FMASK_RESERVED_14', + 15: 'IMG_NUM_FORMAT_FMASK_RESERVED_15', +} +IMG_NUM_FORMAT_FMASK_8_2_1 = 0 +IMG_NUM_FORMAT_FMASK_8_4_1 = 1 +IMG_NUM_FORMAT_FMASK_8_8_1 = 2 +IMG_NUM_FORMAT_FMASK_8_2_2 = 3 +IMG_NUM_FORMAT_FMASK_8_4_2 = 4 +IMG_NUM_FORMAT_FMASK_8_4_4 = 5 +IMG_NUM_FORMAT_FMASK_16_16_1 = 6 +IMG_NUM_FORMAT_FMASK_16_8_2 = 7 +IMG_NUM_FORMAT_FMASK_32_16_2 = 8 +IMG_NUM_FORMAT_FMASK_32_8_4 = 9 +IMG_NUM_FORMAT_FMASK_32_8_8 = 10 +IMG_NUM_FORMAT_FMASK_64_16_4 = 11 +IMG_NUM_FORMAT_FMASK_64_16_8 = 12 +IMG_NUM_FORMAT_FMASK_RESERVED_13 = 13 +IMG_NUM_FORMAT_FMASK_RESERVED_14 = 14 +IMG_NUM_FORMAT_FMASK_RESERVED_15 = 15 +IMG_NUM_FORMAT_FMASK = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_N_IN_16' +IMG_NUM_FORMAT_N_IN_16__enumvalues = { + 0: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_0', + 1: 'IMG_NUM_FORMAT_N_IN_16_UNORM_10', + 2: 'IMG_NUM_FORMAT_N_IN_16_UNORM_9', + 3: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_3', + 4: 'IMG_NUM_FORMAT_N_IN_16_UINT_10', + 5: 'IMG_NUM_FORMAT_N_IN_16_UINT_9', + 6: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_6', + 7: 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10', + 8: 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9', + 9: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_9', + 10: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_10', + 11: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_11', + 12: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_12', + 13: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_13', + 14: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_14', + 15: 'IMG_NUM_FORMAT_N_IN_16_RESERVED_15', +} +IMG_NUM_FORMAT_N_IN_16_RESERVED_0 = 0 +IMG_NUM_FORMAT_N_IN_16_UNORM_10 = 1 +IMG_NUM_FORMAT_N_IN_16_UNORM_9 = 2 +IMG_NUM_FORMAT_N_IN_16_RESERVED_3 = 3 +IMG_NUM_FORMAT_N_IN_16_UINT_10 = 4 +IMG_NUM_FORMAT_N_IN_16_UINT_9 = 5 +IMG_NUM_FORMAT_N_IN_16_RESERVED_6 = 6 +IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10 = 7 +IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9 = 8 +IMG_NUM_FORMAT_N_IN_16_RESERVED_9 = 9 +IMG_NUM_FORMAT_N_IN_16_RESERVED_10 = 10 +IMG_NUM_FORMAT_N_IN_16_RESERVED_11 = 11 +IMG_NUM_FORMAT_N_IN_16_RESERVED_12 = 12 +IMG_NUM_FORMAT_N_IN_16_RESERVED_13 = 13 +IMG_NUM_FORMAT_N_IN_16_RESERVED_14 = 14 +IMG_NUM_FORMAT_N_IN_16_RESERVED_15 = 15 +IMG_NUM_FORMAT_N_IN_16 = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_ASTC_2D' +IMG_NUM_FORMAT_ASTC_2D__enumvalues = { + 0: 'IMG_NUM_FORMAT_ASTC_2D_4x4', + 1: 'IMG_NUM_FORMAT_ASTC_2D_5x4', + 2: 'IMG_NUM_FORMAT_ASTC_2D_5x5', + 3: 'IMG_NUM_FORMAT_ASTC_2D_6x5', + 4: 'IMG_NUM_FORMAT_ASTC_2D_6x6', + 5: 'IMG_NUM_FORMAT_ASTC_2D_8x5', + 6: 'IMG_NUM_FORMAT_ASTC_2D_8x6', + 7: 'IMG_NUM_FORMAT_ASTC_2D_8x8', + 8: 'IMG_NUM_FORMAT_ASTC_2D_10x5', + 9: 'IMG_NUM_FORMAT_ASTC_2D_10x6', + 10: 'IMG_NUM_FORMAT_ASTC_2D_10x8', + 11: 'IMG_NUM_FORMAT_ASTC_2D_10x10', + 12: 'IMG_NUM_FORMAT_ASTC_2D_12x10', + 13: 'IMG_NUM_FORMAT_ASTC_2D_12x12', + 14: 'IMG_NUM_FORMAT_ASTC_2D_RESERVED_14', + 15: 'IMG_NUM_FORMAT_ASTC_2D_RESERVED_15', +} +IMG_NUM_FORMAT_ASTC_2D_4x4 = 0 +IMG_NUM_FORMAT_ASTC_2D_5x4 = 1 +IMG_NUM_FORMAT_ASTC_2D_5x5 = 2 +IMG_NUM_FORMAT_ASTC_2D_6x5 = 3 +IMG_NUM_FORMAT_ASTC_2D_6x6 = 4 +IMG_NUM_FORMAT_ASTC_2D_8x5 = 5 +IMG_NUM_FORMAT_ASTC_2D_8x6 = 6 +IMG_NUM_FORMAT_ASTC_2D_8x8 = 7 +IMG_NUM_FORMAT_ASTC_2D_10x5 = 8 +IMG_NUM_FORMAT_ASTC_2D_10x6 = 9 +IMG_NUM_FORMAT_ASTC_2D_10x8 = 10 +IMG_NUM_FORMAT_ASTC_2D_10x10 = 11 +IMG_NUM_FORMAT_ASTC_2D_12x10 = 12 +IMG_NUM_FORMAT_ASTC_2D_12x12 = 13 +IMG_NUM_FORMAT_ASTC_2D_RESERVED_14 = 14 +IMG_NUM_FORMAT_ASTC_2D_RESERVED_15 = 15 +IMG_NUM_FORMAT_ASTC_2D = ctypes.c_uint32 # enum + +# values for enumeration 'IMG_NUM_FORMAT_ASTC_3D' +IMG_NUM_FORMAT_ASTC_3D__enumvalues = { + 0: 'IMG_NUM_FORMAT_ASTC_3D_3x3x3', + 1: 'IMG_NUM_FORMAT_ASTC_3D_4x3x3', + 2: 'IMG_NUM_FORMAT_ASTC_3D_4x4x3', + 3: 'IMG_NUM_FORMAT_ASTC_3D_4x4x4', + 4: 'IMG_NUM_FORMAT_ASTC_3D_5x4x4', + 5: 'IMG_NUM_FORMAT_ASTC_3D_5x5x4', + 6: 'IMG_NUM_FORMAT_ASTC_3D_5x5x5', + 7: 'IMG_NUM_FORMAT_ASTC_3D_6x5x5', + 8: 'IMG_NUM_FORMAT_ASTC_3D_6x6x5', + 9: 'IMG_NUM_FORMAT_ASTC_3D_6x6x6', + 10: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_10', + 11: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_11', + 12: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_12', + 13: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_13', + 14: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_14', + 15: 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_15', +} +IMG_NUM_FORMAT_ASTC_3D_3x3x3 = 0 +IMG_NUM_FORMAT_ASTC_3D_4x3x3 = 1 +IMG_NUM_FORMAT_ASTC_3D_4x4x3 = 2 +IMG_NUM_FORMAT_ASTC_3D_4x4x4 = 3 +IMG_NUM_FORMAT_ASTC_3D_5x4x4 = 4 +IMG_NUM_FORMAT_ASTC_3D_5x5x4 = 5 +IMG_NUM_FORMAT_ASTC_3D_5x5x5 = 6 +IMG_NUM_FORMAT_ASTC_3D_6x5x5 = 7 +IMG_NUM_FORMAT_ASTC_3D_6x6x5 = 8 +IMG_NUM_FORMAT_ASTC_3D_6x6x6 = 9 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_10 = 10 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_11 = 11 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_12 = 12 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_13 = 13 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_14 = 14 +IMG_NUM_FORMAT_ASTC_3D_RESERVED_15 = 15 +IMG_NUM_FORMAT_ASTC_3D = ctypes.c_uint32 # enum + +# values for enumeration 'TileType' +TileType__enumvalues = { + 0: 'ARRAY_COLOR_TILE', + 1: 'ARRAY_DEPTH_TILE', +} +ARRAY_COLOR_TILE = 0 +ARRAY_DEPTH_TILE = 1 +TileType = ctypes.c_uint32 # enum + +# values for enumeration 'NonDispTilingOrder' +NonDispTilingOrder__enumvalues = { + 0: 'ADDR_SURF_MICRO_TILING_DISPLAY', + 1: 'ADDR_SURF_MICRO_TILING_NON_DISPLAY', +} +ADDR_SURF_MICRO_TILING_DISPLAY = 0 +ADDR_SURF_MICRO_TILING_NON_DISPLAY = 1 +NonDispTilingOrder = ctypes.c_uint32 # enum + +# values for enumeration 'MicroTileMode' +MicroTileMode__enumvalues = { + 0: 'ADDR_SURF_DISPLAY_MICRO_TILING', + 1: 'ADDR_SURF_THIN_MICRO_TILING', + 2: 'ADDR_SURF_DEPTH_MICRO_TILING', + 3: 'ADDR_SURF_ROTATED_MICRO_TILING', + 4: 'ADDR_SURF_THICK_MICRO_TILING', +} +ADDR_SURF_DISPLAY_MICRO_TILING = 0 +ADDR_SURF_THIN_MICRO_TILING = 1 +ADDR_SURF_DEPTH_MICRO_TILING = 2 +ADDR_SURF_ROTATED_MICRO_TILING = 3 +ADDR_SURF_THICK_MICRO_TILING = 4 +MicroTileMode = ctypes.c_uint32 # enum + +# values for enumeration 'TileSplit' +TileSplit__enumvalues = { + 0: 'ADDR_SURF_TILE_SPLIT_64B', + 1: 'ADDR_SURF_TILE_SPLIT_128B', + 2: 'ADDR_SURF_TILE_SPLIT_256B', + 3: 'ADDR_SURF_TILE_SPLIT_512B', + 4: 'ADDR_SURF_TILE_SPLIT_1KB', + 5: 'ADDR_SURF_TILE_SPLIT_2KB', + 6: 'ADDR_SURF_TILE_SPLIT_4KB', +} +ADDR_SURF_TILE_SPLIT_64B = 0 +ADDR_SURF_TILE_SPLIT_128B = 1 +ADDR_SURF_TILE_SPLIT_256B = 2 +ADDR_SURF_TILE_SPLIT_512B = 3 +ADDR_SURF_TILE_SPLIT_1KB = 4 +ADDR_SURF_TILE_SPLIT_2KB = 5 +ADDR_SURF_TILE_SPLIT_4KB = 6 +TileSplit = ctypes.c_uint32 # enum + +# values for enumeration 'SampleSplit' +SampleSplit__enumvalues = { + 0: 'ADDR_SURF_SAMPLE_SPLIT_1', + 1: 'ADDR_SURF_SAMPLE_SPLIT_2', + 2: 'ADDR_SURF_SAMPLE_SPLIT_4', + 3: 'ADDR_SURF_SAMPLE_SPLIT_8', +} +ADDR_SURF_SAMPLE_SPLIT_1 = 0 +ADDR_SURF_SAMPLE_SPLIT_2 = 1 +ADDR_SURF_SAMPLE_SPLIT_4 = 2 +ADDR_SURF_SAMPLE_SPLIT_8 = 3 +SampleSplit = ctypes.c_uint32 # enum + +# values for enumeration 'PipeConfig' +PipeConfig__enumvalues = { + 0: 'ADDR_SURF_P2', + 1: 'ADDR_SURF_P2_RESERVED0', + 2: 'ADDR_SURF_P2_RESERVED1', + 3: 'ADDR_SURF_P2_RESERVED2', + 4: 'ADDR_SURF_P4_8x16', + 5: 'ADDR_SURF_P4_16x16', + 6: 'ADDR_SURF_P4_16x32', + 7: 'ADDR_SURF_P4_32x32', + 8: 'ADDR_SURF_P8_16x16_8x16', + 9: 'ADDR_SURF_P8_16x32_8x16', + 10: 'ADDR_SURF_P8_32x32_8x16', + 11: 'ADDR_SURF_P8_16x32_16x16', + 12: 'ADDR_SURF_P8_32x32_16x16', + 13: 'ADDR_SURF_P8_32x32_16x32', + 14: 'ADDR_SURF_P8_32x64_32x32', + 15: 'ADDR_SURF_P8_RESERVED0', + 16: 'ADDR_SURF_P16_32x32_8x16', + 17: 'ADDR_SURF_P16_32x32_16x16', +} +ADDR_SURF_P2 = 0 +ADDR_SURF_P2_RESERVED0 = 1 +ADDR_SURF_P2_RESERVED1 = 2 +ADDR_SURF_P2_RESERVED2 = 3 +ADDR_SURF_P4_8x16 = 4 +ADDR_SURF_P4_16x16 = 5 +ADDR_SURF_P4_16x32 = 6 +ADDR_SURF_P4_32x32 = 7 +ADDR_SURF_P8_16x16_8x16 = 8 +ADDR_SURF_P8_16x32_8x16 = 9 +ADDR_SURF_P8_32x32_8x16 = 10 +ADDR_SURF_P8_16x32_16x16 = 11 +ADDR_SURF_P8_32x32_16x16 = 12 +ADDR_SURF_P8_32x32_16x32 = 13 +ADDR_SURF_P8_32x64_32x32 = 14 +ADDR_SURF_P8_RESERVED0 = 15 +ADDR_SURF_P16_32x32_8x16 = 16 +ADDR_SURF_P16_32x32_16x16 = 17 +PipeConfig = ctypes.c_uint32 # enum + +# values for enumeration 'SeEnable' +SeEnable__enumvalues = { + 0: 'ADDR_CONFIG_DISABLE_SE', + 1: 'ADDR_CONFIG_ENABLE_SE', +} +ADDR_CONFIG_DISABLE_SE = 0 +ADDR_CONFIG_ENABLE_SE = 1 +SeEnable = ctypes.c_uint32 # enum + +# values for enumeration 'NumBanks' +NumBanks__enumvalues = { + 0: 'ADDR_SURF_2_BANK', + 1: 'ADDR_SURF_4_BANK', + 2: 'ADDR_SURF_8_BANK', + 3: 'ADDR_SURF_16_BANK', +} +ADDR_SURF_2_BANK = 0 +ADDR_SURF_4_BANK = 1 +ADDR_SURF_8_BANK = 2 +ADDR_SURF_16_BANK = 3 +NumBanks = ctypes.c_uint32 # enum + +# values for enumeration 'BankWidth' +BankWidth__enumvalues = { + 0: 'ADDR_SURF_BANK_WIDTH_1', + 1: 'ADDR_SURF_BANK_WIDTH_2', + 2: 'ADDR_SURF_BANK_WIDTH_4', + 3: 'ADDR_SURF_BANK_WIDTH_8', +} +ADDR_SURF_BANK_WIDTH_1 = 0 +ADDR_SURF_BANK_WIDTH_2 = 1 +ADDR_SURF_BANK_WIDTH_4 = 2 +ADDR_SURF_BANK_WIDTH_8 = 3 +BankWidth = ctypes.c_uint32 # enum + +# values for enumeration 'BankHeight' +BankHeight__enumvalues = { + 0: 'ADDR_SURF_BANK_HEIGHT_1', + 1: 'ADDR_SURF_BANK_HEIGHT_2', + 2: 'ADDR_SURF_BANK_HEIGHT_4', + 3: 'ADDR_SURF_BANK_HEIGHT_8', +} +ADDR_SURF_BANK_HEIGHT_1 = 0 +ADDR_SURF_BANK_HEIGHT_2 = 1 +ADDR_SURF_BANK_HEIGHT_4 = 2 +ADDR_SURF_BANK_HEIGHT_8 = 3 +BankHeight = ctypes.c_uint32 # enum + +# values for enumeration 'BankWidthHeight' +BankWidthHeight__enumvalues = { + 0: 'ADDR_SURF_BANK_WH_1', + 1: 'ADDR_SURF_BANK_WH_2', + 2: 'ADDR_SURF_BANK_WH_4', + 3: 'ADDR_SURF_BANK_WH_8', +} +ADDR_SURF_BANK_WH_1 = 0 +ADDR_SURF_BANK_WH_2 = 1 +ADDR_SURF_BANK_WH_4 = 2 +ADDR_SURF_BANK_WH_8 = 3 +BankWidthHeight = ctypes.c_uint32 # enum + +# values for enumeration 'MacroTileAspect' +MacroTileAspect__enumvalues = { + 0: 'ADDR_SURF_MACRO_ASPECT_1', + 1: 'ADDR_SURF_MACRO_ASPECT_2', + 2: 'ADDR_SURF_MACRO_ASPECT_4', + 3: 'ADDR_SURF_MACRO_ASPECT_8', +} +ADDR_SURF_MACRO_ASPECT_1 = 0 +ADDR_SURF_MACRO_ASPECT_2 = 1 +ADDR_SURF_MACRO_ASPECT_4 = 2 +ADDR_SURF_MACRO_ASPECT_8 = 3 +MacroTileAspect = ctypes.c_uint32 # enum + +# values for enumeration 'GATCL1RequestType' +GATCL1RequestType__enumvalues = { + 0: 'GATCL1_TYPE_NORMAL', + 1: 'GATCL1_TYPE_SHOOTDOWN', + 2: 'GATCL1_TYPE_BYPASS', +} +GATCL1_TYPE_NORMAL = 0 +GATCL1_TYPE_SHOOTDOWN = 1 +GATCL1_TYPE_BYPASS = 2 +GATCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1RequestType' +UTCL1RequestType__enumvalues = { + 0: 'UTCL1_TYPE_NORMAL', + 1: 'UTCL1_TYPE_SHOOTDOWN', + 2: 'UTCL1_TYPE_BYPASS', +} +UTCL1_TYPE_NORMAL = 0 +UTCL1_TYPE_SHOOTDOWN = 1 +UTCL1_TYPE_BYPASS = 2 +UTCL1RequestType = ctypes.c_uint32 # enum + +# values for enumeration 'UTCL1FaultType' +UTCL1FaultType__enumvalues = { + 0: 'UTCL1_XNACK_SUCCESS', + 1: 'UTCL1_XNACK_RETRY', + 2: 'UTCL1_XNACK_PRT', + 3: 'UTCL1_XNACK_NO_RETRY', +} +UTCL1_XNACK_SUCCESS = 0 +UTCL1_XNACK_RETRY = 1 +UTCL1_XNACK_PRT = 2 +UTCL1_XNACK_NO_RETRY = 3 +UTCL1FaultType = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_CACHE_POLICIES' +TCC_CACHE_POLICIES__enumvalues = { + 0: 'TCC_CACHE_POLICY_LRU', + 1: 'TCC_CACHE_POLICY_STREAM', +} +TCC_CACHE_POLICY_LRU = 0 +TCC_CACHE_POLICY_STREAM = 1 +TCC_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'MTYPE' +MTYPE__enumvalues = { + 0: 'MTYPE_NC', + 1: 'MTYPE_WC', + 1: 'MTYPE_RW', + 2: 'MTYPE_CC', + 3: 'MTYPE_UC', +} +MTYPE_NC = 0 +MTYPE_WC = 1 +MTYPE_RW = 1 +MTYPE_CC = 2 +MTYPE_UC = 3 +MTYPE = ctypes.c_uint32 # enum + +# values for enumeration 'RMI_CID' +RMI_CID__enumvalues = { + 0: 'RMI_CID_CC', + 1: 'RMI_CID_FC', + 2: 'RMI_CID_CM', + 3: 'RMI_CID_DC', + 4: 'RMI_CID_Z', + 5: 'RMI_CID_S', + 6: 'RMI_CID_TILE', + 7: 'RMI_CID_ZPCPSD', +} +RMI_CID_CC = 0 +RMI_CID_FC = 1 +RMI_CID_CM = 2 +RMI_CID_DC = 3 +RMI_CID_Z = 4 +RMI_CID_S = 5 +RMI_CID_TILE = 6 +RMI_CID_ZPCPSD = 7 +RMI_CID = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_COUNTER_MODE' +PERFMON_COUNTER_MODE__enumvalues = { + 0: 'PERFMON_COUNTER_MODE_ACCUM', + 1: 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 2: 'PERFMON_COUNTER_MODE_MAX', + 3: 'PERFMON_COUNTER_MODE_DIRTY', + 4: 'PERFMON_COUNTER_MODE_SAMPLE', + 5: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 6: 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 7: 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 8: 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 9: 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 15: 'PERFMON_COUNTER_MODE_RESERVED', +} +PERFMON_COUNTER_MODE_ACCUM = 0 +PERFMON_COUNTER_MODE_ACTIVE_CYCLES = 1 +PERFMON_COUNTER_MODE_MAX = 2 +PERFMON_COUNTER_MODE_DIRTY = 3 +PERFMON_COUNTER_MODE_SAMPLE = 4 +PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT = 5 +PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT = 6 +PERFMON_COUNTER_MODE_CYCLES_GE_HI = 7 +PERFMON_COUNTER_MODE_CYCLES_EQ_HI = 8 +PERFMON_COUNTER_MODE_INACTIVE_CYCLES = 9 +PERFMON_COUNTER_MODE_RESERVED = 15 +PERFMON_COUNTER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_SPM_MODE' +PERFMON_SPM_MODE__enumvalues = { + 0: 'PERFMON_SPM_MODE_OFF', + 1: 'PERFMON_SPM_MODE_16BIT_CLAMP', + 2: 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 3: 'PERFMON_SPM_MODE_32BIT_CLAMP', + 4: 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 5: 'PERFMON_SPM_MODE_RESERVED_5', + 6: 'PERFMON_SPM_MODE_RESERVED_6', + 7: 'PERFMON_SPM_MODE_RESERVED_7', + 8: 'PERFMON_SPM_MODE_TEST_MODE_0', + 9: 'PERFMON_SPM_MODE_TEST_MODE_1', + 10: 'PERFMON_SPM_MODE_TEST_MODE_2', +} +PERFMON_SPM_MODE_OFF = 0 +PERFMON_SPM_MODE_16BIT_CLAMP = 1 +PERFMON_SPM_MODE_16BIT_NO_CLAMP = 2 +PERFMON_SPM_MODE_32BIT_CLAMP = 3 +PERFMON_SPM_MODE_32BIT_NO_CLAMP = 4 +PERFMON_SPM_MODE_RESERVED_5 = 5 +PERFMON_SPM_MODE_RESERVED_6 = 6 +PERFMON_SPM_MODE_RESERVED_7 = 7 +PERFMON_SPM_MODE_TEST_MODE_0 = 8 +PERFMON_SPM_MODE_TEST_MODE_1 = 9 +PERFMON_SPM_MODE_TEST_MODE_2 = 10 +PERFMON_SPM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceTiling' +SurfaceTiling__enumvalues = { + 0: 'ARRAY_LINEAR', + 1: 'ARRAY_TILED', +} +ARRAY_LINEAR = 0 +ARRAY_TILED = 1 +SurfaceTiling = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceArray' +SurfaceArray__enumvalues = { + 0: 'ARRAY_1D', + 1: 'ARRAY_2D', + 2: 'ARRAY_3D', + 3: 'ARRAY_3D_SLICE', +} +ARRAY_1D = 0 +ARRAY_2D = 1 +ARRAY_3D = 2 +ARRAY_3D_SLICE = 3 +SurfaceArray = ctypes.c_uint32 # enum + +# values for enumeration 'ColorArray' +ColorArray__enumvalues = { + 0: 'ARRAY_2D_ALT_COLOR', + 1: 'ARRAY_2D_COLOR', + 3: 'ARRAY_3D_SLICE_COLOR', +} +ARRAY_2D_ALT_COLOR = 0 +ARRAY_2D_COLOR = 1 +ARRAY_3D_SLICE_COLOR = 3 +ColorArray = ctypes.c_uint32 # enum + +# values for enumeration 'DepthArray' +DepthArray__enumvalues = { + 0: 'ARRAY_2D_ALT_DEPTH', + 1: 'ARRAY_2D_DEPTH', +} +ARRAY_2D_ALT_DEPTH = 0 +ARRAY_2D_DEPTH = 1 +DepthArray = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_NUM_SIMD_PER_CU' +ENUM_NUM_SIMD_PER_CU__enumvalues = { + 4: 'NUM_SIMD_PER_CU', +} +NUM_SIMD_PER_CU = 4 +ENUM_NUM_SIMD_PER_CU = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_ENABLE_ERROR_INJECT' +DSM_ENABLE_ERROR_INJECT__enumvalues = { + 0: 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 1: 'DSM_ENABLE_ERROR_INJECT_SINGLE', + 2: 'DSM_ENABLE_ERROR_INJECT_DOUBLE', + 3: 'DSM_ENABLE_ERROR_INJECT_DOUBLE_LIMITED', +} +DSM_ENABLE_ERROR_INJECT_FED_IN = 0 +DSM_ENABLE_ERROR_INJECT_SINGLE = 1 +DSM_ENABLE_ERROR_INJECT_DOUBLE = 2 +DSM_ENABLE_ERROR_INJECT_DOUBLE_LIMITED = 3 +DSM_ENABLE_ERROR_INJECT = ctypes.c_uint32 # enum + +# values for enumeration 'DSM_SELECT_INJECT_DELAY' +DSM_SELECT_INJECT_DELAY__enumvalues = { + 0: 'DSM_SELECT_INJECT_DELAY_NO_DELAY', + 1: 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', +} +DSM_SELECT_INJECT_DELAY_NO_DELAY = 0 +DSM_SELECT_INJECT_DELAY_DELAY_ERROR = 1 +DSM_SELECT_INJECT_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'SWIZZLE_TYPE_ENUM' +SWIZZLE_TYPE_ENUM__enumvalues = { + 0: 'SW_Z', + 1: 'SW_S', + 2: 'SW_D', + 3: 'SW_R', + 4: 'SW_L', +} +SW_Z = 0 +SW_S = 1 +SW_D = 2 +SW_R = 3 +SW_L = 4 +SWIZZLE_TYPE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TC_MICRO_TILE_MODE' +TC_MICRO_TILE_MODE__enumvalues = { + 0: 'MICRO_TILE_MODE_LINEAR', + 1: 'MICRO_TILE_MODE_ROTATED', + 2: 'MICRO_TILE_MODE_STD_2D', + 3: 'MICRO_TILE_MODE_STD_3D', + 4: 'MICRO_TILE_MODE_DISPLAY_2D', + 5: 'MICRO_TILE_MODE_DISPLAY_3D', + 6: 'MICRO_TILE_MODE_Z_2D', + 7: 'MICRO_TILE_MODE_Z_3D', +} +MICRO_TILE_MODE_LINEAR = 0 +MICRO_TILE_MODE_ROTATED = 1 +MICRO_TILE_MODE_STD_2D = 2 +MICRO_TILE_MODE_STD_3D = 3 +MICRO_TILE_MODE_DISPLAY_2D = 4 +MICRO_TILE_MODE_DISPLAY_3D = 5 +MICRO_TILE_MODE_Z_2D = 6 +MICRO_TILE_MODE_Z_3D = 7 +TC_MICRO_TILE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SWIZZLE_MODE_ENUM' +SWIZZLE_MODE_ENUM__enumvalues = { + 0: 'SW_LINEAR', + 1: 'SW_256B_S', + 2: 'SW_256B_D', + 3: 'SW_256B_R', + 4: 'SW_4KB_Z', + 5: 'SW_4KB_S', + 6: 'SW_4KB_D', + 7: 'SW_4KB_R', + 8: 'SW_64KB_Z', + 9: 'SW_64KB_S', + 10: 'SW_64KB_D', + 11: 'SW_64KB_R', + 12: 'SW_VAR_Z', + 13: 'SW_VAR_S', + 14: 'SW_VAR_D', + 15: 'SW_VAR_R', + 16: 'SW_RESERVED_16', + 17: 'SW_RESERVED_17', + 18: 'SW_RESERVED_18', + 19: 'SW_RESERVED_19', + 20: 'SW_4KB_Z_X', + 21: 'SW_4KB_S_X', + 22: 'SW_4KB_D_X', + 23: 'SW_4KB_R_X', + 24: 'SW_64KB_Z_X', + 25: 'SW_64KB_S_X', + 26: 'SW_64KB_D_X', + 27: 'SW_64KB_R_X', + 28: 'SW_VAR_Z_X', + 29: 'SW_VAR_S_X', + 30: 'SW_VAR_D_X', + 31: 'SW_VAR_R_X', + 32: 'SW_RESERVED_12', + 33: 'SW_RESERVED_13', + 34: 'SW_RESERVED_14', + 35: 'SW_RESERVED_15', +} +SW_LINEAR = 0 +SW_256B_S = 1 +SW_256B_D = 2 +SW_256B_R = 3 +SW_4KB_Z = 4 +SW_4KB_S = 5 +SW_4KB_D = 6 +SW_4KB_R = 7 +SW_64KB_Z = 8 +SW_64KB_S = 9 +SW_64KB_D = 10 +SW_64KB_R = 11 +SW_VAR_Z = 12 +SW_VAR_S = 13 +SW_VAR_D = 14 +SW_VAR_R = 15 +SW_RESERVED_16 = 16 +SW_RESERVED_17 = 17 +SW_RESERVED_18 = 18 +SW_RESERVED_19 = 19 +SW_4KB_Z_X = 20 +SW_4KB_S_X = 21 +SW_4KB_D_X = 22 +SW_4KB_R_X = 23 +SW_64KB_Z_X = 24 +SW_64KB_S_X = 25 +SW_64KB_D_X = 26 +SW_64KB_R_X = 27 +SW_VAR_Z_X = 28 +SW_VAR_S_X = 29 +SW_VAR_D_X = 30 +SW_VAR_R_X = 31 +SW_RESERVED_12 = 32 +SW_RESERVED_13 = 33 +SW_RESERVED_14 = 34 +SW_RESERVED_15 = 35 +SWIZZLE_MODE_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'PipeTiling' +PipeTiling__enumvalues = { + 0: 'CONFIG_1_PIPE', + 1: 'CONFIG_2_PIPE', + 2: 'CONFIG_4_PIPE', + 3: 'CONFIG_8_PIPE', +} +CONFIG_1_PIPE = 0 +CONFIG_2_PIPE = 1 +CONFIG_4_PIPE = 2 +CONFIG_8_PIPE = 3 +PipeTiling = ctypes.c_uint32 # enum + +# values for enumeration 'BankTiling' +BankTiling__enumvalues = { + 0: 'CONFIG_4_BANK', + 1: 'CONFIG_8_BANK', +} +CONFIG_4_BANK = 0 +CONFIG_8_BANK = 1 +BankTiling = ctypes.c_uint32 # enum + +# values for enumeration 'GroupInterleave' +GroupInterleave__enumvalues = { + 0: 'CONFIG_256B_GROUP', + 1: 'CONFIG_512B_GROUP', +} +CONFIG_256B_GROUP = 0 +CONFIG_512B_GROUP = 1 +GroupInterleave = ctypes.c_uint32 # enum + +# values for enumeration 'RowTiling' +RowTiling__enumvalues = { + 0: 'CONFIG_1KB_ROW', + 1: 'CONFIG_2KB_ROW', + 2: 'CONFIG_4KB_ROW', + 3: 'CONFIG_8KB_ROW', + 4: 'CONFIG_1KB_ROW_OPT', + 5: 'CONFIG_2KB_ROW_OPT', + 6: 'CONFIG_4KB_ROW_OPT', + 7: 'CONFIG_8KB_ROW_OPT', +} +CONFIG_1KB_ROW = 0 +CONFIG_2KB_ROW = 1 +CONFIG_4KB_ROW = 2 +CONFIG_8KB_ROW = 3 +CONFIG_1KB_ROW_OPT = 4 +CONFIG_2KB_ROW_OPT = 5 +CONFIG_4KB_ROW_OPT = 6 +CONFIG_8KB_ROW_OPT = 7 +RowTiling = ctypes.c_uint32 # enum + +# values for enumeration 'BankSwapBytes' +BankSwapBytes__enumvalues = { + 0: 'CONFIG_128B_SWAPS', + 1: 'CONFIG_256B_SWAPS', + 2: 'CONFIG_512B_SWAPS', + 3: 'CONFIG_1KB_SWAPS', +} +CONFIG_128B_SWAPS = 0 +CONFIG_256B_SWAPS = 1 +CONFIG_512B_SWAPS = 2 +CONFIG_1KB_SWAPS = 3 +BankSwapBytes = ctypes.c_uint32 # enum + +# values for enumeration 'SampleSplitBytes' +SampleSplitBytes__enumvalues = { + 0: 'CONFIG_1KB_SPLIT', + 1: 'CONFIG_2KB_SPLIT', + 2: 'CONFIG_4KB_SPLIT', + 3: 'CONFIG_8KB_SPLIT', +} +CONFIG_1KB_SPLIT = 0 +CONFIG_2KB_SPLIT = 1 +CONFIG_4KB_SPLIT = 2 +CONFIG_8KB_SPLIT = 3 +SampleSplitBytes = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET' +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 1: 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', +} +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET = 0 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET = 1 +OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS' +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 9: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 10: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 11: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 12: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 13: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 14: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 15: 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', +} +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED = 8 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED = 9 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED = 10 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED = 11 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED = 12 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED = 13 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED = 14 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED = 15 +OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_MODE' +BLNDV_CONTROL_BLND_MODE__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY', + 1: 'BLNDV_CONTROL_BLND_MODE_OTHER_PIPE_ONLY', + 2: 'BLNDV_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE', + 3: 'BLNDV_CONTROL_BLND_MODE_OTHER_STEREO_TYPE', +} +BLNDV_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY = 0 +BLNDV_CONTROL_BLND_MODE_OTHER_PIPE_ONLY = 1 +BLNDV_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE = 2 +BLNDV_CONTROL_BLND_MODE_OTHER_STEREO_TYPE = 3 +BLNDV_CONTROL_BLND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_STEREO_TYPE' +BLNDV_CONTROL_BLND_STEREO_TYPE__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO', + 1: 'BLNDV_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO', + 2: 'BLNDV_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO', + 3: 'BLNDV_CONTROL_BLND_STEREO_TYPE_UNUSED', +} +BLNDV_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO = 0 +BLNDV_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO = 1 +BLNDV_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO = 2 +BLNDV_CONTROL_BLND_STEREO_TYPE_UNUSED = 3 +BLNDV_CONTROL_BLND_STEREO_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_STEREO_POLARITY' +BLNDV_CONTROL_BLND_STEREO_POLARITY__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_STEREO_POLARITY_LOW', + 1: 'BLNDV_CONTROL_BLND_STEREO_POLARITY_HIGH', +} +BLNDV_CONTROL_BLND_STEREO_POLARITY_LOW = 0 +BLNDV_CONTROL_BLND_STEREO_POLARITY_HIGH = 1 +BLNDV_CONTROL_BLND_STEREO_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN' +BLNDV_CONTROL_BLND_FEEDTHROUGH_EN__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_FALSE', + 1: 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_TRUE', +} +BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_FALSE = 0 +BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_TRUE = 1 +BLNDV_CONTROL_BLND_FEEDTHROUGH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_ALPHA_MODE' +BLNDV_CONTROL_BLND_ALPHA_MODE__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA', + 1: 'BLNDV_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 2: 'BLNDV_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY', + 3: 'BLNDV_CONTROL_BLND_ALPHA_MODE_UNUSED', +} +BLNDV_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA = 0 +BLNDV_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN = 1 +BLNDV_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY = 2 +BLNDV_CONTROL_BLND_ALPHA_MODE_UNUSED = 3 +BLNDV_CONTROL_BLND_ALPHA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY' +BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_FALSE', + 1: 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_TRUE', +} +BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_FALSE = 0 +BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_TRUE = 1 +BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE' +BLNDV_CONTROL_BLND_MULTIPLIED_MODE__enumvalues = { + 0: 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE_FALSE', + 1: 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE_TRUE', +} +BLNDV_CONTROL_BLND_MULTIPLIED_MODE_FALSE = 0 +BLNDV_CONTROL_BLND_MULTIPLIED_MODE_TRUE = 1 +BLNDV_CONTROL_BLND_MULTIPLIED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_SM_CONTROL2_SM_MODE' +BLNDV_SM_CONTROL2_SM_MODE__enumvalues = { + 0: 'BLNDV_SM_CONTROL2_SM_MODE_SINGLE_PLANE', + 2: 'BLNDV_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING', + 4: 'BLNDV_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING', + 6: 'BLNDV_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING', +} +BLNDV_SM_CONTROL2_SM_MODE_SINGLE_PLANE = 0 +BLNDV_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING = 2 +BLNDV_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING = 4 +BLNDV_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING = 6 +BLNDV_SM_CONTROL2_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE' +BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE__enumvalues = { + 0: 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE', + 1: 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE', +} +BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE = 0 +BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE = 1 +BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE' +BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE__enumvalues = { + 0: 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE', + 1: 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE', +} +BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE = 0 +BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE = 1 +BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL' +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL__enumvalues = { + 0: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 1: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 2: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 3: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', +} +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE = 0 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED = 1 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW = 2 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH = 3 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL' +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL__enumvalues = { + 0: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 1: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED', + 2: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 3: 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', +} +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE = 0 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED = 1 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW = 2 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH = 3 +BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL2_PTI_ENABLE' +BLNDV_CONTROL2_PTI_ENABLE__enumvalues = { + 0: 'BLNDV_CONTROL2_PTI_ENABLE_FALSE', + 1: 'BLNDV_CONTROL2_PTI_ENABLE_TRUE', +} +BLNDV_CONTROL2_PTI_ENABLE_FALSE = 0 +BLNDV_CONTROL2_PTI_ENABLE_TRUE = 1 +BLNDV_CONTROL2_PTI_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN' +BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN__enumvalues = { + 0: 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE', + 1: 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE', +} +BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE = 0 +BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE = 1 +BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN' +BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN__enumvalues = { + 0: 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE', + 1: 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE', +} +BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE = 0 +BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE = 1 +BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK' +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK__enumvalues = { + 0: 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE', + 1: 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE', +} +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE = 0 +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE = 1 +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK' +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK__enumvalues = { + 0: 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE', + 1: 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE', +} +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE = 0 +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE = 1 +BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK' +BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE' +BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE__enumvalues = { + 0: 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE', + 1: 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE', +} +BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE = 0 +BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE = 1 +BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT' +BLNDV_DEBUG_BLND_CNV_MUX_SELECT__enumvalues = { + 0: 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT_LOW', + 1: 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT_HIGH', +} +BLNDV_DEBUG_BLND_CNV_MUX_SELECT_LOW = 0 +BLNDV_DEBUG_BLND_CNV_MUX_SELECT_HIGH = 1 +BLNDV_DEBUG_BLND_CNV_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN' +BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE', +} +BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE = 0 +BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE = 1 +BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_PIXEL_DEPTH' +LBV_PIXEL_DEPTH__enumvalues = { + 0: 'PIXEL_DEPTH_30BPP', + 1: 'PIXEL_DEPTH_24BPP', + 2: 'PIXEL_DEPTH_18BPP', + 3: 'PIXEL_DEPTH_38BPP', +} +PIXEL_DEPTH_30BPP = 0 +PIXEL_DEPTH_24BPP = 1 +PIXEL_DEPTH_18BPP = 2 +PIXEL_DEPTH_38BPP = 3 +LBV_PIXEL_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_PIXEL_EXPAN_MODE' +LBV_PIXEL_EXPAN_MODE__enumvalues = { + 0: 'PIXEL_EXPAN_MODE_ZERO_EXP', + 1: 'PIXEL_EXPAN_MODE_DYN_EXP', +} +PIXEL_EXPAN_MODE_ZERO_EXP = 0 +PIXEL_EXPAN_MODE_DYN_EXP = 1 +LBV_PIXEL_EXPAN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_INTERLEAVE_EN' +LBV_INTERLEAVE_EN__enumvalues = { + 0: 'INTERLEAVE_DIS', + 1: 'INTERLEAVE_EN', +} +INTERLEAVE_DIS = 0 +INTERLEAVE_EN = 1 +LBV_INTERLEAVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_PIXEL_REDUCE_MODE' +LBV_PIXEL_REDUCE_MODE__enumvalues = { + 0: 'PIXEL_REDUCE_MODE_TRUNCATION', + 1: 'PIXEL_REDUCE_MODE_ROUNDING', +} +PIXEL_REDUCE_MODE_TRUNCATION = 0 +PIXEL_REDUCE_MODE_ROUNDING = 1 +LBV_PIXEL_REDUCE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_DYNAMIC_PIXEL_DEPTH' +LBV_DYNAMIC_PIXEL_DEPTH__enumvalues = { + 0: 'DYNAMIC_PIXEL_DEPTH_36BPP', + 1: 'DYNAMIC_PIXEL_DEPTH_30BPP', +} +DYNAMIC_PIXEL_DEPTH_36BPP = 0 +DYNAMIC_PIXEL_DEPTH_30BPP = 1 +LBV_DYNAMIC_PIXEL_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_DITHER_EN' +LBV_DITHER_EN__enumvalues = { + 0: 'DITHER_DIS', + 1: 'DITHER_EN', +} +DITHER_DIS = 0 +DITHER_EN = 1 +LBV_DITHER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_DOWNSCALE_PREFETCH_EN' +LBV_DOWNSCALE_PREFETCH_EN__enumvalues = { + 0: 'DOWNSCALE_PREFETCH_DIS', + 1: 'DOWNSCALE_PREFETCH_EN', +} +DOWNSCALE_PREFETCH_DIS = 0 +DOWNSCALE_PREFETCH_EN = 1 +LBV_DOWNSCALE_PREFETCH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_MEMORY_CONFIG' +LBV_MEMORY_CONFIG__enumvalues = { + 0: 'MEMORY_CONFIG_0', + 1: 'MEMORY_CONFIG_1', + 2: 'MEMORY_CONFIG_2', + 3: 'MEMORY_CONFIG_3', +} +MEMORY_CONFIG_0 = 0 +MEMORY_CONFIG_1 = 1 +MEMORY_CONFIG_2 = 2 +MEMORY_CONFIG_3 = 3 +LBV_MEMORY_CONFIG = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_SYNC_RESET_SEL2' +LBV_SYNC_RESET_SEL2__enumvalues = { + 0: 'SYNC_RESET_SEL2_VBLANK', + 1: 'SYNC_RESET_SEL2_VSYNC', +} +SYNC_RESET_SEL2_VBLANK = 0 +SYNC_RESET_SEL2_VSYNC = 1 +LBV_SYNC_RESET_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'LBV_SYNC_DURATION' +LBV_SYNC_DURATION__enumvalues = { + 0: 'SYNC_DURATION_16', + 1: 'SYNC_DURATION_32', + 2: 'SYNC_DURATION_64', + 3: 'SYNC_DURATION_128', +} +SYNC_DURATION_16 = 0 +SYNC_DURATION_32 = 1 +SYNC_DURATION_64 = 2 +SYNC_DURATION_128 = 3 +LBV_SYNC_DURATION = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_START_POINT_CNTL' +CRTC_CONTROL_CRTC_START_POINT_CNTL__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_START_POINT_CNTL_NORMAL', + 1: 'CRTC_CONTROL_CRTC_START_POINT_CNTL_DP', +} +CRTC_CONTROL_CRTC_START_POINT_CNTL_NORMAL = 0 +CRTC_CONTROL_CRTC_START_POINT_CNTL_DP = 1 +CRTC_CONTROL_CRTC_START_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL' +CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_NORMAL', + 1: 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_DP', +} +CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_NORMAL = 0 +CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_DP = 1 +CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL' +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE', + 1: 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 2: 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_RESERVED', + 3: 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_FIRST', +} +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE = 0 +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_CURRENT = 1 +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_RESERVED = 2 +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_FIRST = 3 +CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY' +CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_FALSE', + 1: 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_TRUE', +} +CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_FALSE = 0 +CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_TRUE = 1 +CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE' +CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_FALSE', + 1: 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_TRUE', +} +CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_FALSE = 0 +CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_TRUE = 1 +CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_SOF_PULL_EN' +CRTC_CONTROL_CRTC_SOF_PULL_EN__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_SOF_PULL_EN_FALSE', + 1: 'CRTC_CONTROL_CRTC_SOF_PULL_EN_TRUE', +} +CRTC_CONTROL_CRTC_SOF_PULL_EN_FALSE = 0 +CRTC_CONTROL_CRTC_SOF_PULL_EN_TRUE = 1 +CRTC_CONTROL_CRTC_SOF_PULL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL' +CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL__enumvalues = { + 0: 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_FALSE', + 1: 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_TRUE', +} +CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_FALSE = 0 +CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_TRUE = 1 +CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL' +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL__enumvalues = { + 0: 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_FALSE', + 1: 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_TRUE', +} +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_FALSE = 0 +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_TRUE = 1 +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL' +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL__enumvalues = { + 0: 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_FALSE', + 1: 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_TRUE', +} +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_FALSE = 0 +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_TRUE = 1 +CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN' +CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN__enumvalues = { + 0: 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_FALSE', + 1: 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_TRUE', +} +CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_FALSE = 0 +CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_TRUE = 1 +CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC' +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC__enumvalues = { + 0: 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 1: 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', +} +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE = 0 +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE = 1 +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT' +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT__enumvalues = { + 0: 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_DISABLE', + 1: 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_ENABLE', +} +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_DISABLE = 0 +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_ENABLE = 1 +CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK' +CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK__enumvalues = { + 0: 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE', + 1: 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE', +} +CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE = 0 +CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE = 1 +CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR' +CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR__enumvalues = { + 0: 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_FALSE', + 1: 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_TRUE', +} +CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_FALSE = 0 +CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_TRUE = 1 +CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL' +CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL__enumvalues = { + 0: 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_FALSE', + 1: 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_TRUE', +} +CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_FALSE = 0 +CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_TRUE = 1 +CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN' +CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN__enumvalues = { + 0: 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_FALSE', + 1: 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_TRUE', +} +CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_FALSE = 0 +CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_TRUE = 1 +CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT' +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT__enumvalues = { + 1: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA_OTHER', + 2: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA_OTHER', + 5: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICF', + 6: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICE', + 7: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA', + 8: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA', + 9: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCB', + 10: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCB', + 11: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD1', + 12: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD2', + 13: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICD', + 14: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICC', + 16: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL0', + 17: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL1', + 18: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL2', + 19: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IBLON', + 20: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICA', + 21: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICB', + 22: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL_ALLOW', + 23: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_MANUAL_FLOW', +} +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA_OTHER = 1 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA_OTHER = 2 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICF = 5 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICE = 6 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA = 7 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA = 8 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCB = 9 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCB = 10 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD1 = 11 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD2 = 12 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICD = 13 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICC = 14 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL0 = 16 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL1 = 17 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL2 = 18 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IBLON = 19 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICA = 20 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICB = 21 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL_ALLOW = 22 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_MANUAL_FLOW = 23 +CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT' +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT__enumvalues = { + 1: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_INTERLACE', + 2: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICA', + 3: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICB', + 4: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCA', + 5: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCB', + 6: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_VIDEO', + 7: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICC', +} +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_INTERLACE = 1 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICA = 2 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICB = 3 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCA = 4 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCB = 5 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_VIDEO = 6 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICC = 7 +CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN' +CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN__enumvalues = { + 0: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_FALSE', + 1: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_TRUE', +} +CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_FALSE = 0 +CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_TRUE = 1 +CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR' +CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR__enumvalues = { + 0: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_FALSE', + 1: 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_TRUE', +} +CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_FALSE = 0 +CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_TRUE = 1 +CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT' +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT__enumvalues = { + 1: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA_OTHER', + 2: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA_OTHER', + 5: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICF', + 6: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICE', + 7: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA', + 8: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA', + 9: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCB', + 10: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCB', + 11: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD1', + 12: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD2', + 13: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICD', + 14: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICC', + 16: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL0', + 17: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL1', + 18: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL2', + 19: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IBLON', + 20: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICA', + 21: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICB', + 22: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL_ALLOW', + 23: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_MANUAL_FLOW', +} +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA_OTHER = 1 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA_OTHER = 2 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICF = 5 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICE = 6 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA = 7 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA = 8 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCB = 9 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCB = 10 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD1 = 11 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD2 = 12 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICD = 13 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICC = 14 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL0 = 16 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL1 = 17 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL2 = 18 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IBLON = 19 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICA = 20 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICB = 21 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL_ALLOW = 22 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_MANUAL_FLOW = 23 +CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT' +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT__enumvalues = { + 1: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_INTERLACE', + 2: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICA', + 3: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICB', + 4: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCA', + 5: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCB', + 6: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_VIDEO', + 7: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICC', +} +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_INTERLACE = 1 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICA = 2 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICB = 3 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCA = 4 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCB = 5 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_VIDEO = 6 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICC = 7 +CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN' +CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN__enumvalues = { + 0: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_FALSE', + 1: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_TRUE', +} +CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_FALSE = 0 +CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_TRUE = 1 +CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR' +CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR__enumvalues = { + 0: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_FALSE', + 1: 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_TRUE', +} +CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_FALSE = 0 +CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_TRUE = 1 +CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE' +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE__enumvalues = { + 0: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_DISABLE', + 1: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT', + 2: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 3: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_RESERVED', +} +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_DISABLE = 0 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT = 1 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT = 2 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_RESERVED = 3 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK' +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK__enumvalues = { + 0: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_FALSE', + 1: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_TRUE', +} +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_FALSE = 0 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_TRUE = 1 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL' +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL__enumvalues = { + 0: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 1: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_TRUE', +} +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_FALSE = 0 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_TRUE = 1 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR' +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR__enumvalues = { + 0: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_FALSE', + 1: 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_TRUE', +} +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_FALSE = 0 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_TRUE = 1 +CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT' +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT__enumvalues = { + 0: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 1: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 2: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 3: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 4: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 5: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 6: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 7: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 8: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 9: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DVOCLK', + 10: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_MANUAL', + 11: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 12: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 13: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 14: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 15: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICC', +} +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC0 = 0 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICF = 1 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICE = 2 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD1 = 3 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD2 = 4 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA = 5 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK = 6 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA = 7 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK = 8 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DVOCLK = 9 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_MANUAL = 10 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC1 = 11 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICB = 12 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICA = 13 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICD = 14 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICC = 15 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY' +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY__enumvalues = { + 0: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_FALSE', + 1: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_TRUE', +} +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_FALSE = 0 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_TRUE = 1 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY' +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY__enumvalues = { + 0: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_FALSE', + 1: 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_TRUE', +} +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_FALSE = 0 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_TRUE = 1 +CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE' +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE__enumvalues = { + 0: 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_NO', + 1: 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RIGHT', + 2: 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_LEFT', + 3: 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RESERVED', +} +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_NO = 0 +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RIGHT = 1 +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_LEFT = 2 +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RESERVED = 3 +CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CONTROL_CRTC_MASTER_EN' +CRTC_CONTROL_CRTC_MASTER_EN__enumvalues = { + 0: 'CRTC_CONTROL_CRTC_MASTER_EN_FALSE', + 1: 'CRTC_CONTROL_CRTC_MASTER_EN_TRUE', +} +CRTC_CONTROL_CRTC_MASTER_EN_FALSE = 0 +CRTC_CONTROL_CRTC_MASTER_EN_TRUE = 1 +CRTC_CONTROL_CRTC_MASTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN' +CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN__enumvalues = { + 0: 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_FALSE', + 1: 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_TRUE', +} +CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_FALSE = 0 +CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_TRUE = 1 +CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE' +CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE__enumvalues = { + 0: 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_FALSE', + 1: 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_TRUE', +} +CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_FALSE = 0 +CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_TRUE = 1 +CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE' +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE__enumvalues = { + 0: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_FALSE', + 1: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_TRUE', +} +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_FALSE = 0 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_TRUE = 1 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD' +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD__enumvalues = { + 0: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT', + 1: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_ODD', + 2: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_EVEN', + 3: 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT2', +} +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT = 0 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_ODD = 1 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_EVEN = 2 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT2 = 3 +CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY' +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY__enumvalues = { + 0: 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_FALSE', + 1: 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_TRUE', +} +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_FALSE = 0 +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_TRUE = 1 +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT' +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT__enumvalues = { + 0: 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_FALSE', + 1: 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_TRUE', +} +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_FALSE = 0 +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_TRUE = 1 +CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN' +CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN__enumvalues = { + 0: 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_FALSE', + 1: 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_TRUE', +} +CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_FALSE = 0 +CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_TRUE = 1 +CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE' +CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE__enumvalues = { + 0: 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 1: 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', +} +CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE = 0 +CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE = 1 +CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR' +CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR__enumvalues = { + 0: 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 1: 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', +} +CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE = 0 +CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE = 1 +CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE' +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE__enumvalues = { + 0: 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_DISABLE', + 1: 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 2: 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 3: 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_RESERVED', +} +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_DISABLE = 0 +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERA = 1 +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERB = 2 +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_RESERVED = 3 +CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY' +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY__enumvalues = { + 0: 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 1: 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_TRUE', +} +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_FALSE = 0 +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_TRUE = 1 +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY' +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY__enumvalues = { + 0: 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_FALSE', + 1: 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_TRUE', +} +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_FALSE = 0 +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_TRUE = 1 +CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY' +CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY__enumvalues = { + 0: 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_FALSE', + 1: 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_TRUE', +} +CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_FALSE = 0 +CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_TRUE = 1 +CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN' +CRTC_STEREO_CONTROL_CRTC_STEREO_EN__enumvalues = { + 0: 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN_FALSE', + 1: 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN_TRUE', +} +CRTC_STEREO_CONTROL_CRTC_STEREO_EN_FALSE = 0 +CRTC_STEREO_CONTROL_CRTC_STEREO_EN_TRUE = 1 +CRTC_STEREO_CONTROL_CRTC_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR' +CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR__enumvalues = { + 0: 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_FALSE', + 1: 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_TRUE', +} +CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_FALSE = 0 +CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_TRUE = 1 +CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL' +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL__enumvalues = { + 0: 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 1: 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 2: 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 3: 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', +} +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_DISABLE = 0 +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA = 1 +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB = 2 +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_RESERVED = 3 +CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY' +CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY__enumvalues = { + 0: 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_FALSE', + 1: 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_TRUE', +} +CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_FALSE = 0 +CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_TRUE = 1 +CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY' +CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY__enumvalues = { + 0: 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_FALSE', + 1: 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_TRUE', +} +CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_FALSE = 0 +CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_TRUE = 1 +CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN' +CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN__enumvalues = { + 0: 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_FALSE', + 1: 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_TRUE', +} +CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_FALSE = 0 +CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_TRUE = 1 +CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN' +CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN__enumvalues = { + 0: 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_FALSE', + 1: 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_TRUE', +} +CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_FALSE = 0 +CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_TRUE = 1 +CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK' +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE' +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE__enumvalues = { + 0: 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 1: 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_TRUE', +} +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_FALSE = 0 +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_TRUE = 1 +CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK' +CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK__enumvalues = { + 0: 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_FALSE', + 1: 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_TRUE', +} +CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_FALSE = 0 +CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_TRUE = 1 +CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY' +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY__enumvalues = { + 0: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_FALSE', + 1: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_TRUE', +} +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_FALSE = 0 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_TRUE = 1 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN' +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN__enumvalues = { + 0: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE', + 1: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE', +} +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE = 0 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE = 1 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE' +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE__enumvalues = { + 0: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_0', + 1: 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_1', +} +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_0 = 0 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_1 = 1 +CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE' +CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE__enumvalues = { + 0: 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_FALSE', + 1: 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_TRUE', +} +CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_FALSE = 0 +CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_TRUE = 1 +CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN' +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN__enumvalues = { + 0: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_FALSE', + 1: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_TRUE', +} +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_FALSE = 0 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_TRUE = 1 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE' +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE__enumvalues = { + 0: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_RGB', + 1: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR601', + 2: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR709', + 3: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_VBARS', + 4: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_HBARS', + 5: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_SRRGB', + 6: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_DRRGB', + 7: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_XRBIAS', +} +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_RGB = 0 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR601 = 1 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR709 = 2 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_VBARS = 3 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_HBARS = 4 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_SRRGB = 5 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_DRRGB = 6 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_XRBIAS = 7 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE' +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE__enumvalues = { + 0: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_FALSE', + 1: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_TRUE', +} +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_FALSE = 0 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_TRUE = 1 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT' +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT__enumvalues = { + 0: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_6BPC', + 1: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_8BPC', + 2: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_10BPC', + 3: 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_RESERVED', +} +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_6BPC = 0 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_8BPC = 1 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_10BPC = 2 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_RESERVED = 3 +CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK' +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK' +MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK' +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK__enumvalues = { + 0: 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE', + 1: 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE', +} +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE = 0 +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE = 1 +MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE' +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE__enumvalues = { + 0: 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BETWEEN', + 1: 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_HSYNCA', + 2: 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_VSYNCA', + 3: 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BEFORE', +} +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BETWEEN = 0 +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_HSYNCA = 1 +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_VSYNCA = 2 +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BEFORE = 3 +MASTER_UPDATE_MODE_MASTER_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE' +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE__enumvalues = { + 0: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 1: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_EVEN', + 2: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_ODD', + 3: 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', +} +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH = 0 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_EVEN = 1 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_ODD = 2 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED = 3 +MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE' +CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE__enumvalues = { + 0: 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DISABLE', + 1: 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DEBUG', + 2: 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_NORMAL', +} +CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DISABLE = 0 +CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DEBUG = 1 +CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_NORMAL = 2 +CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR' +CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR__enumvalues = { + 0: 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_FALSE', + 1: 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_TRUE', +} +CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_FALSE = 0 +CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_TRUE = 1 +CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR' +CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR__enumvalues = { + 0: 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE', + 1: 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE', +} +CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE = 0 +CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE = 1 +CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR' +CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR__enumvalues = { + 0: 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_FALSE', + 1: 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_TRUE', +} +CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_FALSE = 0 +CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_TRUE = 1 +CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY' +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', +} +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE = 0 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE = 1 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE' +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', +} +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR' +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_TRUE', +} +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_FALSE = 0 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_TRUE = 1 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE' +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', +} +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR' +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_TRUE', +} +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE = 0 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_TRUE = 1 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE' +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', +} +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE' +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', +} +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR' +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_TRUE', +} +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE = 0 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_TRUE = 1 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE' +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', +} +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE' +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE__enumvalues = { + 0: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 1: 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', +} +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_FALSE = 0 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_TRUE = 1 +CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRC_EN' +CRTC_CRC_CNTL_CRTC_CRC_EN__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRC_EN_FALSE', + 1: 'CRTC_CRC_CNTL_CRTC_CRC_EN_TRUE', +} +CRTC_CRC_CNTL_CRTC_CRC_EN_FALSE = 0 +CRTC_CRC_CNTL_CRTC_CRC_EN_TRUE = 1 +CRTC_CRC_CNTL_CRTC_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN' +CRTC_CRC_CNTL_CRTC_CRC_CONT_EN__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_FALSE', + 1: 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_TRUE', +} +CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_FALSE = 0 +CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_TRUE = 1 +CRTC_CRC_CNTL_CRTC_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE' +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_LEFT', + 1: 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_RIGHT', + 2: 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_EYES', + 3: 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_FIELDS', +} +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_LEFT = 0 +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_RIGHT = 1 +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_EYES = 2 +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_FIELDS = 3 +CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE' +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_TOP', + 1: 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTTOM', + 2: 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 3: 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_FIELD', +} +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_TOP = 0 +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTTOM = 1 +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_BOTTOM = 2 +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_FIELD = 3 +CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS' +CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 1: 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', +} +CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE = 0 +CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE = 1 +CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT' +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UAB', + 1: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UA_B', + 2: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_AB', + 3: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_A_B', + 4: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IAB', + 5: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IA_B', + 6: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_AB', + 7: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_A_B', +} +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UAB = 0 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UA_B = 1 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_AB = 2 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_A_B = 3 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IAB = 4 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IA_B = 5 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_AB = 6 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_A_B = 7 +CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT' +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT__enumvalues = { + 0: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UAB', + 1: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UA_B', + 2: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_AB', + 3: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_A_B', + 4: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IAB', + 5: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IA_B', + 6: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_AB', + 7: 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_A_B', +} +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UAB = 0 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UA_B = 1 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_AB = 2 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_A_B = 3 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IAB = 4 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IA_B = 5 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_AB = 6 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_A_B = 7 +CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_DISABLE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_ONESHOT', + 2: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_CONTINUOUS', + 3: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_RESERVED', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_DISABLE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_ONESHOT = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_CONTINUOUS = 2 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_RESERVED = 3 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel', + 2: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel', + 3: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel = 2 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel = 3 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE' +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE', +} +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE' +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR' +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE', +} +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE = 0 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE = 1 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE' +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE', +} +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT' +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME', + 1: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME', + 2: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME', + 3: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME', + 4: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME', + 5: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME', + 6: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME', + 7: 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME', +} +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME = 0 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME = 1 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME = 2 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME = 3 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME = 4 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME = 5 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME = 6 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME = 7 +CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE' +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR' +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_TRUE', +} +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_FALSE = 0 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_TRUE = 1 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE' +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_TRUE', +} +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE' +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE', +} +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR' +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE', +} +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE = 0 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE = 1 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE' +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE__enumvalues = { + 0: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE', + 1: 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE', +} +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE = 0 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE = 1 +CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE' +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE__enumvalues = { + 0: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_FALSE', + 1: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_TRUE', +} +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_FALSE = 0 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_TRUE = 1 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR' +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR__enumvalues = { + 0: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_FALSE', + 1: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_TRUE', +} +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_FALSE = 0 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_TRUE = 1 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE' +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE__enumvalues = { + 0: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_FALSE', + 1: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_TRUE', +} +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_FALSE = 0 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_TRUE = 1 +CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE' +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE__enumvalues = { + 0: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_FALSE', + 1: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_TRUE', +} +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_FALSE = 0 +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_TRUE = 1 +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE' +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE__enumvalues = { + 0: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 1: 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_ON', +} +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_OFF = 0 +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_ON = 1 +CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN' +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN__enumvalues = { + 0: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_FALSE', + 1: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_TRUE', +} +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_FALSE = 0 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_TRUE = 1 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB' +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB__enumvalues = { + 0: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_FALSE', + 1: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_TRUE', +} +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_FALSE = 0 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_TRUE = 1 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE' +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE__enumvalues = { + 0: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 1: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 2: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 3: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', +} +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH = 0 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE = 1 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE = 2 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_RESERVED = 3 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR' +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR__enumvalues = { + 0: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 1: 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', +} +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_FALSE = 0 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_TRUE = 1 +CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_V_SYNC_A_POL' +CRTC_V_SYNC_A_POL__enumvalues = { + 0: 'CRTC_V_SYNC_A_POL_HIGH', + 1: 'CRTC_V_SYNC_A_POL_LOW', +} +CRTC_V_SYNC_A_POL_HIGH = 0 +CRTC_V_SYNC_A_POL_LOW = 1 +CRTC_V_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_H_SYNC_A_POL' +CRTC_H_SYNC_A_POL__enumvalues = { + 0: 'CRTC_H_SYNC_A_POL_HIGH', + 1: 'CRTC_H_SYNC_A_POL_LOW', +} +CRTC_H_SYNC_A_POL_HIGH = 0 +CRTC_H_SYNC_A_POL_LOW = 1 +CRTC_H_SYNC_A_POL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_HORZ_REPETITION_COUNT' +CRTC_HORZ_REPETITION_COUNT__enumvalues = { + 0: 'CRTC_HORZ_REPETITION_COUNT_0', + 1: 'CRTC_HORZ_REPETITION_COUNT_1', + 2: 'CRTC_HORZ_REPETITION_COUNT_2', + 3: 'CRTC_HORZ_REPETITION_COUNT_3', + 4: 'CRTC_HORZ_REPETITION_COUNT_4', + 5: 'CRTC_HORZ_REPETITION_COUNT_5', + 6: 'CRTC_HORZ_REPETITION_COUNT_6', + 7: 'CRTC_HORZ_REPETITION_COUNT_7', + 8: 'CRTC_HORZ_REPETITION_COUNT_8', + 9: 'CRTC_HORZ_REPETITION_COUNT_9', + 10: 'CRTC_HORZ_REPETITION_COUNT_10', + 11: 'CRTC_HORZ_REPETITION_COUNT_11', + 12: 'CRTC_HORZ_REPETITION_COUNT_12', + 13: 'CRTC_HORZ_REPETITION_COUNT_13', + 14: 'CRTC_HORZ_REPETITION_COUNT_14', + 15: 'CRTC_HORZ_REPETITION_COUNT_15', +} +CRTC_HORZ_REPETITION_COUNT_0 = 0 +CRTC_HORZ_REPETITION_COUNT_1 = 1 +CRTC_HORZ_REPETITION_COUNT_2 = 2 +CRTC_HORZ_REPETITION_COUNT_3 = 3 +CRTC_HORZ_REPETITION_COUNT_4 = 4 +CRTC_HORZ_REPETITION_COUNT_5 = 5 +CRTC_HORZ_REPETITION_COUNT_6 = 6 +CRTC_HORZ_REPETITION_COUNT_7 = 7 +CRTC_HORZ_REPETITION_COUNT_8 = 8 +CRTC_HORZ_REPETITION_COUNT_9 = 9 +CRTC_HORZ_REPETITION_COUNT_10 = 10 +CRTC_HORZ_REPETITION_COUNT_11 = 11 +CRTC_HORZ_REPETITION_COUNT_12 = 12 +CRTC_HORZ_REPETITION_COUNT_13 = 13 +CRTC_HORZ_REPETITION_COUNT_14 = 14 +CRTC_HORZ_REPETITION_COUNT_15 = 15 +CRTC_HORZ_REPETITION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DRR_MODE_DBUF_UPDATE_MODE' +CRTC_DRR_MODE_DBUF_UPDATE_MODE__enumvalues = { + 0: 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_00_IMMEDIATE', + 1: 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_01_MANUAL', + 2: 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_10_DBUF', + 3: 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_11_SYNCED_DBUF', +} +CRTC_DRR_MODE_DBUF_UPDATE_MODE_00_IMMEDIATE = 0 +CRTC_DRR_MODE_DBUF_UPDATE_MODE_01_MANUAL = 1 +CRTC_DRR_MODE_DBUF_UPDATE_MODE_10_DBUF = 2 +CRTC_DRR_MODE_DBUF_UPDATE_MODE_11_SYNCED_DBUF = 3 +CRTC_DRR_MODE_DBUF_UPDATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_PIXEL_ENCODING' +FMT_CONTROL_PIXEL_ENCODING__enumvalues = { + 0: 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 1: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 2: 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 3: 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', +} +FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444 = 0 +FMT_CONTROL_PIXEL_ENCODING_YCBCR422 = 1 +FMT_CONTROL_PIXEL_ENCODING_YCBCR420 = 2 +FMT_CONTROL_PIXEL_ENCODING_RESERVED = 3 +FMT_CONTROL_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_MODE' +FMT_CONTROL_SUBSAMPLING_MODE__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 1: 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 2: 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 3: 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', +} +FMT_CONTROL_SUBSAMPLING_MODE_DROP = 0 +FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE = 1 +FMT_CONTROL_SUBSAMPLING_MOME_3_TAP = 2 +FMT_CONTROL_SUBSAMPLING_MOME_RESERVED = 3 +FMT_CONTROL_SUBSAMPLING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_SUBSAMPLING_ORDER' +FMT_CONTROL_SUBSAMPLING_ORDER__enumvalues = { + 0: 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 1: 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', +} +FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR = 0 +FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB = 1 +FMT_CONTROL_SUBSAMPLING_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS' +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS__enumvalues = { + 0: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 1: 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', +} +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE = 0 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE = 1 +FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH' +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 2: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP = 2 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL' +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 1: 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', +} +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2 = 0 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4 = 1 +FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL' +FMT_BIT_DEPTH_CONTROL_25FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 1: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 2: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 3: 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei = 0 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi = 1 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi = 2 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_25FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL' +FMT_BIT_DEPTH_CONTROL_50FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 1: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 2: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 3: 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', +} +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A = 0 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B = 1 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C = 2 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D = 3 +FMT_BIT_DEPTH_CONTROL_50FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL' +FMT_BIT_DEPTH_CONTROL_75FRC_SEL__enumvalues = { + 0: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 1: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 2: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 3: 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', +} +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E = 0 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F = 1 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G = 2 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED = 3 +FMT_BIT_DEPTH_CONTROL_75FRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT' +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT__enumvalues = { + 0: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_LEGACY_HARDCODED_PATTERN', + 1: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_PROGRAMMABLE_PATTERN', +} +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_LEGACY_HARDCODED_PATTERN = 0 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_PROGRAMMABLE_PATTERN = 1 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0' +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0__enumvalues = { + 0: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 1: 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', +} +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR = 0 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB = 1 +FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0 = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CLAMP_CNTL_COLOR_FORMAT' +FMT_CLAMP_CNTL_COLOR_FORMAT__enumvalues = { + 0: 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 1: 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 2: 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 3: 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 4: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 5: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 6: 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 7: 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', +} +FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC = 0 +FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC = 1 +FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC = 2 +FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC = 3 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1 = 4 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2 = 5 +FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3 = 6 +FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE = 7 +FMT_CLAMP_CNTL_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_CONT_EN' +FMT_CRC_CNTL_CONT_EN__enumvalues = { + 0: 'FMT_CRC_CNTL_CONT_EN_ONE_SHOT', + 1: 'FMT_CRC_CNTL_CONT_EN_CONT', +} +FMT_CRC_CNTL_CONT_EN_ONE_SHOT = 0 +FMT_CRC_CNTL_CONT_EN_CONT = 1 +FMT_CRC_CNTL_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_INCLUDE_OVERSCAN' +FMT_CRC_CNTL_INCLUDE_OVERSCAN__enumvalues = { + 0: 'FMT_CRC_CNTL_INCLUDE_OVERSCAN_NOT_INCLUDE', + 1: 'FMT_CRC_CNTL_INCLUDE_OVERSCAN_INCLUDE', +} +FMT_CRC_CNTL_INCLUDE_OVERSCAN_NOT_INCLUDE = 0 +FMT_CRC_CNTL_INCLUDE_OVERSCAN_INCLUDE = 1 +FMT_CRC_CNTL_INCLUDE_OVERSCAN = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_ONLY_BLANKB' +FMT_CRC_CNTL_ONLY_BLANKB__enumvalues = { + 0: 'FMT_CRC_CNTL_ONLY_BLANKB_ENTIRE_FIELD', + 1: 'FMT_CRC_CNTL_ONLY_BLANKB_NON_BLANK', +} +FMT_CRC_CNTL_ONLY_BLANKB_ENTIRE_FIELD = 0 +FMT_CRC_CNTL_ONLY_BLANKB_NON_BLANK = 1 +FMT_CRC_CNTL_ONLY_BLANKB = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_PSR_MODE_ENABLE' +FMT_CRC_CNTL_PSR_MODE_ENABLE__enumvalues = { + 0: 'FMT_CRC_CNTL_PSR_MODE_ENABLE_NORMAL', + 1: 'FMT_CRC_CNTL_PSR_MODE_ENABLE_EDP_PSR_CRC', +} +FMT_CRC_CNTL_PSR_MODE_ENABLE_NORMAL = 0 +FMT_CRC_CNTL_PSR_MODE_ENABLE_EDP_PSR_CRC = 1 +FMT_CRC_CNTL_PSR_MODE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_INTERLACE_MODE' +FMT_CRC_CNTL_INTERLACE_MODE__enumvalues = { + 0: 'FMT_CRC_CNTL_INTERLACE_MODE_TOP', + 1: 'FMT_CRC_CNTL_INTERLACE_MODE_BOTTOM', + 2: 'FMT_CRC_CNTL_INTERLACE_MODE_BOTH_BOTTOM', + 3: 'FMT_CRC_CNTL_INTERLACE_MODE_BOTH_EACH', +} +FMT_CRC_CNTL_INTERLACE_MODE_TOP = 0 +FMT_CRC_CNTL_INTERLACE_MODE_BOTTOM = 1 +FMT_CRC_CNTL_INTERLACE_MODE_BOTH_BOTTOM = 2 +FMT_CRC_CNTL_INTERLACE_MODE_BOTH_EACH = 3 +FMT_CRC_CNTL_INTERLACE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE' +FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE__enumvalues = { + 0: 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ALL', + 1: 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ODD_EVEN', +} +FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ALL = 0 +FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ODD_EVEN = 1 +FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT' +FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT__enumvalues = { + 0: 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_EVEN', + 1: 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_ODD', +} +FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_EVEN = 0 +FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_ODD = 1 +FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DEBUG_CNTL_COLOR_SELECT' +FMT_DEBUG_CNTL_COLOR_SELECT__enumvalues = { + 0: 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 1: 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 2: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 3: 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', +} +FMT_DEBUG_CNTL_COLOR_SELECT_BLUE = 0 +FMT_DEBUG_CNTL_COLOR_SELECT_GREEN = 1 +FMT_DEBUG_CNTL_COLOR_SELECT_RED1 = 2 +FMT_DEBUG_CNTL_COLOR_SELECT_RED2 = 3 +FMT_DEBUG_CNTL_COLOR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_SPATIAL_DITHER_MODE' +FMT_SPATIAL_DITHER_MODE__enumvalues = { + 0: 'FMT_SPATIAL_DITHER_MODE_0', + 1: 'FMT_SPATIAL_DITHER_MODE_1', + 2: 'FMT_SPATIAL_DITHER_MODE_2', + 3: 'FMT_SPATIAL_DITHER_MODE_3', +} +FMT_SPATIAL_DITHER_MODE_0 = 0 +FMT_SPATIAL_DITHER_MODE_1 = 1 +FMT_SPATIAL_DITHER_MODE_2 = 2 +FMT_SPATIAL_DITHER_MODE_3 = 3 +FMT_SPATIAL_DITHER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_STEREOSYNC_OVR_POL' +FMT_STEREOSYNC_OVR_POL__enumvalues = { + 0: 'FMT_STEREOSYNC_OVR_POL_INVERTED', + 1: 'FMT_STEREOSYNC_OVR_POL_NOT_INVERTED', +} +FMT_STEREOSYNC_OVR_POL_INVERTED = 0 +FMT_STEREOSYNC_OVR_POL_NOT_INVERTED = 1 +FMT_STEREOSYNC_OVR_POL = ctypes.c_uint32 # enum + +# values for enumeration 'FMT_DYNAMIC_EXP_MODE' +FMT_DYNAMIC_EXP_MODE__enumvalues = { + 0: 'FMT_DYNAMIC_EXP_MODE_10to12', + 1: 'FMT_DYNAMIC_EXP_MODE_8to12', +} +FMT_DYNAMIC_EXP_MODE_10to12 = 0 +FMT_DYNAMIC_EXP_MODE_8to12 = 1 +FMT_DYNAMIC_EXP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_ACK' +HPD_INT_CONTROL_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_ACK_0', + 1: 'HPD_INT_CONTROL_ACK_1', +} +HPD_INT_CONTROL_ACK_0 = 0 +HPD_INT_CONTROL_ACK_1 = 1 +HPD_INT_CONTROL_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_POLARITY' +HPD_INT_CONTROL_POLARITY__enumvalues = { + 0: 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', + 1: 'HPD_INT_CONTROL_GEN_INT_ON_CON', +} +HPD_INT_CONTROL_GEN_INT_ON_DISCON = 0 +HPD_INT_CONTROL_GEN_INT_ON_CON = 1 +HPD_INT_CONTROL_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'HPD_INT_CONTROL_RX_INT_ACK' +HPD_INT_CONTROL_RX_INT_ACK__enumvalues = { + 0: 'HPD_INT_CONTROL_RX_INT_ACK_0', + 1: 'HPD_INT_CONTROL_RX_INT_ACK_1', +} +HPD_INT_CONTROL_RX_INT_ACK_0 = 0 +HPD_INT_CONTROL_RX_INT_ACK_1 = 1 +HPD_INT_CONTROL_RX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_PIXEL_DEPTH' +LB_DATA_FORMAT_PIXEL_DEPTH__enumvalues = { + 0: 'LB_DATA_FORMAT_PIXEL_DEPTH_30BPP', + 1: 'LB_DATA_FORMAT_PIXEL_DEPTH_24BPP', + 2: 'LB_DATA_FORMAT_PIXEL_DEPTH_18BPP', + 3: 'LB_DATA_FORMAT_PIXEL_DEPTH_36BPP', +} +LB_DATA_FORMAT_PIXEL_DEPTH_30BPP = 0 +LB_DATA_FORMAT_PIXEL_DEPTH_24BPP = 1 +LB_DATA_FORMAT_PIXEL_DEPTH_18BPP = 2 +LB_DATA_FORMAT_PIXEL_DEPTH_36BPP = 3 +LB_DATA_FORMAT_PIXEL_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE' +LB_DATA_FORMAT_PIXEL_EXPAN_MODE__enumvalues = { + 0: 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE_ZERO_PIXEL_EXPANSION', + 1: 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE_DYNAMIC_PIXEL_EXPANSION', +} +LB_DATA_FORMAT_PIXEL_EXPAN_MODE_ZERO_PIXEL_EXPANSION = 0 +LB_DATA_FORMAT_PIXEL_EXPAN_MODE_DYNAMIC_PIXEL_EXPANSION = 1 +LB_DATA_FORMAT_PIXEL_EXPAN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE' +LB_DATA_FORMAT_PIXEL_REDUCE_MODE__enumvalues = { + 0: 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE_TRUNCATION', + 1: 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE_ROUNDING', +} +LB_DATA_FORMAT_PIXEL_REDUCE_MODE_TRUNCATION = 0 +LB_DATA_FORMAT_PIXEL_REDUCE_MODE_ROUNDING = 1 +LB_DATA_FORMAT_PIXEL_REDUCE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH' +LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH__enumvalues = { + 0: 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_36BPP', + 1: 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_30BPP', +} +LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_36BPP = 0 +LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_30BPP = 1 +LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_INTERLEAVE_EN' +LB_DATA_FORMAT_INTERLEAVE_EN__enumvalues = { + 0: 'LB_DATA_FORMAT_INTERLEAVE_DISABLE', + 1: 'LB_DATA_FORMAT_INTERLEAVE_ENABLE', +} +LB_DATA_FORMAT_INTERLEAVE_DISABLE = 0 +LB_DATA_FORMAT_INTERLEAVE_ENABLE = 1 +LB_DATA_FORMAT_INTERLEAVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_REQUEST_MODE' +LB_DATA_FORMAT_REQUEST_MODE__enumvalues = { + 0: 'LB_DATA_FORMAT_REQUEST_MODE_NORMAL', + 1: 'LB_DATA_FORMAT_REQUEST_MODE_START_OF_LINE', +} +LB_DATA_FORMAT_REQUEST_MODE_NORMAL = 0 +LB_DATA_FORMAT_REQUEST_MODE_START_OF_LINE = 1 +LB_DATA_FORMAT_REQUEST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DATA_FORMAT_ALPHA_EN' +LB_DATA_FORMAT_ALPHA_EN__enumvalues = { + 0: 'LB_DATA_FORMAT_ALPHA_DISABLE', + 1: 'LB_DATA_FORMAT_ALPHA_ENABLE', +} +LB_DATA_FORMAT_ALPHA_DISABLE = 0 +LB_DATA_FORMAT_ALPHA_ENABLE = 1 +LB_DATA_FORMAT_ALPHA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE_START_END_VLINE_INV' +LB_VLINE_START_END_VLINE_INV__enumvalues = { + 0: 'LB_VLINE_START_END_VLINE_NORMAL', + 1: 'LB_VLINE_START_END_VLINE_INVERSE', +} +LB_VLINE_START_END_VLINE_NORMAL = 0 +LB_VLINE_START_END_VLINE_INVERSE = 1 +LB_VLINE_START_END_VLINE_INV = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE2_START_END_VLINE2_INV' +LB_VLINE2_START_END_VLINE2_INV__enumvalues = { + 0: 'LB_VLINE2_START_END_VLINE2_NORMAL', + 1: 'LB_VLINE2_START_END_VLINE2_INVERSE', +} +LB_VLINE2_START_END_VLINE2_NORMAL = 0 +LB_VLINE2_START_END_VLINE2_INVERSE = 1 +LB_VLINE2_START_END_VLINE2_INV = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_MASK' +LB_INTERRUPT_MASK_VBLANK_INTERRUPT_MASK__enumvalues = { + 0: 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_DISABLE', + 1: 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_ENABLE', +} +LB_INTERRUPT_MASK_VBLANK_INTERRUPT_DISABLE = 0 +LB_INTERRUPT_MASK_VBLANK_INTERRUPT_ENABLE = 1 +LB_INTERRUPT_MASK_VBLANK_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_MASK' +LB_INTERRUPT_MASK_VLINE_INTERRUPT_MASK__enumvalues = { + 0: 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_DISABLE', + 1: 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_ENABLE', +} +LB_INTERRUPT_MASK_VLINE_INTERRUPT_DISABLE = 0 +LB_INTERRUPT_MASK_VLINE_INTERRUPT_ENABLE = 1 +LB_INTERRUPT_MASK_VLINE_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_MASK' +LB_INTERRUPT_MASK_VLINE2_INTERRUPT_MASK__enumvalues = { + 0: 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_DISABLE', + 1: 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_ENABLE', +} +LB_INTERRUPT_MASK_VLINE2_INTERRUPT_DISABLE = 0 +LB_INTERRUPT_MASK_VLINE2_INTERRUPT_ENABLE = 1 +LB_INTERRUPT_MASK_VLINE2_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE_STATUS_VLINE_ACK' +LB_VLINE_STATUS_VLINE_ACK__enumvalues = { + 0: 'LB_VLINE_STATUS_VLINE_NORMAL', + 1: 'LB_VLINE_STATUS_VLINE_CLEAR', +} +LB_VLINE_STATUS_VLINE_NORMAL = 0 +LB_VLINE_STATUS_VLINE_CLEAR = 1 +LB_VLINE_STATUS_VLINE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE' +LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE__enumvalues = { + 0: 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_PULSE_BASED', +} +LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_LEVEL_BASED = 0 +LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_PULSE_BASED = 1 +LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE2_STATUS_VLINE2_ACK' +LB_VLINE2_STATUS_VLINE2_ACK__enumvalues = { + 0: 'LB_VLINE2_STATUS_VLINE2_NORMAL', + 1: 'LB_VLINE2_STATUS_VLINE2_CLEAR', +} +LB_VLINE2_STATUS_VLINE2_NORMAL = 0 +LB_VLINE2_STATUS_VLINE2_CLEAR = 1 +LB_VLINE2_STATUS_VLINE2_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE' +LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE__enumvalues = { + 0: 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_PULSE_BASED', +} +LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_LEVEL_BASED = 0 +LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_PULSE_BASED = 1 +LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VBLANK_STATUS_VBLANK_ACK' +LB_VBLANK_STATUS_VBLANK_ACK__enumvalues = { + 0: 'LB_VBLANK_STATUS_VBLANK_NORMAL', + 1: 'LB_VBLANK_STATUS_VBLANK_CLEAR', +} +LB_VBLANK_STATUS_VBLANK_NORMAL = 0 +LB_VBLANK_STATUS_VBLANK_CLEAR = 1 +LB_VBLANK_STATUS_VBLANK_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE' +LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE__enumvalues = { + 0: 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_PULSE_BASED', +} +LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_LEVEL_BASED = 0 +LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_PULSE_BASED = 1 +LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL' +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL__enumvalues = { + 0: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_DISABLE', + 1: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK', + 2: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_POWERDOWN_RESET', + 3: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK_POWERDOWN_RESET', +} +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_DISABLE = 0 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK = 1 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_POWERDOWN_RESET = 2 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK_POWERDOWN_RESET = 3 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2' +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2__enumvalues = { + 0: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VBLANK', + 1: 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VSYNC', +} +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VBLANK = 0 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VSYNC = 1 +LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION' +LB_SYNC_RESET_SEL_LB_SYNC_DURATION__enumvalues = { + 0: 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_16_CLOCKS', + 1: 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_32_CLOCKS', + 2: 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_64_CLOCKS', + 3: 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_128_CLOCKS', +} +LB_SYNC_RESET_SEL_LB_SYNC_DURATION_16_CLOCKS = 0 +LB_SYNC_RESET_SEL_LB_SYNC_DURATION_32_CLOCKS = 1 +LB_SYNC_RESET_SEL_LB_SYNC_DURATION_64_CLOCKS = 2 +LB_SYNC_RESET_SEL_LB_SYNC_DURATION_128_CLOCKS = 3 +LB_SYNC_RESET_SEL_LB_SYNC_DURATION = ctypes.c_uint32 # enum + +# values for enumeration 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_EN' +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_EN__enumvalues = { + 0: 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_DISABLE', + 1: 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_ENABLE', +} +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_DISABLE = 0 +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_ENABLE = 1 +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REP_EN' +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REP_EN__enumvalues = { + 0: 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_DISABLE', + 1: 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_ENABLE', +} +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_DISABLE = 0 +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_ENABLE = 1 +LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_ACK' +LB_BUFFER_STATUS_LB_BUFFER_EMPTY_ACK__enumvalues = { + 0: 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_NORMAL', + 1: 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_RESET', +} +LB_BUFFER_STATUS_LB_BUFFER_EMPTY_NORMAL = 0 +LB_BUFFER_STATUS_LB_BUFFER_EMPTY_RESET = 1 +LB_BUFFER_STATUS_LB_BUFFER_EMPTY_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_BUFFER_STATUS_LB_BUFFER_FULL_ACK' +LB_BUFFER_STATUS_LB_BUFFER_FULL_ACK__enumvalues = { + 0: 'LB_BUFFER_STATUS_LB_BUFFER_FULL_NORMAL', + 1: 'LB_BUFFER_STATUS_LB_BUFFER_FULL_RESET', +} +LB_BUFFER_STATUS_LB_BUFFER_FULL_NORMAL = 0 +LB_BUFFER_STATUS_LB_BUFFER_FULL_RESET = 1 +LB_BUFFER_STATUS_LB_BUFFER_FULL_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE' +LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE__enumvalues = { + 2: 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_REAL_FLIP', + 3: 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_DUMMY_FLIP', +} +LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_REAL_FLIP = 2 +LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_DUMMY_FLIP = 3 +LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET' +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET__enumvalues = { + 0: 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_NORMAL', + 1: 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACTIVE', +} +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_NORMAL = 0 +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACTIVE = 1 +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK' +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK__enumvalues = { + 0: 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED0', + 1: 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED1', +} +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED0 = 0 +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED1 = 1 +LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE' +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE__enumvalues = { + 0: 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_NO_INSERT', + 1: 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_DEBUG', + 2: 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_HSYNC_MODE', +} +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_NO_INSERT = 0 +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_DEBUG = 1 +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_HSYNC_MODE = 2 +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_ENABLE' +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_ENABLE__enumvalues = { + 0: 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_DISABLE', + 1: 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_EN', +} +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_DISABLE = 0 +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_EN = 1 +LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE' +LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE__enumvalues = { + 1: 'ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_MASTER', + 2: 'ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_SLAVE', +} +ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_MASTER = 1 +ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_SLAVE = 2 +LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL' +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL__enumvalues = { + 0: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED0', + 1: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED1', +} +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED0 = 0 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED1 = 1 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ONE' +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ONE__enumvalues = { + 0: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ONE', + 1: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ONE', +} +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ONE = 0 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ONE = 1 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ONE = ctypes.c_uint32 # enum + +# values for enumeration 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ZERO' +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ZERO__enumvalues = { + 0: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ZERO', + 1: 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ZERO', +} +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ZERO = 0 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ZERO = 1 +LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ZERO = ctypes.c_uint32 # enum + +# values for enumeration 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN' +LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED0', + 1: 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED1', +} +LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED0 = 0 +LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED1 = 1 +LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_KEEPOUT_MODE' +HDMI_KEEPOUT_MODE__enumvalues = { + 0: 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 1: 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', +} +HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC = 0 +HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC = 1 +HDMI_KEEPOUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DATA_SCRAMBLE_EN' +HDMI_DATA_SCRAMBLE_EN__enumvalues = { + 0: 'HDMI_DATA_SCRAMBLE_DISABLE', + 1: 'HDMI_DATA_SCRAMBLE_ENABLE', +} +HDMI_DATA_SCRAMBLE_DISABLE = 0 +HDMI_DATA_SCRAMBLE_ENABLE = 1 +HDMI_DATA_SCRAMBLE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_CLOCK_CHANNEL_RATE' +HDMI_CLOCK_CHANNEL_RATE__enumvalues = { + 0: 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 1: 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', +} +HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE = 0 +HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE = 1 +HDMI_CLOCK_CHANNEL_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NO_EXTRA_NULL_PACKET_FILLED' +HDMI_NO_EXTRA_NULL_PACKET_FILLED__enumvalues = { + 0: 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', + 1: 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', +} +HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE = 0 +HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE = 1 +HDMI_NO_EXTRA_NULL_PACKET_FILLED = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKET_GEN_VERSION' +HDMI_PACKET_GEN_VERSION__enumvalues = { + 0: 'HDMI_PACKET_GEN_VERSION_OLD', + 1: 'HDMI_PACKET_GEN_VERSION_NEW', +} +HDMI_PACKET_GEN_VERSION_OLD = 0 +HDMI_PACKET_GEN_VERSION_NEW = 1 +HDMI_PACKET_GEN_VERSION = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_ACK' +HDMI_ERROR_ACK__enumvalues = { + 0: 'HDMI_ERROR_ACK_INT', + 1: 'HDMI_ERROR_NOT_ACK', +} +HDMI_ERROR_ACK_INT = 0 +HDMI_ERROR_NOT_ACK = 1 +HDMI_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ERROR_MASK' +HDMI_ERROR_MASK__enumvalues = { + 0: 'HDMI_ERROR_MASK_INT', + 1: 'HDMI_ERROR_NOT_MASK', +} +HDMI_ERROR_MASK_INT = 0 +HDMI_ERROR_NOT_MASK = 1 +HDMI_ERROR_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEEP_COLOR_DEPTH' +HDMI_DEEP_COLOR_DEPTH__enumvalues = { + 0: 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 1: 'HDMI_DEEP_COLOR_DEPTH_30BPP', + 2: 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 3: 'HDMI_DEEP_COLOR_DEPTH_RESERVED', +} +HDMI_DEEP_COLOR_DEPTH_24BPP = 0 +HDMI_DEEP_COLOR_DEPTH_30BPP = 1 +HDMI_DEEP_COLOR_DEPTH_36BPP = 2 +HDMI_DEEP_COLOR_DEPTH_RESERVED = 3 +HDMI_DEEP_COLOR_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_DELAY_EN' +HDMI_AUDIO_DELAY_EN__enumvalues = { + 0: 'HDMI_AUDIO_DELAY_DISABLE', + 1: 'HDMI_AUDIO_DELAY_58CLK', + 2: 'HDMI_AUDIO_DELAY_56CLK', + 3: 'HDMI_AUDIO_DELAY_RESERVED', +} +HDMI_AUDIO_DELAY_DISABLE = 0 +HDMI_AUDIO_DELAY_58CLK = 1 +HDMI_AUDIO_DELAY_56CLK = 2 +HDMI_AUDIO_DELAY_RESERVED = 3 +HDMI_AUDIO_DELAY_EN = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_SEND_MAX_PACKETS' +HDMI_AUDIO_SEND_MAX_PACKETS__enumvalues = { + 0: 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 1: 'HDMI_SEND_MAX_AUDIO_PACKETS', +} +HDMI_NOT_SEND_MAX_AUDIO_PACKETS = 0 +HDMI_SEND_MAX_AUDIO_PACKETS = 1 +HDMI_AUDIO_SEND_MAX_PACKETS = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SEND' +HDMI_ACR_SEND__enumvalues = { + 0: 'HDMI_ACR_NOT_SEND', + 1: 'HDMI_ACR_PKT_SEND', +} +HDMI_ACR_NOT_SEND = 0 +HDMI_ACR_PKT_SEND = 1 +HDMI_ACR_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_CONT' +HDMI_ACR_CONT__enumvalues = { + 0: 'HDMI_ACR_CONT_DISABLE', + 1: 'HDMI_ACR_CONT_ENABLE', +} +HDMI_ACR_CONT_DISABLE = 0 +HDMI_ACR_CONT_ENABLE = 1 +HDMI_ACR_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SELECT' +HDMI_ACR_SELECT__enumvalues = { + 0: 'HDMI_ACR_SELECT_HW', + 1: 'HDMI_ACR_SELECT_32K', + 2: 'HDMI_ACR_SELECT_44K', + 3: 'HDMI_ACR_SELECT_48K', +} +HDMI_ACR_SELECT_HW = 0 +HDMI_ACR_SELECT_32K = 1 +HDMI_ACR_SELECT_44K = 2 +HDMI_ACR_SELECT_48K = 3 +HDMI_ACR_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_SOURCE' +HDMI_ACR_SOURCE__enumvalues = { + 0: 'HDMI_ACR_SOURCE_HW', + 1: 'HDMI_ACR_SOURCE_SW', +} +HDMI_ACR_SOURCE_HW = 0 +HDMI_ACR_SOURCE_SW = 1 +HDMI_ACR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_N_MULTIPLE' +HDMI_ACR_N_MULTIPLE__enumvalues = { + 0: 'HDMI_ACR_0_MULTIPLE_RESERVED', + 1: 'HDMI_ACR_1_MULTIPLE', + 2: 'HDMI_ACR_2_MULTIPLE', + 3: 'HDMI_ACR_3_MULTIPLE_RESERVED', + 4: 'HDMI_ACR_4_MULTIPLE', + 5: 'HDMI_ACR_5_MULTIPLE_RESERVED', + 6: 'HDMI_ACR_6_MULTIPLE_RESERVED', + 7: 'HDMI_ACR_7_MULTIPLE_RESERVED', +} +HDMI_ACR_0_MULTIPLE_RESERVED = 0 +HDMI_ACR_1_MULTIPLE = 1 +HDMI_ACR_2_MULTIPLE = 2 +HDMI_ACR_3_MULTIPLE_RESERVED = 3 +HDMI_ACR_4_MULTIPLE = 4 +HDMI_ACR_5_MULTIPLE_RESERVED = 5 +HDMI_ACR_6_MULTIPLE_RESERVED = 6 +HDMI_ACR_7_MULTIPLE_RESERVED = 7 +HDMI_ACR_N_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ACR_AUDIO_PRIORITY' +HDMI_ACR_AUDIO_PRIORITY__enumvalues = { + 0: 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 1: 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', +} +HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE = 0 +HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT = 1 +HDMI_ACR_AUDIO_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_NULL_SEND' +HDMI_NULL_SEND__enumvalues = { + 0: 'HDMI_NULL_NOT_SEND', + 1: 'HDMI_NULL_PKT_SEND', +} +HDMI_NULL_NOT_SEND = 0 +HDMI_NULL_PKT_SEND = 1 +HDMI_NULL_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_SEND' +HDMI_GC_SEND__enumvalues = { + 0: 'HDMI_GC_NOT_SEND', + 1: 'HDMI_GC_PKT_SEND', +} +HDMI_GC_NOT_SEND = 0 +HDMI_GC_PKT_SEND = 1 +HDMI_GC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_CONT' +HDMI_GC_CONT__enumvalues = { + 0: 'HDMI_GC_CONT_DISABLE', + 1: 'HDMI_GC_CONT_ENABLE', +} +HDMI_GC_CONT_DISABLE = 0 +HDMI_GC_CONT_ENABLE = 1 +HDMI_GC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_SEND' +HDMI_ISRC_SEND__enumvalues = { + 0: 'HDMI_ISRC_NOT_SEND', + 1: 'HDMI_ISRC_PKT_SEND', +} +HDMI_ISRC_NOT_SEND = 0 +HDMI_ISRC_PKT_SEND = 1 +HDMI_ISRC_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_ISRC_CONT' +HDMI_ISRC_CONT__enumvalues = { + 0: 'HDMI_ISRC_CONT_DISABLE', + 1: 'HDMI_ISRC_CONT_ENABLE', +} +HDMI_ISRC_CONT_DISABLE = 0 +HDMI_ISRC_CONT_ENABLE = 1 +HDMI_ISRC_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AVI_INFO_SEND' +HDMI_AVI_INFO_SEND__enumvalues = { + 0: 'HDMI_AVI_INFO_NOT_SEND', + 1: 'HDMI_AVI_INFO_PKT_SEND', +} +HDMI_AVI_INFO_NOT_SEND = 0 +HDMI_AVI_INFO_PKT_SEND = 1 +HDMI_AVI_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AVI_INFO_CONT' +HDMI_AVI_INFO_CONT__enumvalues = { + 0: 'HDMI_AVI_INFO_CONT_DISABLE', + 1: 'HDMI_AVI_INFO_CONT_ENABLE', +} +HDMI_AVI_INFO_CONT_DISABLE = 0 +HDMI_AVI_INFO_CONT_ENABLE = 1 +HDMI_AVI_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_SEND' +HDMI_AUDIO_INFO_SEND__enumvalues = { + 0: 'HDMI_AUDIO_INFO_NOT_SEND', + 1: 'HDMI_AUDIO_INFO_PKT_SEND', +} +HDMI_AUDIO_INFO_NOT_SEND = 0 +HDMI_AUDIO_INFO_PKT_SEND = 1 +HDMI_AUDIO_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_AUDIO_INFO_CONT' +HDMI_AUDIO_INFO_CONT__enumvalues = { + 0: 'HDMI_AUDIO_INFO_CONT_DISABLE', + 1: 'HDMI_AUDIO_INFO_CONT_ENABLE', +} +HDMI_AUDIO_INFO_CONT_DISABLE = 0 +HDMI_AUDIO_INFO_CONT_ENABLE = 1 +HDMI_AUDIO_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_SEND' +HDMI_MPEG_INFO_SEND__enumvalues = { + 0: 'HDMI_MPEG_INFO_NOT_SEND', + 1: 'HDMI_MPEG_INFO_PKT_SEND', +} +HDMI_MPEG_INFO_NOT_SEND = 0 +HDMI_MPEG_INFO_PKT_SEND = 1 +HDMI_MPEG_INFO_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_MPEG_INFO_CONT' +HDMI_MPEG_INFO_CONT__enumvalues = { + 0: 'HDMI_MPEG_INFO_CONT_DISABLE', + 1: 'HDMI_MPEG_INFO_CONT_ENABLE', +} +HDMI_MPEG_INFO_CONT_DISABLE = 0 +HDMI_MPEG_INFO_CONT_ENABLE = 1 +HDMI_MPEG_INFO_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC0_SEND' +HDMI_GENERIC0_SEND__enumvalues = { + 0: 'HDMI_GENERIC0_NOT_SEND', + 1: 'HDMI_GENERIC0_PKT_SEND', +} +HDMI_GENERIC0_NOT_SEND = 0 +HDMI_GENERIC0_PKT_SEND = 1 +HDMI_GENERIC0_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC0_CONT' +HDMI_GENERIC0_CONT__enumvalues = { + 0: 'HDMI_GENERIC0_CONT_DISABLE', + 1: 'HDMI_GENERIC0_CONT_ENABLE', +} +HDMI_GENERIC0_CONT_DISABLE = 0 +HDMI_GENERIC0_CONT_ENABLE = 1 +HDMI_GENERIC0_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC1_SEND' +HDMI_GENERIC1_SEND__enumvalues = { + 0: 'HDMI_GENERIC1_NOT_SEND', + 1: 'HDMI_GENERIC1_PKT_SEND', +} +HDMI_GENERIC1_NOT_SEND = 0 +HDMI_GENERIC1_PKT_SEND = 1 +HDMI_GENERIC1_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC1_CONT' +HDMI_GENERIC1_CONT__enumvalues = { + 0: 'HDMI_GENERIC1_CONT_DISABLE', + 1: 'HDMI_GENERIC1_CONT_ENABLE', +} +HDMI_GENERIC1_CONT_DISABLE = 0 +HDMI_GENERIC1_CONT_ENABLE = 1 +HDMI_GENERIC1_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE_CONT' +HDMI_GC_AVMUTE_CONT__enumvalues = { + 0: 'HDMI_GC_AVMUTE_CONT_DISABLE', + 1: 'HDMI_GC_AVMUTE_CONT_ENABLE', +} +HDMI_GC_AVMUTE_CONT_DISABLE = 0 +HDMI_GC_AVMUTE_CONT_ENABLE = 1 +HDMI_GC_AVMUTE_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_PACKING_PHASE_OVERRIDE' +HDMI_PACKING_PHASE_OVERRIDE__enumvalues = { + 0: 'HDMI_PACKING_PHASE_SET_BY_HW', + 1: 'HDMI_PACKING_PHASE_SET_BY_SW', +} +HDMI_PACKING_PHASE_SET_BY_HW = 0 +HDMI_PACKING_PHASE_SET_BY_SW = 1 +HDMI_PACKING_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC2_SEND' +HDMI_GENERIC2_SEND__enumvalues = { + 0: 'HDMI_GENERIC2_NOT_SEND', + 1: 'HDMI_GENERIC2_PKT_SEND', +} +HDMI_GENERIC2_NOT_SEND = 0 +HDMI_GENERIC2_PKT_SEND = 1 +HDMI_GENERIC2_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC2_CONT' +HDMI_GENERIC2_CONT__enumvalues = { + 0: 'HDMI_GENERIC2_CONT_DISABLE', + 1: 'HDMI_GENERIC2_CONT_ENABLE', +} +HDMI_GENERIC2_CONT_DISABLE = 0 +HDMI_GENERIC2_CONT_ENABLE = 1 +HDMI_GENERIC2_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC3_SEND' +HDMI_GENERIC3_SEND__enumvalues = { + 0: 'HDMI_GENERIC3_NOT_SEND', + 1: 'HDMI_GENERIC3_PKT_SEND', +} +HDMI_GENERIC3_NOT_SEND = 0 +HDMI_GENERIC3_PKT_SEND = 1 +HDMI_GENERIC3_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GENERIC3_CONT' +HDMI_GENERIC3_CONT__enumvalues = { + 0: 'HDMI_GENERIC3_CONT_DISABLE', + 1: 'HDMI_GENERIC3_CONT_ENABLE', +} +HDMI_GENERIC3_CONT_DISABLE = 0 +HDMI_GENERIC3_CONT_ENABLE = 1 +HDMI_GENERIC3_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_PIXEL_ENCODING' +TMDS_PIXEL_ENCODING__enumvalues = { + 0: 'TMDS_PIXEL_ENCODING_444_OR_420', + 1: 'TMDS_PIXEL_ENCODING_422', +} +TMDS_PIXEL_ENCODING_444_OR_420 = 0 +TMDS_PIXEL_ENCODING_422 = 1 +TMDS_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_COLOR_FORMAT' +TMDS_COLOR_FORMAT__enumvalues = { + 0: 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 1: 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 2: 'TMDS_COLOR_FORMAT_DUAL30BPP', + 3: 'TMDS_COLOR_FORMAT_RESERVED', +} +TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP = 0 +TMDS_COLOR_FORMAT_TWIN30BPP_LSB = 1 +TMDS_COLOR_FORMAT_DUAL30BPP = 2 +TMDS_COLOR_FORMAT_RESERVED = 3 +TMDS_COLOR_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_STEREOSYNC_CTL_SEL_REG' +TMDS_STEREOSYNC_CTL_SEL_REG__enumvalues = { + 0: 'TMDS_STEREOSYNC_CTL0', + 1: 'TMDS_STEREOSYNC_CTL1', + 2: 'TMDS_STEREOSYNC_CTL2', + 3: 'TMDS_STEREOSYNC_CTL3', +} +TMDS_STEREOSYNC_CTL0 = 0 +TMDS_STEREOSYNC_CTL1 = 1 +TMDS_STEREOSYNC_CTL2 = 2 +TMDS_STEREOSYNC_CTL3 = 3 +TMDS_STEREOSYNC_CTL_SEL_REG = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_SEL' +TMDS_CTL0_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL0_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL0_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL0_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL0_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 7: 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', +} +TMDS_CTL0_DATA_SEL0_RESERVED = 0 +TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL0_DATA_SEL2_VSYNC = 2 +TMDS_CTL0_DATA_SEL3_RESERVED = 3 +TMDS_CTL0_DATA_SEL4_HSYNC = 4 +TMDS_CTL0_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL0_DATA_SEL8_RANDOM_DATA = 6 +TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA = 7 +TMDS_CTL0_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_INVERT' +TMDS_CTL0_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL0_DATA_NORMAL', + 1: 'TMDS_CTL0_DATA_INVERT_EN', +} +TMDS_CTL0_DATA_NORMAL = 0 +TMDS_CTL0_DATA_INVERT_EN = 1 +TMDS_CTL0_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_DATA_MODULATION' +TMDS_CTL0_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL0_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL0_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL0_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL0_DATA_MODULATION_BIT2', +} +TMDS_CTL0_DATA_MODULATION_DISABLE = 0 +TMDS_CTL0_DATA_MODULATION_BIT0 = 1 +TMDS_CTL0_DATA_MODULATION_BIT1 = 2 +TMDS_CTL0_DATA_MODULATION_BIT2 = 3 +TMDS_CTL0_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL0_PATTERN_OUT_EN' +TMDS_CTL0_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL0_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL0_PATTERN_OUT_ENABLE', +} +TMDS_CTL0_PATTERN_OUT_DISABLE = 0 +TMDS_CTL0_PATTERN_OUT_ENABLE = 1 +TMDS_CTL0_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_SEL' +TMDS_CTL1_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL1_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL1_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL1_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL1_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL1_DATA_SEL0_RESERVED = 0 +TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL1_DATA_SEL2_VSYNC = 2 +TMDS_CTL1_DATA_SEL3_RESERVED = 3 +TMDS_CTL1_DATA_SEL4_HSYNC = 4 +TMDS_CTL1_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL1_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL1_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL1_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_INVERT' +TMDS_CTL1_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL1_DATA_NORMAL', + 1: 'TMDS_CTL1_DATA_INVERT_EN', +} +TMDS_CTL1_DATA_NORMAL = 0 +TMDS_CTL1_DATA_INVERT_EN = 1 +TMDS_CTL1_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_DATA_MODULATION' +TMDS_CTL1_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL1_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL1_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL1_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL1_DATA_MODULATION_BIT2', +} +TMDS_CTL1_DATA_MODULATION_DISABLE = 0 +TMDS_CTL1_DATA_MODULATION_BIT0 = 1 +TMDS_CTL1_DATA_MODULATION_BIT1 = 2 +TMDS_CTL1_DATA_MODULATION_BIT2 = 3 +TMDS_CTL1_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL1_PATTERN_OUT_EN' +TMDS_CTL1_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL1_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL1_PATTERN_OUT_ENABLE', +} +TMDS_CTL1_PATTERN_OUT_DISABLE = 0 +TMDS_CTL1_PATTERN_OUT_ENABLE = 1 +TMDS_CTL1_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_SEL' +TMDS_CTL2_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL2_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL2_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL2_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL2_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL2_DATA_SEL0_RESERVED = 0 +TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL2_DATA_SEL2_VSYNC = 2 +TMDS_CTL2_DATA_SEL3_RESERVED = 3 +TMDS_CTL2_DATA_SEL4_HSYNC = 4 +TMDS_CTL2_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL2_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL2_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL2_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_INVERT' +TMDS_CTL2_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL2_DATA_NORMAL', + 1: 'TMDS_CTL2_DATA_INVERT_EN', +} +TMDS_CTL2_DATA_NORMAL = 0 +TMDS_CTL2_DATA_INVERT_EN = 1 +TMDS_CTL2_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_DATA_MODULATION' +TMDS_CTL2_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL2_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL2_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL2_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL2_DATA_MODULATION_BIT2', +} +TMDS_CTL2_DATA_MODULATION_DISABLE = 0 +TMDS_CTL2_DATA_MODULATION_BIT0 = 1 +TMDS_CTL2_DATA_MODULATION_BIT1 = 2 +TMDS_CTL2_DATA_MODULATION_BIT2 = 3 +TMDS_CTL2_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL2_PATTERN_OUT_EN' +TMDS_CTL2_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL2_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL2_PATTERN_OUT_ENABLE', +} +TMDS_CTL2_PATTERN_OUT_DISABLE = 0 +TMDS_CTL2_PATTERN_OUT_ENABLE = 1 +TMDS_CTL2_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_INVERT' +TMDS_CTL3_DATA_INVERT__enumvalues = { + 0: 'TMDS_CTL3_DATA_NORMAL', + 1: 'TMDS_CTL3_DATA_INVERT_EN', +} +TMDS_CTL3_DATA_NORMAL = 0 +TMDS_CTL3_DATA_INVERT_EN = 1 +TMDS_CTL3_DATA_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_MODULATION' +TMDS_CTL3_DATA_MODULATION__enumvalues = { + 0: 'TMDS_CTL3_DATA_MODULATION_DISABLE', + 1: 'TMDS_CTL3_DATA_MODULATION_BIT0', + 2: 'TMDS_CTL3_DATA_MODULATION_BIT1', + 3: 'TMDS_CTL3_DATA_MODULATION_BIT2', +} +TMDS_CTL3_DATA_MODULATION_DISABLE = 0 +TMDS_CTL3_DATA_MODULATION_BIT0 = 1 +TMDS_CTL3_DATA_MODULATION_BIT1 = 2 +TMDS_CTL3_DATA_MODULATION_BIT2 = 3 +TMDS_CTL3_DATA_MODULATION = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_PATTERN_OUT_EN' +TMDS_CTL3_PATTERN_OUT_EN__enumvalues = { + 0: 'TMDS_CTL3_PATTERN_OUT_DISABLE', + 1: 'TMDS_CTL3_PATTERN_OUT_ENABLE', +} +TMDS_CTL3_PATTERN_OUT_DISABLE = 0 +TMDS_CTL3_PATTERN_OUT_ENABLE = 1 +TMDS_CTL3_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_CTL3_DATA_SEL' +TMDS_CTL3_DATA_SEL__enumvalues = { + 0: 'TMDS_CTL3_DATA_SEL0_RESERVED', + 1: 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', + 2: 'TMDS_CTL3_DATA_SEL2_VSYNC', + 3: 'TMDS_CTL3_DATA_SEL3_RESERVED', + 4: 'TMDS_CTL3_DATA_SEL4_HSYNC', + 5: 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 6: 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 7: 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', +} +TMDS_CTL3_DATA_SEL0_RESERVED = 0 +TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE = 1 +TMDS_CTL3_DATA_SEL2_VSYNC = 2 +TMDS_CTL3_DATA_SEL3_RESERVED = 3 +TMDS_CTL3_DATA_SEL4_HSYNC = 4 +TMDS_CTL3_DATA_SEL5_SEL7_RESERVED = 5 +TMDS_CTL3_DATA_SEL8_BLANK_TIME = 6 +TMDS_CTL3_DATA_SEL9_SEL15_RESERVED = 7 +TMDS_CTL3_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_SOURCE_SELECT' +DIG_FE_CNTL_SOURCE_SELECT__enumvalues = { + 0: 'DIG_FE_SOURCE_FROM_FMT0', + 1: 'DIG_FE_SOURCE_FROM_FMT1', + 2: 'DIG_FE_SOURCE_FROM_FMT2', + 3: 'DIG_FE_SOURCE_FROM_FMT3', + 4: 'DIG_FE_SOURCE_FROM_FMT4', + 5: 'DIG_FE_SOURCE_FROM_FMT5', +} +DIG_FE_SOURCE_FROM_FMT0 = 0 +DIG_FE_SOURCE_FROM_FMT1 = 1 +DIG_FE_SOURCE_FROM_FMT2 = 2 +DIG_FE_SOURCE_FROM_FMT3 = 3 +DIG_FE_SOURCE_FROM_FMT4 = 4 +DIG_FE_SOURCE_FROM_FMT5 = 5 +DIG_FE_CNTL_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FE_CNTL_STEREOSYNC_SELECT' +DIG_FE_CNTL_STEREOSYNC_SELECT__enumvalues = { + 0: 'DIG_FE_STEREOSYNC_FROM_FMT0', + 1: 'DIG_FE_STEREOSYNC_FROM_FMT1', + 2: 'DIG_FE_STEREOSYNC_FROM_FMT2', + 3: 'DIG_FE_STEREOSYNC_FROM_FMT3', + 4: 'DIG_FE_STEREOSYNC_FROM_FMT4', + 5: 'DIG_FE_STEREOSYNC_FROM_FMT5', +} +DIG_FE_STEREOSYNC_FROM_FMT0 = 0 +DIG_FE_STEREOSYNC_FROM_FMT1 = 1 +DIG_FE_STEREOSYNC_FROM_FMT2 = 2 +DIG_FE_STEREOSYNC_FROM_FMT3 = 3 +DIG_FE_STEREOSYNC_FROM_FMT4 = 4 +DIG_FE_STEREOSYNC_FROM_FMT5 = 5 +DIG_FE_CNTL_STEREOSYNC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_READ_CLOCK_SRC' +DIG_FIFO_READ_CLOCK_SRC__enumvalues = { + 0: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 1: 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', +} +DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG = 0 +DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE = 1 +DIG_FIFO_READ_CLOCK_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_CNTL_LINK_SEL' +DIG_OUTPUT_CRC_CNTL_LINK_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_ON_LINK0', + 1: 'DIG_OUTPUT_CRC_ON_LINK1', +} +DIG_OUTPUT_CRC_ON_LINK0 = 0 +DIG_OUTPUT_CRC_ON_LINK1 = 1 +DIG_OUTPUT_CRC_CNTL_LINK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_OUTPUT_CRC_DATA_SEL' +DIG_OUTPUT_CRC_DATA_SEL__enumvalues = { + 0: 'DIG_OUTPUT_CRC_FOR_FULLFRAME', + 1: 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', + 2: 'DIG_OUTPUT_CRC_FOR_VBI', + 3: 'DIG_OUTPUT_CRC_FOR_AUDIO', +} +DIG_OUTPUT_CRC_FOR_FULLFRAME = 0 +DIG_OUTPUT_CRC_FOR_ACTIVEONLY = 1 +DIG_OUTPUT_CRC_FOR_VBI = 2 +DIG_OUTPUT_CRC_FOR_AUDIO = 3 +DIG_OUTPUT_CRC_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN' +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_IN_NORMAL_OPERATION', + 1: 'DIG_IN_DEBUG_MODE', +} +DIG_IN_NORMAL_OPERATION = 0 +DIG_IN_DEBUG_MODE = 1 +DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL' +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL__enumvalues = { + 0: 'DIG_10BIT_TEST_PATTERN', + 1: 'DIG_ALTERNATING_TEST_PATTERN', +} +DIG_10BIT_TEST_PATTERN = 0 +DIG_ALTERNATING_TEST_PATTERN = 1 +DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN' +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_NORMAL', + 1: 'DIG_TEST_PATTERN_RANDOM', +} +DIG_TEST_PATTERN_NORMAL = 0 +DIG_TEST_PATTERN_RANDOM = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET' +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_ENABLED', + 1: 'DIG_RANDOM_PATTERN_RESETED', +} +DIG_RANDOM_PATTERN_ENABLED = 0 +DIG_RANDOM_PATTERN_RESETED = 1 +DIG_TEST_PATTERN_RANDOM_PATTERN_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN' +DIG_TEST_PATTERN_EXTERNAL_RESET_EN__enumvalues = { + 0: 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 1: 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', +} +DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE = 0 +DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG = 1 +DIG_TEST_PATTERN_EXTERNAL_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_RANDOM_PATTERN_SEED_RAN_PAT' +DIG_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 1: 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', +} +DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS = 0 +DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH = 1 +DIG_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL' +DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL__enumvalues = { + 0: 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 1: 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', +} +DIG_FIFO_USE_OVERWRITE_LEVEL = 0 +DIG_FIFO_USE_CAL_AVERAGE_LEVEL = 1 +DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_ERROR_ACK' +DIG_FIFO_ERROR_ACK__enumvalues = { + 0: 'DIG_FIFO_ERROR_ACK_INT', + 1: 'DIG_FIFO_ERROR_NOT_ACK', +} +DIG_FIFO_ERROR_ACK_INT = 0 +DIG_FIFO_ERROR_NOT_ACK = 1 +DIG_FIFO_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE' +DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 1: 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', +} +DIG_FIFO_NOT_FORCE_RECAL_AVERAGE = 0 +DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL = 1 +DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX' +DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX__enumvalues = { + 0: 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', + 1: 'DIG_FIFO_FORCE_RECOMP_MINMAX', +} +DIG_FIFO_NOT_FORCE_RECOMP_MINMAX = 0 +DIG_FIFO_FORCE_RECOMP_MINMAX = 1 +DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INTERRUPT_STATUS_CHG_MASK' +AFMT_INTERRUPT_STATUS_CHG_MASK__enumvalues = { + 0: 'AFMT_INTERRUPT_DISABLE', + 1: 'AFMT_INTERRUPT_ENABLE', +} +AFMT_INTERRUPT_DISABLE = 0 +AFMT_INTERRUPT_ENABLE = 1 +AFMT_INTERRUPT_STATUS_CHG_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_GC_AVMUTE' +HDMI_GC_AVMUTE__enumvalues = { + 0: 'HDMI_GC_AVMUTE_SET', + 1: 'HDMI_GC_AVMUTE_UNSET', +} +HDMI_GC_AVMUTE_SET = 0 +HDMI_GC_AVMUTE_UNSET = 1 +HDMI_GC_AVMUTE = ctypes.c_uint32 # enum + +# values for enumeration 'HDMI_DEFAULT_PAHSE' +HDMI_DEFAULT_PAHSE__enumvalues = { + 0: 'HDMI_DEFAULT_PHASE_IS_0', + 1: 'HDMI_DEFAULT_PHASE_IS_1', +} +HDMI_DEFAULT_PHASE_IS_0 = 0 +HDMI_DEFAULT_PHASE_IS_1 = 1 +HDMI_DEFAULT_PAHSE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD' +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD__enumvalues = { + 0: 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 1: 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', +} +AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS = 0 +AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER = 1 +AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD = ctypes.c_uint32 # enum + +# values for enumeration 'AUDIO_LAYOUT_SELECT' +AUDIO_LAYOUT_SELECT__enumvalues = { + 0: 'AUDIO_LAYOUT_0', + 1: 'AUDIO_LAYOUT_1', +} +AUDIO_LAYOUT_0 = 0 +AUDIO_LAYOUT_1 = 1 +AUDIO_LAYOUT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CONT' +AFMT_AUDIO_CRC_CONTROL_CONT__enumvalues = { + 0: 'AFMT_AUDIO_CRC_ONESHOT', + 1: 'AFMT_AUDIO_CRC_AUTO_RESTART', +} +AFMT_AUDIO_CRC_ONESHOT = 0 +AFMT_AUDIO_CRC_AUTO_RESTART = 1 +AFMT_AUDIO_CRC_CONTROL_CONT = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_SOURCE' +AFMT_AUDIO_CRC_CONTROL_SOURCE__enumvalues = { + 0: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 1: 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', +} +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT = 0 +AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT = 1 +AFMT_AUDIO_CRC_CONTROL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_CRC_CONTROL_CH_SEL' +AFMT_AUDIO_CRC_CONTROL_CH_SEL__enumvalues = { + 0: 'AFMT_AUDIO_CRC_CH0_SIG', + 1: 'AFMT_AUDIO_CRC_CH1_SIG', + 2: 'AFMT_AUDIO_CRC_CH2_SIG', + 3: 'AFMT_AUDIO_CRC_CH3_SIG', + 4: 'AFMT_AUDIO_CRC_CH4_SIG', + 5: 'AFMT_AUDIO_CRC_CH5_SIG', + 6: 'AFMT_AUDIO_CRC_CH6_SIG', + 7: 'AFMT_AUDIO_CRC_CH7_SIG', + 8: 'AFMT_AUDIO_CRC_RESERVED_8', + 9: 'AFMT_AUDIO_CRC_RESERVED_9', + 10: 'AFMT_AUDIO_CRC_RESERVED_10', + 11: 'AFMT_AUDIO_CRC_RESERVED_11', + 12: 'AFMT_AUDIO_CRC_RESERVED_12', + 13: 'AFMT_AUDIO_CRC_RESERVED_13', + 14: 'AFMT_AUDIO_CRC_RESERVED_14', + 15: 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', +} +AFMT_AUDIO_CRC_CH0_SIG = 0 +AFMT_AUDIO_CRC_CH1_SIG = 1 +AFMT_AUDIO_CRC_CH2_SIG = 2 +AFMT_AUDIO_CRC_CH3_SIG = 3 +AFMT_AUDIO_CRC_CH4_SIG = 4 +AFMT_AUDIO_CRC_CH5_SIG = 5 +AFMT_AUDIO_CRC_CH6_SIG = 6 +AFMT_AUDIO_CRC_CH7_SIG = 7 +AFMT_AUDIO_CRC_RESERVED_8 = 8 +AFMT_AUDIO_CRC_RESERVED_9 = 9 +AFMT_AUDIO_CRC_RESERVED_10 = 10 +AFMT_AUDIO_CRC_RESERVED_11 = 11 +AFMT_AUDIO_CRC_RESERVED_12 = 12 +AFMT_AUDIO_CRC_RESERVED_13 = 13 +AFMT_AUDIO_CRC_RESERVED_14 = 14 +AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT = 15 +AFMT_AUDIO_CRC_CONTROL_CH_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_RAMP_CONTROL0_SIGN' +AFMT_RAMP_CONTROL0_SIGN__enumvalues = { + 0: 'AFMT_RAMP_SIGNED', + 1: 'AFMT_RAMP_UNSIGNED', +} +AFMT_RAMP_SIGNED = 0 +AFMT_RAMP_UNSIGNED = 1 +AFMT_RAMP_CONTROL0_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND' +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND__enumvalues = { + 0: 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 1: 'AFMT_AUDIO_PACKET_SENT_ENABLED', +} +AFMT_AUDIO_PACKET_SENT_DISABLED = 0 +AFMT_AUDIO_PACKET_SENT_ENABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS' +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS__enumvalues = { + 0: 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 1: 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', +} +AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED = 0 +AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED = 1 +AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE' +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE__enumvalues = { + 0: 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 1: 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', +} +AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK = 0 +AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS = 1 +AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'AFMT_AUDIO_SRC_CONTROL_SELECT' +AFMT_AUDIO_SRC_CONTROL_SELECT__enumvalues = { + 0: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 1: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 2: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 3: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 4: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 5: 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', + 6: 'AFMT_AUDIO_SRC_RESERVED', +} +AFMT_AUDIO_SRC_FROM_AZ_STREAM0 = 0 +AFMT_AUDIO_SRC_FROM_AZ_STREAM1 = 1 +AFMT_AUDIO_SRC_FROM_AZ_STREAM2 = 2 +AFMT_AUDIO_SRC_FROM_AZ_STREAM3 = 3 +AFMT_AUDIO_SRC_FROM_AZ_STREAM4 = 4 +AFMT_AUDIO_SRC_FROM_AZ_STREAM5 = 5 +AFMT_AUDIO_SRC_RESERVED = 6 +AFMT_AUDIO_SRC_CONTROL_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_MODE' +DIG_BE_CNTL_MODE__enumvalues = { + 0: 'DIG_BE_DP_SST_MODE', + 1: 'DIG_BE_RESERVED1', + 2: 'DIG_BE_TMDS_DVI_MODE', + 3: 'DIG_BE_TMDS_HDMI_MODE', + 4: 'DIG_BE_SDVO_RESERVED', + 5: 'DIG_BE_DP_MST_MODE', + 6: 'DIG_BE_RESERVED2', + 7: 'DIG_BE_RESERVED3', +} +DIG_BE_DP_SST_MODE = 0 +DIG_BE_RESERVED1 = 1 +DIG_BE_TMDS_DVI_MODE = 2 +DIG_BE_TMDS_HDMI_MODE = 3 +DIG_BE_SDVO_RESERVED = 4 +DIG_BE_DP_MST_MODE = 5 +DIG_BE_RESERVED2 = 6 +DIG_BE_RESERVED3 = 7 +DIG_BE_CNTL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DIG_BE_CNTL_HPD_SELECT' +DIG_BE_CNTL_HPD_SELECT__enumvalues = { + 0: 'DIG_BE_CNTL_HPD1', + 1: 'DIG_BE_CNTL_HPD2', + 2: 'DIG_BE_CNTL_HPD3', + 3: 'DIG_BE_CNTL_HPD4', + 4: 'DIG_BE_CNTL_HPD5', + 5: 'DIG_BE_CNTL_HPD6', +} +DIG_BE_CNTL_HPD1 = 0 +DIG_BE_CNTL_HPD2 = 1 +DIG_BE_CNTL_HPD3 = 2 +DIG_BE_CNTL_HPD4 = 3 +DIG_BE_CNTL_HPD5 = 4 +DIG_BE_CNTL_HPD6 = 5 +DIG_BE_CNTL_HPD_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT' +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT__enumvalues = { + 0: 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 1: 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', +} +LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS = 0 +LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH = 1 +LVTMA_RANDOM_PATTERN_SEED_RAN_PAT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_SYNC_PHASE' +TMDS_SYNC_PHASE__enumvalues = { + 0: 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', + 1: 'TMDS_SYNC_PHASE_ON_FRAME_START', +} +TMDS_NOT_SYNC_PHASE_ON_FRAME_START = 0 +TMDS_SYNC_PHASE_ON_FRAME_START = 1 +TMDS_SYNC_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL' +TMDS_DATA_SYNCHRONIZATION_DSINTSEL__enumvalues = { + 0: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 1: 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', +} +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS = 0 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL = 1 +TMDS_DATA_SYNCHRONIZATION_DSINTSEL = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK' +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 1: 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', +} +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE = 0 +TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE = 1 +TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 1: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 2: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 3: 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', +} +TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE = 0 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON = 1 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON = 2 +TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE = 3 +TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA' +TMDS_TRANSMITTER_CONTROL_IDSCKSELA__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB' +TMDS_TRANSMITTER_CONTROL_IDSCKSELB__enumvalues = { + 0: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 1: 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', +} +TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK = 0 +TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK = 1 +TMDS_TRANSMITTER_CONTROL_IDSCKSELB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN' +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 1: 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', +} +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE = 0 +TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE = 1 +TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK' +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 1: 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', +} +TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD = 0 +TMDS_TRANSMITTER_PLL_RST_ON_HPD = 1 +TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 1: 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK = 0 +TMDS_TRANSMITTER_TMCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS' +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS__enumvalues = { + 0: 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 1: 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', +} +TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK = 0 +TMDS_TRANSMITTER_TDCLK_FROM_PADS = 1 +TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN' +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN__enumvalues = { + 0: 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 1: 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', +} +TMDS_TRANSMITTER_PLLSEL_BY_HW = 0 +TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW = 1 +TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB' +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB__enumvalues = { + 0: 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 1: 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', +} +TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT = 0 +TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT = 1 +TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTA_CNTLA' +TMDS_REG_TEST_OUTPUTA_CNTLA__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 1: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 2: 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 3: 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', +} +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0 = 0 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1 = 1 +TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2 = 2 +TMDS_REG_TEST_OUTPUTA_CNTLA_NA = 3 +TMDS_REG_TEST_OUTPUTA_CNTLA = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_REG_TEST_OUTPUTB_CNTLB' +TMDS_REG_TEST_OUTPUTB_CNTLB__enumvalues = { + 0: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 1: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 2: 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', + 3: 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', +} +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0 = 0 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1 = 1 +TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2 = 2 +TMDS_REG_TEST_OUTPUTB_CNTLB_NA = 3 +TMDS_REG_TEST_OUTPUTB_CNTLB = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_ENABLE' +DCP_GRPH_ENABLE__enumvalues = { + 0: 'DCP_GRPH_ENABLE_FALSE', + 1: 'DCP_GRPH_ENABLE_TRUE', +} +DCP_GRPH_ENABLE_FALSE = 0 +DCP_GRPH_ENABLE_TRUE = 1 +DCP_GRPH_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_KEYER_ALPHA_SEL' +DCP_GRPH_KEYER_ALPHA_SEL__enumvalues = { + 0: 'DCP_GRPH_KEYER_ALPHA_SEL_FALSE', + 1: 'DCP_GRPH_KEYER_ALPHA_SEL_TRUE', +} +DCP_GRPH_KEYER_ALPHA_SEL_FALSE = 0 +DCP_GRPH_KEYER_ALPHA_SEL_TRUE = 1 +DCP_GRPH_KEYER_ALPHA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DEPTH' +DCP_GRPH_DEPTH__enumvalues = { + 0: 'DCP_GRPH_DEPTH_8BPP', + 1: 'DCP_GRPH_DEPTH_16BPP', + 2: 'DCP_GRPH_DEPTH_32BPP', + 3: 'DCP_GRPH_DEPTH_64BPP', +} +DCP_GRPH_DEPTH_8BPP = 0 +DCP_GRPH_DEPTH_16BPP = 1 +DCP_GRPH_DEPTH_32BPP = 2 +DCP_GRPH_DEPTH_64BPP = 3 +DCP_GRPH_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_NUM_BANKS' +DCP_GRPH_NUM_BANKS__enumvalues = { + 0: 'DCP_GRPH_NUM_BANKS_1BANK', + 1: 'DCP_GRPH_NUM_BANKS_2BANK', + 2: 'DCP_GRPH_NUM_BANKS_4BANK', + 3: 'DCP_GRPH_NUM_BANKS_8BANK', + 4: 'DCP_GRPH_NUM_BANKS_16BANK', +} +DCP_GRPH_NUM_BANKS_1BANK = 0 +DCP_GRPH_NUM_BANKS_2BANK = 1 +DCP_GRPH_NUM_BANKS_4BANK = 2 +DCP_GRPH_NUM_BANKS_8BANK = 3 +DCP_GRPH_NUM_BANKS_16BANK = 4 +DCP_GRPH_NUM_BANKS = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_NUM_PIPES' +DCP_GRPH_NUM_PIPES__enumvalues = { + 0: 'DCP_GRPH_NUM_PIPES_1PIPE', + 1: 'DCP_GRPH_NUM_PIPES_2PIPE', + 2: 'DCP_GRPH_NUM_PIPES_4PIPE', + 3: 'DCP_GRPH_NUM_PIPES_8PIPE', +} +DCP_GRPH_NUM_PIPES_1PIPE = 0 +DCP_GRPH_NUM_PIPES_2PIPE = 1 +DCP_GRPH_NUM_PIPES_4PIPE = 2 +DCP_GRPH_NUM_PIPES_8PIPE = 3 +DCP_GRPH_NUM_PIPES = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_FORMAT' +DCP_GRPH_FORMAT__enumvalues = { + 0: 'DCP_GRPH_FORMAT_8BPP', + 1: 'DCP_GRPH_FORMAT_16BPP', + 2: 'DCP_GRPH_FORMAT_32BPP', + 3: 'DCP_GRPH_FORMAT_64BPP', +} +DCP_GRPH_FORMAT_8BPP = 0 +DCP_GRPH_FORMAT_16BPP = 1 +DCP_GRPH_FORMAT_32BPP = 2 +DCP_GRPH_FORMAT_64BPP = 3 +DCP_GRPH_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE' +DCP_GRPH_ADDRESS_TRANSLATION_ENABLE__enumvalues = { + 0: 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_FALSE', + 1: 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_TRUE', +} +DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_FALSE = 0 +DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_TRUE = 1 +DCP_GRPH_ADDRESS_TRANSLATION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SW_MODE' +DCP_GRPH_SW_MODE__enumvalues = { + 0: 'DCP_GRPH_SW_MODE_0', + 2: 'DCP_GRPH_SW_MODE_2', + 3: 'DCP_GRPH_SW_MODE_3', + 22: 'DCP_GRPH_SW_MODE_22', + 23: 'DCP_GRPH_SW_MODE_23', + 26: 'DCP_GRPH_SW_MODE_26', + 27: 'DCP_GRPH_SW_MODE_27', + 30: 'DCP_GRPH_SW_MODE_30', + 31: 'DCP_GRPH_SW_MODE_31', +} +DCP_GRPH_SW_MODE_0 = 0 +DCP_GRPH_SW_MODE_2 = 2 +DCP_GRPH_SW_MODE_3 = 3 +DCP_GRPH_SW_MODE_22 = 22 +DCP_GRPH_SW_MODE_23 = 23 +DCP_GRPH_SW_MODE_26 = 26 +DCP_GRPH_SW_MODE_27 = 27 +DCP_GRPH_SW_MODE_30 = 30 +DCP_GRPH_SW_MODE_31 = 31 +DCP_GRPH_SW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_COLOR_EXPANSION_MODE' +DCP_GRPH_COLOR_EXPANSION_MODE__enumvalues = { + 0: 'DCP_GRPH_COLOR_EXPANSION_MODE_DEXP', + 1: 'DCP_GRPH_COLOR_EXPANSION_MODE_ZEXP', +} +DCP_GRPH_COLOR_EXPANSION_MODE_DEXP = 0 +DCP_GRPH_COLOR_EXPANSION_MODE_ZEXP = 1 +DCP_GRPH_COLOR_EXPANSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_LUT_10BIT_BYPASS_EN' +DCP_GRPH_LUT_10BIT_BYPASS_EN__enumvalues = { + 0: 'DCP_GRPH_LUT_10BIT_BYPASS_EN_FALSE', + 1: 'DCP_GRPH_LUT_10BIT_BYPASS_EN_TRUE', +} +DCP_GRPH_LUT_10BIT_BYPASS_EN_FALSE = 0 +DCP_GRPH_LUT_10BIT_BYPASS_EN_TRUE = 1 +DCP_GRPH_LUT_10BIT_BYPASS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN' +DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN__enumvalues = { + 0: 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_FALSE', + 1: 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_TRUE', +} +DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_FALSE = 0 +DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_TRUE = 1 +DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_ENDIAN_SWAP' +DCP_GRPH_ENDIAN_SWAP__enumvalues = { + 0: 'DCP_GRPH_ENDIAN_SWAP_NONE', + 1: 'DCP_GRPH_ENDIAN_SWAP_8IN16', + 2: 'DCP_GRPH_ENDIAN_SWAP_8IN32', + 3: 'DCP_GRPH_ENDIAN_SWAP_8IN64', +} +DCP_GRPH_ENDIAN_SWAP_NONE = 0 +DCP_GRPH_ENDIAN_SWAP_8IN16 = 1 +DCP_GRPH_ENDIAN_SWAP_8IN32 = 2 +DCP_GRPH_ENDIAN_SWAP_8IN64 = 3 +DCP_GRPH_ENDIAN_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_RED_CROSSBAR' +DCP_GRPH_RED_CROSSBAR__enumvalues = { + 0: 'DCP_GRPH_RED_CROSSBAR_FROM_R', + 1: 'DCP_GRPH_RED_CROSSBAR_FROM_G', + 2: 'DCP_GRPH_RED_CROSSBAR_FROM_B', + 3: 'DCP_GRPH_RED_CROSSBAR_FROM_A', +} +DCP_GRPH_RED_CROSSBAR_FROM_R = 0 +DCP_GRPH_RED_CROSSBAR_FROM_G = 1 +DCP_GRPH_RED_CROSSBAR_FROM_B = 2 +DCP_GRPH_RED_CROSSBAR_FROM_A = 3 +DCP_GRPH_RED_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_GREEN_CROSSBAR' +DCP_GRPH_GREEN_CROSSBAR__enumvalues = { + 0: 'DCP_GRPH_GREEN_CROSSBAR_FROM_G', + 1: 'DCP_GRPH_GREEN_CROSSBAR_FROM_B', + 2: 'DCP_GRPH_GREEN_CROSSBAR_FROM_A', + 3: 'DCP_GRPH_GREEN_CROSSBAR_FROM_R', +} +DCP_GRPH_GREEN_CROSSBAR_FROM_G = 0 +DCP_GRPH_GREEN_CROSSBAR_FROM_B = 1 +DCP_GRPH_GREEN_CROSSBAR_FROM_A = 2 +DCP_GRPH_GREEN_CROSSBAR_FROM_R = 3 +DCP_GRPH_GREEN_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_BLUE_CROSSBAR' +DCP_GRPH_BLUE_CROSSBAR__enumvalues = { + 0: 'DCP_GRPH_BLUE_CROSSBAR_FROM_B', + 1: 'DCP_GRPH_BLUE_CROSSBAR_FROM_A', + 2: 'DCP_GRPH_BLUE_CROSSBAR_FROM_R', + 3: 'DCP_GRPH_BLUE_CROSSBAR_FROM_G', +} +DCP_GRPH_BLUE_CROSSBAR_FROM_B = 0 +DCP_GRPH_BLUE_CROSSBAR_FROM_A = 1 +DCP_GRPH_BLUE_CROSSBAR_FROM_R = 2 +DCP_GRPH_BLUE_CROSSBAR_FROM_G = 3 +DCP_GRPH_BLUE_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_ALPHA_CROSSBAR' +DCP_GRPH_ALPHA_CROSSBAR__enumvalues = { + 0: 'DCP_GRPH_ALPHA_CROSSBAR_FROM_A', + 1: 'DCP_GRPH_ALPHA_CROSSBAR_FROM_R', + 2: 'DCP_GRPH_ALPHA_CROSSBAR_FROM_G', + 3: 'DCP_GRPH_ALPHA_CROSSBAR_FROM_B', +} +DCP_GRPH_ALPHA_CROSSBAR_FROM_A = 0 +DCP_GRPH_ALPHA_CROSSBAR_FROM_R = 1 +DCP_GRPH_ALPHA_CROSSBAR_FROM_G = 2 +DCP_GRPH_ALPHA_CROSSBAR_FROM_B = 3 +DCP_GRPH_ALPHA_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRIMARY_DFQ_ENABLE' +DCP_GRPH_PRIMARY_DFQ_ENABLE__enumvalues = { + 0: 'DCP_GRPH_PRIMARY_DFQ_ENABLE_FALSE', + 1: 'DCP_GRPH_PRIMARY_DFQ_ENABLE_TRUE', +} +DCP_GRPH_PRIMARY_DFQ_ENABLE_FALSE = 0 +DCP_GRPH_PRIMARY_DFQ_ENABLE_TRUE = 1 +DCP_GRPH_PRIMARY_DFQ_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SECONDARY_DFQ_ENABLE' +DCP_GRPH_SECONDARY_DFQ_ENABLE__enumvalues = { + 0: 'DCP_GRPH_SECONDARY_DFQ_ENABLE_FALSE', + 1: 'DCP_GRPH_SECONDARY_DFQ_ENABLE_TRUE', +} +DCP_GRPH_SECONDARY_DFQ_ENABLE_FALSE = 0 +DCP_GRPH_SECONDARY_DFQ_ENABLE_TRUE = 1 +DCP_GRPH_SECONDARY_DFQ_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_INPUT_GAMMA_MODE' +DCP_GRPH_INPUT_GAMMA_MODE__enumvalues = { + 0: 'DCP_GRPH_INPUT_GAMMA_MODE_LUT', + 1: 'DCP_GRPH_INPUT_GAMMA_MODE_BYPASS', +} +DCP_GRPH_INPUT_GAMMA_MODE_LUT = 0 +DCP_GRPH_INPUT_GAMMA_MODE_BYPASS = 1 +DCP_GRPH_INPUT_GAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_MODE_UPDATE_PENDING' +DCP_GRPH_MODE_UPDATE_PENDING__enumvalues = { + 0: 'DCP_GRPH_MODE_UPDATE_PENDING_FALSE', + 1: 'DCP_GRPH_MODE_UPDATE_PENDING_TRUE', +} +DCP_GRPH_MODE_UPDATE_PENDING_FALSE = 0 +DCP_GRPH_MODE_UPDATE_PENDING_TRUE = 1 +DCP_GRPH_MODE_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_MODE_UPDATE_TAKEN' +DCP_GRPH_MODE_UPDATE_TAKEN__enumvalues = { + 0: 'DCP_GRPH_MODE_UPDATE_TAKEN_FALSE', + 1: 'DCP_GRPH_MODE_UPDATE_TAKEN_TRUE', +} +DCP_GRPH_MODE_UPDATE_TAKEN_FALSE = 0 +DCP_GRPH_MODE_UPDATE_TAKEN_TRUE = 1 +DCP_GRPH_MODE_UPDATE_TAKEN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_UPDATE_PENDING' +DCP_GRPH_SURFACE_UPDATE_PENDING__enumvalues = { + 0: 'DCP_GRPH_SURFACE_UPDATE_PENDING_FALSE', + 1: 'DCP_GRPH_SURFACE_UPDATE_PENDING_TRUE', +} +DCP_GRPH_SURFACE_UPDATE_PENDING_FALSE = 0 +DCP_GRPH_SURFACE_UPDATE_PENDING_TRUE = 1 +DCP_GRPH_SURFACE_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_UPDATE_TAKEN' +DCP_GRPH_SURFACE_UPDATE_TAKEN__enumvalues = { + 0: 'DCP_GRPH_SURFACE_UPDATE_TAKEN_FALSE', + 1: 'DCP_GRPH_SURFACE_UPDATE_TAKEN_TRUE', +} +DCP_GRPH_SURFACE_UPDATE_TAKEN_FALSE = 0 +DCP_GRPH_SURFACE_UPDATE_TAKEN_TRUE = 1 +DCP_GRPH_SURFACE_UPDATE_TAKEN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE' +DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE__enumvalues = { + 0: 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_FALSE', + 1: 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_TRUE', +} +DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_FALSE = 0 +DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_TRUE = 1 +DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_UPDATE_LOCK' +DCP_GRPH_UPDATE_LOCK__enumvalues = { + 0: 'DCP_GRPH_UPDATE_LOCK_FALSE', + 1: 'DCP_GRPH_UPDATE_LOCK_TRUE', +} +DCP_GRPH_UPDATE_LOCK_FALSE = 0 +DCP_GRPH_UPDATE_LOCK_TRUE = 1 +DCP_GRPH_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK' +DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK__enumvalues = { + 0: 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_FALSE', + 1: 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_TRUE', +} +DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_FALSE = 0 +DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_TRUE = 1 +DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE' +DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_FALSE', + 1: 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_TRUE', +} +DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_FALSE = 0 +DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_TRUE = 1 +DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE' +DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_FALSE', + 1: 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_TRUE', +} +DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_FALSE = 0 +DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_TRUE = 1 +DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN' +DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN__enumvalues = { + 0: 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_FALSE', + 1: 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_TRUE', +} +DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_FALSE = 0 +DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_TRUE = 1 +DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_SUPER_AA_EN' +DCP_GRPH_XDMA_SUPER_AA_EN__enumvalues = { + 0: 'DCP_GRPH_XDMA_SUPER_AA_EN_FALSE', + 1: 'DCP_GRPH_XDMA_SUPER_AA_EN_TRUE', +} +DCP_GRPH_XDMA_SUPER_AA_EN_FALSE = 0 +DCP_GRPH_XDMA_SUPER_AA_EN_TRUE = 1 +DCP_GRPH_XDMA_SUPER_AA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DFQ_RESET' +DCP_GRPH_DFQ_RESET__enumvalues = { + 0: 'DCP_GRPH_DFQ_RESET_FALSE', + 1: 'DCP_GRPH_DFQ_RESET_TRUE', +} +DCP_GRPH_DFQ_RESET_FALSE = 0 +DCP_GRPH_DFQ_RESET_TRUE = 1 +DCP_GRPH_DFQ_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DFQ_SIZE' +DCP_GRPH_DFQ_SIZE__enumvalues = { + 0: 'DCP_GRPH_DFQ_SIZE_DEEP1', + 1: 'DCP_GRPH_DFQ_SIZE_DEEP2', + 2: 'DCP_GRPH_DFQ_SIZE_DEEP3', + 3: 'DCP_GRPH_DFQ_SIZE_DEEP4', + 4: 'DCP_GRPH_DFQ_SIZE_DEEP5', + 5: 'DCP_GRPH_DFQ_SIZE_DEEP6', + 6: 'DCP_GRPH_DFQ_SIZE_DEEP7', + 7: 'DCP_GRPH_DFQ_SIZE_DEEP8', +} +DCP_GRPH_DFQ_SIZE_DEEP1 = 0 +DCP_GRPH_DFQ_SIZE_DEEP2 = 1 +DCP_GRPH_DFQ_SIZE_DEEP3 = 2 +DCP_GRPH_DFQ_SIZE_DEEP4 = 3 +DCP_GRPH_DFQ_SIZE_DEEP5 = 4 +DCP_GRPH_DFQ_SIZE_DEEP6 = 5 +DCP_GRPH_DFQ_SIZE_DEEP7 = 6 +DCP_GRPH_DFQ_SIZE_DEEP8 = 7 +DCP_GRPH_DFQ_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES' +DCP_GRPH_DFQ_MIN_FREE_ENTRIES__enumvalues = { + 0: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_1', + 1: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_2', + 2: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_3', + 3: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_4', + 4: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_5', + 5: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_6', + 6: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_7', + 7: 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_8', +} +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_1 = 0 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_2 = 1 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_3 = 2 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_4 = 3 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_5 = 4 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_6 = 5 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_7 = 6 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES_8 = 7 +DCP_GRPH_DFQ_MIN_FREE_ENTRIES = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DFQ_RESET_ACK' +DCP_GRPH_DFQ_RESET_ACK__enumvalues = { + 0: 'DCP_GRPH_DFQ_RESET_ACK_FALSE', + 1: 'DCP_GRPH_DFQ_RESET_ACK_TRUE', +} +DCP_GRPH_DFQ_RESET_ACK_FALSE = 0 +DCP_GRPH_DFQ_RESET_ACK_TRUE = 1 +DCP_GRPH_DFQ_RESET_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PFLIP_INT_CLEAR' +DCP_GRPH_PFLIP_INT_CLEAR__enumvalues = { + 0: 'DCP_GRPH_PFLIP_INT_CLEAR_FALSE', + 1: 'DCP_GRPH_PFLIP_INT_CLEAR_TRUE', +} +DCP_GRPH_PFLIP_INT_CLEAR_FALSE = 0 +DCP_GRPH_PFLIP_INT_CLEAR_TRUE = 1 +DCP_GRPH_PFLIP_INT_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PFLIP_INT_MASK' +DCP_GRPH_PFLIP_INT_MASK__enumvalues = { + 0: 'DCP_GRPH_PFLIP_INT_MASK_FALSE', + 1: 'DCP_GRPH_PFLIP_INT_MASK_TRUE', +} +DCP_GRPH_PFLIP_INT_MASK_FALSE = 0 +DCP_GRPH_PFLIP_INT_MASK_TRUE = 1 +DCP_GRPH_PFLIP_INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PFLIP_INT_TYPE' +DCP_GRPH_PFLIP_INT_TYPE__enumvalues = { + 0: 'DCP_GRPH_PFLIP_INT_TYPE_LEGACY_LEVEL', + 1: 'DCP_GRPH_PFLIP_INT_TYPE_PULSE', +} +DCP_GRPH_PFLIP_INT_TYPE_LEGACY_LEVEL = 0 +DCP_GRPH_PFLIP_INT_TYPE_PULSE = 1 +DCP_GRPH_PFLIP_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRESCALE_SELECT' +DCP_GRPH_PRESCALE_SELECT__enumvalues = { + 0: 'DCP_GRPH_PRESCALE_SELECT_FIXED', + 1: 'DCP_GRPH_PRESCALE_SELECT_FLOATING', +} +DCP_GRPH_PRESCALE_SELECT_FIXED = 0 +DCP_GRPH_PRESCALE_SELECT_FLOATING = 1 +DCP_GRPH_PRESCALE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRESCALE_R_SIGN' +DCP_GRPH_PRESCALE_R_SIGN__enumvalues = { + 0: 'DCP_GRPH_PRESCALE_R_SIGN_UNSIGNED', + 1: 'DCP_GRPH_PRESCALE_R_SIGN_SIGNED', +} +DCP_GRPH_PRESCALE_R_SIGN_UNSIGNED = 0 +DCP_GRPH_PRESCALE_R_SIGN_SIGNED = 1 +DCP_GRPH_PRESCALE_R_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRESCALE_G_SIGN' +DCP_GRPH_PRESCALE_G_SIGN__enumvalues = { + 0: 'DCP_GRPH_PRESCALE_G_SIGN_UNSIGNED', + 1: 'DCP_GRPH_PRESCALE_G_SIGN_SIGNED', +} +DCP_GRPH_PRESCALE_G_SIGN_UNSIGNED = 0 +DCP_GRPH_PRESCALE_G_SIGN_SIGNED = 1 +DCP_GRPH_PRESCALE_G_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRESCALE_B_SIGN' +DCP_GRPH_PRESCALE_B_SIGN__enumvalues = { + 0: 'DCP_GRPH_PRESCALE_B_SIGN_UNSIGNED', + 1: 'DCP_GRPH_PRESCALE_B_SIGN_SIGNED', +} +DCP_GRPH_PRESCALE_B_SIGN_UNSIGNED = 0 +DCP_GRPH_PRESCALE_B_SIGN_SIGNED = 1 +DCP_GRPH_PRESCALE_B_SIGN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_PRESCALE_BYPASS' +DCP_GRPH_PRESCALE_BYPASS__enumvalues = { + 0: 'DCP_GRPH_PRESCALE_BYPASS_FALSE', + 1: 'DCP_GRPH_PRESCALE_BYPASS_TRUE', +} +DCP_GRPH_PRESCALE_BYPASS_FALSE = 0 +DCP_GRPH_PRESCALE_BYPASS_TRUE = 1 +DCP_GRPH_PRESCALE_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_INPUT_CSC_GRPH_MODE' +DCP_INPUT_CSC_GRPH_MODE__enumvalues = { + 0: 'DCP_INPUT_CSC_GRPH_MODE_BYPASS', + 1: 'DCP_INPUT_CSC_GRPH_MODE_INPUT_CSC_COEF', + 2: 'DCP_INPUT_CSC_GRPH_MODE_SHARED_COEF', + 3: 'DCP_INPUT_CSC_GRPH_MODE_RESERVED', +} +DCP_INPUT_CSC_GRPH_MODE_BYPASS = 0 +DCP_INPUT_CSC_GRPH_MODE_INPUT_CSC_COEF = 1 +DCP_INPUT_CSC_GRPH_MODE_SHARED_COEF = 2 +DCP_INPUT_CSC_GRPH_MODE_RESERVED = 3 +DCP_INPUT_CSC_GRPH_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_OUTPUT_CSC_GRPH_MODE' +DCP_OUTPUT_CSC_GRPH_MODE__enumvalues = { + 0: 'DCP_OUTPUT_CSC_GRPH_MODE_BYPASS', + 1: 'DCP_OUTPUT_CSC_GRPH_MODE_RGB', + 2: 'DCP_OUTPUT_CSC_GRPH_MODE_YCBCR601', + 3: 'DCP_OUTPUT_CSC_GRPH_MODE_YCBCR709', + 4: 'DCP_OUTPUT_CSC_GRPH_MODE_OUTPUT_CSC_COEF', + 5: 'DCP_OUTPUT_CSC_GRPH_MODE_SHARED_COEF', + 6: 'DCP_OUTPUT_CSC_GRPH_MODE_RESERVED0', + 7: 'DCP_OUTPUT_CSC_GRPH_MODE_RESERVED1', +} +DCP_OUTPUT_CSC_GRPH_MODE_BYPASS = 0 +DCP_OUTPUT_CSC_GRPH_MODE_RGB = 1 +DCP_OUTPUT_CSC_GRPH_MODE_YCBCR601 = 2 +DCP_OUTPUT_CSC_GRPH_MODE_YCBCR709 = 3 +DCP_OUTPUT_CSC_GRPH_MODE_OUTPUT_CSC_COEF = 4 +DCP_OUTPUT_CSC_GRPH_MODE_SHARED_COEF = 5 +DCP_OUTPUT_CSC_GRPH_MODE_RESERVED0 = 6 +DCP_OUTPUT_CSC_GRPH_MODE_RESERVED1 = 7 +DCP_OUTPUT_CSC_GRPH_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DENORM_MODE' +DCP_DENORM_MODE__enumvalues = { + 0: 'DCP_DENORM_MODE_UNITY', + 1: 'DCP_DENORM_MODE_6BIT', + 2: 'DCP_DENORM_MODE_8BIT', + 3: 'DCP_DENORM_MODE_10BIT', + 4: 'DCP_DENORM_MODE_11BIT', + 5: 'DCP_DENORM_MODE_12BIT', + 6: 'DCP_DENORM_MODE_RESERVED0', + 7: 'DCP_DENORM_MODE_RESERVED1', +} +DCP_DENORM_MODE_UNITY = 0 +DCP_DENORM_MODE_6BIT = 1 +DCP_DENORM_MODE_8BIT = 2 +DCP_DENORM_MODE_10BIT = 3 +DCP_DENORM_MODE_11BIT = 4 +DCP_DENORM_MODE_12BIT = 5 +DCP_DENORM_MODE_RESERVED0 = 6 +DCP_DENORM_MODE_RESERVED1 = 7 +DCP_DENORM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DENORM_14BIT_OUT' +DCP_DENORM_14BIT_OUT__enumvalues = { + 0: 'DCP_DENORM_14BIT_OUT_FALSE', + 1: 'DCP_DENORM_14BIT_OUT_TRUE', +} +DCP_DENORM_14BIT_OUT_FALSE = 0 +DCP_DENORM_14BIT_OUT_TRUE = 1 +DCP_DENORM_14BIT_OUT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_OUT_ROUND_TRUNC_MODE' +DCP_OUT_ROUND_TRUNC_MODE__enumvalues = { + 0: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_12', + 1: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_11', + 2: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_10', + 3: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_9', + 4: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_8', + 5: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_RESERVED', + 6: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_14', + 7: 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_13', + 8: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_12', + 9: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_11', + 10: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_10', + 11: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_9', + 12: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_8', + 13: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_RESERVED', + 14: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_14', + 15: 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_13', +} +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_12 = 0 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_11 = 1 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_10 = 2 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_9 = 3 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_8 = 4 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_RESERVED = 5 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_14 = 6 +DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_13 = 7 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_12 = 8 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_11 = 9 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_10 = 10 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_9 = 11 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_8 = 12 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_RESERVED = 13 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_14 = 14 +DCP_OUT_ROUND_TRUNC_MODE_ROUND_13 = 15 +DCP_OUT_ROUND_TRUNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_KEY_MODE' +DCP_KEY_MODE__enumvalues = { + 0: 'DCP_KEY_MODE_ALPHA0', + 1: 'DCP_KEY_MODE_ALPHA1', + 2: 'DCP_KEY_MODE_IN_RANGE_ALPHA1', + 3: 'DCP_KEY_MODE_IN_RANGE_ALPHA0', +} +DCP_KEY_MODE_ALPHA0 = 0 +DCP_KEY_MODE_ALPHA1 = 1 +DCP_KEY_MODE_IN_RANGE_ALPHA1 = 2 +DCP_KEY_MODE_IN_RANGE_ALPHA0 = 3 +DCP_KEY_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_DEGAMMA_MODE' +DCP_GRPH_DEGAMMA_MODE__enumvalues = { + 0: 'DCP_GRPH_DEGAMMA_MODE_BYPASS', + 1: 'DCP_GRPH_DEGAMMA_MODE_ROMA', + 2: 'DCP_GRPH_DEGAMMA_MODE_ROMB', + 3: 'DCP_GRPH_DEGAMMA_MODE_RESERVED', +} +DCP_GRPH_DEGAMMA_MODE_BYPASS = 0 +DCP_GRPH_DEGAMMA_MODE_ROMA = 1 +DCP_GRPH_DEGAMMA_MODE_ROMB = 2 +DCP_GRPH_DEGAMMA_MODE_RESERVED = 3 +DCP_GRPH_DEGAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_DEGAMMA_MODE' +DCP_CURSOR_DEGAMMA_MODE__enumvalues = { + 0: 'DCP_CURSOR_DEGAMMA_MODE_BYPASS', + 1: 'DCP_CURSOR_DEGAMMA_MODE_ROMA', + 2: 'DCP_CURSOR_DEGAMMA_MODE_ROMB', + 3: 'DCP_CURSOR_DEGAMMA_MODE_RESERVED', +} +DCP_CURSOR_DEGAMMA_MODE_BYPASS = 0 +DCP_CURSOR_DEGAMMA_MODE_ROMA = 1 +DCP_CURSOR_DEGAMMA_MODE_ROMB = 2 +DCP_CURSOR_DEGAMMA_MODE_RESERVED = 3 +DCP_CURSOR_DEGAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_GAMUT_REMAP_MODE' +DCP_GRPH_GAMUT_REMAP_MODE__enumvalues = { + 0: 'DCP_GRPH_GAMUT_REMAP_MODE_BYPASS', + 1: 'DCP_GRPH_GAMUT_REMAP_MODE_ROMA', + 2: 'DCP_GRPH_GAMUT_REMAP_MODE_ROMB', + 3: 'DCP_GRPH_GAMUT_REMAP_MODE_RESERVED', +} +DCP_GRPH_GAMUT_REMAP_MODE_BYPASS = 0 +DCP_GRPH_GAMUT_REMAP_MODE_ROMA = 1 +DCP_GRPH_GAMUT_REMAP_MODE_ROMB = 2 +DCP_GRPH_GAMUT_REMAP_MODE_RESERVED = 3 +DCP_GRPH_GAMUT_REMAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_SPATIAL_DITHER_EN' +DCP_SPATIAL_DITHER_EN__enumvalues = { + 0: 'DCP_SPATIAL_DITHER_EN_FALSE', + 1: 'DCP_SPATIAL_DITHER_EN_TRUE', +} +DCP_SPATIAL_DITHER_EN_FALSE = 0 +DCP_SPATIAL_DITHER_EN_TRUE = 1 +DCP_SPATIAL_DITHER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_SPATIAL_DITHER_MODE' +DCP_SPATIAL_DITHER_MODE__enumvalues = { + 0: 'DCP_SPATIAL_DITHER_MODE_BYPASS', + 1: 'DCP_SPATIAL_DITHER_MODE_ROMA', + 2: 'DCP_SPATIAL_DITHER_MODE_ROMB', + 3: 'DCP_SPATIAL_DITHER_MODE_RESERVED', +} +DCP_SPATIAL_DITHER_MODE_BYPASS = 0 +DCP_SPATIAL_DITHER_MODE_ROMA = 1 +DCP_SPATIAL_DITHER_MODE_ROMB = 2 +DCP_SPATIAL_DITHER_MODE_RESERVED = 3 +DCP_SPATIAL_DITHER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_SPATIAL_DITHER_DEPTH' +DCP_SPATIAL_DITHER_DEPTH__enumvalues = { + 0: 'DCP_SPATIAL_DITHER_DEPTH_30BPP', + 1: 'DCP_SPATIAL_DITHER_DEPTH_24BPP', + 2: 'DCP_SPATIAL_DITHER_DEPTH_36BPP', + 3: 'DCP_SPATIAL_DITHER_DEPTH_UNDEFINED', +} +DCP_SPATIAL_DITHER_DEPTH_30BPP = 0 +DCP_SPATIAL_DITHER_DEPTH_24BPP = 1 +DCP_SPATIAL_DITHER_DEPTH_36BPP = 2 +DCP_SPATIAL_DITHER_DEPTH_UNDEFINED = 3 +DCP_SPATIAL_DITHER_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_FRAME_RANDOM_ENABLE' +DCP_FRAME_RANDOM_ENABLE__enumvalues = { + 0: 'DCP_FRAME_RANDOM_ENABLE_FALSE', + 1: 'DCP_FRAME_RANDOM_ENABLE_TRUE', +} +DCP_FRAME_RANDOM_ENABLE_FALSE = 0 +DCP_FRAME_RANDOM_ENABLE_TRUE = 1 +DCP_FRAME_RANDOM_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_RGB_RANDOM_ENABLE' +DCP_RGB_RANDOM_ENABLE__enumvalues = { + 0: 'DCP_RGB_RANDOM_ENABLE_FALSE', + 1: 'DCP_RGB_RANDOM_ENABLE_TRUE', +} +DCP_RGB_RANDOM_ENABLE_FALSE = 0 +DCP_RGB_RANDOM_ENABLE_TRUE = 1 +DCP_RGB_RANDOM_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_HIGHPASS_RANDOM_ENABLE' +DCP_HIGHPASS_RANDOM_ENABLE__enumvalues = { + 0: 'DCP_HIGHPASS_RANDOM_ENABLE_FALSE', + 1: 'DCP_HIGHPASS_RANDOM_ENABLE_TRUE', +} +DCP_HIGHPASS_RANDOM_ENABLE_FALSE = 0 +DCP_HIGHPASS_RANDOM_ENABLE_TRUE = 1 +DCP_HIGHPASS_RANDOM_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_EN' +DCP_CURSOR_EN__enumvalues = { + 0: 'DCP_CURSOR_EN_FALSE', + 1: 'DCP_CURSOR_EN_TRUE', +} +DCP_CURSOR_EN_FALSE = 0 +DCP_CURSOR_EN_TRUE = 1 +DCP_CURSOR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CUR_INV_TRANS_CLAMP' +DCP_CUR_INV_TRANS_CLAMP__enumvalues = { + 0: 'DCP_CUR_INV_TRANS_CLAMP_FALSE', + 1: 'DCP_CUR_INV_TRANS_CLAMP_TRUE', +} +DCP_CUR_INV_TRANS_CLAMP_FALSE = 0 +DCP_CUR_INV_TRANS_CLAMP_TRUE = 1 +DCP_CUR_INV_TRANS_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_MODE' +DCP_CURSOR_MODE__enumvalues = { + 0: 'DCP_CURSOR_MODE_MONO_2BPP', + 1: 'DCP_CURSOR_MODE_24BPP_1BIT', + 2: 'DCP_CURSOR_MODE_24BPP_8BIT_PREMULTI', + 3: 'DCP_CURSOR_MODE_24BPP_8BIT_UNPREMULTI', +} +DCP_CURSOR_MODE_MONO_2BPP = 0 +DCP_CURSOR_MODE_24BPP_1BIT = 1 +DCP_CURSOR_MODE_24BPP_8BIT_PREMULTI = 2 +DCP_CURSOR_MODE_24BPP_8BIT_UNPREMULTI = 3 +DCP_CURSOR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM' +DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM__enumvalues = { + 0: 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_ONE', + 1: 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_TWO', +} +DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_ONE = 0 +DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_TWO = 1 +DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_2X_MAGNIFY' +DCP_CURSOR_2X_MAGNIFY__enumvalues = { + 0: 'DCP_CURSOR_2X_MAGNIFY_FALSE', + 1: 'DCP_CURSOR_2X_MAGNIFY_TRUE', +} +DCP_CURSOR_2X_MAGNIFY_FALSE = 0 +DCP_CURSOR_2X_MAGNIFY_TRUE = 1 +DCP_CURSOR_2X_MAGNIFY = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_FORCE_MC_ON' +DCP_CURSOR_FORCE_MC_ON__enumvalues = { + 0: 'DCP_CURSOR_FORCE_MC_ON_FALSE', + 1: 'DCP_CURSOR_FORCE_MC_ON_TRUE', +} +DCP_CURSOR_FORCE_MC_ON_FALSE = 0 +DCP_CURSOR_FORCE_MC_ON_TRUE = 1 +DCP_CURSOR_FORCE_MC_ON = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_URGENT_CONTROL' +DCP_CURSOR_URGENT_CONTROL__enumvalues = { + 0: 'DCP_CURSOR_URGENT_CONTROL_MODE_0', + 1: 'DCP_CURSOR_URGENT_CONTROL_MODE_1', + 2: 'DCP_CURSOR_URGENT_CONTROL_MODE_2', + 3: 'DCP_CURSOR_URGENT_CONTROL_MODE_3', + 4: 'DCP_CURSOR_URGENT_CONTROL_MODE_4', +} +DCP_CURSOR_URGENT_CONTROL_MODE_0 = 0 +DCP_CURSOR_URGENT_CONTROL_MODE_1 = 1 +DCP_CURSOR_URGENT_CONTROL_MODE_2 = 2 +DCP_CURSOR_URGENT_CONTROL_MODE_3 = 3 +DCP_CURSOR_URGENT_CONTROL_MODE_4 = 4 +DCP_CURSOR_URGENT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_UPDATE_PENDING' +DCP_CURSOR_UPDATE_PENDING__enumvalues = { + 0: 'DCP_CURSOR_UPDATE_PENDING_FALSE', + 1: 'DCP_CURSOR_UPDATE_PENDING_TRUE', +} +DCP_CURSOR_UPDATE_PENDING_FALSE = 0 +DCP_CURSOR_UPDATE_PENDING_TRUE = 1 +DCP_CURSOR_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_UPDATE_TAKEN' +DCP_CURSOR_UPDATE_TAKEN__enumvalues = { + 0: 'DCP_CURSOR_UPDATE_TAKEN_FALSE', + 1: 'DCP_CURSOR_UPDATE_TAKEN_TRUE', +} +DCP_CURSOR_UPDATE_TAKEN_FALSE = 0 +DCP_CURSOR_UPDATE_TAKEN_TRUE = 1 +DCP_CURSOR_UPDATE_TAKEN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_UPDATE_LOCK' +DCP_CURSOR_UPDATE_LOCK__enumvalues = { + 0: 'DCP_CURSOR_UPDATE_LOCK_FALSE', + 1: 'DCP_CURSOR_UPDATE_LOCK_TRUE', +} +DCP_CURSOR_UPDATE_LOCK_FALSE = 0 +DCP_CURSOR_UPDATE_LOCK_TRUE = 1 +DCP_CURSOR_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE' +DCP_CURSOR_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_FALSE', + 1: 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_TRUE', +} +DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_FALSE = 0 +DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_TRUE = 1 +DCP_CURSOR_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_UPDATE_STEREO_MODE' +DCP_CURSOR_UPDATE_STEREO_MODE__enumvalues = { + 0: 'DCP_CURSOR_UPDATE_STEREO_MODE_BOTH', + 1: 'DCP_CURSOR_UPDATE_STEREO_MODE_SECONDARY_ONLY', + 2: 'DCP_CURSOR_UPDATE_STEREO_MODE_UNDEFINED', + 3: 'DCP_CURSOR_UPDATE_STEREO_MODE_PRIMARY_ONLY', +} +DCP_CURSOR_UPDATE_STEREO_MODE_BOTH = 0 +DCP_CURSOR_UPDATE_STEREO_MODE_SECONDARY_ONLY = 1 +DCP_CURSOR_UPDATE_STEREO_MODE_UNDEFINED = 2 +DCP_CURSOR_UPDATE_STEREO_MODE_PRIMARY_ONLY = 3 +DCP_CURSOR_UPDATE_STEREO_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CUR2_INV_TRANS_CLAMP' +DCP_CUR2_INV_TRANS_CLAMP__enumvalues = { + 0: 'DCP_CUR2_INV_TRANS_CLAMP_FALSE', + 1: 'DCP_CUR2_INV_TRANS_CLAMP_TRUE', +} +DCP_CUR2_INV_TRANS_CLAMP_FALSE = 0 +DCP_CUR2_INV_TRANS_CLAMP_TRUE = 1 +DCP_CUR2_INV_TRANS_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CUR_REQUEST_FILTER_DIS' +DCP_CUR_REQUEST_FILTER_DIS__enumvalues = { + 0: 'DCP_CUR_REQUEST_FILTER_DIS_FALSE', + 1: 'DCP_CUR_REQUEST_FILTER_DIS_TRUE', +} +DCP_CUR_REQUEST_FILTER_DIS_FALSE = 0 +DCP_CUR_REQUEST_FILTER_DIS_TRUE = 1 +DCP_CUR_REQUEST_FILTER_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_STEREO_EN' +DCP_CURSOR_STEREO_EN__enumvalues = { + 0: 'DCP_CURSOR_STEREO_EN_FALSE', + 1: 'DCP_CURSOR_STEREO_EN_TRUE', +} +DCP_CURSOR_STEREO_EN_FALSE = 0 +DCP_CURSOR_STEREO_EN_TRUE = 1 +DCP_CURSOR_STEREO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_STEREO_OFFSET_YNX' +DCP_CURSOR_STEREO_OFFSET_YNX__enumvalues = { + 0: 'DCP_CURSOR_STEREO_OFFSET_YNX_X_POSITION', + 1: 'DCP_CURSOR_STEREO_OFFSET_YNX_Y_POSITION', +} +DCP_CURSOR_STEREO_OFFSET_YNX_X_POSITION = 0 +DCP_CURSOR_STEREO_OFFSET_YNX_Y_POSITION = 1 +DCP_CURSOR_STEREO_OFFSET_YNX = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_RW_MODE' +DCP_DC_LUT_RW_MODE__enumvalues = { + 0: 'DCP_DC_LUT_RW_MODE_256_ENTRY', + 1: 'DCP_DC_LUT_RW_MODE_PWL', +} +DCP_DC_LUT_RW_MODE_256_ENTRY = 0 +DCP_DC_LUT_RW_MODE_PWL = 1 +DCP_DC_LUT_RW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_VGA_ACCESS_ENABLE' +DCP_DC_LUT_VGA_ACCESS_ENABLE__enumvalues = { + 0: 'DCP_DC_LUT_VGA_ACCESS_ENABLE_FALSE', + 1: 'DCP_DC_LUT_VGA_ACCESS_ENABLE_TRUE', +} +DCP_DC_LUT_VGA_ACCESS_ENABLE_FALSE = 0 +DCP_DC_LUT_VGA_ACCESS_ENABLE_TRUE = 1 +DCP_DC_LUT_VGA_ACCESS_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_AUTOFILL' +DCP_DC_LUT_AUTOFILL__enumvalues = { + 0: 'DCP_DC_LUT_AUTOFILL_FALSE', + 1: 'DCP_DC_LUT_AUTOFILL_TRUE', +} +DCP_DC_LUT_AUTOFILL_FALSE = 0 +DCP_DC_LUT_AUTOFILL_TRUE = 1 +DCP_DC_LUT_AUTOFILL = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_AUTOFILL_DONE' +DCP_DC_LUT_AUTOFILL_DONE__enumvalues = { + 0: 'DCP_DC_LUT_AUTOFILL_DONE_FALSE', + 1: 'DCP_DC_LUT_AUTOFILL_DONE_TRUE', +} +DCP_DC_LUT_AUTOFILL_DONE_FALSE = 0 +DCP_DC_LUT_AUTOFILL_DONE_TRUE = 1 +DCP_DC_LUT_AUTOFILL_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_INC_B' +DCP_DC_LUT_INC_B__enumvalues = { + 0: 'DCP_DC_LUT_INC_B_NA', + 1: 'DCP_DC_LUT_INC_B_2', + 2: 'DCP_DC_LUT_INC_B_4', + 3: 'DCP_DC_LUT_INC_B_8', + 4: 'DCP_DC_LUT_INC_B_16', + 5: 'DCP_DC_LUT_INC_B_32', + 6: 'DCP_DC_LUT_INC_B_64', + 7: 'DCP_DC_LUT_INC_B_128', + 8: 'DCP_DC_LUT_INC_B_256', + 9: 'DCP_DC_LUT_INC_B_512', +} +DCP_DC_LUT_INC_B_NA = 0 +DCP_DC_LUT_INC_B_2 = 1 +DCP_DC_LUT_INC_B_4 = 2 +DCP_DC_LUT_INC_B_8 = 3 +DCP_DC_LUT_INC_B_16 = 4 +DCP_DC_LUT_INC_B_32 = 5 +DCP_DC_LUT_INC_B_64 = 6 +DCP_DC_LUT_INC_B_128 = 7 +DCP_DC_LUT_INC_B_256 = 8 +DCP_DC_LUT_INC_B_512 = 9 +DCP_DC_LUT_INC_B = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_B_SIGNED_EN' +DCP_DC_LUT_DATA_B_SIGNED_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_B_SIGNED_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_B_SIGNED_EN_TRUE', +} +DCP_DC_LUT_DATA_B_SIGNED_EN_FALSE = 0 +DCP_DC_LUT_DATA_B_SIGNED_EN_TRUE = 1 +DCP_DC_LUT_DATA_B_SIGNED_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN' +DCP_DC_LUT_DATA_B_FLOAT_POINT_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_TRUE', +} +DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_FALSE = 0 +DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_TRUE = 1 +DCP_DC_LUT_DATA_B_FLOAT_POINT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_B_FORMAT' +DCP_DC_LUT_DATA_B_FORMAT__enumvalues = { + 0: 'DCP_DC_LUT_DATA_B_FORMAT_U0P10', + 1: 'DCP_DC_LUT_DATA_B_FORMAT_S1P10', + 2: 'DCP_DC_LUT_DATA_B_FORMAT_U1P11', + 3: 'DCP_DC_LUT_DATA_B_FORMAT_U0P12', +} +DCP_DC_LUT_DATA_B_FORMAT_U0P10 = 0 +DCP_DC_LUT_DATA_B_FORMAT_S1P10 = 1 +DCP_DC_LUT_DATA_B_FORMAT_U1P11 = 2 +DCP_DC_LUT_DATA_B_FORMAT_U0P12 = 3 +DCP_DC_LUT_DATA_B_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_INC_G' +DCP_DC_LUT_INC_G__enumvalues = { + 0: 'DCP_DC_LUT_INC_G_NA', + 1: 'DCP_DC_LUT_INC_G_2', + 2: 'DCP_DC_LUT_INC_G_4', + 3: 'DCP_DC_LUT_INC_G_8', + 4: 'DCP_DC_LUT_INC_G_16', + 5: 'DCP_DC_LUT_INC_G_32', + 6: 'DCP_DC_LUT_INC_G_64', + 7: 'DCP_DC_LUT_INC_G_128', + 8: 'DCP_DC_LUT_INC_G_256', + 9: 'DCP_DC_LUT_INC_G_512', +} +DCP_DC_LUT_INC_G_NA = 0 +DCP_DC_LUT_INC_G_2 = 1 +DCP_DC_LUT_INC_G_4 = 2 +DCP_DC_LUT_INC_G_8 = 3 +DCP_DC_LUT_INC_G_16 = 4 +DCP_DC_LUT_INC_G_32 = 5 +DCP_DC_LUT_INC_G_64 = 6 +DCP_DC_LUT_INC_G_128 = 7 +DCP_DC_LUT_INC_G_256 = 8 +DCP_DC_LUT_INC_G_512 = 9 +DCP_DC_LUT_INC_G = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_G_SIGNED_EN' +DCP_DC_LUT_DATA_G_SIGNED_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_G_SIGNED_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_G_SIGNED_EN_TRUE', +} +DCP_DC_LUT_DATA_G_SIGNED_EN_FALSE = 0 +DCP_DC_LUT_DATA_G_SIGNED_EN_TRUE = 1 +DCP_DC_LUT_DATA_G_SIGNED_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN' +DCP_DC_LUT_DATA_G_FLOAT_POINT_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_TRUE', +} +DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_FALSE = 0 +DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_TRUE = 1 +DCP_DC_LUT_DATA_G_FLOAT_POINT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_G_FORMAT' +DCP_DC_LUT_DATA_G_FORMAT__enumvalues = { + 0: 'DCP_DC_LUT_DATA_G_FORMAT_U0P10', + 1: 'DCP_DC_LUT_DATA_G_FORMAT_S1P10', + 2: 'DCP_DC_LUT_DATA_G_FORMAT_U1P11', + 3: 'DCP_DC_LUT_DATA_G_FORMAT_U0P12', +} +DCP_DC_LUT_DATA_G_FORMAT_U0P10 = 0 +DCP_DC_LUT_DATA_G_FORMAT_S1P10 = 1 +DCP_DC_LUT_DATA_G_FORMAT_U1P11 = 2 +DCP_DC_LUT_DATA_G_FORMAT_U0P12 = 3 +DCP_DC_LUT_DATA_G_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_INC_R' +DCP_DC_LUT_INC_R__enumvalues = { + 0: 'DCP_DC_LUT_INC_R_NA', + 1: 'DCP_DC_LUT_INC_R_2', + 2: 'DCP_DC_LUT_INC_R_4', + 3: 'DCP_DC_LUT_INC_R_8', + 4: 'DCP_DC_LUT_INC_R_16', + 5: 'DCP_DC_LUT_INC_R_32', + 6: 'DCP_DC_LUT_INC_R_64', + 7: 'DCP_DC_LUT_INC_R_128', + 8: 'DCP_DC_LUT_INC_R_256', + 9: 'DCP_DC_LUT_INC_R_512', +} +DCP_DC_LUT_INC_R_NA = 0 +DCP_DC_LUT_INC_R_2 = 1 +DCP_DC_LUT_INC_R_4 = 2 +DCP_DC_LUT_INC_R_8 = 3 +DCP_DC_LUT_INC_R_16 = 4 +DCP_DC_LUT_INC_R_32 = 5 +DCP_DC_LUT_INC_R_64 = 6 +DCP_DC_LUT_INC_R_128 = 7 +DCP_DC_LUT_INC_R_256 = 8 +DCP_DC_LUT_INC_R_512 = 9 +DCP_DC_LUT_INC_R = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_R_SIGNED_EN' +DCP_DC_LUT_DATA_R_SIGNED_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_R_SIGNED_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_R_SIGNED_EN_TRUE', +} +DCP_DC_LUT_DATA_R_SIGNED_EN_FALSE = 0 +DCP_DC_LUT_DATA_R_SIGNED_EN_TRUE = 1 +DCP_DC_LUT_DATA_R_SIGNED_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN' +DCP_DC_LUT_DATA_R_FLOAT_POINT_EN__enumvalues = { + 0: 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_FALSE', + 1: 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_TRUE', +} +DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_FALSE = 0 +DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_TRUE = 1 +DCP_DC_LUT_DATA_R_FLOAT_POINT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_DC_LUT_DATA_R_FORMAT' +DCP_DC_LUT_DATA_R_FORMAT__enumvalues = { + 0: 'DCP_DC_LUT_DATA_R_FORMAT_U0P10', + 1: 'DCP_DC_LUT_DATA_R_FORMAT_S1P10', + 2: 'DCP_DC_LUT_DATA_R_FORMAT_U1P11', + 3: 'DCP_DC_LUT_DATA_R_FORMAT_U0P12', +} +DCP_DC_LUT_DATA_R_FORMAT_U0P10 = 0 +DCP_DC_LUT_DATA_R_FORMAT_S1P10 = 1 +DCP_DC_LUT_DATA_R_FORMAT_U1P11 = 2 +DCP_DC_LUT_DATA_R_FORMAT_U0P12 = 3 +DCP_DC_LUT_DATA_R_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CRC_ENABLE' +DCP_CRC_ENABLE__enumvalues = { + 0: 'DCP_CRC_ENABLE_FALSE', + 1: 'DCP_CRC_ENABLE_TRUE', +} +DCP_CRC_ENABLE_FALSE = 0 +DCP_CRC_ENABLE_TRUE = 1 +DCP_CRC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CRC_SOURCE_SEL' +DCP_CRC_SOURCE_SEL__enumvalues = { + 0: 'DCP_CRC_SOURCE_SEL_OUTPUT_PIX', + 1: 'DCP_CRC_SOURCE_SEL_INPUT_L32', + 2: 'DCP_CRC_SOURCE_SEL_INPUT_H32', + 4: 'DCP_CRC_SOURCE_SEL_OUTPUT_CNTL', +} +DCP_CRC_SOURCE_SEL_OUTPUT_PIX = 0 +DCP_CRC_SOURCE_SEL_INPUT_L32 = 1 +DCP_CRC_SOURCE_SEL_INPUT_H32 = 2 +DCP_CRC_SOURCE_SEL_OUTPUT_CNTL = 4 +DCP_CRC_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CRC_LINE_SEL' +DCP_CRC_LINE_SEL__enumvalues = { + 0: 'DCP_CRC_LINE_SEL_RESERVED', + 1: 'DCP_CRC_LINE_SEL_EVEN', + 2: 'DCP_CRC_LINE_SEL_ODD', + 3: 'DCP_CRC_LINE_SEL_BOTH', +} +DCP_CRC_LINE_SEL_RESERVED = 0 +DCP_CRC_LINE_SEL_EVEN = 1 +DCP_CRC_LINE_SEL_ODD = 2 +DCP_CRC_LINE_SEL_BOTH = 3 +DCP_CRC_LINE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_FLIP_RATE' +DCP_GRPH_FLIP_RATE__enumvalues = { + 0: 'DCP_GRPH_FLIP_RATE_1FRAME', + 1: 'DCP_GRPH_FLIP_RATE_2FRAME', + 2: 'DCP_GRPH_FLIP_RATE_3FRAME', + 3: 'DCP_GRPH_FLIP_RATE_4FRAME', + 4: 'DCP_GRPH_FLIP_RATE_5FRAME', + 5: 'DCP_GRPH_FLIP_RATE_6FRAME', + 6: 'DCP_GRPH_FLIP_RATE_7FRAME', + 7: 'DCP_GRPH_FLIP_RATE_8FRAME', +} +DCP_GRPH_FLIP_RATE_1FRAME = 0 +DCP_GRPH_FLIP_RATE_2FRAME = 1 +DCP_GRPH_FLIP_RATE_3FRAME = 2 +DCP_GRPH_FLIP_RATE_4FRAME = 3 +DCP_GRPH_FLIP_RATE_5FRAME = 4 +DCP_GRPH_FLIP_RATE_6FRAME = 5 +DCP_GRPH_FLIP_RATE_7FRAME = 6 +DCP_GRPH_FLIP_RATE_8FRAME = 7 +DCP_GRPH_FLIP_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_FLIP_RATE_ENABLE' +DCP_GRPH_FLIP_RATE_ENABLE__enumvalues = { + 0: 'DCP_GRPH_FLIP_RATE_ENABLE_FALSE', + 1: 'DCP_GRPH_FLIP_RATE_ENABLE_TRUE', +} +DCP_GRPH_FLIP_RATE_ENABLE_FALSE = 0 +DCP_GRPH_FLIP_RATE_ENABLE_TRUE = 1 +DCP_GRPH_FLIP_RATE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL0_EN' +DCP_GSL0_EN__enumvalues = { + 0: 'DCP_GSL0_EN_FALSE', + 1: 'DCP_GSL0_EN_TRUE', +} +DCP_GSL0_EN_FALSE = 0 +DCP_GSL0_EN_TRUE = 1 +DCP_GSL0_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL1_EN' +DCP_GSL1_EN__enumvalues = { + 0: 'DCP_GSL1_EN_FALSE', + 1: 'DCP_GSL1_EN_TRUE', +} +DCP_GSL1_EN_FALSE = 0 +DCP_GSL1_EN_TRUE = 1 +DCP_GSL1_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL2_EN' +DCP_GSL2_EN__enumvalues = { + 0: 'DCP_GSL2_EN_FALSE', + 1: 'DCP_GSL2_EN_TRUE', +} +DCP_GSL2_EN_FALSE = 0 +DCP_GSL2_EN_TRUE = 1 +DCP_GSL2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_MASTER_EN' +DCP_GSL_MASTER_EN__enumvalues = { + 0: 'DCP_GSL_MASTER_EN_FALSE', + 1: 'DCP_GSL_MASTER_EN_TRUE', +} +DCP_GSL_MASTER_EN_FALSE = 0 +DCP_GSL_MASTER_EN_TRUE = 1 +DCP_GSL_MASTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_XDMA_GROUP' +DCP_GSL_XDMA_GROUP__enumvalues = { + 0: 'DCP_GSL_XDMA_GROUP_VSYNC', + 1: 'DCP_GSL_XDMA_GROUP_HSYNC0', + 2: 'DCP_GSL_XDMA_GROUP_HSYNC1', + 3: 'DCP_GSL_XDMA_GROUP_HSYNC2', +} +DCP_GSL_XDMA_GROUP_VSYNC = 0 +DCP_GSL_XDMA_GROUP_HSYNC0 = 1 +DCP_GSL_XDMA_GROUP_HSYNC1 = 2 +DCP_GSL_XDMA_GROUP_HSYNC2 = 3 +DCP_GSL_XDMA_GROUP = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN' +DCP_GSL_XDMA_GROUP_UNDERFLOW_EN__enumvalues = { + 0: 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_FALSE', + 1: 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_TRUE', +} +DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_FALSE = 0 +DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_TRUE = 1 +DCP_GSL_XDMA_GROUP_UNDERFLOW_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_SYNC_SOURCE' +DCP_GSL_SYNC_SOURCE__enumvalues = { + 0: 'DCP_GSL_SYNC_SOURCE_FLIP', + 1: 'DCP_GSL_SYNC_SOURCE_PHASE0', + 2: 'DCP_GSL_SYNC_SOURCE_RESET', + 3: 'DCP_GSL_SYNC_SOURCE_PHASE1', +} +DCP_GSL_SYNC_SOURCE_FLIP = 0 +DCP_GSL_SYNC_SOURCE_PHASE0 = 1 +DCP_GSL_SYNC_SOURCE_RESET = 2 +DCP_GSL_SYNC_SOURCE_PHASE1 = 3 +DCP_GSL_SYNC_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC' +DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC__enumvalues = { + 0: 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_DIS', + 1: 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_EN', +} +DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_DIS = 0 +DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_EN = 1 +DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING' +DCP_GSL_DELAY_SURFACE_UPDATE_PENDING__enumvalues = { + 0: 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_FALSE', + 1: 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_TRUE', +} +DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_FALSE = 0 +DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_TRUE = 1 +DCP_GSL_DELAY_SURFACE_UPDATE_PENDING = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_TEST_DEBUG_WRITE_EN' +DCP_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'DCP_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'DCP_TEST_DEBUG_WRITE_EN_TRUE', +} +DCP_TEST_DEBUG_WRITE_EN_FALSE = 0 +DCP_TEST_DEBUG_WRITE_EN_TRUE = 1 +DCP_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_STEREOSYNC_FLIP_EN' +DCP_GRPH_STEREOSYNC_FLIP_EN__enumvalues = { + 0: 'DCP_GRPH_STEREOSYNC_FLIP_EN_FALSE', + 1: 'DCP_GRPH_STEREOSYNC_FLIP_EN_TRUE', +} +DCP_GRPH_STEREOSYNC_FLIP_EN_FALSE = 0 +DCP_GRPH_STEREOSYNC_FLIP_EN_TRUE = 1 +DCP_GRPH_STEREOSYNC_FLIP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_STEREOSYNC_FLIP_MODE' +DCP_GRPH_STEREOSYNC_FLIP_MODE__enumvalues = { + 0: 'DCP_GRPH_STEREOSYNC_FLIP_MODE_FLIP', + 1: 'DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE0', + 2: 'DCP_GRPH_STEREOSYNC_FLIP_MODE_RESET', + 3: 'DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE1', +} +DCP_GRPH_STEREOSYNC_FLIP_MODE_FLIP = 0 +DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE0 = 1 +DCP_GRPH_STEREOSYNC_FLIP_MODE_RESET = 2 +DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE1 = 3 +DCP_GRPH_STEREOSYNC_FLIP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE' +DCP_GRPH_STEREOSYNC_SELECT_DISABLE__enumvalues = { + 0: 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE_FALSE', + 1: 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE_TRUE', +} +DCP_GRPH_STEREOSYNC_SELECT_DISABLE_FALSE = 0 +DCP_GRPH_STEREOSYNC_SELECT_DISABLE_TRUE = 1 +DCP_GRPH_STEREOSYNC_SELECT_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_ROTATION_ANGLE' +DCP_GRPH_ROTATION_ANGLE__enumvalues = { + 0: 'DCP_GRPH_ROTATION_ANGLE_0', + 1: 'DCP_GRPH_ROTATION_ANGLE_90', + 2: 'DCP_GRPH_ROTATION_ANGLE_180', + 3: 'DCP_GRPH_ROTATION_ANGLE_270', +} +DCP_GRPH_ROTATION_ANGLE_0 = 0 +DCP_GRPH_ROTATION_ANGLE_90 = 1 +DCP_GRPH_ROTATION_ANGLE_180 = 2 +DCP_GRPH_ROTATION_ANGLE_270 = 3 +DCP_GRPH_ROTATION_ANGLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_FALSE', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_TRUE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_FALSE = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_TRUE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_NUM', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_ENABLE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_NUM = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_ENABLE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_REGAMMA_MODE' +DCP_GRPH_REGAMMA_MODE__enumvalues = { + 0: 'DCP_GRPH_REGAMMA_MODE_BYPASS', + 1: 'DCP_GRPH_REGAMMA_MODE_SRGB', + 2: 'DCP_GRPH_REGAMMA_MODE_XVYCC', + 3: 'DCP_GRPH_REGAMMA_MODE_PROGA', + 4: 'DCP_GRPH_REGAMMA_MODE_PROGB', +} +DCP_GRPH_REGAMMA_MODE_BYPASS = 0 +DCP_GRPH_REGAMMA_MODE_SRGB = 1 +DCP_GRPH_REGAMMA_MODE_XVYCC = 2 +DCP_GRPH_REGAMMA_MODE_PROGA = 3 +DCP_GRPH_REGAMMA_MODE_PROGB = 4 +DCP_GRPH_REGAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_ALPHA_ROUND_TRUNC_MODE' +DCP_ALPHA_ROUND_TRUNC_MODE__enumvalues = { + 0: 'DCP_ALPHA_ROUND_TRUNC_MODE_ROUND', + 1: 'DCP_ALPHA_ROUND_TRUNC_MODE_TRUNC', +} +DCP_ALPHA_ROUND_TRUNC_MODE_ROUND = 0 +DCP_ALPHA_ROUND_TRUNC_MODE_TRUNC = 1 +DCP_ALPHA_ROUND_TRUNC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_CURSOR_ALPHA_BLND_ENA' +DCP_CURSOR_ALPHA_BLND_ENA__enumvalues = { + 0: 'DCP_CURSOR_ALPHA_BLND_ENA_FALSE', + 1: 'DCP_CURSOR_ALPHA_BLND_ENA_TRUE', +} +DCP_CURSOR_ALPHA_BLND_ENA_FALSE = 0 +DCP_CURSOR_ALPHA_BLND_ENA_TRUE = 1 +DCP_CURSOR_ALPHA_BLND_ENA = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_FALSE', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_TRUE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_FALSE = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_TRUE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_FALSE', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_TRUE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_FALSE = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_TRUE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_FALSE', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_TRUE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_FALSE = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_TRUE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK' +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK__enumvalues = { + 0: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_FALSE', + 1: 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_TRUE', +} +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_FALSE = 0 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_TRUE = 1 +DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_COUNTER_EN' +DCP_GRPH_SURFACE_COUNTER_EN__enumvalues = { + 0: 'DCP_GRPH_SURFACE_COUNTER_EN_DISABLE', + 1: 'DCP_GRPH_SURFACE_COUNTER_EN_ENABLE', +} +DCP_GRPH_SURFACE_COUNTER_EN_DISABLE = 0 +DCP_GRPH_SURFACE_COUNTER_EN_ENABLE = 1 +DCP_GRPH_SURFACE_COUNTER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT' +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT__enumvalues = { + 0: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_0', + 1: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_1', + 2: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_2', + 3: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_3', + 4: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_4', + 5: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_5', + 6: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_6', + 7: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_7', + 8: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_8', + 9: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_9', + 10: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_10', + 11: 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_11', +} +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_0 = 0 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_1 = 1 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_2 = 2 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_3 = 3 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_4 = 4 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_5 = 5 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_6 = 6 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_7 = 7 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_8 = 8 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_9 = 9 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_10 = 10 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_11 = 11 +DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED' +DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED__enumvalues = { + 0: 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_NO', + 1: 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_YES', +} +DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_NO = 0 +DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_YES = 1 +DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR' +DCP_GRPH_XDMA_FLIP_TYPE_CLEAR__enumvalues = { + 0: 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_DISABLE', + 1: 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_ENABLE', +} +DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_DISABLE = 0 +DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_ENABLE = 1 +DCP_GRPH_XDMA_FLIP_TYPE_CLEAR = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_DRR_MODE_ENABLE' +DCP_GRPH_XDMA_DRR_MODE_ENABLE__enumvalues = { + 0: 'DCP_GRPH_XDMA_DRR_MODE_ENABLE_DISABLE', + 1: 'DCP_GRPH_XDMA_DRR_MODE_ENABLE_ENABLE', +} +DCP_GRPH_XDMA_DRR_MODE_ENABLE_DISABLE = 0 +DCP_GRPH_XDMA_DRR_MODE_ENABLE_ENABLE = 1 +DCP_GRPH_XDMA_DRR_MODE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE' +DCP_GRPH_XDMA_MULTIFLIP_ENABLE__enumvalues = { + 0: 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE_DISABLE', + 1: 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE_ENABLE', +} +DCP_GRPH_XDMA_MULTIFLIP_ENABLE_DISABLE = 0 +DCP_GRPH_XDMA_MULTIFLIP_ENABLE_ENABLE = 1 +DCP_GRPH_XDMA_MULTIFLIP_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK' +DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK__enumvalues = { + 0: 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_FALSE', + 1: 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_TRUE', +} +DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_FALSE = 0 +DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_TRUE = 1 +DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK' +DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK__enumvalues = { + 0: 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_FALSE', + 1: 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_TRUE', +} +DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_FALSE = 0 +DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_TRUE = 1 +DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CVALUE_SEL' +PERFCOUNTER_CVALUE_SEL__enumvalues = { + 0: 'PERFCOUNTER_CVALUE_SEL_47_0', + 1: 'PERFCOUNTER_CVALUE_SEL_15_0', + 2: 'PERFCOUNTER_CVALUE_SEL_31_16', + 3: 'PERFCOUNTER_CVALUE_SEL_47_32', + 4: 'PERFCOUNTER_CVALUE_SEL_11_0', + 5: 'PERFCOUNTER_CVALUE_SEL_23_12', + 6: 'PERFCOUNTER_CVALUE_SEL_35_24', + 7: 'PERFCOUNTER_CVALUE_SEL_47_36', +} +PERFCOUNTER_CVALUE_SEL_47_0 = 0 +PERFCOUNTER_CVALUE_SEL_15_0 = 1 +PERFCOUNTER_CVALUE_SEL_31_16 = 2 +PERFCOUNTER_CVALUE_SEL_47_32 = 3 +PERFCOUNTER_CVALUE_SEL_11_0 = 4 +PERFCOUNTER_CVALUE_SEL_23_12 = 5 +PERFCOUNTER_CVALUE_SEL_35_24 = 6 +PERFCOUNTER_CVALUE_SEL_47_36 = 7 +PERFCOUNTER_CVALUE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INC_MODE' +PERFCOUNTER_INC_MODE__enumvalues = { + 0: 'PERFCOUNTER_INC_MODE_MULTI_BIT', + 1: 'PERFCOUNTER_INC_MODE_BOTH_EDGE', + 2: 'PERFCOUNTER_INC_MODE_LSB', + 3: 'PERFCOUNTER_INC_MODE_POS_EDGE', + 4: 'PERFCOUNTER_INC_MODE_NEG_EDGE', +} +PERFCOUNTER_INC_MODE_MULTI_BIT = 0 +PERFCOUNTER_INC_MODE_BOTH_EDGE = 1 +PERFCOUNTER_INC_MODE_LSB = 2 +PERFCOUNTER_INC_MODE_POS_EDGE = 3 +PERFCOUNTER_INC_MODE_NEG_EDGE = 4 +PERFCOUNTER_INC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_HW_CNTL_SEL' +PERFCOUNTER_HW_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', + 1: 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', +} +PERFCOUNTER_HW_CNTL_SEL_RUNEN = 0 +PERFCOUNTER_HW_CNTL_SEL_CNTOFF = 1 +PERFCOUNTER_HW_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RUNEN_MODE' +PERFCOUNTER_RUNEN_MODE__enumvalues = { + 0: 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 1: 'PERFCOUNTER_RUNEN_MODE_EDGE', +} +PERFCOUNTER_RUNEN_MODE_LEVEL = 0 +PERFCOUNTER_RUNEN_MODE_EDGE = 1 +PERFCOUNTER_RUNEN_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTOFF_START_DIS' +PERFCOUNTER_CNTOFF_START_DIS__enumvalues = { + 0: 'PERFCOUNTER_CNTOFF_START_ENABLE', + 1: 'PERFCOUNTER_CNTOFF_START_DISABLE', +} +PERFCOUNTER_CNTOFF_START_ENABLE = 0 +PERFCOUNTER_CNTOFF_START_DISABLE = 1 +PERFCOUNTER_CNTOFF_START_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_RESTART_EN' +PERFCOUNTER_RESTART_EN__enumvalues = { + 0: 'PERFCOUNTER_RESTART_DISABLE', + 1: 'PERFCOUNTER_RESTART_ENABLE', +} +PERFCOUNTER_RESTART_DISABLE = 0 +PERFCOUNTER_RESTART_ENABLE = 1 +PERFCOUNTER_RESTART_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_EN' +PERFCOUNTER_INT_EN__enumvalues = { + 0: 'PERFCOUNTER_INT_DISABLE', + 1: 'PERFCOUNTER_INT_ENABLE', +} +PERFCOUNTER_INT_DISABLE = 0 +PERFCOUNTER_INT_ENABLE = 1 +PERFCOUNTER_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_OFF_MASK' +PERFCOUNTER_OFF_MASK__enumvalues = { + 0: 'PERFCOUNTER_OFF_MASK_DISABLE', + 1: 'PERFCOUNTER_OFF_MASK_ENABLE', +} +PERFCOUNTER_OFF_MASK_DISABLE = 0 +PERFCOUNTER_OFF_MASK_ENABLE = 1 +PERFCOUNTER_OFF_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_ACTIVE' +PERFCOUNTER_ACTIVE__enumvalues = { + 0: 'PERFCOUNTER_IS_IDLE', + 1: 'PERFCOUNTER_IS_ACTIVE', +} +PERFCOUNTER_IS_IDLE = 0 +PERFCOUNTER_IS_ACTIVE = 1 +PERFCOUNTER_ACTIVE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_INT_TYPE' +PERFCOUNTER_INT_TYPE__enumvalues = { + 0: 'PERFCOUNTER_INT_TYPE_LEVEL', + 1: 'PERFCOUNTER_INT_TYPE_PULSE', +} +PERFCOUNTER_INT_TYPE_LEVEL = 0 +PERFCOUNTER_INT_TYPE_PULSE = 1 +PERFCOUNTER_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_COUNTED_VALUE_TYPE' +PERFCOUNTER_COUNTED_VALUE_TYPE__enumvalues = { + 0: 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 1: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 2: 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', +} +PERFCOUNTER_COUNTED_VALUE_TYPE_ACC = 0 +PERFCOUNTER_COUNTED_VALUE_TYPE_MAX = 1 +PERFCOUNTER_COUNTED_VALUE_TYPE_MIN = 2 +PERFCOUNTER_COUNTED_VALUE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNTL_SEL' +PERFCOUNTER_CNTL_SEL__enumvalues = { + 0: 'PERFCOUNTER_CNTL_SEL_0', + 1: 'PERFCOUNTER_CNTL_SEL_1', + 2: 'PERFCOUNTER_CNTL_SEL_2', + 3: 'PERFCOUNTER_CNTL_SEL_3', + 4: 'PERFCOUNTER_CNTL_SEL_4', + 5: 'PERFCOUNTER_CNTL_SEL_5', + 6: 'PERFCOUNTER_CNTL_SEL_6', + 7: 'PERFCOUNTER_CNTL_SEL_7', +} +PERFCOUNTER_CNTL_SEL_0 = 0 +PERFCOUNTER_CNTL_SEL_1 = 1 +PERFCOUNTER_CNTL_SEL_2 = 2 +PERFCOUNTER_CNTL_SEL_3 = 3 +PERFCOUNTER_CNTL_SEL_4 = 4 +PERFCOUNTER_CNTL_SEL_5 = 5 +PERFCOUNTER_CNTL_SEL_6 = 6 +PERFCOUNTER_CNTL_SEL_7 = 7 +PERFCOUNTER_CNTL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT0_STATE' +PERFCOUNTER_CNT0_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT0_STATE_RESET', + 1: 'PERFCOUNTER_CNT0_STATE_START', + 2: 'PERFCOUNTER_CNT0_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT0_STATE_HW', +} +PERFCOUNTER_CNT0_STATE_RESET = 0 +PERFCOUNTER_CNT0_STATE_START = 1 +PERFCOUNTER_CNT0_STATE_FREEZE = 2 +PERFCOUNTER_CNT0_STATE_HW = 3 +PERFCOUNTER_CNT0_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL0' +PERFCOUNTER_STATE_SEL0__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL0_LOCAL', +} +PERFCOUNTER_STATE_SEL0_GLOBAL = 0 +PERFCOUNTER_STATE_SEL0_LOCAL = 1 +PERFCOUNTER_STATE_SEL0 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT1_STATE' +PERFCOUNTER_CNT1_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT1_STATE_RESET', + 1: 'PERFCOUNTER_CNT1_STATE_START', + 2: 'PERFCOUNTER_CNT1_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT1_STATE_HW', +} +PERFCOUNTER_CNT1_STATE_RESET = 0 +PERFCOUNTER_CNT1_STATE_START = 1 +PERFCOUNTER_CNT1_STATE_FREEZE = 2 +PERFCOUNTER_CNT1_STATE_HW = 3 +PERFCOUNTER_CNT1_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL1' +PERFCOUNTER_STATE_SEL1__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL1_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL1_LOCAL', +} +PERFCOUNTER_STATE_SEL1_GLOBAL = 0 +PERFCOUNTER_STATE_SEL1_LOCAL = 1 +PERFCOUNTER_STATE_SEL1 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT2_STATE' +PERFCOUNTER_CNT2_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT2_STATE_RESET', + 1: 'PERFCOUNTER_CNT2_STATE_START', + 2: 'PERFCOUNTER_CNT2_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT2_STATE_HW', +} +PERFCOUNTER_CNT2_STATE_RESET = 0 +PERFCOUNTER_CNT2_STATE_START = 1 +PERFCOUNTER_CNT2_STATE_FREEZE = 2 +PERFCOUNTER_CNT2_STATE_HW = 3 +PERFCOUNTER_CNT2_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL2' +PERFCOUNTER_STATE_SEL2__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL2_LOCAL', +} +PERFCOUNTER_STATE_SEL2_GLOBAL = 0 +PERFCOUNTER_STATE_SEL2_LOCAL = 1 +PERFCOUNTER_STATE_SEL2 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT3_STATE' +PERFCOUNTER_CNT3_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT3_STATE_RESET', + 1: 'PERFCOUNTER_CNT3_STATE_START', + 2: 'PERFCOUNTER_CNT3_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT3_STATE_HW', +} +PERFCOUNTER_CNT3_STATE_RESET = 0 +PERFCOUNTER_CNT3_STATE_START = 1 +PERFCOUNTER_CNT3_STATE_FREEZE = 2 +PERFCOUNTER_CNT3_STATE_HW = 3 +PERFCOUNTER_CNT3_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL3' +PERFCOUNTER_STATE_SEL3__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL3_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL3_LOCAL', +} +PERFCOUNTER_STATE_SEL3_GLOBAL = 0 +PERFCOUNTER_STATE_SEL3_LOCAL = 1 +PERFCOUNTER_STATE_SEL3 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT4_STATE' +PERFCOUNTER_CNT4_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT4_STATE_RESET', + 1: 'PERFCOUNTER_CNT4_STATE_START', + 2: 'PERFCOUNTER_CNT4_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT4_STATE_HW', +} +PERFCOUNTER_CNT4_STATE_RESET = 0 +PERFCOUNTER_CNT4_STATE_START = 1 +PERFCOUNTER_CNT4_STATE_FREEZE = 2 +PERFCOUNTER_CNT4_STATE_HW = 3 +PERFCOUNTER_CNT4_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL4' +PERFCOUNTER_STATE_SEL4__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL4_LOCAL', +} +PERFCOUNTER_STATE_SEL4_GLOBAL = 0 +PERFCOUNTER_STATE_SEL4_LOCAL = 1 +PERFCOUNTER_STATE_SEL4 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT5_STATE' +PERFCOUNTER_CNT5_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT5_STATE_RESET', + 1: 'PERFCOUNTER_CNT5_STATE_START', + 2: 'PERFCOUNTER_CNT5_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT5_STATE_HW', +} +PERFCOUNTER_CNT5_STATE_RESET = 0 +PERFCOUNTER_CNT5_STATE_START = 1 +PERFCOUNTER_CNT5_STATE_FREEZE = 2 +PERFCOUNTER_CNT5_STATE_HW = 3 +PERFCOUNTER_CNT5_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL5' +PERFCOUNTER_STATE_SEL5__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL5_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL5_LOCAL', +} +PERFCOUNTER_STATE_SEL5_GLOBAL = 0 +PERFCOUNTER_STATE_SEL5_LOCAL = 1 +PERFCOUNTER_STATE_SEL5 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT6_STATE' +PERFCOUNTER_CNT6_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT6_STATE_RESET', + 1: 'PERFCOUNTER_CNT6_STATE_START', + 2: 'PERFCOUNTER_CNT6_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT6_STATE_HW', +} +PERFCOUNTER_CNT6_STATE_RESET = 0 +PERFCOUNTER_CNT6_STATE_START = 1 +PERFCOUNTER_CNT6_STATE_FREEZE = 2 +PERFCOUNTER_CNT6_STATE_HW = 3 +PERFCOUNTER_CNT6_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL6' +PERFCOUNTER_STATE_SEL6__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL6_LOCAL', +} +PERFCOUNTER_STATE_SEL6_GLOBAL = 0 +PERFCOUNTER_STATE_SEL6_LOCAL = 1 +PERFCOUNTER_STATE_SEL6 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_CNT7_STATE' +PERFCOUNTER_CNT7_STATE__enumvalues = { + 0: 'PERFCOUNTER_CNT7_STATE_RESET', + 1: 'PERFCOUNTER_CNT7_STATE_START', + 2: 'PERFCOUNTER_CNT7_STATE_FREEZE', + 3: 'PERFCOUNTER_CNT7_STATE_HW', +} +PERFCOUNTER_CNT7_STATE_RESET = 0 +PERFCOUNTER_CNT7_STATE_START = 1 +PERFCOUNTER_CNT7_STATE_FREEZE = 2 +PERFCOUNTER_CNT7_STATE_HW = 3 +PERFCOUNTER_CNT7_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFCOUNTER_STATE_SEL7' +PERFCOUNTER_STATE_SEL7__enumvalues = { + 0: 'PERFCOUNTER_STATE_SEL7_GLOBAL', + 1: 'PERFCOUNTER_STATE_SEL7_LOCAL', +} +PERFCOUNTER_STATE_SEL7_GLOBAL = 0 +PERFCOUNTER_STATE_SEL7_LOCAL = 1 +PERFCOUNTER_STATE_SEL7 = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_STATE' +PERFMON_STATE__enumvalues = { + 0: 'PERFMON_STATE_RESET', + 1: 'PERFMON_STATE_START', + 2: 'PERFMON_STATE_FREEZE', + 3: 'PERFMON_STATE_HW', +} +PERFMON_STATE_RESET = 0 +PERFMON_STATE_START = 1 +PERFMON_STATE_FREEZE = 2 +PERFMON_STATE_HW = 3 +PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_AND_OR' +PERFMON_CNTOFF_AND_OR__enumvalues = { + 0: 'PERFMON_CNTOFF_OR', + 1: 'PERFMON_CNTOFF_AND', +} +PERFMON_CNTOFF_OR = 0 +PERFMON_CNTOFF_AND = 1 +PERFMON_CNTOFF_AND_OR = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_EN' +PERFMON_CNTOFF_INT_EN__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_DISABLE', + 1: 'PERFMON_CNTOFF_INT_ENABLE', +} +PERFMON_CNTOFF_INT_DISABLE = 0 +PERFMON_CNTOFF_INT_ENABLE = 1 +PERFMON_CNTOFF_INT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'PERFMON_CNTOFF_INT_TYPE' +PERFMON_CNTOFF_INT_TYPE__enumvalues = { + 0: 'PERFMON_CNTOFF_INT_TYPE_LEVEL', + 1: 'PERFMON_CNTOFF_INT_TYPE_PULSE', +} +PERFMON_CNTOFF_INT_TYPE_LEVEL = 0 +PERFMON_CNTOFF_INT_TYPE_PULSE = 1 +PERFMON_CNTOFF_INT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_C_RAM_TAP_PAIR_IDX' +SCL_C_RAM_TAP_PAIR_IDX__enumvalues = { + 0: 'SCL_C_RAM_TAP_PAIR_ID0', + 1: 'SCL_C_RAM_TAP_PAIR_ID1', + 2: 'SCL_C_RAM_TAP_PAIR_ID2', + 3: 'SCL_C_RAM_TAP_PAIR_ID3', + 4: 'SCL_C_RAM_TAP_PAIR_ID4', +} +SCL_C_RAM_TAP_PAIR_ID0 = 0 +SCL_C_RAM_TAP_PAIR_ID1 = 1 +SCL_C_RAM_TAP_PAIR_ID2 = 2 +SCL_C_RAM_TAP_PAIR_ID3 = 3 +SCL_C_RAM_TAP_PAIR_ID4 = 4 +SCL_C_RAM_TAP_PAIR_IDX = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_C_RAM_PHASE' +SCL_C_RAM_PHASE__enumvalues = { + 0: 'SCL_C_RAM_PHASE_0', + 1: 'SCL_C_RAM_PHASE_1', + 2: 'SCL_C_RAM_PHASE_2', + 3: 'SCL_C_RAM_PHASE_3', + 4: 'SCL_C_RAM_PHASE_4', + 5: 'SCL_C_RAM_PHASE_5', + 6: 'SCL_C_RAM_PHASE_6', + 7: 'SCL_C_RAM_PHASE_7', + 8: 'SCL_C_RAM_PHASE_8', +} +SCL_C_RAM_PHASE_0 = 0 +SCL_C_RAM_PHASE_1 = 1 +SCL_C_RAM_PHASE_2 = 2 +SCL_C_RAM_PHASE_3 = 3 +SCL_C_RAM_PHASE_4 = 4 +SCL_C_RAM_PHASE_5 = 5 +SCL_C_RAM_PHASE_6 = 6 +SCL_C_RAM_PHASE_7 = 7 +SCL_C_RAM_PHASE_8 = 8 +SCL_C_RAM_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_C_RAM_FILTER_TYPE' +SCL_C_RAM_FILTER_TYPE__enumvalues = { + 0: 'SCL_C_RAM_FILTER_TYPE_VERT_LUMA_RGB_LUT', + 1: 'SCL_C_RAM_FILTER_TYPE_VERT_CHROMA_LUT', + 2: 'SCL_C_RAM_FILTER_TYPE_HORI_LUMA_RGB_LUT', + 3: 'SCL_C_RAM_FILTER_TYPE_HORI_CHROMA_LUT', +} +SCL_C_RAM_FILTER_TYPE_VERT_LUMA_RGB_LUT = 0 +SCL_C_RAM_FILTER_TYPE_VERT_CHROMA_LUT = 1 +SCL_C_RAM_FILTER_TYPE_HORI_LUMA_RGB_LUT = 2 +SCL_C_RAM_FILTER_TYPE_HORI_CHROMA_LUT = 3 +SCL_C_RAM_FILTER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_MODE_SEL' +SCL_MODE_SEL__enumvalues = { + 0: 'SCL_MODE_RGB_BYPASS', + 1: 'SCL_MODE_RGB_SCALING', + 2: 'SCL_MODE_YCBCR_SCALING', + 3: 'SCL_MODE_YCBCR_BYPASS', +} +SCL_MODE_RGB_BYPASS = 0 +SCL_MODE_RGB_SCALING = 1 +SCL_MODE_YCBCR_SCALING = 2 +SCL_MODE_YCBCR_BYPASS = 3 +SCL_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_PSCL_EN' +SCL_PSCL_EN__enumvalues = { + 0: 'SCL_PSCL_DISABLE', + 1: 'SCL_PSCL_ENANBLE', +} +SCL_PSCL_DISABLE = 0 +SCL_PSCL_ENANBLE = 1 +SCL_PSCL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_V_NUM_OF_TAPS' +SCL_V_NUM_OF_TAPS__enumvalues = { + 0: 'SCL_V_NUM_OF_TAPS_1', + 1: 'SCL_V_NUM_OF_TAPS_2', + 2: 'SCL_V_NUM_OF_TAPS_3', + 3: 'SCL_V_NUM_OF_TAPS_4', + 4: 'SCL_V_NUM_OF_TAPS_5', + 5: 'SCL_V_NUM_OF_TAPS_6', +} +SCL_V_NUM_OF_TAPS_1 = 0 +SCL_V_NUM_OF_TAPS_2 = 1 +SCL_V_NUM_OF_TAPS_3 = 2 +SCL_V_NUM_OF_TAPS_4 = 3 +SCL_V_NUM_OF_TAPS_5 = 4 +SCL_V_NUM_OF_TAPS_6 = 5 +SCL_V_NUM_OF_TAPS = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_H_NUM_OF_TAPS' +SCL_H_NUM_OF_TAPS__enumvalues = { + 0: 'SCL_H_NUM_OF_TAPS_1', + 1: 'SCL_H_NUM_OF_TAPS_2', + 3: 'SCL_H_NUM_OF_TAPS_4', + 5: 'SCL_H_NUM_OF_TAPS_6', + 7: 'SCL_H_NUM_OF_TAPS_8', + 9: 'SCL_H_NUM_OF_TAPS_10', +} +SCL_H_NUM_OF_TAPS_1 = 0 +SCL_H_NUM_OF_TAPS_2 = 1 +SCL_H_NUM_OF_TAPS_4 = 3 +SCL_H_NUM_OF_TAPS_6 = 5 +SCL_H_NUM_OF_TAPS_8 = 7 +SCL_H_NUM_OF_TAPS_10 = 9 +SCL_H_NUM_OF_TAPS = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_BOUNDARY_MODE' +SCL_BOUNDARY_MODE__enumvalues = { + 0: 'SCL_BOUNDARY_MODE_BLACK', + 1: 'SCL_BOUNDARY_MODE_EDGE', +} +SCL_BOUNDARY_MODE_BLACK = 0 +SCL_BOUNDARY_MODE_EDGE = 1 +SCL_BOUNDARY_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_EARLY_EOL_MOD' +SCL_EARLY_EOL_MOD__enumvalues = { + 0: 'SCL_EARLY_EOL_MODE_CRTC', + 1: 'SCL_EARLY_EOL_MODE_INTERNAL', +} +SCL_EARLY_EOL_MODE_CRTC = 0 +SCL_EARLY_EOL_MODE_INTERNAL = 1 +SCL_EARLY_EOL_MOD = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_BYPASS_MODE' +SCL_BYPASS_MODE__enumvalues = { + 0: 'SCL_BYPASS_MODE_MC_MR', + 1: 'SCL_BYPASS_MODE_AC_NR', + 2: 'SCL_BYPASS_MODE_AC_AR', + 3: 'SCL_BYPASS_MODE_RESERVED', +} +SCL_BYPASS_MODE_MC_MR = 0 +SCL_BYPASS_MODE_AC_NR = 1 +SCL_BYPASS_MODE_AC_AR = 2 +SCL_BYPASS_MODE_RESERVED = 3 +SCL_BYPASS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_V_MANUAL_REPLICATE_FACTOR' +SCL_V_MANUAL_REPLICATE_FACTOR__enumvalues = { + 0: 'SCL_V_MANUAL_REPLICATE_FACTOR_1', + 1: 'SCL_V_MANUAL_REPLICATE_FACTOR_2', + 2: 'SCL_V_MANUAL_REPLICATE_FACTOR_3', + 3: 'SCL_V_MANUAL_REPLICATE_FACTOR_4', + 4: 'SCL_V_MANUAL_REPLICATE_FACTOR_5', + 5: 'SCL_V_MANUAL_REPLICATE_FACTOR_6', + 6: 'SCL_V_MANUAL_REPLICATE_FACTOR_7', + 7: 'SCL_V_MANUAL_REPLICATE_FACTOR_8', + 8: 'SCL_V_MANUAL_REPLICATE_FACTOR_9', + 9: 'SCL_V_MANUAL_REPLICATE_FACTOR_10', + 10: 'SCL_V_MANUAL_REPLICATE_FACTOR_11', + 11: 'SCL_V_MANUAL_REPLICATE_FACTOR_12', + 12: 'SCL_V_MANUAL_REPLICATE_FACTOR_13', + 13: 'SCL_V_MANUAL_REPLICATE_FACTOR_14', + 14: 'SCL_V_MANUAL_REPLICATE_FACTOR_15', + 15: 'SCL_V_MANUAL_REPLICATE_FACTOR_16', +} +SCL_V_MANUAL_REPLICATE_FACTOR_1 = 0 +SCL_V_MANUAL_REPLICATE_FACTOR_2 = 1 +SCL_V_MANUAL_REPLICATE_FACTOR_3 = 2 +SCL_V_MANUAL_REPLICATE_FACTOR_4 = 3 +SCL_V_MANUAL_REPLICATE_FACTOR_5 = 4 +SCL_V_MANUAL_REPLICATE_FACTOR_6 = 5 +SCL_V_MANUAL_REPLICATE_FACTOR_7 = 6 +SCL_V_MANUAL_REPLICATE_FACTOR_8 = 7 +SCL_V_MANUAL_REPLICATE_FACTOR_9 = 8 +SCL_V_MANUAL_REPLICATE_FACTOR_10 = 9 +SCL_V_MANUAL_REPLICATE_FACTOR_11 = 10 +SCL_V_MANUAL_REPLICATE_FACTOR_12 = 11 +SCL_V_MANUAL_REPLICATE_FACTOR_13 = 12 +SCL_V_MANUAL_REPLICATE_FACTOR_14 = 13 +SCL_V_MANUAL_REPLICATE_FACTOR_15 = 14 +SCL_V_MANUAL_REPLICATE_FACTOR_16 = 15 +SCL_V_MANUAL_REPLICATE_FACTOR = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_H_MANUAL_REPLICATE_FACTOR' +SCL_H_MANUAL_REPLICATE_FACTOR__enumvalues = { + 0: 'SCL_H_MANUAL_REPLICATE_FACTOR_1', + 1: 'SCL_H_MANUAL_REPLICATE_FACTOR_2', + 2: 'SCL_H_MANUAL_REPLICATE_FACTOR_3', + 3: 'SCL_H_MANUAL_REPLICATE_FACTOR_4', + 4: 'SCL_H_MANUAL_REPLICATE_FACTOR_5', + 5: 'SCL_H_MANUAL_REPLICATE_FACTOR_6', + 6: 'SCL_H_MANUAL_REPLICATE_FACTOR_7', + 7: 'SCL_H_MANUAL_REPLICATE_FACTOR_8', + 8: 'SCL_H_MANUAL_REPLICATE_FACTOR_9', + 9: 'SCL_H_MANUAL_REPLICATE_FACTOR_10', + 10: 'SCL_H_MANUAL_REPLICATE_FACTOR_11', + 11: 'SCL_H_MANUAL_REPLICATE_FACTOR_12', + 12: 'SCL_H_MANUAL_REPLICATE_FACTOR_13', + 13: 'SCL_H_MANUAL_REPLICATE_FACTOR_14', + 14: 'SCL_H_MANUAL_REPLICATE_FACTOR_15', + 15: 'SCL_H_MANUAL_REPLICATE_FACTOR_16', +} +SCL_H_MANUAL_REPLICATE_FACTOR_1 = 0 +SCL_H_MANUAL_REPLICATE_FACTOR_2 = 1 +SCL_H_MANUAL_REPLICATE_FACTOR_3 = 2 +SCL_H_MANUAL_REPLICATE_FACTOR_4 = 3 +SCL_H_MANUAL_REPLICATE_FACTOR_5 = 4 +SCL_H_MANUAL_REPLICATE_FACTOR_6 = 5 +SCL_H_MANUAL_REPLICATE_FACTOR_7 = 6 +SCL_H_MANUAL_REPLICATE_FACTOR_8 = 7 +SCL_H_MANUAL_REPLICATE_FACTOR_9 = 8 +SCL_H_MANUAL_REPLICATE_FACTOR_10 = 9 +SCL_H_MANUAL_REPLICATE_FACTOR_11 = 10 +SCL_H_MANUAL_REPLICATE_FACTOR_12 = 11 +SCL_H_MANUAL_REPLICATE_FACTOR_13 = 12 +SCL_H_MANUAL_REPLICATE_FACTOR_14 = 13 +SCL_H_MANUAL_REPLICATE_FACTOR_15 = 14 +SCL_H_MANUAL_REPLICATE_FACTOR_16 = 15 +SCL_H_MANUAL_REPLICATE_FACTOR = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_V_CALC_AUTO_RATIO_EN' +SCL_V_CALC_AUTO_RATIO_EN__enumvalues = { + 0: 'SCL_V_CALC_AUTO_RATIO_DISABLE', + 1: 'SCL_V_CALC_AUTO_RATIO_ENABLE', +} +SCL_V_CALC_AUTO_RATIO_DISABLE = 0 +SCL_V_CALC_AUTO_RATIO_ENABLE = 1 +SCL_V_CALC_AUTO_RATIO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_H_CALC_AUTO_RATIO_EN' +SCL_H_CALC_AUTO_RATIO_EN__enumvalues = { + 0: 'SCL_H_CALC_AUTO_RATIO_DISABLE', + 1: 'SCL_H_CALC_AUTO_RATIO_ENABLE', +} +SCL_H_CALC_AUTO_RATIO_DISABLE = 0 +SCL_H_CALC_AUTO_RATIO_ENABLE = 1 +SCL_H_CALC_AUTO_RATIO_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_H_FILTER_PICK_NEAREST' +SCL_H_FILTER_PICK_NEAREST__enumvalues = { + 0: 'SCL_H_FILTER_PICK_NEAREST_DISABLE', + 1: 'SCL_H_FILTER_PICK_NEAREST_ENABLE', +} +SCL_H_FILTER_PICK_NEAREST_DISABLE = 0 +SCL_H_FILTER_PICK_NEAREST_ENABLE = 1 +SCL_H_FILTER_PICK_NEAREST = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_H_2TAP_HARDCODE_COEF_EN' +SCL_H_2TAP_HARDCODE_COEF_EN__enumvalues = { + 0: 'SCL_H_2TAP_HARDCODE_COEF_DISABLE', + 1: 'SCL_H_2TAP_HARDCODE_COEF_ENABLE', +} +SCL_H_2TAP_HARDCODE_COEF_DISABLE = 0 +SCL_H_2TAP_HARDCODE_COEF_ENABLE = 1 +SCL_H_2TAP_HARDCODE_COEF_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_V_FILTER_PICK_NEAREST' +SCL_V_FILTER_PICK_NEAREST__enumvalues = { + 0: 'SCL_V_FILTER_PICK_NEAREST_DISABLE', + 1: 'SCL_V_FILTER_PICK_NEAREST_ENABLE', +} +SCL_V_FILTER_PICK_NEAREST_DISABLE = 0 +SCL_V_FILTER_PICK_NEAREST_ENABLE = 1 +SCL_V_FILTER_PICK_NEAREST = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_V_2TAP_HARDCODE_COEF_EN' +SCL_V_2TAP_HARDCODE_COEF_EN__enumvalues = { + 0: 'SCL_V_2TAP_HARDCODE_COEF_DISABLE', + 1: 'SCL_V_2TAP_HARDCODE_COEF_ENABLE', +} +SCL_V_2TAP_HARDCODE_COEF_DISABLE = 0 +SCL_V_2TAP_HARDCODE_COEF_ENABLE = 1 +SCL_V_2TAP_HARDCODE_COEF_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_UPDATE_TAKEN' +SCL_UPDATE_TAKEN__enumvalues = { + 0: 'SCL_UPDATE_TAKEN_NO', + 1: 'SCL_UPDATE_TAKEN_YES', +} +SCL_UPDATE_TAKEN_NO = 0 +SCL_UPDATE_TAKEN_YES = 1 +SCL_UPDATE_TAKEN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_UPDATE_LOCK' +SCL_UPDATE_LOCK__enumvalues = { + 0: 'SCL_UPDATE_UNLOCKED', + 1: 'SCL_UPDATE_LOCKED', +} +SCL_UPDATE_UNLOCKED = 0 +SCL_UPDATE_LOCKED = 1 +SCL_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_COEF_UPDATE_COMPLETE' +SCL_COEF_UPDATE_COMPLETE__enumvalues = { + 0: 'SCL_COEF_UPDATE_NOT_COMPLETED', + 1: 'SCL_COEF_UPDATE_COMPLETED', +} +SCL_COEF_UPDATE_NOT_COMPLETED = 0 +SCL_COEF_UPDATE_COMPLETED = 1 +SCL_COEF_UPDATE_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_HF_SHARP_SCALE_FACTOR' +SCL_HF_SHARP_SCALE_FACTOR__enumvalues = { + 0: 'SCL_HF_SHARP_SCALE_FACTOR_0', + 1: 'SCL_HF_SHARP_SCALE_FACTOR_1', + 2: 'SCL_HF_SHARP_SCALE_FACTOR_2', + 3: 'SCL_HF_SHARP_SCALE_FACTOR_3', + 4: 'SCL_HF_SHARP_SCALE_FACTOR_4', + 5: 'SCL_HF_SHARP_SCALE_FACTOR_5', + 6: 'SCL_HF_SHARP_SCALE_FACTOR_6', + 7: 'SCL_HF_SHARP_SCALE_FACTOR_7', +} +SCL_HF_SHARP_SCALE_FACTOR_0 = 0 +SCL_HF_SHARP_SCALE_FACTOR_1 = 1 +SCL_HF_SHARP_SCALE_FACTOR_2 = 2 +SCL_HF_SHARP_SCALE_FACTOR_3 = 3 +SCL_HF_SHARP_SCALE_FACTOR_4 = 4 +SCL_HF_SHARP_SCALE_FACTOR_5 = 5 +SCL_HF_SHARP_SCALE_FACTOR_6 = 6 +SCL_HF_SHARP_SCALE_FACTOR_7 = 7 +SCL_HF_SHARP_SCALE_FACTOR = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_HF_SHARP_EN' +SCL_HF_SHARP_EN__enumvalues = { + 0: 'SCL_HF_SHARP_DISABLE', + 1: 'SCL_HF_SHARP_ENABLE', +} +SCL_HF_SHARP_DISABLE = 0 +SCL_HF_SHARP_ENABLE = 1 +SCL_HF_SHARP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_VF_SHARP_SCALE_FACTOR' +SCL_VF_SHARP_SCALE_FACTOR__enumvalues = { + 0: 'SCL_VF_SHARP_SCALE_FACTOR_0', + 1: 'SCL_VF_SHARP_SCALE_FACTOR_1', + 2: 'SCL_VF_SHARP_SCALE_FACTOR_2', + 3: 'SCL_VF_SHARP_SCALE_FACTOR_3', + 4: 'SCL_VF_SHARP_SCALE_FACTOR_4', + 5: 'SCL_VF_SHARP_SCALE_FACTOR_5', + 6: 'SCL_VF_SHARP_SCALE_FACTOR_6', + 7: 'SCL_VF_SHARP_SCALE_FACTOR_7', +} +SCL_VF_SHARP_SCALE_FACTOR_0 = 0 +SCL_VF_SHARP_SCALE_FACTOR_1 = 1 +SCL_VF_SHARP_SCALE_FACTOR_2 = 2 +SCL_VF_SHARP_SCALE_FACTOR_3 = 3 +SCL_VF_SHARP_SCALE_FACTOR_4 = 4 +SCL_VF_SHARP_SCALE_FACTOR_5 = 5 +SCL_VF_SHARP_SCALE_FACTOR_6 = 6 +SCL_VF_SHARP_SCALE_FACTOR_7 = 7 +SCL_VF_SHARP_SCALE_FACTOR = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_VF_SHARP_EN' +SCL_VF_SHARP_EN__enumvalues = { + 0: 'SCL_VF_SHARP_DISABLE', + 1: 'SCL_VF_SHARP_ENABLE', +} +SCL_VF_SHARP_DISABLE = 0 +SCL_VF_SHARP_ENABLE = 1 +SCL_VF_SHARP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_ALU_DISABLE' +SCL_ALU_DISABLE__enumvalues = { + 0: 'SCL_ALU_ENABLED', + 1: 'SCL_ALU_DISABLED', +} +SCL_ALU_ENABLED = 0 +SCL_ALU_DISABLED = 1 +SCL_ALU_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_HOST_CONFLICT_MASK' +SCL_HOST_CONFLICT_MASK__enumvalues = { + 0: 'SCL_HOST_CONFLICT_DISABLE_INTERRUPT', + 1: 'SCL_HOST_CONFLICT_ENABLE_INTERRUPT', +} +SCL_HOST_CONFLICT_DISABLE_INTERRUPT = 0 +SCL_HOST_CONFLICT_ENABLE_INTERRUPT = 1 +SCL_HOST_CONFLICT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SCL_SCL_MODE_CHANGE_MASK' +SCL_SCL_MODE_CHANGE_MASK__enumvalues = { + 0: 'SCL_MODE_CHANGE_DISABLE_INTERRUPT', + 1: 'SCL_MODE_CHANGE_ENABLE_INTERRUPT', +} +SCL_MODE_CHANGE_DISABLE_INTERRUPT = 0 +SCL_MODE_CHANGE_ENABLE_INTERRUPT = 1 +SCL_SCL_MODE_CHANGE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SCLV_MODE_SEL' +SCLV_MODE_SEL__enumvalues = { + 0: 'SCLV_MODE_RGB_BYPASS', + 1: 'SCLV_MODE_RGB_SCALING', + 2: 'SCLV_MODE_YCBCR_SCALING', + 3: 'SCLV_MODE_YCBCR_BYPASS', +} +SCLV_MODE_RGB_BYPASS = 0 +SCLV_MODE_RGB_SCALING = 1 +SCLV_MODE_YCBCR_SCALING = 2 +SCLV_MODE_YCBCR_BYPASS = 3 +SCLV_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SCLV_INTERLACE_SOURCE' +SCLV_INTERLACE_SOURCE__enumvalues = { + 0: 'INTERLACE_SOURCE_PROGRESSIVE', + 1: 'INTERLACE_SOURCE_INTERLEAVE', + 2: 'INTERLACE_SOURCE_STACK', +} +INTERLACE_SOURCE_PROGRESSIVE = 0 +INTERLACE_SOURCE_INTERLEAVE = 1 +INTERLACE_SOURCE_STACK = 2 +SCLV_INTERLACE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'SCLV_UPDATE_LOCK' +SCLV_UPDATE_LOCK__enumvalues = { + 0: 'UPDATE_UNLOCKED', + 1: 'UPDATE_LOCKED', +} +UPDATE_UNLOCKED = 0 +UPDATE_LOCKED = 1 +SCLV_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'SCLV_COEF_UPDATE_COMPLETE' +SCLV_COEF_UPDATE_COMPLETE__enumvalues = { + 0: 'COEF_UPDATE_NOT_COMPLETE', + 1: 'COEF_UPDATE_COMPLETE', +} +COEF_UPDATE_NOT_COMPLETE = 0 +COEF_UPDATE_COMPLETE = 1 +SCLV_COEF_UPDATE_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'DPRX_SD_PIXEL_ENCODING' +DPRX_SD_PIXEL_ENCODING__enumvalues = { + 0: 'PIXEL_FORMAT_RGB_444', + 1: 'PIXEL_FORMAT_YCBCR_444', + 2: 'PIXEL_FORMAT_YCBCR_422', + 3: 'PIXEL_FORMAT_Y_ONLY', +} +PIXEL_FORMAT_RGB_444 = 0 +PIXEL_FORMAT_YCBCR_444 = 1 +PIXEL_FORMAT_YCBCR_422 = 2 +PIXEL_FORMAT_Y_ONLY = 3 +DPRX_SD_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'DPRX_SD_COMPONENT_DEPTH' +DPRX_SD_COMPONENT_DEPTH__enumvalues = { + 0: 'COMPONENT_DEPTH_6BPC', + 1: 'COMPONENT_DEPTH_8BPC', + 2: 'COMPONENT_DEPTH_10BPC', + 3: 'COMPONENT_DEPTH_12BPC', + 4: 'COMPONENT_DEPTH_16BPC', +} +COMPONENT_DEPTH_6BPC = 0 +COMPONENT_DEPTH_8BPC = 1 +COMPONENT_DEPTH_10BPC = 2 +COMPONENT_DEPTH_12BPC = 3 +COMPONENT_DEPTH_16BPC = 4 +DPRX_SD_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_LATENCY_COUNTER_CONTROL' +AZ_LATENCY_COUNTER_CONTROL__enumvalues = { + 0: 'AZ_LATENCY_COUNTER_NO_RESET', + 1: 'AZ_LATENCY_COUNTER_RESET_DONE', +} +AZ_LATENCY_COUNTER_NO_RESET = 0 +AZ_LATENCY_COUNTER_RESET_DONE = 1 +AZ_LATENCY_COUNTER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_MODE' +BLND_CONTROL_BLND_MODE__enumvalues = { + 0: 'BLND_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY', + 1: 'BLND_CONTROL_BLND_MODE_OTHER_PIPE_ONLY', + 2: 'BLND_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE', + 3: 'BLND_CONTROL_BLND_MODE_OTHER_STEREO_TYPE', +} +BLND_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY = 0 +BLND_CONTROL_BLND_MODE_OTHER_PIPE_ONLY = 1 +BLND_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE = 2 +BLND_CONTROL_BLND_MODE_OTHER_STEREO_TYPE = 3 +BLND_CONTROL_BLND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_STEREO_TYPE' +BLND_CONTROL_BLND_STEREO_TYPE__enumvalues = { + 0: 'BLND_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO', + 1: 'BLND_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO', + 2: 'BLND_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO', + 3: 'BLND_CONTROL_BLND_STEREO_TYPE_UNUSED', +} +BLND_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO = 0 +BLND_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO = 1 +BLND_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO = 2 +BLND_CONTROL_BLND_STEREO_TYPE_UNUSED = 3 +BLND_CONTROL_BLND_STEREO_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_STEREO_POLARITY' +BLND_CONTROL_BLND_STEREO_POLARITY__enumvalues = { + 0: 'BLND_CONTROL_BLND_STEREO_POLARITY_LOW', + 1: 'BLND_CONTROL_BLND_STEREO_POLARITY_HIGH', +} +BLND_CONTROL_BLND_STEREO_POLARITY_LOW = 0 +BLND_CONTROL_BLND_STEREO_POLARITY_HIGH = 1 +BLND_CONTROL_BLND_STEREO_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_FEEDTHROUGH_EN' +BLND_CONTROL_BLND_FEEDTHROUGH_EN__enumvalues = { + 0: 'BLND_CONTROL_BLND_FEEDTHROUGH_EN_FALSE', + 1: 'BLND_CONTROL_BLND_FEEDTHROUGH_EN_TRUE', +} +BLND_CONTROL_BLND_FEEDTHROUGH_EN_FALSE = 0 +BLND_CONTROL_BLND_FEEDTHROUGH_EN_TRUE = 1 +BLND_CONTROL_BLND_FEEDTHROUGH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_ALPHA_MODE' +BLND_CONTROL_BLND_ALPHA_MODE__enumvalues = { + 0: 'BLND_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA', + 1: 'BLND_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 2: 'BLND_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY', + 3: 'BLND_CONTROL_BLND_ALPHA_MODE_UNUSED', +} +BLND_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA = 0 +BLND_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN = 1 +BLND_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY = 2 +BLND_CONTROL_BLND_ALPHA_MODE_UNUSED = 3 +BLND_CONTROL_BLND_ALPHA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_ACTIVE_OVERLAP_ONLY' +BLND_CONTROL_BLND_ACTIVE_OVERLAP_ONLY__enumvalues = { + 0: 'BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_FALSE', + 1: 'BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_TRUE', +} +BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_FALSE = 0 +BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_TRUE = 1 +BLND_CONTROL_BLND_ACTIVE_OVERLAP_ONLY = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL_BLND_MULTIPLIED_MODE' +BLND_CONTROL_BLND_MULTIPLIED_MODE__enumvalues = { + 0: 'BLND_CONTROL_BLND_MULTIPLIED_MODE_FALSE', + 1: 'BLND_CONTROL_BLND_MULTIPLIED_MODE_TRUE', +} +BLND_CONTROL_BLND_MULTIPLIED_MODE_FALSE = 0 +BLND_CONTROL_BLND_MULTIPLIED_MODE_TRUE = 1 +BLND_CONTROL_BLND_MULTIPLIED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_SM_CONTROL2_SM_MODE' +BLND_SM_CONTROL2_SM_MODE__enumvalues = { + 0: 'BLND_SM_CONTROL2_SM_MODE_SINGLE_PLANE', + 2: 'BLND_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING', + 4: 'BLND_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING', + 6: 'BLND_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING', +} +BLND_SM_CONTROL2_SM_MODE_SINGLE_PLANE = 0 +BLND_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING = 2 +BLND_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING = 4 +BLND_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING = 6 +BLND_SM_CONTROL2_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE' +BLND_SM_CONTROL2_SM_FRAME_ALTERNATE__enumvalues = { + 0: 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE', + 1: 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE', +} +BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE = 0 +BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE = 1 +BLND_SM_CONTROL2_SM_FRAME_ALTERNATE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE' +BLND_SM_CONTROL2_SM_FIELD_ALTERNATE__enumvalues = { + 0: 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE', + 1: 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE', +} +BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE = 0 +BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE = 1 +BLND_SM_CONTROL2_SM_FIELD_ALTERNATE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL' +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL__enumvalues = { + 0: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 1: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 2: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 3: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', +} +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE = 0 +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED = 1 +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW = 2 +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH = 3 +BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL' +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL__enumvalues = { + 0: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 1: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED', + 2: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 3: 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', +} +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE = 0 +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED = 1 +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW = 2 +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH = 3 +BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL2_PTI_ENABLE' +BLND_CONTROL2_PTI_ENABLE__enumvalues = { + 0: 'BLND_CONTROL2_PTI_ENABLE_FALSE', + 1: 'BLND_CONTROL2_PTI_ENABLE_TRUE', +} +BLND_CONTROL2_PTI_ENABLE_FALSE = 0 +BLND_CONTROL2_PTI_ENABLE_TRUE = 1 +BLND_CONTROL2_PTI_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN' +BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN__enumvalues = { + 0: 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE', + 1: 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE', +} +BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE = 0 +BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE = 1 +BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN' +BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN__enumvalues = { + 0: 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE', + 1: 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE', +} +BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE = 0 +BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE = 1 +BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK' +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK__enumvalues = { + 0: 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE', + 1: 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE', +} +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE = 0 +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE = 1 +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK' +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK__enumvalues = { + 0: 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE', + 1: 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE', +} +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE = 0 +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE = 1 +BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK' +BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE' +BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE__enumvalues = { + 0: 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE', + 1: 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE', +} +BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE = 0 +BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE = 1 +BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_DEBUG_BLND_CNV_MUX_SELECT' +BLND_DEBUG_BLND_CNV_MUX_SELECT__enumvalues = { + 0: 'BLND_DEBUG_BLND_CNV_MUX_SELECT_LOW', + 1: 'BLND_DEBUG_BLND_CNV_MUX_SELECT_HIGH', +} +BLND_DEBUG_BLND_CNV_MUX_SELECT_LOW = 0 +BLND_DEBUG_BLND_CNV_MUX_SELECT_HIGH = 1 +BLND_DEBUG_BLND_CNV_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN' +BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN__enumvalues = { + 0: 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE', + 1: 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE', +} +BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE = 0 +BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE = 1 +BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 9: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED = 8 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 1: 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', +} +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY = 0 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY = 1 +AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES' +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 1: 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', +} +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC = 0 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO = 1 +AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 2: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 3: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 4: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 5: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 6: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 7: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 8: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 9: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED = 2 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED = 3 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED = 4 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED = 5 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED = 6 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED = 7 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED = 8 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED = 9 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE' +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE__enumvalues = { + 0: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 1: 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', +} +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY = 0 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY = 1 +AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_EN' +UNP_GRPH_EN__enumvalues = { + 0: 'UNP_GRPH_DISABLED', + 1: 'UNP_GRPH_ENABLED', +} +UNP_GRPH_DISABLED = 0 +UNP_GRPH_ENABLED = 1 +UNP_GRPH_EN = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_DEPTH' +UNP_GRPH_DEPTH__enumvalues = { + 0: 'UNP_GRPH_8BPP', + 1: 'UNP_GRPH_16BPP', + 2: 'UNP_GRPH_32BPP', +} +UNP_GRPH_8BPP = 0 +UNP_GRPH_16BPP = 1 +UNP_GRPH_32BPP = 2 +UNP_GRPH_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_NUM_BANKS' +UNP_GRPH_NUM_BANKS__enumvalues = { + 0: 'UNP_GRPH_ADDR_SURF_2_BANK', + 1: 'UNP_GRPH_ADDR_SURF_4_BANK', + 2: 'UNP_GRPH_ADDR_SURF_8_BANK', + 3: 'UNP_GRPH_ADDR_SURF_16_BANK', +} +UNP_GRPH_ADDR_SURF_2_BANK = 0 +UNP_GRPH_ADDR_SURF_4_BANK = 1 +UNP_GRPH_ADDR_SURF_8_BANK = 2 +UNP_GRPH_ADDR_SURF_16_BANK = 3 +UNP_GRPH_NUM_BANKS = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_BANK_WIDTH' +UNP_GRPH_BANK_WIDTH__enumvalues = { + 0: 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_1', + 1: 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_2', + 2: 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_4', + 3: 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_8', +} +UNP_GRPH_ADDR_SURF_BANK_WIDTH_1 = 0 +UNP_GRPH_ADDR_SURF_BANK_WIDTH_2 = 1 +UNP_GRPH_ADDR_SURF_BANK_WIDTH_4 = 2 +UNP_GRPH_ADDR_SURF_BANK_WIDTH_8 = 3 +UNP_GRPH_BANK_WIDTH = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_BANK_HEIGHT' +UNP_GRPH_BANK_HEIGHT__enumvalues = { + 0: 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_1', + 1: 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_2', + 2: 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_4', + 3: 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_8', +} +UNP_GRPH_ADDR_SURF_BANK_HEIGHT_1 = 0 +UNP_GRPH_ADDR_SURF_BANK_HEIGHT_2 = 1 +UNP_GRPH_ADDR_SURF_BANK_HEIGHT_4 = 2 +UNP_GRPH_ADDR_SURF_BANK_HEIGHT_8 = 3 +UNP_GRPH_BANK_HEIGHT = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_TILE_SPLIT' +UNP_GRPH_TILE_SPLIT__enumvalues = { + 0: 'UNP_ADDR_SURF_TILE_SPLIT_64B', + 1: 'UNP_ADDR_SURF_TILE_SPLIT_128B', + 2: 'UNP_ADDR_SURF_TILE_SPLIT_256B', + 3: 'UNP_ADDR_SURF_TILE_SPLIT_512B', + 4: 'UNP_ADDR_SURF_TILE_SPLIT_1KB', + 5: 'UNP_ADDR_SURF_TILE_SPLIT_2KB', + 6: 'UNP_ADDR_SURF_TILE_SPLIT_4KB', +} +UNP_ADDR_SURF_TILE_SPLIT_64B = 0 +UNP_ADDR_SURF_TILE_SPLIT_128B = 1 +UNP_ADDR_SURF_TILE_SPLIT_256B = 2 +UNP_ADDR_SURF_TILE_SPLIT_512B = 3 +UNP_ADDR_SURF_TILE_SPLIT_1KB = 4 +UNP_ADDR_SURF_TILE_SPLIT_2KB = 5 +UNP_ADDR_SURF_TILE_SPLIT_4KB = 6 +UNP_GRPH_TILE_SPLIT = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE' +UNP_GRPH_ADDRESS_TRANSLATION_ENABLE__enumvalues = { + 0: 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE0', + 1: 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE1', +} +UNP_GRPH_ADDRESS_TRANSLATION_ENABLE0 = 0 +UNP_GRPH_ADDRESS_TRANSLATION_ENABLE1 = 1 +UNP_GRPH_ADDRESS_TRANSLATION_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_MACRO_TILE_ASPECT' +UNP_GRPH_MACRO_TILE_ASPECT__enumvalues = { + 0: 'UNP_ADDR_SURF_MACRO_ASPECT_1', + 1: 'UNP_ADDR_SURF_MACRO_ASPECT_2', + 2: 'UNP_ADDR_SURF_MACRO_ASPECT_4', + 3: 'UNP_ADDR_SURF_MACRO_ASPECT_8', +} +UNP_ADDR_SURF_MACRO_ASPECT_1 = 0 +UNP_ADDR_SURF_MACRO_ASPECT_2 = 1 +UNP_ADDR_SURF_MACRO_ASPECT_4 = 2 +UNP_ADDR_SURF_MACRO_ASPECT_8 = 3 +UNP_GRPH_MACRO_TILE_ASPECT = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_COLOR_EXPANSION_MODE' +UNP_GRPH_COLOR_EXPANSION_MODE__enumvalues = { + 0: 'UNP_GRPH_DYNAMIC_EXPANSION', + 1: 'UNP_GRPH_ZERO_EXPANSION', +} +UNP_GRPH_DYNAMIC_EXPANSION = 0 +UNP_GRPH_ZERO_EXPANSION = 1 +UNP_GRPH_COLOR_EXPANSION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_VIDEO_FORMAT' +UNP_VIDEO_FORMAT__enumvalues = { + 0: 'UNP_VIDEO_FORMAT0', + 1: 'UNP_VIDEO_FORMAT1', + 2: 'UNP_VIDEO_FORMAT_YUV420_YCbCr', + 3: 'UNP_VIDEO_FORMAT_YUV420_YCrCb', + 4: 'UNP_VIDEO_FORMAT_YUV422_YCb', + 5: 'UNP_VIDEO_FORMAT_YUV422_YCr', + 6: 'UNP_VIDEO_FORMAT_YUV422_CbY', + 7: 'UNP_VIDEO_FORMAT_YUV422_CrY', +} +UNP_VIDEO_FORMAT0 = 0 +UNP_VIDEO_FORMAT1 = 1 +UNP_VIDEO_FORMAT_YUV420_YCbCr = 2 +UNP_VIDEO_FORMAT_YUV420_YCrCb = 3 +UNP_VIDEO_FORMAT_YUV422_YCb = 4 +UNP_VIDEO_FORMAT_YUV422_YCr = 5 +UNP_VIDEO_FORMAT_YUV422_CbY = 6 +UNP_VIDEO_FORMAT_YUV422_CrY = 7 +UNP_VIDEO_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_ENDIAN_SWAP' +UNP_GRPH_ENDIAN_SWAP__enumvalues = { + 0: 'UNP_GRPH_ENDIAN_SWAP_NONE', + 1: 'UNP_GRPH_ENDIAN_SWAP_8IN16', + 2: 'UNP_GRPH_ENDIAN_SWAP_8IN32', + 3: 'UNP_GRPH_ENDIAN_SWAP_8IN43', +} +UNP_GRPH_ENDIAN_SWAP_NONE = 0 +UNP_GRPH_ENDIAN_SWAP_8IN16 = 1 +UNP_GRPH_ENDIAN_SWAP_8IN32 = 2 +UNP_GRPH_ENDIAN_SWAP_8IN43 = 3 +UNP_GRPH_ENDIAN_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_RED_CROSSBAR' +UNP_GRPH_RED_CROSSBAR__enumvalues = { + 0: 'UNP_GRPH_RED_CROSSBAR_R_Cr', + 1: 'UNP_GRPH_RED_CROSSBAR_G_Y', + 2: 'UNP_GRPH_RED_CROSSBAR_B_Cb', + 3: 'UNP_GRPH_RED_CROSSBAR_A', +} +UNP_GRPH_RED_CROSSBAR_R_Cr = 0 +UNP_GRPH_RED_CROSSBAR_G_Y = 1 +UNP_GRPH_RED_CROSSBAR_B_Cb = 2 +UNP_GRPH_RED_CROSSBAR_A = 3 +UNP_GRPH_RED_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_GREEN_CROSSBAR' +UNP_GRPH_GREEN_CROSSBAR__enumvalues = { + 0: 'UNP_UNP_GRPH_GREEN_CROSSBAR_GY_AND_Y', + 1: 'UNP_UNP_GRPH_GREEN_CROSSBAR_B_Cb_AND_C', + 2: 'UNP_UNP_GRPH_GREEN_CROSSBAR_A', + 3: 'UNP_UNP_GRPH_GREEN_CROSSBAR_R_Cr', +} +UNP_UNP_GRPH_GREEN_CROSSBAR_GY_AND_Y = 0 +UNP_UNP_GRPH_GREEN_CROSSBAR_B_Cb_AND_C = 1 +UNP_UNP_GRPH_GREEN_CROSSBAR_A = 2 +UNP_UNP_GRPH_GREEN_CROSSBAR_R_Cr = 3 +UNP_GRPH_GREEN_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_BLUE_CROSSBAR' +UNP_GRPH_BLUE_CROSSBAR__enumvalues = { + 0: 'UNP_GRPH_BLUE_CROSSBAR_B_Cb_AND_C', + 1: 'UNP_GRPH_BLUE_CROSSBAR_A', + 2: 'UNP_GRPH_BLUE_CROSSBAR_R_Cr', + 3: 'UNP_GRPH_BLUE_CROSSBAR_GY_AND_Y', +} +UNP_GRPH_BLUE_CROSSBAR_B_Cb_AND_C = 0 +UNP_GRPH_BLUE_CROSSBAR_A = 1 +UNP_GRPH_BLUE_CROSSBAR_R_Cr = 2 +UNP_GRPH_BLUE_CROSSBAR_GY_AND_Y = 3 +UNP_GRPH_BLUE_CROSSBAR = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_MODE_UPDATE_LOCKG' +UNP_GRPH_MODE_UPDATE_LOCKG__enumvalues = { + 0: 'UNP_GRPH_UPDATE_LOCK_0', + 1: 'UNP_GRPH_UPDATE_LOCK_1', +} +UNP_GRPH_UPDATE_LOCK_0 = 0 +UNP_GRPH_UPDATE_LOCK_1 = 1 +UNP_GRPH_MODE_UPDATE_LOCKG = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK' +UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK__enumvalues = { + 0: 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_0', + 1: 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_1', +} +UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_0 = 0 +UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_1 = 1 +UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE' +UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_0', + 1: 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_1', +} +UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_0 = 0 +UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_1 = 1 +UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE' +UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_0', + 1: 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_1', +} +UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_0 = 0 +UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_1 = 1 +UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_STEREOSYNC_FLIP_EN' +UNP_GRPH_STEREOSYNC_FLIP_EN__enumvalues = { + 0: 'UNP_GRPH_STEREOSYNC_FLIP_DISABLE', + 1: 'UNP_GRPH_STEREOSYNC_FLIP_ENABLE', +} +UNP_GRPH_STEREOSYNC_FLIP_DISABLE = 0 +UNP_GRPH_STEREOSYNC_FLIP_ENABLE = 1 +UNP_GRPH_STEREOSYNC_FLIP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_STEREOSYNC_FLIP_MODE' +UNP_GRPH_STEREOSYNC_FLIP_MODE__enumvalues = { + 0: 'UNP_GRPH_STEREOSYNC_FLIP_MODE_0', + 1: 'UNP_GRPH_STEREOSYNC_FLIP_MODE_1', + 2: 'UNP_GRPH_STEREOSYNC_FLIP_MODE_2', + 3: 'UNP_GRPH_STEREOSYNC_FLIP_MODE_3', +} +UNP_GRPH_STEREOSYNC_FLIP_MODE_0 = 0 +UNP_GRPH_STEREOSYNC_FLIP_MODE_1 = 1 +UNP_GRPH_STEREOSYNC_FLIP_MODE_2 = 2 +UNP_GRPH_STEREOSYNC_FLIP_MODE_3 = 3 +UNP_GRPH_STEREOSYNC_FLIP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_STACK_INTERLACE_FLIP_EN' +UNP_GRPH_STACK_INTERLACE_FLIP_EN__enumvalues = { + 0: 'UNP_GRPH_STACK_INTERLACE_FLIP_DISABLE', + 1: 'UNP_GRPH_STACK_INTERLACE_FLIP_ENABLE', +} +UNP_GRPH_STACK_INTERLACE_FLIP_DISABLE = 0 +UNP_GRPH_STACK_INTERLACE_FLIP_ENABLE = 1 +UNP_GRPH_STACK_INTERLACE_FLIP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE' +UNP_GRPH_STACK_INTERLACE_FLIP_MODE__enumvalues = { + 0: 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_0', + 1: 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_1', + 2: 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_2', + 3: 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_3', +} +UNP_GRPH_STACK_INTERLACE_FLIP_MODE_0 = 0 +UNP_GRPH_STACK_INTERLACE_FLIP_MODE_1 = 1 +UNP_GRPH_STACK_INTERLACE_FLIP_MODE_2 = 2 +UNP_GRPH_STACK_INTERLACE_FLIP_MODE_3 = 3 +UNP_GRPH_STACK_INTERLACE_FLIP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_GRPH_STEREOSYNC_SELECT_DISABLE' +UNP_GRPH_STEREOSYNC_SELECT_DISABLE__enumvalues = { + 0: 'UNP_GRPH_STEREOSYNC_SELECT_EN', + 1: 'UNP_GRPH_STEREOSYNC_SELECT_DIS', +} +UNP_GRPH_STEREOSYNC_SELECT_EN = 0 +UNP_GRPH_STEREOSYNC_SELECT_DIS = 1 +UNP_GRPH_STEREOSYNC_SELECT_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_CRC_SOURCE_SEL' +UNP_CRC_SOURCE_SEL__enumvalues = { + 0: 'UNP_CRC_SOURCE_SEL_NP_TO_LBV', + 1: 'UNP_CRC_SOURCE_SEL_LOWER32', + 2: 'UNP_CRC_SOURCE_SEL_RESERVED', + 3: 'UNP_CRC_SOURCE_SEL_LOWER16', + 4: 'UNP_CRC_SOURCE_SEL_UNP_TO_LBV', +} +UNP_CRC_SOURCE_SEL_NP_TO_LBV = 0 +UNP_CRC_SOURCE_SEL_LOWER32 = 1 +UNP_CRC_SOURCE_SEL_RESERVED = 2 +UNP_CRC_SOURCE_SEL_LOWER16 = 3 +UNP_CRC_SOURCE_SEL_UNP_TO_LBV = 4 +UNP_CRC_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_CRC_LINE_SEL' +UNP_CRC_LINE_SEL__enumvalues = { + 0: 'UNP_CRC_LINE_SEL_RESERVED', + 1: 'UNP_CRC_LINE_SEL_EVEN_ONLY', + 2: 'UNP_CRC_LINE_SEL_ODD_ONLY', + 3: 'UNP_CRC_LINE_SEL_ODD_EVEN', +} +UNP_CRC_LINE_SEL_RESERVED = 0 +UNP_CRC_LINE_SEL_EVEN_ONLY = 1 +UNP_CRC_LINE_SEL_ODD_ONLY = 2 +UNP_CRC_LINE_SEL_ODD_EVEN = 3 +UNP_CRC_LINE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_ROTATION_ANGLE' +UNP_ROTATION_ANGLE__enumvalues = { + 0: 'UNP_ROTATION_ANGLE_0', + 1: 'UNP_ROTATION_ANGLE_90', + 2: 'UNP_ROTATION_ANGLE_180', + 3: 'UNP_ROTATION_ANGLE_270', + 4: 'UNP_ROTATION_ANGLE_0m', + 5: 'UNP_ROTATION_ANGLE_90m', + 6: 'UNP_ROTATION_ANGLE_180m', + 7: 'UNP_ROTATION_ANGLE_270m', +} +UNP_ROTATION_ANGLE_0 = 0 +UNP_ROTATION_ANGLE_90 = 1 +UNP_ROTATION_ANGLE_180 = 2 +UNP_ROTATION_ANGLE_270 = 3 +UNP_ROTATION_ANGLE_0m = 4 +UNP_ROTATION_ANGLE_90m = 5 +UNP_ROTATION_ANGLE_180m = 6 +UNP_ROTATION_ANGLE_270m = 7 +UNP_ROTATION_ANGLE = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_PIXEL_DROP' +UNP_PIXEL_DROP__enumvalues = { + 0: 'UNP_PIXEL_NO_DROP', + 1: 'UNP_PIXEL_DROPPING', +} +UNP_PIXEL_NO_DROP = 0 +UNP_PIXEL_DROPPING = 1 +UNP_PIXEL_DROP = ctypes.c_uint32 # enum + +# values for enumeration 'UNP_BUFFER_MODE' +UNP_BUFFER_MODE__enumvalues = { + 0: 'UNP_BUFFER_MODE_LUMA', + 1: 'UNP_BUFFER_MODE_LUMA_CHROMA', +} +UNP_BUFFER_MODE_LUMA = 0 +UNP_BUFFER_MODE_LUMA_CHROMA = 1 +UNP_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_LINK_TRAINING_COMPLETE' +DP_LINK_TRAINING_COMPLETE__enumvalues = { + 0: 'DP_LINK_TRAINING_NOT_COMPLETE', + 1: 'DP_LINK_TRAINING_ALREADY_COMPLETE', +} +DP_LINK_TRAINING_NOT_COMPLETE = 0 +DP_LINK_TRAINING_ALREADY_COMPLETE = 1 +DP_LINK_TRAINING_COMPLETE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_EMBEDDED_PANEL_MODE' +DP_EMBEDDED_PANEL_MODE__enumvalues = { + 0: 'DP_EXTERNAL_PANEL', + 1: 'DP_EMBEDDED_PANEL', +} +DP_EXTERNAL_PANEL = 0 +DP_EMBEDDED_PANEL = 1 +DP_EMBEDDED_PANEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_PIXEL_ENCODING' +DP_PIXEL_ENCODING__enumvalues = { + 0: 'DP_PIXEL_ENCODING_RGB444', + 1: 'DP_PIXEL_ENCODING_YCBCR422', + 2: 'DP_PIXEL_ENCODING_YCBCR444', + 3: 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', + 4: 'DP_PIXEL_ENCODING_Y_ONLY', + 5: 'DP_PIXEL_ENCODING_YCBCR420', + 6: 'DP_PIXEL_ENCODING_RESERVED', +} +DP_PIXEL_ENCODING_RGB444 = 0 +DP_PIXEL_ENCODING_YCBCR422 = 1 +DP_PIXEL_ENCODING_YCBCR444 = 2 +DP_PIXEL_ENCODING_RGB_WIDE_GAMUT = 3 +DP_PIXEL_ENCODING_Y_ONLY = 4 +DP_PIXEL_ENCODING_YCBCR420 = 5 +DP_PIXEL_ENCODING_RESERVED = 6 +DP_PIXEL_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DYN_RANGE' +DP_DYN_RANGE__enumvalues = { + 0: 'DP_DYN_VESA_RANGE', + 1: 'DP_DYN_CEA_RANGE', +} +DP_DYN_VESA_RANGE = 0 +DP_DYN_CEA_RANGE = 1 +DP_DYN_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_YCBCR_RANGE' +DP_YCBCR_RANGE__enumvalues = { + 0: 'DP_YCBCR_RANGE_BT601_5', + 1: 'DP_YCBCR_RANGE_BT709_5', +} +DP_YCBCR_RANGE_BT601_5 = 0 +DP_YCBCR_RANGE_BT709_5 = 1 +DP_YCBCR_RANGE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_COMPONENT_DEPTH' +DP_COMPONENT_DEPTH__enumvalues = { + 0: 'DP_COMPONENT_DEPTH_6BPC', + 1: 'DP_COMPONENT_DEPTH_8BPC', + 2: 'DP_COMPONENT_DEPTH_10BPC', + 3: 'DP_COMPONENT_DEPTH_12BPC', + 4: 'DP_COMPONENT_DEPTH_16BPC_RESERVED', + 5: 'DP_COMPONENT_DEPTH_RESERVED', +} +DP_COMPONENT_DEPTH_6BPC = 0 +DP_COMPONENT_DEPTH_8BPC = 1 +DP_COMPONENT_DEPTH_10BPC = 2 +DP_COMPONENT_DEPTH_12BPC = 3 +DP_COMPONENT_DEPTH_16BPC_RESERVED = 4 +DP_COMPONENT_DEPTH_RESERVED = 5 +DP_COMPONENT_DEPTH = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_MISC0_OVERRIDE_ENABLE' +DP_MSA_MISC0_OVERRIDE_ENABLE__enumvalues = { + 0: 'MSA_MISC0_OVERRIDE_DISABLE', + 1: 'MSA_MISC0_OVERRIDE_ENABLE', +} +MSA_MISC0_OVERRIDE_DISABLE = 0 +MSA_MISC0_OVERRIDE_ENABLE = 1 +DP_MSA_MISC0_OVERRIDE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_MISC1_BIT7_OVERRIDE_ENABLE' +DP_MSA_MISC1_BIT7_OVERRIDE_ENABLE__enumvalues = { + 0: 'MSA_MISC1_BIT7_OVERRIDE_DISABLE', + 1: 'MSA_MISC1_BIT7_OVERRIDE_ENABLE', +} +MSA_MISC1_BIT7_OVERRIDE_DISABLE = 0 +MSA_MISC1_BIT7_OVERRIDE_ENABLE = 1 +DP_MSA_MISC1_BIT7_OVERRIDE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_UDI_LANES' +DP_UDI_LANES__enumvalues = { + 0: 'DP_UDI_1_LANE', + 1: 'DP_UDI_2_LANES', + 2: 'DP_UDI_LANES_RESERVED', + 3: 'DP_UDI_4_LANES', +} +DP_UDI_1_LANE = 0 +DP_UDI_2_LANES = 1 +DP_UDI_LANES_RESERVED = 2 +DP_UDI_4_LANES = 3 +DP_UDI_LANES = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DIS_DEFER' +DP_VID_STREAM_DIS_DEFER__enumvalues = { + 0: 'DP_VID_STREAM_DIS_NO_DEFER', + 1: 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 2: 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', +} +DP_VID_STREAM_DIS_NO_DEFER = 0 +DP_VID_STREAM_DIS_DEFER_TO_HBLANK = 1 +DP_VID_STREAM_DIS_DEFER_TO_VBLANK = 2 +DP_VID_STREAM_DIS_DEFER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_ACK' +DP_STEER_OVERFLOW_ACK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_STEER_OVERFLOW_ACK_NO_EFFECT = 0 +DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_STEER_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_STEER_OVERFLOW_MASK' +DP_STEER_OVERFLOW_MASK__enumvalues = { + 0: 'DP_STEER_OVERFLOW_MASKED', + 1: 'DP_STEER_OVERFLOW_UNMASK', +} +DP_STEER_OVERFLOW_MASKED = 0 +DP_STEER_OVERFLOW_UNMASK = 1 +DP_STEER_OVERFLOW_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_TU_OVERFLOW_ACK' +DP_TU_OVERFLOW_ACK__enumvalues = { + 0: 'DP_TU_OVERFLOW_ACK_NO_EFFECT', + 1: 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', +} +DP_TU_OVERFLOW_ACK_NO_EFFECT = 0 +DP_TU_OVERFLOW_ACK_CLR_INTERRUPT = 1 +DP_TU_OVERFLOW_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ALT_SCRAMBLER_RESET_EN' +DPHY_ALT_SCRAMBLER_RESET_EN__enumvalues = { + 0: 'DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE', + 1: 'DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION', +} +DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE = 0 +DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION = 1 +DPHY_ALT_SCRAMBLER_RESET_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ALT_SCRAMBLER_RESET_SEL' +DPHY_ALT_SCRAMBLER_RESET_SEL__enumvalues = { + 0: 'DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE', + 1: 'DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE', +} +DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE = 0 +DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE = 1 +DPHY_ALT_SCRAMBLER_RESET_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_TIMING_MODE' +DP_VID_TIMING_MODE__enumvalues = { + 0: 'DP_VID_TIMING_MODE_ASYNC', + 1: 'DP_VID_TIMING_MODE_SYNC', +} +DP_VID_TIMING_MODE_ASYNC = 0 +DP_VID_TIMING_MODE_SYNC = 1 +DP_VID_TIMING_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_DOUBLE_BUFFER_MODE' +DP_VID_M_N_DOUBLE_BUFFER_MODE__enumvalues = { + 0: 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 1: 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', +} +DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE = 0 +DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START = 1 +DP_VID_M_N_DOUBLE_BUFFER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_N_GEN_EN' +DP_VID_M_N_GEN_EN__enumvalues = { + 0: 'DP_VID_M_N_PROGRAMMED_VIA_REG', + 1: 'DP_VID_M_N_CALC_AUTO', +} +DP_VID_M_N_PROGRAMMED_VIA_REG = 0 +DP_VID_M_N_CALC_AUTO = 1 +DP_VID_M_N_GEN_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_M_DOUBLE_VALUE_EN' +DP_VID_M_DOUBLE_VALUE_EN__enumvalues = { + 0: 'DP_VID_M_INPUT_PIXEL_RATE', + 1: 'DP_VID_M_DOUBLE_INPUT_PIXEL_RATE', +} +DP_VID_M_INPUT_PIXEL_RATE = 0 +DP_VID_M_DOUBLE_INPUT_PIXEL_RATE = 1 +DP_VID_M_DOUBLE_VALUE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_ENHANCED_FRAME_MODE' +DP_VID_ENHANCED_FRAME_MODE__enumvalues = { + 0: 'VID_NORMAL_FRAME_MODE', + 1: 'VID_ENHANCED_MODE', +} +VID_NORMAL_FRAME_MODE = 0 +VID_ENHANCED_MODE = 1 +DP_VID_ENHANCED_FRAME_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_MSA_TOP_FIELD_MODE' +DP_VID_MSA_TOP_FIELD_MODE__enumvalues = { + 0: 'DP_TOP_FIELD_ONLY', + 1: 'DP_TOP_PLUS_BOTTOM_FIELD', +} +DP_TOP_FIELD_ONLY = 0 +DP_TOP_PLUS_BOTTOM_FIELD = 1 +DP_VID_MSA_TOP_FIELD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_VBID_FIELD_POL' +DP_VID_VBID_FIELD_POL__enumvalues = { + 0: 'DP_VID_VBID_FIELD_POL_NORMAL', + 1: 'DP_VID_VBID_FIELD_POL_INV', +} +DP_VID_VBID_FIELD_POL_NORMAL = 0 +DP_VID_VBID_FIELD_POL_INV = 1 +DP_VID_VBID_FIELD_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_ACK' +DP_VID_STREAM_DISABLE_ACK__enumvalues = { + 0: 'ID_STREAM_DISABLE_NO_ACK', + 1: 'ID_STREAM_DISABLE_ACKED', +} +ID_STREAM_DISABLE_NO_ACK = 0 +ID_STREAM_DISABLE_ACKED = 1 +DP_VID_STREAM_DISABLE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_VID_STREAM_DISABLE_MASK' +DP_VID_STREAM_DISABLE_MASK__enumvalues = { + 0: 'VID_STREAM_DISABLE_MASKED', + 1: 'VID_STREAM_DISABLE_UNMASK', +} +VID_STREAM_DISABLE_MASKED = 0 +VID_STREAM_DISABLE_UNMASK = 1 +DP_VID_STREAM_DISABLE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE0' +DPHY_ATEST_SEL_LANE0__enumvalues = { + 0: 'DPHY_ATEST_LANE0_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE0_REG_PATTERN', +} +DPHY_ATEST_LANE0_PRBS_PATTERN = 0 +DPHY_ATEST_LANE0_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE0 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE1' +DPHY_ATEST_SEL_LANE1__enumvalues = { + 0: 'DPHY_ATEST_LANE1_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE1_REG_PATTERN', +} +DPHY_ATEST_LANE1_PRBS_PATTERN = 0 +DPHY_ATEST_LANE1_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE1 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE2' +DPHY_ATEST_SEL_LANE2__enumvalues = { + 0: 'DPHY_ATEST_LANE2_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE2_REG_PATTERN', +} +DPHY_ATEST_LANE2_PRBS_PATTERN = 0 +DPHY_ATEST_LANE2_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE2 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_ATEST_SEL_LANE3' +DPHY_ATEST_SEL_LANE3__enumvalues = { + 0: 'DPHY_ATEST_LANE3_PRBS_PATTERN', + 1: 'DPHY_ATEST_LANE3_REG_PATTERN', +} +DPHY_ATEST_LANE3_PRBS_PATTERN = 0 +DPHY_ATEST_LANE3_REG_PATTERN = 1 +DPHY_ATEST_SEL_LANE3 = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_SEL' +DPHY_SCRAMBLER_SEL__enumvalues = { + 0: 'DPHY_SCRAMBLER_SEL_LANE_DATA', + 1: 'DPHY_SCRAMBLER_SEL_DBG_DATA', +} +DPHY_SCRAMBLER_SEL_LANE_DATA = 0 +DPHY_SCRAMBLER_SEL_DBG_DATA = 1 +DPHY_SCRAMBLER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_BYPASS' +DPHY_BYPASS__enumvalues = { + 0: 'DPHY_8B10B_OUTPUT', + 1: 'DPHY_DBG_OUTPUT', +} +DPHY_8B10B_OUTPUT = 0 +DPHY_DBG_OUTPUT = 1 +DPHY_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SKEW_BYPASS' +DPHY_SKEW_BYPASS__enumvalues = { + 0: 'DPHY_WITH_SKEW', + 1: 'DPHY_NO_SKEW', +} +DPHY_WITH_SKEW = 0 +DPHY_NO_SKEW = 1 +DPHY_SKEW_BYPASS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_TRAINING_PATTERN_SEL' +DPHY_TRAINING_PATTERN_SEL__enumvalues = { + 0: 'DPHY_TRAINING_PATTERN_1', + 1: 'DPHY_TRAINING_PATTERN_2', + 2: 'DPHY_TRAINING_PATTERN_3', + 3: 'DPHY_TRAINING_PATTERN_4', +} +DPHY_TRAINING_PATTERN_1 = 0 +DPHY_TRAINING_PATTERN_2 = 1 +DPHY_TRAINING_PATTERN_3 = 2 +DPHY_TRAINING_PATTERN_4 = 3 +DPHY_TRAINING_PATTERN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_RESET' +DPHY_8B10B_RESET__enumvalues = { + 0: 'DPHY_8B10B_NOT_RESET', + 1: 'DPHY_8B10B_RESETET', +} +DPHY_8B10B_NOT_RESET = 0 +DPHY_8B10B_RESETET = 1 +DPHY_8B10B_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_8B10B_EXT_DISP' +DP_DPHY_8B10B_EXT_DISP__enumvalues = { + 0: 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 1: 'DP_DPHY_8B10B_EXT_DISP_ONE', +} +DP_DPHY_8B10B_EXT_DISP_ZERO = 0 +DP_DPHY_8B10B_EXT_DISP_ONE = 1 +DP_DPHY_8B10B_EXT_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_8B10B_CUR_DISP' +DPHY_8B10B_CUR_DISP__enumvalues = { + 0: 'DPHY_8B10B_CUR_DISP_ZERO', + 1: 'DPHY_8B10B_CUR_DISP_ONE', +} +DPHY_8B10B_CUR_DISP_ZERO = 0 +DPHY_8B10B_CUR_DISP_ONE = 1 +DPHY_8B10B_CUR_DISP = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_EN' +DPHY_PRBS_EN__enumvalues = { + 0: 'DPHY_PRBS_DISABLE', + 1: 'DPHY_PRBS_ENABLE', +} +DPHY_PRBS_DISABLE = 0 +DPHY_PRBS_ENABLE = 1 +DPHY_PRBS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_PRBS_SEL' +DPHY_PRBS_SEL__enumvalues = { + 0: 'DPHY_PRBS7_SELECTED', + 1: 'DPHY_PRBS23_SELECTED', + 2: 'DPHY_PRBS11_SELECTED', +} +DPHY_PRBS7_SELECTED = 0 +DPHY_PRBS23_SELECTED = 1 +DPHY_PRBS11_SELECTED = 2 +DPHY_PRBS_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_DIS' +DPHY_SCRAMBLER_DIS__enumvalues = { + 0: 'DPHY_SCR_ENABLED', + 1: 'DPHY_SCR_DISABLED', +} +DPHY_SCR_ENABLED = 0 +DPHY_SCR_DISABLED = 1 +DPHY_SCRAMBLER_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_ADVANCE' +DPHY_SCRAMBLER_ADVANCE__enumvalues = { + 0: 'DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY', + 1: 'DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL', +} +DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY = 0 +DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL = 1 +DPHY_SCRAMBLER_ADVANCE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SCRAMBLER_KCODE' +DPHY_SCRAMBLER_KCODE__enumvalues = { + 0: 'DPHY_SCRAMBLER_KCODE_DISABLED', + 1: 'DPHY_SCRAMBLER_KCODE_ENABLED', +} +DPHY_SCRAMBLER_KCODE_DISABLED = 0 +DPHY_SCRAMBLER_KCODE_ENABLED = 1 +DPHY_SCRAMBLER_KCODE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_LOAD_BS_COUNT_START' +DPHY_LOAD_BS_COUNT_START__enumvalues = { + 0: 'DPHY_LOAD_BS_COUNT_STARTED', + 1: 'DPHY_LOAD_BS_COUNT_NOT_STARTED', +} +DPHY_LOAD_BS_COUNT_STARTED = 0 +DPHY_LOAD_BS_COUNT_NOT_STARTED = 1 +DPHY_LOAD_BS_COUNT_START = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_EN' +DPHY_CRC_EN__enumvalues = { + 0: 'DPHY_CRC_DISABLED', + 1: 'DPHY_CRC_ENABLED', +} +DPHY_CRC_DISABLED = 0 +DPHY_CRC_ENABLED = 1 +DPHY_CRC_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_CONT_EN' +DPHY_CRC_CONT_EN__enumvalues = { + 0: 'DPHY_CRC_ONE_SHOT', + 1: 'DPHY_CRC_CONTINUOUS', +} +DPHY_CRC_ONE_SHOT = 0 +DPHY_CRC_CONTINUOUS = 1 +DPHY_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_FIELD' +DPHY_CRC_FIELD__enumvalues = { + 0: 'DPHY_CRC_START_FROM_TOP_FIELD', + 1: 'DPHY_CRC_START_FROM_BOTTOM_FIELD', +} +DPHY_CRC_START_FROM_TOP_FIELD = 0 +DPHY_CRC_START_FROM_BOTTOM_FIELD = 1 +DPHY_CRC_FIELD = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_SEL' +DPHY_CRC_SEL__enumvalues = { + 0: 'DPHY_CRC_LANE0_SELECTED', + 1: 'DPHY_CRC_LANE1_SELECTED', + 2: 'DPHY_CRC_LANE2_SELECTED', + 3: 'DPHY_CRC_LANE3_SELECTED', +} +DPHY_CRC_LANE0_SELECTED = 0 +DPHY_CRC_LANE1_SELECTED = 1 +DPHY_CRC_LANE2_SELECTED = 2 +DPHY_CRC_LANE3_SELECTED = 3 +DPHY_CRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_RX_FAST_TRAINING_CAPABLE' +DPHY_RX_FAST_TRAINING_CAPABLE__enumvalues = { + 0: 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 1: 'DPHY_FAST_TRAINING_CAPABLE', +} +DPHY_FAST_TRAINING_NOT_CAPABLE_0 = 0 +DPHY_FAST_TRAINING_CAPABLE = 1 +DPHY_RX_FAST_TRAINING_CAPABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_COLLISION_ACK' +DP_SEC_COLLISION_ACK__enumvalues = { + 0: 'DP_SEC_COLLISION_ACK_NO_EFFECT', + 1: 'DP_SEC_COLLISION_ACK_CLR_FLAG', +} +DP_SEC_COLLISION_ACK_NO_EFFECT = 0 +DP_SEC_COLLISION_ACK_CLR_FLAG = 1 +DP_SEC_COLLISION_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_AUDIO_MUTE' +DP_SEC_AUDIO_MUTE__enumvalues = { + 0: 'DP_SEC_AUDIO_MUTE_HW_CTRL', + 1: 'DP_SEC_AUDIO_MUTE_SW_CTRL', +} +DP_SEC_AUDIO_MUTE_HW_CTRL = 0 +DP_SEC_AUDIO_MUTE_SW_CTRL = 1 +DP_SEC_AUDIO_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_TIMESTAMP_MODE' +DP_SEC_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', + 1: 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', +} +DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE = 0 +DP_SEC_TIMESTAMP_AUTO_CALC_MODE = 1 +DP_SEC_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_PRIORITY' +DP_SEC_ASP_PRIORITY__enumvalues = { + 0: 'DP_SEC_ASP_LOW_PRIORITY', + 1: 'DP_SEC_ASP_HIGH_PRIORITY', +} +DP_SEC_ASP_LOW_PRIORITY = 0 +DP_SEC_ASP_HIGH_PRIORITY = 1 +DP_SEC_ASP_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE' +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE__enumvalues = { + 0: 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 1: 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', +} +DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ = 0 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED = 1 +DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_SAT_UPDATE_ACT' +DP_MSE_SAT_UPDATE_ACT__enumvalues = { + 0: 'DP_MSE_SAT_UPDATE_NO_ACTION', + 1: 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 2: 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', +} +DP_MSE_SAT_UPDATE_NO_ACTION = 0 +DP_MSE_SAT_UPDATE_WITH_TRIGGER = 1 +DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER = 2 +DP_MSE_SAT_UPDATE_ACT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_LINK_LINE' +DP_MSE_LINK_LINE__enumvalues = { + 0: 'DP_MSE_LINK_LINE_32_MTP_LONG', + 1: 'DP_MSE_LINK_LINE_64_MTP_LONG', + 2: 'DP_MSE_LINK_LINE_128_MTP_LONG', + 3: 'DP_MSE_LINK_LINE_256_MTP_LONG', +} +DP_MSE_LINK_LINE_32_MTP_LONG = 0 +DP_MSE_LINK_LINE_64_MTP_LONG = 1 +DP_MSE_LINK_LINE_128_MTP_LONG = 2 +DP_MSE_LINK_LINE_256_MTP_LONG = 3 +DP_MSE_LINK_LINE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_BLANK_CODE' +DP_MSE_BLANK_CODE__enumvalues = { + 0: 'DP_MSE_BLANK_CODE_SF_FILLED', + 1: 'DP_MSE_BLANK_CODE_ZERO_FILLED', +} +DP_MSE_BLANK_CODE_SF_FILLED = 0 +DP_MSE_BLANK_CODE_ZERO_FILLED = 1 +DP_MSE_BLANK_CODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_TIMESTAMP_MODE' +DP_MSE_TIMESTAMP_MODE__enumvalues = { + 0: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 1: 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', +} +DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE = 0 +DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE = 1 +DP_MSE_TIMESTAMP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_ZERO_ENCODER' +DP_MSE_ZERO_ENCODER__enumvalues = { + 0: 'DP_MSE_NOT_ZERO_FE_ENCODER', + 1: 'DP_MSE_ZERO_FE_ENCODER', +} +DP_MSE_NOT_ZERO_FE_ENCODER = 0 +DP_MSE_ZERO_FE_ENCODER = 1 +DP_MSE_ZERO_ENCODER = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSE_OUTPUT_DPDBG_DATA' +DP_MSE_OUTPUT_DPDBG_DATA__enumvalues = { + 0: 'DP_MSE_OUTPUT_DPDBG_DATA_DIS', + 1: 'DP_MSE_OUTPUT_DPDBG_DATA_EN', +} +DP_MSE_OUTPUT_DPDBG_DATA_DIS = 0 +DP_MSE_OUTPUT_DPDBG_DATA_EN = 1 +DP_MSE_OUTPUT_DPDBG_DATA = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE' +DP_DPHY_HBR2_PATTERN_CONTROL_MODE__enumvalues = { + 0: 'DP_DPHY_HBR2_PASS_THROUGH', + 1: 'DP_DPHY_HBR2_PATTERN_1', + 2: 'DP_DPHY_HBR2_PATTERN_2_NEG', + 3: 'DP_DPHY_HBR2_PATTERN_3', + 6: 'DP_DPHY_HBR2_PATTERN_2_POS', +} +DP_DPHY_HBR2_PASS_THROUGH = 0 +DP_DPHY_HBR2_PATTERN_1 = 1 +DP_DPHY_HBR2_PATTERN_2_NEG = 2 +DP_DPHY_HBR2_PATTERN_3 = 3 +DP_DPHY_HBR2_PATTERN_2_POS = 6 +DP_DPHY_HBR2_PATTERN_CONTROL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_CRC_MST_PHASE_ERROR_ACK' +DPHY_CRC_MST_PHASE_ERROR_ACK__enumvalues = { + 0: 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', + 1: 'DPHY_CRC_MST_PHASE_ERROR_ACKED', +} +DPHY_CRC_MST_PHASE_ERROR_NO_ACK = 0 +DPHY_CRC_MST_PHASE_ERROR_ACKED = 1 +DPHY_CRC_MST_PHASE_ERROR_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DPHY_SW_FAST_TRAINING_START' +DPHY_SW_FAST_TRAINING_START__enumvalues = { + 0: 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 1: 'DPHY_SW_FAST_TRAINING_STARTED', +} +DPHY_SW_FAST_TRAINING_NOT_STARTED = 0 +DPHY_SW_FAST_TRAINING_STARTED = 1 +DPHY_SW_FAST_TRAINING_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN' +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 1: 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', +} +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED = 0 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED = 1 +DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK' +DP_DPHY_FAST_TRAINING_COMPLETE_MASK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_MASKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK' +DP_DPHY_FAST_TRAINING_COMPLETE_ACK__enumvalues = { + 0: 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 1: 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', +} +DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED = 0 +DP_DPHY_FAST_TRAINING_COMPLETE_ACKED = 1 +DP_DPHY_FAST_TRAINING_COMPLETE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_MSA_V_TIMING_OVERRIDE_EN' +DP_MSA_V_TIMING_OVERRIDE_EN__enumvalues = { + 0: 'MSA_V_TIMING_OVERRIDE_DISABLED', + 1: 'MSA_V_TIMING_OVERRIDE_ENABLED', +} +MSA_V_TIMING_OVERRIDE_DISABLED = 0 +MSA_V_TIMING_OVERRIDE_ENABLED = 1 +DP_MSA_V_TIMING_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP0_PRIORITY' +DP_SEC_GSP0_PRIORITY__enumvalues = { + 0: 'SEC_GSP0_PRIORITY_LOW', + 1: 'SEC_GSP0_PRIORITY_HIGH', +} +SEC_GSP0_PRIORITY_LOW = 0 +SEC_GSP0_PRIORITY_HIGH = 1 +DP_SEC_GSP0_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_SEC_GSP0_SEND' +DP_SEC_GSP0_SEND__enumvalues = { + 0: 'NOT_SENT', + 1: 'FORCE_SENT', +} +NOT_SENT = 0 +FORCE_SENT = 1 +DP_SEC_GSP0_SEND = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_UPDATE_LOCK' +COL_MAN_UPDATE_LOCK__enumvalues = { + 0: 'COL_MAN_UPDATE_UNLOCKED', + 1: 'COL_MAN_UPDATE_LOCKED', +} +COL_MAN_UPDATE_UNLOCKED = 0 +COL_MAN_UPDATE_LOCKED = 1 +COL_MAN_UPDATE_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_DISABLE_MULTIPLE_UPDATE' +COL_MAN_DISABLE_MULTIPLE_UPDATE__enumvalues = { + 0: 'COL_MAN_MULTIPLE_UPDATE', + 1: 'COL_MAN_MULTIPLE_UPDAT_EDISABLE', +} +COL_MAN_MULTIPLE_UPDATE = 0 +COL_MAN_MULTIPLE_UPDAT_EDISABLE = 1 +COL_MAN_DISABLE_MULTIPLE_UPDATE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_INPUTCSC_MODE' +COL_MAN_INPUTCSC_MODE__enumvalues = { + 0: 'INPUTCSC_MODE_BYPASS', + 1: 'INPUTCSC_MODE_A', + 2: 'INPUTCSC_MODE_B', + 3: 'INPUTCSC_MODE_UNITY', +} +INPUTCSC_MODE_BYPASS = 0 +INPUTCSC_MODE_A = 1 +INPUTCSC_MODE_B = 2 +INPUTCSC_MODE_UNITY = 3 +COL_MAN_INPUTCSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_INPUTCSC_TYPE' +COL_MAN_INPUTCSC_TYPE__enumvalues = { + 0: 'INPUTCSC_TYPE_12_0', + 1: 'INPUTCSC_TYPE_10_2', + 2: 'INPUTCSC_TYPE_8_4', +} +INPUTCSC_TYPE_12_0 = 0 +INPUTCSC_TYPE_10_2 = 1 +INPUTCSC_TYPE_8_4 = 2 +COL_MAN_INPUTCSC_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_INPUTCSC_CONVERT' +COL_MAN_INPUTCSC_CONVERT__enumvalues = { + 0: 'INPUTCSC_ROUND', + 1: 'INPUTCSC_TRUNCATE', +} +INPUTCSC_ROUND = 0 +INPUTCSC_TRUNCATE = 1 +COL_MAN_INPUTCSC_CONVERT = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_PRESCALE_MODE' +COL_MAN_PRESCALE_MODE__enumvalues = { + 0: 'PRESCALE_MODE_BYPASS', + 1: 'PRESCALE_MODE_PROGRAM', + 2: 'PRESCALE_MODE_UNITY', +} +PRESCALE_MODE_BYPASS = 0 +PRESCALE_MODE_PROGRAM = 1 +PRESCALE_MODE_UNITY = 2 +COL_MAN_PRESCALE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_INPUT_GAMMA_MODE' +COL_MAN_INPUT_GAMMA_MODE__enumvalues = { + 0: 'INGAMMA_MODE_BYPASS', + 1: 'INGAMMA_MODE_FIX', + 2: 'INGAMMA_MODE_FLOAT', +} +INGAMMA_MODE_BYPASS = 0 +INGAMMA_MODE_FIX = 1 +INGAMMA_MODE_FLOAT = 2 +COL_MAN_INPUT_GAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_OUTPUT_CSC_MODE' +COL_MAN_OUTPUT_CSC_MODE__enumvalues = { + 0: 'COL_MAN_OUTPUT_CSC_BYPASS', + 1: 'COL_MAN_OUTPUT_CSC_RGB', + 2: 'COL_MAN_OUTPUT_CSC_YCrCb601', + 3: 'COL_MAN_OUTPUT_CSC_YCrCb709', + 4: 'COL_MAN_OUTPUT_CSC_A', + 5: 'COL_MAN_OUTPUT_CSC_B', + 6: 'COL_MAN_OUTPUT_CSC_UNITY', +} +COL_MAN_OUTPUT_CSC_BYPASS = 0 +COL_MAN_OUTPUT_CSC_RGB = 1 +COL_MAN_OUTPUT_CSC_YCrCb601 = 2 +COL_MAN_OUTPUT_CSC_YCrCb709 = 3 +COL_MAN_OUTPUT_CSC_A = 4 +COL_MAN_OUTPUT_CSC_B = 5 +COL_MAN_OUTPUT_CSC_UNITY = 6 +COL_MAN_OUTPUT_CSC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_DENORM_CLAMP_CONTROL' +COL_MAN_DENORM_CLAMP_CONTROL__enumvalues = { + 0: 'DENORM_CLAMP_MODE_UNITY', + 1: 'DENORM_CLAMP_MODE_8', + 2: 'DENORM_CLAMP_MODE_10', + 3: 'DENORM_CLAMP_MODE_12', +} +DENORM_CLAMP_MODE_UNITY = 0 +DENORM_CLAMP_MODE_8 = 1 +DENORM_CLAMP_MODE_10 = 2 +DENORM_CLAMP_MODE_12 = 3 +COL_MAN_DENORM_CLAMP_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_REGAMMA_MODE_CONTROL' +COL_MAN_REGAMMA_MODE_CONTROL__enumvalues = { + 0: 'COL_MAN_REGAMMA_MODE_BYPASS', + 1: 'COL_MAN_REGAMMA_MODE_ROM_A', + 2: 'COL_MAN_REGAMMA_MODE_ROM_B', + 3: 'COL_MAN_REGAMMA_MODE_A', + 4: 'COL_MAN_REGAMMA_MODE_B', +} +COL_MAN_REGAMMA_MODE_BYPASS = 0 +COL_MAN_REGAMMA_MODE_ROM_A = 1 +COL_MAN_REGAMMA_MODE_ROM_B = 2 +COL_MAN_REGAMMA_MODE_A = 3 +COL_MAN_REGAMMA_MODE_B = 4 +COL_MAN_REGAMMA_MODE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_GLOBAL_PASSTHROUGH_ENABLE' +COL_MAN_GLOBAL_PASSTHROUGH_ENABLE__enumvalues = { + 0: 'CM_GLOBAL_PASSTHROUGH_DISBALE', + 1: 'CM_GLOBAL_PASSTHROUGH_ENABLE', +} +CM_GLOBAL_PASSTHROUGH_DISBALE = 0 +CM_GLOBAL_PASSTHROUGH_ENABLE = 1 +COL_MAN_GLOBAL_PASSTHROUGH_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_DEGAMMA_MODE' +COL_MAN_DEGAMMA_MODE__enumvalues = { + 0: 'DEGAMMA_MODE_BYPASS', + 1: 'DEGAMMA_MODE_A', + 2: 'DEGAMMA_MODE_B', +} +DEGAMMA_MODE_BYPASS = 0 +DEGAMMA_MODE_A = 1 +DEGAMMA_MODE_B = 2 +COL_MAN_DEGAMMA_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'COL_MAN_GAMUT_REMAP_MODE' +COL_MAN_GAMUT_REMAP_MODE__enumvalues = { + 0: 'GAMUT_REMAP_MODE_BYPASS', + 1: 'GAMUT_REMAP_MODE_1', + 2: 'GAMUT_REMAP_MODE_2', + 3: 'GAMUT_REMAP_MODE_3', +} +GAMUT_REMAP_MODE_BYPASS = 0 +GAMUT_REMAP_MODE_1 = 1 +GAMUT_REMAP_MODE_2 = 2 +GAMUT_REMAP_MODE_3 = 3 +COL_MAN_GAMUT_REMAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_HPD_SEL' +DP_AUX_CONTROL_HPD_SEL__enumvalues = { + 0: 'DP_AUX_CONTROL_HPD1_SELECTED', + 1: 'DP_AUX_CONTROL_HPD2_SELECTED', + 2: 'DP_AUX_CONTROL_HPD3_SELECTED', + 3: 'DP_AUX_CONTROL_HPD4_SELECTED', + 4: 'DP_AUX_CONTROL_HPD5_SELECTED', + 5: 'DP_AUX_CONTROL_HPD6_SELECTED', +} +DP_AUX_CONTROL_HPD1_SELECTED = 0 +DP_AUX_CONTROL_HPD2_SELECTED = 1 +DP_AUX_CONTROL_HPD3_SELECTED = 2 +DP_AUX_CONTROL_HPD4_SELECTED = 3 +DP_AUX_CONTROL_HPD5_SELECTED = 4 +DP_AUX_CONTROL_HPD6_SELECTED = 5 +DP_AUX_CONTROL_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_CONTROL_TEST_MODE' +DP_AUX_CONTROL_TEST_MODE__enumvalues = { + 0: 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 1: 'DP_AUX_CONTROL_TEST_MODE_ENABLE', +} +DP_AUX_CONTROL_TEST_MODE_DISABLE = 0 +DP_AUX_CONTROL_TEST_MODE_ENABLE = 1 +DP_AUX_CONTROL_TEST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_SW_GO' +DP_AUX_SW_CONTROL_SW_GO__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 1: 'DP_AUX_SW_CONTROL_SW__GO', +} +DP_AUX_SW_CONTROL_SW__NOT_GO = 0 +DP_AUX_SW_CONTROL_SW__GO = 1 +DP_AUX_SW_CONTROL_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_SW_CONTROL_LS_READ_TRIG' +DP_AUX_SW_CONTROL_LS_READ_TRIG__enumvalues = { + 0: 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 1: 'DP_AUX_SW_CONTROL_LS_READ__TRIG', +} +DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG = 0 +DP_AUX_SW_CONTROL_LS_READ__TRIG = 1 +DP_AUX_SW_CONTROL_LS_READ_TRIG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_ARB_PRIORITY' +DP_AUX_ARB_CONTROL_ARB_PRIORITY__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 1: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 2: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 3: 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', +} +DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW = 0 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW = 1 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC = 2 +DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS = 3 +DP_AUX_ARB_CONTROL_ARB_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ' +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 1: 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', +} +DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ = 0 +DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ = 1 +DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG' +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG__enumvalues = { + 0: 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 1: 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', +} +DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG = 0 +DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG = 1 +DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_INT_ACK' +DP_AUX_INT_ACK__enumvalues = { + 0: 'DP_AUX_INT__NOT_ACK', + 1: 'DP_AUX_INT__ACK', +} +DP_AUX_INT__NOT_ACK = 0 +DP_AUX_INT__ACK = 1 +DP_AUX_INT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_LS_UPDATE_ACK' +DP_AUX_LS_UPDATE_ACK__enumvalues = { + 0: 'DP_AUX_INT_LS_UPDATE_NOT_ACK', + 1: 'DP_AUX_INT_LS_UPDATE_ACK', +} +DP_AUX_INT_LS_UPDATE_NOT_ACK = 0 +DP_AUX_INT_LS_UPDATE_ACK = 1 +DP_AUX_LS_UPDATE_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL' +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE' +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__enumvalues = { + 0: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 1: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 2: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 3: 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', +} +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ = 0 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ = 1 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ = 2 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ = 3 +DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN' +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__0US', + 1: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__8US', + 2: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__16US', + 3: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__24US', + 4: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__32US', + 5: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__40US', + 6: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__48US', + 7: 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__56US', +} +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__0US = 0 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__8US = 1 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__16US = 2 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__24US = 3 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__32US = 4 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__40US = 5 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__48US = 6 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__56US = 7 +DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY' +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__enumvalues = { + 0: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 1: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 2: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 3: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 4: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 5: 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', +} +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0 = 0 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US = 1 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US = 2 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US = 3 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US = 4 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US = 5 +DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW' +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_START_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW' +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 1: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 2: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 3: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 4: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 5: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 6: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 7: 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', +} +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD = 0 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD = 1 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD = 2 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD = 3 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD = 4 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD = 5 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD = 6 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD = 7 +DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 1: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 2: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 3: 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', +} +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES = 0 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES = 1 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES = 2 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED = 3 +DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP' +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 1: 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', +} +DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP = 0 +DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP = 1 +DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN' +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 1: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 2: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 3: 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', +} +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS = 0 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS = 1 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS = 2 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS = 3 +DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN' +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN__enumvalues = { + 0: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_450US', + 1: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_500US', + 2: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_550US', + 3: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_600US', + 4: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_650US', + 5: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_700US', + 6: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_750US', + 7: 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_800US', +} +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_450US = 0 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_500US = 1 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_550US = 2 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_600US = 3 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_650US = 4 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_700US = 5 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_750US = 6 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_800US = 7 +DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD' +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__enumvalues = { + 0: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 1: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 2: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 3: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 4: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 5: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 6: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 7: 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', +} +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2 = 0 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4 = 1 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8 = 2 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16 = 3 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32 = 4 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64 = 5 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128 = 6 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256 = 7 +DP_AUX_DPHY_RX_DETECTION_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ' +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 1: 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', +} +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX = 0 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX = 1 +DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW' +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 1: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 2: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 3: 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', +} +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US = 0 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US = 1 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US = 2 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US = 3 +DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT' +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 1: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 2: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 3: 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', +} +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS = 0 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS = 1 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS = 2 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED = 3 +DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN' +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__enumvalues = { + 0: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 1: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 2: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 3: 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', +} +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0 = 0 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64 = 1 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128 = 2 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256 = 3 +DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_ERR_OCCURRED_ACK' +DP_AUX_ERR_OCCURRED_ACK__enumvalues = { + 0: 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 1: 'DP_AUX_ERR_OCCURRED__ACK', +} +DP_AUX_ERR_OCCURRED__NOT_ACK = 0 +DP_AUX_ERR_OCCURRED__ACK = 1 +DP_AUX_ERR_OCCURRED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_POTENTIAL_ERR_REACHED_ACK' +DP_AUX_POTENTIAL_ERR_REACHED_ACK__enumvalues = { + 0: 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', + 1: 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', +} +DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK = 0 +DP_AUX_POTENTIAL_ERR_REACHED__ACK = 1 +DP_AUX_POTENTIAL_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_DEFINITE_ERR_REACHED_ACK' +DP_AUX_DEFINITE_ERR_REACHED_ACK__enumvalues = { + 0: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', + 1: 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', +} +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK = 0 +ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK = 1 +DP_AUX_DEFINITE_ERR_REACHED_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET' +DP_AUX_RESET__enumvalues = { + 0: 'DP_AUX_RESET_DEASSERTED', + 1: 'DP_AUX_RESET_ASSERTED', +} +DP_AUX_RESET_DEASSERTED = 0 +DP_AUX_RESET_ASSERTED = 1 +DP_AUX_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DP_AUX_RESET_DONE' +DP_AUX_RESET_DONE__enumvalues = { + 0: 'DP_AUX_RESET_SEQUENCE_NOT_DONE', + 1: 'DP_AUX_RESET_SEQUENCE_DONE', +} +DP_AUX_RESET_SEQUENCE_NOT_DONE = 0 +DP_AUX_RESET_SEQUENCE_DONE = 1 +DP_AUX_RESET_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_COMMAND_MODE_SRC_FORMAT' +DSI_COMMAND_MODE_SRC_FORMAT__enumvalues = { + 2: 'DSI_COMMAND_SRC_FORMAT_RGB8BIT', + 3: 'DSI_COMMAND_SRC_FORMAT_RGB332', + 4: 'DSI_COMMAND_SRC_FORMAT_RGB444', + 5: 'DSI_COMMAND_SRC_FORMAT_RGB555', + 6: 'DSI_COMMAND_SRC_FORMAT_RGB565', + 8: 'DSI_COMMAND_SRC_FORMAT_RGB888', +} +DSI_COMMAND_SRC_FORMAT_RGB8BIT = 2 +DSI_COMMAND_SRC_FORMAT_RGB332 = 3 +DSI_COMMAND_SRC_FORMAT_RGB444 = 4 +DSI_COMMAND_SRC_FORMAT_RGB555 = 5 +DSI_COMMAND_SRC_FORMAT_RGB565 = 6 +DSI_COMMAND_SRC_FORMAT_RGB888 = 8 +DSI_COMMAND_MODE_SRC_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_COMMAND_MODE_DST_FORMAT' +DSI_COMMAND_MODE_DST_FORMAT__enumvalues = { + 0: 'DSI_COMMAND_DST_FORMAT_RGB111', + 3: 'DSI_COMMAND_DST_FORMAT_RGB332', + 4: 'DSI_COMMAND_DST_FORMAT_RGB444', + 6: 'DSI_COMMAND_DST_FORMAT_RGB565', + 7: 'DSI_COMMAND_DST_FORMAT_RGB666', + 8: 'DSI_COMMAND_DST_FORMAT_RGB888', +} +DSI_COMMAND_DST_FORMAT_RGB111 = 0 +DSI_COMMAND_DST_FORMAT_RGB332 = 3 +DSI_COMMAND_DST_FORMAT_RGB444 = 4 +DSI_COMMAND_DST_FORMAT_RGB565 = 6 +DSI_COMMAND_DST_FORMAT_RGB666 = 7 +DSI_COMMAND_DST_FORMAT_RGB888 = 8 +DSI_COMMAND_MODE_DST_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_FLAG_CLR' +DSI_FLAG_CLR__enumvalues = { + 0: 'DSI_FLAG_NO_CLEAR', + 1: 'DSI_FLAG_CLEAR', +} +DSI_FLAG_NO_CLEAR = 0 +DSI_FLAG_CLEAR = 1 +DSI_FLAG_CLR = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_BIT_SWAP' +DSI_BIT_SWAP__enumvalues = { + 0: 'DSI_BIT_SWAP_DISABLE', + 1: 'DSI_BIT_SWAP_ENABLE', +} +DSI_BIT_SWAP_DISABLE = 0 +DSI_BIT_SWAP_ENABLE = 1 +DSI_BIT_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CLK_GATING' +DSI_CLK_GATING__enumvalues = { + 0: 'DSI_CLK_GATING_ENABLE', + 1: 'DSI_CLK_GATING_DISABLE', +} +DSI_CLK_GATING_ENABLE = 0 +DSI_CLK_GATING_DISABLE = 1 +DSI_CLK_GATING = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_LANE_ULPS_REQUEST' +DSI_LANE_ULPS_REQUEST__enumvalues = { + 0: 'DSI_LANE_ULPS_REQUEST_DEASSERT', + 1: 'DSI_LANE_ULPS_REQUEST_ASSERT', +} +DSI_LANE_ULPS_REQUEST_DEASSERT = 0 +DSI_LANE_ULPS_REQUEST_ASSERT = 1 +DSI_LANE_ULPS_REQUEST = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_LANE_ULPS_EXIT' +DSI_LANE_ULPS_EXIT__enumvalues = { + 0: 'DSI_LANE_ULPS_EXIT_DEASSERT', + 1: 'DSI_LANE_ULPS_EXIT_ASSERT', +} +DSI_LANE_ULPS_EXIT_DEASSERT = 0 +DSI_LANE_ULPS_EXIT_ASSERT = 1 +DSI_LANE_ULPS_EXIT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_LANE_FORCE_TX_STOP' +DSI_LANE_FORCE_TX_STOP__enumvalues = { + 0: 'DSI_LANE_FORCE_TX_STOP_DEASSERT', + 1: 'DSI_LANE_FORCE_TX_STOP_ASSERT', +} +DSI_LANE_FORCE_TX_STOP_DEASSERT = 0 +DSI_LANE_FORCE_TX_STOP_ASSERT = 1 +DSI_LANE_FORCE_TX_STOP = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CLOCK_LANE_HS_FORCE_REQUEST' +DSI_CLOCK_LANE_HS_FORCE_REQUEST__enumvalues = { + 0: 'DSI_CLOCK_LANE_HS_FORCE_REQUEST_DEASSERT', + 1: 'DSI_CLOCK_LANE_HS_FORCE_REQUEST_ASSERT', +} +DSI_CLOCK_LANE_HS_FORCE_REQUEST_DEASSERT = 0 +DSI_CLOCK_LANE_HS_FORCE_REQUEST_ASSERT = 1 +DSI_CLOCK_LANE_HS_FORCE_REQUEST = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CONTROLLER_EN' +DSI_CONTROLLER_EN__enumvalues = { + 0: 'DSI_CONTROLLER_DISABLE', + 1: 'DSI_CONTROLLER_ENABLE', +} +DSI_CONTROLLER_DISABLE = 0 +DSI_CONTROLLER_ENABLE = 1 +DSI_CONTROLLER_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_MODE_EN' +DSI_VIDEO_MODE_EN__enumvalues = { + 0: 'DSI_VIDEO_MODE_DISABLE', + 1: 'DSI_VIDEO_MODE_ENABLE', +} +DSI_VIDEO_MODE_DISABLE = 0 +DSI_VIDEO_MODE_ENABLE = 1 +DSI_VIDEO_MODE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CMD_MODE_EN' +DSI_CMD_MODE_EN__enumvalues = { + 0: 'DSI_CMD_MODE_DISABLE', + 1: 'DSI_CMD_MODE_ENABLE', +} +DSI_CMD_MODE_DISABLE = 0 +DSI_CMD_MODE_ENABLE = 1 +DSI_CMD_MODE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DATA_LANE0_EN' +DSI_DATA_LANE0_EN__enumvalues = { + 0: 'DSI_DATA_LANE0_DISABLE', + 1: 'DSI_DATA_LANE0_ENABLE', +} +DSI_DATA_LANE0_DISABLE = 0 +DSI_DATA_LANE0_ENABLE = 1 +DSI_DATA_LANE0_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DATA_LANE1_EN' +DSI_DATA_LANE1_EN__enumvalues = { + 0: 'DSI_DATA_LANE1_DISABLE', + 1: 'DSI_DATA_LANE1_ENABLE', +} +DSI_DATA_LANE1_DISABLE = 0 +DSI_DATA_LANE1_ENABLE = 1 +DSI_DATA_LANE1_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DATA_LANE2_EN' +DSI_DATA_LANE2_EN__enumvalues = { + 0: 'DSI_DATA_LANE2_DISABLE', + 1: 'DSI_DATA_LANE2_ENABLE', +} +DSI_DATA_LANE2_DISABLE = 0 +DSI_DATA_LANE2_ENABLE = 1 +DSI_DATA_LANE2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DATA_LANE3_EN' +DSI_DATA_LANE3_EN__enumvalues = { + 0: 'DSI_DATA_LANE3_DISABLE', + 1: 'DSI_DATA_LANE3_ENABLE', +} +DSI_DATA_LANE3_DISABLE = 0 +DSI_DATA_LANE3_ENABLE = 1 +DSI_DATA_LANE3_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CLOCK_LANE_EN' +DSI_CLOCK_LANE_EN__enumvalues = { + 0: 'DSI_CLOCK_LANE_DISABLE', + 1: 'DSI_CLOCK_LANE_ENABLE', +} +DSI_CLOCK_LANE_DISABLE = 0 +DSI_CLOCK_LANE_ENABLE = 1 +DSI_CLOCK_LANE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PHY_DATA_LANE0_EN' +DSI_PHY_DATA_LANE0_EN__enumvalues = { + 0: 'DSI_PHY_DATA_LANE0_DISABLE', + 1: 'DSI_PHY_DATA_LANE0_ENABLE', +} +DSI_PHY_DATA_LANE0_DISABLE = 0 +DSI_PHY_DATA_LANE0_ENABLE = 1 +DSI_PHY_DATA_LANE0_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PHY_DATA_LANE1_EN' +DSI_PHY_DATA_LANE1_EN__enumvalues = { + 0: 'DSI_PHY_DATA_LANE1_DISABLE', + 1: 'DSI_PHY_DATA_LANE1_ENABLE', +} +DSI_PHY_DATA_LANE1_DISABLE = 0 +DSI_PHY_DATA_LANE1_ENABLE = 1 +DSI_PHY_DATA_LANE1_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PHY_DATA_LANE2_EN' +DSI_PHY_DATA_LANE2_EN__enumvalues = { + 0: 'DSI_PHY_DATA_LANE2_DISABLE', + 1: 'DSI_PHY_DATA_LANE2_ENABLE', +} +DSI_PHY_DATA_LANE2_DISABLE = 0 +DSI_PHY_DATA_LANE2_ENABLE = 1 +DSI_PHY_DATA_LANE2_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PHY_DATA_LANE3_EN' +DSI_PHY_DATA_LANE3_EN__enumvalues = { + 0: 'DSI_PHY_DATA_LANE3_DISABLE', + 1: 'DSI_PHY_DATA_LANE3_ENABLE', +} +DSI_PHY_DATA_LANE3_DISABLE = 0 +DSI_PHY_DATA_LANE3_ENABLE = 1 +DSI_PHY_DATA_LANE3_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RESET_DISPCLK' +DSI_RESET_DISPCLK__enumvalues = { + 0: 'DSI_NO_RESET_ON_DISPCLK_DOMAIN_LOGIC', + 1: 'DSI_RESET_ON_DISPCLK_DOMAIN_LOGIC', +} +DSI_NO_RESET_ON_DISPCLK_DOMAIN_LOGIC = 0 +DSI_RESET_ON_DISPCLK_DOMAIN_LOGIC = 1 +DSI_RESET_DISPCLK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RESET_DSICLK' +DSI_RESET_DSICLK__enumvalues = { + 0: 'DSI_NO_RESET_ON_DSICLK_DOMAIN_LOGIC', + 1: 'DSI_RESET_ON_DSICLK_DOMAIN_LOGIC', +} +DSI_NO_RESET_ON_DSICLK_DOMAIN_LOGIC = 0 +DSI_RESET_ON_DSICLK_DOMAIN_LOGIC = 1 +DSI_RESET_DSICLK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RESET_BYTECLK' +DSI_RESET_BYTECLK__enumvalues = { + 0: 'DSI_NO_RESET_ON_BYTECLK_DOMAIN_LOGIC', + 1: 'DSI_RESET_ON_BYTECLK_DOMAIN_LOGIC', +} +DSI_NO_RESET_ON_BYTECLK_DOMAIN_LOGIC = 0 +DSI_RESET_ON_BYTECLK_DOMAIN_LOGIC = 1 +DSI_RESET_BYTECLK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RESET_ESCCLK' +DSI_RESET_ESCCLK__enumvalues = { + 0: 'DSI_NO_RESET_ON_ESCCLK_DOMAIN_LOGIC', + 1: 'DSI_RESET_ON_ESCCLK_DOMAIN_LOGIC', +} +DSI_NO_RESET_ON_ESCCLK_DOMAIN_LOGIC = 0 +DSI_RESET_ON_ESCCLK_DOMAIN_LOGIC = 1 +DSI_RESET_ESCCLK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CRTC_SEL' +DSI_CRTC_SEL__enumvalues = { + 0: 'DSI_GET_PIXEL_STREAM_FROM_FMT0', + 1: 'DSI_GET_PIXEL_STREAM_FROM_FMT1', + 2: 'DSI_GET_PIXEL_STREAM_FROM_FMT2', + 3: 'DSI_GET_PIXEL_STREAM_FROM_FMT3', + 4: 'DSI_GET_PIXEL_STREAM_FROM_FMT4', + 5: 'DSI_GET_PIXEL_STREAM_FROM_FMT5', +} +DSI_GET_PIXEL_STREAM_FROM_FMT0 = 0 +DSI_GET_PIXEL_STREAM_FROM_FMT1 = 1 +DSI_GET_PIXEL_STREAM_FROM_FMT2 = 2 +DSI_GET_PIXEL_STREAM_FROM_FMT3 = 3 +DSI_GET_PIXEL_STREAM_FROM_FMT4 = 4 +DSI_GET_PIXEL_STREAM_FROM_FMT5 = 5 +DSI_CRTC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PACKET_BYTE_MSB_LSB_FLIP' +DSI_PACKET_BYTE_MSB_LSB_FLIP__enumvalues = { + 0: 'DSI_PACKET_BYTE_MSB_LSB_FLIP_NO_SWAP', + 1: 'DSI_PACKET_BYTE_MSB_LSB_FLIP_SWAP', +} +DSI_PACKET_BYTE_MSB_LSB_FLIP_NO_SWAP = 0 +DSI_PACKET_BYTE_MSB_LSB_FLIP_SWAP = 1 +DSI_PACKET_BYTE_MSB_LSB_FLIP = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_MODE_DST_FORMAT' +DSI_VIDEO_MODE_DST_FORMAT__enumvalues = { + 0: 'DSI_VIDEO_DST_FORMAT_RGB565', + 1: 'DSI_VIDEO_DST_FORMAT_RGB666_PACKED', + 2: 'DSI_VIDEO_DST_FORMAT_RGB666_LOOSELY_PACKED', + 3: 'DSI_VIDEO_DST_FORMAT_RGB888', +} +DSI_VIDEO_DST_FORMAT_RGB565 = 0 +DSI_VIDEO_DST_FORMAT_RGB666_PACKED = 1 +DSI_VIDEO_DST_FORMAT_RGB666_LOOSELY_PACKED = 2 +DSI_VIDEO_DST_FORMAT_RGB888 = 3 +DSI_VIDEO_MODE_DST_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_TRAFFIC_MODE' +DSI_VIDEO_TRAFFIC_MODE__enumvalues = { + 0: 'DSI_TRAFFIC_MODE_SYNC_PULSES', + 1: 'DSI_TRAFFIC_MODE_SYNC_EVENTS', + 2: 'DSI_TRAFFIC_MODE_BURST', + 3: 'DSI_TRAFFIC_MODE_RESERVED', +} +DSI_TRAFFIC_MODE_SYNC_PULSES = 0 +DSI_TRAFFIC_MODE_SYNC_EVENTS = 1 +DSI_TRAFFIC_MODE_BURST = 2 +DSI_TRAFFIC_MODE_RESERVED = 3 +DSI_VIDEO_TRAFFIC_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_BLLP_PWR_MODE' +DSI_VIDEO_BLLP_PWR_MODE__enumvalues = { + 0: 'DSI_VIDEO_BLLP_PWR_MODE_HS', + 1: 'DSI_VIDEO_BLLP_PWR_MODE_LP', +} +DSI_VIDEO_BLLP_PWR_MODE_HS = 0 +DSI_VIDEO_BLLP_PWR_MODE_LP = 1 +DSI_VIDEO_BLLP_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_EOF_BLLP_PWR_MODE' +DSI_VIDEO_EOF_BLLP_PWR_MODE__enumvalues = { + 0: 'DSI_VIDEO_EOF_BLLP_PWR_MODE_HS', + 1: 'DSI_VIDEO_EOF_BLLP_PWR_MODE_LP', +} +DSI_VIDEO_EOF_BLLP_PWR_MODE_HS = 0 +DSI_VIDEO_EOF_BLLP_PWR_MODE_LP = 1 +DSI_VIDEO_EOF_BLLP_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_PWR_MODE' +DSI_VIDEO_PWR_MODE__enumvalues = { + 0: 'DSI_VIDEO_PWR_MODE_HS', + 1: 'DSI_VIDEO_PWR_MODE_LP', +} +DSI_VIDEO_PWR_MODE_HS = 0 +DSI_VIDEO_PWR_MODE_LP = 1 +DSI_VIDEO_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_VIDEO_PULSE_MODE_OPT' +DSI_VIDEO_PULSE_MODE_OPT__enumvalues = { + 0: 'PULSE_MODE_OPT_NO_HSA', + 1: 'PULSE_MODE_OPT_SEND', +} +PULSE_MODE_OPT_NO_HSA = 0 +PULSE_MODE_OPT_SEND = 1 +DSI_VIDEO_PULSE_MODE_OPT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RGB_SWAP' +DSI_RGB_SWAP__enumvalues = { + 0: 'DSI_SWAP_RGB', + 1: 'DSI_SWAP_RBG', + 2: 'DSI_SWAP_BGR', + 3: 'DSI_SWAP_BRG', + 4: 'DSI_SWAP_GRB', + 5: 'DSI_SWAP_GBR', +} +DSI_SWAP_RGB = 0 +DSI_SWAP_RBG = 1 +DSI_SWAP_BGR = 2 +DSI_SWAP_BRG = 3 +DSI_SWAP_GRB = 4 +DSI_SWAP_GBR = 5 +DSI_RGB_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CMD_PACKET_TYPE' +DSI_CMD_PACKET_TYPE__enumvalues = { + 0: 'DSI_CMD_PACKET_TYPE_SHORT', + 1: 'DSI_CMD_PACKET_TYPE_LONG', +} +DSI_CMD_PACKET_TYPE_SHORT = 0 +DSI_CMD_PACKET_TYPE_LONG = 1 +DSI_CMD_PACKET_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CMD_PWR_MODE' +DSI_CMD_PWR_MODE__enumvalues = { + 0: 'DSI_CMD_PWR_MODE_HS', + 1: 'DSI_CMD_PWR_MODE_LP', +} +DSI_CMD_PWR_MODE_HS = 0 +DSI_CMD_PWR_MODE_LP = 1 +DSI_CMD_PWR_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CMD_EMBEDDED_MODE' +DSI_CMD_EMBEDDED_MODE__enumvalues = { + 0: 'CMD_EMBEDDED_MODE_DISABLE', + 1: 'CMD_EMBEDDED_MODE_ENABLE', +} +CMD_EMBEDDED_MODE_DISABLE = 0 +CMD_EMBEDDED_MODE_ENABLE = 1 +DSI_CMD_EMBEDDED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CMD_ORDER' +DSI_CMD_ORDER__enumvalues = { + 0: 'DSI_CMD_ORDER_COMMAND_FIRST', + 1: 'DSI_CMD_ORDER_DATA_FIRST', +} +DSI_CMD_ORDER_COMMAND_FIRST = 0 +DSI_CMD_ORDER_DATA_FIRST = 1 +DSI_CMD_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DATA_BUFFER_ID' +DSI_DATA_BUFFER_ID__enumvalues = { + 0: 'DSI_DATA_BUFFER_OFFSET0', + 1: 'DSI_DATA_BUFFER_OFFSET1', +} +DSI_DATA_BUFFER_OFFSET0 = 0 +DSI_DATA_BUFFER_OFFSET1 = 1 +DSI_DATA_BUFFER_ID = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DWORD_BYTE_SWAP' +DSI_DWORD_BYTE_SWAP__enumvalues = { + 0: 'DWORD_BYTE_SWAP_NO_SWAP', + 1: 'DWORD_BYTE_SWAP_BYTE_SWAP', + 2: 'DWORD_BYTE_SWAP_WORD_SWAP', + 3: 'DWORD_BYTE_SWAP_BOTH_SWAP', +} +DWORD_BYTE_SWAP_NO_SWAP = 0 +DWORD_BYTE_SWAP_BYTE_SWAP = 1 +DWORD_BYTE_SWAP_WORD_SWAP = 2 +DWORD_BYTE_SWAP_BOTH_SWAP = 3 +DSI_DWORD_BYTE_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_INSERT_DCS_COMMAND' +DSI_INSERT_DCS_COMMAND__enumvalues = { + 0: 'DSI_INSERT_DCS_COMMAND_DISABLE', + 1: 'DSI_INSERT_DCS_COMMAND_ENABLE', +} +DSI_INSERT_DCS_COMMAND_DISABLE = 0 +DSI_INSERT_DCS_COMMAND_ENABLE = 1 +DSI_INSERT_DCS_COMMAND = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DMAFIFO_WRITE_WATERMARK' +DSI_DMAFIFO_WRITE_WATERMARK__enumvalues = { + 0: 'DSI_DMAFIFO_WRITE_WATERMARK_HALF', + 1: 'DSI_DMAFIFO_WRITE_WATERMARK_FOURTH', + 2: 'DSI_DMAFIFO_WRITE_WATERMARK_EIGHTH', + 3: 'DSI_DMAFIFO_WRITE_WATERMARK_SIXTEENTH', +} +DSI_DMAFIFO_WRITE_WATERMARK_HALF = 0 +DSI_DMAFIFO_WRITE_WATERMARK_FOURTH = 1 +DSI_DMAFIFO_WRITE_WATERMARK_EIGHTH = 2 +DSI_DMAFIFO_WRITE_WATERMARK_SIXTEENTH = 3 +DSI_DMAFIFO_WRITE_WATERMARK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DMAFIFO_READ_WATERMARK' +DSI_DMAFIFO_READ_WATERMARK__enumvalues = { + 0: 'DSI_DMAFIFO_READ_WATERMARK_HALF', + 1: 'DSI_DMAFIFO_READ_WATERMARK_FOURTH', + 2: 'DSI_DMAFIFO_READ_WATERMARK_EIGHTH', + 3: 'DSI_DMAFIFO_READ_WATERMARK_SIXTEENTH', +} +DSI_DMAFIFO_READ_WATERMARK_HALF = 0 +DSI_DMAFIFO_READ_WATERMARK_FOURTH = 1 +DSI_DMAFIFO_READ_WATERMARK_EIGHTH = 2 +DSI_DMAFIFO_READ_WATERMARK_SIXTEENTH = 3 +DSI_DMAFIFO_READ_WATERMARK = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_USE_DENG_LENGTH' +DSI_USE_DENG_LENGTH__enumvalues = { + 0: 'DSI_USE_DENG_LENGTH_DISABLE', + 1: 'DSI_USE_DENG_LENGTH_ENABLE', +} +DSI_USE_DENG_LENGTH_DISABLE = 0 +DSI_USE_DENG_LENGTH_ENABLE = 1 +DSI_USE_DENG_LENGTH = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_COMMAND_TRIGGER_MODE' +DSI_COMMAND_TRIGGER_MODE__enumvalues = { + 0: 'DSI_COMMAND_TRIGGER_MODE_AUTO', + 1: 'DSI_COMMAND_TRIGGER_MODE_MANUAL', +} +DSI_COMMAND_TRIGGER_MODE_AUTO = 0 +DSI_COMMAND_TRIGGER_MODE_MANUAL = 1 +DSI_COMMAND_TRIGGER_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_COMMAND_TRIGGER_SEL' +DSI_COMMAND_TRIGGER_SEL__enumvalues = { + 0: 'DSI_COMMAND_TRIGGER_SEL_NONE', + 1: 'DSI_COMMAND_TRIGGER_SEL_CRTC', + 2: 'DSI_COMMAND_TRIGGER_SEL_TE', + 3: 'DSI_COMMAND_TRIGGER_SEL_HW', +} +DSI_COMMAND_TRIGGER_SEL_NONE = 0 +DSI_COMMAND_TRIGGER_SEL_CRTC = 1 +DSI_COMMAND_TRIGGER_SEL_TE = 2 +DSI_COMMAND_TRIGGER_SEL_HW = 3 +DSI_COMMAND_TRIGGER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_HW_SOURCE_SEL' +DSI_HW_SOURCE_SEL__enumvalues = { + 0: 'HW_SOURCE_SEL_NONE', + 1: 'HW_SOURCE_SEL_DSC_VUP', + 2: 'HW_SOURCE_SEL_DSC_VLP', + 3: 'HW_SOURCE_SEL_DSC_JPEG', +} +HW_SOURCE_SEL_NONE = 0 +HW_SOURCE_SEL_DSC_VUP = 1 +HW_SOURCE_SEL_DSC_VLP = 2 +HW_SOURCE_SEL_DSC_JPEG = 3 +DSI_HW_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_COMMAND_TRIGGER_ORDER' +DSI_COMMAND_TRIGGER_ORDER__enumvalues = { + 0: 'DSI_COMMAND_TRIGGER_ORDER_DMA', + 1: 'DSI_COMMAND_TRIGGER_ORDER_DENG', +} +DSI_COMMAND_TRIGGER_ORDER_DMA = 0 +DSI_COMMAND_TRIGGER_ORDER_DENG = 1 +DSI_COMMAND_TRIGGER_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_TE_SRC_SEL' +DSI_TE_SRC_SEL__enumvalues = { + 0: 'DSI_TE_SEL_LINK', + 1: 'DSI_TE_SEL_PIN', +} +DSI_TE_SEL_LINK = 0 +DSI_TE_SEL_PIN = 1 +DSI_TE_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_EXT_TE_MUX' +DSI_EXT_TE_MUX__enumvalues = { + 0: 'DSI_XT_TE_MUX_LCDD17', + 1: 'DSI_XT_TE_MUX_DCLK', + 2: 'DSI_XT_TE_MUX_SS', + 3: 'DSI_XT_TE_MUX_GCLK', + 4: 'DSI_XT_TE_MUX_GOE', + 5: 'DSI_XT_TE_MUX_DINV', + 6: 'DSI_XT_TE_MUX_FRAME', + 7: 'DSI_XT_TE_MUX_GPIO4', + 8: 'DSI_XT_TE_MUX_GPIO5', +} +DSI_XT_TE_MUX_LCDD17 = 0 +DSI_XT_TE_MUX_DCLK = 1 +DSI_XT_TE_MUX_SS = 2 +DSI_XT_TE_MUX_GCLK = 3 +DSI_XT_TE_MUX_GOE = 4 +DSI_XT_TE_MUX_DINV = 5 +DSI_XT_TE_MUX_FRAME = 6 +DSI_XT_TE_MUX_GPIO4 = 7 +DSI_XT_TE_MUX_GPIO5 = 8 +DSI_EXT_TE_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_EXT_TE_MODE' +DSI_EXT_TE_MODE__enumvalues = { + 0: 'DSI_EXT_TE_MODE_VSYNC_EDGE', + 1: 'DSI_EXT_TE_MODE_VSYNC_WIDTH', + 2: 'DSI_EXT_TE_MODE_HVSYNC_EDGE', + 3: 'DSI_EXT_TE_MODE_HVSYNC_WIDTH', +} +DSI_EXT_TE_MODE_VSYNC_EDGE = 0 +DSI_EXT_TE_MODE_VSYNC_WIDTH = 1 +DSI_EXT_TE_MODE_HVSYNC_EDGE = 2 +DSI_EXT_TE_MODE_HVSYNC_WIDTH = 3 +DSI_EXT_TE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_EXT_RESET_POL' +DSI_EXT_RESET_POL__enumvalues = { + 0: 'DSI_EXT_RESET_POL_HIGH', + 1: 'DSI_EXT_RESET_POL_LOW', +} +DSI_EXT_RESET_POL_HIGH = 0 +DSI_EXT_RESET_POL_LOW = 1 +DSI_EXT_RESET_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_EXT_TE_POL' +DSI_EXT_TE_POL__enumvalues = { + 0: 'DSI_EXT_TE_POL_RISING', + 1: 'DSI_EXT_TE_POL_FALLING', +} +DSI_EXT_TE_POL_RISING = 0 +DSI_EXT_TE_POL_FALLING = 1 +DSI_EXT_TE_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RESET_PANEL' +DSI_RESET_PANEL__enumvalues = { + 0: 'DSI_RESET_PANEL_DEASSERT', + 1: 'DSI_RESET_PANEL_ASSERT', +} +DSI_RESET_PANEL_DEASSERT = 0 +DSI_RESET_PANEL_ASSERT = 1 +DSI_RESET_PANEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CRC_ENABLE' +DSI_CRC_ENABLE__enumvalues = { + 0: 'DSI_CRC_CAL_DISABLE', + 1: 'DSI_CRC_CAL_ENABLE', +} +DSI_CRC_CAL_DISABLE = 0 +DSI_CRC_CAL_ENABLE = 1 +DSI_CRC_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_TX_EOT_APPEND' +DSI_TX_EOT_APPEND__enumvalues = { + 0: 'DSI_TX_EOT_APPEND_DISABLE', + 1: 'DSI_TX_EOT_APPEND_ENABLE', +} +DSI_TX_EOT_APPEND_DISABLE = 0 +DSI_TX_EOT_APPEND_ENABLE = 1 +DSI_TX_EOT_APPEND = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_RX_EOT_IGNORE' +DSI_RX_EOT_IGNORE__enumvalues = { + 0: 'DSI_RX_EOT_IGNORE_DISABLE', + 1: 'DSI_RX_EOT_IGNORE_ENABLE', +} +DSI_RX_EOT_IGNORE_DISABLE = 0 +DSI_RX_EOT_IGNORE_ENABLE = 1 +DSI_RX_EOT_IGNORE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_MIPI_BIST_RESET' +DSI_MIPI_BIST_RESET__enumvalues = { + 0: 'DSI_MIPI_BIST_RESET_DEASSERT', + 1: 'DSI_MIPI_BIST_RESET_ASSERT', +} +DSI_MIPI_BIST_RESET_DEASSERT = 0 +DSI_MIPI_BIST_RESET_ASSERT = 1 +DSI_MIPI_BIST_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_MIPI_BIST_VIDEO_FRMT' +DSI_MIPI_BIST_VIDEO_FRMT__enumvalues = { + 0: 'DSI_MIPI_BIST_VIDEO_FRMT_YUV422', + 1: 'DSI_MIPI_BIST_VIDEO_FRMT_RAW8', +} +DSI_MIPI_BIST_VIDEO_FRMT_YUV422 = 0 +DSI_MIPI_BIST_VIDEO_FRMT_RAW8 = 1 +DSI_MIPI_BIST_VIDEO_FRMT = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_MIPI_BIST_START' +DSI_MIPI_BIST_START__enumvalues = { + 0: 'DSI_MIPI_BIST_START_DEASSERT', + 1: 'DSI_MIPI_BIST_START_ASSERT', +} +DSI_MIPI_BIST_START_DEASSERT = 0 +DSI_MIPI_BIST_START_ASSERT = 1 +DSI_MIPI_BIST_START = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DBG_CLK_SEL' +DSI_DBG_CLK_SEL__enumvalues = { + 0: 'DSI_TEST_CLK_SEL_DISPCLK_P', + 1: 'DSI_TEST_CLK_SEL_DISPCLK_G', + 2: 'DSI_TEST_CLK_SEL_DISPCLK_R', + 3: 'DSI_TEST_CLK_SEL_ESCCLK_G', + 4: 'DSI_TEST_CLK_SEL_BYTECLK_G', + 5: 'DSI_TEST_CLK_SEL_DSICLK_P', + 6: 'DSI_TEST_CLK_SEL_DSICLK_R', + 7: 'DSI_TEST_CLK_SEL_DSICLK_G', + 8: 'DSI_TEST_CLK_SEL_DSICLK_TRN', +} +DSI_TEST_CLK_SEL_DISPCLK_P = 0 +DSI_TEST_CLK_SEL_DISPCLK_G = 1 +DSI_TEST_CLK_SEL_DISPCLK_R = 2 +DSI_TEST_CLK_SEL_ESCCLK_G = 3 +DSI_TEST_CLK_SEL_BYTECLK_G = 4 +DSI_TEST_CLK_SEL_DSICLK_P = 5 +DSI_TEST_CLK_SEL_DSICLK_R = 6 +DSI_TEST_CLK_SEL_DSICLK_G = 7 +DSI_TEST_CLK_SEL_DSICLK_TRN = 8 +DSI_DBG_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DENG_FIFO_USE_OVERWRITE_LEVEL' +DSI_DENG_FIFO_USE_OVERWRITE_LEVEL__enumvalues = { + 0: 'DSI_DENG_FIFO_LEVEL_OVERWRITE', + 1: 'DSI_DENG_FIFO_LEVEL_CAL_AVERAGE', +} +DSI_DENG_FIFO_LEVEL_OVERWRITE = 0 +DSI_DENG_FIFO_LEVEL_CAL_AVERAGE = 1 +DSI_DENG_FIFO_USE_OVERWRITE_LEVEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE' +DSI_DENG_FIFO_FORCE_RECAL_AVERAGE__enumvalues = { + 0: 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_DEASSERT', + 1: 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_ASSERT', +} +DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_DEASSERT = 0 +DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_ASSERT = 1 +DSI_DENG_FIFO_FORCE_RECAL_AVERAGE = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX' +DSI_DENG_FIFO_FORCE_RECOMP_MINMAX__enumvalues = { + 0: 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_DEASSERT', + 1: 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_ASSERT', +} +DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_DEASSERT = 0 +DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_ASSERT = 1 +DSI_DENG_FIFO_FORCE_RECOMP_MINMAX = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DENG_FIFO_START' +DSI_DENG_FIFO_START__enumvalues = { + 0: 'DSI_DENG_FIFO_START_DEASSERT', + 1: 'DSI_DENG_FIFO_START_ASSERT', +} +DSI_DENG_FIFO_START_DEASSERT = 0 +DSI_DENG_FIFO_START_ASSERT = 1 +DSI_DENG_FIFO_START = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_USE_CMDFIFO' +DSI_USE_CMDFIFO__enumvalues = { + 0: 'DSI_CMD_USE_DMAFIFO', + 1: 'DSI_CMD_USE_CMDFIFO', +} +DSI_CMD_USE_DMAFIFO = 0 +DSI_CMD_USE_CMDFIFO = 1 +DSI_USE_CMDFIFO = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_CRTC_FREEZE_TRIG' +DSI_CRTC_FREEZE_TRIG__enumvalues = { + 0: 'DSI_CRTC_FREEZE_TRIG_DEASSERT', + 1: 'DSI_CRTC_FREEZE_TRIG_ASSERT', +} +DSI_CRTC_FREEZE_TRIG_DEASSERT = 0 +DSI_CRTC_FREEZE_TRIG_ASSERT = 1 +DSI_CRTC_FREEZE_TRIG = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_PERF_LATENCY_SEL' +DSI_PERF_LATENCY_SEL__enumvalues = { + 0: 'DSI_PERF_LATENCY_SEL_DATA_LANE0', + 1: 'DSI_PERF_LATENCY_SEL_DATA_LANE1', + 2: 'DSI_PERF_LATENCY_SEL_DATA_LANE2', + 3: 'DSI_PERF_LATENCY_SEL_DATA_LANE3', +} +DSI_PERF_LATENCY_SEL_DATA_LANE0 = 0 +DSI_PERF_LATENCY_SEL_DATA_LANE1 = 1 +DSI_PERF_LATENCY_SEL_DATA_LANE2 = 2 +DSI_PERF_LATENCY_SEL_DATA_LANE3 = 3 +DSI_PERF_LATENCY_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DEBUG_DSICLK_SEL' +DSI_DEBUG_DSICLK_SEL__enumvalues = { + 0: 'DSI_DEBUG_DSICLK_SEL_VIDEO_ENGINE', + 1: 'DSI_DEBUG_DSICLK_SEL_CMD_ENGINE', + 2: 'DSI_DEBUG_DSICLK_SEL_RESYNC_FIFO', + 3: 'DSI_DEBUG_DSICLK_SEL_CMDFIFO', + 4: 'DSI_DEBUG_DSICLK_SEL_CMDBUFFER', + 5: 'DSI_DEBUG_DSICLK_SEL_AFIFO', + 6: 'DSI_DEBUG_DSICLK_SEL_LANECTRL', +} +DSI_DEBUG_DSICLK_SEL_VIDEO_ENGINE = 0 +DSI_DEBUG_DSICLK_SEL_CMD_ENGINE = 1 +DSI_DEBUG_DSICLK_SEL_RESYNC_FIFO = 2 +DSI_DEBUG_DSICLK_SEL_CMDFIFO = 3 +DSI_DEBUG_DSICLK_SEL_CMDBUFFER = 4 +DSI_DEBUG_DSICLK_SEL_AFIFO = 5 +DSI_DEBUG_DSICLK_SEL_LANECTRL = 6 +DSI_DEBUG_DSICLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DSI_DEBUG_BYTECLK_SEL' +DSI_DEBUG_BYTECLK_SEL__enumvalues = { + 0: 'DSI_DEBUG_BYTECLK_SEL_AFIFO', + 1: 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO0', + 2: 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO1', + 3: 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO2', + 4: 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO3', + 5: 'DSI_DEBUG_BYTECLK_SEL_LANEBUF0', + 6: 'DSI_DEBUG_BYTECLK_SEL_LANEBUF1', + 7: 'DSI_DEBUG_BYTECLK_SEL_LANEBUF2', + 8: 'DSI_DEBUG_BYTECLK_SEL_LANEBUF3', + 9: 'DSI_DEBUG_BYTECLK_SEL_PINGPONG0', + 10: 'DSI_DEBUG_BYTECLK_SEL_PINGPONG1', + 11: 'DSI_DEBUG_BYTECLK_SEL_PINGPING2', + 12: 'DSI_DEBUG_BYTECLK_SEL_PINGPING3', + 13: 'DSI_DEBUG_BYTECLK_SEL_EOT', + 14: 'DSI_DEBUG_BYTECLK_SEL_LANECTRL', +} +DSI_DEBUG_BYTECLK_SEL_AFIFO = 0 +DSI_DEBUG_BYTECLK_SEL_LANEFIFO0 = 1 +DSI_DEBUG_BYTECLK_SEL_LANEFIFO1 = 2 +DSI_DEBUG_BYTECLK_SEL_LANEFIFO2 = 3 +DSI_DEBUG_BYTECLK_SEL_LANEFIFO3 = 4 +DSI_DEBUG_BYTECLK_SEL_LANEBUF0 = 5 +DSI_DEBUG_BYTECLK_SEL_LANEBUF1 = 6 +DSI_DEBUG_BYTECLK_SEL_LANEBUF2 = 7 +DSI_DEBUG_BYTECLK_SEL_LANEBUF3 = 8 +DSI_DEBUG_BYTECLK_SEL_PINGPONG0 = 9 +DSI_DEBUG_BYTECLK_SEL_PINGPONG1 = 10 +DSI_DEBUG_BYTECLK_SEL_PINGPING2 = 11 +DSI_DEBUG_BYTECLK_SEL_PINGPING3 = 12 +DSI_DEBUG_BYTECLK_SEL_EOT = 13 +DSI_DEBUG_BYTECLK_SEL_LANECTRL = 14 +DSI_DEBUG_BYTECLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_HPD_SEL' +DCIOCHIP_HPD_SEL__enumvalues = { + 0: 'DCIOCHIP_HPD_SEL_ASYNC', + 1: 'DCIOCHIP_HPD_SEL_CLOCKED', +} +DCIOCHIP_HPD_SEL_ASYNC = 0 +DCIOCHIP_HPD_SEL_CLOCKED = 1 +DCIOCHIP_HPD_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PAD_MODE' +DCIOCHIP_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_PAD_MODE_DDC', + 1: 'DCIOCHIP_PAD_MODE_DP', +} +DCIOCHIP_PAD_MODE_DDC = 0 +DCIOCHIP_PAD_MODE_DP = 1 +DCIOCHIP_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUXSLAVE_PAD_MODE' +DCIOCHIP_AUXSLAVE_PAD_MODE__enumvalues = { + 0: 'DCIOCHIP_AUXSLAVE_PAD_MODE_I2C', + 1: 'DCIOCHIP_AUXSLAVE_PAD_MODE_AUX', +} +DCIOCHIP_AUXSLAVE_PAD_MODE_I2C = 0 +DCIOCHIP_AUXSLAVE_PAD_MODE_AUX = 1 +DCIOCHIP_AUXSLAVE_PAD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_INVERT' +DCIOCHIP_INVERT__enumvalues = { + 0: 'DCIOCHIP_POL_NON_INVERT', + 1: 'DCIOCHIP_POL_INVERT', +} +DCIOCHIP_POL_NON_INVERT = 0 +DCIOCHIP_POL_INVERT = 1 +DCIOCHIP_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_PD_EN' +DCIOCHIP_PD_EN__enumvalues = { + 0: 'DCIOCHIP_PD_EN_NOTALLOW', + 1: 'DCIOCHIP_PD_EN_ALLOW', +} +DCIOCHIP_PD_EN_NOTALLOW = 0 +DCIOCHIP_PD_EN_ALLOW = 1 +DCIOCHIP_PD_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_MASK_EN' +DCIOCHIP_GPIO_MASK_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 1: 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', +} +DCIOCHIP_GPIO_MASK_EN_HARDWARE = 0 +DCIOCHIP_GPIO_MASK_EN_SOFTWARE = 1 +DCIOCHIP_GPIO_MASK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK' +DCIOCHIP_MASK__enumvalues = { + 0: 'DCIOCHIP_MASK_DISABLE', + 1: 'DCIOCHIP_MASK_ENABLE', +} +DCIOCHIP_MASK_DISABLE = 0 +DCIOCHIP_MASK_ENABLE = 1 +DCIOCHIP_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_MASK' +DCIOCHIP_GPIO_I2C_MASK__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_MASK_DISABLE', + 1: 'DCIOCHIP_GPIO_I2C_MASK_ENABLE', +} +DCIOCHIP_GPIO_I2C_MASK_DISABLE = 0 +DCIOCHIP_GPIO_I2C_MASK_ENABLE = 1 +DCIOCHIP_GPIO_I2C_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_DRIVE' +DCIOCHIP_GPIO_I2C_DRIVE__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_DRIVE_LOW', + 1: 'DCIOCHIP_GPIO_I2C_DRIVE_HIGH', +} +DCIOCHIP_GPIO_I2C_DRIVE_LOW = 0 +DCIOCHIP_GPIO_I2C_DRIVE_HIGH = 1 +DCIOCHIP_GPIO_I2C_DRIVE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_GPIO_I2C_EN' +DCIOCHIP_GPIO_I2C_EN__enumvalues = { + 0: 'DCIOCHIP_GPIO_I2C_DISABLE', + 1: 'DCIOCHIP_GPIO_I2C_ENABLE', +} +DCIOCHIP_GPIO_I2C_DISABLE = 0 +DCIOCHIP_GPIO_I2C_ENABLE = 1 +DCIOCHIP_GPIO_I2C_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_4BIT' +DCIOCHIP_MASK_4BIT__enumvalues = { + 0: 'DCIOCHIP_MASK_4BIT_DISABLE', + 15: 'DCIOCHIP_MASK_4BIT_ENABLE', +} +DCIOCHIP_MASK_4BIT_DISABLE = 0 +DCIOCHIP_MASK_4BIT_ENABLE = 15 +DCIOCHIP_MASK_4BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_4BIT' +DCIOCHIP_ENABLE_4BIT__enumvalues = { + 0: 'DCIOCHIP_4BIT_DISABLE', + 15: 'DCIOCHIP_4BIT_ENABLE', +} +DCIOCHIP_4BIT_DISABLE = 0 +DCIOCHIP_4BIT_ENABLE = 15 +DCIOCHIP_ENABLE_4BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_5BIT' +DCIOCHIP_MASK_5BIT__enumvalues = { + 0: 'DCIOCHIP_MASIK_5BIT_DISABLE', + 31: 'DCIOCHIP_MASIK_5BIT_ENABLE', +} +DCIOCHIP_MASIK_5BIT_DISABLE = 0 +DCIOCHIP_MASIK_5BIT_ENABLE = 31 +DCIOCHIP_MASK_5BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_5BIT' +DCIOCHIP_ENABLE_5BIT__enumvalues = { + 0: 'DCIOCHIP_5BIT_DISABLE', + 31: 'DCIOCHIP_5BIT_ENABLE', +} +DCIOCHIP_5BIT_DISABLE = 0 +DCIOCHIP_5BIT_ENABLE = 31 +DCIOCHIP_ENABLE_5BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_MASK_2BIT' +DCIOCHIP_MASK_2BIT__enumvalues = { + 0: 'DCIOCHIP_MASK_2BIT_DISABLE', + 3: 'DCIOCHIP_MASK_2BIT_ENABLE', +} +DCIOCHIP_MASK_2BIT_DISABLE = 0 +DCIOCHIP_MASK_2BIT_ENABLE = 3 +DCIOCHIP_MASK_2BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_ENABLE_2BIT' +DCIOCHIP_ENABLE_2BIT__enumvalues = { + 0: 'DCIOCHIP_2BIT_DISABLE', + 3: 'DCIOCHIP_2BIT_ENABLE', +} +DCIOCHIP_2BIT_DISABLE = 0 +DCIOCHIP_2BIT_ENABLE = 3 +DCIOCHIP_ENABLE_2BIT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_REF_27_SRC_SEL' +DCIOCHIP_REF_27_SRC_SEL__enumvalues = { + 0: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', + 1: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 2: 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 3: 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', +} +DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER = 0 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER = 1 +DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS = 2 +DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS = 3 +DCIOCHIP_REF_27_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_DVO_VREFPON' +DCIOCHIP_DVO_VREFPON__enumvalues = { + 0: 'DCIOCHIP_DVO_VREFPON_DISABLE', + 1: 'DCIOCHIP_DVO_VREFPON_ENABLE', +} +DCIOCHIP_DVO_VREFPON_DISABLE = 0 +DCIOCHIP_DVO_VREFPON_ENABLE = 1 +DCIOCHIP_DVO_VREFPON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_DVO_VREFSEL' +DCIOCHIP_DVO_VREFSEL__enumvalues = { + 0: 'DCIOCHIP_DVO_VREFSEL_ONCHIP', + 1: 'DCIOCHIP_DVO_VREFSEL_EXTERNAL', +} +DCIOCHIP_DVO_VREFSEL_ONCHIP = 0 +DCIOCHIP_DVO_VREFSEL_EXTERNAL = 1 +DCIOCHIP_DVO_VREFSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_SPDIF1_IMODE' +DCIOCHIP_SPDIF1_IMODE__enumvalues = { + 0: 'DCIOCHIP_SPDIF1_IMODE_OE_A', + 1: 'DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO', +} +DCIOCHIP_SPDIF1_IMODE_OE_A = 0 +DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO = 1 +DCIOCHIP_SPDIF1_IMODE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_FALLSLEWSEL' +DCIOCHIP_AUX_FALLSLEWSEL__enumvalues = { + 0: 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 1: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 2: 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', + 3: 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', +} +DCIOCHIP_AUX_FALLSLEWSEL_LOW = 0 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH0 = 1 +DCIOCHIP_AUX_FALLSLEWSEL_HIGH1 = 2 +DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH = 3 +DCIOCHIP_AUX_FALLSLEWSEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_SPIKESEL' +DCIOCHIP_AUX_SPIKESEL__enumvalues = { + 0: 'DCIOCHIP_AUX_SPIKESEL_50NS', + 1: 'DCIOCHIP_AUX_SPIKESEL_10NS', +} +DCIOCHIP_AUX_SPIKESEL_50NS = 0 +DCIOCHIP_AUX_SPIKESEL_10NS = 1 +DCIOCHIP_AUX_SPIKESEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL0P9' +DCIOCHIP_AUX_CSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_CSEL_DEC0P9', +} +DCIOCHIP_AUX_CSEL_DEC1P0 = 0 +DCIOCHIP_AUX_CSEL_DEC0P9 = 1 +DCIOCHIP_AUX_CSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_CSEL1P1' +DCIOCHIP_AUX_CSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_CSEL_INC1P0', + 1: 'DCIOCHIP_AUX_CSEL_INC1P1', +} +DCIOCHIP_AUX_CSEL_INC1P0 = 0 +DCIOCHIP_AUX_CSEL_INC1P1 = 1 +DCIOCHIP_AUX_CSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL0P9' +DCIOCHIP_AUX_RSEL0P9__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_DEC1P0', + 1: 'DCIOCHIP_AUX_RSEL_DEC0P9', +} +DCIOCHIP_AUX_RSEL_DEC1P0 = 0 +DCIOCHIP_AUX_RSEL_DEC0P9 = 1 +DCIOCHIP_AUX_RSEL0P9 = ctypes.c_uint32 # enum + +# values for enumeration 'DCIOCHIP_AUX_RSEL1P1' +DCIOCHIP_AUX_RSEL1P1__enumvalues = { + 0: 'DCIOCHIP_AUX_RSEL_INC1P0', + 1: 'DCIOCHIP_AUX_RSEL_INC1P1', +} +DCIOCHIP_AUX_RSEL_INC1P0 = 0 +DCIOCHIP_AUX_RSEL_INC1P1 = 1 +DCIOCHIP_AUX_RSEL1P1 = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED' +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED__enumvalues = { + 0: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 1: 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', +} +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED = 0 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED = 1 +GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_GLOBAL_CAPABILITIES' +AZ_GLOBAL_CAPABILITIES__enumvalues = { + 0: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 1: 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', +} +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED = 0 +AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED = 1 +AZ_GLOBAL_CAPABILITIES = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE' +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE__enumvalues = { + 0: 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', + 1: 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', +} +ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE = 0 +ACCEPT_UNSOLICITED_RESPONSE_ENABLE = 1 +GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_FLUSH_CONTROL' +GLOBAL_CONTROL_FLUSH_CONTROL__enumvalues = { + 0: 'FLUSH_CONTROL_FLUSH_NOT_STARTED', + 1: 'FLUSH_CONTROL_FLUSH_STARTED', +} +FLUSH_CONTROL_FLUSH_NOT_STARTED = 0 +FLUSH_CONTROL_FLUSH_STARTED = 1 +GLOBAL_CONTROL_FLUSH_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_CONTROL_CONTROLLER_RESET' +GLOBAL_CONTROL_CONTROLLER_RESET__enumvalues = { + 0: 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 1: 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', +} +CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET = 0 +CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET = 1 +GLOBAL_CONTROL_CONTROLLER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_STATE_CHANGE_STATUS' +AZ_STATE_CHANGE_STATUS__enumvalues = { + 0: 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 1: 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', +} +AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT = 0 +AZ_STATE_CHANGE_STATUS_CODEC_PRESENT = 1 +AZ_STATE_CHANGE_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'GLOBAL_STATUS_FLUSH_STATUS' +GLOBAL_STATUS_FLUSH_STATUS__enumvalues = { + 0: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 1: 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', +} +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED = 0 +GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED = 1 +GLOBAL_STATUS_FLUSH_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_0_SYNCHRONIZATION' +STREAM_0_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_0_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_0_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_1_SYNCHRONIZATION' +STREAM_1_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_1_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_1_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_2_SYNCHRONIZATION' +STREAM_2_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_2_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_2_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_3_SYNCHRONIZATION' +STREAM_3_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_3_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_3_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_4_SYNCHRONIZATION' +STREAM_4_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_4_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_4_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_5_SYNCHRONIZATION' +STREAM_5_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 1: 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED', +} +STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED = 0 +STREAM_5_SYNCHRONIZATION_STEAM_STOPPED = 1 +STREAM_5_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_6_SYNCHRONIZATION' +STREAM_6_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_6_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_7_SYNCHRONIZATION' +STREAM_7_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_7_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_8_SYNCHRONIZATION' +STREAM_8_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_8_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_9_SYNCHRONIZATION' +STREAM_9_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_9_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_10_SYNCHRONIZATION' +STREAM_10_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_10_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_11_SYNCHRONIZATION' +STREAM_11_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_11_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_12_SYNCHRONIZATION' +STREAM_12_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_12_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_13_SYNCHRONIZATION' +STREAM_13_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_13_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_14_SYNCHRONIZATION' +STREAM_14_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_14_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'STREAM_15_SYNCHRONIZATION' +STREAM_15_SYNCHRONIZATION__enumvalues = { + 0: 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 1: 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', +} +STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED = 0 +STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED = 1 +STREAM_15_SYNCHRONIZATION = ctypes.c_uint32 # enum + +# values for enumeration 'CORB_READ_POINTER_RESET' +CORB_READ_POINTER_RESET__enumvalues = { + 0: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 1: 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', +} +CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET = 0 +CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET = 1 +CORB_READ_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_CORB_SIZE' +AZ_CORB_SIZE__enumvalues = { + 0: 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_CORB_SIZE_256ENTRIES', + 3: 'AZ_CORB_SIZE_RESERVED', +} +AZ_CORB_SIZE_2ENTRIES_RESERVED = 0 +AZ_CORB_SIZE_16ENTRIES_RESERVED = 1 +AZ_CORB_SIZE_256ENTRIES = 2 +AZ_CORB_SIZE_RESERVED = 3 +AZ_CORB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_WRITE_POINTER_RESET' +AZ_RIRB_WRITE_POINTER_RESET__enumvalues = { + 0: 'AZ_RIRB_WRITE_POINTER_NOT_RESET', + 1: 'AZ_RIRB_WRITE_POINTER_DO_RESET', +} +AZ_RIRB_WRITE_POINTER_NOT_RESET = 0 +AZ_RIRB_WRITE_POINTER_DO_RESET = 1 +AZ_RIRB_WRITE_POINTER_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL' +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL__enumvalues = { + 0: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 1: 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', +} +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED = 0 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED = 1 +RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL = ctypes.c_uint32 # enum + +# values for enumeration 'AZ_RIRB_SIZE' +AZ_RIRB_SIZE__enumvalues = { + 0: 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', + 1: 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', + 2: 'AZ_RIRB_SIZE_256ENTRIES', + 3: 'AZ_RIRB_SIZE_UNDEFINED', +} +AZ_RIRB_SIZE_2ENTRIES_RESERVED = 0 +AZ_RIRB_SIZE_16ENTRIES_RESERVED = 1 +AZ_RIRB_SIZE_256ENTRIES = 2 +AZ_RIRB_SIZE_UNDEFINED = 3 +AZ_RIRB_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID = ctypes.c_uint32 # enum + +# values for enumeration 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY' +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY__enumvalues = { + 0: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 1: 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', +} +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY = 0 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY = 1 +IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY = ctypes.c_uint32 # enum + +# values for enumeration 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE' +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE__enumvalues = { + 0: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 1: 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', +} +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE = 0 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE = 1 +DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE' +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE__enumvalues = { + 0: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 1: 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', +} +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE = 0 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE = 1 +AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT' +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', +} +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN = 1 +AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE' +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE__enumvalues = { + 0: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 1: 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', +} +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE = 0 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE = 1 +AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET' +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET__enumvalues = { + 0: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 1: 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', +} +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET = 0 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC = 1 +AZALIA_SOFT_RESET_REFCLK_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY' +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY__enumvalues = { + 0: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 1: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 2: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 3: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 4: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 5: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 6: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 7: 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', +} +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL = 0 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6 = 1 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5 = 2 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4 = 3 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3 = 4 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2 = 5 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1 = 6 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0 = 7 +CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 2: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 3: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 4: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 5: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 6: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 7: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 8: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1 = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2 = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3 = 2 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4 = 3 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5 = 4 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6 = 5 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7 = 6 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8 = 7 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED = 8 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN' +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', +} +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE' +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE__enumvalues = { + 0: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 1: 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', +} +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED = 0 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED = 1 +AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE = ctypes.c_uint32 # enum + +# values for enumeration 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET' +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET__enumvalues = { + 0: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 1: 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', +} +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET = 0 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET = 1 +AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE' +ENABLE__enumvalues = { + 0: 'DISABLE_THE_FEATURE', + 1: 'ENABLE_THE_FEATURE', +} +DISABLE_THE_FEATURE = 0 +ENABLE_THE_FEATURE = 1 +ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'ENABLE_CLOCK' +ENABLE_CLOCK__enumvalues = { + 0: 'DISABLE_THE_CLOCK', + 1: 'ENABLE_THE_CLOCK', +} +DISABLE_THE_CLOCK = 0 +ENABLE_THE_CLOCK = 1 +ENABLE_CLOCK = ctypes.c_uint32 # enum + +# values for enumeration 'FORCE_VBI' +FORCE_VBI__enumvalues = { + 0: 'FORCE_VBI_LOW', + 1: 'FORCE_VBI_HIGH', +} +FORCE_VBI_LOW = 0 +FORCE_VBI_HIGH = 1 +FORCE_VBI = ctypes.c_uint32 # enum + +# values for enumeration 'OVERRIDE_CGTT_SCLK' +OVERRIDE_CGTT_SCLK__enumvalues = { + 0: 'OVERRIDE_CGTT_SCLK_NOOP', + 1: 'SET_OVERRIDE_CGTT_SCLK', +} +OVERRIDE_CGTT_SCLK_NOOP = 0 +SET_OVERRIDE_CGTT_SCLK = 1 +OVERRIDE_CGTT_SCLK = ctypes.c_uint32 # enum + +# values for enumeration 'CLEAR_SMU_INTR' +CLEAR_SMU_INTR__enumvalues = { + 0: 'SMU_INTR_STATUS_NOOP', + 1: 'SMU_INTR_STATUS_CLEAR', +} +SMU_INTR_STATUS_NOOP = 0 +SMU_INTR_STATUS_CLEAR = 1 +CLEAR_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'STATIC_SCREEN_SMU_INTR' +STATIC_SCREEN_SMU_INTR__enumvalues = { + 0: 'STATIC_SCREEN_SMU_INTR_NOOP', + 1: 'SET_STATIC_SCREEN_SMU_INTR', +} +STATIC_SCREEN_SMU_INTR_NOOP = 0 +SET_STATIC_SCREEN_SMU_INTR = 1 +STATIC_SCREEN_SMU_INTR = ctypes.c_uint32 # enum + +# values for enumeration 'JITTER_REMOVE_DISABLE' +JITTER_REMOVE_DISABLE__enumvalues = { + 0: 'ENABLE_JITTER_REMOVAL', + 1: 'DISABLE_JITTER_REMOVAL', +} +ENABLE_JITTER_REMOVAL = 0 +DISABLE_JITTER_REMOVAL = 1 +JITTER_REMOVE_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DS_REF_SRC' +DS_REF_SRC__enumvalues = { + 0: 'DS_REF_IS_XTALIN', + 1: 'DS_REF_IS_EXT_GENLOCK', + 2: 'DS_REF_IS_PCIE', +} +DS_REF_IS_XTALIN = 0 +DS_REF_IS_EXT_GENLOCK = 1 +DS_REF_IS_PCIE = 2 +DS_REF_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING' +DISABLE_CLOCK_GATING__enumvalues = { + 0: 'CLOCK_GATING_ENABLED', + 1: 'CLOCK_GATING_DISABLED', +} +CLOCK_GATING_ENABLED = 0 +CLOCK_GATING_DISABLED = 1 +DISABLE_CLOCK_GATING = ctypes.c_uint32 # enum + +# values for enumeration 'DISABLE_CLOCK_GATING_IN_DCO' +DISABLE_CLOCK_GATING_IN_DCO__enumvalues = { + 0: 'CLOCK_GATING_ENABLED_IN_DCO', + 1: 'CLOCK_GATING_DISABLED_IN_DCO', +} +CLOCK_GATING_ENABLED_IN_DCO = 0 +CLOCK_GATING_DISABLED_IN_DCO = 1 +DISABLE_CLOCK_GATING_IN_DCO = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DEEP_COLOR_CNTL' +DCCG_DEEP_COLOR_CNTL__enumvalues = { + 0: 'DCCG_DEEP_COLOR_DTO_DISABLE', + 1: 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', + 2: 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 3: 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', +} +DCCG_DEEP_COLOR_DTO_DISABLE = 0 +DCCG_DEEP_COLOR_DTO_5_4_RATIO = 1 +DCCG_DEEP_COLOR_DTO_3_2_RATIO = 2 +DCCG_DEEP_COLOR_DTO_2_1_RATIO = 3 +DCCG_DEEP_COLOR_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'REFCLK_CLOCK_EN' +REFCLK_CLOCK_EN__enumvalues = { + 0: 'REFCLK_CLOCK_EN_XTALIN_CLK', + 1: 'REFCLK_CLOCK_EN_ALLOW_SRC_SEL', +} +REFCLK_CLOCK_EN_XTALIN_CLK = 0 +REFCLK_CLOCK_EN_ALLOW_SRC_SEL = 1 +REFCLK_CLOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'REFCLK_SRC_SEL' +REFCLK_SRC_SEL__enumvalues = { + 0: 'REFCLK_SRC_SEL_PCIE_REFCLK', + 1: 'REFCLK_SRC_SEL_CPL_REFCLK', +} +REFCLK_SRC_SEL_PCIE_REFCLK = 0 +REFCLK_SRC_SEL_CPL_REFCLK = 1 +REFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPREFCLK_SRC_SEL' +DPREFCLK_SRC_SEL__enumvalues = { + 0: 'DPREFCLK_SRC_SEL_CK', + 1: 'DPREFCLK_SRC_SEL_P0PLL', + 2: 'DPREFCLK_SRC_SEL_P1PLL', + 3: 'DPREFCLK_SRC_SEL_P2PLL', + 4: 'DPREFCLK_SRC_SEL_P3PLL', +} +DPREFCLK_SRC_SEL_CK = 0 +DPREFCLK_SRC_SEL_P0PLL = 1 +DPREFCLK_SRC_SEL_P1PLL = 2 +DPREFCLK_SRC_SEL_P2PLL = 3 +DPREFCLK_SRC_SEL_P3PLL = 4 +DPREFCLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_SEL' +XTAL_REF_SEL__enumvalues = { + 0: 'XTAL_REF_SEL_1X', + 1: 'XTAL_REF_SEL_2X', +} +XTAL_REF_SEL_1X = 0 +XTAL_REF_SEL_2X = 1 +XTAL_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'XTAL_REF_CLOCK_SOURCE_SEL' +XTAL_REF_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', + 1: 'XTAL_REF_CLOCK_SOURCE_SEL_PPLL', +} +XTAL_REF_CLOCK_SOURCE_SEL_XTALIN = 0 +XTAL_REF_CLOCK_SOURCE_SEL_PPLL = 1 +XTAL_REF_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MICROSECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK', +} +MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MICROSECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK = 1 +MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ALLOW_SR_ON_TRANS_REQ' +ALLOW_SR_ON_TRANS_REQ__enumvalues = { + 0: 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 1: 'ALLOW_SR_ON_TRANS_REQ_DISABLE', +} +ALLOW_SR_ON_TRANS_REQ_ENABLE = 0 +ALLOW_SR_ON_TRANS_REQ_DISABLE = 1 +ALLOW_SR_ON_TRANS_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL' +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL__enumvalues = { + 0: 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 1: 'MILLISECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK', +} +MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN = 0 +MILLISECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK = 1 +MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_SOURCE' +PIPE_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_SOURCE_P0PLL', + 1: 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 2: 'PIPE_PIXEL_RATE_SOURCE_P2PLL', +} +PIPE_PIXEL_RATE_SOURCE_P0PLL = 0 +PIPE_PIXEL_RATE_SOURCE_P1PLL = 1 +PIPE_PIXEL_RATE_SOURCE_P2PLL = 2 +PIPE_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PHYPLL_PIXEL_RATE_SOURCE' +PIPE_PHYPLL_PIXEL_RATE_SOURCE__enumvalues = { + 0: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 1: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 2: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 3: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 4: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE', + 5: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF', + 6: 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYG', +} +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA = 0 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB = 1 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC = 2 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD = 3 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE = 4 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF = 5 +PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYG = 6 +PIPE_PHYPLL_PIXEL_RATE_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'PIPE_PIXEL_RATE_PLL_SOURCE' +PIPE_PIXEL_RATE_PLL_SOURCE__enumvalues = { + 0: 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', + 1: 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', +} +PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL = 0 +PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL = 1 +PIPE_PIXEL_RATE_PLL_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DP_DTO_DS_DISABLE' +DP_DTO_DS_DISABLE__enumvalues = { + 0: 'DP_DTO_DESPREAD_DISABLE', + 1: 'DP_DTO_DESPREAD_ENABLE', +} +DP_DTO_DESPREAD_DISABLE = 0 +DP_DTO_DESPREAD_ENABLE = 1 +DP_DTO_DS_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_ADD_PIXEL' +CRTC_ADD_PIXEL__enumvalues = { + 0: 'CRTC_ADD_PIXEL_NOOP', + 1: 'CRTC_ADD_PIXEL_FORCE', +} +CRTC_ADD_PIXEL_NOOP = 0 +CRTC_ADD_PIXEL_FORCE = 1 +CRTC_ADD_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'CRTC_DROP_PIXEL' +CRTC_DROP_PIXEL__enumvalues = { + 0: 'CRTC_DROP_PIXEL_NOOP', + 1: 'CRTC_DROP_PIXEL_FORCE', +} +CRTC_DROP_PIXEL_NOOP = 0 +CRTC_DROP_PIXEL_FORCE = 1 +CRTC_DROP_PIXEL = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_EN' +SYMCLK_FE_FORCE_EN__enumvalues = { + 0: 'SYMCLK_FE_FORCE_EN_DISABLE', + 1: 'SYMCLK_FE_FORCE_EN_ENABLE', +} +SYMCLK_FE_FORCE_EN_DISABLE = 0 +SYMCLK_FE_FORCE_EN_ENABLE = 1 +SYMCLK_FE_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'SYMCLK_FE_FORCE_SRC' +SYMCLK_FE_FORCE_SRC__enumvalues = { + 0: 'SYMCLK_FE_FORCE_SRC_UNIPHYA', + 1: 'SYMCLK_FE_FORCE_SRC_UNIPHYB', + 2: 'SYMCLK_FE_FORCE_SRC_UNIPHYC', + 3: 'SYMCLK_FE_FORCE_SRC_UNIPHYD', + 4: 'SYMCLK_FE_FORCE_SRC_UNIPHYE', + 5: 'SYMCLK_FE_FORCE_SRC_UNIPHYF', + 6: 'SYMCLK_FE_FORCE_SRC_UNIPHYG', +} +SYMCLK_FE_FORCE_SRC_UNIPHYA = 0 +SYMCLK_FE_FORCE_SRC_UNIPHYB = 1 +SYMCLK_FE_FORCE_SRC_UNIPHYC = 2 +SYMCLK_FE_FORCE_SRC_UNIPHYD = 3 +SYMCLK_FE_FORCE_SRC_UNIPHYE = 4 +SYMCLK_FE_FORCE_SRC_UNIPHYF = 5 +SYMCLK_FE_FORCE_SRC_UNIPHYG = 6 +SYMCLK_FE_FORCE_SRC = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_CLK_FORCE_EN' +DPDBG_CLK_FORCE_EN__enumvalues = { + 0: 'DPDBG_CLK_FORCE_EN_DISABLE', + 1: 'DPDBG_CLK_FORCE_EN_ENABLE', +} +DPDBG_CLK_FORCE_EN_DISABLE = 0 +DPDBG_CLK_FORCE_EN_ENABLE = 1 +DPDBG_CLK_FORCE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_COARSE_SKEW_CNTL' +DVOACLK_COARSE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 5: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 6: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 7: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 8: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 9: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 10: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 11: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 12: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 13: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 14: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 15: 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 16: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 17: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 18: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 19: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 20: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 21: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 22: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 23: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 24: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 25: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 26: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 27: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 28: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 29: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 30: 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', +} +DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS = 4 +DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS = 5 +DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS = 6 +DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS = 7 +DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS = 8 +DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS = 9 +DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS = 10 +DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS = 11 +DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS = 12 +DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS = 13 +DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS = 14 +DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS = 15 +DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP = 16 +DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS = 17 +DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS = 18 +DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS = 19 +DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS = 20 +DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS = 21 +DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS = 22 +DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS = 23 +DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS = 24 +DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS = 25 +DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS = 26 +DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS = 27 +DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS = 28 +DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS = 29 +DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS = 30 +DVOACLK_COARSE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLK_FINE_SKEW_CNTL' +DVOACLK_FINE_SKEW_CNTL__enumvalues = { + 0: 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', + 1: 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 2: 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 3: 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 4: 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 5: 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 6: 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 7: 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', +} +DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT = 0 +DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP = 1 +DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS = 2 +DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS = 3 +DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP = 4 +DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS = 5 +DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS = 6 +DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS = 7 +DVOACLK_FINE_SKEW_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKD_IN_PHASE' +DVOACLKD_IN_PHASE__enumvalues = { + 0: 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKD_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKD_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_IN_PHASE' +DVOACLKC_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_IN_PHASE' +DVOACLKC_MVP_IN_PHASE__enumvalues = { + 0: 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 1: 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', +} +DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO = 0 +DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO = 1 +DVOACLKC_MVP_IN_PHASE = ctypes.c_uint32 # enum + +# values for enumeration 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE' +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE__enumvalues = { + 0: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 1: 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', +} +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE = 0 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE = 1 +DVOACLKC_MVP_SKEW_PHASE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'MVP_CLK_SRC_SEL' +MVP_CLK_SRC_SEL__enumvalues = { + 0: 'MVP_CLK_SRC_SEL_RSRV', + 1: 'MVP_CLK_SRC_SEL_IO_1', + 2: 'MVP_CLK_SRC_SEL_IO_2', + 3: 'MVP_CLK_SRC_SEL_REFCLK', +} +MVP_CLK_SRC_SEL_RSRV = 0 +MVP_CLK_SRC_SEL_IO_1 = 1 +MVP_CLK_SRC_SEL_IO_2 = 2 +MVP_CLK_SRC_SEL_REFCLK = 3 +MVP_CLK_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO0_SOURCE_SEL' +DCCG_AUDIO_DTO0_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC0', + 1: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC1', + 2: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC2', + 3: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC3', + 4: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC4', + 5: 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC5', + 6: 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', +} +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC0 = 0 +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC1 = 1 +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC2 = 2 +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC3 = 3 +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC4 = 4 +DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC5 = 5 +DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED = 6 +DCCG_AUDIO_DTO0_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_SEL' +DCCG_AUDIO_DTO_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', + 1: 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 2: 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', +} +DCCG_AUDIO_DTO_SEL_AUDIO_DTO0 = 0 +DCCG_AUDIO_DTO_SEL_AUDIO_DTO1 = 1 +DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO = 2 +DCCG_AUDIO_DTO_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO2_SOURCE_SEL' +DCCG_AUDIO_DTO2_SOURCE_SEL__enumvalues = { + 0: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 1: 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1', +} +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0 = 0 +DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1 = 1 +DCCG_AUDIO_DTO2_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_AUDIO_DTO_USE_512FBR_DTO' +DCCG_AUDIO_DTO_USE_512FBR_DTO__enumvalues = { + 0: 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 1: 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', +} +DCCG_AUDIO_DTO_USE_128FBR_FOR_DP = 0 +DCCG_AUDIO_DTO_USE_512FBR_FOR_DP = 1 +DCCG_AUDIO_DTO_USE_512FBR_DTO = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_EN' +DCCG_DBG_EN__enumvalues = { + 0: 'DCCG_DBG_EN_DISABLE', + 1: 'DCCG_DBG_EN_ENABLE', +} +DCCG_DBG_EN_DISABLE = 0 +DCCG_DBG_EN_ENABLE = 1 +DCCG_DBG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_DBG_BLOCK_SEL' +DCCG_DBG_BLOCK_SEL__enumvalues = { + 0: 'DCCG_DBG_BLOCK_SEL_DCCG', + 1: 'DCCG_DBG_BLOCK_SEL_PMON', + 2: 'DCCG_DBG_BLOCK_SEL_PMON2', +} +DCCG_DBG_BLOCK_SEL_DCCG = 0 +DCCG_DBG_BLOCK_SEL_PMON = 1 +DCCG_DBG_BLOCK_SEL_PMON2 = 2 +DCCG_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_FREQ_RAMP_DONE' +DISPCLK_FREQ_RAMP_DONE__enumvalues = { + 0: 'DISPCLK_FREQ_RAMP_IN_PROGRESS', + 1: 'DISPCLK_FREQ_RAMP_COMPLETED', +} +DISPCLK_FREQ_RAMP_IN_PROGRESS = 0 +DISPCLK_FREQ_RAMP_COMPLETED = 1 +DISPCLK_FREQ_RAMP_DONE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_RESET' +DCCG_FIFO_ERRDET_RESET__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_RESET_NOOP', + 1: 'DCCG_FIFO_ERRDET_RESET_FORCE', +} +DCCG_FIFO_ERRDET_RESET_NOOP = 0 +DCCG_FIFO_ERRDET_RESET_FORCE = 1 +DCCG_FIFO_ERRDET_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_STATE' +DCCG_FIFO_ERRDET_STATE__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_STATE_DETECTION', + 1: 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', +} +DCCG_FIFO_ERRDET_STATE_DETECTION = 0 +DCCG_FIFO_ERRDET_STATE_CALIBRATION = 1 +DCCG_FIFO_ERRDET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_FIFO_ERRDET_OVR_EN' +DCCG_FIFO_ERRDET_OVR_EN__enumvalues = { + 0: 'DCCG_FIFO_ERRDET_OVR_DISABLE', + 1: 'DCCG_FIFO_ERRDET_OVR_ENABLE', +} +DCCG_FIFO_ERRDET_OVR_DISABLE = 0 +DCCG_FIFO_ERRDET_OVR_ENABLE = 1 +DCCG_FIFO_ERRDET_OVR_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DISPCLK_CHG_FWD_CORR_DISABLE' +DISPCLK_CHG_FWD_CORR_DISABLE__enumvalues = { + 0: 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 1: 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', +} +DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING = 0 +DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING = 1 +DISPCLK_CHG_FWD_CORR_DISABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DC_MEM_GLOBAL_PWR_REQ_DIS' +DC_MEM_GLOBAL_PWR_REQ_DIS__enumvalues = { + 0: 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 1: 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', +} +DC_MEM_GLOBAL_PWR_REQ_ENABLE = 0 +DC_MEM_GLOBAL_PWR_REQ_DISABLE = 1 +DC_MEM_GLOBAL_PWR_REQ_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_RUN' +DCCG_PERF_RUN__enumvalues = { + 0: 'DCCG_PERF_RUN_NOOP', + 1: 'DCCG_PERF_RUN_START', +} +DCCG_PERF_RUN_NOOP = 0 +DCCG_PERF_RUN_START = 1 +DCCG_PERF_RUN = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_VSYNC' +DCCG_PERF_MODE_VSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_VSYNC_NOOP', + 1: 'DCCG_PERF_MODE_VSYNC_START', +} +DCCG_PERF_MODE_VSYNC_NOOP = 0 +DCCG_PERF_MODE_VSYNC_START = 1 +DCCG_PERF_MODE_VSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_MODE_HSYNC' +DCCG_PERF_MODE_HSYNC__enumvalues = { + 0: 'DCCG_PERF_MODE_HSYNC_NOOP', + 1: 'DCCG_PERF_MODE_HSYNC_START', +} +DCCG_PERF_MODE_HSYNC_NOOP = 0 +DCCG_PERF_MODE_HSYNC_START = 1 +DCCG_PERF_MODE_HSYNC = ctypes.c_uint32 # enum + +# values for enumeration 'DCCG_PERF_CRTC_SELECT' +DCCG_PERF_CRTC_SELECT__enumvalues = { + 0: 'DCCG_PERF_SEL_CRTC0', + 1: 'DCCG_PERF_SEL_CRTC1', + 2: 'DCCG_PERF_SEL_CRTC2', + 3: 'DCCG_PERF_SEL_CRTC3', + 4: 'DCCG_PERF_SEL_CRTC4', + 5: 'DCCG_PERF_SEL_CRTC5', +} +DCCG_PERF_SEL_CRTC0 = 0 +DCCG_PERF_SEL_CRTC1 = 1 +DCCG_PERF_SEL_CRTC2 = 2 +DCCG_PERF_SEL_CRTC3 = 3 +DCCG_PERF_SEL_CRTC4 = 4 +DCCG_PERF_SEL_CRTC5 = 5 +DCCG_PERF_CRTC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'CLOCK_BRANCH_SOFT_RESET' +CLOCK_BRANCH_SOFT_RESET__enumvalues = { + 0: 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 1: 'CLOCK_BRANCH_SOFT_RESET_FORCE', +} +CLOCK_BRANCH_SOFT_RESET_NOOP = 0 +CLOCK_BRANCH_SOFT_RESET_FORCE = 1 +CLOCK_BRANCH_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'PLL_CFG_IF_SOFT_RESET' +PLL_CFG_IF_SOFT_RESET__enumvalues = { + 0: 'PLL_CFG_IF_SOFT_RESET_NOOP', + 1: 'PLL_CFG_IF_SOFT_RESET_FORCE', +} +PLL_CFG_IF_SOFT_RESET_NOOP = 0 +PLL_CFG_IF_SOFT_RESET_FORCE = 1 +PLL_CFG_IF_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DVO_ENABLE_RST' +DVO_ENABLE_RST__enumvalues = { + 0: 'DVO_ENABLE_RST_DISABLE', + 1: 'DVO_ENABLE_RST_ENABLE', +} +DVO_ENABLE_RST_DISABLE = 0 +DVO_ENABLE_RST_ENABLE = 1 +DVO_ENABLE_RST = ctypes.c_uint32 # enum + +# values for enumeration 'LptNumPipes' +LptNumPipes__enumvalues = { + 0: 'LPT_NUM_PIPES_1CH', + 1: 'LPT_NUM_PIPES_2CH', + 2: 'LPT_NUM_PIPES_4CH', + 3: 'LPT_NUM_PIPES_8CH', +} +LPT_NUM_PIPES_1CH = 0 +LPT_NUM_PIPES_2CH = 1 +LPT_NUM_PIPES_4CH = 2 +LPT_NUM_PIPES_8CH = 3 +LptNumPipes = ctypes.c_uint32 # enum + +# values for enumeration 'LptNumBanks' +LptNumBanks__enumvalues = { + 0: 'LPT_NUM_BANKS_2BANK', + 1: 'LPT_NUM_BANKS_4BANK', + 2: 'LPT_NUM_BANKS_8BANK', + 3: 'LPT_NUM_BANKS_16BANK', + 4: 'LPT_NUM_BANKS_32BANK', +} +LPT_NUM_BANKS_2BANK = 0 +LPT_NUM_BANKS_4BANK = 1 +LPT_NUM_BANKS_8BANK = 2 +LPT_NUM_BANKS_16BANK = 3 +LPT_NUM_BANKS_32BANK = 4 +LptNumBanks = ctypes.c_uint32 # enum + +# values for enumeration 'OVERRIDE_CGTT_DCEFCLK' +OVERRIDE_CGTT_DCEFCLK__enumvalues = { + 0: 'OVERRIDE_CGTT_DCEFCLK_NOOP', + 1: 'SET_OVERRIDE_CGTT_DCEFCLK', +} +OVERRIDE_CGTT_DCEFCLK_NOOP = 0 +SET_OVERRIDE_CGTT_DCEFCLK = 1 +OVERRIDE_CGTT_DCEFCLK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICA_SEL' +DCIO_DC_GENERICA_SEL__enumvalues = { + 0: 'DCIO_GENERICA_SEL_DACA_STEREOSYNC', + 1: 'DCIO_GENERICA_SEL_STEREOSYNC', + 2: 'DCIO_GENERICA_SEL_DACA_PIXCLK', + 3: 'DCIO_GENERICA_SEL_DACB_PIXCLK', + 4: 'DCIO_GENERICA_SEL_DVOA_CTL3', + 5: 'DCIO_GENERICA_SEL_P1_PLLCLK', + 6: 'DCIO_GENERICA_SEL_P2_PLLCLK', + 7: 'DCIO_GENERICA_SEL_DVOA_STEREOSYNC', + 8: 'DCIO_GENERICA_SEL_DACA_FIELD_NUMBER', + 9: 'DCIO_GENERICA_SEL_DACB_FIELD_NUMBER', + 10: 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 11: 'DCIO_GENERICA_SEL_SYNCEN', + 12: 'DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK', + 13: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK', + 14: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK', + 15: 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2', + 16: 'DCIO_GENERICA_SEL_GENERICA_DPRX', + 17: 'DCIO_GENERICA_SEL_GENERICB_DPRX', +} +DCIO_GENERICA_SEL_DACA_STEREOSYNC = 0 +DCIO_GENERICA_SEL_STEREOSYNC = 1 +DCIO_GENERICA_SEL_DACA_PIXCLK = 2 +DCIO_GENERICA_SEL_DACB_PIXCLK = 3 +DCIO_GENERICA_SEL_DVOA_CTL3 = 4 +DCIO_GENERICA_SEL_P1_PLLCLK = 5 +DCIO_GENERICA_SEL_P2_PLLCLK = 6 +DCIO_GENERICA_SEL_DVOA_STEREOSYNC = 7 +DCIO_GENERICA_SEL_DACA_FIELD_NUMBER = 8 +DCIO_GENERICA_SEL_DACB_FIELD_NUMBER = 9 +DCIO_GENERICA_SEL_GENERICA_DCCG = 10 +DCIO_GENERICA_SEL_SYNCEN = 11 +DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK = 12 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK = 13 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK = 14 +DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2 = 15 +DCIO_GENERICA_SEL_GENERICA_DPRX = 16 +DCIO_GENERICA_SEL_GENERICB_DPRX = 17 +DCIO_DC_GENERICA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_REFDIV_CLK', + 1: 'DCIO_UNIPHYB_TEST_REFDIV_CLK', + 2: 'DCIO_UNIPHYC_TEST_REFDIV_CLK', + 3: 'DCIO_UNIPHYD_TEST_REFDIV_CLK', + 4: 'DCIO_UNIPHYE_TEST_REFDIV_CLK', + 5: 'DCIO_UNIPHYF_TEST_REFDIV_CLK', + 6: 'DCIO_UNIPHYG_TEST_REFDIV_CLK', + 7: 'DCIO_UNIPHYLPA_TEST_REFDIV_CLK', + 8: 'DCIO_UNIPHYLPB_TEST_REFDIV_CLK', +} +DCIO_UNIPHYA_TEST_REFDIV_CLK = 0 +DCIO_UNIPHYB_TEST_REFDIV_CLK = 1 +DCIO_UNIPHYC_TEST_REFDIV_CLK = 2 +DCIO_UNIPHYD_TEST_REFDIV_CLK = 3 +DCIO_UNIPHYE_TEST_REFDIV_CLK = 4 +DCIO_UNIPHYF_TEST_REFDIV_CLK = 5 +DCIO_UNIPHYG_TEST_REFDIV_CLK = 6 +DCIO_UNIPHYLPA_TEST_REFDIV_CLK = 7 +DCIO_UNIPHYLPB_TEST_REFDIV_CLK = 8 +DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_CLK', + 7: 'DCIO_UNIPHYLPA_FBDIV_CLK', + 8: 'DCIO_UNIPHYLPB_FBDIV_CLK', +} +DCIO_UNIPHYA_FBDIV_CLK = 0 +DCIO_UNIPHYB_FBDIV_CLK = 1 +DCIO_UNIPHYC_FBDIV_CLK = 2 +DCIO_UNIPHYD_FBDIV_CLK = 3 +DCIO_UNIPHYE_FBDIV_CLK = 4 +DCIO_UNIPHYF_FBDIV_CLK = 5 +DCIO_UNIPHYG_FBDIV_CLK = 6 +DCIO_UNIPHYLPA_FBDIV_CLK = 7 +DCIO_UNIPHYLPB_FBDIV_CLK = 8 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 1: 'DCIO_UNIPHYB_FBDIV_SSC_CLK', + 2: 'DCIO_UNIPHYC_FBDIV_SSC_CLK', + 3: 'DCIO_UNIPHYD_FBDIV_SSC_CLK', + 4: 'DCIO_UNIPHYE_FBDIV_SSC_CLK', + 5: 'DCIO_UNIPHYF_FBDIV_SSC_CLK', + 6: 'DCIO_UNIPHYG_FBDIV_SSC_CLK', + 7: 'DCIO_UNIPHYLPA_FBDIV_SSC_CLK', + 8: 'DCIO_UNIPHYLPB_FBDIV_SSC_CLK', +} +DCIO_UNIPHYA_FBDIV_SSC_CLK = 0 +DCIO_UNIPHYB_FBDIV_SSC_CLK = 1 +DCIO_UNIPHYC_FBDIV_SSC_CLK = 2 +DCIO_UNIPHYD_FBDIV_SSC_CLK = 3 +DCIO_UNIPHYE_FBDIV_SSC_CLK = 4 +DCIO_UNIPHYF_FBDIV_SSC_CLK = 5 +DCIO_UNIPHYG_FBDIV_SSC_CLK = 6 +DCIO_UNIPHYLPA_FBDIV_SSC_CLK = 7 +DCIO_UNIPHYLPB_FBDIV_SSC_CLK = 8 +DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL' +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL__enumvalues = { + 0: 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 1: 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 2: 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 3: 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 4: 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 5: 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 6: 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', + 7: 'DCIO_UNIPHYLPA_TEST_FBDIV_CLK_DIV2', + 8: 'DCIO_UNIPHYLPB_TEST_FBDIV_CLK_DIV2', +} +DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2 = 0 +DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2 = 1 +DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2 = 2 +DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2 = 3 +DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2 = 4 +DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2 = 5 +DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2 = 6 +DCIO_UNIPHYLPA_TEST_FBDIV_CLK_DIV2 = 7 +DCIO_UNIPHYLPB_TEST_FBDIV_CLK_DIV2 = 8 +DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GENERICB_SEL' +DCIO_DC_GENERICB_SEL__enumvalues = { + 0: 'DCIO_GENERICB_SEL_DACA_STEREOSYNC', + 1: 'DCIO_GENERICB_SEL_STEREOSYNC', + 2: 'DCIO_GENERICB_SEL_DACA_PIXCLK', + 3: 'DCIO_GENERICB_SEL_DACB_PIXCLK', + 4: 'DCIO_GENERICB_SEL_DVOA_CTL3', + 5: 'DCIO_GENERICB_SEL_P1_PLLCLK', + 6: 'DCIO_GENERICB_SEL_P2_PLLCLK', + 7: 'DCIO_GENERICB_SEL_DVOA_STEREOSYNC', + 8: 'DCIO_GENERICB_SEL_DACA_FIELD_NUMBER', + 9: 'DCIO_GENERICB_SEL_DACB_FIELD_NUMBER', + 10: 'DCIO_GENERICB_SEL_GENERICB_DCCG', + 11: 'DCIO_GENERICB_SEL_SYNCEN', + 12: 'DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK', + 13: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK', + 14: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK', + 15: 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2', +} +DCIO_GENERICB_SEL_DACA_STEREOSYNC = 0 +DCIO_GENERICB_SEL_STEREOSYNC = 1 +DCIO_GENERICB_SEL_DACA_PIXCLK = 2 +DCIO_GENERICB_SEL_DACB_PIXCLK = 3 +DCIO_GENERICB_SEL_DVOA_CTL3 = 4 +DCIO_GENERICB_SEL_P1_PLLCLK = 5 +DCIO_GENERICB_SEL_P2_PLLCLK = 6 +DCIO_GENERICB_SEL_DVOA_STEREOSYNC = 7 +DCIO_GENERICB_SEL_DACA_FIELD_NUMBER = 8 +DCIO_GENERICB_SEL_DACB_FIELD_NUMBER = 9 +DCIO_GENERICB_SEL_GENERICB_DCCG = 10 +DCIO_GENERICB_SEL_SYNCEN = 11 +DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK = 12 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK = 13 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK = 14 +DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2 = 15 +DCIO_DC_GENERICB_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_PAD_EXTERN_SIG_SEL' +DCIO_DC_PAD_EXTERN_SIG_SEL__enumvalues = { + 0: 'DCIO_DC_PAD_EXTERN_SIG_SEL_MVP', + 1: 'DCIO_DC_PAD_EXTERN_SIG_SEL_VSYNCA', + 2: 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_CLK', + 3: 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_VSYNC', + 4: 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICA', + 5: 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICB', + 6: 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICC', + 7: 'DCIO_DC_PAD_EXTERN_SIG_SEL_HPD1', + 8: 'DCIO_DC_PAD_EXTERN_SIG_SEL_HPD2', + 9: 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1CLK', + 10: 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1DATA', + 11: 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2CLK', + 12: 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2DATA', + 13: 'DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD1', + 14: 'DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD0', + 15: 'DCIO_DC_PAD_EXTERN_SIG_SEL_VPHCTL', +} +DCIO_DC_PAD_EXTERN_SIG_SEL_MVP = 0 +DCIO_DC_PAD_EXTERN_SIG_SEL_VSYNCA = 1 +DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_CLK = 2 +DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_VSYNC = 3 +DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICA = 4 +DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICB = 5 +DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICC = 6 +DCIO_DC_PAD_EXTERN_SIG_SEL_HPD1 = 7 +DCIO_DC_PAD_EXTERN_SIG_SEL_HPD2 = 8 +DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1CLK = 9 +DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1DATA = 10 +DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2CLK = 11 +DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2DATA = 12 +DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD1 = 13 +DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD0 = 14 +DCIO_DC_PAD_EXTERN_SIG_SEL_VPHCTL = 15 +DCIO_DC_PAD_EXTERN_SIG_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_PAD_EXTERN_SIG_MVP_PIXEL_SRC_STATUS' +DCIO_DC_PAD_EXTERN_SIG_MVP_PIXEL_SRC_STATUS__enumvalues = { + 0: 'DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA', + 1: 'DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA_DUPLICATE', + 2: 'DCIO_MVP_PIXEL_SRC_STATUS_CRTC', + 3: 'DCIO_MVP_PIXEL_SRC_STATUS_LB', +} +DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA = 0 +DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA_DUPLICATE = 1 +DCIO_MVP_PIXEL_SRC_STATUS_CRTC = 2 +DCIO_MVP_PIXEL_SRC_STATUS_LB = 3 +DCIO_DC_PAD_EXTERN_SIG_MVP_PIXEL_SRC_STATUS = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', + 1: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', + 2: 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', + 3: 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', +} +DCIO_HSYNCA_OUTPUT_SEL_DISABLE = 0 +DCIO_HSYNCA_OUTPUT_SEL_PPLL1 = 1 +DCIO_HSYNCA_OUTPUT_SEL_PPLL2 = 2 +DCIO_HSYNCA_OUTPUT_SEL_RESERVED = 3 +DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL' +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL__enumvalues = { + 0: 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 1: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 2: 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 3: 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', +} +DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE = 0 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1 = 1 +DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2 = 2 +DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3 = 3 +DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_VIP_DEBUG' +DCIO_DC_GPIO_VIP_DEBUG__enumvalues = { + 0: 'DCIO_DC_GPIO_VIP_DEBUG_NORMAL', + 1: 'DCIO_DC_GPIO_VIP_DEBUG_CG_BIG', +} +DCIO_DC_GPIO_VIP_DEBUG_NORMAL = 0 +DCIO_DC_GPIO_VIP_DEBUG_CG_BIG = 1 +DCIO_DC_GPIO_VIP_DEBUG = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_MACRO_DEBUG' +DCIO_DC_GPIO_MACRO_DEBUG__enumvalues = { + 0: 'DCIO_DC_GPIO_MACRO_DEBUG_NORMAL', + 1: 'DCIO_DC_GPIO_MACRO_DEBUG_CHIP_BIF', + 2: 'DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE2', + 3: 'DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE3', +} +DCIO_DC_GPIO_MACRO_DEBUG_NORMAL = 0 +DCIO_DC_GPIO_MACRO_DEBUG_CHIP_BIF = 1 +DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE2 = 2 +DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE3 = 3 +DCIO_DC_GPIO_MACRO_DEBUG = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL' +DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL__enumvalues = { + 0: 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_NORMAL', + 1: 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_SWAP', +} +DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_NORMAL = 0 +DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_SWAP = 1 +DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN' +DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN__enumvalues = { + 0: 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_BYPASS', + 1: 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_ENABLE', +} +DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_BYPASS = 0 +DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_ENABLE = 1 +DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE' +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE__enumvalues = { + 0: 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', + 1: 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', +} +DCIO_DPRX_LOOPBACK_ENABLE_NORMAL = 0 +DCIO_DPRX_LOOPBACK_ENABLE_LOOP = 1 +DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION' +DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION__enumvalues = { + 0: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS', + 1: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS', + 2: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS', + 3: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS', + 4: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS', + 5: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS', + 6: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS', + 7: 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS', +} +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS = 0 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS = 1 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS = 2 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS = 3 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS = 4 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS = 5 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS = 6 +DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS = 7 +DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT' +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 1: 'DCIO_UNIPHY_CHANNEL_INVERTED', +} +DCIO_UNIPHY_CHANNEL_NO_INVERSION = 0 +DCIO_UNIPHY_CHANNEL_INVERTED = 1 +DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK' +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK__enumvalues = { + 0: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 1: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 2: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 3: 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', +} +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW = 0 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW = 1 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED = 2 +DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED = 3 +DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE' +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE__enumvalues = { + 0: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 1: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 2: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 3: 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', +} +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0 = 0 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1 = 1 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2 = 2 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3 = 3 +DCIO_UNIPHY_CHANNEL_XBAR_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN' +DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN__enumvalues = { + 0: 'DCIO_VIP_MUX_EN_DVO', + 1: 'DCIO_VIP_MUX_EN_VIP', +} +DCIO_VIP_MUX_EN_DVO = 0 +DCIO_VIP_MUX_EN_VIP = 1 +DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN' +DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN__enumvalues = { + 0: 'DCIO_VIP_ALTER_MAPPING_EN_DEFAULT', + 1: 'DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE', +} +DCIO_VIP_ALTER_MAPPING_EN_DEFAULT = 0 +DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE = 1 +DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN' +DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN__enumvalues = { + 0: 'DCIO_DVO_ALTER_MAPPING_EN_DEFAULT', + 1: 'DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE', +} +DCIO_DVO_ALTER_MAPPING_EN_DEFAULT = 0 +DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE = 1 +DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN' +DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN__enumvalues = { + 0: 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE', + 1: 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE', +} +DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE = 0 +DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE = 1 +DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE' +DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE__enumvalues = { + 0: 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF', + 1: 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON', +} +DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF = 0 +DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL__enumvalues = { + 0: 'DCIO_LVTMA_SYNCEN_POL_NON_INVERT', + 1: 'DCIO_LVTMA_SYNCEN_POL_INVERT', +} +DCIO_LVTMA_SYNCEN_POL_NON_INVERT = 0 +DCIO_LVTMA_SYNCEN_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON__enumvalues = { + 0: 'DCIO_LVTMA_DIGON_OFF', + 1: 'DCIO_LVTMA_DIGON_ON', +} +DCIO_LVTMA_DIGON_OFF = 0 +DCIO_LVTMA_DIGON_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL__enumvalues = { + 0: 'DCIO_LVTMA_DIGON_POL_NON_INVERT', + 1: 'DCIO_LVTMA_DIGON_POL_INVERT', +} +DCIO_LVTMA_DIGON_POL_NON_INVERT = 0 +DCIO_LVTMA_DIGON_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON__enumvalues = { + 0: 'DCIO_LVTMA_BLON_OFF', + 1: 'DCIO_LVTMA_BLON_ON', +} +DCIO_LVTMA_BLON_OFF = 0 +DCIO_LVTMA_BLON_ON = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL' +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL__enumvalues = { + 0: 'DCIO_LVTMA_BLON_POL_NON_INVERT', + 1: 'DCIO_LVTMA_BLON_POL_INVERT', +} +DCIO_LVTMA_BLON_POL_NON_INVERT = 0 +DCIO_LVTMA_BLON_POL_INVERT = 1 +DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN' +DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN__enumvalues = { + 0: 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON', + 1: 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE', +} +DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON = 0 +DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE = 1 +DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN' +DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN__enumvalues = { + 0: 'DCIO_BL_PWM_FRACTIONAL_DISABLE', + 1: 'DCIO_BL_PWM_FRACTIONAL_ENABLE', +} +DCIO_BL_PWM_FRACTIONAL_DISABLE = 0 +DCIO_BL_PWM_FRACTIONAL_ENABLE = 1 +DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL_BL_PWM_EN' +DCIO_BL_PWM_CNTL_BL_PWM_EN__enumvalues = { + 0: 'DCIO_BL_PWM_DISABLE', + 1: 'DCIO_BL_PWM_ENABLE', +} +DCIO_BL_PWM_DISABLE = 0 +DCIO_BL_PWM_ENABLE = 1 +DCIO_BL_PWM_CNTL_BL_PWM_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT' +DCIO_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT__enumvalues = { + 0: 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 1: 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 2: 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 3: 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', +} +DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL = 0 +DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1 = 1 +DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2 = 2 +DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3 = 3 +DCIO_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE' +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE__enumvalues = { + 0: 'DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 1: 'DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE', +} +DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE = 0 +DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE = 1 +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN' +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN__enumvalues = { + 0: 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL', + 1: 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM', +} +DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL = 0 +DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM = 1 +DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_REG_LOCK' +DCIO_BL_PWM_GRP1_REG_LOCK__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE', + 1: 'DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE', +} +DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE = 0 +DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE = 1 +DCIO_BL_PWM_GRP1_REG_LOCK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START' +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 1: 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', +} +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE = 0 +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE = 1 +DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL' +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 1: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 2: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 3: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 4: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 5: 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', +} +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1 = 0 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2 = 1 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3 = 2 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4 = 3 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5 = 4 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6 = 5 +DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN' +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 1: 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', +} +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM = 0 +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM = 1 +DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN' +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN__enumvalues = { + 0: 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 1: 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', +} +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE = 0 +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE = 1 +DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL_SEL' +DCIO_GSL_SEL__enumvalues = { + 0: 'DCIO_GSL_SEL_GROUP_0', + 1: 'DCIO_GSL_SEL_GROUP_1', + 2: 'DCIO_GSL_SEL_GROUP_2', +} +DCIO_GSL_SEL_GROUP_0 = 0 +DCIO_GSL_SEL_GROUP_1 = 1 +DCIO_GSL_SEL_GROUP_2 = 2 +DCIO_GSL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_CLK_GSL_MASK' +DCIO_GENLK_CLK_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_CLK_GSL_MASK_NO', + 1: 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_CLK_GSL_MASK_STEREO', +} +DCIO_GENLK_CLK_GSL_MASK_NO = 0 +DCIO_GENLK_CLK_GSL_MASK_TIMING = 1 +DCIO_GENLK_CLK_GSL_MASK_STEREO = 2 +DCIO_GENLK_CLK_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GENLK_VSYNC_GSL_MASK' +DCIO_GENLK_VSYNC_GSL_MASK__enumvalues = { + 0: 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 1: 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 2: 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', +} +DCIO_GENLK_VSYNC_GSL_MASK_NO = 0 +DCIO_GENLK_VSYNC_GSL_MASK_TIMING = 1 +DCIO_GENLK_VSYNC_GSL_MASK_STEREO = 2 +DCIO_GENLK_VSYNC_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_A_GSL_MASK' +DCIO_SWAPLOCK_A_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_A_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_A_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_A_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_A_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_A_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_SWAPLOCK_B_GSL_MASK' +DCIO_SWAPLOCK_B_GSL_MASK__enumvalues = { + 0: 'DCIO_SWAPLOCK_B_GSL_MASK_NO', + 1: 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', + 2: 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', +} +DCIO_SWAPLOCK_B_GSL_MASK_NO = 0 +DCIO_SWAPLOCK_B_GSL_MASK_TIMING = 1 +DCIO_SWAPLOCK_B_GSL_MASK_STEREO = 2 +DCIO_SWAPLOCK_B_GSL_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL_VSYNC_SEL' +DCIO_GSL_VSYNC_SEL__enumvalues = { + 0: 'DCIO_GSL_VSYNC_SEL_PIPE0', + 1: 'DCIO_GSL_VSYNC_SEL_PIPE1', + 2: 'DCIO_GSL_VSYNC_SEL_PIPE2', + 3: 'DCIO_GSL_VSYNC_SEL_PIPE3', + 4: 'DCIO_GSL_VSYNC_SEL_PIPE4', + 5: 'DCIO_GSL_VSYNC_SEL_PIPE5', +} +DCIO_GSL_VSYNC_SEL_PIPE0 = 0 +DCIO_GSL_VSYNC_SEL_PIPE1 = 1 +DCIO_GSL_VSYNC_SEL_PIPE2 = 2 +DCIO_GSL_VSYNC_SEL_PIPE3 = 3 +DCIO_GSL_VSYNC_SEL_PIPE4 = 4 +DCIO_GSL_VSYNC_SEL_PIPE5 = 5 +DCIO_GSL_VSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL0_TIMING_SYNC_SEL' +DCIO_GSL0_TIMING_SYNC_SEL__enumvalues = { + 0: 'DCIO_GSL0_TIMING_SYNC_SEL_PIPE', + 1: 'DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_CLK', + 3: 'DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_B', +} +DCIO_GSL0_TIMING_SYNC_SEL_PIPE = 0 +DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_VSYNC = 1 +DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_CLK = 2 +DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_A = 3 +DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_B = 4 +DCIO_GSL0_TIMING_SYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL0_GLOBAL_UNLOCK_SEL' +DCIO_GSL0_GLOBAL_UNLOCK_SEL__enumvalues = { + 0: 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_INVERSION', + 1: 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 3: 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', +} +DCIO_GSL0_GLOBAL_UNLOCK_SEL_INVERSION = 0 +DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC = 1 +DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENLK_CLK = 2 +DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_A = 3 +DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_B = 4 +DCIO_GSL0_GLOBAL_UNLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL1_TIMING_SYNC_SEL' +DCIO_GSL1_TIMING_SYNC_SEL__enumvalues = { + 0: 'DCIO_GSL1_TIMING_SYNC_SEL_PIPE', + 1: 'DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_CLK', + 3: 'DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_B', +} +DCIO_GSL1_TIMING_SYNC_SEL_PIPE = 0 +DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_VSYNC = 1 +DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_CLK = 2 +DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_A = 3 +DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_B = 4 +DCIO_GSL1_TIMING_SYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL1_GLOBAL_UNLOCK_SEL' +DCIO_GSL1_GLOBAL_UNLOCK_SEL__enumvalues = { + 0: 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_INVERSION', + 1: 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 3: 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', +} +DCIO_GSL1_GLOBAL_UNLOCK_SEL_INVERSION = 0 +DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC = 1 +DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENLK_CLK = 2 +DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_A = 3 +DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_B = 4 +DCIO_GSL1_GLOBAL_UNLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL2_TIMING_SYNC_SEL' +DCIO_GSL2_TIMING_SYNC_SEL__enumvalues = { + 0: 'DCIO_GSL2_TIMING_SYNC_SEL_PIPE', + 1: 'DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_CLK', + 3: 'DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_B', +} +DCIO_GSL2_TIMING_SYNC_SEL_PIPE = 0 +DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_VSYNC = 1 +DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_CLK = 2 +DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_A = 3 +DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_B = 4 +DCIO_GSL2_TIMING_SYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_GSL2_GLOBAL_UNLOCK_SEL' +DCIO_GSL2_GLOBAL_UNLOCK_SEL__enumvalues = { + 0: 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_INVERSION', + 1: 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 2: 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 3: 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 4: 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', +} +DCIO_GSL2_GLOBAL_UNLOCK_SEL_INVERSION = 0 +DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC = 1 +DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENLK_CLK = 2 +DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_A = 3 +DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_B = 4 +DCIO_GSL2_GLOBAL_UNLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_START_POSITION' +DCIO_DC_GPU_TIMER_START_POSITION__enumvalues = { + 0: 'DCIO_GPU_TIMER_START_0_END_27', + 1: 'DCIO_GPU_TIMER_START_1_END_28', + 2: 'DCIO_GPU_TIMER_START_2_END_29', + 3: 'DCIO_GPU_TIMER_START_3_END_30', + 4: 'DCIO_GPU_TIMER_START_4_END_31', + 5: 'DCIO_GPU_TIMER_START_6_END_33', + 6: 'DCIO_GPU_TIMER_START_8_END_35', + 7: 'DCIO_GPU_TIMER_START_10_END_37', +} +DCIO_GPU_TIMER_START_0_END_27 = 0 +DCIO_GPU_TIMER_START_1_END_28 = 1 +DCIO_GPU_TIMER_START_2_END_29 = 2 +DCIO_GPU_TIMER_START_3_END_30 = 3 +DCIO_GPU_TIMER_START_4_END_31 = 4 +DCIO_GPU_TIMER_START_6_END_33 = 5 +DCIO_GPU_TIMER_START_8_END_35 = 6 +DCIO_GPU_TIMER_START_10_END_37 = 7 +DCIO_DC_GPU_TIMER_START_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL' +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL__enumvalues = { + 0: 'DCIO_TEST_CLK_SEL_DISPCLK', + 1: 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', + 2: 'DCIO_TEST_CLK_SEL_SCLK', +} +DCIO_TEST_CLK_SEL_DISPCLK = 0 +DCIO_TEST_CLK_SEL_GATED_DISPCLK = 1 +DCIO_TEST_CLK_SEL_SCLK = 2 +DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS' +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS__enumvalues = { + 0: 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 1: 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', +} +DCIO_DISPCLK_R_DCIO_GATE_DISABLE = 0 +DCIO_DISPCLK_R_DCIO_GATE_ENABLE = 1 +DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCO_DCFE_EXT_VSYNC_MUX' +DCIO_DCO_DCFE_EXT_VSYNC_MUX__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 1: 'DCIO_EXT_VSYNC_MUX_CRTC0', + 2: 'DCIO_EXT_VSYNC_MUX_CRTC1', + 3: 'DCIO_EXT_VSYNC_MUX_CRTC2', + 4: 'DCIO_EXT_VSYNC_MUX_CRTC3', + 5: 'DCIO_EXT_VSYNC_MUX_CRTC4', + 6: 'DCIO_EXT_VSYNC_MUX_CRTC5', + 7: 'DCIO_EXT_VSYNC_MUX_GENERICB', +} +DCIO_EXT_VSYNC_MUX_SWAPLOCKB = 0 +DCIO_EXT_VSYNC_MUX_CRTC0 = 1 +DCIO_EXT_VSYNC_MUX_CRTC1 = 2 +DCIO_EXT_VSYNC_MUX_CRTC2 = 3 +DCIO_EXT_VSYNC_MUX_CRTC3 = 4 +DCIO_EXT_VSYNC_MUX_CRTC4 = 5 +DCIO_EXT_VSYNC_MUX_CRTC5 = 6 +DCIO_EXT_VSYNC_MUX_GENERICB = 7 +DCIO_DCO_DCFE_EXT_VSYNC_MUX = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCO_EXT_VSYNC_MASK' +DCIO_DCO_EXT_VSYNC_MASK__enumvalues = { + 0: 'DCIO_EXT_VSYNC_MASK_NONE', + 1: 'DCIO_EXT_VSYNC_MASK_PIPE0', + 2: 'DCIO_EXT_VSYNC_MASK_PIPE1', + 3: 'DCIO_EXT_VSYNC_MASK_PIPE2', + 4: 'DCIO_EXT_VSYNC_MASK_PIPE3', + 5: 'DCIO_EXT_VSYNC_MASK_PIPE4', + 6: 'DCIO_EXT_VSYNC_MASK_PIPE5', + 7: 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', +} +DCIO_EXT_VSYNC_MASK_NONE = 0 +DCIO_EXT_VSYNC_MASK_PIPE0 = 1 +DCIO_EXT_VSYNC_MASK_PIPE1 = 2 +DCIO_EXT_VSYNC_MASK_PIPE2 = 3 +DCIO_EXT_VSYNC_MASK_PIPE3 = 4 +DCIO_EXT_VSYNC_MASK_PIPE4 = 5 +DCIO_EXT_VSYNC_MASK_PIPE5 = 6 +DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE = 7 +DCIO_DCO_EXT_VSYNC_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DSYNC_SOFT_RESET' +DCIO_DSYNC_SOFT_RESET__enumvalues = { + 0: 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 1: 'DCIO_DSYNC_SOFT_RESET_ASSERT', +} +DCIO_DSYNC_SOFT_RESET_DEASSERT = 0 +DCIO_DSYNC_SOFT_RESET_ASSERT = 1 +DCIO_DSYNC_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DACA_SOFT_RESET' +DCIO_DACA_SOFT_RESET__enumvalues = { + 0: 'DCIO_DACA_SOFT_RESET_DEASSERT', + 1: 'DCIO_DACA_SOFT_RESET_ASSERT', +} +DCIO_DACA_SOFT_RESET_DEASSERT = 0 +DCIO_DACA_SOFT_RESET_ASSERT = 1 +DCIO_DACA_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DCRXPHY_SOFT_RESET' +DCIO_DCRXPHY_SOFT_RESET__enumvalues = { + 0: 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 1: 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', +} +DCIO_DCRXPHY_SOFT_RESET_DEASSERT = 0 +DCIO_DCRXPHY_SOFT_RESET_ASSERT = 1 +DCIO_DCRXPHY_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPHY_LANE_SEL' +DCIO_DPHY_LANE_SEL__enumvalues = { + 0: 'DCIO_DPHY_LANE_SEL_LANE0', + 1: 'DCIO_DPHY_LANE_SEL_LANE1', + 2: 'DCIO_DPHY_LANE_SEL_LANE2', + 3: 'DCIO_DPHY_LANE_SEL_LANE3', +} +DCIO_DPHY_LANE_SEL_LANE0 = 0 +DCIO_DPHY_LANE_SEL_LANE1 = 1 +DCIO_DPHY_LANE_SEL_LANE2 = 2 +DCIO_DPHY_LANE_SEL_LANE3 = 3 +DCIO_DPHY_LANE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_TYPE' +DCIO_DPCS_INTERRUPT_TYPE__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 1: 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', +} +DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED = 0 +DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED = 1 +DCIO_DPCS_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DPCS_INTERRUPT_MASK' +DCIO_DPCS_INTERRUPT_MASK__enumvalues = { + 0: 'DCIO_DPCS_INTERRUPT_DISABLE', + 1: 'DCIO_DPCS_INTERRUPT_ENABLE', +} +DCIO_DPCS_INTERRUPT_DISABLE = 0 +DCIO_DPCS_INTERRUPT_ENABLE = 1 +DCIO_DPCS_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DC_GPU_TIMER_READ_SELECT' +DCIO_DC_GPU_TIMER_READ_SELECT__enumvalues = { + 0: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 1: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 2: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE', + 3: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE', + 4: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE', + 5: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE', + 6: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE', + 7: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE', + 8: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE', + 9: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE', + 10: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE', + 11: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE', + 12: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 13: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 14: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_P_FLIP', + 15: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_P_FLIP', + 16: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_P_FLIP', + 17: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_P_FLIP', + 18: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_P_FLIP', + 19: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_P_FLIP', + 20: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_P_FLIP', + 21: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_P_FLIP', + 22: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_P_FLIP', + 23: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_P_FLIP', + 24: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 25: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', + 26: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM', + 27: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM', + 28: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM', + 29: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM', + 30: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM', + 31: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM', + 32: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM', + 33: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM', + 34: 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM', + 35: 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM', +} +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE = 0 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE = 1 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE = 2 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE = 3 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE = 4 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE = 5 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE = 6 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE = 7 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE = 8 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE = 9 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE = 10 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE = 11 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP = 12 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP = 13 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_P_FLIP = 14 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_P_FLIP = 15 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_P_FLIP = 16 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_P_FLIP = 17 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_P_FLIP = 18 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_P_FLIP = 19 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_P_FLIP = 20 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_P_FLIP = 21 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_P_FLIP = 22 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_P_FLIP = 23 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM = 24 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM = 25 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM = 26 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM = 27 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM = 28 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM = 29 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM = 30 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM = 31 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM = 32 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM = 33 +DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM = 34 +DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM = 35 +DCIO_DC_GPU_TIMER_READ_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_IMPCAL_STEP_DELAY' +DCIO_IMPCAL_STEP_DELAY__enumvalues = { + 0: 'DCIO_IMPCAL_STEP_DELAY_1us', + 1: 'DCIO_IMPCAL_STEP_DELAY_2us', + 2: 'DCIO_IMPCAL_STEP_DELAY_3us', + 3: 'DCIO_IMPCAL_STEP_DELAY_4us', + 4: 'DCIO_IMPCAL_STEP_DELAY_5us', + 5: 'DCIO_IMPCAL_STEP_DELAY_6us', + 6: 'DCIO_IMPCAL_STEP_DELAY_7us', + 7: 'DCIO_IMPCAL_STEP_DELAY_8us', + 8: 'DCIO_IMPCAL_STEP_DELAY_9us', + 9: 'DCIO_IMPCAL_STEP_DELAY_10us', + 10: 'DCIO_IMPCAL_STEP_DELAY_11us', + 11: 'DCIO_IMPCAL_STEP_DELAY_12us', + 12: 'DCIO_IMPCAL_STEP_DELAY_13us', + 13: 'DCIO_IMPCAL_STEP_DELAY_14us', + 14: 'DCIO_IMPCAL_STEP_DELAY_15us', + 15: 'DCIO_IMPCAL_STEP_DELAY_16us', +} +DCIO_IMPCAL_STEP_DELAY_1us = 0 +DCIO_IMPCAL_STEP_DELAY_2us = 1 +DCIO_IMPCAL_STEP_DELAY_3us = 2 +DCIO_IMPCAL_STEP_DELAY_4us = 3 +DCIO_IMPCAL_STEP_DELAY_5us = 4 +DCIO_IMPCAL_STEP_DELAY_6us = 5 +DCIO_IMPCAL_STEP_DELAY_7us = 6 +DCIO_IMPCAL_STEP_DELAY_8us = 7 +DCIO_IMPCAL_STEP_DELAY_9us = 8 +DCIO_IMPCAL_STEP_DELAY_10us = 9 +DCIO_IMPCAL_STEP_DELAY_11us = 10 +DCIO_IMPCAL_STEP_DELAY_12us = 11 +DCIO_IMPCAL_STEP_DELAY_13us = 12 +DCIO_IMPCAL_STEP_DELAY_14us = 13 +DCIO_IMPCAL_STEP_DELAY_15us = 14 +DCIO_IMPCAL_STEP_DELAY_16us = 15 +DCIO_IMPCAL_STEP_DELAY = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_UNIPHY_IMPCAL_SEL' +DCIO_UNIPHY_IMPCAL_SEL__enumvalues = { + 0: 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 1: 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', +} +DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE = 0 +DCIO_UNIPHY_IMPCAL_SEL_BINARY = 1 +DCIO_UNIPHY_IMPCAL_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_BLOCK_SEL' +DCIO_DBG_ASYNC_BLOCK_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', + 1: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', + 2: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 3: 'DCIO_DBG_ASYNC_BLOCK_SEL_DCO', +} +DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE = 0 +DCIO_DBG_ASYNC_BLOCK_SEL_DCCG = 1 +DCIO_DBG_ASYNC_BLOCK_SEL_DCIO = 2 +DCIO_DBG_ASYNC_BLOCK_SEL_DCO = 3 +DCIO_DBG_ASYNC_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCIO_DBG_ASYNC_4BIT_SEL' +DCIO_DBG_ASYNC_4BIT_SEL__enumvalues = { + 0: 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 1: 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', + 2: 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 3: 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 4: 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 5: 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 6: 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 7: 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', +} +DCIO_DBG_ASYNC_4BIT_SEL_3TO0 = 0 +DCIO_DBG_ASYNC_4BIT_SEL_7TO4 = 1 +DCIO_DBG_ASYNC_4BIT_SEL_11TO8 = 2 +DCIO_DBG_ASYNC_4BIT_SEL_15TO12 = 3 +DCIO_DBG_ASYNC_4BIT_SEL_19TO16 = 4 +DCIO_DBG_ASYNC_4BIT_SEL_23TO20 = 5 +DCIO_DBG_ASYNC_4BIT_SEL_27TO24 = 6 +DCIO_DBG_ASYNC_4BIT_SEL_31TO28 = 7 +DCIO_DBG_ASYNC_4BIT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'AOUT_EN' +AOUT_EN__enumvalues = { + 0: 'AOUT_DISABLE', + 1: 'AOUT_ENABLE', +} +AOUT_DISABLE = 0 +AOUT_ENABLE = 1 +AOUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'AOUT_FIFO_START_ADDR' +AOUT_FIFO_START_ADDR__enumvalues = { + 0: 'AOUT_FIFO_START_ADDR_2', + 1: 'AOUT_FIFO_START_ADDR_3', +} +AOUT_FIFO_START_ADDR_2 = 0 +AOUT_FIFO_START_ADDR_3 = 1 +AOUT_FIFO_START_ADDR = ctypes.c_uint32 # enum + +# values for enumeration 'AOUT_CRC_TEST_EN' +AOUT_CRC_TEST_EN__enumvalues = { + 0: 'AOUT_CRC_DISABLE', + 1: 'AOUT_CRC_ENABLE', +} +AOUT_CRC_DISABLE = 0 +AOUT_CRC_ENABLE = 1 +AOUT_CRC_TEST_EN = ctypes.c_uint32 # enum + +# values for enumeration 'AOUT_CRC_SOFT_RESET' +AOUT_CRC_SOFT_RESET__enumvalues = { + 0: 'AOUT_CRC_NO_RESET', + 1: 'AOUT_CRC_RESET', +} +AOUT_CRC_NO_RESET = 0 +AOUT_CRC_RESET = 1 +AOUT_CRC_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'AOUT_CRC_CONT_EN' +AOUT_CRC_CONT_EN__enumvalues = { + 0: 'AOUT_CRC_ONE_SHOT', + 1: 'AOUT_CRC_CONT', +} +AOUT_CRC_ONE_SHOT = 0 +AOUT_CRC_CONT = 1 +AOUT_CRC_CONT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'I2S_WORD_SIZE' +I2S_WORD_SIZE__enumvalues = { + 0: 'I2S_WORD_SIZE_32', + 1: 'I2S_WORD_SIZE_16', +} +I2S_WORD_SIZE_32 = 0 +I2S_WORD_SIZE_16 = 1 +I2S_WORD_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'I2S_SAMPLE_ALIGNMENT' +I2S_SAMPLE_ALIGNMENT__enumvalues = { + 0: 'I2S_SAMPLE_LEFT_ALIGNED', + 1: 'I2S_SAMPLE_RIGHT_ALIGNED', +} +I2S_SAMPLE_LEFT_ALIGNED = 0 +I2S_SAMPLE_RIGHT_ALIGNED = 1 +I2S_SAMPLE_ALIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'I2S_SAMPLE_BIT_ORDER' +I2S_SAMPLE_BIT_ORDER__enumvalues = { + 0: 'I2S_SAMPLE_BIT_ORDER_MSB', + 1: 'I2S_SAMPLE_BIT_ORDER_LSB', +} +I2S_SAMPLE_BIT_ORDER_MSB = 0 +I2S_SAMPLE_BIT_ORDER_LSB = 1 +I2S_SAMPLE_BIT_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'I2S_LRCLK_POLARITY' +I2S_LRCLK_POLARITY__enumvalues = { + 0: 'I2S_LRCLK_LOW_LEFT', + 1: 'I2S_LRCLK_HIGH_LEFT', +} +I2S_LRCLK_LOW_LEFT = 0 +I2S_LRCLK_HIGH_LEFT = 1 +I2S_LRCLK_POLARITY = ctypes.c_uint32 # enum + +# values for enumeration 'I2S_WORD_ALIGNMENT' +I2S_WORD_ALIGNMENT__enumvalues = { + 0: 'I2S_WORD_ALTERNATE_ALIGNMENT', + 1: 'I2S_WORD_I2S_ALIGNMENT', +} +I2S_WORD_ALTERNATE_ALIGNMENT = 0 +I2S_WORD_I2S_ALIGNMENT = 1 +I2S_WORD_ALIGNMENT = ctypes.c_uint32 # enum + +# values for enumeration 'SPDIF_INVERT_EN' +SPDIF_INVERT_EN__enumvalues = { + 0: 'SPDIF_INVERT_DISABLE', + 1: 'SPDIF_INVERT_ENABLE', +} +SPDIF_INVERT_DISABLE = 0 +SPDIF_INVERT_ENABLE = 1 +SPDIF_INVERT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_EN' +DPDBG_EN__enumvalues = { + 0: 'DPDBG_DISABLE', + 1: 'DPDBG_ENABLE', +} +DPDBG_DISABLE = 0 +DPDBG_ENABLE = 1 +DPDBG_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_INPUT_EN' +DPDBG_INPUT_EN__enumvalues = { + 0: 'DPDBG_INPUT_DISABLE', + 1: 'DPDBG_INPUT_ENABLE', +} +DPDBG_INPUT_DISABLE = 0 +DPDBG_INPUT_ENABLE = 1 +DPDBG_INPUT_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_ERROR_DETECTION_MODE' +DPDBG_ERROR_DETECTION_MODE__enumvalues = { + 0: 'DPDBG_ERROR_DETECTION_MODE_CSC', + 1: 'DPDBG_ERROR_DETECTION_MODE_RS_ENCODING', +} +DPDBG_ERROR_DETECTION_MODE_CSC = 0 +DPDBG_ERROR_DETECTION_MODE_RS_ENCODING = 1 +DPDBG_ERROR_DETECTION_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_FIFO_OVERFLOW_INTERRUPT_MASK' +DPDBG_FIFO_OVERFLOW_INTERRUPT_MASK__enumvalues = { + 0: 'DPDBG_FIFO_OVERFLOW_INT_DISABLE', + 1: 'DPDBG_FIFO_OVERFLOW_INT_ENABLE', +} +DPDBG_FIFO_OVERFLOW_INT_DISABLE = 0 +DPDBG_FIFO_OVERFLOW_INT_ENABLE = 1 +DPDBG_FIFO_OVERFLOW_INTERRUPT_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_FIFO_OVERFLOW_INTERRUPT_TYPE' +DPDBG_FIFO_OVERFLOW_INTERRUPT_TYPE__enumvalues = { + 0: 'DPDBG_FIFO_OVERFLOW_INT_LEVEL_BASED', + 1: 'DPDBG_FIFO_OVERFLOW_INT_PULSE_BASED', +} +DPDBG_FIFO_OVERFLOW_INT_LEVEL_BASED = 0 +DPDBG_FIFO_OVERFLOW_INT_PULSE_BASED = 1 +DPDBG_FIFO_OVERFLOW_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_FIFO_OVERFLOW_INTERRUPT_ACK' +DPDBG_FIFO_OVERFLOW_INTERRUPT_ACK__enumvalues = { + 0: 'DPDBG_FIFO_OVERFLOW_INT_NO_ACK', + 1: 'DPDBG_FIFO_OVERFLOW_INT_CLEAR', +} +DPDBG_FIFO_OVERFLOW_INT_NO_ACK = 0 +DPDBG_FIFO_OVERFLOW_INT_CLEAR = 1 +DPDBG_FIFO_OVERFLOW_INTERRUPT_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'PM_ASSERT_RESET' +PM_ASSERT_RESET__enumvalues = { + 0: 'PM_ASSERT_RESET_0', + 1: 'PM_ASSERT_RESET_1', +} +PM_ASSERT_RESET_0 = 0 +PM_ASSERT_RESET_1 = 1 +PM_ASSERT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DAC_MUX_SELECT' +DAC_MUX_SELECT__enumvalues = { + 0: 'DAC_MUX_SELECT_DACA', + 1: 'DAC_MUX_SELECT_DACB', +} +DAC_MUX_SELECT_DACA = 0 +DAC_MUX_SELECT_DACB = 1 +DAC_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TMDS_DVO_MUX_SELECT' +TMDS_DVO_MUX_SELECT__enumvalues = { + 0: 'TMDS_DVO_MUX_SELECT_B', + 1: 'TMDS_DVO_MUX_SELECT_G', + 2: 'TMDS_DVO_MUX_SELECT_R', + 3: 'TMDS_DVO_MUX_SELECT_RESERVED', +} +TMDS_DVO_MUX_SELECT_B = 0 +TMDS_DVO_MUX_SELECT_G = 1 +TMDS_DVO_MUX_SELECT_R = 2 +TMDS_DVO_MUX_SELECT_RESERVED = 3 +TMDS_DVO_MUX_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DACA_SOFT_RESET' +DACA_SOFT_RESET__enumvalues = { + 0: 'DACA_SOFT_RESET_0', + 1: 'DACA_SOFT_RESET_1', +} +DACA_SOFT_RESET_0 = 0 +DACA_SOFT_RESET_1 = 1 +DACA_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'I2S0_SPDIF0_SOFT_RESET' +I2S0_SPDIF0_SOFT_RESET__enumvalues = { + 0: 'I2S0_SPDIF0_SOFT_RESET_0', + 1: 'I2S0_SPDIF0_SOFT_RESET_1', +} +I2S0_SPDIF0_SOFT_RESET_0 = 0 +I2S0_SPDIF0_SOFT_RESET_1 = 1 +I2S0_SPDIF0_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'I2S1_SOFT_RESET' +I2S1_SOFT_RESET__enumvalues = { + 0: 'I2S1_SOFT_RESET_0', + 1: 'I2S1_SOFT_RESET_1', +} +I2S1_SOFT_RESET_0 = 0 +I2S1_SOFT_RESET_1 = 1 +I2S1_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'SPDIF1_SOFT_RESET' +SPDIF1_SOFT_RESET__enumvalues = { + 0: 'SPDIF1_SOFT_RESET_0', + 1: 'SPDIF1_SOFT_RESET_1', +} +SPDIF1_SOFT_RESET_0 = 0 +SPDIF1_SOFT_RESET_1 = 1 +SPDIF1_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DB_CLK_SOFT_RESET' +DB_CLK_SOFT_RESET__enumvalues = { + 0: 'DB_CLK_SOFT_RESET_0', + 1: 'DB_CLK_SOFT_RESET_1', +} +DB_CLK_SOFT_RESET_0 = 0 +DB_CLK_SOFT_RESET_1 = 1 +DB_CLK_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT0_SOFT_RESET' +FMT0_SOFT_RESET__enumvalues = { + 0: 'FMT0_SOFT_RESET_0', + 1: 'FMT0_SOFT_RESET_1', +} +FMT0_SOFT_RESET_0 = 0 +FMT0_SOFT_RESET_1 = 1 +FMT0_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT1_SOFT_RESET' +FMT1_SOFT_RESET__enumvalues = { + 0: 'FMT1_SOFT_RESET_0', + 1: 'FMT1_SOFT_RESET_1', +} +FMT1_SOFT_RESET_0 = 0 +FMT1_SOFT_RESET_1 = 1 +FMT1_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT2_SOFT_RESET' +FMT2_SOFT_RESET__enumvalues = { + 0: 'FMT2_SOFT_RESET_0', + 1: 'FMT2_SOFT_RESET_1', +} +FMT2_SOFT_RESET_0 = 0 +FMT2_SOFT_RESET_1 = 1 +FMT2_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT3_SOFT_RESET' +FMT3_SOFT_RESET__enumvalues = { + 0: 'FMT3_SOFT_RESET_0', + 1: 'FMT3_SOFT_RESET_1', +} +FMT3_SOFT_RESET_0 = 0 +FMT3_SOFT_RESET_1 = 1 +FMT3_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT4_SOFT_RESET' +FMT4_SOFT_RESET__enumvalues = { + 0: 'FMT4_SOFT_RESET_0', + 1: 'FMT4_SOFT_RESET_1', +} +FMT4_SOFT_RESET_0 = 0 +FMT4_SOFT_RESET_1 = 1 +FMT4_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'FMT5_SOFT_RESET' +FMT5_SOFT_RESET__enumvalues = { + 0: 'FMT5_SOFT_RESET_0', + 1: 'FMT5_SOFT_RESET_1', +} +FMT5_SOFT_RESET_0 = 0 +FMT5_SOFT_RESET_1 = 1 +FMT5_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'MVP_SOFT_RESET' +MVP_SOFT_RESET__enumvalues = { + 0: 'MVP_SOFT_RESET_0', + 1: 'MVP_SOFT_RESET_1', +} +MVP_SOFT_RESET_0 = 0 +MVP_SOFT_RESET_1 = 1 +MVP_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'ABM_SOFT_RESET' +ABM_SOFT_RESET__enumvalues = { + 0: 'ABM_SOFT_RESET_0', + 1: 'ABM_SOFT_RESET_1', +} +ABM_SOFT_RESET_0 = 0 +ABM_SOFT_RESET_1 = 1 +ABM_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DVO_SOFT_RESET' +DVO_SOFT_RESET__enumvalues = { + 0: 'DVO_SOFT_RESET_0', + 1: 'DVO_SOFT_RESET_1', +} +DVO_SOFT_RESET_0 = 0 +DVO_SOFT_RESET_1 = 1 +DVO_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGA_FE_SOFT_RESET' +DIGA_FE_SOFT_RESET__enumvalues = { + 0: 'DIGA_FE_SOFT_RESET_0', + 1: 'DIGA_FE_SOFT_RESET_1', +} +DIGA_FE_SOFT_RESET_0 = 0 +DIGA_FE_SOFT_RESET_1 = 1 +DIGA_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGA_BE_SOFT_RESET' +DIGA_BE_SOFT_RESET__enumvalues = { + 0: 'DIGA_BE_SOFT_RESET_0', + 1: 'DIGA_BE_SOFT_RESET_1', +} +DIGA_BE_SOFT_RESET_0 = 0 +DIGA_BE_SOFT_RESET_1 = 1 +DIGA_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGB_FE_SOFT_RESET' +DIGB_FE_SOFT_RESET__enumvalues = { + 0: 'DIGB_FE_SOFT_RESET_0', + 1: 'DIGB_FE_SOFT_RESET_1', +} +DIGB_FE_SOFT_RESET_0 = 0 +DIGB_FE_SOFT_RESET_1 = 1 +DIGB_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGB_BE_SOFT_RESET' +DIGB_BE_SOFT_RESET__enumvalues = { + 0: 'DIGB_BE_SOFT_RESET_0', + 1: 'DIGB_BE_SOFT_RESET_1', +} +DIGB_BE_SOFT_RESET_0 = 0 +DIGB_BE_SOFT_RESET_1 = 1 +DIGB_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGC_FE_SOFT_RESET' +DIGC_FE_SOFT_RESET__enumvalues = { + 0: 'DIGC_FE_SOFT_RESET_0', + 1: 'DIGC_FE_SOFT_RESET_1', +} +DIGC_FE_SOFT_RESET_0 = 0 +DIGC_FE_SOFT_RESET_1 = 1 +DIGC_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGC_BE_SOFT_RESET' +DIGC_BE_SOFT_RESET__enumvalues = { + 0: 'DIGC_BE_SOFT_RESET_0', + 1: 'DIGC_BE_SOFT_RESET_1', +} +DIGC_BE_SOFT_RESET_0 = 0 +DIGC_BE_SOFT_RESET_1 = 1 +DIGC_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGD_FE_SOFT_RESET' +DIGD_FE_SOFT_RESET__enumvalues = { + 0: 'DIGD_FE_SOFT_RESET_0', + 1: 'DIGD_FE_SOFT_RESET_1', +} +DIGD_FE_SOFT_RESET_0 = 0 +DIGD_FE_SOFT_RESET_1 = 1 +DIGD_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGD_BE_SOFT_RESET' +DIGD_BE_SOFT_RESET__enumvalues = { + 0: 'DIGD_BE_SOFT_RESET_0', + 1: 'DIGD_BE_SOFT_RESET_1', +} +DIGD_BE_SOFT_RESET_0 = 0 +DIGD_BE_SOFT_RESET_1 = 1 +DIGD_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGE_FE_SOFT_RESET' +DIGE_FE_SOFT_RESET__enumvalues = { + 0: 'DIGE_FE_SOFT_RESET_0', + 1: 'DIGE_FE_SOFT_RESET_1', +} +DIGE_FE_SOFT_RESET_0 = 0 +DIGE_FE_SOFT_RESET_1 = 1 +DIGE_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGE_BE_SOFT_RESET' +DIGE_BE_SOFT_RESET__enumvalues = { + 0: 'DIGE_BE_SOFT_RESET_0', + 1: 'DIGE_BE_SOFT_RESET_1', +} +DIGE_BE_SOFT_RESET_0 = 0 +DIGE_BE_SOFT_RESET_1 = 1 +DIGE_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGF_FE_SOFT_RESET' +DIGF_FE_SOFT_RESET__enumvalues = { + 0: 'DIGF_FE_SOFT_RESET_0', + 1: 'DIGF_FE_SOFT_RESET_1', +} +DIGF_FE_SOFT_RESET_0 = 0 +DIGF_FE_SOFT_RESET_1 = 1 +DIGF_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGF_BE_SOFT_RESET' +DIGF_BE_SOFT_RESET__enumvalues = { + 0: 'DIGF_BE_SOFT_RESET_0', + 1: 'DIGF_BE_SOFT_RESET_1', +} +DIGF_BE_SOFT_RESET_0 = 0 +DIGF_BE_SOFT_RESET_1 = 1 +DIGF_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGG_FE_SOFT_RESET' +DIGG_FE_SOFT_RESET__enumvalues = { + 0: 'DIGG_FE_SOFT_RESET_0', + 1: 'DIGG_FE_SOFT_RESET_1', +} +DIGG_FE_SOFT_RESET_0 = 0 +DIGG_FE_SOFT_RESET_1 = 1 +DIGG_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGG_BE_SOFT_RESET' +DIGG_BE_SOFT_RESET__enumvalues = { + 0: 'DIGG_BE_SOFT_RESET_0', + 1: 'DIGG_BE_SOFT_RESET_1', +} +DIGG_BE_SOFT_RESET_0 = 0 +DIGG_BE_SOFT_RESET_1 = 1 +DIGG_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DPDBG_SOFT_RESET' +DPDBG_SOFT_RESET__enumvalues = { + 0: 'DPDBG_SOFT_RESET_0', + 1: 'DPDBG_SOFT_RESET_1', +} +DPDBG_SOFT_RESET_0 = 0 +DPDBG_SOFT_RESET_1 = 1 +DPDBG_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGLPA_FE_SOFT_RESET' +DIGLPA_FE_SOFT_RESET__enumvalues = { + 0: 'DIGLPA_FE_SOFT_RESET_0', + 1: 'DIGLPA_FE_SOFT_RESET_1', +} +DIGLPA_FE_SOFT_RESET_0 = 0 +DIGLPA_FE_SOFT_RESET_1 = 1 +DIGLPA_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGLPA_BE_SOFT_RESET' +DIGLPA_BE_SOFT_RESET__enumvalues = { + 0: 'DIGLPA_BE_SOFT_RESET_0', + 1: 'DIGLPA_BE_SOFT_RESET_1', +} +DIGLPA_BE_SOFT_RESET_0 = 0 +DIGLPA_BE_SOFT_RESET_1 = 1 +DIGLPA_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGLPB_FE_SOFT_RESET' +DIGLPB_FE_SOFT_RESET__enumvalues = { + 0: 'DIGLPB_FE_SOFT_RESET_0', + 1: 'DIGLPB_FE_SOFT_RESET_1', +} +DIGLPB_FE_SOFT_RESET_0 = 0 +DIGLPB_FE_SOFT_RESET_1 = 1 +DIGLPB_FE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DIGLPB_BE_SOFT_RESET' +DIGLPB_BE_SOFT_RESET__enumvalues = { + 0: 'DIGLPB_BE_SOFT_RESET_0', + 1: 'DIGLPB_BE_SOFT_RESET_1', +} +DIGLPB_BE_SOFT_RESET_0 = 0 +DIGLPB_BE_SOFT_RESET_1 = 1 +DIGLPB_BE_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'GENERICA_STEREOSYNC_SEL' +GENERICA_STEREOSYNC_SEL__enumvalues = { + 0: 'GENERICA_STEREOSYNC_SEL_D1', + 1: 'GENERICA_STEREOSYNC_SEL_D2', + 2: 'GENERICA_STEREOSYNC_SEL_D3', + 3: 'GENERICA_STEREOSYNC_SEL_D4', + 4: 'GENERICA_STEREOSYNC_SEL_D5', + 5: 'GENERICA_STEREOSYNC_SEL_D6', + 6: 'GENERICA_STEREOSYNC_SEL_RESERVED', +} +GENERICA_STEREOSYNC_SEL_D1 = 0 +GENERICA_STEREOSYNC_SEL_D2 = 1 +GENERICA_STEREOSYNC_SEL_D3 = 2 +GENERICA_STEREOSYNC_SEL_D4 = 3 +GENERICA_STEREOSYNC_SEL_D5 = 4 +GENERICA_STEREOSYNC_SEL_D6 = 5 +GENERICA_STEREOSYNC_SEL_RESERVED = 6 +GENERICA_STEREOSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GENERICB_STEREOSYNC_SEL' +GENERICB_STEREOSYNC_SEL__enumvalues = { + 0: 'GENERICB_STEREOSYNC_SEL_D1', + 1: 'GENERICB_STEREOSYNC_SEL_D2', + 2: 'GENERICB_STEREOSYNC_SEL_D3', + 3: 'GENERICB_STEREOSYNC_SEL_D4', + 4: 'GENERICB_STEREOSYNC_SEL_D5', + 5: 'GENERICB_STEREOSYNC_SEL_D6', + 6: 'GENERICB_STEREOSYNC_SEL_RESERVED', +} +GENERICB_STEREOSYNC_SEL_D1 = 0 +GENERICB_STEREOSYNC_SEL_D2 = 1 +GENERICB_STEREOSYNC_SEL_D3 = 2 +GENERICB_STEREOSYNC_SEL_D4 = 3 +GENERICB_STEREOSYNC_SEL_D5 = 4 +GENERICB_STEREOSYNC_SEL_D6 = 5 +GENERICB_STEREOSYNC_SEL_RESERVED = 6 +GENERICB_STEREOSYNC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCO_DBG_BLOCK_SEL' +DCO_DBG_BLOCK_SEL__enumvalues = { + 0: 'DCO_DBG_BLOCK_SEL_DCO', + 1: 'DCO_DBG_BLOCK_SEL_ABM', + 2: 'DCO_DBG_BLOCK_SEL_DVO', + 3: 'DCO_DBG_BLOCK_SEL_DAC', + 4: 'DCO_DBG_BLOCK_SEL_MVP', + 5: 'DCO_DBG_BLOCK_SEL_FMT0', + 6: 'DCO_DBG_BLOCK_SEL_FMT1', + 7: 'DCO_DBG_BLOCK_SEL_FMT2', + 8: 'DCO_DBG_BLOCK_SEL_FMT3', + 9: 'DCO_DBG_BLOCK_SEL_FMT4', + 10: 'DCO_DBG_BLOCK_SEL_FMT5', + 11: 'DCO_DBG_BLOCK_SEL_DIGFE_A', + 12: 'DCO_DBG_BLOCK_SEL_DIGFE_B', + 13: 'DCO_DBG_BLOCK_SEL_DIGFE_C', + 14: 'DCO_DBG_BLOCK_SEL_DIGFE_D', + 15: 'DCO_DBG_BLOCK_SEL_DIGFE_E', + 16: 'DCO_DBG_BLOCK_SEL_DIGFE_F', + 17: 'DCO_DBG_BLOCK_SEL_DIGFE_G', + 18: 'DCO_DBG_BLOCK_SEL_DIGA', + 19: 'DCO_DBG_BLOCK_SEL_DIGB', + 20: 'DCO_DBG_BLOCK_SEL_DIGC', + 21: 'DCO_DBG_BLOCK_SEL_DIGD', + 22: 'DCO_DBG_BLOCK_SEL_DIGE', + 23: 'DCO_DBG_BLOCK_SEL_DIGF', + 24: 'DCO_DBG_BLOCK_SEL_DIGG', + 25: 'DCO_DBG_BLOCK_SEL_DPFE_A', + 26: 'DCO_DBG_BLOCK_SEL_DPFE_B', + 27: 'DCO_DBG_BLOCK_SEL_DPFE_C', + 28: 'DCO_DBG_BLOCK_SEL_DPFE_D', + 29: 'DCO_DBG_BLOCK_SEL_DPFE_E', + 30: 'DCO_DBG_BLOCK_SEL_DPFE_F', + 31: 'DCO_DBG_BLOCK_SEL_DPFE_G', + 32: 'DCO_DBG_BLOCK_SEL_DPA', + 33: 'DCO_DBG_BLOCK_SEL_DPB', + 34: 'DCO_DBG_BLOCK_SEL_DPC', + 35: 'DCO_DBG_BLOCK_SEL_DPD', + 36: 'DCO_DBG_BLOCK_SEL_DPE', + 37: 'DCO_DBG_BLOCK_SEL_DPF', + 38: 'DCO_DBG_BLOCK_SEL_DPG', + 39: 'DCO_DBG_BLOCK_SEL_AUX0', + 40: 'DCO_DBG_BLOCK_SEL_AUX1', + 41: 'DCO_DBG_BLOCK_SEL_AUX2', + 42: 'DCO_DBG_BLOCK_SEL_AUX3', + 43: 'DCO_DBG_BLOCK_SEL_AUX4', + 44: 'DCO_DBG_BLOCK_SEL_AUX5', + 45: 'DCO_DBG_BLOCK_SEL_PERFMON_DCO', + 46: 'DCO_DBG_BLOCK_SEL_AUDIO_OUT', + 47: 'DCO_DBG_BLOCK_SEL_DIGLPFEA', + 48: 'DCO_DBG_BLOCK_SEL_DIGLPFEB', + 49: 'DCO_DBG_BLOCK_SEL_DIGLPA', + 50: 'DCO_DBG_BLOCK_SEL_DIGLPB', + 51: 'DCO_DBG_BLOCK_SEL_DPLPFEA', + 52: 'DCO_DBG_BLOCK_SEL_DPLPFEB', + 53: 'DCO_DBG_BLOCK_SEL_DPLPA', + 54: 'DCO_DBG_BLOCK_SEL_DPLPB', +} +DCO_DBG_BLOCK_SEL_DCO = 0 +DCO_DBG_BLOCK_SEL_ABM = 1 +DCO_DBG_BLOCK_SEL_DVO = 2 +DCO_DBG_BLOCK_SEL_DAC = 3 +DCO_DBG_BLOCK_SEL_MVP = 4 +DCO_DBG_BLOCK_SEL_FMT0 = 5 +DCO_DBG_BLOCK_SEL_FMT1 = 6 +DCO_DBG_BLOCK_SEL_FMT2 = 7 +DCO_DBG_BLOCK_SEL_FMT3 = 8 +DCO_DBG_BLOCK_SEL_FMT4 = 9 +DCO_DBG_BLOCK_SEL_FMT5 = 10 +DCO_DBG_BLOCK_SEL_DIGFE_A = 11 +DCO_DBG_BLOCK_SEL_DIGFE_B = 12 +DCO_DBG_BLOCK_SEL_DIGFE_C = 13 +DCO_DBG_BLOCK_SEL_DIGFE_D = 14 +DCO_DBG_BLOCK_SEL_DIGFE_E = 15 +DCO_DBG_BLOCK_SEL_DIGFE_F = 16 +DCO_DBG_BLOCK_SEL_DIGFE_G = 17 +DCO_DBG_BLOCK_SEL_DIGA = 18 +DCO_DBG_BLOCK_SEL_DIGB = 19 +DCO_DBG_BLOCK_SEL_DIGC = 20 +DCO_DBG_BLOCK_SEL_DIGD = 21 +DCO_DBG_BLOCK_SEL_DIGE = 22 +DCO_DBG_BLOCK_SEL_DIGF = 23 +DCO_DBG_BLOCK_SEL_DIGG = 24 +DCO_DBG_BLOCK_SEL_DPFE_A = 25 +DCO_DBG_BLOCK_SEL_DPFE_B = 26 +DCO_DBG_BLOCK_SEL_DPFE_C = 27 +DCO_DBG_BLOCK_SEL_DPFE_D = 28 +DCO_DBG_BLOCK_SEL_DPFE_E = 29 +DCO_DBG_BLOCK_SEL_DPFE_F = 30 +DCO_DBG_BLOCK_SEL_DPFE_G = 31 +DCO_DBG_BLOCK_SEL_DPA = 32 +DCO_DBG_BLOCK_SEL_DPB = 33 +DCO_DBG_BLOCK_SEL_DPC = 34 +DCO_DBG_BLOCK_SEL_DPD = 35 +DCO_DBG_BLOCK_SEL_DPE = 36 +DCO_DBG_BLOCK_SEL_DPF = 37 +DCO_DBG_BLOCK_SEL_DPG = 38 +DCO_DBG_BLOCK_SEL_AUX0 = 39 +DCO_DBG_BLOCK_SEL_AUX1 = 40 +DCO_DBG_BLOCK_SEL_AUX2 = 41 +DCO_DBG_BLOCK_SEL_AUX3 = 42 +DCO_DBG_BLOCK_SEL_AUX4 = 43 +DCO_DBG_BLOCK_SEL_AUX5 = 44 +DCO_DBG_BLOCK_SEL_PERFMON_DCO = 45 +DCO_DBG_BLOCK_SEL_AUDIO_OUT = 46 +DCO_DBG_BLOCK_SEL_DIGLPFEA = 47 +DCO_DBG_BLOCK_SEL_DIGLPFEB = 48 +DCO_DBG_BLOCK_SEL_DIGLPA = 49 +DCO_DBG_BLOCK_SEL_DIGLPB = 50 +DCO_DBG_BLOCK_SEL_DPLPFEA = 51 +DCO_DBG_BLOCK_SEL_DPLPFEB = 52 +DCO_DBG_BLOCK_SEL_DPLPA = 53 +DCO_DBG_BLOCK_SEL_DPLPB = 54 +DCO_DBG_BLOCK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DCO_HDMI_RXSTATUS_TIMER_CONTROL_DCO_HDMI_RXSTATUS_TIMER_TYPE' +DCO_HDMI_RXSTATUS_TIMER_CONTROL_DCO_HDMI_RXSTATUS_TIMER_TYPE__enumvalues = { + 0: 'DCO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 1: 'DCO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', +} +DCO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL = 0 +DCO_HDMI_RXSTATUS_TIMER_TYPE_PULSE = 1 +DCO_HDMI_RXSTATUS_TIMER_CONTROL_DCO_HDMI_RXSTATUS_TIMER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'FMT420_MEMORY_SOURCE_SEL' +FMT420_MEMORY_SOURCE_SEL__enumvalues = { + 0: 'FMT420_MEMORY_SOURCE_SEL_FMT0', + 1: 'FMT420_MEMORY_SOURCE_SEL_FMT1', + 2: 'FMT420_MEMORY_SOURCE_SEL_FMT2', + 3: 'FMT420_MEMORY_SOURCE_SEL_FMT3', + 4: 'FMT420_MEMORY_SOURCE_SEL_FMT4', + 5: 'FMT420_MEMORY_SOURCE_SEL_FMT5', + 6: 'FMT420_MEMORY_SOURCE_SEL_FMT_RESERVED', +} +FMT420_MEMORY_SOURCE_SEL_FMT0 = 0 +FMT420_MEMORY_SOURCE_SEL_FMT1 = 1 +FMT420_MEMORY_SOURCE_SEL_FMT2 = 2 +FMT420_MEMORY_SOURCE_SEL_FMT3 = 3 +FMT420_MEMORY_SOURCE_SEL_FMT4 = 4 +FMT420_MEMORY_SOURCE_SEL_FMT5 = 5 +FMT420_MEMORY_SOURCE_SEL_FMT_RESERVED = 6 +FMT420_MEMORY_SOURCE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_GO' +DOUT_I2C_CONTROL_GO__enumvalues = { + 0: 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 1: 'DOUT_I2C_CONTROL_START_TRANSFER', +} +DOUT_I2C_CONTROL_STOP_TRANSFER = 0 +DOUT_I2C_CONTROL_START_TRANSFER = 1 +DOUT_I2C_CONTROL_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SOFT_RESET' +DOUT_I2C_CONTROL_SOFT_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 1: 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', +} +DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER = 0 +DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER = 1 +DOUT_I2C_CONTROL_SOFT_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SEND_RESET' +DOUT_I2C_CONTROL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 1: 'DOUT_I2C_CONTROL__SEND_RESET', +} +DOUT_I2C_CONTROL__NOT_SEND_RESET = 0 +DOUT_I2C_CONTROL__SEND_RESET = 1 +DOUT_I2C_CONTROL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_SW_STATUS_RESET' +DOUT_I2C_CONTROL_SW_STATUS_RESET__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 1: 'DOUT_I2C_CONTROL_RESET_SW_STATUS', +} +DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS = 0 +DOUT_I2C_CONTROL_RESET_SW_STATUS = 1 +DOUT_I2C_CONTROL_SW_STATUS_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DDC_SELECT' +DOUT_I2C_CONTROL_DDC_SELECT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_SELECT_DDC1', + 1: 'DOUT_I2C_CONTROL_SELECT_DDC2', + 2: 'DOUT_I2C_CONTROL_SELECT_DDC3', + 3: 'DOUT_I2C_CONTROL_SELECT_DDC4', + 4: 'DOUT_I2C_CONTROL_SELECT_DDC5', + 5: 'DOUT_I2C_CONTROL_SELECT_DDC6', + 6: 'DOUT_I2C_CONTROL_SELECT_DDCVGA', +} +DOUT_I2C_CONTROL_SELECT_DDC1 = 0 +DOUT_I2C_CONTROL_SELECT_DDC2 = 1 +DOUT_I2C_CONTROL_SELECT_DDC3 = 2 +DOUT_I2C_CONTROL_SELECT_DDC4 = 3 +DOUT_I2C_CONTROL_SELECT_DDC5 = 4 +DOUT_I2C_CONTROL_SELECT_DDC6 = 5 +DOUT_I2C_CONTROL_SELECT_DDCVGA = 6 +DOUT_I2C_CONTROL_DDC_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_TRANSACTION_COUNT' +DOUT_I2C_CONTROL_TRANSACTION_COUNT__enumvalues = { + 0: 'DOUT_I2C_CONTROL_TRANS0', + 1: 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 2: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 3: 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', +} +DOUT_I2C_CONTROL_TRANS0 = 0 +DOUT_I2C_CONTROL_TRANS0_TRANS1 = 1 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2 = 2 +DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3 = 3 +DOUT_I2C_CONTROL_TRANSACTION_COUNT = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_CONTROL_DBG_REF_SEL' +DOUT_I2C_CONTROL_DBG_REF_SEL__enumvalues = { + 0: 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 1: 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', +} +DOUT_I2C_CONTROL_NORMAL_DEBUG = 0 +DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG = 1 +DOUT_I2C_CONTROL_DBG_REF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_SW_PRIORITY' +DOUT_I2C_ARBITRATION_SW_PRIORITY__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 1: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 2: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 3: 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', +} +DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL = 0 +DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH = 1 +DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED = 2 +DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED = 3 +DOUT_I2C_ARBITRATION_SW_PRIORITY = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO' +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 1: 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', +} +DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED = 0 +DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED = 1 +DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_ABORT_XFER' +DOUT_I2C_ARBITRATION_ABORT_XFER__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 1: 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', +} +DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER = 0 +DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER = 1 +DOUT_I2C_ARBITRATION_ABORT_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ' +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 1: 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', +} +DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ = 0 +DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ = 1 +DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG' +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG__enumvalues = { + 0: 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 1: 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', +} +DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG = 0 +DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG = 1 +DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_ACK' +DOUT_I2C_ACK__enumvalues = { + 0: 'DOUT_I2C_NO_ACK', + 1: 'DOUT_I2C_ACK_TO_CLEAN', +} +DOUT_I2C_NO_ACK = 0 +DOUT_I2C_ACK_TO_CLEAN = 1 +DOUT_I2C_ACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SPEED_THRESHOLD' +DOUT_I2C_DDC_SPEED_THRESHOLD__enumvalues = { + 0: 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 1: 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 2: 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 3: 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', +} +DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO = 0 +DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE = 1 +DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE = 2 +DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE = 3 +DOUT_I2C_DDC_SPEED_THRESHOLD = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL' +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 1: 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', +} +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS = 0 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS = 1 +DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE' +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 1: 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', +} +DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT = 0 +DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT = 1 +DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN' +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN__enumvalues = { + 0: 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 1: 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', +} +DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR = 0 +DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL = 1 +DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_TRANSACTION_STOP_ON_NACK' +DOUT_I2C_TRANSACTION_STOP_ON_NACK__enumvalues = { + 0: 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 1: 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', +} +DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS = 0 +DOUT_I2C_TRANSACTION_STOP_ALL_TRANS = 1 +DOUT_I2C_TRANSACTION_STOP_ON_NACK = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_DATA_INDEX_WRITE' +DOUT_I2C_DATA_INDEX_WRITE__enumvalues = { + 0: 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 1: 'DOUT_I2C_DATA__INDEX_WRITE', +} +DOUT_I2C_DATA__NOT_INDEX_WRITE = 0 +DOUT_I2C_DATA__INDEX_WRITE = 1 +DOUT_I2C_DATA_INDEX_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET' +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET__enumvalues = { + 0: 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 1: 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', +} +DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION = 0 +DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION = 1 +DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET = ctypes.c_uint32 # enum + +# values for enumeration 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE' +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__enumvalues = { + 0: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 1: 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', +} +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL = 0 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE = 1 +DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'FBC_IDLE_MASK_MASK_BITS' +FBC_IDLE_MASK_MASK_BITS__enumvalues = { + 0: 'FBC_IDLE_MASK_DISP_REG_UPDATE', + 1: 'FBC_IDLE_MASK_RESERVED1', + 2: 'FBC_IDLE_MASK_FBC_GRPH_COMP_EN', + 3: 'FBC_IDLE_MASK_FBC_MIN_COMPRESSION', + 4: 'FBC_IDLE_MASK_FBC_ALPHA_COMP_EN', + 5: 'FBC_IDLE_MASK_FBC_ZERO_ALPHA_CHUNK_SKIP_EN', + 6: 'FBC_IDLE_MASK_FBC_FORCE_COPY_TO_COMP_BUF', + 7: 'FBC_IDLE_MASK_RESERVED7', + 8: 'FBC_IDLE_MASK_RESERVED8', + 9: 'FBC_IDLE_MASK_RESERVED9', + 10: 'FBC_IDLE_MASK_RESERVED10', + 11: 'FBC_IDLE_MASK_RESERVED11', + 12: 'FBC_IDLE_MASK_RESERVED12', + 13: 'FBC_IDLE_MASK_RESERVED13', + 14: 'FBC_IDLE_MASK_RESERVED14', + 15: 'FBC_IDLE_MASK_RESERVED15', + 16: 'FBC_IDLE_MASK_RESERVED16', + 17: 'FBC_IDLE_MASK_RESERVED17', + 18: 'FBC_IDLE_MASK_RESERVED18', + 19: 'FBC_IDLE_MASK_RESERVED19', + 20: 'FBC_IDLE_MASK_RESERVED20', + 21: 'FBC_IDLE_MASK_RESERVED21', + 22: 'FBC_IDLE_MASK_RESERVED22', + 23: 'FBC_IDLE_MASK_RESERVED23', + 24: 'FBC_IDLE_MASK_MC_HIT_REGION_0', + 25: 'FBC_IDLE_MASK_MC_HIT_REGION_1', + 26: 'FBC_IDLE_MASK_MC_HIT_REGION_2', + 27: 'FBC_IDLE_MASK_MC_HIT_REGION_3', + 28: 'FBC_IDLE_MASK_MC_WRITE', + 29: 'FBC_IDLE_MASK_RESERVED29', + 30: 'FBC_IDLE_MASK_RESERVED30', + 31: 'FBC_IDLE_MASK_RESERVED31', +} +FBC_IDLE_MASK_DISP_REG_UPDATE = 0 +FBC_IDLE_MASK_RESERVED1 = 1 +FBC_IDLE_MASK_FBC_GRPH_COMP_EN = 2 +FBC_IDLE_MASK_FBC_MIN_COMPRESSION = 3 +FBC_IDLE_MASK_FBC_ALPHA_COMP_EN = 4 +FBC_IDLE_MASK_FBC_ZERO_ALPHA_CHUNK_SKIP_EN = 5 +FBC_IDLE_MASK_FBC_FORCE_COPY_TO_COMP_BUF = 6 +FBC_IDLE_MASK_RESERVED7 = 7 +FBC_IDLE_MASK_RESERVED8 = 8 +FBC_IDLE_MASK_RESERVED9 = 9 +FBC_IDLE_MASK_RESERVED10 = 10 +FBC_IDLE_MASK_RESERVED11 = 11 +FBC_IDLE_MASK_RESERVED12 = 12 +FBC_IDLE_MASK_RESERVED13 = 13 +FBC_IDLE_MASK_RESERVED14 = 14 +FBC_IDLE_MASK_RESERVED15 = 15 +FBC_IDLE_MASK_RESERVED16 = 16 +FBC_IDLE_MASK_RESERVED17 = 17 +FBC_IDLE_MASK_RESERVED18 = 18 +FBC_IDLE_MASK_RESERVED19 = 19 +FBC_IDLE_MASK_RESERVED20 = 20 +FBC_IDLE_MASK_RESERVED21 = 21 +FBC_IDLE_MASK_RESERVED22 = 22 +FBC_IDLE_MASK_RESERVED23 = 23 +FBC_IDLE_MASK_MC_HIT_REGION_0 = 24 +FBC_IDLE_MASK_MC_HIT_REGION_1 = 25 +FBC_IDLE_MASK_MC_HIT_REGION_2 = 26 +FBC_IDLE_MASK_MC_HIT_REGION_3 = 27 +FBC_IDLE_MASK_MC_WRITE = 28 +FBC_IDLE_MASK_RESERVED29 = 29 +FBC_IDLE_MASK_RESERVED30 = 30 +FBC_IDLE_MASK_RESERVED31 = 31 +FBC_IDLE_MASK_MASK_BITS = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL' +DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL__enumvalues = { + 0: 'DPCSRX_BPHY_PCS_RX0_CLK', + 1: 'DPCSRX_BPHY_PCS_RX1_CLK', + 2: 'DPCSRX_BPHY_PCS_RX2_CLK', + 3: 'DPCSRX_BPHY_PCS_RX3_CLK', +} +DPCSRX_BPHY_PCS_RX0_CLK = 0 +DPCSRX_BPHY_PCS_RX1_CLK = 1 +DPCSRX_BPHY_PCS_RX2_CLK = 2 +DPCSRX_BPHY_PCS_RX3_CLK = 3 +DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSRX_DBG_CFGCLK_SEL' +DPCSRX_DBG_CFGCLK_SEL__enumvalues = { + 0: 'DPCSRX_DBG_CFGCLK_SEL_DC_DPCS_INF', + 1: 'DPCSRX_DBG_CFGCLK_SEL_DPCS_BPHY_INF', + 2: 'DPCSRX_DBG_CFGCLK_SEL_CBUS_SLAVE', + 3: 'DPCSRX_DBG_CFGCLK_SEL_CBUS_MASTER', +} +DPCSRX_DBG_CFGCLK_SEL_DC_DPCS_INF = 0 +DPCSRX_DBG_CFGCLK_SEL_DPCS_BPHY_INF = 1 +DPCSRX_DBG_CFGCLK_SEL_CBUS_SLAVE = 2 +DPCSRX_DBG_CFGCLK_SEL_CBUS_MASTER = 3 +DPCSRX_DBG_CFGCLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSRX_RX_SYMCLK_SEL' +DPCSRX_RX_SYMCLK_SEL__enumvalues = { + 0: 'DPCSRX_DBG_RX_SYMCLK_SEL_OUT0', + 1: 'DPCSRX_DBG_RX_SYMCLK_SEL_OUT1', + 2: 'DPCSRX_DBG_RX_SYMCLK_SEL_INT', +} +DPCSRX_DBG_RX_SYMCLK_SEL_OUT0 = 0 +DPCSRX_DBG_RX_SYMCLK_SEL_OUT1 = 1 +DPCSRX_DBG_RX_SYMCLK_SEL_INT = 2 +DPCSRX_RX_SYMCLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSTX_DBG_CFGCLK_SEL' +DPCSTX_DBG_CFGCLK_SEL__enumvalues = { + 0: 'DPCSTX_DBG_CFGCLK_SEL_DC_DPCS_INF', + 1: 'DPCSTX_DBG_CFGCLK_SEL_DPCS_BPHY_INF', + 2: 'DPCSTX_DBG_CFGCLK_SEL_CBUS_SLAVE', + 3: 'DPCSTX_DBG_CFGCLK_SEL_CBUS_MASTER', +} +DPCSTX_DBG_CFGCLK_SEL_DC_DPCS_INF = 0 +DPCSTX_DBG_CFGCLK_SEL_DPCS_BPHY_INF = 1 +DPCSTX_DBG_CFGCLK_SEL_CBUS_SLAVE = 2 +DPCSTX_DBG_CFGCLK_SEL_CBUS_MASTER = 3 +DPCSTX_DBG_CFGCLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSTX_TX_SYMCLK_SEL' +DPCSTX_TX_SYMCLK_SEL__enumvalues = { + 0: 'DPCSTX_DBG_TX_SYMCLK_SEL_IN0', + 1: 'DPCSTX_DBG_TX_SYMCLK_SEL_IN1', + 2: 'DPCSTX_DBG_TX_SYMCLK_SEL_FIFO_WR', +} +DPCSTX_DBG_TX_SYMCLK_SEL_IN0 = 0 +DPCSTX_DBG_TX_SYMCLK_SEL_IN1 = 1 +DPCSTX_DBG_TX_SYMCLK_SEL_FIFO_WR = 2 +DPCSTX_TX_SYMCLK_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'DPCSTX_TX_SYMCLK_DIV2_SEL' +DPCSTX_TX_SYMCLK_DIV2_SEL__enumvalues = { + 0: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT0', + 1: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT1', + 2: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT2', + 3: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT3', + 4: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_FIFO_RD', + 5: 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_INT', +} +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT0 = 0 +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT1 = 1 +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT2 = 2 +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT3 = 3 +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_FIFO_RD = 4 +DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_INT = 5 +DPCSTX_TX_SYMCLK_DIV2_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceNumber' +SurfaceNumber__enumvalues = { + 0: 'NUMBER_UNORM', + 1: 'NUMBER_SNORM', + 2: 'NUMBER_USCALED', + 3: 'NUMBER_SSCALED', + 4: 'NUMBER_UINT', + 5: 'NUMBER_SINT', + 6: 'NUMBER_SRGB', + 7: 'NUMBER_FLOAT', +} +NUMBER_UNORM = 0 +NUMBER_SNORM = 1 +NUMBER_USCALED = 2 +NUMBER_SSCALED = 3 +NUMBER_UINT = 4 +NUMBER_SINT = 5 +NUMBER_SRGB = 6 +NUMBER_FLOAT = 7 +SurfaceNumber = ctypes.c_uint32 # enum + +# values for enumeration 'SurfaceSwap' +SurfaceSwap__enumvalues = { + 0: 'SWAP_STD', + 1: 'SWAP_ALT', + 2: 'SWAP_STD_REV', + 3: 'SWAP_ALT_REV', +} +SWAP_STD = 0 +SWAP_ALT = 1 +SWAP_STD_REV = 2 +SWAP_ALT_REV = 3 +SurfaceSwap = ctypes.c_uint32 # enum + +# values for enumeration 'CBMode' +CBMode__enumvalues = { + 0: 'CB_DISABLE', + 1: 'CB_NORMAL', + 2: 'CB_ELIMINATE_FAST_CLEAR', + 3: 'CB_RESOLVE', + 4: 'CB_DECOMPRESS', + 5: 'CB_FMASK_DECOMPRESS', + 6: 'CB_DCC_DECOMPRESS', +} +CB_DISABLE = 0 +CB_NORMAL = 1 +CB_ELIMINATE_FAST_CLEAR = 2 +CB_RESOLVE = 3 +CB_DECOMPRESS = 4 +CB_FMASK_DECOMPRESS = 5 +CB_DCC_DECOMPRESS = 6 +CBMode = ctypes.c_uint32 # enum + +# values for enumeration 'RoundMode' +RoundMode__enumvalues = { + 0: 'ROUND_BY_HALF', + 1: 'ROUND_TRUNCATE', +} +ROUND_BY_HALF = 0 +ROUND_TRUNCATE = 1 +RoundMode = ctypes.c_uint32 # enum + +# values for enumeration 'SourceFormat' +SourceFormat__enumvalues = { + 0: 'EXPORT_4C_32BPC', + 1: 'EXPORT_4C_16BPC', + 2: 'EXPORT_2C_32BPC_GR', + 3: 'EXPORT_2C_32BPC_AR', +} +EXPORT_4C_32BPC = 0 +EXPORT_4C_16BPC = 1 +EXPORT_2C_32BPC_GR = 2 +EXPORT_2C_32BPC_AR = 3 +SourceFormat = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOp' +BlendOp__enumvalues = { + 0: 'BLEND_ZERO', + 1: 'BLEND_ONE', + 2: 'BLEND_SRC_COLOR', + 3: 'BLEND_ONE_MINUS_SRC_COLOR', + 4: 'BLEND_SRC_ALPHA', + 5: 'BLEND_ONE_MINUS_SRC_ALPHA', + 6: 'BLEND_DST_ALPHA', + 7: 'BLEND_ONE_MINUS_DST_ALPHA', + 8: 'BLEND_DST_COLOR', + 9: 'BLEND_ONE_MINUS_DST_COLOR', + 10: 'BLEND_SRC_ALPHA_SATURATE', + 11: 'BLEND_BOTH_SRC_ALPHA', + 12: 'BLEND_BOTH_INV_SRC_ALPHA', + 13: 'BLEND_CONSTANT_COLOR', + 14: 'BLEND_ONE_MINUS_CONSTANT_COLOR', + 15: 'BLEND_SRC1_COLOR', + 16: 'BLEND_INV_SRC1_COLOR', + 17: 'BLEND_SRC1_ALPHA', + 18: 'BLEND_INV_SRC1_ALPHA', + 19: 'BLEND_CONSTANT_ALPHA', + 20: 'BLEND_ONE_MINUS_CONSTANT_ALPHA', +} +BLEND_ZERO = 0 +BLEND_ONE = 1 +BLEND_SRC_COLOR = 2 +BLEND_ONE_MINUS_SRC_COLOR = 3 +BLEND_SRC_ALPHA = 4 +BLEND_ONE_MINUS_SRC_ALPHA = 5 +BLEND_DST_ALPHA = 6 +BLEND_ONE_MINUS_DST_ALPHA = 7 +BLEND_DST_COLOR = 8 +BLEND_ONE_MINUS_DST_COLOR = 9 +BLEND_SRC_ALPHA_SATURATE = 10 +BLEND_BOTH_SRC_ALPHA = 11 +BLEND_BOTH_INV_SRC_ALPHA = 12 +BLEND_CONSTANT_COLOR = 13 +BLEND_ONE_MINUS_CONSTANT_COLOR = 14 +BLEND_SRC1_COLOR = 15 +BLEND_INV_SRC1_COLOR = 16 +BLEND_SRC1_ALPHA = 17 +BLEND_INV_SRC1_ALPHA = 18 +BLEND_CONSTANT_ALPHA = 19 +BLEND_ONE_MINUS_CONSTANT_ALPHA = 20 +BlendOp = ctypes.c_uint32 # enum +GL__ZERO = BLEND_ZERO # macro +GL__ONE = BLEND_ONE # macro +GL__SRC_COLOR = BLEND_SRC_COLOR # macro +GL__ONE_MINUS_SRC_COLOR = BLEND_ONE_MINUS_SRC_COLOR # macro +GL__DST_COLOR = BLEND_DST_COLOR # macro +GL__ONE_MINUS_DST_COLOR = BLEND_ONE_MINUS_DST_COLOR # macro +GL__SRC_ALPHA = BLEND_SRC_ALPHA # macro +GL__ONE_MINUS_SRC_ALPHA = BLEND_ONE_MINUS_SRC_ALPHA # macro +GL__DST_ALPHA = BLEND_DST_ALPHA # macro +GL__ONE_MINUS_DST_ALPHA = BLEND_ONE_MINUS_DST_ALPHA # macro +GL__SRC_ALPHA_SATURATE = BLEND_SRC_ALPHA_SATURATE # macro +GL__CONSTANT_COLOR = BLEND_CONSTANT_COLOR # macro +GL__ONE_MINUS_CONSTANT_COLOR = BLEND_ONE_MINUS_CONSTANT_COLOR # macro +GL__CONSTANT_ALPHA = BLEND_CONSTANT_ALPHA # macro +GL__ONE_MINUS_CONSTANT_ALPHA = BLEND_ONE_MINUS_CONSTANT_ALPHA # macro + +# values for enumeration 'CombFunc' +CombFunc__enumvalues = { + 0: 'COMB_DST_PLUS_SRC', + 1: 'COMB_SRC_MINUS_DST', + 2: 'COMB_MIN_DST_SRC', + 3: 'COMB_MAX_DST_SRC', + 4: 'COMB_DST_MINUS_SRC', +} +COMB_DST_PLUS_SRC = 0 +COMB_SRC_MINUS_DST = 1 +COMB_MIN_DST_SRC = 2 +COMB_MAX_DST_SRC = 3 +COMB_DST_MINUS_SRC = 4 +CombFunc = ctypes.c_uint32 # enum + +# values for enumeration 'BlendOpt' +BlendOpt__enumvalues = { + 0: 'FORCE_OPT_AUTO', + 1: 'FORCE_OPT_DISABLE', + 2: 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 3: 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 4: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 5: 'FORCE_OPT_ENABLE_IF_SRC_A_1', + 6: 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', + 7: 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', +} +FORCE_OPT_AUTO = 0 +FORCE_OPT_DISABLE = 1 +FORCE_OPT_ENABLE_IF_SRC_A_0 = 2 +FORCE_OPT_ENABLE_IF_SRC_RGB_0 = 3 +FORCE_OPT_ENABLE_IF_SRC_ARGB_0 = 4 +FORCE_OPT_ENABLE_IF_SRC_A_1 = 5 +FORCE_OPT_ENABLE_IF_SRC_RGB_1 = 6 +FORCE_OPT_ENABLE_IF_SRC_ARGB_1 = 7 +BlendOpt = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskCode' +CmaskCode__enumvalues = { + 0: 'CMASK_CLR00_F0', + 1: 'CMASK_CLR00_F1', + 2: 'CMASK_CLR00_F2', + 3: 'CMASK_CLR00_FX', + 4: 'CMASK_CLR01_F0', + 5: 'CMASK_CLR01_F1', + 6: 'CMASK_CLR01_F2', + 7: 'CMASK_CLR01_FX', + 8: 'CMASK_CLR10_F0', + 9: 'CMASK_CLR10_F1', + 10: 'CMASK_CLR10_F2', + 11: 'CMASK_CLR10_FX', + 12: 'CMASK_CLR11_F0', + 13: 'CMASK_CLR11_F1', + 14: 'CMASK_CLR11_F2', + 15: 'CMASK_CLR11_FX', +} +CMASK_CLR00_F0 = 0 +CMASK_CLR00_F1 = 1 +CMASK_CLR00_F2 = 2 +CMASK_CLR00_FX = 3 +CMASK_CLR01_F0 = 4 +CMASK_CLR01_F1 = 5 +CMASK_CLR01_F2 = 6 +CMASK_CLR01_FX = 7 +CMASK_CLR10_F0 = 8 +CMASK_CLR10_F1 = 9 +CMASK_CLR10_F2 = 10 +CMASK_CLR10_FX = 11 +CMASK_CLR11_F0 = 12 +CMASK_CLR11_F1 = 13 +CMASK_CLR11_F2 = 14 +CMASK_CLR11_FX = 15 +CmaskCode = ctypes.c_uint32 # enum + +# values for enumeration 'CmaskAddr' +CmaskAddr__enumvalues = { + 0: 'CMASK_ADDR_TILED', + 1: 'CMASK_ADDR_LINEAR', + 2: 'CMASK_ADDR_COMPATIBLE', +} +CMASK_ADDR_TILED = 0 +CMASK_ADDR_LINEAR = 1 +CMASK_ADDR_COMPATIBLE = 2 +CmaskAddr = ctypes.c_uint32 # enum + +# values for enumeration 'MemArbMode' +MemArbMode__enumvalues = { + 0: 'MEM_ARB_MODE_FIXED', + 1: 'MEM_ARB_MODE_AGE', + 2: 'MEM_ARB_MODE_WEIGHT', + 3: 'MEM_ARB_MODE_BOTH', +} +MEM_ARB_MODE_FIXED = 0 +MEM_ARB_MODE_AGE = 1 +MEM_ARB_MODE_WEIGHT = 2 +MEM_ARB_MODE_BOTH = 3 +MemArbMode = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfSel' +CBPerfSel__enumvalues = { + 0: 'CB_PERF_SEL_NONE', + 1: 'CB_PERF_SEL_BUSY', + 2: 'CB_PERF_SEL_CORE_SCLK_VLD', + 3: 'CB_PERF_SEL_REG_SCLK0_VLD', + 4: 'CB_PERF_SEL_REG_SCLK1_VLD', + 5: 'CB_PERF_SEL_DRAWN_QUAD', + 6: 'CB_PERF_SEL_DRAWN_PIXEL', + 7: 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', + 8: 'CB_PERF_SEL_DRAWN_TILE', + 9: 'CB_PERF_SEL_DB_CB_TILE_VALID_READY', + 10: 'CB_PERF_SEL_DB_CB_TILE_VALID_READYB', + 11: 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READY', + 12: 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB', + 13: 'CB_PERF_SEL_CM_FC_TILE_VALID_READY', + 14: 'CB_PERF_SEL_CM_FC_TILE_VALID_READYB', + 15: 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READY', + 16: 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB', + 17: 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY', + 18: 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB', + 19: 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READY', + 20: 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB', + 21: 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY', + 22: 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB', + 23: 'CB_PERF_SEL_LQUAD_NO_TILE', + 24: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R', + 25: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR', + 26: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR', + 27: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR', + 28: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR', + 29: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR', + 30: 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR', + 31: 'CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT', + 32: 'CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID', + 33: 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK', + 34: 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK', + 35: 'CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL', + 36: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY', + 37: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB', + 38: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY', + 39: 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB', + 40: 'CB_PERF_SEL_FOP_IN_VALID_READY', + 41: 'CB_PERF_SEL_FOP_IN_VALID_READYB', + 42: 'CB_PERF_SEL_FOP_IN_VALIDB_READY', + 43: 'CB_PERF_SEL_FOP_IN_VALIDB_READYB', + 44: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY', + 45: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB', + 46: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY', + 47: 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB', + 48: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY', + 49: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB', + 50: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY', + 51: 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB', + 52: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY', + 53: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB', + 54: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY', + 55: 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB', + 56: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY', + 57: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB', + 58: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY', + 59: 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB', + 60: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY', + 61: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB', + 62: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY', + 63: 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB', + 64: 'CB_PERF_SEL_CC_BC_CS_FRAG_VALID', + 65: 'CB_PERF_SEL_CM_CACHE_HIT', + 66: 'CB_PERF_SEL_CM_CACHE_TAG_MISS', + 67: 'CB_PERF_SEL_CM_CACHE_SECTOR_MISS', + 68: 'CB_PERF_SEL_CM_CACHE_REEVICTION_STALL', + 69: 'CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 70: 'CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL', + 71: 'CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 72: 'CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL', + 73: 'CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL', + 74: 'CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL', + 75: 'CB_PERF_SEL_CM_CACHE_STALL', + 76: 'CB_PERF_SEL_CM_CACHE_FLUSH', + 77: 'CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED', + 78: 'CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED', + 79: 'CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED', + 80: 'CB_PERF_SEL_FC_CACHE_HIT', + 81: 'CB_PERF_SEL_FC_CACHE_TAG_MISS', + 82: 'CB_PERF_SEL_FC_CACHE_SECTOR_MISS', + 83: 'CB_PERF_SEL_FC_CACHE_REEVICTION_STALL', + 84: 'CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 85: 'CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL', + 86: 'CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 87: 'CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL', + 88: 'CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL', + 89: 'CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL', + 90: 'CB_PERF_SEL_FC_CACHE_STALL', + 91: 'CB_PERF_SEL_FC_CACHE_FLUSH', + 92: 'CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED', + 93: 'CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED', + 94: 'CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED', + 95: 'CB_PERF_SEL_CC_CACHE_HIT', + 96: 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 97: 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', + 98: 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 99: 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 100: 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 101: 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 102: 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 103: 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 104: 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 105: 'CB_PERF_SEL_CC_CACHE_STALL', + 106: 'CB_PERF_SEL_CC_CACHE_FLUSH', + 107: 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 108: 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 109: 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 110: 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 111: 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 112: 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY', + 113: 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB', + 114: 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY', + 115: 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB', + 116: 'CB_PERF_SEL_CM_MC_WRITE_REQUEST', + 117: 'CB_PERF_SEL_FC_MC_WRITE_REQUEST', + 118: 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 119: 'CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT', + 120: 'CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT', + 121: 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 122: 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY', + 123: 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB', + 124: 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY', + 125: 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB', + 126: 'CB_PERF_SEL_CM_MC_READ_REQUEST', + 127: 'CB_PERF_SEL_FC_MC_READ_REQUEST', + 128: 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 129: 'CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT', + 130: 'CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT', + 131: 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 132: 'CB_PERF_SEL_CM_TQ_FULL', + 133: 'CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL', + 134: 'CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL', + 135: 'CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL', + 136: 'CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 137: 'CB_PERF_SEL_FOP_FMASK_RAW_STALL', + 138: 'CB_PERF_SEL_FOP_FMASK_BYPASS_STALL', + 139: 'CB_PERF_SEL_CC_SF_FULL', + 140: 'CB_PERF_SEL_CC_RB_FULL', + 141: 'CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL', + 142: 'CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL', + 143: 'CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL', + 144: 'CB_PERF_SEL_EVENT', + 145: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 146: 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 147: 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 148: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 149: 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 150: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 151: 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 152: 'CB_PERF_SEL_CC_SURFACE_SYNC', + 153: 'CB_PERF_SEL_CMASK_READ_DATA_0xC', + 154: 'CB_PERF_SEL_CMASK_READ_DATA_0xD', + 155: 'CB_PERF_SEL_CMASK_READ_DATA_0xE', + 156: 'CB_PERF_SEL_CMASK_READ_DATA_0xF', + 157: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xC', + 158: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xD', + 159: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xE', + 160: 'CB_PERF_SEL_CMASK_WRITE_DATA_0xF', + 161: 'CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT', + 162: 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 163: 'CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT', + 164: 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE', + 165: 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 166: 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 167: 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 168: 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 169: 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 170: 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 171: 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 172: 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE', + 173: 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE', + 174: 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE', + 175: 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE', + 176: 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE', + 177: 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE', + 178: 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE', + 179: 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE', + 180: 'CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT', + 181: 'CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS', + 182: 'CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS', + 183: 'CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS', + 184: 'CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS', + 185: 'CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS', + 186: 'CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS', + 187: 'CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT', + 188: 'CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS', + 189: 'CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS', + 190: 'CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS', + 191: 'CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS', + 192: 'CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS', + 193: 'CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS', + 194: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_0', + 195: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_1', + 196: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_2', + 197: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_3', + 198: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_4', + 199: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_5', + 200: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_6', + 201: 'CB_PERF_SEL_QUAD_READS_FRAGMENT_7', + 202: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0', + 203: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1', + 204: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2', + 205: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3', + 206: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4', + 207: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5', + 208: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6', + 209: 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7', + 210: 'CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST', + 211: 'CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS', + 212: 'CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS', + 213: 'CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 214: 'CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 215: 'CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED', + 216: 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', + 217: 'CB_PERF_SEL_DRAWN_BUSY', + 218: 'CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY', + 219: 'CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY', + 220: 'CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY', + 221: 'CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY', + 222: 'CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED', + 223: 'CB_PERF_SEL_FC_SEQUENCER_CLEAR', + 224: 'CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR', + 225: 'CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS', + 226: 'CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE', + 227: 'CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL', + 228: 'CB_PERF_SEL_FC_DOC_IS_STALLED', + 229: 'CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED', + 230: 'CB_PERF_SEL_FC_DOC_MRTS_COMBINED', + 231: 'CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS', + 232: 'CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT', + 233: 'CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS', + 234: 'CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT', + 235: 'CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL', + 236: 'CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR', + 237: 'CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS', + 238: 'CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS', + 239: 'CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS', + 240: 'CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS', + 241: 'CB_PERF_SEL_FC_DCC_CACHE_HIT', + 242: 'CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS', + 243: 'CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS', + 244: 'CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL', + 245: 'CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 246: 'CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 247: 'CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 248: 'CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL', + 249: 'CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL', + 250: 'CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL', + 251: 'CB_PERF_SEL_FC_DCC_CACHE_STALL', + 252: 'CB_PERF_SEL_FC_DCC_CACHE_FLUSH', + 253: 'CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED', + 254: 'CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED', + 255: 'CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 256: 'CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT', + 257: 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST', + 258: 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT', + 259: 'CB_PERF_SEL_FC_MC_DCC_READ_REQUEST', + 260: 'CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT', + 261: 'CB_PERF_SEL_CC_DCC_RDREQ_STALL', + 262: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN', + 263: 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT', + 264: 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN', + 265: 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT', + 266: 'CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR', + 267: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1', + 268: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2', + 269: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 270: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1', + 271: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1', + 272: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2', + 273: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1', + 274: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 275: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 276: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1', + 277: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2', + 278: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2', + 279: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2', + 280: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 281: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1', + 282: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1', + 283: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2', + 284: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3', + 285: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4', + 286: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1', + 287: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2', + 288: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3', + 289: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4', + 290: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1', + 291: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2', + 292: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3', + 293: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4', + 294: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1', + 295: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2', + 296: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3', + 297: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1', + 298: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2', + 299: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3', + 300: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4', + 301: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1', + 302: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2', + 303: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3', + 304: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4', + 305: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1', + 306: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2', + 307: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3', + 308: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4', + 309: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1', + 310: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2', + 311: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3', + 312: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1', + 313: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1', + 314: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1', + 315: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1', + 316: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1', + 317: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1', + 318: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1', + 319: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1', + 320: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2', + 321: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2', + 322: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2', + 323: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2', + 324: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2', + 325: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2', + 326: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2', + 327: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1', + 328: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1', + 329: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1', + 330: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1', + 331: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2', + 332: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2', + 333: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2', + 334: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2', + 335: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 336: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2', + 337: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2', + 338: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 339: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1', + 340: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1', + 341: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1', + 342: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1', + 343: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2', + 344: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3', + 345: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4', + 346: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5', + 347: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6', + 348: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0', + 349: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1', + 350: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1', + 351: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2', + 352: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3', + 353: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4', + 354: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5', + 355: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0', + 356: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1', + 357: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1', + 358: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1', + 359: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1', + 360: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1', + 361: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1', + 362: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1', + 363: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1', + 364: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1', + 365: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2', + 366: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2', + 367: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2', + 368: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2', + 369: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2', + 370: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2', + 371: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2', + 372: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1', + 373: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2', + 374: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3', + 375: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4', + 376: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5', + 377: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6', + 378: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7', + 379: 'CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED', + 380: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1', + 381: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1', + 382: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2', + 383: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3', + 384: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1', + 385: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2', + 386: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3', + 387: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4', + 388: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5', + 389: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1', + 390: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2', + 391: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3', + 392: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4', + 393: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5', + 394: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6', + 395: 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7', + 396: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 397: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 398: 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 399: 'CB_PERF_SEL_RBP_SPLIT_MICROTILE', + 400: 'CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK', + 401: 'CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK', + 402: 'CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING', + 403: 'CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS', + 404: 'CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD', +} +CB_PERF_SEL_NONE = 0 +CB_PERF_SEL_BUSY = 1 +CB_PERF_SEL_CORE_SCLK_VLD = 2 +CB_PERF_SEL_REG_SCLK0_VLD = 3 +CB_PERF_SEL_REG_SCLK1_VLD = 4 +CB_PERF_SEL_DRAWN_QUAD = 5 +CB_PERF_SEL_DRAWN_PIXEL = 6 +CB_PERF_SEL_DRAWN_QUAD_FRAGMENT = 7 +CB_PERF_SEL_DRAWN_TILE = 8 +CB_PERF_SEL_DB_CB_TILE_VALID_READY = 9 +CB_PERF_SEL_DB_CB_TILE_VALID_READYB = 10 +CB_PERF_SEL_DB_CB_TILE_VALIDB_READY = 11 +CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB = 12 +CB_PERF_SEL_CM_FC_TILE_VALID_READY = 13 +CB_PERF_SEL_CM_FC_TILE_VALID_READYB = 14 +CB_PERF_SEL_CM_FC_TILE_VALIDB_READY = 15 +CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB = 16 +CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY = 17 +CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB = 18 +CB_PERF_SEL_DB_CB_LQUAD_VALID_READY = 19 +CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB = 20 +CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY = 21 +CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB = 22 +CB_PERF_SEL_LQUAD_NO_TILE = 23 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R = 24 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR = 25 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR = 26 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR = 27 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR = 28 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR = 29 +CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR = 30 +CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT = 31 +CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID = 32 +CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK = 33 +CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK = 34 +CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL = 35 +CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY = 36 +CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB = 37 +CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY = 38 +CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB = 39 +CB_PERF_SEL_FOP_IN_VALID_READY = 40 +CB_PERF_SEL_FOP_IN_VALID_READYB = 41 +CB_PERF_SEL_FOP_IN_VALIDB_READY = 42 +CB_PERF_SEL_FOP_IN_VALIDB_READYB = 43 +CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY = 44 +CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB = 45 +CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY = 46 +CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB = 47 +CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY = 48 +CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB = 49 +CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY = 50 +CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB = 51 +CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY = 52 +CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB = 53 +CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY = 54 +CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB = 55 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY = 56 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB = 57 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY = 58 +CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB = 59 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY = 60 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB = 61 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY = 62 +CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB = 63 +CB_PERF_SEL_CC_BC_CS_FRAG_VALID = 64 +CB_PERF_SEL_CM_CACHE_HIT = 65 +CB_PERF_SEL_CM_CACHE_TAG_MISS = 66 +CB_PERF_SEL_CM_CACHE_SECTOR_MISS = 67 +CB_PERF_SEL_CM_CACHE_REEVICTION_STALL = 68 +CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 69 +CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL = 70 +CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 71 +CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL = 72 +CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL = 73 +CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL = 74 +CB_PERF_SEL_CM_CACHE_STALL = 75 +CB_PERF_SEL_CM_CACHE_FLUSH = 76 +CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED = 77 +CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED = 78 +CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED = 79 +CB_PERF_SEL_FC_CACHE_HIT = 80 +CB_PERF_SEL_FC_CACHE_TAG_MISS = 81 +CB_PERF_SEL_FC_CACHE_SECTOR_MISS = 82 +CB_PERF_SEL_FC_CACHE_REEVICTION_STALL = 83 +CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 84 +CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL = 85 +CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 86 +CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL = 87 +CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL = 88 +CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL = 89 +CB_PERF_SEL_FC_CACHE_STALL = 90 +CB_PERF_SEL_FC_CACHE_FLUSH = 91 +CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED = 92 +CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED = 93 +CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED = 94 +CB_PERF_SEL_CC_CACHE_HIT = 95 +CB_PERF_SEL_CC_CACHE_TAG_MISS = 96 +CB_PERF_SEL_CC_CACHE_SECTOR_MISS = 97 +CB_PERF_SEL_CC_CACHE_REEVICTION_STALL = 98 +CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 99 +CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL = 100 +CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 101 +CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL = 102 +CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL = 103 +CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL = 104 +CB_PERF_SEL_CC_CACHE_STALL = 105 +CB_PERF_SEL_CC_CACHE_FLUSH = 106 +CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED = 107 +CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED = 108 +CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED = 109 +CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION = 110 +CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC = 111 +CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY = 112 +CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB = 113 +CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY = 114 +CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB = 115 +CB_PERF_SEL_CM_MC_WRITE_REQUEST = 116 +CB_PERF_SEL_FC_MC_WRITE_REQUEST = 117 +CB_PERF_SEL_CC_MC_WRITE_REQUEST = 118 +CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT = 119 +CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT = 120 +CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT = 121 +CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY = 122 +CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB = 123 +CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY = 124 +CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB = 125 +CB_PERF_SEL_CM_MC_READ_REQUEST = 126 +CB_PERF_SEL_FC_MC_READ_REQUEST = 127 +CB_PERF_SEL_CC_MC_READ_REQUEST = 128 +CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT = 129 +CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT = 130 +CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT = 131 +CB_PERF_SEL_CM_TQ_FULL = 132 +CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL = 133 +CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL = 134 +CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL = 135 +CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL = 136 +CB_PERF_SEL_FOP_FMASK_RAW_STALL = 137 +CB_PERF_SEL_FOP_FMASK_BYPASS_STALL = 138 +CB_PERF_SEL_CC_SF_FULL = 139 +CB_PERF_SEL_CC_RB_FULL = 140 +CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL = 141 +CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL = 142 +CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL = 143 +CB_PERF_SEL_EVENT = 144 +CB_PERF_SEL_EVENT_CACHE_FLUSH_TS = 145 +CB_PERF_SEL_EVENT_CONTEXT_DONE = 146 +CB_PERF_SEL_EVENT_CACHE_FLUSH = 147 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT = 148 +CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT = 149 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS = 150 +CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META = 151 +CB_PERF_SEL_CC_SURFACE_SYNC = 152 +CB_PERF_SEL_CMASK_READ_DATA_0xC = 153 +CB_PERF_SEL_CMASK_READ_DATA_0xD = 154 +CB_PERF_SEL_CMASK_READ_DATA_0xE = 155 +CB_PERF_SEL_CMASK_READ_DATA_0xF = 156 +CB_PERF_SEL_CMASK_WRITE_DATA_0xC = 157 +CB_PERF_SEL_CMASK_WRITE_DATA_0xD = 158 +CB_PERF_SEL_CMASK_WRITE_DATA_0xE = 159 +CB_PERF_SEL_CMASK_WRITE_DATA_0xF = 160 +CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT = 161 +CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT = 162 +CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT = 163 +CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE = 164 +CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE = 165 +CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE = 166 +CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE = 167 +CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE = 168 +CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE = 169 +CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE = 170 +CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE = 171 +CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE = 172 +CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE = 173 +CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE = 174 +CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE = 175 +CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE = 176 +CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE = 177 +CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE = 178 +CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE = 179 +CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT = 180 +CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS = 181 +CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS = 182 +CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS = 183 +CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS = 184 +CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS = 185 +CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS = 186 +CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT = 187 +CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS = 188 +CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS = 189 +CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS = 190 +CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS = 191 +CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS = 192 +CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS = 193 +CB_PERF_SEL_QUAD_READS_FRAGMENT_0 = 194 +CB_PERF_SEL_QUAD_READS_FRAGMENT_1 = 195 +CB_PERF_SEL_QUAD_READS_FRAGMENT_2 = 196 +CB_PERF_SEL_QUAD_READS_FRAGMENT_3 = 197 +CB_PERF_SEL_QUAD_READS_FRAGMENT_4 = 198 +CB_PERF_SEL_QUAD_READS_FRAGMENT_5 = 199 +CB_PERF_SEL_QUAD_READS_FRAGMENT_6 = 200 +CB_PERF_SEL_QUAD_READS_FRAGMENT_7 = 201 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0 = 202 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1 = 203 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2 = 204 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3 = 205 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4 = 206 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5 = 207 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6 = 208 +CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7 = 209 +CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST = 210 +CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS = 211 +CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS = 212 +CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED = 213 +CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED = 214 +CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED = 215 +CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST = 216 +CB_PERF_SEL_DRAWN_BUSY = 217 +CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY = 218 +CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY = 219 +CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY = 220 +CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY = 221 +CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED = 222 +CB_PERF_SEL_FC_SEQUENCER_CLEAR = 223 +CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR = 224 +CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS = 225 +CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE = 226 +CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL = 227 +CB_PERF_SEL_FC_DOC_IS_STALLED = 228 +CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED = 229 +CB_PERF_SEL_FC_DOC_MRTS_COMBINED = 230 +CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS = 231 +CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT = 232 +CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS = 233 +CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT = 234 +CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL = 235 +CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR = 236 +CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS = 237 +CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS = 238 +CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS = 239 +CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS = 240 +CB_PERF_SEL_FC_DCC_CACHE_HIT = 241 +CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS = 242 +CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS = 243 +CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL = 244 +CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL = 245 +CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL = 246 +CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL = 247 +CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL = 248 +CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL = 249 +CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL = 250 +CB_PERF_SEL_FC_DCC_CACHE_STALL = 251 +CB_PERF_SEL_FC_DCC_CACHE_FLUSH = 252 +CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED = 253 +CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED = 254 +CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED = 255 +CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT = 256 +CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST = 257 +CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT = 258 +CB_PERF_SEL_FC_MC_DCC_READ_REQUEST = 259 +CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT = 260 +CB_PERF_SEL_CC_DCC_RDREQ_STALL = 261 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN = 262 +CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT = 263 +CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN = 264 +CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT = 265 +CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR = 266 +CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1 = 267 +CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2 = 268 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 269 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1 = 270 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1 = 271 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2 = 272 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1 = 273 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 274 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 275 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1 = 276 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2 = 277 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2 = 278 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2 = 279 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 280 +CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1 = 281 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1 = 282 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2 = 283 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3 = 284 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4 = 285 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1 = 286 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2 = 287 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3 = 288 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4 = 289 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1 = 290 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2 = 291 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3 = 292 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4 = 293 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1 = 294 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2 = 295 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3 = 296 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1 = 297 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2 = 298 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3 = 299 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4 = 300 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1 = 301 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2 = 302 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3 = 303 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4 = 304 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1 = 305 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2 = 306 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3 = 307 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4 = 308 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1 = 309 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2 = 310 +CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3 = 311 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1 = 312 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1 = 313 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1 = 314 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1 = 315 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1 = 316 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1 = 317 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1 = 318 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1 = 319 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2 = 320 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2 = 321 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2 = 322 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2 = 323 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2 = 324 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2 = 325 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2 = 326 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1 = 327 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1 = 328 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1 = 329 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1 = 330 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2 = 331 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2 = 332 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2 = 333 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2 = 334 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2 = 335 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2 = 336 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2 = 337 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1 = 338 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1 = 339 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1 = 340 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1 = 341 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1 = 342 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2 = 343 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3 = 344 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4 = 345 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5 = 346 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6 = 347 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0 = 348 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1 = 349 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1 = 350 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2 = 351 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3 = 352 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4 = 353 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5 = 354 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0 = 355 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1 = 356 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1 = 357 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1 = 358 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1 = 359 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1 = 360 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1 = 361 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1 = 362 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1 = 363 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1 = 364 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2 = 365 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2 = 366 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2 = 367 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2 = 368 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2 = 369 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2 = 370 +CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2 = 371 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1 = 372 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2 = 373 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3 = 374 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4 = 375 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5 = 376 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6 = 377 +CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7 = 378 +CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED = 379 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1 = 380 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1 = 381 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2 = 382 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3 = 383 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1 = 384 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2 = 385 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3 = 386 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4 = 387 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5 = 388 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1 = 389 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2 = 390 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3 = 391 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4 = 392 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5 = 393 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6 = 394 +CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7 = 395 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH = 396 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT = 397 +CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT = 398 +CB_PERF_SEL_RBP_SPLIT_MICROTILE = 399 +CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK = 400 +CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK = 401 +CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING = 402 +CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS = 403 +CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD = 404 +CBPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfOpFilterSel' +CBPerfOpFilterSel__enumvalues = { + 0: 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 1: 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 2: 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 3: 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 4: 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 5: 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', +} +CB_PERF_OP_FILTER_SEL_WRITE_ONLY = 0 +CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION = 1 +CB_PERF_OP_FILTER_SEL_RESOLVE = 2 +CB_PERF_OP_FILTER_SEL_DECOMPRESS = 3 +CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS = 4 +CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR = 5 +CBPerfOpFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'CBPerfClearFilterSel' +CBPerfClearFilterSel__enumvalues = { + 0: 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 1: 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', +} +CB_PERF_CLEAR_FILTER_SEL_NONCLEAR = 0 +CB_PERF_CLEAR_FILTER_SEL_CLEAR = 1 +CBPerfClearFilterSel = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP_MASKS' +TC_OP_MASKS__enumvalues = { + 8: 'TC_OP_MASK_FLUSH_DENROM', + 32: 'TC_OP_MASK_64', + 64: 'TC_OP_MASK_NO_RTN', +} +TC_OP_MASK_FLUSH_DENROM = 8 +TC_OP_MASK_64 = 32 +TC_OP_MASK_NO_RTN = 64 +TC_OP_MASKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_OP' +TC_OP__enumvalues = { + 0: 'TC_OP_READ', + 1: 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', + 2: 'TC_OP_ATOMIC_FMIN_RTN_32', + 3: 'TC_OP_ATOMIC_FMAX_RTN_32', + 4: 'TC_OP_RESERVED_FOP_RTN_32_0', + 5: 'TC_OP_RESERVED_FOP_RTN_32_1', + 6: 'TC_OP_RESERVED_FOP_RTN_32_2', + 7: 'TC_OP_ATOMIC_SWAP_RTN_32', + 8: 'TC_OP_ATOMIC_CMPSWAP_RTN_32', + 9: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 10: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 11: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 12: 'TC_OP_PROBE_FILTER', + 13: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 14: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 15: 'TC_OP_ATOMIC_ADD_RTN_32', + 16: 'TC_OP_ATOMIC_SUB_RTN_32', + 17: 'TC_OP_ATOMIC_SMIN_RTN_32', + 18: 'TC_OP_ATOMIC_UMIN_RTN_32', + 19: 'TC_OP_ATOMIC_SMAX_RTN_32', + 20: 'TC_OP_ATOMIC_UMAX_RTN_32', + 21: 'TC_OP_ATOMIC_AND_RTN_32', + 22: 'TC_OP_ATOMIC_OR_RTN_32', + 23: 'TC_OP_ATOMIC_XOR_RTN_32', + 24: 'TC_OP_ATOMIC_INC_RTN_32', + 25: 'TC_OP_ATOMIC_DEC_RTN_32', + 26: 'TC_OP_WBINVL1_VOL', + 27: 'TC_OP_WBINVL1_SD', + 28: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 29: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 30: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 31: 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 32: 'TC_OP_WRITE', + 33: 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 34: 'TC_OP_ATOMIC_FMIN_RTN_64', + 35: 'TC_OP_ATOMIC_FMAX_RTN_64', + 36: 'TC_OP_RESERVED_FOP_RTN_64_0', + 37: 'TC_OP_RESERVED_FOP_RTN_64_1', + 38: 'TC_OP_RESERVED_FOP_RTN_64_2', + 39: 'TC_OP_ATOMIC_SWAP_RTN_64', + 40: 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 41: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 42: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 43: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 44: 'TC_OP_WBINVL2_SD', + 45: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 46: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 47: 'TC_OP_ATOMIC_ADD_RTN_64', + 48: 'TC_OP_ATOMIC_SUB_RTN_64', + 49: 'TC_OP_ATOMIC_SMIN_RTN_64', + 50: 'TC_OP_ATOMIC_UMIN_RTN_64', + 51: 'TC_OP_ATOMIC_SMAX_RTN_64', + 52: 'TC_OP_ATOMIC_UMAX_RTN_64', + 53: 'TC_OP_ATOMIC_AND_RTN_64', + 54: 'TC_OP_ATOMIC_OR_RTN_64', + 55: 'TC_OP_ATOMIC_XOR_RTN_64', + 56: 'TC_OP_ATOMIC_INC_RTN_64', + 57: 'TC_OP_ATOMIC_DEC_RTN_64', + 58: 'TC_OP_WBL2_NC', + 59: 'TC_OP_WBL2_WC', + 60: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 61: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 62: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 63: 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', + 64: 'TC_OP_WBINVL1', + 65: 'TC_OP_ATOMIC_FCMPSWAP_32', + 66: 'TC_OP_ATOMIC_FMIN_32', + 67: 'TC_OP_ATOMIC_FMAX_32', + 68: 'TC_OP_RESERVED_FOP_32_0', + 69: 'TC_OP_RESERVED_FOP_32_1', + 70: 'TC_OP_RESERVED_FOP_32_2', + 71: 'TC_OP_ATOMIC_SWAP_32', + 72: 'TC_OP_ATOMIC_CMPSWAP_32', + 73: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 74: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 75: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 76: 'TC_OP_INV_METADATA', + 77: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1', + 78: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 79: 'TC_OP_ATOMIC_ADD_32', + 80: 'TC_OP_ATOMIC_SUB_32', + 81: 'TC_OP_ATOMIC_SMIN_32', + 82: 'TC_OP_ATOMIC_UMIN_32', + 83: 'TC_OP_ATOMIC_SMAX_32', + 84: 'TC_OP_ATOMIC_UMAX_32', + 85: 'TC_OP_ATOMIC_AND_32', + 86: 'TC_OP_ATOMIC_OR_32', + 87: 'TC_OP_ATOMIC_XOR_32', + 88: 'TC_OP_ATOMIC_INC_32', + 89: 'TC_OP_ATOMIC_DEC_32', + 90: 'TC_OP_INVL2_NC', + 91: 'TC_OP_NOP_RTN0', + 92: 'TC_OP_RESERVED_NON_FLOAT_32_1', + 93: 'TC_OP_RESERVED_NON_FLOAT_32_2', + 94: 'TC_OP_RESERVED_NON_FLOAT_32_3', + 95: 'TC_OP_RESERVED_NON_FLOAT_32_4', + 96: 'TC_OP_WBINVL2', + 97: 'TC_OP_ATOMIC_FCMPSWAP_64', + 98: 'TC_OP_ATOMIC_FMIN_64', + 99: 'TC_OP_ATOMIC_FMAX_64', + 100: 'TC_OP_RESERVED_FOP_64_0', + 101: 'TC_OP_RESERVED_FOP_64_1', + 102: 'TC_OP_RESERVED_FOP_64_2', + 103: 'TC_OP_ATOMIC_SWAP_64', + 104: 'TC_OP_ATOMIC_CMPSWAP_64', + 105: 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 106: 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 107: 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 108: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 109: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 110: 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 111: 'TC_OP_ATOMIC_ADD_64', + 112: 'TC_OP_ATOMIC_SUB_64', + 113: 'TC_OP_ATOMIC_SMIN_64', + 114: 'TC_OP_ATOMIC_UMIN_64', + 115: 'TC_OP_ATOMIC_SMAX_64', + 116: 'TC_OP_ATOMIC_UMAX_64', + 117: 'TC_OP_ATOMIC_AND_64', + 118: 'TC_OP_ATOMIC_OR_64', + 119: 'TC_OP_ATOMIC_XOR_64', + 120: 'TC_OP_ATOMIC_INC_64', + 121: 'TC_OP_ATOMIC_DEC_64', + 122: 'TC_OP_WBINVL2_NC', + 123: 'TC_OP_NOP_ACK', + 124: 'TC_OP_RESERVED_NON_FLOAT_64_1', + 125: 'TC_OP_RESERVED_NON_FLOAT_64_2', + 126: 'TC_OP_RESERVED_NON_FLOAT_64_3', + 127: 'TC_OP_RESERVED_NON_FLOAT_64_4', +} +TC_OP_READ = 0 +TC_OP_ATOMIC_FCMPSWAP_RTN_32 = 1 +TC_OP_ATOMIC_FMIN_RTN_32 = 2 +TC_OP_ATOMIC_FMAX_RTN_32 = 3 +TC_OP_RESERVED_FOP_RTN_32_0 = 4 +TC_OP_RESERVED_FOP_RTN_32_1 = 5 +TC_OP_RESERVED_FOP_RTN_32_2 = 6 +TC_OP_ATOMIC_SWAP_RTN_32 = 7 +TC_OP_ATOMIC_CMPSWAP_RTN_32 = 8 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32 = 9 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32 = 10 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32 = 11 +TC_OP_PROBE_FILTER = 12 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1 = 13 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2 = 14 +TC_OP_ATOMIC_ADD_RTN_32 = 15 +TC_OP_ATOMIC_SUB_RTN_32 = 16 +TC_OP_ATOMIC_SMIN_RTN_32 = 17 +TC_OP_ATOMIC_UMIN_RTN_32 = 18 +TC_OP_ATOMIC_SMAX_RTN_32 = 19 +TC_OP_ATOMIC_UMAX_RTN_32 = 20 +TC_OP_ATOMIC_AND_RTN_32 = 21 +TC_OP_ATOMIC_OR_RTN_32 = 22 +TC_OP_ATOMIC_XOR_RTN_32 = 23 +TC_OP_ATOMIC_INC_RTN_32 = 24 +TC_OP_ATOMIC_DEC_RTN_32 = 25 +TC_OP_WBINVL1_VOL = 26 +TC_OP_WBINVL1_SD = 27 +TC_OP_RESERVED_NON_FLOAT_RTN_32_0 = 28 +TC_OP_RESERVED_NON_FLOAT_RTN_32_1 = 29 +TC_OP_RESERVED_NON_FLOAT_RTN_32_2 = 30 +TC_OP_RESERVED_NON_FLOAT_RTN_32_3 = 31 +TC_OP_WRITE = 32 +TC_OP_ATOMIC_FCMPSWAP_RTN_64 = 33 +TC_OP_ATOMIC_FMIN_RTN_64 = 34 +TC_OP_ATOMIC_FMAX_RTN_64 = 35 +TC_OP_RESERVED_FOP_RTN_64_0 = 36 +TC_OP_RESERVED_FOP_RTN_64_1 = 37 +TC_OP_RESERVED_FOP_RTN_64_2 = 38 +TC_OP_ATOMIC_SWAP_RTN_64 = 39 +TC_OP_ATOMIC_CMPSWAP_RTN_64 = 40 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64 = 41 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64 = 42 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64 = 43 +TC_OP_WBINVL2_SD = 44 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0 = 45 +TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1 = 46 +TC_OP_ATOMIC_ADD_RTN_64 = 47 +TC_OP_ATOMIC_SUB_RTN_64 = 48 +TC_OP_ATOMIC_SMIN_RTN_64 = 49 +TC_OP_ATOMIC_UMIN_RTN_64 = 50 +TC_OP_ATOMIC_SMAX_RTN_64 = 51 +TC_OP_ATOMIC_UMAX_RTN_64 = 52 +TC_OP_ATOMIC_AND_RTN_64 = 53 +TC_OP_ATOMIC_OR_RTN_64 = 54 +TC_OP_ATOMIC_XOR_RTN_64 = 55 +TC_OP_ATOMIC_INC_RTN_64 = 56 +TC_OP_ATOMIC_DEC_RTN_64 = 57 +TC_OP_WBL2_NC = 58 +TC_OP_WBL2_WC = 59 +TC_OP_RESERVED_NON_FLOAT_RTN_64_1 = 60 +TC_OP_RESERVED_NON_FLOAT_RTN_64_2 = 61 +TC_OP_RESERVED_NON_FLOAT_RTN_64_3 = 62 +TC_OP_RESERVED_NON_FLOAT_RTN_64_4 = 63 +TC_OP_WBINVL1 = 64 +TC_OP_ATOMIC_FCMPSWAP_32 = 65 +TC_OP_ATOMIC_FMIN_32 = 66 +TC_OP_ATOMIC_FMAX_32 = 67 +TC_OP_RESERVED_FOP_32_0 = 68 +TC_OP_RESERVED_FOP_32_1 = 69 +TC_OP_RESERVED_FOP_32_2 = 70 +TC_OP_ATOMIC_SWAP_32 = 71 +TC_OP_ATOMIC_CMPSWAP_32 = 72 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32 = 73 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32 = 74 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32 = 75 +TC_OP_INV_METADATA = 76 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1 = 77 +TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2 = 78 +TC_OP_ATOMIC_ADD_32 = 79 +TC_OP_ATOMIC_SUB_32 = 80 +TC_OP_ATOMIC_SMIN_32 = 81 +TC_OP_ATOMIC_UMIN_32 = 82 +TC_OP_ATOMIC_SMAX_32 = 83 +TC_OP_ATOMIC_UMAX_32 = 84 +TC_OP_ATOMIC_AND_32 = 85 +TC_OP_ATOMIC_OR_32 = 86 +TC_OP_ATOMIC_XOR_32 = 87 +TC_OP_ATOMIC_INC_32 = 88 +TC_OP_ATOMIC_DEC_32 = 89 +TC_OP_INVL2_NC = 90 +TC_OP_NOP_RTN0 = 91 +TC_OP_RESERVED_NON_FLOAT_32_1 = 92 +TC_OP_RESERVED_NON_FLOAT_32_2 = 93 +TC_OP_RESERVED_NON_FLOAT_32_3 = 94 +TC_OP_RESERVED_NON_FLOAT_32_4 = 95 +TC_OP_WBINVL2 = 96 +TC_OP_ATOMIC_FCMPSWAP_64 = 97 +TC_OP_ATOMIC_FMIN_64 = 98 +TC_OP_ATOMIC_FMAX_64 = 99 +TC_OP_RESERVED_FOP_64_0 = 100 +TC_OP_RESERVED_FOP_64_1 = 101 +TC_OP_RESERVED_FOP_64_2 = 102 +TC_OP_ATOMIC_SWAP_64 = 103 +TC_OP_ATOMIC_CMPSWAP_64 = 104 +TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64 = 105 +TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64 = 106 +TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64 = 107 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0 = 108 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1 = 109 +TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2 = 110 +TC_OP_ATOMIC_ADD_64 = 111 +TC_OP_ATOMIC_SUB_64 = 112 +TC_OP_ATOMIC_SMIN_64 = 113 +TC_OP_ATOMIC_UMIN_64 = 114 +TC_OP_ATOMIC_SMAX_64 = 115 +TC_OP_ATOMIC_UMAX_64 = 116 +TC_OP_ATOMIC_AND_64 = 117 +TC_OP_ATOMIC_OR_64 = 118 +TC_OP_ATOMIC_XOR_64 = 119 +TC_OP_ATOMIC_INC_64 = 120 +TC_OP_ATOMIC_DEC_64 = 121 +TC_OP_WBINVL2_NC = 122 +TC_OP_NOP_ACK = 123 +TC_OP_RESERVED_NON_FLOAT_64_1 = 124 +TC_OP_RESERVED_NON_FLOAT_64_2 = 125 +TC_OP_RESERVED_NON_FLOAT_64_3 = 126 +TC_OP_RESERVED_NON_FLOAT_64_4 = 127 +TC_OP = ctypes.c_uint32 # enum + +# values for enumeration 'TC_CHUB_REQ_CREDITS_ENUM' +TC_CHUB_REQ_CREDITS_ENUM__enumvalues = { + 16: 'TC_CHUB_REQ_CREDITS', +} +TC_CHUB_REQ_CREDITS = 16 +TC_CHUB_REQ_CREDITS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'CHUB_TC_RET_CREDITS_ENUM' +CHUB_TC_RET_CREDITS_ENUM__enumvalues = { + 32: 'CHUB_TC_RET_CREDITS', +} +CHUB_TC_RET_CREDITS = 32 +CHUB_TC_RET_CREDITS_ENUM = ctypes.c_uint32 # enum + +# values for enumeration 'TC_NACKS' +TC_NACKS__enumvalues = { + 0: 'TC_NACK_NO_FAULT', + 1: 'TC_NACK_PAGE_FAULT', + 2: 'TC_NACK_PROTECTION_FAULT', + 3: 'TC_NACK_DATA_ERROR', +} +TC_NACK_NO_FAULT = 0 +TC_NACK_PAGE_FAULT = 1 +TC_NACK_PROTECTION_FAULT = 2 +TC_NACK_DATA_ERROR = 3 +TC_NACKS = ctypes.c_uint32 # enum + +# values for enumeration 'TC_EA_CID' +TC_EA_CID__enumvalues = { + 0: 'TC_EA_CID_RT', + 1: 'TC_EA_CID_FMASK', + 2: 'TC_EA_CID_DCC', + 3: 'TC_EA_CID_TCPMETA', + 4: 'TC_EA_CID_Z', + 5: 'TC_EA_CID_STENCIL', + 6: 'TC_EA_CID_HTILE', + 7: 'TC_EA_CID_MISC', + 8: 'TC_EA_CID_TCP', + 9: 'TC_EA_CID_SQC', + 10: 'TC_EA_CID_CPF', + 11: 'TC_EA_CID_CPG', + 12: 'TC_EA_CID_IA', + 13: 'TC_EA_CID_WD', + 14: 'TC_EA_CID_PA', + 15: 'TC_EA_CID_UTCL2_TPI', +} +TC_EA_CID_RT = 0 +TC_EA_CID_FMASK = 1 +TC_EA_CID_DCC = 2 +TC_EA_CID_TCPMETA = 3 +TC_EA_CID_Z = 4 +TC_EA_CID_STENCIL = 5 +TC_EA_CID_HTILE = 6 +TC_EA_CID_MISC = 7 +TC_EA_CID_TCP = 8 +TC_EA_CID_SQC = 9 +TC_EA_CID_CPF = 10 +TC_EA_CID_CPG = 11 +TC_EA_CID_IA = 12 +TC_EA_CID_WD = 13 +TC_EA_CID_PA = 14 +TC_EA_CID_UTCL2_TPI = 15 +TC_EA_CID = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SAMPLE_CNTL' +SPI_SAMPLE_CNTL__enumvalues = { + 0: 'CENTROIDS_ONLY', + 1: 'CENTERS_ONLY', + 2: 'CENTROIDS_AND_CENTERS', + 3: 'UNDEF', +} +CENTROIDS_ONLY = 0 +CENTERS_ONLY = 1 +CENTROIDS_AND_CENTERS = 2 +UNDEF = 3 +SPI_SAMPLE_CNTL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_FOG_MODE' +SPI_FOG_MODE__enumvalues = { + 0: 'SPI_FOG_NONE', + 1: 'SPI_FOG_EXP', + 2: 'SPI_FOG_EXP2', + 3: 'SPI_FOG_LINEAR', +} +SPI_FOG_NONE = 0 +SPI_FOG_EXP = 1 +SPI_FOG_EXP2 = 2 +SPI_FOG_LINEAR = 3 +SPI_FOG_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PNT_SPRITE_OVERRIDE' +SPI_PNT_SPRITE_OVERRIDE__enumvalues = { + 0: 'SPI_PNT_SPRITE_SEL_0', + 1: 'SPI_PNT_SPRITE_SEL_1', + 2: 'SPI_PNT_SPRITE_SEL_S', + 3: 'SPI_PNT_SPRITE_SEL_T', + 4: 'SPI_PNT_SPRITE_SEL_NONE', +} +SPI_PNT_SPRITE_SEL_0 = 0 +SPI_PNT_SPRITE_SEL_1 = 1 +SPI_PNT_SPRITE_SEL_S = 2 +SPI_PNT_SPRITE_SEL_T = 3 +SPI_PNT_SPRITE_SEL_NONE = 4 +SPI_PNT_SPRITE_OVERRIDE = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_PERFCNT_SEL' +SPI_PERFCNT_SEL__enumvalues = { + 0: 'SPI_PERF_VS_WINDOW_VALID', + 1: 'SPI_PERF_VS_BUSY', + 2: 'SPI_PERF_VS_FIRST_WAVE', + 3: 'SPI_PERF_VS_LAST_WAVE', + 4: 'SPI_PERF_VS_LSHS_DEALLOC', + 5: 'SPI_PERF_VS_PC_STALL', + 6: 'SPI_PERF_VS_POS0_STALL', + 7: 'SPI_PERF_VS_POS1_STALL', + 8: 'SPI_PERF_VS_CRAWLER_STALL', + 9: 'SPI_PERF_VS_EVENT_WAVE', + 10: 'SPI_PERF_VS_WAVE', + 11: 'SPI_PERF_VS_PERS_UPD_FULL0', + 12: 'SPI_PERF_VS_PERS_UPD_FULL1', + 13: 'SPI_PERF_VS_LATE_ALLOC_FULL', + 14: 'SPI_PERF_VS_FIRST_SUBGRP', + 15: 'SPI_PERF_VS_LAST_SUBGRP', + 16: 'SPI_PERF_GS_WINDOW_VALID', + 17: 'SPI_PERF_GS_BUSY', + 18: 'SPI_PERF_GS_CRAWLER_STALL', + 19: 'SPI_PERF_GS_EVENT_WAVE', + 20: 'SPI_PERF_GS_WAVE', + 21: 'SPI_PERF_GS_PERS_UPD_FULL0', + 22: 'SPI_PERF_GS_PERS_UPD_FULL1', + 23: 'SPI_PERF_GS_FIRST_SUBGRP', + 24: 'SPI_PERF_GS_LAST_SUBGRP', + 25: 'SPI_PERF_ES_WINDOW_VALID', + 26: 'SPI_PERF_ES_BUSY', + 27: 'SPI_PERF_ES_CRAWLER_STALL', + 28: 'SPI_PERF_ES_FIRST_WAVE', + 29: 'SPI_PERF_ES_LAST_WAVE', + 30: 'SPI_PERF_ES_LSHS_DEALLOC', + 31: 'SPI_PERF_ES_EVENT_WAVE', + 32: 'SPI_PERF_ES_WAVE', + 33: 'SPI_PERF_ES_PERS_UPD_FULL0', + 34: 'SPI_PERF_ES_PERS_UPD_FULL1', + 35: 'SPI_PERF_ES_FIRST_SUBGRP', + 36: 'SPI_PERF_ES_LAST_SUBGRP', + 37: 'SPI_PERF_HS_WINDOW_VALID', + 38: 'SPI_PERF_HS_BUSY', + 39: 'SPI_PERF_HS_CRAWLER_STALL', + 40: 'SPI_PERF_HS_FIRST_WAVE', + 41: 'SPI_PERF_HS_LAST_WAVE', + 42: 'SPI_PERF_HS_LSHS_DEALLOC', + 43: 'SPI_PERF_HS_EVENT_WAVE', + 44: 'SPI_PERF_HS_WAVE', + 45: 'SPI_PERF_HS_PERS_UPD_FULL0', + 46: 'SPI_PERF_HS_PERS_UPD_FULL1', + 47: 'SPI_PERF_LS_WINDOW_VALID', + 48: 'SPI_PERF_LS_BUSY', + 49: 'SPI_PERF_LS_CRAWLER_STALL', + 50: 'SPI_PERF_LS_FIRST_WAVE', + 51: 'SPI_PERF_LS_LAST_WAVE', + 52: 'SPI_PERF_OFFCHIP_LDS_STALL_LS', + 53: 'SPI_PERF_LS_EVENT_WAVE', + 54: 'SPI_PERF_LS_WAVE', + 55: 'SPI_PERF_LS_PERS_UPD_FULL0', + 56: 'SPI_PERF_LS_PERS_UPD_FULL1', + 57: 'SPI_PERF_CSG_WINDOW_VALID', + 58: 'SPI_PERF_CSG_BUSY', + 59: 'SPI_PERF_CSG_NUM_THREADGROUPS', + 60: 'SPI_PERF_CSG_CRAWLER_STALL', + 61: 'SPI_PERF_CSG_EVENT_WAVE', + 62: 'SPI_PERF_CSG_WAVE', + 63: 'SPI_PERF_CSN_WINDOW_VALID', + 64: 'SPI_PERF_CSN_BUSY', + 65: 'SPI_PERF_CSN_NUM_THREADGROUPS', + 66: 'SPI_PERF_CSN_CRAWLER_STALL', + 67: 'SPI_PERF_CSN_EVENT_WAVE', + 68: 'SPI_PERF_CSN_WAVE', + 69: 'SPI_PERF_PS_CTL_WINDOW_VALID', + 70: 'SPI_PERF_PS_CTL_BUSY', + 71: 'SPI_PERF_PS_CTL_ACTIVE', + 72: 'SPI_PERF_PS_CTL_DEALLOC_BIN0', + 73: 'SPI_PERF_PS_CTL_FPOS_BIN1_STALL', + 74: 'SPI_PERF_PS_CTL_EVENT_WAVE', + 75: 'SPI_PERF_PS_CTL_WAVE', + 76: 'SPI_PERF_PS_CTL_OPT_WAVE', + 77: 'SPI_PERF_PS_CTL_PASS_BIN0', + 78: 'SPI_PERF_PS_CTL_PASS_BIN1', + 79: 'SPI_PERF_PS_CTL_FPOS_BIN2', + 80: 'SPI_PERF_PS_CTL_PRIM_BIN0', + 81: 'SPI_PERF_PS_CTL_PRIM_BIN1', + 82: 'SPI_PERF_PS_CTL_CNF_BIN2', + 83: 'SPI_PERF_PS_CTL_CNF_BIN3', + 84: 'SPI_PERF_PS_CTL_CRAWLER_STALL', + 85: 'SPI_PERF_PS_CTL_LDS_RES_FULL', + 86: 'SPI_PERF_PS_PERS_UPD_FULL0', + 87: 'SPI_PERF_PS_PERS_UPD_FULL1', + 88: 'SPI_PERF_PIX_ALLOC_PEND_CNT', + 89: 'SPI_PERF_PIX_ALLOC_SCB_STALL', + 90: 'SPI_PERF_PIX_ALLOC_DB0_STALL', + 91: 'SPI_PERF_PIX_ALLOC_DB1_STALL', + 92: 'SPI_PERF_PIX_ALLOC_DB2_STALL', + 93: 'SPI_PERF_PIX_ALLOC_DB3_STALL', + 94: 'SPI_PERF_LDS0_PC_VALID', + 95: 'SPI_PERF_LDS1_PC_VALID', + 96: 'SPI_PERF_RA_PIPE_REQ_BIN2', + 97: 'SPI_PERF_RA_TASK_REQ_BIN3', + 98: 'SPI_PERF_RA_WR_CTL_FULL', + 99: 'SPI_PERF_RA_REQ_NO_ALLOC', + 100: 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 101: 'SPI_PERF_RA_REQ_NO_ALLOC_VS', + 102: 'SPI_PERF_RA_REQ_NO_ALLOC_GS', + 103: 'SPI_PERF_RA_REQ_NO_ALLOC_ES', + 104: 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 105: 'SPI_PERF_RA_REQ_NO_ALLOC_LS', + 106: 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 107: 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', + 108: 'SPI_PERF_RA_RES_STALL_PS', + 109: 'SPI_PERF_RA_RES_STALL_VS', + 110: 'SPI_PERF_RA_RES_STALL_GS', + 111: 'SPI_PERF_RA_RES_STALL_ES', + 112: 'SPI_PERF_RA_RES_STALL_HS', + 113: 'SPI_PERF_RA_RES_STALL_LS', + 114: 'SPI_PERF_RA_RES_STALL_CSG', + 115: 'SPI_PERF_RA_RES_STALL_CSN', + 116: 'SPI_PERF_RA_TMP_STALL_PS', + 117: 'SPI_PERF_RA_TMP_STALL_VS', + 118: 'SPI_PERF_RA_TMP_STALL_GS', + 119: 'SPI_PERF_RA_TMP_STALL_ES', + 120: 'SPI_PERF_RA_TMP_STALL_HS', + 121: 'SPI_PERF_RA_TMP_STALL_LS', + 122: 'SPI_PERF_RA_TMP_STALL_CSG', + 123: 'SPI_PERF_RA_TMP_STALL_CSN', + 124: 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 125: 'SPI_PERF_RA_WAVE_SIMD_FULL_VS', + 126: 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', + 127: 'SPI_PERF_RA_WAVE_SIMD_FULL_ES', + 128: 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', + 129: 'SPI_PERF_RA_WAVE_SIMD_FULL_LS', + 130: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 131: 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', + 132: 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 133: 'SPI_PERF_RA_VGPR_SIMD_FULL_VS', + 134: 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', + 135: 'SPI_PERF_RA_VGPR_SIMD_FULL_ES', + 136: 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', + 137: 'SPI_PERF_RA_VGPR_SIMD_FULL_LS', + 138: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 139: 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', + 140: 'SPI_PERF_RA_SGPR_SIMD_FULL_PS', + 141: 'SPI_PERF_RA_SGPR_SIMD_FULL_VS', + 142: 'SPI_PERF_RA_SGPR_SIMD_FULL_GS', + 143: 'SPI_PERF_RA_SGPR_SIMD_FULL_ES', + 144: 'SPI_PERF_RA_SGPR_SIMD_FULL_HS', + 145: 'SPI_PERF_RA_SGPR_SIMD_FULL_LS', + 146: 'SPI_PERF_RA_SGPR_SIMD_FULL_CSG', + 147: 'SPI_PERF_RA_SGPR_SIMD_FULL_CSN', + 148: 'SPI_PERF_RA_LDS_CU_FULL_PS', + 149: 'SPI_PERF_RA_LDS_CU_FULL_LS', + 150: 'SPI_PERF_RA_LDS_CU_FULL_ES', + 151: 'SPI_PERF_RA_LDS_CU_FULL_CSG', + 152: 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 153: 'SPI_PERF_RA_BAR_CU_FULL_HS', + 154: 'SPI_PERF_RA_BAR_CU_FULL_CSG', + 155: 'SPI_PERF_RA_BAR_CU_FULL_CSN', + 156: 'SPI_PERF_RA_BULKY_CU_FULL_CSG', + 157: 'SPI_PERF_RA_BULKY_CU_FULL_CSN', + 158: 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', + 159: 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 160: 'SPI_PERF_RA_WVLIM_STALL_PS', + 161: 'SPI_PERF_RA_WVLIM_STALL_VS', + 162: 'SPI_PERF_RA_WVLIM_STALL_GS', + 163: 'SPI_PERF_RA_WVLIM_STALL_ES', + 164: 'SPI_PERF_RA_WVLIM_STALL_HS', + 165: 'SPI_PERF_RA_WVLIM_STALL_LS', + 166: 'SPI_PERF_RA_WVLIM_STALL_CSG', + 167: 'SPI_PERF_RA_WVLIM_STALL_CSN', + 168: 'SPI_PERF_RA_PS_LOCK_NA', + 169: 'SPI_PERF_RA_VS_LOCK', + 170: 'SPI_PERF_RA_GS_LOCK', + 171: 'SPI_PERF_RA_ES_LOCK', + 172: 'SPI_PERF_RA_HS_LOCK', + 173: 'SPI_PERF_RA_LS_LOCK', + 174: 'SPI_PERF_RA_CSG_LOCK', + 175: 'SPI_PERF_RA_CSN_LOCK', + 176: 'SPI_PERF_RA_RSV_UPD', + 177: 'SPI_PERF_EXP_ARB_COL_CNT', + 178: 'SPI_PERF_EXP_ARB_PAR_CNT', + 179: 'SPI_PERF_EXP_ARB_POS_CNT', + 180: 'SPI_PERF_EXP_ARB_GDS_CNT', + 181: 'SPI_PERF_CLKGATE_BUSY_STALL', + 182: 'SPI_PERF_CLKGATE_ACTIVE_STALL', + 183: 'SPI_PERF_CLKGATE_ALL_CLOCKS_ON', + 184: 'SPI_PERF_CLKGATE_CGTT_DYN_ON', + 185: 'SPI_PERF_CLKGATE_CGTT_REG_ON', + 186: 'SPI_PERF_NUM_VS_POS_EXPORTS', + 187: 'SPI_PERF_NUM_VS_PARAM_EXPORTS', + 188: 'SPI_PERF_NUM_PS_COL_EXPORTS', + 189: 'SPI_PERF_ES_GRP_FIFO_FULL', + 190: 'SPI_PERF_GS_GRP_FIFO_FULL', + 191: 'SPI_PERF_HS_GRP_FIFO_FULL', + 192: 'SPI_PERF_LS_GRP_FIFO_FULL', + 193: 'SPI_PERF_VS_ALLOC_CNT', + 194: 'SPI_PERF_VS_LATE_ALLOC_ACCUM', + 195: 'SPI_PERF_PC_ALLOC_CNT', + 196: 'SPI_PERF_PC_ALLOC_ACCUM', +} +SPI_PERF_VS_WINDOW_VALID = 0 +SPI_PERF_VS_BUSY = 1 +SPI_PERF_VS_FIRST_WAVE = 2 +SPI_PERF_VS_LAST_WAVE = 3 +SPI_PERF_VS_LSHS_DEALLOC = 4 +SPI_PERF_VS_PC_STALL = 5 +SPI_PERF_VS_POS0_STALL = 6 +SPI_PERF_VS_POS1_STALL = 7 +SPI_PERF_VS_CRAWLER_STALL = 8 +SPI_PERF_VS_EVENT_WAVE = 9 +SPI_PERF_VS_WAVE = 10 +SPI_PERF_VS_PERS_UPD_FULL0 = 11 +SPI_PERF_VS_PERS_UPD_FULL1 = 12 +SPI_PERF_VS_LATE_ALLOC_FULL = 13 +SPI_PERF_VS_FIRST_SUBGRP = 14 +SPI_PERF_VS_LAST_SUBGRP = 15 +SPI_PERF_GS_WINDOW_VALID = 16 +SPI_PERF_GS_BUSY = 17 +SPI_PERF_GS_CRAWLER_STALL = 18 +SPI_PERF_GS_EVENT_WAVE = 19 +SPI_PERF_GS_WAVE = 20 +SPI_PERF_GS_PERS_UPD_FULL0 = 21 +SPI_PERF_GS_PERS_UPD_FULL1 = 22 +SPI_PERF_GS_FIRST_SUBGRP = 23 +SPI_PERF_GS_LAST_SUBGRP = 24 +SPI_PERF_ES_WINDOW_VALID = 25 +SPI_PERF_ES_BUSY = 26 +SPI_PERF_ES_CRAWLER_STALL = 27 +SPI_PERF_ES_FIRST_WAVE = 28 +SPI_PERF_ES_LAST_WAVE = 29 +SPI_PERF_ES_LSHS_DEALLOC = 30 +SPI_PERF_ES_EVENT_WAVE = 31 +SPI_PERF_ES_WAVE = 32 +SPI_PERF_ES_PERS_UPD_FULL0 = 33 +SPI_PERF_ES_PERS_UPD_FULL1 = 34 +SPI_PERF_ES_FIRST_SUBGRP = 35 +SPI_PERF_ES_LAST_SUBGRP = 36 +SPI_PERF_HS_WINDOW_VALID = 37 +SPI_PERF_HS_BUSY = 38 +SPI_PERF_HS_CRAWLER_STALL = 39 +SPI_PERF_HS_FIRST_WAVE = 40 +SPI_PERF_HS_LAST_WAVE = 41 +SPI_PERF_HS_LSHS_DEALLOC = 42 +SPI_PERF_HS_EVENT_WAVE = 43 +SPI_PERF_HS_WAVE = 44 +SPI_PERF_HS_PERS_UPD_FULL0 = 45 +SPI_PERF_HS_PERS_UPD_FULL1 = 46 +SPI_PERF_LS_WINDOW_VALID = 47 +SPI_PERF_LS_BUSY = 48 +SPI_PERF_LS_CRAWLER_STALL = 49 +SPI_PERF_LS_FIRST_WAVE = 50 +SPI_PERF_LS_LAST_WAVE = 51 +SPI_PERF_OFFCHIP_LDS_STALL_LS = 52 +SPI_PERF_LS_EVENT_WAVE = 53 +SPI_PERF_LS_WAVE = 54 +SPI_PERF_LS_PERS_UPD_FULL0 = 55 +SPI_PERF_LS_PERS_UPD_FULL1 = 56 +SPI_PERF_CSG_WINDOW_VALID = 57 +SPI_PERF_CSG_BUSY = 58 +SPI_PERF_CSG_NUM_THREADGROUPS = 59 +SPI_PERF_CSG_CRAWLER_STALL = 60 +SPI_PERF_CSG_EVENT_WAVE = 61 +SPI_PERF_CSG_WAVE = 62 +SPI_PERF_CSN_WINDOW_VALID = 63 +SPI_PERF_CSN_BUSY = 64 +SPI_PERF_CSN_NUM_THREADGROUPS = 65 +SPI_PERF_CSN_CRAWLER_STALL = 66 +SPI_PERF_CSN_EVENT_WAVE = 67 +SPI_PERF_CSN_WAVE = 68 +SPI_PERF_PS_CTL_WINDOW_VALID = 69 +SPI_PERF_PS_CTL_BUSY = 70 +SPI_PERF_PS_CTL_ACTIVE = 71 +SPI_PERF_PS_CTL_DEALLOC_BIN0 = 72 +SPI_PERF_PS_CTL_FPOS_BIN1_STALL = 73 +SPI_PERF_PS_CTL_EVENT_WAVE = 74 +SPI_PERF_PS_CTL_WAVE = 75 +SPI_PERF_PS_CTL_OPT_WAVE = 76 +SPI_PERF_PS_CTL_PASS_BIN0 = 77 +SPI_PERF_PS_CTL_PASS_BIN1 = 78 +SPI_PERF_PS_CTL_FPOS_BIN2 = 79 +SPI_PERF_PS_CTL_PRIM_BIN0 = 80 +SPI_PERF_PS_CTL_PRIM_BIN1 = 81 +SPI_PERF_PS_CTL_CNF_BIN2 = 82 +SPI_PERF_PS_CTL_CNF_BIN3 = 83 +SPI_PERF_PS_CTL_CRAWLER_STALL = 84 +SPI_PERF_PS_CTL_LDS_RES_FULL = 85 +SPI_PERF_PS_PERS_UPD_FULL0 = 86 +SPI_PERF_PS_PERS_UPD_FULL1 = 87 +SPI_PERF_PIX_ALLOC_PEND_CNT = 88 +SPI_PERF_PIX_ALLOC_SCB_STALL = 89 +SPI_PERF_PIX_ALLOC_DB0_STALL = 90 +SPI_PERF_PIX_ALLOC_DB1_STALL = 91 +SPI_PERF_PIX_ALLOC_DB2_STALL = 92 +SPI_PERF_PIX_ALLOC_DB3_STALL = 93 +SPI_PERF_LDS0_PC_VALID = 94 +SPI_PERF_LDS1_PC_VALID = 95 +SPI_PERF_RA_PIPE_REQ_BIN2 = 96 +SPI_PERF_RA_TASK_REQ_BIN3 = 97 +SPI_PERF_RA_WR_CTL_FULL = 98 +SPI_PERF_RA_REQ_NO_ALLOC = 99 +SPI_PERF_RA_REQ_NO_ALLOC_PS = 100 +SPI_PERF_RA_REQ_NO_ALLOC_VS = 101 +SPI_PERF_RA_REQ_NO_ALLOC_GS = 102 +SPI_PERF_RA_REQ_NO_ALLOC_ES = 103 +SPI_PERF_RA_REQ_NO_ALLOC_HS = 104 +SPI_PERF_RA_REQ_NO_ALLOC_LS = 105 +SPI_PERF_RA_REQ_NO_ALLOC_CSG = 106 +SPI_PERF_RA_REQ_NO_ALLOC_CSN = 107 +SPI_PERF_RA_RES_STALL_PS = 108 +SPI_PERF_RA_RES_STALL_VS = 109 +SPI_PERF_RA_RES_STALL_GS = 110 +SPI_PERF_RA_RES_STALL_ES = 111 +SPI_PERF_RA_RES_STALL_HS = 112 +SPI_PERF_RA_RES_STALL_LS = 113 +SPI_PERF_RA_RES_STALL_CSG = 114 +SPI_PERF_RA_RES_STALL_CSN = 115 +SPI_PERF_RA_TMP_STALL_PS = 116 +SPI_PERF_RA_TMP_STALL_VS = 117 +SPI_PERF_RA_TMP_STALL_GS = 118 +SPI_PERF_RA_TMP_STALL_ES = 119 +SPI_PERF_RA_TMP_STALL_HS = 120 +SPI_PERF_RA_TMP_STALL_LS = 121 +SPI_PERF_RA_TMP_STALL_CSG = 122 +SPI_PERF_RA_TMP_STALL_CSN = 123 +SPI_PERF_RA_WAVE_SIMD_FULL_PS = 124 +SPI_PERF_RA_WAVE_SIMD_FULL_VS = 125 +SPI_PERF_RA_WAVE_SIMD_FULL_GS = 126 +SPI_PERF_RA_WAVE_SIMD_FULL_ES = 127 +SPI_PERF_RA_WAVE_SIMD_FULL_HS = 128 +SPI_PERF_RA_WAVE_SIMD_FULL_LS = 129 +SPI_PERF_RA_WAVE_SIMD_FULL_CSG = 130 +SPI_PERF_RA_WAVE_SIMD_FULL_CSN = 131 +SPI_PERF_RA_VGPR_SIMD_FULL_PS = 132 +SPI_PERF_RA_VGPR_SIMD_FULL_VS = 133 +SPI_PERF_RA_VGPR_SIMD_FULL_GS = 134 +SPI_PERF_RA_VGPR_SIMD_FULL_ES = 135 +SPI_PERF_RA_VGPR_SIMD_FULL_HS = 136 +SPI_PERF_RA_VGPR_SIMD_FULL_LS = 137 +SPI_PERF_RA_VGPR_SIMD_FULL_CSG = 138 +SPI_PERF_RA_VGPR_SIMD_FULL_CSN = 139 +SPI_PERF_RA_SGPR_SIMD_FULL_PS = 140 +SPI_PERF_RA_SGPR_SIMD_FULL_VS = 141 +SPI_PERF_RA_SGPR_SIMD_FULL_GS = 142 +SPI_PERF_RA_SGPR_SIMD_FULL_ES = 143 +SPI_PERF_RA_SGPR_SIMD_FULL_HS = 144 +SPI_PERF_RA_SGPR_SIMD_FULL_LS = 145 +SPI_PERF_RA_SGPR_SIMD_FULL_CSG = 146 +SPI_PERF_RA_SGPR_SIMD_FULL_CSN = 147 +SPI_PERF_RA_LDS_CU_FULL_PS = 148 +SPI_PERF_RA_LDS_CU_FULL_LS = 149 +SPI_PERF_RA_LDS_CU_FULL_ES = 150 +SPI_PERF_RA_LDS_CU_FULL_CSG = 151 +SPI_PERF_RA_LDS_CU_FULL_CSN = 152 +SPI_PERF_RA_BAR_CU_FULL_HS = 153 +SPI_PERF_RA_BAR_CU_FULL_CSG = 154 +SPI_PERF_RA_BAR_CU_FULL_CSN = 155 +SPI_PERF_RA_BULKY_CU_FULL_CSG = 156 +SPI_PERF_RA_BULKY_CU_FULL_CSN = 157 +SPI_PERF_RA_TGLIM_CU_FULL_CSG = 158 +SPI_PERF_RA_TGLIM_CU_FULL_CSN = 159 +SPI_PERF_RA_WVLIM_STALL_PS = 160 +SPI_PERF_RA_WVLIM_STALL_VS = 161 +SPI_PERF_RA_WVLIM_STALL_GS = 162 +SPI_PERF_RA_WVLIM_STALL_ES = 163 +SPI_PERF_RA_WVLIM_STALL_HS = 164 +SPI_PERF_RA_WVLIM_STALL_LS = 165 +SPI_PERF_RA_WVLIM_STALL_CSG = 166 +SPI_PERF_RA_WVLIM_STALL_CSN = 167 +SPI_PERF_RA_PS_LOCK_NA = 168 +SPI_PERF_RA_VS_LOCK = 169 +SPI_PERF_RA_GS_LOCK = 170 +SPI_PERF_RA_ES_LOCK = 171 +SPI_PERF_RA_HS_LOCK = 172 +SPI_PERF_RA_LS_LOCK = 173 +SPI_PERF_RA_CSG_LOCK = 174 +SPI_PERF_RA_CSN_LOCK = 175 +SPI_PERF_RA_RSV_UPD = 176 +SPI_PERF_EXP_ARB_COL_CNT = 177 +SPI_PERF_EXP_ARB_PAR_CNT = 178 +SPI_PERF_EXP_ARB_POS_CNT = 179 +SPI_PERF_EXP_ARB_GDS_CNT = 180 +SPI_PERF_CLKGATE_BUSY_STALL = 181 +SPI_PERF_CLKGATE_ACTIVE_STALL = 182 +SPI_PERF_CLKGATE_ALL_CLOCKS_ON = 183 +SPI_PERF_CLKGATE_CGTT_DYN_ON = 184 +SPI_PERF_CLKGATE_CGTT_REG_ON = 185 +SPI_PERF_NUM_VS_POS_EXPORTS = 186 +SPI_PERF_NUM_VS_PARAM_EXPORTS = 187 +SPI_PERF_NUM_PS_COL_EXPORTS = 188 +SPI_PERF_ES_GRP_FIFO_FULL = 189 +SPI_PERF_GS_GRP_FIFO_FULL = 190 +SPI_PERF_HS_GRP_FIFO_FULL = 191 +SPI_PERF_LS_GRP_FIFO_FULL = 192 +SPI_PERF_VS_ALLOC_CNT = 193 +SPI_PERF_VS_LATE_ALLOC_ACCUM = 194 +SPI_PERF_PC_ALLOC_CNT = 195 +SPI_PERF_PC_ALLOC_ACCUM = 196 +SPI_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_FORMAT' +SPI_SHADER_FORMAT__enumvalues = { + 0: 'SPI_SHADER_NONE', + 1: 'SPI_SHADER_1COMP', + 2: 'SPI_SHADER_2COMP', + 3: 'SPI_SHADER_4COMPRESS', + 4: 'SPI_SHADER_4COMP', +} +SPI_SHADER_NONE = 0 +SPI_SHADER_1COMP = 1 +SPI_SHADER_2COMP = 2 +SPI_SHADER_4COMPRESS = 3 +SPI_SHADER_4COMP = 4 +SPI_SHADER_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SPI_SHADER_EX_FORMAT' +SPI_SHADER_EX_FORMAT__enumvalues = { + 0: 'SPI_SHADER_ZERO', + 1: 'SPI_SHADER_32_R', + 2: 'SPI_SHADER_32_GR', + 3: 'SPI_SHADER_32_AR', + 4: 'SPI_SHADER_FP16_ABGR', + 5: 'SPI_SHADER_UNORM16_ABGR', + 6: 'SPI_SHADER_SNORM16_ABGR', + 7: 'SPI_SHADER_UINT16_ABGR', + 8: 'SPI_SHADER_SINT16_ABGR', + 9: 'SPI_SHADER_32_ABGR', +} +SPI_SHADER_ZERO = 0 +SPI_SHADER_32_R = 1 +SPI_SHADER_32_GR = 2 +SPI_SHADER_32_AR = 3 +SPI_SHADER_FP16_ABGR = 4 +SPI_SHADER_UNORM16_ABGR = 5 +SPI_SHADER_SNORM16_ABGR = 6 +SPI_SHADER_UINT16_ABGR = 7 +SPI_SHADER_SINT16_ABGR = 8 +SPI_SHADER_32_ABGR = 9 +SPI_SHADER_EX_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_SM_MODE' +CLKGATE_SM_MODE__enumvalues = { + 0: 'ON_SEQ', + 1: 'OFF_SEQ', + 2: 'PROG_SEQ', + 3: 'READ_SEQ', + 4: 'SM_MODE_RESERVED', +} +ON_SEQ = 0 +OFF_SEQ = 1 +PROG_SEQ = 2 +READ_SEQ = 3 +SM_MODE_RESERVED = 4 +CLKGATE_SM_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CLKGATE_BASE_MODE' +CLKGATE_BASE_MODE__enumvalues = { + 0: 'MULT_8', + 1: 'MULT_16', +} +MULT_8 = 0 +MULT_16 = 1 +CLKGATE_BASE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_CLAMP' +SQ_TEX_CLAMP__enumvalues = { + 0: 'SQ_TEX_WRAP', + 1: 'SQ_TEX_MIRROR', + 2: 'SQ_TEX_CLAMP_LAST_TEXEL', + 3: 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 4: 'SQ_TEX_CLAMP_HALF_BORDER', + 5: 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', + 6: 'SQ_TEX_CLAMP_BORDER', + 7: 'SQ_TEX_MIRROR_ONCE_BORDER', +} +SQ_TEX_WRAP = 0 +SQ_TEX_MIRROR = 1 +SQ_TEX_CLAMP_LAST_TEXEL = 2 +SQ_TEX_MIRROR_ONCE_LAST_TEXEL = 3 +SQ_TEX_CLAMP_HALF_BORDER = 4 +SQ_TEX_MIRROR_ONCE_HALF_BORDER = 5 +SQ_TEX_CLAMP_BORDER = 6 +SQ_TEX_MIRROR_ONCE_BORDER = 7 +SQ_TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_XY_FILTER' +SQ_TEX_XY_FILTER__enumvalues = { + 0: 'SQ_TEX_XY_FILTER_POINT', + 1: 'SQ_TEX_XY_FILTER_BILINEAR', + 2: 'SQ_TEX_XY_FILTER_ANISO_POINT', + 3: 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', +} +SQ_TEX_XY_FILTER_POINT = 0 +SQ_TEX_XY_FILTER_BILINEAR = 1 +SQ_TEX_XY_FILTER_ANISO_POINT = 2 +SQ_TEX_XY_FILTER_ANISO_BILINEAR = 3 +SQ_TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_Z_FILTER' +SQ_TEX_Z_FILTER__enumvalues = { + 0: 'SQ_TEX_Z_FILTER_NONE', + 1: 'SQ_TEX_Z_FILTER_POINT', + 2: 'SQ_TEX_Z_FILTER_LINEAR', +} +SQ_TEX_Z_FILTER_NONE = 0 +SQ_TEX_Z_FILTER_POINT = 1 +SQ_TEX_Z_FILTER_LINEAR = 2 +SQ_TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_MIP_FILTER' +SQ_TEX_MIP_FILTER__enumvalues = { + 0: 'SQ_TEX_MIP_FILTER_NONE', + 1: 'SQ_TEX_MIP_FILTER_POINT', + 2: 'SQ_TEX_MIP_FILTER_LINEAR', + 3: 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', +} +SQ_TEX_MIP_FILTER_NONE = 0 +SQ_TEX_MIP_FILTER_POINT = 1 +SQ_TEX_MIP_FILTER_LINEAR = 2 +SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ = 3 +SQ_TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_ANISO_RATIO' +SQ_TEX_ANISO_RATIO__enumvalues = { + 0: 'SQ_TEX_ANISO_RATIO_1', + 1: 'SQ_TEX_ANISO_RATIO_2', + 2: 'SQ_TEX_ANISO_RATIO_4', + 3: 'SQ_TEX_ANISO_RATIO_8', + 4: 'SQ_TEX_ANISO_RATIO_16', +} +SQ_TEX_ANISO_RATIO_1 = 0 +SQ_TEX_ANISO_RATIO_2 = 1 +SQ_TEX_ANISO_RATIO_4 = 2 +SQ_TEX_ANISO_RATIO_8 = 3 +SQ_TEX_ANISO_RATIO_16 = 4 +SQ_TEX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_DEPTH_COMPARE' +SQ_TEX_DEPTH_COMPARE__enumvalues = { + 0: 'SQ_TEX_DEPTH_COMPARE_NEVER', + 1: 'SQ_TEX_DEPTH_COMPARE_LESS', + 2: 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 3: 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', + 4: 'SQ_TEX_DEPTH_COMPARE_GREATER', + 5: 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', + 6: 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', + 7: 'SQ_TEX_DEPTH_COMPARE_ALWAYS', +} +SQ_TEX_DEPTH_COMPARE_NEVER = 0 +SQ_TEX_DEPTH_COMPARE_LESS = 1 +SQ_TEX_DEPTH_COMPARE_EQUAL = 2 +SQ_TEX_DEPTH_COMPARE_LESSEQUAL = 3 +SQ_TEX_DEPTH_COMPARE_GREATER = 4 +SQ_TEX_DEPTH_COMPARE_NOTEQUAL = 5 +SQ_TEX_DEPTH_COMPARE_GREATEREQUAL = 6 +SQ_TEX_DEPTH_COMPARE_ALWAYS = 7 +SQ_TEX_DEPTH_COMPARE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_TEX_BORDER_COLOR' +SQ_TEX_BORDER_COLOR__enumvalues = { + 0: 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 1: 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 2: 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 3: 'SQ_TEX_BORDER_COLOR_REGISTER', +} +SQ_TEX_BORDER_COLOR_TRANS_BLACK = 0 +SQ_TEX_BORDER_COLOR_OPAQUE_BLACK = 1 +SQ_TEX_BORDER_COLOR_OPAQUE_WHITE = 2 +SQ_TEX_BORDER_COLOR_REGISTER = 3 +SQ_TEX_BORDER_COLOR = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_BUF_TYPE' +SQ_RSRC_BUF_TYPE__enumvalues = { + 0: 'SQ_RSRC_BUF', + 1: 'SQ_RSRC_BUF_RSVD_1', + 2: 'SQ_RSRC_BUF_RSVD_2', + 3: 'SQ_RSRC_BUF_RSVD_3', +} +SQ_RSRC_BUF = 0 +SQ_RSRC_BUF_RSVD_1 = 1 +SQ_RSRC_BUF_RSVD_2 = 2 +SQ_RSRC_BUF_RSVD_3 = 3 +SQ_RSRC_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_IMG_TYPE' +SQ_RSRC_IMG_TYPE__enumvalues = { + 0: 'SQ_RSRC_IMG_RSVD_0', + 1: 'SQ_RSRC_IMG_RSVD_1', + 2: 'SQ_RSRC_IMG_RSVD_2', + 3: 'SQ_RSRC_IMG_RSVD_3', + 4: 'SQ_RSRC_IMG_RSVD_4', + 5: 'SQ_RSRC_IMG_RSVD_5', + 6: 'SQ_RSRC_IMG_RSVD_6', + 7: 'SQ_RSRC_IMG_RSVD_7', + 8: 'SQ_RSRC_IMG_1D', + 9: 'SQ_RSRC_IMG_2D', + 10: 'SQ_RSRC_IMG_3D', + 11: 'SQ_RSRC_IMG_CUBE', + 12: 'SQ_RSRC_IMG_1D_ARRAY', + 13: 'SQ_RSRC_IMG_2D_ARRAY', + 14: 'SQ_RSRC_IMG_2D_MSAA', + 15: 'SQ_RSRC_IMG_2D_MSAA_ARRAY', +} +SQ_RSRC_IMG_RSVD_0 = 0 +SQ_RSRC_IMG_RSVD_1 = 1 +SQ_RSRC_IMG_RSVD_2 = 2 +SQ_RSRC_IMG_RSVD_3 = 3 +SQ_RSRC_IMG_RSVD_4 = 4 +SQ_RSRC_IMG_RSVD_5 = 5 +SQ_RSRC_IMG_RSVD_6 = 6 +SQ_RSRC_IMG_RSVD_7 = 7 +SQ_RSRC_IMG_1D = 8 +SQ_RSRC_IMG_2D = 9 +SQ_RSRC_IMG_3D = 10 +SQ_RSRC_IMG_CUBE = 11 +SQ_RSRC_IMG_1D_ARRAY = 12 +SQ_RSRC_IMG_2D_ARRAY = 13 +SQ_RSRC_IMG_2D_MSAA = 14 +SQ_RSRC_IMG_2D_MSAA_ARRAY = 15 +SQ_RSRC_IMG_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_RSRC_FLAT_TYPE' +SQ_RSRC_FLAT_TYPE__enumvalues = { + 0: 'SQ_RSRC_FLAT_RSVD_0', + 1: 'SQ_RSRC_FLAT', + 2: 'SQ_RSRC_FLAT_RSVD_2', + 3: 'SQ_RSRC_FLAT_RSVD_3', +} +SQ_RSRC_FLAT_RSVD_0 = 0 +SQ_RSRC_FLAT = 1 +SQ_RSRC_FLAT_RSVD_2 = 2 +SQ_RSRC_FLAT_RSVD_3 = 3 +SQ_RSRC_FLAT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IMG_FILTER_TYPE' +SQ_IMG_FILTER_TYPE__enumvalues = { + 0: 'SQ_IMG_FILTER_MODE_BLEND', + 1: 'SQ_IMG_FILTER_MODE_MIN', + 2: 'SQ_IMG_FILTER_MODE_MAX', +} +SQ_IMG_FILTER_MODE_BLEND = 0 +SQ_IMG_FILTER_MODE_MIN = 1 +SQ_IMG_FILTER_MODE_MAX = 2 +SQ_IMG_FILTER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_SEL_XYZW01' +SQ_SEL_XYZW01__enumvalues = { + 0: 'SQ_SEL_0', + 1: 'SQ_SEL_1', + 2: 'SQ_SEL_RESERVED_0', + 3: 'SQ_SEL_RESERVED_1', + 4: 'SQ_SEL_X', + 5: 'SQ_SEL_Y', + 6: 'SQ_SEL_Z', + 7: 'SQ_SEL_W', +} +SQ_SEL_0 = 0 +SQ_SEL_1 = 1 +SQ_SEL_RESERVED_0 = 2 +SQ_SEL_RESERVED_1 = 3 +SQ_SEL_X = 4 +SQ_SEL_Y = 5 +SQ_SEL_Z = 6 +SQ_SEL_W = 7 +SQ_SEL_XYZW01 = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_TYPE' +SQ_WAVE_TYPE__enumvalues = { + 0: 'SQ_WAVE_TYPE_PS', + 1: 'SQ_WAVE_TYPE_VS', + 2: 'SQ_WAVE_TYPE_GS', + 3: 'SQ_WAVE_TYPE_ES', + 4: 'SQ_WAVE_TYPE_HS', + 5: 'SQ_WAVE_TYPE_LS', + 6: 'SQ_WAVE_TYPE_CS', + 7: 'SQ_WAVE_TYPE_PS1', +} +SQ_WAVE_TYPE_PS = 0 +SQ_WAVE_TYPE_VS = 1 +SQ_WAVE_TYPE_GS = 2 +SQ_WAVE_TYPE_ES = 3 +SQ_WAVE_TYPE_HS = 4 +SQ_WAVE_TYPE_LS = 5 +SQ_WAVE_TYPE_CS = 6 +SQ_WAVE_TYPE_PS1 = 7 +SQ_WAVE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_TOKEN_TYPE' +SQ_THREAD_TRACE_TOKEN_TYPE__enumvalues = { + 0: 'SQ_THREAD_TRACE_TOKEN_MISC', + 1: 'SQ_THREAD_TRACE_TOKEN_TIMESTAMP', + 2: 'SQ_THREAD_TRACE_TOKEN_REG', + 3: 'SQ_THREAD_TRACE_TOKEN_WAVE_START', + 4: 'SQ_THREAD_TRACE_TOKEN_WAVE_ALLOC', + 5: 'SQ_THREAD_TRACE_TOKEN_REG_CSPRIV', + 6: 'SQ_THREAD_TRACE_TOKEN_WAVE_END', + 7: 'SQ_THREAD_TRACE_TOKEN_EVENT', + 8: 'SQ_THREAD_TRACE_TOKEN_EVENT_CS', + 9: 'SQ_THREAD_TRACE_TOKEN_EVENT_GFX1', + 10: 'SQ_THREAD_TRACE_TOKEN_INST', + 11: 'SQ_THREAD_TRACE_TOKEN_INST_PC', + 12: 'SQ_THREAD_TRACE_TOKEN_INST_USERDATA', + 13: 'SQ_THREAD_TRACE_TOKEN_ISSUE', + 14: 'SQ_THREAD_TRACE_TOKEN_PERF', + 15: 'SQ_THREAD_TRACE_TOKEN_REG_CS', +} +SQ_THREAD_TRACE_TOKEN_MISC = 0 +SQ_THREAD_TRACE_TOKEN_TIMESTAMP = 1 +SQ_THREAD_TRACE_TOKEN_REG = 2 +SQ_THREAD_TRACE_TOKEN_WAVE_START = 3 +SQ_THREAD_TRACE_TOKEN_WAVE_ALLOC = 4 +SQ_THREAD_TRACE_TOKEN_REG_CSPRIV = 5 +SQ_THREAD_TRACE_TOKEN_WAVE_END = 6 +SQ_THREAD_TRACE_TOKEN_EVENT = 7 +SQ_THREAD_TRACE_TOKEN_EVENT_CS = 8 +SQ_THREAD_TRACE_TOKEN_EVENT_GFX1 = 9 +SQ_THREAD_TRACE_TOKEN_INST = 10 +SQ_THREAD_TRACE_TOKEN_INST_PC = 11 +SQ_THREAD_TRACE_TOKEN_INST_USERDATA = 12 +SQ_THREAD_TRACE_TOKEN_ISSUE = 13 +SQ_THREAD_TRACE_TOKEN_PERF = 14 +SQ_THREAD_TRACE_TOKEN_REG_CS = 15 +SQ_THREAD_TRACE_TOKEN_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_MISC_TOKEN_TYPE' +SQ_THREAD_TRACE_MISC_TOKEN_TYPE__enumvalues = { + 0: 'SQ_THREAD_TRACE_MISC_TOKEN_TIME', + 1: 'SQ_THREAD_TRACE_MISC_TOKEN_TIME_RESET', + 2: 'SQ_THREAD_TRACE_MISC_TOKEN_PACKET_LOST', + 3: 'SQ_THREAD_TRACE_MISC_TOKEN_SURF_SYNC', + 4: 'SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_BEGIN', + 5: 'SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_END', + 6: 'SQ_THREAD_TRACE_MISC_TOKEN_SAVECTX', + 7: 'SQ_THREAD_TRACE_MISC_TOKEN_SHOOT_DOWN', +} +SQ_THREAD_TRACE_MISC_TOKEN_TIME = 0 +SQ_THREAD_TRACE_MISC_TOKEN_TIME_RESET = 1 +SQ_THREAD_TRACE_MISC_TOKEN_PACKET_LOST = 2 +SQ_THREAD_TRACE_MISC_TOKEN_SURF_SYNC = 3 +SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_BEGIN = 4 +SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_END = 5 +SQ_THREAD_TRACE_MISC_TOKEN_SAVECTX = 6 +SQ_THREAD_TRACE_MISC_TOKEN_SHOOT_DOWN = 7 +SQ_THREAD_TRACE_MISC_TOKEN_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_INST_TYPE' +SQ_THREAD_TRACE_INST_TYPE__enumvalues = { + 0: 'SQ_THREAD_TRACE_INST_TYPE_SMEM_RD', + 1: 'SQ_THREAD_TRACE_INST_TYPE_SALU_32', + 2: 'SQ_THREAD_TRACE_INST_TYPE_VMEM_RD', + 3: 'SQ_THREAD_TRACE_INST_TYPE_VMEM_WR', + 4: 'SQ_THREAD_TRACE_INST_TYPE_FLAT_WR', + 5: 'SQ_THREAD_TRACE_INST_TYPE_VALU_32', + 6: 'SQ_THREAD_TRACE_INST_TYPE_LDS', + 7: 'SQ_THREAD_TRACE_INST_TYPE_PC', + 8: 'SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GDS', + 9: 'SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GFX', + 10: 'SQ_THREAD_TRACE_INST_TYPE_EXPGNT_PAR_COL', + 11: 'SQ_THREAD_TRACE_INST_TYPE_EXPGNT_POS_GDS', + 12: 'SQ_THREAD_TRACE_INST_TYPE_JUMP', + 13: 'SQ_THREAD_TRACE_INST_TYPE_NEXT', + 14: 'SQ_THREAD_TRACE_INST_TYPE_FLAT_RD', + 15: 'SQ_THREAD_TRACE_INST_TYPE_OTHER_MSG', + 16: 'SQ_THREAD_TRACE_INST_TYPE_SMEM_WR', + 17: 'SQ_THREAD_TRACE_INST_TYPE_SALU_64', + 18: 'SQ_THREAD_TRACE_INST_TYPE_VALU_64', + 19: 'SQ_THREAD_TRACE_INST_TYPE_SMEM_RD_REPLAY', + 20: 'SQ_THREAD_TRACE_INST_TYPE_SMEM_WR_REPLAY', + 21: 'SQ_THREAD_TRACE_INST_TYPE_VMEM_RD_REPLAY', + 22: 'SQ_THREAD_TRACE_INST_TYPE_VMEM_WR_REPLAY', + 23: 'SQ_THREAD_TRACE_INST_TYPE_FLAT_RD_REPLAY', + 24: 'SQ_THREAD_TRACE_INST_TYPE_FLAT_WR_REPLAY', + 25: 'SQ_THREAD_TRACE_INST_TYPE_FATAL_HALT', +} +SQ_THREAD_TRACE_INST_TYPE_SMEM_RD = 0 +SQ_THREAD_TRACE_INST_TYPE_SALU_32 = 1 +SQ_THREAD_TRACE_INST_TYPE_VMEM_RD = 2 +SQ_THREAD_TRACE_INST_TYPE_VMEM_WR = 3 +SQ_THREAD_TRACE_INST_TYPE_FLAT_WR = 4 +SQ_THREAD_TRACE_INST_TYPE_VALU_32 = 5 +SQ_THREAD_TRACE_INST_TYPE_LDS = 6 +SQ_THREAD_TRACE_INST_TYPE_PC = 7 +SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GDS = 8 +SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GFX = 9 +SQ_THREAD_TRACE_INST_TYPE_EXPGNT_PAR_COL = 10 +SQ_THREAD_TRACE_INST_TYPE_EXPGNT_POS_GDS = 11 +SQ_THREAD_TRACE_INST_TYPE_JUMP = 12 +SQ_THREAD_TRACE_INST_TYPE_NEXT = 13 +SQ_THREAD_TRACE_INST_TYPE_FLAT_RD = 14 +SQ_THREAD_TRACE_INST_TYPE_OTHER_MSG = 15 +SQ_THREAD_TRACE_INST_TYPE_SMEM_WR = 16 +SQ_THREAD_TRACE_INST_TYPE_SALU_64 = 17 +SQ_THREAD_TRACE_INST_TYPE_VALU_64 = 18 +SQ_THREAD_TRACE_INST_TYPE_SMEM_RD_REPLAY = 19 +SQ_THREAD_TRACE_INST_TYPE_SMEM_WR_REPLAY = 20 +SQ_THREAD_TRACE_INST_TYPE_VMEM_RD_REPLAY = 21 +SQ_THREAD_TRACE_INST_TYPE_VMEM_WR_REPLAY = 22 +SQ_THREAD_TRACE_INST_TYPE_FLAT_RD_REPLAY = 23 +SQ_THREAD_TRACE_INST_TYPE_FLAT_WR_REPLAY = 24 +SQ_THREAD_TRACE_INST_TYPE_FATAL_HALT = 25 +SQ_THREAD_TRACE_INST_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_REG_TYPE' +SQ_THREAD_TRACE_REG_TYPE__enumvalues = { + 0: 'SQ_THREAD_TRACE_REG_TYPE_EVENT', + 1: 'SQ_THREAD_TRACE_REG_TYPE_DRAW', + 2: 'SQ_THREAD_TRACE_REG_TYPE_DISPATCH', + 3: 'SQ_THREAD_TRACE_REG_TYPE_USERDATA', + 4: 'SQ_THREAD_TRACE_REG_TYPE_MARKER', + 5: 'SQ_THREAD_TRACE_REG_TYPE_GFXDEC', + 6: 'SQ_THREAD_TRACE_REG_TYPE_SHDEC', + 7: 'SQ_THREAD_TRACE_REG_TYPE_OTHER', +} +SQ_THREAD_TRACE_REG_TYPE_EVENT = 0 +SQ_THREAD_TRACE_REG_TYPE_DRAW = 1 +SQ_THREAD_TRACE_REG_TYPE_DISPATCH = 2 +SQ_THREAD_TRACE_REG_TYPE_USERDATA = 3 +SQ_THREAD_TRACE_REG_TYPE_MARKER = 4 +SQ_THREAD_TRACE_REG_TYPE_GFXDEC = 5 +SQ_THREAD_TRACE_REG_TYPE_SHDEC = 6 +SQ_THREAD_TRACE_REG_TYPE_OTHER = 7 +SQ_THREAD_TRACE_REG_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_REG_OP' +SQ_THREAD_TRACE_REG_OP__enumvalues = { + 0: 'SQ_THREAD_TRACE_REG_OP_READ', + 1: 'SQ_THREAD_TRACE_REG_OP_WRITE', +} +SQ_THREAD_TRACE_REG_OP_READ = 0 +SQ_THREAD_TRACE_REG_OP_WRITE = 1 +SQ_THREAD_TRACE_REG_OP = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_MODE_SEL' +SQ_THREAD_TRACE_MODE_SEL__enumvalues = { + 0: 'SQ_THREAD_TRACE_MODE_OFF', + 1: 'SQ_THREAD_TRACE_MODE_ON', +} +SQ_THREAD_TRACE_MODE_OFF = 0 +SQ_THREAD_TRACE_MODE_ON = 1 +SQ_THREAD_TRACE_MODE_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_CAPTURE_MODE' +SQ_THREAD_TRACE_CAPTURE_MODE__enumvalues = { + 0: 'SQ_THREAD_TRACE_CAPTURE_MODE_ALL', + 1: 'SQ_THREAD_TRACE_CAPTURE_MODE_SELECT', + 2: 'SQ_THREAD_TRACE_CAPTURE_MODE_SELECT_DETAIL', +} +SQ_THREAD_TRACE_CAPTURE_MODE_ALL = 0 +SQ_THREAD_TRACE_CAPTURE_MODE_SELECT = 1 +SQ_THREAD_TRACE_CAPTURE_MODE_SELECT_DETAIL = 2 +SQ_THREAD_TRACE_CAPTURE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_VM_ID_MASK' +SQ_THREAD_TRACE_VM_ID_MASK__enumvalues = { + 0: 'SQ_THREAD_TRACE_VM_ID_MASK_SINGLE', + 1: 'SQ_THREAD_TRACE_VM_ID_MASK_ALL', + 2: 'SQ_THREAD_TRACE_VM_ID_MASK_SINGLE_DETAIL', +} +SQ_THREAD_TRACE_VM_ID_MASK_SINGLE = 0 +SQ_THREAD_TRACE_VM_ID_MASK_ALL = 1 +SQ_THREAD_TRACE_VM_ID_MASK_SINGLE_DETAIL = 2 +SQ_THREAD_TRACE_VM_ID_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_WAVE_MASK' +SQ_THREAD_TRACE_WAVE_MASK__enumvalues = { + 0: 'SQ_THREAD_TRACE_WAVE_MASK_NONE', + 1: 'SQ_THREAD_TRACE_WAVE_MASK_ALL', +} +SQ_THREAD_TRACE_WAVE_MASK_NONE = 0 +SQ_THREAD_TRACE_WAVE_MASK_ALL = 1 +SQ_THREAD_TRACE_WAVE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_ISSUE' +SQ_THREAD_TRACE_ISSUE__enumvalues = { + 0: 'SQ_THREAD_TRACE_ISSUE_NULL', + 1: 'SQ_THREAD_TRACE_ISSUE_STALL', + 2: 'SQ_THREAD_TRACE_ISSUE_INST', + 3: 'SQ_THREAD_TRACE_ISSUE_IMMED', +} +SQ_THREAD_TRACE_ISSUE_NULL = 0 +SQ_THREAD_TRACE_ISSUE_STALL = 1 +SQ_THREAD_TRACE_ISSUE_INST = 2 +SQ_THREAD_TRACE_ISSUE_IMMED = 3 +SQ_THREAD_TRACE_ISSUE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_ISSUE_MASK' +SQ_THREAD_TRACE_ISSUE_MASK__enumvalues = { + 0: 'SQ_THREAD_TRACE_ISSUE_MASK_ALL', + 1: 'SQ_THREAD_TRACE_ISSUE_MASK_STALLED', + 2: 'SQ_THREAD_TRACE_ISSUE_MASK_STALLED_AND_IMMED', + 3: 'SQ_THREAD_TRACE_ISSUE_MASK_IMMED', +} +SQ_THREAD_TRACE_ISSUE_MASK_ALL = 0 +SQ_THREAD_TRACE_ISSUE_MASK_STALLED = 1 +SQ_THREAD_TRACE_ISSUE_MASK_STALLED_AND_IMMED = 2 +SQ_THREAD_TRACE_ISSUE_MASK_IMMED = 3 +SQ_THREAD_TRACE_ISSUE_MASK = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_PERF_SEL' +SQ_PERF_SEL__enumvalues = { + 0: 'SQ_PERF_SEL_NONE', + 1: 'SQ_PERF_SEL_ACCUM_PREV', + 2: 'SQ_PERF_SEL_CYCLES', + 3: 'SQ_PERF_SEL_BUSY_CYCLES', + 4: 'SQ_PERF_SEL_WAVES', + 5: 'SQ_PERF_SEL_LEVEL_WAVES', + 6: 'SQ_PERF_SEL_WAVES_EQ_64', + 7: 'SQ_PERF_SEL_WAVES_LT_64', + 8: 'SQ_PERF_SEL_WAVES_LT_48', + 9: 'SQ_PERF_SEL_WAVES_LT_32', + 10: 'SQ_PERF_SEL_WAVES_LT_16', + 11: 'SQ_PERF_SEL_WAVES_CU', + 12: 'SQ_PERF_SEL_LEVEL_WAVES_CU', + 13: 'SQ_PERF_SEL_BUSY_CU_CYCLES', + 14: 'SQ_PERF_SEL_ITEMS', + 15: 'SQ_PERF_SEL_QUADS', + 16: 'SQ_PERF_SEL_EVENTS', + 17: 'SQ_PERF_SEL_SURF_SYNCS', + 18: 'SQ_PERF_SEL_TTRACE_REQS', + 19: 'SQ_PERF_SEL_TTRACE_INFLIGHT_REQS', + 20: 'SQ_PERF_SEL_TTRACE_STALL', + 21: 'SQ_PERF_SEL_MSG_CNTR', + 22: 'SQ_PERF_SEL_MSG_PERF', + 23: 'SQ_PERF_SEL_MSG_GSCNT', + 24: 'SQ_PERF_SEL_MSG_INTERRUPT', + 25: 'SQ_PERF_SEL_INSTS', + 26: 'SQ_PERF_SEL_INSTS_VALU', + 27: 'SQ_PERF_SEL_INSTS_VMEM_WR', + 28: 'SQ_PERF_SEL_INSTS_VMEM_RD', + 29: 'SQ_PERF_SEL_INSTS_VMEM', + 30: 'SQ_PERF_SEL_INSTS_SALU', + 31: 'SQ_PERF_SEL_INSTS_SMEM', + 32: 'SQ_PERF_SEL_INSTS_FLAT', + 33: 'SQ_PERF_SEL_INSTS_FLAT_LDS_ONLY', + 34: 'SQ_PERF_SEL_INSTS_LDS', + 35: 'SQ_PERF_SEL_INSTS_GDS', + 36: 'SQ_PERF_SEL_INSTS_EXP', + 37: 'SQ_PERF_SEL_INSTS_EXP_GDS', + 38: 'SQ_PERF_SEL_INSTS_BRANCH', + 39: 'SQ_PERF_SEL_INSTS_SENDMSG', + 40: 'SQ_PERF_SEL_INSTS_VSKIPPED', + 41: 'SQ_PERF_SEL_INST_LEVEL_VMEM', + 42: 'SQ_PERF_SEL_INST_LEVEL_SMEM', + 43: 'SQ_PERF_SEL_INST_LEVEL_LDS', + 44: 'SQ_PERF_SEL_INST_LEVEL_GDS', + 45: 'SQ_PERF_SEL_INST_LEVEL_EXP', + 46: 'SQ_PERF_SEL_WAVE_CYCLES', + 47: 'SQ_PERF_SEL_WAVE_READY', + 48: 'SQ_PERF_SEL_WAIT_CNT_VM', + 49: 'SQ_PERF_SEL_WAIT_CNT_LGKM', + 50: 'SQ_PERF_SEL_WAIT_CNT_EXP', + 51: 'SQ_PERF_SEL_WAIT_CNT_ANY', + 52: 'SQ_PERF_SEL_WAIT_BARRIER', + 53: 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 54: 'SQ_PERF_SEL_WAIT_SLEEP', + 55: 'SQ_PERF_SEL_WAIT_SLEEP_XNACK', + 56: 'SQ_PERF_SEL_WAIT_OTHER', + 57: 'SQ_PERF_SEL_WAIT_ANY', + 58: 'SQ_PERF_SEL_WAIT_TTRACE', + 59: 'SQ_PERF_SEL_WAIT_IFETCH', + 60: 'SQ_PERF_SEL_WAIT_INST_ANY', + 61: 'SQ_PERF_SEL_WAIT_INST_VMEM', + 62: 'SQ_PERF_SEL_WAIT_INST_SCA', + 63: 'SQ_PERF_SEL_WAIT_INST_LDS', + 64: 'SQ_PERF_SEL_WAIT_INST_VALU', + 65: 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', + 66: 'SQ_PERF_SEL_WAIT_INST_MISC', + 67: 'SQ_PERF_SEL_WAIT_INST_FLAT', + 68: 'SQ_PERF_SEL_ACTIVE_INST_ANY', + 69: 'SQ_PERF_SEL_ACTIVE_INST_VMEM', + 70: 'SQ_PERF_SEL_ACTIVE_INST_LDS', + 71: 'SQ_PERF_SEL_ACTIVE_INST_VALU', + 72: 'SQ_PERF_SEL_ACTIVE_INST_SCA', + 73: 'SQ_PERF_SEL_ACTIVE_INST_EXP_GDS', + 74: 'SQ_PERF_SEL_ACTIVE_INST_MISC', + 75: 'SQ_PERF_SEL_ACTIVE_INST_FLAT', + 76: 'SQ_PERF_SEL_INST_CYCLES_VMEM_WR', + 77: 'SQ_PERF_SEL_INST_CYCLES_VMEM_RD', + 78: 'SQ_PERF_SEL_INST_CYCLES_VMEM_ADDR', + 79: 'SQ_PERF_SEL_INST_CYCLES_VMEM_DATA', + 80: 'SQ_PERF_SEL_INST_CYCLES_VMEM_CMD', + 81: 'SQ_PERF_SEL_INST_CYCLES_EXP', + 82: 'SQ_PERF_SEL_INST_CYCLES_GDS', + 83: 'SQ_PERF_SEL_INST_CYCLES_SMEM', + 84: 'SQ_PERF_SEL_INST_CYCLES_SALU', + 85: 'SQ_PERF_SEL_THREAD_CYCLES_VALU', + 86: 'SQ_PERF_SEL_THREAD_CYCLES_VALU_MAX', + 87: 'SQ_PERF_SEL_IFETCH', + 88: 'SQ_PERF_SEL_IFETCH_LEVEL', + 89: 'SQ_PERF_SEL_CBRANCH_FORK', + 90: 'SQ_PERF_SEL_CBRANCH_FORK_SPLIT', + 91: 'SQ_PERF_SEL_VALU_LDS_DIRECT_RD', + 92: 'SQ_PERF_SEL_VALU_LDS_INTERP_OP', + 93: 'SQ_PERF_SEL_LDS_BANK_CONFLICT', + 94: 'SQ_PERF_SEL_LDS_ADDR_CONFLICT', + 95: 'SQ_PERF_SEL_LDS_UNALIGNED_STALL', + 96: 'SQ_PERF_SEL_LDS_MEM_VIOLATIONS', + 97: 'SQ_PERF_SEL_LDS_ATOMIC_RETURN', + 98: 'SQ_PERF_SEL_LDS_IDX_ACTIVE', + 99: 'SQ_PERF_SEL_VALU_DEP_STALL', + 100: 'SQ_PERF_SEL_VALU_STARVE', + 101: 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 102: 'SQ_PERF_SEL_LDS_DATA_FIFO_FULL', + 103: 'SQ_PERF_SEL_LDS_CMD_FIFO_FULL', + 104: 'SQ_PERF_SEL_VMEM_TA_ADDR_FIFO_FULL', + 105: 'SQ_PERF_SEL_VMEM_TA_CMD_FIFO_FULL', + 106: 'SQ_PERF_SEL_VMEM_EX_DATA_REG_BUSY', + 107: 'SQ_PERF_SEL_VMEM_WR_TA_DATA_FIFO_FULL', + 108: 'SQ_PERF_SEL_VALU_SRC_C_CONFLICT', + 109: 'SQ_PERF_SEL_VMEM_RD_SRC_CD_CONFLICT', + 110: 'SQ_PERF_SEL_VMEM_WR_SRC_CD_CONFLICT', + 111: 'SQ_PERF_SEL_FLAT_SRC_CD_CONFLICT', + 112: 'SQ_PERF_SEL_LDS_SRC_CD_CONFLICT', + 113: 'SQ_PERF_SEL_SRC_CD_BUSY', + 114: 'SQ_PERF_SEL_PT_POWER_STALL', + 115: 'SQ_PERF_SEL_USER0', + 116: 'SQ_PERF_SEL_USER1', + 117: 'SQ_PERF_SEL_USER2', + 118: 'SQ_PERF_SEL_USER3', + 119: 'SQ_PERF_SEL_USER4', + 120: 'SQ_PERF_SEL_USER5', + 121: 'SQ_PERF_SEL_USER6', + 122: 'SQ_PERF_SEL_USER7', + 123: 'SQ_PERF_SEL_USER8', + 124: 'SQ_PERF_SEL_USER9', + 125: 'SQ_PERF_SEL_USER10', + 126: 'SQ_PERF_SEL_USER11', + 127: 'SQ_PERF_SEL_USER12', + 128: 'SQ_PERF_SEL_USER13', + 129: 'SQ_PERF_SEL_USER14', + 130: 'SQ_PERF_SEL_USER15', + 131: 'SQ_PERF_SEL_USER_LEVEL0', + 132: 'SQ_PERF_SEL_USER_LEVEL1', + 133: 'SQ_PERF_SEL_USER_LEVEL2', + 134: 'SQ_PERF_SEL_USER_LEVEL3', + 135: 'SQ_PERF_SEL_USER_LEVEL4', + 136: 'SQ_PERF_SEL_USER_LEVEL5', + 137: 'SQ_PERF_SEL_USER_LEVEL6', + 138: 'SQ_PERF_SEL_USER_LEVEL7', + 139: 'SQ_PERF_SEL_USER_LEVEL8', + 140: 'SQ_PERF_SEL_USER_LEVEL9', + 141: 'SQ_PERF_SEL_USER_LEVEL10', + 142: 'SQ_PERF_SEL_USER_LEVEL11', + 143: 'SQ_PERF_SEL_USER_LEVEL12', + 144: 'SQ_PERF_SEL_USER_LEVEL13', + 145: 'SQ_PERF_SEL_USER_LEVEL14', + 146: 'SQ_PERF_SEL_USER_LEVEL15', + 147: 'SQ_PERF_SEL_POWER_VALU', + 148: 'SQ_PERF_SEL_POWER_VALU0', + 149: 'SQ_PERF_SEL_POWER_VALU1', + 150: 'SQ_PERF_SEL_POWER_VALU2', + 151: 'SQ_PERF_SEL_POWER_GPR_RD', + 152: 'SQ_PERF_SEL_POWER_GPR_WR', + 153: 'SQ_PERF_SEL_POWER_LDS_BUSY', + 154: 'SQ_PERF_SEL_POWER_ALU_BUSY', + 155: 'SQ_PERF_SEL_POWER_TEX_BUSY', + 156: 'SQ_PERF_SEL_ACCUM_PREV_HIRES', + 157: 'SQ_PERF_SEL_WAVES_RESTORED', + 158: 'SQ_PERF_SEL_WAVES_SAVED', + 159: 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 160: 'SQ_PERF_SEL_ATC_INSTS_VMEM', + 161: 'SQ_PERF_SEL_ATC_INST_LEVEL_VMEM', + 162: 'SQ_PERF_SEL_ATC_XNACK_FIRST', + 163: 'SQ_PERF_SEL_ATC_XNACK_ALL', + 164: 'SQ_PERF_SEL_ATC_XNACK_FIFO_FULL', + 165: 'SQ_PERF_SEL_ATC_INSTS_SMEM', + 166: 'SQ_PERF_SEL_ATC_INST_LEVEL_SMEM', + 167: 'SQ_PERF_SEL_IFETCH_XNACK', + 168: 'SQ_PERF_SEL_TLB_SHOOTDOWN', + 169: 'SQ_PERF_SEL_TLB_SHOOTDOWN_CYCLES', + 170: 'SQ_PERF_SEL_INSTS_VMEM_WR_REPLAY', + 171: 'SQ_PERF_SEL_INSTS_VMEM_RD_REPLAY', + 172: 'SQ_PERF_SEL_INSTS_VMEM_REPLAY', + 173: 'SQ_PERF_SEL_INSTS_SMEM_REPLAY', + 174: 'SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY', + 175: 'SQ_PERF_SEL_INSTS_FLAT_REPLAY', + 176: 'SQ_PERF_SEL_ATC_INSTS_VMEM_REPLAY', + 177: 'SQ_PERF_SEL_ATC_INSTS_SMEM_REPLAY', + 178: 'SQ_PERF_SEL_UTCL1_TRANSLATION_MISS', + 179: 'SQ_PERF_SEL_UTCL1_PERMISSION_MISS', + 180: 'SQ_PERF_SEL_UTCL1_REQUEST', + 181: 'SQ_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 182: 'SQ_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 183: 'SQ_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 184: 'SQ_PERF_SEL_UTCL1_LFIFO_FULL', + 185: 'SQ_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 186: 'SQ_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 187: 'SQ_PERF_SEL_DUMMY_END', + 255: 'SQ_PERF_SEL_DUMMY_LAST', + 256: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READY', + 257: 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 258: 'SQC_PERF_SEL_ICACHE_INPUT_VALIDB', + 259: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READY', + 260: 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 261: 'SQC_PERF_SEL_DCACHE_INPUT_VALIDB', + 262: 'SQC_PERF_SEL_TC_REQ', + 263: 'SQC_PERF_SEL_TC_INST_REQ', + 264: 'SQC_PERF_SEL_TC_DATA_READ_REQ', + 265: 'SQC_PERF_SEL_TC_DATA_WRITE_REQ', + 266: 'SQC_PERF_SEL_TC_DATA_ATOMIC_REQ', + 267: 'SQC_PERF_SEL_TC_STALL', + 268: 'SQC_PERF_SEL_TC_STARVE', + 269: 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 270: 'SQC_PERF_SEL_ICACHE_REQ', + 271: 'SQC_PERF_SEL_ICACHE_HITS', + 272: 'SQC_PERF_SEL_ICACHE_MISSES', + 273: 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 274: 'SQC_PERF_SEL_ICACHE_INVAL_INST', + 275: 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 276: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 277: 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 278: 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 279: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO', + 280: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 281: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT', + 282: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 283: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 284: 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF', + 285: 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 286: 'SQC_PERF_SEL_ICACHE_PREFETCH_1', + 287: 'SQC_PERF_SEL_ICACHE_PREFETCH_2', + 288: 'SQC_PERF_SEL_ICACHE_PREFETCH_FILTERED', + 289: 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 290: 'SQC_PERF_SEL_DCACHE_REQ', + 291: 'SQC_PERF_SEL_DCACHE_HITS', + 292: 'SQC_PERF_SEL_DCACHE_MISSES', + 293: 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 294: 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 295: 'SQC_PERF_SEL_DCACHE_MISS_EVICT_READ', + 296: 'SQC_PERF_SEL_DCACHE_WC_LRU_WRITE', + 297: 'SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE', + 298: 'SQC_PERF_SEL_DCACHE_ATOMIC', + 299: 'SQC_PERF_SEL_DCACHE_VOLATILE', + 300: 'SQC_PERF_SEL_DCACHE_INVAL_INST', + 301: 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 302: 'SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_INST', + 303: 'SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_ASYNC', + 304: 'SQC_PERF_SEL_DCACHE_WB_INST', + 305: 'SQC_PERF_SEL_DCACHE_WB_ASYNC', + 306: 'SQC_PERF_SEL_DCACHE_WB_VOLATILE_INST', + 307: 'SQC_PERF_SEL_DCACHE_WB_VOLATILE_ASYNC', + 308: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 309: 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 310: 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 311: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 312: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 313: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT', + 314: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED', + 315: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE', + 316: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT', + 317: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH', + 318: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE', + 319: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 320: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 321: 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF', + 322: 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 323: 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 324: 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 325: 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 326: 'SQC_PERF_SEL_DCACHE_REQ_READ_8', + 327: 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 328: 'SQC_PERF_SEL_DCACHE_REQ_TIME', + 329: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_1', + 330: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_2', + 331: 'SQC_PERF_SEL_DCACHE_REQ_WRITE_4', + 332: 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 333: 'SQC_PERF_SEL_SQ_DCACHE_REQS', + 334: 'SQC_PERF_SEL_DCACHE_FLAT_REQ', + 335: 'SQC_PERF_SEL_DCACHE_NONFLAT_REQ', + 336: 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 337: 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 338: 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', + 339: 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 340: 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 341: 'SQC_PERF_SEL_ICACHE_GATCL1_TRANSLATION_MISS', + 342: 'SQC_PERF_SEL_ICACHE_GATCL1_PERMISSION_MISS', + 343: 'SQC_PERF_SEL_ICACHE_GATCL1_REQUEST', + 344: 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_INFLIGHT_MAX', + 345: 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_LRU_INFLIGHT', + 346: 'SQC_PERF_SEL_ICACHE_GATCL1_LFIFO_FULL', + 347: 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_LFIFO_NOT_RES', + 348: 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS', + 349: 'SQC_PERF_SEL_ICACHE_GATCL1_ATCL2_INFLIGHT', + 350: 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_MISSFIFO_FULL', + 351: 'SQC_PERF_SEL_DCACHE_GATCL1_TRANSLATION_MISS', + 352: 'SQC_PERF_SEL_DCACHE_GATCL1_PERMISSION_MISS', + 353: 'SQC_PERF_SEL_DCACHE_GATCL1_REQUEST', + 354: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_INFLIGHT_MAX', + 355: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_LRU_INFLIGHT', + 356: 'SQC_PERF_SEL_DCACHE_GATCL1_LFIFO_FULL', + 357: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_LFIFO_NOT_RES', + 358: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS', + 359: 'SQC_PERF_SEL_DCACHE_GATCL1_ATCL2_INFLIGHT', + 360: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_MISSFIFO_FULL', + 361: 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_MULTI_MISS', + 362: 'SQC_PERF_SEL_DCACHE_GATCL1_HIT_FIFO_FULL', + 363: 'SQC_PERF_SEL_DUMMY_LAST', +} +SQ_PERF_SEL_NONE = 0 +SQ_PERF_SEL_ACCUM_PREV = 1 +SQ_PERF_SEL_CYCLES = 2 +SQ_PERF_SEL_BUSY_CYCLES = 3 +SQ_PERF_SEL_WAVES = 4 +SQ_PERF_SEL_LEVEL_WAVES = 5 +SQ_PERF_SEL_WAVES_EQ_64 = 6 +SQ_PERF_SEL_WAVES_LT_64 = 7 +SQ_PERF_SEL_WAVES_LT_48 = 8 +SQ_PERF_SEL_WAVES_LT_32 = 9 +SQ_PERF_SEL_WAVES_LT_16 = 10 +SQ_PERF_SEL_WAVES_CU = 11 +SQ_PERF_SEL_LEVEL_WAVES_CU = 12 +SQ_PERF_SEL_BUSY_CU_CYCLES = 13 +SQ_PERF_SEL_ITEMS = 14 +SQ_PERF_SEL_QUADS = 15 +SQ_PERF_SEL_EVENTS = 16 +SQ_PERF_SEL_SURF_SYNCS = 17 +SQ_PERF_SEL_TTRACE_REQS = 18 +SQ_PERF_SEL_TTRACE_INFLIGHT_REQS = 19 +SQ_PERF_SEL_TTRACE_STALL = 20 +SQ_PERF_SEL_MSG_CNTR = 21 +SQ_PERF_SEL_MSG_PERF = 22 +SQ_PERF_SEL_MSG_GSCNT = 23 +SQ_PERF_SEL_MSG_INTERRUPT = 24 +SQ_PERF_SEL_INSTS = 25 +SQ_PERF_SEL_INSTS_VALU = 26 +SQ_PERF_SEL_INSTS_VMEM_WR = 27 +SQ_PERF_SEL_INSTS_VMEM_RD = 28 +SQ_PERF_SEL_INSTS_VMEM = 29 +SQ_PERF_SEL_INSTS_SALU = 30 +SQ_PERF_SEL_INSTS_SMEM = 31 +SQ_PERF_SEL_INSTS_FLAT = 32 +SQ_PERF_SEL_INSTS_FLAT_LDS_ONLY = 33 +SQ_PERF_SEL_INSTS_LDS = 34 +SQ_PERF_SEL_INSTS_GDS = 35 +SQ_PERF_SEL_INSTS_EXP = 36 +SQ_PERF_SEL_INSTS_EXP_GDS = 37 +SQ_PERF_SEL_INSTS_BRANCH = 38 +SQ_PERF_SEL_INSTS_SENDMSG = 39 +SQ_PERF_SEL_INSTS_VSKIPPED = 40 +SQ_PERF_SEL_INST_LEVEL_VMEM = 41 +SQ_PERF_SEL_INST_LEVEL_SMEM = 42 +SQ_PERF_SEL_INST_LEVEL_LDS = 43 +SQ_PERF_SEL_INST_LEVEL_GDS = 44 +SQ_PERF_SEL_INST_LEVEL_EXP = 45 +SQ_PERF_SEL_WAVE_CYCLES = 46 +SQ_PERF_SEL_WAVE_READY = 47 +SQ_PERF_SEL_WAIT_CNT_VM = 48 +SQ_PERF_SEL_WAIT_CNT_LGKM = 49 +SQ_PERF_SEL_WAIT_CNT_EXP = 50 +SQ_PERF_SEL_WAIT_CNT_ANY = 51 +SQ_PERF_SEL_WAIT_BARRIER = 52 +SQ_PERF_SEL_WAIT_EXP_ALLOC = 53 +SQ_PERF_SEL_WAIT_SLEEP = 54 +SQ_PERF_SEL_WAIT_SLEEP_XNACK = 55 +SQ_PERF_SEL_WAIT_OTHER = 56 +SQ_PERF_SEL_WAIT_ANY = 57 +SQ_PERF_SEL_WAIT_TTRACE = 58 +SQ_PERF_SEL_WAIT_IFETCH = 59 +SQ_PERF_SEL_WAIT_INST_ANY = 60 +SQ_PERF_SEL_WAIT_INST_VMEM = 61 +SQ_PERF_SEL_WAIT_INST_SCA = 62 +SQ_PERF_SEL_WAIT_INST_LDS = 63 +SQ_PERF_SEL_WAIT_INST_VALU = 64 +SQ_PERF_SEL_WAIT_INST_EXP_GDS = 65 +SQ_PERF_SEL_WAIT_INST_MISC = 66 +SQ_PERF_SEL_WAIT_INST_FLAT = 67 +SQ_PERF_SEL_ACTIVE_INST_ANY = 68 +SQ_PERF_SEL_ACTIVE_INST_VMEM = 69 +SQ_PERF_SEL_ACTIVE_INST_LDS = 70 +SQ_PERF_SEL_ACTIVE_INST_VALU = 71 +SQ_PERF_SEL_ACTIVE_INST_SCA = 72 +SQ_PERF_SEL_ACTIVE_INST_EXP_GDS = 73 +SQ_PERF_SEL_ACTIVE_INST_MISC = 74 +SQ_PERF_SEL_ACTIVE_INST_FLAT = 75 +SQ_PERF_SEL_INST_CYCLES_VMEM_WR = 76 +SQ_PERF_SEL_INST_CYCLES_VMEM_RD = 77 +SQ_PERF_SEL_INST_CYCLES_VMEM_ADDR = 78 +SQ_PERF_SEL_INST_CYCLES_VMEM_DATA = 79 +SQ_PERF_SEL_INST_CYCLES_VMEM_CMD = 80 +SQ_PERF_SEL_INST_CYCLES_EXP = 81 +SQ_PERF_SEL_INST_CYCLES_GDS = 82 +SQ_PERF_SEL_INST_CYCLES_SMEM = 83 +SQ_PERF_SEL_INST_CYCLES_SALU = 84 +SQ_PERF_SEL_THREAD_CYCLES_VALU = 85 +SQ_PERF_SEL_THREAD_CYCLES_VALU_MAX = 86 +SQ_PERF_SEL_IFETCH = 87 +SQ_PERF_SEL_IFETCH_LEVEL = 88 +SQ_PERF_SEL_CBRANCH_FORK = 89 +SQ_PERF_SEL_CBRANCH_FORK_SPLIT = 90 +SQ_PERF_SEL_VALU_LDS_DIRECT_RD = 91 +SQ_PERF_SEL_VALU_LDS_INTERP_OP = 92 +SQ_PERF_SEL_LDS_BANK_CONFLICT = 93 +SQ_PERF_SEL_LDS_ADDR_CONFLICT = 94 +SQ_PERF_SEL_LDS_UNALIGNED_STALL = 95 +SQ_PERF_SEL_LDS_MEM_VIOLATIONS = 96 +SQ_PERF_SEL_LDS_ATOMIC_RETURN = 97 +SQ_PERF_SEL_LDS_IDX_ACTIVE = 98 +SQ_PERF_SEL_VALU_DEP_STALL = 99 +SQ_PERF_SEL_VALU_STARVE = 100 +SQ_PERF_SEL_EXP_REQ_FIFO_FULL = 101 +SQ_PERF_SEL_LDS_DATA_FIFO_FULL = 102 +SQ_PERF_SEL_LDS_CMD_FIFO_FULL = 103 +SQ_PERF_SEL_VMEM_TA_ADDR_FIFO_FULL = 104 +SQ_PERF_SEL_VMEM_TA_CMD_FIFO_FULL = 105 +SQ_PERF_SEL_VMEM_EX_DATA_REG_BUSY = 106 +SQ_PERF_SEL_VMEM_WR_TA_DATA_FIFO_FULL = 107 +SQ_PERF_SEL_VALU_SRC_C_CONFLICT = 108 +SQ_PERF_SEL_VMEM_RD_SRC_CD_CONFLICT = 109 +SQ_PERF_SEL_VMEM_WR_SRC_CD_CONFLICT = 110 +SQ_PERF_SEL_FLAT_SRC_CD_CONFLICT = 111 +SQ_PERF_SEL_LDS_SRC_CD_CONFLICT = 112 +SQ_PERF_SEL_SRC_CD_BUSY = 113 +SQ_PERF_SEL_PT_POWER_STALL = 114 +SQ_PERF_SEL_USER0 = 115 +SQ_PERF_SEL_USER1 = 116 +SQ_PERF_SEL_USER2 = 117 +SQ_PERF_SEL_USER3 = 118 +SQ_PERF_SEL_USER4 = 119 +SQ_PERF_SEL_USER5 = 120 +SQ_PERF_SEL_USER6 = 121 +SQ_PERF_SEL_USER7 = 122 +SQ_PERF_SEL_USER8 = 123 +SQ_PERF_SEL_USER9 = 124 +SQ_PERF_SEL_USER10 = 125 +SQ_PERF_SEL_USER11 = 126 +SQ_PERF_SEL_USER12 = 127 +SQ_PERF_SEL_USER13 = 128 +SQ_PERF_SEL_USER14 = 129 +SQ_PERF_SEL_USER15 = 130 +SQ_PERF_SEL_USER_LEVEL0 = 131 +SQ_PERF_SEL_USER_LEVEL1 = 132 +SQ_PERF_SEL_USER_LEVEL2 = 133 +SQ_PERF_SEL_USER_LEVEL3 = 134 +SQ_PERF_SEL_USER_LEVEL4 = 135 +SQ_PERF_SEL_USER_LEVEL5 = 136 +SQ_PERF_SEL_USER_LEVEL6 = 137 +SQ_PERF_SEL_USER_LEVEL7 = 138 +SQ_PERF_SEL_USER_LEVEL8 = 139 +SQ_PERF_SEL_USER_LEVEL9 = 140 +SQ_PERF_SEL_USER_LEVEL10 = 141 +SQ_PERF_SEL_USER_LEVEL11 = 142 +SQ_PERF_SEL_USER_LEVEL12 = 143 +SQ_PERF_SEL_USER_LEVEL13 = 144 +SQ_PERF_SEL_USER_LEVEL14 = 145 +SQ_PERF_SEL_USER_LEVEL15 = 146 +SQ_PERF_SEL_POWER_VALU = 147 +SQ_PERF_SEL_POWER_VALU0 = 148 +SQ_PERF_SEL_POWER_VALU1 = 149 +SQ_PERF_SEL_POWER_VALU2 = 150 +SQ_PERF_SEL_POWER_GPR_RD = 151 +SQ_PERF_SEL_POWER_GPR_WR = 152 +SQ_PERF_SEL_POWER_LDS_BUSY = 153 +SQ_PERF_SEL_POWER_ALU_BUSY = 154 +SQ_PERF_SEL_POWER_TEX_BUSY = 155 +SQ_PERF_SEL_ACCUM_PREV_HIRES = 156 +SQ_PERF_SEL_WAVES_RESTORED = 157 +SQ_PERF_SEL_WAVES_SAVED = 158 +SQ_PERF_SEL_INSTS_SMEM_NORM = 159 +SQ_PERF_SEL_ATC_INSTS_VMEM = 160 +SQ_PERF_SEL_ATC_INST_LEVEL_VMEM = 161 +SQ_PERF_SEL_ATC_XNACK_FIRST = 162 +SQ_PERF_SEL_ATC_XNACK_ALL = 163 +SQ_PERF_SEL_ATC_XNACK_FIFO_FULL = 164 +SQ_PERF_SEL_ATC_INSTS_SMEM = 165 +SQ_PERF_SEL_ATC_INST_LEVEL_SMEM = 166 +SQ_PERF_SEL_IFETCH_XNACK = 167 +SQ_PERF_SEL_TLB_SHOOTDOWN = 168 +SQ_PERF_SEL_TLB_SHOOTDOWN_CYCLES = 169 +SQ_PERF_SEL_INSTS_VMEM_WR_REPLAY = 170 +SQ_PERF_SEL_INSTS_VMEM_RD_REPLAY = 171 +SQ_PERF_SEL_INSTS_VMEM_REPLAY = 172 +SQ_PERF_SEL_INSTS_SMEM_REPLAY = 173 +SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY = 174 +SQ_PERF_SEL_INSTS_FLAT_REPLAY = 175 +SQ_PERF_SEL_ATC_INSTS_VMEM_REPLAY = 176 +SQ_PERF_SEL_ATC_INSTS_SMEM_REPLAY = 177 +SQ_PERF_SEL_UTCL1_TRANSLATION_MISS = 178 +SQ_PERF_SEL_UTCL1_PERMISSION_MISS = 179 +SQ_PERF_SEL_UTCL1_REQUEST = 180 +SQ_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL = 181 +SQ_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX = 182 +SQ_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT = 183 +SQ_PERF_SEL_UTCL1_LFIFO_FULL = 184 +SQ_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES = 185 +SQ_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS = 186 +SQ_PERF_SEL_DUMMY_END = 187 +SQ_PERF_SEL_DUMMY_LAST = 255 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READY = 256 +SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB = 257 +SQC_PERF_SEL_ICACHE_INPUT_VALIDB = 258 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READY = 259 +SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB = 260 +SQC_PERF_SEL_DCACHE_INPUT_VALIDB = 261 +SQC_PERF_SEL_TC_REQ = 262 +SQC_PERF_SEL_TC_INST_REQ = 263 +SQC_PERF_SEL_TC_DATA_READ_REQ = 264 +SQC_PERF_SEL_TC_DATA_WRITE_REQ = 265 +SQC_PERF_SEL_TC_DATA_ATOMIC_REQ = 266 +SQC_PERF_SEL_TC_STALL = 267 +SQC_PERF_SEL_TC_STARVE = 268 +SQC_PERF_SEL_ICACHE_BUSY_CYCLES = 269 +SQC_PERF_SEL_ICACHE_REQ = 270 +SQC_PERF_SEL_ICACHE_HITS = 271 +SQC_PERF_SEL_ICACHE_MISSES = 272 +SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE = 273 +SQC_PERF_SEL_ICACHE_INVAL_INST = 274 +SQC_PERF_SEL_ICACHE_INVAL_ASYNC = 275 +SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT = 276 +SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB = 277 +SQC_PERF_SEL_ICACHE_CACHE_STALLED = 278 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO = 279 +SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX = 280 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT = 281 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO = 282 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO = 283 +SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF = 284 +SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT = 285 +SQC_PERF_SEL_ICACHE_PREFETCH_1 = 286 +SQC_PERF_SEL_ICACHE_PREFETCH_2 = 287 +SQC_PERF_SEL_ICACHE_PREFETCH_FILTERED = 288 +SQC_PERF_SEL_DCACHE_BUSY_CYCLES = 289 +SQC_PERF_SEL_DCACHE_REQ = 290 +SQC_PERF_SEL_DCACHE_HITS = 291 +SQC_PERF_SEL_DCACHE_MISSES = 292 +SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE = 293 +SQC_PERF_SEL_DCACHE_HIT_LRU_READ = 294 +SQC_PERF_SEL_DCACHE_MISS_EVICT_READ = 295 +SQC_PERF_SEL_DCACHE_WC_LRU_WRITE = 296 +SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE = 297 +SQC_PERF_SEL_DCACHE_ATOMIC = 298 +SQC_PERF_SEL_DCACHE_VOLATILE = 299 +SQC_PERF_SEL_DCACHE_INVAL_INST = 300 +SQC_PERF_SEL_DCACHE_INVAL_ASYNC = 301 +SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_INST = 302 +SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_ASYNC = 303 +SQC_PERF_SEL_DCACHE_WB_INST = 304 +SQC_PERF_SEL_DCACHE_WB_ASYNC = 305 +SQC_PERF_SEL_DCACHE_WB_VOLATILE_INST = 306 +SQC_PERF_SEL_DCACHE_WB_VOLATILE_ASYNC = 307 +SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT = 308 +SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB = 309 +SQC_PERF_SEL_DCACHE_CACHE_STALLED = 310 +SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX = 311 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT = 312 +SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT = 313 +SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED = 314 +SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE = 315 +SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT = 316 +SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH = 317 +SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE = 318 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO = 319 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO = 320 +SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF = 321 +SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT = 322 +SQC_PERF_SEL_DCACHE_REQ_READ_1 = 323 +SQC_PERF_SEL_DCACHE_REQ_READ_2 = 324 +SQC_PERF_SEL_DCACHE_REQ_READ_4 = 325 +SQC_PERF_SEL_DCACHE_REQ_READ_8 = 326 +SQC_PERF_SEL_DCACHE_REQ_READ_16 = 327 +SQC_PERF_SEL_DCACHE_REQ_TIME = 328 +SQC_PERF_SEL_DCACHE_REQ_WRITE_1 = 329 +SQC_PERF_SEL_DCACHE_REQ_WRITE_2 = 330 +SQC_PERF_SEL_DCACHE_REQ_WRITE_4 = 331 +SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE = 332 +SQC_PERF_SEL_SQ_DCACHE_REQS = 333 +SQC_PERF_SEL_DCACHE_FLAT_REQ = 334 +SQC_PERF_SEL_DCACHE_NONFLAT_REQ = 335 +SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL = 336 +SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL = 337 +SQC_PERF_SEL_TC_INFLIGHT_LEVEL = 338 +SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL = 339 +SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL = 340 +SQC_PERF_SEL_ICACHE_GATCL1_TRANSLATION_MISS = 341 +SQC_PERF_SEL_ICACHE_GATCL1_PERMISSION_MISS = 342 +SQC_PERF_SEL_ICACHE_GATCL1_REQUEST = 343 +SQC_PERF_SEL_ICACHE_GATCL1_STALL_INFLIGHT_MAX = 344 +SQC_PERF_SEL_ICACHE_GATCL1_STALL_LRU_INFLIGHT = 345 +SQC_PERF_SEL_ICACHE_GATCL1_LFIFO_FULL = 346 +SQC_PERF_SEL_ICACHE_GATCL1_STALL_LFIFO_NOT_RES = 347 +SQC_PERF_SEL_ICACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS = 348 +SQC_PERF_SEL_ICACHE_GATCL1_ATCL2_INFLIGHT = 349 +SQC_PERF_SEL_ICACHE_GATCL1_STALL_MISSFIFO_FULL = 350 +SQC_PERF_SEL_DCACHE_GATCL1_TRANSLATION_MISS = 351 +SQC_PERF_SEL_DCACHE_GATCL1_PERMISSION_MISS = 352 +SQC_PERF_SEL_DCACHE_GATCL1_REQUEST = 353 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_INFLIGHT_MAX = 354 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_LRU_INFLIGHT = 355 +SQC_PERF_SEL_DCACHE_GATCL1_LFIFO_FULL = 356 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_LFIFO_NOT_RES = 357 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS = 358 +SQC_PERF_SEL_DCACHE_GATCL1_ATCL2_INFLIGHT = 359 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_MISSFIFO_FULL = 360 +SQC_PERF_SEL_DCACHE_GATCL1_STALL_MULTI_MISS = 361 +SQC_PERF_SEL_DCACHE_GATCL1_HIT_FIFO_FULL = 362 +SQC_PERF_SEL_DUMMY_LAST = 363 +SQ_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_CAC_POWER_SEL' +SQ_CAC_POWER_SEL__enumvalues = { + 0: 'SQ_CAC_POWER_VALU', + 1: 'SQ_CAC_POWER_VALU0', + 2: 'SQ_CAC_POWER_VALU1', + 3: 'SQ_CAC_POWER_VALU2', + 4: 'SQ_CAC_POWER_GPR_RD', + 5: 'SQ_CAC_POWER_GPR_WR', + 6: 'SQ_CAC_POWER_LDS_BUSY', + 7: 'SQ_CAC_POWER_ALU_BUSY', + 8: 'SQ_CAC_POWER_TEX_BUSY', +} +SQ_CAC_POWER_VALU = 0 +SQ_CAC_POWER_VALU0 = 1 +SQ_CAC_POWER_VALU1 = 2 +SQ_CAC_POWER_VALU2 = 3 +SQ_CAC_POWER_GPR_RD = 4 +SQ_CAC_POWER_GPR_WR = 5 +SQ_CAC_POWER_LDS_BUSY = 6 +SQ_CAC_POWER_ALU_BUSY = 7 +SQ_CAC_POWER_TEX_BUSY = 8 +SQ_CAC_POWER_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_CMD' +SQ_IND_CMD_CMD__enumvalues = { + 0: 'SQ_IND_CMD_CMD_NULL', + 1: 'SQ_IND_CMD_CMD_SETHALT', + 2: 'SQ_IND_CMD_CMD_SAVECTX', + 3: 'SQ_IND_CMD_CMD_KILL', + 4: 'SQ_IND_CMD_CMD_DEBUG', + 5: 'SQ_IND_CMD_CMD_TRAP', + 6: 'SQ_IND_CMD_CMD_SET_SPI_PRIO', + 7: 'SQ_IND_CMD_CMD_SETFATALHALT', +} +SQ_IND_CMD_CMD_NULL = 0 +SQ_IND_CMD_CMD_SETHALT = 1 +SQ_IND_CMD_CMD_SAVECTX = 2 +SQ_IND_CMD_CMD_KILL = 3 +SQ_IND_CMD_CMD_DEBUG = 4 +SQ_IND_CMD_CMD_TRAP = 5 +SQ_IND_CMD_CMD_SET_SPI_PRIO = 6 +SQ_IND_CMD_CMD_SETFATALHALT = 7 +SQ_IND_CMD_CMD = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IND_CMD_MODE' +SQ_IND_CMD_MODE__enumvalues = { + 0: 'SQ_IND_CMD_MODE_SINGLE', + 1: 'SQ_IND_CMD_MODE_BROADCAST', + 2: 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', + 3: 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 4: 'SQ_IND_CMD_MODE_BROADCAST_ME', +} +SQ_IND_CMD_MODE_SINGLE = 0 +SQ_IND_CMD_MODE_BROADCAST = 1 +SQ_IND_CMD_MODE_BROADCAST_QUEUE = 2 +SQ_IND_CMD_MODE_BROADCAST_PIPE = 3 +SQ_IND_CMD_MODE_BROADCAST_ME = 4 +SQ_IND_CMD_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_EDC_INFO_SOURCE' +SQ_EDC_INFO_SOURCE__enumvalues = { + 0: 'SQ_EDC_INFO_SOURCE_INVALID', + 1: 'SQ_EDC_INFO_SOURCE_INST', + 2: 'SQ_EDC_INFO_SOURCE_SGPR', + 3: 'SQ_EDC_INFO_SOURCE_VGPR', + 4: 'SQ_EDC_INFO_SOURCE_LDS', + 5: 'SQ_EDC_INFO_SOURCE_GDS', + 6: 'SQ_EDC_INFO_SOURCE_TA', +} +SQ_EDC_INFO_SOURCE_INVALID = 0 +SQ_EDC_INFO_SOURCE_INST = 1 +SQ_EDC_INFO_SOURCE_SGPR = 2 +SQ_EDC_INFO_SOURCE_VGPR = 3 +SQ_EDC_INFO_SOURCE_LDS = 4 +SQ_EDC_INFO_SOURCE_GDS = 5 +SQ_EDC_INFO_SOURCE_TA = 6 +SQ_EDC_INFO_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_ROUND_MODE' +SQ_ROUND_MODE__enumvalues = { + 0: 'SQ_ROUND_NEAREST_EVEN', + 1: 'SQ_ROUND_PLUS_INFINITY', + 2: 'SQ_ROUND_MINUS_INFINITY', + 3: 'SQ_ROUND_TO_ZERO', +} +SQ_ROUND_NEAREST_EVEN = 0 +SQ_ROUND_PLUS_INFINITY = 1 +SQ_ROUND_MINUS_INFINITY = 2 +SQ_ROUND_TO_ZERO = 3 +SQ_ROUND_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INTERRUPT_WORD_ENCODING' +SQ_INTERRUPT_WORD_ENCODING__enumvalues = { + 0: 'SQ_INTERRUPT_WORD_ENCODING_AUTO', + 1: 'SQ_INTERRUPT_WORD_ENCODING_INST', + 2: 'SQ_INTERRUPT_WORD_ENCODING_ERROR', +} +SQ_INTERRUPT_WORD_ENCODING_AUTO = 0 +SQ_INTERRUPT_WORD_ENCODING_INST = 1 +SQ_INTERRUPT_WORD_ENCODING_ERROR = 2 +SQ_INTERRUPT_WORD_ENCODING = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_SQ_EXPORT_RAT_INST' +ENUM_SQ_EXPORT_RAT_INST__enumvalues = { + 0: 'SQ_EXPORT_RAT_INST_NOP', + 1: 'SQ_EXPORT_RAT_INST_STORE_TYPED', + 2: 'SQ_EXPORT_RAT_INST_STORE_RAW', + 3: 'SQ_EXPORT_RAT_INST_STORE_RAW_FDENORM', + 4: 'SQ_EXPORT_RAT_INST_CMPXCHG_INT', + 5: 'SQ_EXPORT_RAT_INST_CMPXCHG_FLT', + 6: 'SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM', + 7: 'SQ_EXPORT_RAT_INST_ADD', + 8: 'SQ_EXPORT_RAT_INST_SUB', + 9: 'SQ_EXPORT_RAT_INST_RSUB', + 10: 'SQ_EXPORT_RAT_INST_MIN_INT', + 11: 'SQ_EXPORT_RAT_INST_MIN_UINT', + 12: 'SQ_EXPORT_RAT_INST_MAX_INT', + 13: 'SQ_EXPORT_RAT_INST_MAX_UINT', + 14: 'SQ_EXPORT_RAT_INST_AND', + 15: 'SQ_EXPORT_RAT_INST_OR', + 16: 'SQ_EXPORT_RAT_INST_XOR', + 17: 'SQ_EXPORT_RAT_INST_MSKOR', + 18: 'SQ_EXPORT_RAT_INST_INC_UINT', + 19: 'SQ_EXPORT_RAT_INST_DEC_UINT', + 20: 'SQ_EXPORT_RAT_INST_STORE_DWORD', + 21: 'SQ_EXPORT_RAT_INST_STORE_SHORT', + 22: 'SQ_EXPORT_RAT_INST_STORE_BYTE', + 32: 'SQ_EXPORT_RAT_INST_NOP_RTN', + 34: 'SQ_EXPORT_RAT_INST_XCHG_RTN', + 35: 'SQ_EXPORT_RAT_INST_XCHG_FDENORM_RTN', + 36: 'SQ_EXPORT_RAT_INST_CMPXCHG_INT_RTN', + 37: 'SQ_EXPORT_RAT_INST_CMPXCHG_FLT_RTN', + 38: 'SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM_RTN', + 39: 'SQ_EXPORT_RAT_INST_ADD_RTN', + 40: 'SQ_EXPORT_RAT_INST_SUB_RTN', + 41: 'SQ_EXPORT_RAT_INST_RSUB_RTN', + 42: 'SQ_EXPORT_RAT_INST_MIN_INT_RTN', + 43: 'SQ_EXPORT_RAT_INST_MIN_UINT_RTN', + 44: 'SQ_EXPORT_RAT_INST_MAX_INT_RTN', + 45: 'SQ_EXPORT_RAT_INST_MAX_UINT_RTN', + 46: 'SQ_EXPORT_RAT_INST_AND_RTN', + 47: 'SQ_EXPORT_RAT_INST_OR_RTN', + 48: 'SQ_EXPORT_RAT_INST_XOR_RTN', + 49: 'SQ_EXPORT_RAT_INST_MSKOR_RTN', + 50: 'SQ_EXPORT_RAT_INST_INC_UINT_RTN', + 51: 'SQ_EXPORT_RAT_INST_DEC_UINT_RTN', +} +SQ_EXPORT_RAT_INST_NOP = 0 +SQ_EXPORT_RAT_INST_STORE_TYPED = 1 +SQ_EXPORT_RAT_INST_STORE_RAW = 2 +SQ_EXPORT_RAT_INST_STORE_RAW_FDENORM = 3 +SQ_EXPORT_RAT_INST_CMPXCHG_INT = 4 +SQ_EXPORT_RAT_INST_CMPXCHG_FLT = 5 +SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM = 6 +SQ_EXPORT_RAT_INST_ADD = 7 +SQ_EXPORT_RAT_INST_SUB = 8 +SQ_EXPORT_RAT_INST_RSUB = 9 +SQ_EXPORT_RAT_INST_MIN_INT = 10 +SQ_EXPORT_RAT_INST_MIN_UINT = 11 +SQ_EXPORT_RAT_INST_MAX_INT = 12 +SQ_EXPORT_RAT_INST_MAX_UINT = 13 +SQ_EXPORT_RAT_INST_AND = 14 +SQ_EXPORT_RAT_INST_OR = 15 +SQ_EXPORT_RAT_INST_XOR = 16 +SQ_EXPORT_RAT_INST_MSKOR = 17 +SQ_EXPORT_RAT_INST_INC_UINT = 18 +SQ_EXPORT_RAT_INST_DEC_UINT = 19 +SQ_EXPORT_RAT_INST_STORE_DWORD = 20 +SQ_EXPORT_RAT_INST_STORE_SHORT = 21 +SQ_EXPORT_RAT_INST_STORE_BYTE = 22 +SQ_EXPORT_RAT_INST_NOP_RTN = 32 +SQ_EXPORT_RAT_INST_XCHG_RTN = 34 +SQ_EXPORT_RAT_INST_XCHG_FDENORM_RTN = 35 +SQ_EXPORT_RAT_INST_CMPXCHG_INT_RTN = 36 +SQ_EXPORT_RAT_INST_CMPXCHG_FLT_RTN = 37 +SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM_RTN = 38 +SQ_EXPORT_RAT_INST_ADD_RTN = 39 +SQ_EXPORT_RAT_INST_SUB_RTN = 40 +SQ_EXPORT_RAT_INST_RSUB_RTN = 41 +SQ_EXPORT_RAT_INST_MIN_INT_RTN = 42 +SQ_EXPORT_RAT_INST_MIN_UINT_RTN = 43 +SQ_EXPORT_RAT_INST_MAX_INT_RTN = 44 +SQ_EXPORT_RAT_INST_MAX_UINT_RTN = 45 +SQ_EXPORT_RAT_INST_AND_RTN = 46 +SQ_EXPORT_RAT_INST_OR_RTN = 47 +SQ_EXPORT_RAT_INST_XOR_RTN = 48 +SQ_EXPORT_RAT_INST_MSKOR_RTN = 49 +SQ_EXPORT_RAT_INST_INC_UINT_RTN = 50 +SQ_EXPORT_RAT_INST_DEC_UINT_RTN = 51 +ENUM_SQ_EXPORT_RAT_INST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_IBUF_ST' +SQ_IBUF_ST__enumvalues = { + 0: 'SQ_IBUF_IB_IDLE', + 1: 'SQ_IBUF_IB_INI_WAIT_GNT', + 2: 'SQ_IBUF_IB_INI_WAIT_DRET', + 3: 'SQ_IBUF_IB_LE_4DW', + 4: 'SQ_IBUF_IB_WAIT_DRET', + 5: 'SQ_IBUF_IB_EMPTY_WAIT_DRET', + 6: 'SQ_IBUF_IB_DRET', + 7: 'SQ_IBUF_IB_EMPTY_WAIT_GNT', +} +SQ_IBUF_IB_IDLE = 0 +SQ_IBUF_IB_INI_WAIT_GNT = 1 +SQ_IBUF_IB_INI_WAIT_DRET = 2 +SQ_IBUF_IB_LE_4DW = 3 +SQ_IBUF_IB_WAIT_DRET = 4 +SQ_IBUF_IB_EMPTY_WAIT_DRET = 5 +SQ_IBUF_IB_DRET = 6 +SQ_IBUF_IB_EMPTY_WAIT_GNT = 7 +SQ_IBUF_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_INST_STR_ST' +SQ_INST_STR_ST__enumvalues = { + 0: 'SQ_INST_STR_IB_WAVE_NORML', + 1: 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 2: 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 3: 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 4: 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST0', + 5: 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST1', + 6: 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', + 7: 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', +} +SQ_INST_STR_IB_WAVE_NORML = 0 +SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV = 1 +SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV = 2 +SQ_INST_STR_IB_WAVE_INST_SKIP_AV = 3 +SQ_INST_STR_IB_WAVE_SETVSKIP_ST0 = 4 +SQ_INST_STR_IB_WAVE_SETVSKIP_ST1 = 5 +SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT = 6 +SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT = 7 +SQ_INST_STR_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_WAVE_IB_ECC_ST' +SQ_WAVE_IB_ECC_ST__enumvalues = { + 0: 'SQ_WAVE_IB_ECC_CLEAN', + 1: 'SQ_WAVE_IB_ECC_ERR_CONTINUE', + 2: 'SQ_WAVE_IB_ECC_ERR_HALT', + 3: 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', +} +SQ_WAVE_IB_ECC_CLEAN = 0 +SQ_WAVE_IB_ECC_ERR_CONTINUE = 1 +SQ_WAVE_IB_ECC_ERR_HALT = 2 +SQ_WAVE_IB_ECC_WITH_ERR_MSG = 3 +SQ_WAVE_IB_ECC_ST = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ADDRESS_MODE' +SH_MEM_ADDRESS_MODE__enumvalues = { + 0: 'SH_MEM_ADDRESS_MODE_64', + 1: 'SH_MEM_ADDRESS_MODE_32', +} +SH_MEM_ADDRESS_MODE_64 = 0 +SH_MEM_ADDRESS_MODE_32 = 1 +SH_MEM_ADDRESS_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SH_MEM_ALIGNMENT_MODE' +SH_MEM_ALIGNMENT_MODE__enumvalues = { + 0: 'SH_MEM_ALIGNMENT_MODE_DWORD', + 1: 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 2: 'SH_MEM_ALIGNMENT_MODE_STRICT', + 3: 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', +} +SH_MEM_ALIGNMENT_MODE_DWORD = 0 +SH_MEM_ALIGNMENT_MODE_DWORD_STRICT = 1 +SH_MEM_ALIGNMENT_MODE_STRICT = 2 +SH_MEM_ALIGNMENT_MODE_UNALIGNED = 3 +SH_MEM_ALIGNMENT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX' +SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX__enumvalues = { + 24: 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_WREXEC', + 25: 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_RESTORE', +} +SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_WREXEC = 24 +SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_RESTORE = 25 +SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX = ctypes.c_uint32 # enum + +# values for enumeration 'SQ_LB_CTR_SEL_VALUES' +SQ_LB_CTR_SEL_VALUES__enumvalues = { + 0: 'SQ_LB_CTR_SEL_ALU_CYCLES', + 1: 'SQ_LB_CTR_SEL_ALU_STALLS', + 2: 'SQ_LB_CTR_SEL_TEX_CYCLES', + 3: 'SQ_LB_CTR_SEL_TEX_STALLS', + 4: 'SQ_LB_CTR_SEL_SALU_CYCLES', + 5: 'SQ_LB_CTR_SEL_SCALAR_STALLS', + 6: 'SQ_LB_CTR_SEL_SMEM_CYCLES', + 7: 'SQ_LB_CTR_SEL_ICACHE_STALLS', + 8: 'SQ_LB_CTR_SEL_DCACHE_STALLS', + 9: 'SQ_LB_CTR_SEL_RESERVED0', + 10: 'SQ_LB_CTR_SEL_RESERVED1', + 11: 'SQ_LB_CTR_SEL_RESERVED2', + 12: 'SQ_LB_CTR_SEL_RESERVED3', + 13: 'SQ_LB_CTR_SEL_RESERVED4', + 14: 'SQ_LB_CTR_SEL_RESERVED5', + 15: 'SQ_LB_CTR_SEL_RESERVED6', +} +SQ_LB_CTR_SEL_ALU_CYCLES = 0 +SQ_LB_CTR_SEL_ALU_STALLS = 1 +SQ_LB_CTR_SEL_TEX_CYCLES = 2 +SQ_LB_CTR_SEL_TEX_STALLS = 3 +SQ_LB_CTR_SEL_SALU_CYCLES = 4 +SQ_LB_CTR_SEL_SCALAR_STALLS = 5 +SQ_LB_CTR_SEL_SMEM_CYCLES = 6 +SQ_LB_CTR_SEL_ICACHE_STALLS = 7 +SQ_LB_CTR_SEL_DCACHE_STALLS = 8 +SQ_LB_CTR_SEL_RESERVED0 = 9 +SQ_LB_CTR_SEL_RESERVED1 = 10 +SQ_LB_CTR_SEL_RESERVED2 = 11 +SQ_LB_CTR_SEL_RESERVED3 = 12 +SQ_LB_CTR_SEL_RESERVED4 = 13 +SQ_LB_CTR_SEL_RESERVED5 = 14 +SQ_LB_CTR_SEL_RESERVED6 = 15 +SQ_LB_CTR_SEL_VALUES = ctypes.c_uint32 # enum + +# values for enumeration 'CSDATA_TYPE' +CSDATA_TYPE__enumvalues = { + 0: 'CSDATA_TYPE_TG', + 1: 'CSDATA_TYPE_STATE', + 2: 'CSDATA_TYPE_EVENT', + 3: 'CSDATA_TYPE_PRIVATE', +} +CSDATA_TYPE_TG = 0 +CSDATA_TYPE_STATE = 1 +CSDATA_TYPE_EVENT = 2 +CSDATA_TYPE_PRIVATE = 3 +CSDATA_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUT_PRIM_TYPE' +VGT_OUT_PRIM_TYPE__enumvalues = { + 0: 'VGT_OUT_POINT', + 1: 'VGT_OUT_LINE', + 2: 'VGT_OUT_TRI', + 3: 'VGT_OUT_RECT_V0', + 4: 'VGT_OUT_RECT_V1', + 5: 'VGT_OUT_RECT_V2', + 6: 'VGT_OUT_RECT_V3', + 7: 'VGT_OUT_2D_RECT', + 8: 'VGT_TE_QUAD', + 9: 'VGT_TE_PRIM_INDEX_LINE', + 10: 'VGT_TE_PRIM_INDEX_TRI', + 11: 'VGT_TE_PRIM_INDEX_QUAD', + 12: 'VGT_OUT_LINE_ADJ', + 13: 'VGT_OUT_TRI_ADJ', + 14: 'VGT_OUT_PATCH', +} +VGT_OUT_POINT = 0 +VGT_OUT_LINE = 1 +VGT_OUT_TRI = 2 +VGT_OUT_RECT_V0 = 3 +VGT_OUT_RECT_V1 = 4 +VGT_OUT_RECT_V2 = 5 +VGT_OUT_RECT_V3 = 6 +VGT_OUT_2D_RECT = 7 +VGT_TE_QUAD = 8 +VGT_TE_PRIM_INDEX_LINE = 9 +VGT_TE_PRIM_INDEX_TRI = 10 +VGT_TE_PRIM_INDEX_QUAD = 11 +VGT_OUT_LINE_ADJ = 12 +VGT_OUT_TRI_ADJ = 13 +VGT_OUT_PATCH = 14 +VGT_OUT_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_PRIM_TYPE' +VGT_DI_PRIM_TYPE__enumvalues = { + 0: 'DI_PT_NONE', + 1: 'DI_PT_POINTLIST', + 2: 'DI_PT_LINELIST', + 3: 'DI_PT_LINESTRIP', + 4: 'DI_PT_TRILIST', + 5: 'DI_PT_TRIFAN', + 6: 'DI_PT_TRISTRIP', + 7: 'DI_PT_2D_RECTANGLE', + 8: 'DI_PT_UNUSED_1', + 9: 'DI_PT_PATCH', + 10: 'DI_PT_LINELIST_ADJ', + 11: 'DI_PT_LINESTRIP_ADJ', + 12: 'DI_PT_TRILIST_ADJ', + 13: 'DI_PT_TRISTRIP_ADJ', + 14: 'DI_PT_UNUSED_3', + 15: 'DI_PT_UNUSED_4', + 16: 'DI_PT_TRI_WITH_WFLAGS', + 17: 'DI_PT_RECTLIST', + 18: 'DI_PT_LINELOOP', + 19: 'DI_PT_QUADLIST', + 20: 'DI_PT_QUADSTRIP', + 21: 'DI_PT_POLYGON', +} +DI_PT_NONE = 0 +DI_PT_POINTLIST = 1 +DI_PT_LINELIST = 2 +DI_PT_LINESTRIP = 3 +DI_PT_TRILIST = 4 +DI_PT_TRIFAN = 5 +DI_PT_TRISTRIP = 6 +DI_PT_2D_RECTANGLE = 7 +DI_PT_UNUSED_1 = 8 +DI_PT_PATCH = 9 +DI_PT_LINELIST_ADJ = 10 +DI_PT_LINESTRIP_ADJ = 11 +DI_PT_TRILIST_ADJ = 12 +DI_PT_TRISTRIP_ADJ = 13 +DI_PT_UNUSED_3 = 14 +DI_PT_UNUSED_4 = 15 +DI_PT_TRI_WITH_WFLAGS = 16 +DI_PT_RECTLIST = 17 +DI_PT_LINELOOP = 18 +DI_PT_QUADLIST = 19 +DI_PT_QUADSTRIP = 20 +DI_PT_POLYGON = 21 +VGT_DI_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_SOURCE_SELECT' +VGT_DI_SOURCE_SELECT__enumvalues = { + 0: 'DI_SRC_SEL_DMA', + 1: 'DI_SRC_SEL_IMMEDIATE', + 2: 'DI_SRC_SEL_AUTO_INDEX', + 3: 'DI_SRC_SEL_RESERVED', +} +DI_SRC_SEL_DMA = 0 +DI_SRC_SEL_IMMEDIATE = 1 +DI_SRC_SEL_AUTO_INDEX = 2 +DI_SRC_SEL_RESERVED = 3 +VGT_DI_SOURCE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_MAJOR_MODE_SELECT' +VGT_DI_MAJOR_MODE_SELECT__enumvalues = { + 0: 'DI_MAJOR_MODE_0', + 1: 'DI_MAJOR_MODE_1', +} +DI_MAJOR_MODE_0 = 0 +DI_MAJOR_MODE_1 = 1 +VGT_DI_MAJOR_MODE_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DI_INDEX_SIZE' +VGT_DI_INDEX_SIZE__enumvalues = { + 0: 'DI_INDEX_SIZE_16_BIT', + 1: 'DI_INDEX_SIZE_32_BIT', + 2: 'DI_INDEX_SIZE_8_BIT', +} +DI_INDEX_SIZE_16_BIT = 0 +DI_INDEX_SIZE_32_BIT = 1 +DI_INDEX_SIZE_8_BIT = 2 +VGT_DI_INDEX_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_EVENT_TYPE' +VGT_EVENT_TYPE__enumvalues = { + 0: 'Reserved_0x00', + 1: 'SAMPLE_STREAMOUTSTATS1', + 2: 'SAMPLE_STREAMOUTSTATS2', + 3: 'SAMPLE_STREAMOUTSTATS3', + 4: 'CACHE_FLUSH_TS', + 5: 'CONTEXT_DONE', + 6: 'CACHE_FLUSH', + 7: 'CS_PARTIAL_FLUSH', + 8: 'VGT_STREAMOUT_SYNC', + 9: 'Reserved_0x09', + 10: 'VGT_STREAMOUT_RESET', + 11: 'END_OF_PIPE_INCR_DE', + 12: 'END_OF_PIPE_IB_END', + 13: 'RST_PIX_CNT', + 14: 'BREAK_BATCH', + 15: 'VS_PARTIAL_FLUSH', + 16: 'PS_PARTIAL_FLUSH', + 17: 'FLUSH_HS_OUTPUT', + 18: 'FLUSH_DFSM', + 19: 'RESET_TO_LOWEST_VGT', + 20: 'CACHE_FLUSH_AND_INV_TS_EVENT', + 21: 'ZPASS_DONE', + 22: 'CACHE_FLUSH_AND_INV_EVENT', + 23: 'PERFCOUNTER_START', + 24: 'PERFCOUNTER_STOP', + 25: 'PIPELINESTAT_START', + 26: 'PIPELINESTAT_STOP', + 27: 'PERFCOUNTER_SAMPLE', + 28: 'Available_0x1c', + 29: 'Available_0x1d', + 30: 'SAMPLE_PIPELINESTAT', + 31: 'SO_VGTSTREAMOUT_FLUSH', + 32: 'SAMPLE_STREAMOUTSTATS', + 33: 'RESET_VTX_CNT', + 34: 'BLOCK_CONTEXT_DONE', + 35: 'CS_CONTEXT_DONE', + 36: 'VGT_FLUSH', + 37: 'TGID_ROLLOVER', + 38: 'SQ_NON_EVENT', + 39: 'SC_SEND_DB_VPZ', + 40: 'BOTTOM_OF_PIPE_TS', + 41: 'FLUSH_SX_TS', + 42: 'DB_CACHE_FLUSH_AND_INV', + 43: 'FLUSH_AND_INV_DB_DATA_TS', + 44: 'FLUSH_AND_INV_DB_META', + 45: 'FLUSH_AND_INV_CB_DATA_TS', + 46: 'FLUSH_AND_INV_CB_META', + 47: 'CS_DONE', + 48: 'PS_DONE', + 49: 'FLUSH_AND_INV_CB_PIXEL_DATA', + 50: 'SX_CB_RAT_ACK_REQUEST', + 51: 'THREAD_TRACE_START', + 52: 'THREAD_TRACE_STOP', + 53: 'THREAD_TRACE_MARKER', + 54: 'THREAD_TRACE_FLUSH', + 55: 'THREAD_TRACE_FINISH', + 56: 'PIXEL_PIPE_STAT_CONTROL', + 57: 'PIXEL_PIPE_STAT_DUMP', + 58: 'PIXEL_PIPE_STAT_RESET', + 59: 'CONTEXT_SUSPEND', + 60: 'OFFCHIP_HS_DEALLOC', + 61: 'ENABLE_NGG_PIPELINE', + 62: 'ENABLE_LEGACY_PIPELINE', + 63: 'Reserved_0x3f', +} +Reserved_0x00 = 0 +SAMPLE_STREAMOUTSTATS1 = 1 +SAMPLE_STREAMOUTSTATS2 = 2 +SAMPLE_STREAMOUTSTATS3 = 3 +CACHE_FLUSH_TS = 4 +CONTEXT_DONE = 5 +CACHE_FLUSH = 6 +CS_PARTIAL_FLUSH = 7 +VGT_STREAMOUT_SYNC = 8 +Reserved_0x09 = 9 +VGT_STREAMOUT_RESET = 10 +END_OF_PIPE_INCR_DE = 11 +END_OF_PIPE_IB_END = 12 +RST_PIX_CNT = 13 +BREAK_BATCH = 14 +VS_PARTIAL_FLUSH = 15 +PS_PARTIAL_FLUSH = 16 +FLUSH_HS_OUTPUT = 17 +FLUSH_DFSM = 18 +RESET_TO_LOWEST_VGT = 19 +CACHE_FLUSH_AND_INV_TS_EVENT = 20 +ZPASS_DONE = 21 +CACHE_FLUSH_AND_INV_EVENT = 22 +PERFCOUNTER_START = 23 +PERFCOUNTER_STOP = 24 +PIPELINESTAT_START = 25 +PIPELINESTAT_STOP = 26 +PERFCOUNTER_SAMPLE = 27 +Available_0x1c = 28 +Available_0x1d = 29 +SAMPLE_PIPELINESTAT = 30 +SO_VGTSTREAMOUT_FLUSH = 31 +SAMPLE_STREAMOUTSTATS = 32 +RESET_VTX_CNT = 33 +BLOCK_CONTEXT_DONE = 34 +CS_CONTEXT_DONE = 35 +VGT_FLUSH = 36 +TGID_ROLLOVER = 37 +SQ_NON_EVENT = 38 +SC_SEND_DB_VPZ = 39 +BOTTOM_OF_PIPE_TS = 40 +FLUSH_SX_TS = 41 +DB_CACHE_FLUSH_AND_INV = 42 +FLUSH_AND_INV_DB_DATA_TS = 43 +FLUSH_AND_INV_DB_META = 44 +FLUSH_AND_INV_CB_DATA_TS = 45 +FLUSH_AND_INV_CB_META = 46 +CS_DONE = 47 +PS_DONE = 48 +FLUSH_AND_INV_CB_PIXEL_DATA = 49 +SX_CB_RAT_ACK_REQUEST = 50 +THREAD_TRACE_START = 51 +THREAD_TRACE_STOP = 52 +THREAD_TRACE_MARKER = 53 +THREAD_TRACE_FLUSH = 54 +THREAD_TRACE_FINISH = 55 +PIXEL_PIPE_STAT_CONTROL = 56 +PIXEL_PIPE_STAT_DUMP = 57 +PIXEL_PIPE_STAT_RESET = 58 +CONTEXT_SUSPEND = 59 +OFFCHIP_HS_DEALLOC = 60 +ENABLE_NGG_PIPELINE = 61 +ENABLE_LEGACY_PIPELINE = 62 +Reserved_0x3f = 63 +VGT_EVENT_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_SWAP_MODE' +VGT_DMA_SWAP_MODE__enumvalues = { + 0: 'VGT_DMA_SWAP_NONE', + 1: 'VGT_DMA_SWAP_16_BIT', + 2: 'VGT_DMA_SWAP_32_BIT', + 3: 'VGT_DMA_SWAP_WORD', +} +VGT_DMA_SWAP_NONE = 0 +VGT_DMA_SWAP_16_BIT = 1 +VGT_DMA_SWAP_32_BIT = 2 +VGT_DMA_SWAP_WORD = 3 +VGT_DMA_SWAP_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_INDEX_TYPE_MODE' +VGT_INDEX_TYPE_MODE__enumvalues = { + 0: 'VGT_INDEX_16', + 1: 'VGT_INDEX_32', + 2: 'VGT_INDEX_8', +} +VGT_INDEX_16 = 0 +VGT_INDEX_32 = 1 +VGT_INDEX_8 = 2 +VGT_INDEX_TYPE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DMA_BUF_TYPE' +VGT_DMA_BUF_TYPE__enumvalues = { + 0: 'VGT_DMA_BUF_MEM', + 1: 'VGT_DMA_BUF_RING', + 2: 'VGT_DMA_BUF_SETUP', + 3: 'VGT_DMA_PTR_UPDATE', +} +VGT_DMA_BUF_MEM = 0 +VGT_DMA_BUF_RING = 1 +VGT_DMA_BUF_SETUP = 2 +VGT_DMA_PTR_UPDATE = 3 +VGT_DMA_BUF_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_OUTPATH_SELECT' +VGT_OUTPATH_SELECT__enumvalues = { + 0: 'VGT_OUTPATH_VTX_REUSE', + 1: 'VGT_OUTPATH_TESS_EN', + 2: 'VGT_OUTPATH_PASSTHRU', + 3: 'VGT_OUTPATH_GS_BLOCK', + 4: 'VGT_OUTPATH_HS_BLOCK', + 5: 'VGT_OUTPATH_PRIM_GEN', +} +VGT_OUTPATH_VTX_REUSE = 0 +VGT_OUTPATH_TESS_EN = 1 +VGT_OUTPATH_PASSTHRU = 2 +VGT_OUTPATH_GS_BLOCK = 3 +VGT_OUTPATH_HS_BLOCK = 4 +VGT_OUTPATH_PRIM_GEN = 5 +VGT_OUTPATH_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GRP_PRIM_TYPE' +VGT_GRP_PRIM_TYPE__enumvalues = { + 0: 'VGT_GRP_3D_POINT', + 1: 'VGT_GRP_3D_LINE', + 2: 'VGT_GRP_3D_TRI', + 3: 'VGT_GRP_3D_RECT', + 4: 'VGT_GRP_3D_QUAD', + 5: 'VGT_GRP_2D_COPY_RECT_V0', + 6: 'VGT_GRP_2D_COPY_RECT_V1', + 7: 'VGT_GRP_2D_COPY_RECT_V2', + 8: 'VGT_GRP_2D_COPY_RECT_V3', + 9: 'VGT_GRP_2D_FILL_RECT', + 10: 'VGT_GRP_2D_LINE', + 11: 'VGT_GRP_2D_TRI', + 12: 'VGT_GRP_PRIM_INDEX_LINE', + 13: 'VGT_GRP_PRIM_INDEX_TRI', + 14: 'VGT_GRP_PRIM_INDEX_QUAD', + 15: 'VGT_GRP_3D_LINE_ADJ', + 16: 'VGT_GRP_3D_TRI_ADJ', + 17: 'VGT_GRP_3D_PATCH', + 18: 'VGT_GRP_2D_RECT', +} +VGT_GRP_3D_POINT = 0 +VGT_GRP_3D_LINE = 1 +VGT_GRP_3D_TRI = 2 +VGT_GRP_3D_RECT = 3 +VGT_GRP_3D_QUAD = 4 +VGT_GRP_2D_COPY_RECT_V0 = 5 +VGT_GRP_2D_COPY_RECT_V1 = 6 +VGT_GRP_2D_COPY_RECT_V2 = 7 +VGT_GRP_2D_COPY_RECT_V3 = 8 +VGT_GRP_2D_FILL_RECT = 9 +VGT_GRP_2D_LINE = 10 +VGT_GRP_2D_TRI = 11 +VGT_GRP_PRIM_INDEX_LINE = 12 +VGT_GRP_PRIM_INDEX_TRI = 13 +VGT_GRP_PRIM_INDEX_QUAD = 14 +VGT_GRP_3D_LINE_ADJ = 15 +VGT_GRP_3D_TRI_ADJ = 16 +VGT_GRP_3D_PATCH = 17 +VGT_GRP_2D_RECT = 18 +VGT_GRP_PRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GRP_PRIM_ORDER' +VGT_GRP_PRIM_ORDER__enumvalues = { + 0: 'VGT_GRP_LIST', + 1: 'VGT_GRP_STRIP', + 2: 'VGT_GRP_FAN', + 3: 'VGT_GRP_LOOP', + 4: 'VGT_GRP_POLYGON', +} +VGT_GRP_LIST = 0 +VGT_GRP_STRIP = 1 +VGT_GRP_FAN = 2 +VGT_GRP_LOOP = 3 +VGT_GRP_POLYGON = 4 +VGT_GRP_PRIM_ORDER = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GROUP_CONV_SEL' +VGT_GROUP_CONV_SEL__enumvalues = { + 0: 'VGT_GRP_INDEX_16', + 1: 'VGT_GRP_INDEX_32', + 2: 'VGT_GRP_UINT_16', + 3: 'VGT_GRP_UINT_32', + 4: 'VGT_GRP_SINT_16', + 5: 'VGT_GRP_SINT_32', + 6: 'VGT_GRP_FLOAT_32', + 7: 'VGT_GRP_AUTO_PRIM', + 8: 'VGT_GRP_FIX_1_23_TO_FLOAT', +} +VGT_GRP_INDEX_16 = 0 +VGT_GRP_INDEX_32 = 1 +VGT_GRP_UINT_16 = 2 +VGT_GRP_UINT_32 = 3 +VGT_GRP_SINT_16 = 4 +VGT_GRP_SINT_32 = 5 +VGT_GRP_FLOAT_32 = 6 +VGT_GRP_AUTO_PRIM = 7 +VGT_GRP_FIX_1_23_TO_FLOAT = 8 +VGT_GROUP_CONV_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_MODE_TYPE' +VGT_GS_MODE_TYPE__enumvalues = { + 0: 'GS_OFF', + 1: 'GS_SCENARIO_A', + 2: 'GS_SCENARIO_B', + 3: 'GS_SCENARIO_G', + 4: 'GS_SCENARIO_C', + 5: 'SPRITE_EN', +} +GS_OFF = 0 +GS_SCENARIO_A = 1 +GS_SCENARIO_B = 2 +GS_SCENARIO_G = 3 +GS_SCENARIO_C = 4 +SPRITE_EN = 5 +VGT_GS_MODE_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_CUT_MODE' +VGT_GS_CUT_MODE__enumvalues = { + 0: 'GS_CUT_1024', + 1: 'GS_CUT_512', + 2: 'GS_CUT_256', + 3: 'GS_CUT_128', +} +GS_CUT_1024 = 0 +GS_CUT_512 = 1 +GS_CUT_256 = 2 +GS_CUT_128 = 3 +VGT_GS_CUT_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_GS_OUTPRIM_TYPE' +VGT_GS_OUTPRIM_TYPE__enumvalues = { + 0: 'POINTLIST', + 1: 'LINESTRIP', + 2: 'TRISTRIP', + 3: 'RECTLIST', +} +POINTLIST = 0 +LINESTRIP = 1 +TRISTRIP = 2 +RECTLIST = 3 +VGT_GS_OUTPRIM_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_CACHE_INVALID_MODE' +VGT_CACHE_INVALID_MODE__enumvalues = { + 0: 'VC_ONLY', + 1: 'TC_ONLY', + 2: 'VC_AND_TC', +} +VC_ONLY = 0 +TC_ONLY = 1 +VC_AND_TC = 2 +VGT_CACHE_INVALID_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TYPE' +VGT_TESS_TYPE__enumvalues = { + 0: 'TESS_ISOLINE', + 1: 'TESS_TRIANGLE', + 2: 'TESS_QUAD', +} +TESS_ISOLINE = 0 +TESS_TRIANGLE = 1 +TESS_QUAD = 2 +VGT_TESS_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_PARTITION' +VGT_TESS_PARTITION__enumvalues = { + 0: 'PART_INTEGER', + 1: 'PART_POW2', + 2: 'PART_FRAC_ODD', + 3: 'PART_FRAC_EVEN', +} +PART_INTEGER = 0 +PART_POW2 = 1 +PART_FRAC_ODD = 2 +PART_FRAC_EVEN = 3 +VGT_TESS_PARTITION = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_TESS_TOPOLOGY' +VGT_TESS_TOPOLOGY__enumvalues = { + 0: 'OUTPUT_POINT', + 1: 'OUTPUT_LINE', + 2: 'OUTPUT_TRIANGLE_CW', + 3: 'OUTPUT_TRIANGLE_CCW', +} +OUTPUT_POINT = 0 +OUTPUT_LINE = 1 +OUTPUT_TRIANGLE_CW = 2 +OUTPUT_TRIANGLE_CCW = 3 +VGT_TESS_TOPOLOGY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_RDREQ_POLICY' +VGT_RDREQ_POLICY__enumvalues = { + 0: 'VGT_POLICY_LRU', + 1: 'VGT_POLICY_STREAM', +} +VGT_POLICY_LRU = 0 +VGT_POLICY_STREAM = 1 +VGT_RDREQ_POLICY = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_DIST_MODE' +VGT_DIST_MODE__enumvalues = { + 0: 'NO_DIST', + 1: 'PATCHES', + 2: 'DONUTS', + 3: 'TRAPEZOIDS', +} +NO_DIST = 0 +PATCHES = 1 +DONUTS = 2 +TRAPEZOIDS = 3 +VGT_DIST_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_LS_EN' +VGT_STAGES_LS_EN__enumvalues = { + 0: 'LS_STAGE_OFF', + 1: 'LS_STAGE_ON', + 2: 'CS_STAGE_ON', + 3: 'RESERVED_LS', +} +LS_STAGE_OFF = 0 +LS_STAGE_ON = 1 +CS_STAGE_ON = 2 +RESERVED_LS = 3 +VGT_STAGES_LS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_HS_EN' +VGT_STAGES_HS_EN__enumvalues = { + 0: 'HS_STAGE_OFF', + 1: 'HS_STAGE_ON', +} +HS_STAGE_OFF = 0 +HS_STAGE_ON = 1 +VGT_STAGES_HS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_ES_EN' +VGT_STAGES_ES_EN__enumvalues = { + 0: 'ES_STAGE_OFF', + 1: 'ES_STAGE_DS', + 2: 'ES_STAGE_REAL', + 3: 'RESERVED_ES', +} +ES_STAGE_OFF = 0 +ES_STAGE_DS = 1 +ES_STAGE_REAL = 2 +RESERVED_ES = 3 +VGT_STAGES_ES_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_GS_EN' +VGT_STAGES_GS_EN__enumvalues = { + 0: 'GS_STAGE_OFF', + 1: 'GS_STAGE_ON', +} +GS_STAGE_OFF = 0 +GS_STAGE_ON = 1 +VGT_STAGES_GS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_STAGES_VS_EN' +VGT_STAGES_VS_EN__enumvalues = { + 0: 'VS_STAGE_REAL', + 1: 'VS_STAGE_DS', + 2: 'VS_STAGE_COPY_SHADER', + 3: 'RESERVED_VS', +} +VS_STAGE_REAL = 0 +VS_STAGE_DS = 1 +VS_STAGE_COPY_SHADER = 2 +RESERVED_VS = 3 +VGT_STAGES_VS_EN = ctypes.c_uint32 # enum + +# values for enumeration 'VGT_PERFCOUNT_SELECT' +VGT_PERFCOUNT_SELECT__enumvalues = { + 0: 'vgt_perf_VGT_SPI_ESTHREAD_EVENT_WINDOW_ACTIVE', + 1: 'vgt_perf_VGT_SPI_ESVERT_VALID', + 2: 'vgt_perf_VGT_SPI_ESVERT_EOV', + 3: 'vgt_perf_VGT_SPI_ESVERT_STALLED', + 4: 'vgt_perf_VGT_SPI_ESVERT_STARVED_BUSY', + 5: 'vgt_perf_VGT_SPI_ESVERT_STARVED_IDLE', + 6: 'vgt_perf_VGT_SPI_ESVERT_STATIC', + 7: 'vgt_perf_VGT_SPI_ESTHREAD_IS_EVENT', + 8: 'vgt_perf_VGT_SPI_ESTHREAD_SEND', + 9: 'vgt_perf_VGT_SPI_GSPRIM_VALID', + 10: 'vgt_perf_VGT_SPI_GSPRIM_EOV', + 11: 'vgt_perf_VGT_SPI_GSPRIM_CONT', + 12: 'vgt_perf_VGT_SPI_GSPRIM_STALLED', + 13: 'vgt_perf_VGT_SPI_GSPRIM_STARVED_BUSY', + 14: 'vgt_perf_VGT_SPI_GSPRIM_STARVED_IDLE', + 15: 'vgt_perf_VGT_SPI_GSPRIM_STATIC', + 16: 'vgt_perf_VGT_SPI_GSTHREAD_EVENT_WINDOW_ACTIVE', + 17: 'vgt_perf_VGT_SPI_GSTHREAD_IS_EVENT', + 18: 'vgt_perf_VGT_SPI_GSTHREAD_SEND', + 19: 'vgt_perf_VGT_SPI_VSTHREAD_EVENT_WINDOW_ACTIVE', + 20: 'vgt_perf_VGT_SPI_VSVERT_SEND', + 21: 'vgt_perf_VGT_SPI_VSVERT_EOV', + 22: 'vgt_perf_VGT_SPI_VSVERT_STALLED', + 23: 'vgt_perf_VGT_SPI_VSVERT_STARVED_BUSY', + 24: 'vgt_perf_VGT_SPI_VSVERT_STARVED_IDLE', + 25: 'vgt_perf_VGT_SPI_VSVERT_STATIC', + 26: 'vgt_perf_VGT_SPI_VSTHREAD_IS_EVENT', + 27: 'vgt_perf_VGT_SPI_VSTHREAD_SEND', + 28: 'vgt_perf_VGT_PA_EVENT_WINDOW_ACTIVE', + 29: 'vgt_perf_VGT_PA_CLIPV_SEND', + 30: 'vgt_perf_VGT_PA_CLIPV_FIRSTVERT', + 31: 'vgt_perf_VGT_PA_CLIPV_STALLED', + 32: 'vgt_perf_VGT_PA_CLIPV_STARVED_BUSY', + 33: 'vgt_perf_VGT_PA_CLIPV_STARVED_IDLE', + 34: 'vgt_perf_VGT_PA_CLIPV_STATIC', + 35: 'vgt_perf_VGT_PA_CLIPP_SEND', + 36: 'vgt_perf_VGT_PA_CLIPP_EOP', + 37: 'vgt_perf_VGT_PA_CLIPP_IS_EVENT', + 38: 'vgt_perf_VGT_PA_CLIPP_NULL_PRIM', + 39: 'vgt_perf_VGT_PA_CLIPP_NEW_VTX_VECT', + 40: 'vgt_perf_VGT_PA_CLIPP_STALLED', + 41: 'vgt_perf_VGT_PA_CLIPP_STARVED_BUSY', + 42: 'vgt_perf_VGT_PA_CLIPP_STARVED_IDLE', + 43: 'vgt_perf_VGT_PA_CLIPP_STATIC', + 44: 'vgt_perf_VGT_PA_CLIPS_SEND', + 45: 'vgt_perf_VGT_PA_CLIPS_STALLED', + 46: 'vgt_perf_VGT_PA_CLIPS_STARVED_BUSY', + 47: 'vgt_perf_VGT_PA_CLIPS_STARVED_IDLE', + 48: 'vgt_perf_VGT_PA_CLIPS_STATIC', + 49: 'vgt_perf_vsvert_ds_send', + 50: 'vgt_perf_vsvert_api_send', + 51: 'vgt_perf_hs_tif_stall', + 52: 'vgt_perf_hs_input_stall', + 53: 'vgt_perf_hs_interface_stall', + 54: 'vgt_perf_hs_tfm_stall', + 55: 'vgt_perf_te11_starved', + 56: 'vgt_perf_gs_event_stall', + 57: 'vgt_perf_vgt_pa_clipp_send_not_event', + 58: 'vgt_perf_vgt_pa_clipp_valid_prim', + 59: 'vgt_perf_reused_es_indices', + 60: 'vgt_perf_vs_cache_hits', + 61: 'vgt_perf_gs_cache_hits', + 62: 'vgt_perf_ds_cache_hits', + 63: 'vgt_perf_total_cache_hits', + 64: 'vgt_perf_vgt_busy', + 65: 'vgt_perf_vgt_gs_busy', + 66: 'vgt_perf_esvert_stalled_es_tbl', + 67: 'vgt_perf_esvert_stalled_gs_tbl', + 68: 'vgt_perf_esvert_stalled_gs_event', + 69: 'vgt_perf_esvert_stalled_gsprim', + 70: 'vgt_perf_gsprim_stalled_es_tbl', + 71: 'vgt_perf_gsprim_stalled_gs_tbl', + 72: 'vgt_perf_gsprim_stalled_gs_event', + 73: 'vgt_perf_gsprim_stalled_esvert', + 74: 'vgt_perf_esthread_stalled_es_rb_full', + 75: 'vgt_perf_esthread_stalled_spi_bp', + 76: 'vgt_perf_counters_avail_stalled', + 77: 'vgt_perf_gs_rb_space_avail_stalled', + 78: 'vgt_perf_gs_issue_rtr_stalled', + 79: 'vgt_perf_gsthread_stalled', + 80: 'vgt_perf_strmout_stalled', + 81: 'vgt_perf_wait_for_es_done_stalled', + 82: 'vgt_perf_cm_stalled_by_gog', + 83: 'vgt_perf_cm_reading_stalled', + 84: 'vgt_perf_cm_stalled_by_gsfetch_done', + 85: 'vgt_perf_gog_vs_tbl_stalled', + 86: 'vgt_perf_gog_out_indx_stalled', + 87: 'vgt_perf_gog_out_prim_stalled', + 88: 'vgt_perf_waveid_stalled', + 89: 'vgt_perf_gog_busy', + 90: 'vgt_perf_reused_vs_indices', + 91: 'vgt_perf_sclk_reg_vld_event', + 92: 'vgt_perf_vs_conflicting_indices', + 93: 'vgt_perf_sclk_core_vld_event', + 94: 'vgt_perf_hswave_stalled', + 95: 'vgt_perf_sclk_gs_vld_event', + 96: 'vgt_perf_VGT_SPI_LSVERT_VALID', + 97: 'vgt_perf_VGT_SPI_LSVERT_EOV', + 98: 'vgt_perf_VGT_SPI_LSVERT_STALLED', + 99: 'vgt_perf_VGT_SPI_LSVERT_STARVED_BUSY', + 100: 'vgt_perf_VGT_SPI_LSVERT_STARVED_IDLE', + 101: 'vgt_perf_VGT_SPI_LSVERT_STATIC', + 102: 'vgt_perf_VGT_SPI_LSWAVE_EVENT_WINDOW_ACTIVE', + 103: 'vgt_perf_VGT_SPI_LSWAVE_IS_EVENT', + 104: 'vgt_perf_VGT_SPI_LSWAVE_SEND', + 105: 'vgt_perf_VGT_SPI_HSVERT_VALID', + 106: 'vgt_perf_VGT_SPI_HSVERT_EOV', + 107: 'vgt_perf_VGT_SPI_HSVERT_STALLED', + 108: 'vgt_perf_VGT_SPI_HSVERT_STARVED_BUSY', + 109: 'vgt_perf_VGT_SPI_HSVERT_STARVED_IDLE', + 110: 'vgt_perf_VGT_SPI_HSVERT_STATIC', + 111: 'vgt_perf_VGT_SPI_HSWAVE_EVENT_WINDOW_ACTIVE', + 112: 'vgt_perf_VGT_SPI_HSWAVE_IS_EVENT', + 113: 'vgt_perf_VGT_SPI_HSWAVE_SEND', + 114: 'vgt_perf_ds_prims', + 115: 'vgt_perf_ds_RESERVED', + 116: 'vgt_perf_ls_thread_groups', + 117: 'vgt_perf_hs_thread_groups', + 118: 'vgt_perf_es_thread_groups', + 119: 'vgt_perf_vs_thread_groups', + 120: 'vgt_perf_ls_done_latency', + 121: 'vgt_perf_hs_done_latency', + 122: 'vgt_perf_es_done_latency', + 123: 'vgt_perf_gs_done_latency', + 124: 'vgt_perf_vgt_hs_busy', + 125: 'vgt_perf_vgt_te11_busy', + 126: 'vgt_perf_ls_flush', + 127: 'vgt_perf_hs_flush', + 128: 'vgt_perf_es_flush', + 129: 'vgt_perf_vgt_pa_clipp_eopg', + 130: 'vgt_perf_ls_done', + 131: 'vgt_perf_hs_done', + 132: 'vgt_perf_es_done', + 133: 'vgt_perf_gs_done', + 134: 'vgt_perf_vsfetch_done', + 135: 'vgt_perf_gs_done_received', + 136: 'vgt_perf_es_ring_high_water_mark', + 137: 'vgt_perf_gs_ring_high_water_mark', + 138: 'vgt_perf_vs_table_high_water_mark', + 139: 'vgt_perf_hs_tgs_active_high_water_mark', + 140: 'vgt_perf_pa_clipp_dealloc', + 141: 'vgt_perf_cut_mem_flush_stalled', + 142: 'vgt_perf_vsvert_work_received', + 143: 'vgt_perf_vgt_pa_clipp_starved_after_work', + 144: 'vgt_perf_te11_con_starved_after_work', + 145: 'vgt_perf_hs_waiting_on_ls_done_stall', + 146: 'vgt_spi_vsvert_valid', +} +vgt_perf_VGT_SPI_ESTHREAD_EVENT_WINDOW_ACTIVE = 0 +vgt_perf_VGT_SPI_ESVERT_VALID = 1 +vgt_perf_VGT_SPI_ESVERT_EOV = 2 +vgt_perf_VGT_SPI_ESVERT_STALLED = 3 +vgt_perf_VGT_SPI_ESVERT_STARVED_BUSY = 4 +vgt_perf_VGT_SPI_ESVERT_STARVED_IDLE = 5 +vgt_perf_VGT_SPI_ESVERT_STATIC = 6 +vgt_perf_VGT_SPI_ESTHREAD_IS_EVENT = 7 +vgt_perf_VGT_SPI_ESTHREAD_SEND = 8 +vgt_perf_VGT_SPI_GSPRIM_VALID = 9 +vgt_perf_VGT_SPI_GSPRIM_EOV = 10 +vgt_perf_VGT_SPI_GSPRIM_CONT = 11 +vgt_perf_VGT_SPI_GSPRIM_STALLED = 12 +vgt_perf_VGT_SPI_GSPRIM_STARVED_BUSY = 13 +vgt_perf_VGT_SPI_GSPRIM_STARVED_IDLE = 14 +vgt_perf_VGT_SPI_GSPRIM_STATIC = 15 +vgt_perf_VGT_SPI_GSTHREAD_EVENT_WINDOW_ACTIVE = 16 +vgt_perf_VGT_SPI_GSTHREAD_IS_EVENT = 17 +vgt_perf_VGT_SPI_GSTHREAD_SEND = 18 +vgt_perf_VGT_SPI_VSTHREAD_EVENT_WINDOW_ACTIVE = 19 +vgt_perf_VGT_SPI_VSVERT_SEND = 20 +vgt_perf_VGT_SPI_VSVERT_EOV = 21 +vgt_perf_VGT_SPI_VSVERT_STALLED = 22 +vgt_perf_VGT_SPI_VSVERT_STARVED_BUSY = 23 +vgt_perf_VGT_SPI_VSVERT_STARVED_IDLE = 24 +vgt_perf_VGT_SPI_VSVERT_STATIC = 25 +vgt_perf_VGT_SPI_VSTHREAD_IS_EVENT = 26 +vgt_perf_VGT_SPI_VSTHREAD_SEND = 27 +vgt_perf_VGT_PA_EVENT_WINDOW_ACTIVE = 28 +vgt_perf_VGT_PA_CLIPV_SEND = 29 +vgt_perf_VGT_PA_CLIPV_FIRSTVERT = 30 +vgt_perf_VGT_PA_CLIPV_STALLED = 31 +vgt_perf_VGT_PA_CLIPV_STARVED_BUSY = 32 +vgt_perf_VGT_PA_CLIPV_STARVED_IDLE = 33 +vgt_perf_VGT_PA_CLIPV_STATIC = 34 +vgt_perf_VGT_PA_CLIPP_SEND = 35 +vgt_perf_VGT_PA_CLIPP_EOP = 36 +vgt_perf_VGT_PA_CLIPP_IS_EVENT = 37 +vgt_perf_VGT_PA_CLIPP_NULL_PRIM = 38 +vgt_perf_VGT_PA_CLIPP_NEW_VTX_VECT = 39 +vgt_perf_VGT_PA_CLIPP_STALLED = 40 +vgt_perf_VGT_PA_CLIPP_STARVED_BUSY = 41 +vgt_perf_VGT_PA_CLIPP_STARVED_IDLE = 42 +vgt_perf_VGT_PA_CLIPP_STATIC = 43 +vgt_perf_VGT_PA_CLIPS_SEND = 44 +vgt_perf_VGT_PA_CLIPS_STALLED = 45 +vgt_perf_VGT_PA_CLIPS_STARVED_BUSY = 46 +vgt_perf_VGT_PA_CLIPS_STARVED_IDLE = 47 +vgt_perf_VGT_PA_CLIPS_STATIC = 48 +vgt_perf_vsvert_ds_send = 49 +vgt_perf_vsvert_api_send = 50 +vgt_perf_hs_tif_stall = 51 +vgt_perf_hs_input_stall = 52 +vgt_perf_hs_interface_stall = 53 +vgt_perf_hs_tfm_stall = 54 +vgt_perf_te11_starved = 55 +vgt_perf_gs_event_stall = 56 +vgt_perf_vgt_pa_clipp_send_not_event = 57 +vgt_perf_vgt_pa_clipp_valid_prim = 58 +vgt_perf_reused_es_indices = 59 +vgt_perf_vs_cache_hits = 60 +vgt_perf_gs_cache_hits = 61 +vgt_perf_ds_cache_hits = 62 +vgt_perf_total_cache_hits = 63 +vgt_perf_vgt_busy = 64 +vgt_perf_vgt_gs_busy = 65 +vgt_perf_esvert_stalled_es_tbl = 66 +vgt_perf_esvert_stalled_gs_tbl = 67 +vgt_perf_esvert_stalled_gs_event = 68 +vgt_perf_esvert_stalled_gsprim = 69 +vgt_perf_gsprim_stalled_es_tbl = 70 +vgt_perf_gsprim_stalled_gs_tbl = 71 +vgt_perf_gsprim_stalled_gs_event = 72 +vgt_perf_gsprim_stalled_esvert = 73 +vgt_perf_esthread_stalled_es_rb_full = 74 +vgt_perf_esthread_stalled_spi_bp = 75 +vgt_perf_counters_avail_stalled = 76 +vgt_perf_gs_rb_space_avail_stalled = 77 +vgt_perf_gs_issue_rtr_stalled = 78 +vgt_perf_gsthread_stalled = 79 +vgt_perf_strmout_stalled = 80 +vgt_perf_wait_for_es_done_stalled = 81 +vgt_perf_cm_stalled_by_gog = 82 +vgt_perf_cm_reading_stalled = 83 +vgt_perf_cm_stalled_by_gsfetch_done = 84 +vgt_perf_gog_vs_tbl_stalled = 85 +vgt_perf_gog_out_indx_stalled = 86 +vgt_perf_gog_out_prim_stalled = 87 +vgt_perf_waveid_stalled = 88 +vgt_perf_gog_busy = 89 +vgt_perf_reused_vs_indices = 90 +vgt_perf_sclk_reg_vld_event = 91 +vgt_perf_vs_conflicting_indices = 92 +vgt_perf_sclk_core_vld_event = 93 +vgt_perf_hswave_stalled = 94 +vgt_perf_sclk_gs_vld_event = 95 +vgt_perf_VGT_SPI_LSVERT_VALID = 96 +vgt_perf_VGT_SPI_LSVERT_EOV = 97 +vgt_perf_VGT_SPI_LSVERT_STALLED = 98 +vgt_perf_VGT_SPI_LSVERT_STARVED_BUSY = 99 +vgt_perf_VGT_SPI_LSVERT_STARVED_IDLE = 100 +vgt_perf_VGT_SPI_LSVERT_STATIC = 101 +vgt_perf_VGT_SPI_LSWAVE_EVENT_WINDOW_ACTIVE = 102 +vgt_perf_VGT_SPI_LSWAVE_IS_EVENT = 103 +vgt_perf_VGT_SPI_LSWAVE_SEND = 104 +vgt_perf_VGT_SPI_HSVERT_VALID = 105 +vgt_perf_VGT_SPI_HSVERT_EOV = 106 +vgt_perf_VGT_SPI_HSVERT_STALLED = 107 +vgt_perf_VGT_SPI_HSVERT_STARVED_BUSY = 108 +vgt_perf_VGT_SPI_HSVERT_STARVED_IDLE = 109 +vgt_perf_VGT_SPI_HSVERT_STATIC = 110 +vgt_perf_VGT_SPI_HSWAVE_EVENT_WINDOW_ACTIVE = 111 +vgt_perf_VGT_SPI_HSWAVE_IS_EVENT = 112 +vgt_perf_VGT_SPI_HSWAVE_SEND = 113 +vgt_perf_ds_prims = 114 +vgt_perf_ds_RESERVED = 115 +vgt_perf_ls_thread_groups = 116 +vgt_perf_hs_thread_groups = 117 +vgt_perf_es_thread_groups = 118 +vgt_perf_vs_thread_groups = 119 +vgt_perf_ls_done_latency = 120 +vgt_perf_hs_done_latency = 121 +vgt_perf_es_done_latency = 122 +vgt_perf_gs_done_latency = 123 +vgt_perf_vgt_hs_busy = 124 +vgt_perf_vgt_te11_busy = 125 +vgt_perf_ls_flush = 126 +vgt_perf_hs_flush = 127 +vgt_perf_es_flush = 128 +vgt_perf_vgt_pa_clipp_eopg = 129 +vgt_perf_ls_done = 130 +vgt_perf_hs_done = 131 +vgt_perf_es_done = 132 +vgt_perf_gs_done = 133 +vgt_perf_vsfetch_done = 134 +vgt_perf_gs_done_received = 135 +vgt_perf_es_ring_high_water_mark = 136 +vgt_perf_gs_ring_high_water_mark = 137 +vgt_perf_vs_table_high_water_mark = 138 +vgt_perf_hs_tgs_active_high_water_mark = 139 +vgt_perf_pa_clipp_dealloc = 140 +vgt_perf_cut_mem_flush_stalled = 141 +vgt_perf_vsvert_work_received = 142 +vgt_perf_vgt_pa_clipp_starved_after_work = 143 +vgt_perf_te11_con_starved_after_work = 144 +vgt_perf_hs_waiting_on_ls_done_stall = 145 +vgt_spi_vsvert_valid = 146 +VGT_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'IA_PERFCOUNT_SELECT' +IA_PERFCOUNT_SELECT__enumvalues = { + 0: 'ia_perf_GRP_INPUT_EVENT_WINDOW_ACTIVE', + 1: 'ia_perf_dma_data_fifo_full', + 2: 'ia_perf_RESERVED1', + 3: 'ia_perf_RESERVED2', + 4: 'ia_perf_RESERVED3', + 5: 'ia_perf_RESERVED4', + 6: 'ia_perf_RESERVED5', + 7: 'ia_perf_MC_LAT_BIN_0', + 8: 'ia_perf_MC_LAT_BIN_1', + 9: 'ia_perf_MC_LAT_BIN_2', + 10: 'ia_perf_MC_LAT_BIN_3', + 11: 'ia_perf_MC_LAT_BIN_4', + 12: 'ia_perf_MC_LAT_BIN_5', + 13: 'ia_perf_MC_LAT_BIN_6', + 14: 'ia_perf_MC_LAT_BIN_7', + 15: 'ia_perf_ia_busy', + 16: 'ia_perf_ia_sclk_reg_vld_event', + 17: 'ia_perf_RESERVED6', + 18: 'ia_perf_ia_sclk_core_vld_event', + 19: 'ia_perf_RESERVED7', + 20: 'ia_perf_ia_dma_return', + 21: 'ia_perf_ia_stalled', + 22: 'ia_perf_shift_starved_pipe0_event', + 23: 'ia_perf_shift_starved_pipe1_event', +} +ia_perf_GRP_INPUT_EVENT_WINDOW_ACTIVE = 0 +ia_perf_dma_data_fifo_full = 1 +ia_perf_RESERVED1 = 2 +ia_perf_RESERVED2 = 3 +ia_perf_RESERVED3 = 4 +ia_perf_RESERVED4 = 5 +ia_perf_RESERVED5 = 6 +ia_perf_MC_LAT_BIN_0 = 7 +ia_perf_MC_LAT_BIN_1 = 8 +ia_perf_MC_LAT_BIN_2 = 9 +ia_perf_MC_LAT_BIN_3 = 10 +ia_perf_MC_LAT_BIN_4 = 11 +ia_perf_MC_LAT_BIN_5 = 12 +ia_perf_MC_LAT_BIN_6 = 13 +ia_perf_MC_LAT_BIN_7 = 14 +ia_perf_ia_busy = 15 +ia_perf_ia_sclk_reg_vld_event = 16 +ia_perf_RESERVED6 = 17 +ia_perf_ia_sclk_core_vld_event = 18 +ia_perf_RESERVED7 = 19 +ia_perf_ia_dma_return = 20 +ia_perf_ia_stalled = 21 +ia_perf_shift_starved_pipe0_event = 22 +ia_perf_shift_starved_pipe1_event = 23 +IA_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'WD_PERFCOUNT_SELECT' +WD_PERFCOUNT_SELECT__enumvalues = { + 0: 'wd_perf_RBIU_FIFOS_EVENT_WINDOW_ACTIVE', + 1: 'wd_perf_RBIU_DR_FIFO_STARVED', + 2: 'wd_perf_RBIU_DR_FIFO_STALLED', + 3: 'wd_perf_RBIU_DI_FIFO_STARVED', + 4: 'wd_perf_RBIU_DI_FIFO_STALLED', + 5: 'wd_perf_wd_busy', + 6: 'wd_perf_wd_sclk_reg_vld_event', + 7: 'wd_perf_wd_sclk_input_vld_event', + 8: 'wd_perf_wd_sclk_core_vld_event', + 9: 'wd_perf_wd_stalled', + 10: 'wd_perf_inside_tf_bin_0', + 11: 'wd_perf_inside_tf_bin_1', + 12: 'wd_perf_inside_tf_bin_2', + 13: 'wd_perf_inside_tf_bin_3', + 14: 'wd_perf_inside_tf_bin_4', + 15: 'wd_perf_inside_tf_bin_5', + 16: 'wd_perf_inside_tf_bin_6', + 17: 'wd_perf_inside_tf_bin_7', + 18: 'wd_perf_inside_tf_bin_8', + 19: 'wd_perf_tfreq_lat_bin_0', + 20: 'wd_perf_tfreq_lat_bin_1', + 21: 'wd_perf_tfreq_lat_bin_2', + 22: 'wd_perf_tfreq_lat_bin_3', + 23: 'wd_perf_tfreq_lat_bin_4', + 24: 'wd_perf_tfreq_lat_bin_5', + 25: 'wd_perf_tfreq_lat_bin_6', + 26: 'wd_perf_tfreq_lat_bin_7', + 27: 'wd_starved_on_hs_done', + 28: 'wd_perf_se0_hs_done_latency', + 29: 'wd_perf_se1_hs_done_latency', + 30: 'wd_perf_se2_hs_done_latency', + 31: 'wd_perf_se3_hs_done_latency', + 32: 'wd_perf_hs_done_se0', + 33: 'wd_perf_hs_done_se1', + 34: 'wd_perf_hs_done_se2', + 35: 'wd_perf_hs_done_se3', + 36: 'wd_perf_null_patches', +} +wd_perf_RBIU_FIFOS_EVENT_WINDOW_ACTIVE = 0 +wd_perf_RBIU_DR_FIFO_STARVED = 1 +wd_perf_RBIU_DR_FIFO_STALLED = 2 +wd_perf_RBIU_DI_FIFO_STARVED = 3 +wd_perf_RBIU_DI_FIFO_STALLED = 4 +wd_perf_wd_busy = 5 +wd_perf_wd_sclk_reg_vld_event = 6 +wd_perf_wd_sclk_input_vld_event = 7 +wd_perf_wd_sclk_core_vld_event = 8 +wd_perf_wd_stalled = 9 +wd_perf_inside_tf_bin_0 = 10 +wd_perf_inside_tf_bin_1 = 11 +wd_perf_inside_tf_bin_2 = 12 +wd_perf_inside_tf_bin_3 = 13 +wd_perf_inside_tf_bin_4 = 14 +wd_perf_inside_tf_bin_5 = 15 +wd_perf_inside_tf_bin_6 = 16 +wd_perf_inside_tf_bin_7 = 17 +wd_perf_inside_tf_bin_8 = 18 +wd_perf_tfreq_lat_bin_0 = 19 +wd_perf_tfreq_lat_bin_1 = 20 +wd_perf_tfreq_lat_bin_2 = 21 +wd_perf_tfreq_lat_bin_3 = 22 +wd_perf_tfreq_lat_bin_4 = 23 +wd_perf_tfreq_lat_bin_5 = 24 +wd_perf_tfreq_lat_bin_6 = 25 +wd_perf_tfreq_lat_bin_7 = 26 +wd_starved_on_hs_done = 27 +wd_perf_se0_hs_done_latency = 28 +wd_perf_se1_hs_done_latency = 29 +wd_perf_se2_hs_done_latency = 30 +wd_perf_se3_hs_done_latency = 31 +wd_perf_hs_done_se0 = 32 +wd_perf_hs_done_se1 = 33 +wd_perf_hs_done_se2 = 34 +wd_perf_hs_done_se3 = 35 +wd_perf_null_patches = 36 +WD_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_TYPE' +WD_IA_DRAW_TYPE__enumvalues = { + 0: 'WD_IA_DRAW_TYPE_DI_MM0', + 1: 'WD_IA_DRAW_TYPE_REG_XFER', + 2: 'WD_IA_DRAW_TYPE_EVENT_INIT', + 3: 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 4: 'WD_IA_DRAW_TYPE_MIN_INDX', + 5: 'WD_IA_DRAW_TYPE_MAX_INDX', + 6: 'WD_IA_DRAW_TYPE_INDX_OFF', + 7: 'WD_IA_DRAW_TYPE_IMM_DATA', +} +WD_IA_DRAW_TYPE_DI_MM0 = 0 +WD_IA_DRAW_TYPE_REG_XFER = 1 +WD_IA_DRAW_TYPE_EVENT_INIT = 2 +WD_IA_DRAW_TYPE_EVENT_ADDR = 3 +WD_IA_DRAW_TYPE_MIN_INDX = 4 +WD_IA_DRAW_TYPE_MAX_INDX = 5 +WD_IA_DRAW_TYPE_INDX_OFF = 6 +WD_IA_DRAW_TYPE_IMM_DATA = 7 +WD_IA_DRAW_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_REG_XFER' +WD_IA_DRAW_REG_XFER__enumvalues = { + 0: 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 1: 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', +} +WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM = 0 +WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN = 1 +WD_IA_DRAW_REG_XFER = ctypes.c_uint32 # enum + +# values for enumeration 'WD_IA_DRAW_SOURCE' +WD_IA_DRAW_SOURCE__enumvalues = { + 0: 'WD_IA_DRAW_SOURCE_DMA', + 1: 'WD_IA_DRAW_SOURCE_IMMD', + 2: 'WD_IA_DRAW_SOURCE_AUTO', + 3: 'WD_IA_DRAW_SOURCE_OPAQ', +} +WD_IA_DRAW_SOURCE_DMA = 0 +WD_IA_DRAW_SOURCE_IMMD = 1 +WD_IA_DRAW_SOURCE_AUTO = 2 +WD_IA_DRAW_SOURCE_OPAQ = 3 +WD_IA_DRAW_SOURCE = ctypes.c_uint32 # enum + +# values for enumeration 'GB_EDC_DED_MODE' +GB_EDC_DED_MODE__enumvalues = { + 0: 'GB_EDC_DED_MODE_LOG', + 1: 'GB_EDC_DED_MODE_HALT', + 2: 'GB_EDC_DED_MODE_INT_HALT', +} +GB_EDC_DED_MODE_LOG = 0 +GB_EDC_DED_MODE_HALT = 1 +GB_EDC_DED_MODE_INT_HALT = 2 +GB_EDC_DED_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'TA_TC_ADDR_MODES' +TA_TC_ADDR_MODES__enumvalues = { + 0: 'TA_TC_ADDR_MODE_DEFAULT', + 1: 'TA_TC_ADDR_MODE_COMP0', + 2: 'TA_TC_ADDR_MODE_COMP1', + 3: 'TA_TC_ADDR_MODE_COMP2', + 4: 'TA_TC_ADDR_MODE_COMP3', + 5: 'TA_TC_ADDR_MODE_UNALIGNED', + 6: 'TA_TC_ADDR_MODE_BORDER_COLOR', +} +TA_TC_ADDR_MODE_DEFAULT = 0 +TA_TC_ADDR_MODE_COMP0 = 1 +TA_TC_ADDR_MODE_COMP1 = 2 +TA_TC_ADDR_MODE_COMP2 = 3 +TA_TC_ADDR_MODE_COMP3 = 4 +TA_TC_ADDR_MODE_UNALIGNED = 5 +TA_TC_ADDR_MODE_BORDER_COLOR = 6 +TA_TC_ADDR_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TA_PERFCOUNT_SEL' +TA_PERFCOUNT_SEL__enumvalues = { + 0: 'TA_PERF_SEL_NULL', + 1: 'TA_PERF_SEL_sh_fifo_busy', + 2: 'TA_PERF_SEL_sh_fifo_cmd_busy', + 3: 'TA_PERF_SEL_sh_fifo_addr_busy', + 4: 'TA_PERF_SEL_sh_fifo_data_busy', + 5: 'TA_PERF_SEL_sh_fifo_data_sfifo_busy', + 6: 'TA_PERF_SEL_sh_fifo_data_tfifo_busy', + 7: 'TA_PERF_SEL_gradient_busy', + 8: 'TA_PERF_SEL_gradient_fifo_busy', + 9: 'TA_PERF_SEL_lod_busy', + 10: 'TA_PERF_SEL_lod_fifo_busy', + 11: 'TA_PERF_SEL_addresser_busy', + 12: 'TA_PERF_SEL_addresser_fifo_busy', + 13: 'TA_PERF_SEL_aligner_busy', + 14: 'TA_PERF_SEL_write_path_busy', + 15: 'TA_PERF_SEL_ta_busy', + 16: 'TA_PERF_SEL_sq_ta_cmd_cycles', + 17: 'TA_PERF_SEL_sp_ta_addr_cycles', + 18: 'TA_PERF_SEL_sp_ta_data_cycles', + 19: 'TA_PERF_SEL_ta_fa_data_state_cycles', + 20: 'TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles', + 21: 'TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles', + 22: 'TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles', + 23: 'TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles', + 24: 'TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles', + 25: 'TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles', + 26: 'TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles', + 27: 'TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles', + 28: 'TA_PERF_SEL_RESERVED_28', + 29: 'TA_PERF_SEL_RESERVED_29', + 30: 'TA_PERF_SEL_sh_fifo_addr_cycles', + 31: 'TA_PERF_SEL_sh_fifo_data_cycles', + 32: 'TA_PERF_SEL_total_wavefronts', + 33: 'TA_PERF_SEL_gradient_cycles', + 34: 'TA_PERF_SEL_walker_cycles', + 35: 'TA_PERF_SEL_aligner_cycles', + 36: 'TA_PERF_SEL_image_wavefronts', + 37: 'TA_PERF_SEL_image_read_wavefronts', + 38: 'TA_PERF_SEL_image_write_wavefronts', + 39: 'TA_PERF_SEL_image_atomic_wavefronts', + 40: 'TA_PERF_SEL_image_total_cycles', + 41: 'TA_PERF_SEL_RESERVED_41', + 42: 'TA_PERF_SEL_RESERVED_42', + 43: 'TA_PERF_SEL_RESERVED_43', + 44: 'TA_PERF_SEL_buffer_wavefronts', + 45: 'TA_PERF_SEL_buffer_read_wavefronts', + 46: 'TA_PERF_SEL_buffer_write_wavefronts', + 47: 'TA_PERF_SEL_buffer_atomic_wavefronts', + 48: 'TA_PERF_SEL_buffer_coalescable_wavefronts', + 49: 'TA_PERF_SEL_buffer_total_cycles', + 50: 'TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles', + 51: 'TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles', + 52: 'TA_PERF_SEL_buffer_coalesced_read_cycles', + 53: 'TA_PERF_SEL_buffer_coalesced_write_cycles', + 54: 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 55: 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 56: 'TA_PERF_SEL_data_stalled_by_tc_cycles', + 57: 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 58: 'TA_PERF_SEL_addresser_stalled_cycles', + 59: 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 60: 'TA_PERF_SEL_aniso_stalled_cycles', + 61: 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 62: 'TA_PERF_SEL_deriv_stalled_cycles', + 63: 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 64: 'TA_PERF_SEL_color_1_cycle_pixels', + 65: 'TA_PERF_SEL_color_2_cycle_pixels', + 66: 'TA_PERF_SEL_color_3_cycle_pixels', + 67: 'TA_PERF_SEL_color_4_cycle_pixels', + 68: 'TA_PERF_SEL_mip_1_cycle_pixels', + 69: 'TA_PERF_SEL_mip_2_cycle_pixels', + 70: 'TA_PERF_SEL_vol_1_cycle_pixels', + 71: 'TA_PERF_SEL_vol_2_cycle_pixels', + 72: 'TA_PERF_SEL_bilin_point_1_cycle_pixels', + 73: 'TA_PERF_SEL_mipmap_lod_0_samples', + 74: 'TA_PERF_SEL_mipmap_lod_1_samples', + 75: 'TA_PERF_SEL_mipmap_lod_2_samples', + 76: 'TA_PERF_SEL_mipmap_lod_3_samples', + 77: 'TA_PERF_SEL_mipmap_lod_4_samples', + 78: 'TA_PERF_SEL_mipmap_lod_5_samples', + 79: 'TA_PERF_SEL_mipmap_lod_6_samples', + 80: 'TA_PERF_SEL_mipmap_lod_7_samples', + 81: 'TA_PERF_SEL_mipmap_lod_8_samples', + 82: 'TA_PERF_SEL_mipmap_lod_9_samples', + 83: 'TA_PERF_SEL_mipmap_lod_10_samples', + 84: 'TA_PERF_SEL_mipmap_lod_11_samples', + 85: 'TA_PERF_SEL_mipmap_lod_12_samples', + 86: 'TA_PERF_SEL_mipmap_lod_13_samples', + 87: 'TA_PERF_SEL_mipmap_lod_14_samples', + 88: 'TA_PERF_SEL_mipmap_invalid_samples', + 89: 'TA_PERF_SEL_aniso_1_cycle_quads', + 90: 'TA_PERF_SEL_aniso_2_cycle_quads', + 91: 'TA_PERF_SEL_aniso_4_cycle_quads', + 92: 'TA_PERF_SEL_aniso_6_cycle_quads', + 93: 'TA_PERF_SEL_aniso_8_cycle_quads', + 94: 'TA_PERF_SEL_aniso_10_cycle_quads', + 95: 'TA_PERF_SEL_aniso_12_cycle_quads', + 96: 'TA_PERF_SEL_aniso_14_cycle_quads', + 97: 'TA_PERF_SEL_aniso_16_cycle_quads', + 98: 'TA_PERF_SEL_write_path_input_cycles', + 99: 'TA_PERF_SEL_write_path_output_cycles', + 100: 'TA_PERF_SEL_flat_wavefronts', + 101: 'TA_PERF_SEL_flat_read_wavefronts', + 102: 'TA_PERF_SEL_flat_write_wavefronts', + 103: 'TA_PERF_SEL_flat_atomic_wavefronts', + 104: 'TA_PERF_SEL_flat_coalesceable_wavefronts', + 105: 'TA_PERF_SEL_reg_sclk_vld', + 106: 'TA_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 107: 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 108: 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en', + 109: 'TA_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 110: 'TA_PERF_SEL_local_cg_dyn_sclk_grp5_en', + 111: 'TA_PERF_SEL_xnack_on_phase0', + 112: 'TA_PERF_SEL_xnack_on_phase1', + 113: 'TA_PERF_SEL_xnack_on_phase2', + 114: 'TA_PERF_SEL_xnack_on_phase3', + 115: 'TA_PERF_SEL_first_xnack_on_phase0', + 116: 'TA_PERF_SEL_first_xnack_on_phase1', + 117: 'TA_PERF_SEL_first_xnack_on_phase2', + 118: 'TA_PERF_SEL_first_xnack_on_phase3', +} +TA_PERF_SEL_NULL = 0 +TA_PERF_SEL_sh_fifo_busy = 1 +TA_PERF_SEL_sh_fifo_cmd_busy = 2 +TA_PERF_SEL_sh_fifo_addr_busy = 3 +TA_PERF_SEL_sh_fifo_data_busy = 4 +TA_PERF_SEL_sh_fifo_data_sfifo_busy = 5 +TA_PERF_SEL_sh_fifo_data_tfifo_busy = 6 +TA_PERF_SEL_gradient_busy = 7 +TA_PERF_SEL_gradient_fifo_busy = 8 +TA_PERF_SEL_lod_busy = 9 +TA_PERF_SEL_lod_fifo_busy = 10 +TA_PERF_SEL_addresser_busy = 11 +TA_PERF_SEL_addresser_fifo_busy = 12 +TA_PERF_SEL_aligner_busy = 13 +TA_PERF_SEL_write_path_busy = 14 +TA_PERF_SEL_ta_busy = 15 +TA_PERF_SEL_sq_ta_cmd_cycles = 16 +TA_PERF_SEL_sp_ta_addr_cycles = 17 +TA_PERF_SEL_sp_ta_data_cycles = 18 +TA_PERF_SEL_ta_fa_data_state_cycles = 19 +TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles = 20 +TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles = 21 +TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles = 22 +TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles = 23 +TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles = 24 +TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles = 25 +TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles = 26 +TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles = 27 +TA_PERF_SEL_RESERVED_28 = 28 +TA_PERF_SEL_RESERVED_29 = 29 +TA_PERF_SEL_sh_fifo_addr_cycles = 30 +TA_PERF_SEL_sh_fifo_data_cycles = 31 +TA_PERF_SEL_total_wavefronts = 32 +TA_PERF_SEL_gradient_cycles = 33 +TA_PERF_SEL_walker_cycles = 34 +TA_PERF_SEL_aligner_cycles = 35 +TA_PERF_SEL_image_wavefronts = 36 +TA_PERF_SEL_image_read_wavefronts = 37 +TA_PERF_SEL_image_write_wavefronts = 38 +TA_PERF_SEL_image_atomic_wavefronts = 39 +TA_PERF_SEL_image_total_cycles = 40 +TA_PERF_SEL_RESERVED_41 = 41 +TA_PERF_SEL_RESERVED_42 = 42 +TA_PERF_SEL_RESERVED_43 = 43 +TA_PERF_SEL_buffer_wavefronts = 44 +TA_PERF_SEL_buffer_read_wavefronts = 45 +TA_PERF_SEL_buffer_write_wavefronts = 46 +TA_PERF_SEL_buffer_atomic_wavefronts = 47 +TA_PERF_SEL_buffer_coalescable_wavefronts = 48 +TA_PERF_SEL_buffer_total_cycles = 49 +TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles = 50 +TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles = 51 +TA_PERF_SEL_buffer_coalesced_read_cycles = 52 +TA_PERF_SEL_buffer_coalesced_write_cycles = 53 +TA_PERF_SEL_addr_stalled_by_tc_cycles = 54 +TA_PERF_SEL_addr_stalled_by_td_cycles = 55 +TA_PERF_SEL_data_stalled_by_tc_cycles = 56 +TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles = 57 +TA_PERF_SEL_addresser_stalled_cycles = 58 +TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles = 59 +TA_PERF_SEL_aniso_stalled_cycles = 60 +TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles = 61 +TA_PERF_SEL_deriv_stalled_cycles = 62 +TA_PERF_SEL_aniso_gt1_cycle_quads = 63 +TA_PERF_SEL_color_1_cycle_pixels = 64 +TA_PERF_SEL_color_2_cycle_pixels = 65 +TA_PERF_SEL_color_3_cycle_pixels = 66 +TA_PERF_SEL_color_4_cycle_pixels = 67 +TA_PERF_SEL_mip_1_cycle_pixels = 68 +TA_PERF_SEL_mip_2_cycle_pixels = 69 +TA_PERF_SEL_vol_1_cycle_pixels = 70 +TA_PERF_SEL_vol_2_cycle_pixels = 71 +TA_PERF_SEL_bilin_point_1_cycle_pixels = 72 +TA_PERF_SEL_mipmap_lod_0_samples = 73 +TA_PERF_SEL_mipmap_lod_1_samples = 74 +TA_PERF_SEL_mipmap_lod_2_samples = 75 +TA_PERF_SEL_mipmap_lod_3_samples = 76 +TA_PERF_SEL_mipmap_lod_4_samples = 77 +TA_PERF_SEL_mipmap_lod_5_samples = 78 +TA_PERF_SEL_mipmap_lod_6_samples = 79 +TA_PERF_SEL_mipmap_lod_7_samples = 80 +TA_PERF_SEL_mipmap_lod_8_samples = 81 +TA_PERF_SEL_mipmap_lod_9_samples = 82 +TA_PERF_SEL_mipmap_lod_10_samples = 83 +TA_PERF_SEL_mipmap_lod_11_samples = 84 +TA_PERF_SEL_mipmap_lod_12_samples = 85 +TA_PERF_SEL_mipmap_lod_13_samples = 86 +TA_PERF_SEL_mipmap_lod_14_samples = 87 +TA_PERF_SEL_mipmap_invalid_samples = 88 +TA_PERF_SEL_aniso_1_cycle_quads = 89 +TA_PERF_SEL_aniso_2_cycle_quads = 90 +TA_PERF_SEL_aniso_4_cycle_quads = 91 +TA_PERF_SEL_aniso_6_cycle_quads = 92 +TA_PERF_SEL_aniso_8_cycle_quads = 93 +TA_PERF_SEL_aniso_10_cycle_quads = 94 +TA_PERF_SEL_aniso_12_cycle_quads = 95 +TA_PERF_SEL_aniso_14_cycle_quads = 96 +TA_PERF_SEL_aniso_16_cycle_quads = 97 +TA_PERF_SEL_write_path_input_cycles = 98 +TA_PERF_SEL_write_path_output_cycles = 99 +TA_PERF_SEL_flat_wavefronts = 100 +TA_PERF_SEL_flat_read_wavefronts = 101 +TA_PERF_SEL_flat_write_wavefronts = 102 +TA_PERF_SEL_flat_atomic_wavefronts = 103 +TA_PERF_SEL_flat_coalesceable_wavefronts = 104 +TA_PERF_SEL_reg_sclk_vld = 105 +TA_PERF_SEL_local_cg_dyn_sclk_grp0_en = 106 +TA_PERF_SEL_local_cg_dyn_sclk_grp1_en = 107 +TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en = 108 +TA_PERF_SEL_local_cg_dyn_sclk_grp4_en = 109 +TA_PERF_SEL_local_cg_dyn_sclk_grp5_en = 110 +TA_PERF_SEL_xnack_on_phase0 = 111 +TA_PERF_SEL_xnack_on_phase1 = 112 +TA_PERF_SEL_xnack_on_phase2 = 113 +TA_PERF_SEL_xnack_on_phase3 = 114 +TA_PERF_SEL_first_xnack_on_phase0 = 115 +TA_PERF_SEL_first_xnack_on_phase1 = 116 +TA_PERF_SEL_first_xnack_on_phase2 = 117 +TA_PERF_SEL_first_xnack_on_phase3 = 118 +TA_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TD_PERFCOUNT_SEL' +TD_PERFCOUNT_SEL__enumvalues = { + 0: 'TD_PERF_SEL_none', + 1: 'TD_PERF_SEL_td_busy', + 2: 'TD_PERF_SEL_input_busy', + 3: 'TD_PERF_SEL_output_busy', + 4: 'TD_PERF_SEL_lerp_busy', + 5: 'TD_PERF_SEL_reg_sclk_vld', + 6: 'TD_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 7: 'TD_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 8: 'TD_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 9: 'TD_PERF_SEL_local_cg_dyn_sclk_grp5_en', + 10: 'TD_PERF_SEL_tc_td_fifo_full', + 11: 'TD_PERF_SEL_constant_state_full', + 12: 'TD_PERF_SEL_sample_state_full', + 13: 'TD_PERF_SEL_output_fifo_full', + 14: 'TD_PERF_SEL_RESERVED_14', + 15: 'TD_PERF_SEL_tc_stall', + 16: 'TD_PERF_SEL_pc_stall', + 17: 'TD_PERF_SEL_gds_stall', + 18: 'TD_PERF_SEL_RESERVED_18', + 19: 'TD_PERF_SEL_RESERVED_19', + 20: 'TD_PERF_SEL_gather4_wavefront', + 21: 'TD_PERF_SEL_gather4h_wavefront', + 22: 'TD_PERF_SEL_gather4h_packed_wavefront', + 23: 'TD_PERF_SEL_gather8h_packed_wavefront', + 24: 'TD_PERF_SEL_sample_c_wavefront', + 25: 'TD_PERF_SEL_load_wavefront', + 26: 'TD_PERF_SEL_atomic_wavefront', + 27: 'TD_PERF_SEL_store_wavefront', + 28: 'TD_PERF_SEL_ldfptr_wavefront', + 29: 'TD_PERF_SEL_d16_en_wavefront', + 30: 'TD_PERF_SEL_bypass_filter_wavefront', + 31: 'TD_PERF_SEL_min_max_filter_wavefront', + 32: 'TD_PERF_SEL_coalescable_wavefront', + 33: 'TD_PERF_SEL_coalesced_phase', + 34: 'TD_PERF_SEL_four_phase_wavefront', + 35: 'TD_PERF_SEL_eight_phase_wavefront', + 36: 'TD_PERF_SEL_sixteen_phase_wavefront', + 37: 'TD_PERF_SEL_four_phase_forward_wavefront', + 38: 'TD_PERF_SEL_write_ack_wavefront', + 39: 'TD_PERF_SEL_RESERVED_39', + 40: 'TD_PERF_SEL_user_defined_border', + 41: 'TD_PERF_SEL_white_border', + 42: 'TD_PERF_SEL_opaque_black_border', + 43: 'TD_PERF_SEL_RESERVED_43', + 44: 'TD_PERF_SEL_RESERVED_44', + 45: 'TD_PERF_SEL_nack', + 46: 'TD_PERF_SEL_td_sp_traffic', + 47: 'TD_PERF_SEL_consume_gds_traffic', + 48: 'TD_PERF_SEL_addresscmd_poison', + 49: 'TD_PERF_SEL_data_poison', + 50: 'TD_PERF_SEL_start_cycle_0', + 51: 'TD_PERF_SEL_start_cycle_1', + 52: 'TD_PERF_SEL_start_cycle_2', + 53: 'TD_PERF_SEL_start_cycle_3', + 54: 'TD_PERF_SEL_null_cycle_output', + 55: 'TD_PERF_SEL_d16_data_packed', + 56: 'TD_PERF_SEL_texels_zeroed_out_by_blend_zero_prt', +} +TD_PERF_SEL_none = 0 +TD_PERF_SEL_td_busy = 1 +TD_PERF_SEL_input_busy = 2 +TD_PERF_SEL_output_busy = 3 +TD_PERF_SEL_lerp_busy = 4 +TD_PERF_SEL_reg_sclk_vld = 5 +TD_PERF_SEL_local_cg_dyn_sclk_grp0_en = 6 +TD_PERF_SEL_local_cg_dyn_sclk_grp1_en = 7 +TD_PERF_SEL_local_cg_dyn_sclk_grp4_en = 8 +TD_PERF_SEL_local_cg_dyn_sclk_grp5_en = 9 +TD_PERF_SEL_tc_td_fifo_full = 10 +TD_PERF_SEL_constant_state_full = 11 +TD_PERF_SEL_sample_state_full = 12 +TD_PERF_SEL_output_fifo_full = 13 +TD_PERF_SEL_RESERVED_14 = 14 +TD_PERF_SEL_tc_stall = 15 +TD_PERF_SEL_pc_stall = 16 +TD_PERF_SEL_gds_stall = 17 +TD_PERF_SEL_RESERVED_18 = 18 +TD_PERF_SEL_RESERVED_19 = 19 +TD_PERF_SEL_gather4_wavefront = 20 +TD_PERF_SEL_gather4h_wavefront = 21 +TD_PERF_SEL_gather4h_packed_wavefront = 22 +TD_PERF_SEL_gather8h_packed_wavefront = 23 +TD_PERF_SEL_sample_c_wavefront = 24 +TD_PERF_SEL_load_wavefront = 25 +TD_PERF_SEL_atomic_wavefront = 26 +TD_PERF_SEL_store_wavefront = 27 +TD_PERF_SEL_ldfptr_wavefront = 28 +TD_PERF_SEL_d16_en_wavefront = 29 +TD_PERF_SEL_bypass_filter_wavefront = 30 +TD_PERF_SEL_min_max_filter_wavefront = 31 +TD_PERF_SEL_coalescable_wavefront = 32 +TD_PERF_SEL_coalesced_phase = 33 +TD_PERF_SEL_four_phase_wavefront = 34 +TD_PERF_SEL_eight_phase_wavefront = 35 +TD_PERF_SEL_sixteen_phase_wavefront = 36 +TD_PERF_SEL_four_phase_forward_wavefront = 37 +TD_PERF_SEL_write_ack_wavefront = 38 +TD_PERF_SEL_RESERVED_39 = 39 +TD_PERF_SEL_user_defined_border = 40 +TD_PERF_SEL_white_border = 41 +TD_PERF_SEL_opaque_black_border = 42 +TD_PERF_SEL_RESERVED_43 = 43 +TD_PERF_SEL_RESERVED_44 = 44 +TD_PERF_SEL_nack = 45 +TD_PERF_SEL_td_sp_traffic = 46 +TD_PERF_SEL_consume_gds_traffic = 47 +TD_PERF_SEL_addresscmd_poison = 48 +TD_PERF_SEL_data_poison = 49 +TD_PERF_SEL_start_cycle_0 = 50 +TD_PERF_SEL_start_cycle_1 = 51 +TD_PERF_SEL_start_cycle_2 = 52 +TD_PERF_SEL_start_cycle_3 = 53 +TD_PERF_SEL_null_cycle_output = 54 +TD_PERF_SEL_d16_data_packed = 55 +TD_PERF_SEL_texels_zeroed_out_by_blend_zero_prt = 56 +TD_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_PERFCOUNT_SELECT' +TCP_PERFCOUNT_SELECT__enumvalues = { + 0: 'TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES', + 1: 'TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES', + 2: 'TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES', + 3: 'TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES', + 4: 'TCP_PERF_SEL_TD_TCP_STALL_CYCLES', + 5: 'TCP_PERF_SEL_TCR_TCP_STALL_CYCLES', + 6: 'TCP_PERF_SEL_LOD_STALL_CYCLES', + 7: 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES', + 8: 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES', + 9: 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES', + 10: 'TCP_PERF_SEL_ALLOC_STALL_CYCLES', + 11: 'TCP_PERF_SEL_LFIFO_STALL_CYCLES', + 12: 'TCP_PERF_SEL_RFIFO_STALL_CYCLES', + 13: 'TCP_PERF_SEL_TCR_RDRET_STALL', + 14: 'TCP_PERF_SEL_WRITE_CONFLICT_STALL', + 15: 'TCP_PERF_SEL_HOLE_READ_STALL', + 16: 'TCP_PERF_SEL_READCONFLICT_STALL_CYCLES', + 17: 'TCP_PERF_SEL_PENDING_STALL_CYCLES', + 18: 'TCP_PERF_SEL_READFIFO_STALL_CYCLES', + 19: 'TCP_PERF_SEL_TCP_LATENCY', + 20: 'TCP_PERF_SEL_TCC_READ_REQ_LATENCY', + 21: 'TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY', + 22: 'TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY', + 23: 'TCP_PERF_SEL_TCC_READ_REQ', + 24: 'TCP_PERF_SEL_TCC_WRITE_REQ', + 25: 'TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ', + 26: 'TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ', + 27: 'TCP_PERF_SEL_TOTAL_LOCAL_READ', + 28: 'TCP_PERF_SEL_TOTAL_GLOBAL_READ', + 29: 'TCP_PERF_SEL_TOTAL_LOCAL_WRITE', + 30: 'TCP_PERF_SEL_TOTAL_GLOBAL_WRITE', + 31: 'TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET', + 32: 'TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET', + 33: 'TCP_PERF_SEL_TOTAL_WBINVL1', + 34: 'TCP_PERF_SEL_IMG_READ_FMT_1', + 35: 'TCP_PERF_SEL_IMG_READ_FMT_8', + 36: 'TCP_PERF_SEL_IMG_READ_FMT_16', + 37: 'TCP_PERF_SEL_IMG_READ_FMT_32', + 38: 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_8', + 39: 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_16', + 40: 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_128', + 41: 'TCP_PERF_SEL_IMG_READ_FMT_64_2_CYCLE', + 42: 'TCP_PERF_SEL_IMG_READ_FMT_64_1_CYCLE', + 43: 'TCP_PERF_SEL_IMG_READ_FMT_96', + 44: 'TCP_PERF_SEL_IMG_READ_FMT_128_4_CYCLE', + 45: 'TCP_PERF_SEL_IMG_READ_FMT_128_1_CYCLE', + 46: 'TCP_PERF_SEL_IMG_READ_FMT_BC1', + 47: 'TCP_PERF_SEL_IMG_READ_FMT_BC2', + 48: 'TCP_PERF_SEL_IMG_READ_FMT_BC3', + 49: 'TCP_PERF_SEL_IMG_READ_FMT_BC4', + 50: 'TCP_PERF_SEL_IMG_READ_FMT_BC5', + 51: 'TCP_PERF_SEL_IMG_READ_FMT_BC6', + 52: 'TCP_PERF_SEL_IMG_READ_FMT_BC7', + 53: 'TCP_PERF_SEL_IMG_READ_FMT_I8', + 54: 'TCP_PERF_SEL_IMG_READ_FMT_I16', + 55: 'TCP_PERF_SEL_IMG_READ_FMT_I32', + 56: 'TCP_PERF_SEL_IMG_READ_FMT_I32_AS_8', + 57: 'TCP_PERF_SEL_IMG_READ_FMT_I32_AS_16', + 58: 'TCP_PERF_SEL_IMG_READ_FMT_D8', + 59: 'TCP_PERF_SEL_IMG_READ_FMT_D16', + 60: 'TCP_PERF_SEL_IMG_READ_FMT_D32', + 61: 'TCP_PERF_SEL_IMG_WRITE_FMT_8', + 62: 'TCP_PERF_SEL_IMG_WRITE_FMT_16', + 63: 'TCP_PERF_SEL_IMG_WRITE_FMT_32', + 64: 'TCP_PERF_SEL_IMG_WRITE_FMT_64', + 65: 'TCP_PERF_SEL_IMG_WRITE_FMT_128', + 66: 'TCP_PERF_SEL_IMG_WRITE_FMT_D8', + 67: 'TCP_PERF_SEL_IMG_WRITE_FMT_D16', + 68: 'TCP_PERF_SEL_IMG_WRITE_FMT_D32', + 69: 'TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_32', + 70: 'TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_32', + 71: 'TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_64', + 72: 'TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_64', + 73: 'TCP_PERF_SEL_BUF_READ_FMT_8', + 74: 'TCP_PERF_SEL_BUF_READ_FMT_16', + 75: 'TCP_PERF_SEL_BUF_READ_FMT_32', + 76: 'TCP_PERF_SEL_BUF_WRITE_FMT_8', + 77: 'TCP_PERF_SEL_BUF_WRITE_FMT_16', + 78: 'TCP_PERF_SEL_BUF_WRITE_FMT_32', + 79: 'TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_32', + 80: 'TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_32', + 81: 'TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_64', + 82: 'TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_64', + 83: 'TCP_PERF_SEL_ARR_LINEAR_GENERAL', + 84: 'TCP_PERF_SEL_ARR_LINEAR_ALIGNED', + 85: 'TCP_PERF_SEL_ARR_1D_THIN1', + 86: 'TCP_PERF_SEL_ARR_1D_THICK', + 87: 'TCP_PERF_SEL_ARR_2D_THIN1', + 88: 'TCP_PERF_SEL_ARR_2D_THICK', + 89: 'TCP_PERF_SEL_ARR_2D_XTHICK', + 90: 'TCP_PERF_SEL_ARR_3D_THIN1', + 91: 'TCP_PERF_SEL_ARR_3D_THICK', + 92: 'TCP_PERF_SEL_ARR_3D_XTHICK', + 93: 'TCP_PERF_SEL_DIM_1D', + 94: 'TCP_PERF_SEL_DIM_2D', + 95: 'TCP_PERF_SEL_DIM_3D', + 96: 'TCP_PERF_SEL_DIM_1D_ARRAY', + 97: 'TCP_PERF_SEL_DIM_2D_ARRAY', + 98: 'TCP_PERF_SEL_DIM_2D_MSAA', + 99: 'TCP_PERF_SEL_DIM_2D_ARRAY_MSAA', + 100: 'TCP_PERF_SEL_DIM_CUBE_ARRAY', + 101: 'TCP_PERF_SEL_CP_TCP_INVALIDATE', + 102: 'TCP_PERF_SEL_TA_TCP_STATE_READ', + 103: 'TCP_PERF_SEL_TAGRAM0_REQ', + 104: 'TCP_PERF_SEL_TAGRAM1_REQ', + 105: 'TCP_PERF_SEL_TAGRAM2_REQ', + 106: 'TCP_PERF_SEL_TAGRAM3_REQ', + 107: 'TCP_PERF_SEL_GATE_EN1', + 108: 'TCP_PERF_SEL_GATE_EN2', + 109: 'TCP_PERF_SEL_CORE_REG_SCLK_VLD', + 110: 'TCP_PERF_SEL_TCC_REQ', + 111: 'TCP_PERF_SEL_TCC_NON_READ_REQ', + 112: 'TCP_PERF_SEL_TCC_BYPASS_READ_REQ', + 113: 'TCP_PERF_SEL_TCC_MISS_EVICT_READ_REQ', + 114: 'TCP_PERF_SEL_TCC_VOLATILE_READ_REQ', + 115: 'TCP_PERF_SEL_TCC_VOLATILE_BYPASS_READ_REQ', + 116: 'TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_READ_REQ', + 117: 'TCP_PERF_SEL_TCC_BYPASS_WRITE_REQ', + 118: 'TCP_PERF_SEL_TCC_MISS_EVICT_WRITE_REQ', + 119: 'TCP_PERF_SEL_TCC_VOLATILE_BYPASS_WRITE_REQ', + 120: 'TCP_PERF_SEL_TCC_VOLATILE_WRITE_REQ', + 121: 'TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_WRITE_REQ', + 122: 'TCP_PERF_SEL_TCC_BYPASS_ATOMIC_REQ', + 123: 'TCP_PERF_SEL_TCC_ATOMIC_REQ', + 124: 'TCP_PERF_SEL_TCC_VOLATILE_ATOMIC_REQ', + 125: 'TCP_PERF_SEL_TCC_DATA_BUS_BUSY', + 126: 'TCP_PERF_SEL_TOTAL_ACCESSES', + 127: 'TCP_PERF_SEL_TOTAL_READ', + 128: 'TCP_PERF_SEL_TOTAL_HIT_LRU_READ', + 129: 'TCP_PERF_SEL_TOTAL_HIT_EVICT_READ', + 130: 'TCP_PERF_SEL_TOTAL_MISS_LRU_READ', + 131: 'TCP_PERF_SEL_TOTAL_MISS_EVICT_READ', + 132: 'TCP_PERF_SEL_TOTAL_NON_READ', + 133: 'TCP_PERF_SEL_TOTAL_WRITE', + 134: 'TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE', + 135: 'TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE', + 136: 'TCP_PERF_SEL_TOTAL_WBINVL1_VOL', + 137: 'TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES', + 138: 'TCP_PERF_SEL_DISPLAY_MICROTILING', + 139: 'TCP_PERF_SEL_THIN_MICROTILING', + 140: 'TCP_PERF_SEL_DEPTH_MICROTILING', + 141: 'TCP_PERF_SEL_ARR_PRT_THIN1', + 142: 'TCP_PERF_SEL_ARR_PRT_2D_THIN1', + 143: 'TCP_PERF_SEL_ARR_PRT_3D_THIN1', + 144: 'TCP_PERF_SEL_ARR_PRT_THICK', + 145: 'TCP_PERF_SEL_ARR_PRT_2D_THICK', + 146: 'TCP_PERF_SEL_ARR_PRT_3D_THICK', + 147: 'TCP_PERF_SEL_CP_TCP_INVALIDATE_VOL', + 148: 'TCP_PERF_SEL_SQ_TCP_INVALIDATE_VOL', + 149: 'TCP_PERF_SEL_UNALIGNED', + 150: 'TCP_PERF_SEL_ROTATED_MICROTILING', + 151: 'TCP_PERF_SEL_THICK_MICROTILING', + 152: 'TCP_PERF_SEL_ATC', + 153: 'TCP_PERF_SEL_POWER_STALL', + 154: 'TCP_PERF_SEL_RESERVED_154', + 155: 'TCP_PERF_SEL_TCC_LRU_REQ', + 156: 'TCP_PERF_SEL_TCC_STREAM_REQ', + 157: 'TCP_PERF_SEL_TCC_NC_READ_REQ', + 158: 'TCP_PERF_SEL_TCC_NC_WRITE_REQ', + 159: 'TCP_PERF_SEL_TCC_NC_ATOMIC_REQ', + 160: 'TCP_PERF_SEL_TCC_UC_READ_REQ', + 161: 'TCP_PERF_SEL_TCC_UC_WRITE_REQ', + 162: 'TCP_PERF_SEL_TCC_UC_ATOMIC_REQ', + 163: 'TCP_PERF_SEL_TCC_CC_READ_REQ', + 164: 'TCP_PERF_SEL_TCC_CC_WRITE_REQ', + 165: 'TCP_PERF_SEL_TCC_CC_ATOMIC_REQ', + 166: 'TCP_PERF_SEL_TCC_DCC_REQ', + 167: 'TCP_PERF_SEL_TCC_PHYSICAL_REQ', + 168: 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 169: 'TCP_PERF_SEL_VOLATILE', + 170: 'TCP_PERF_SEL_TC_TA_XNACK_STALL', + 171: 'TCP_PERF_SEL_UTCL1_SERIALIZATION_STALL', + 172: 'TCP_PERF_SEL_SHOOTDOWN', + 173: 'TCP_PERF_SEL_UTCL1_TRANSLATION_MISS', + 174: 'TCP_PERF_SEL_UTCL1_PERMISSION_MISS', + 175: 'TCP_PERF_SEL_UTCL1_REQUEST', + 176: 'TCP_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 177: 'TCP_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 178: 'TCP_PERF_SEL_UTCL1_LFIFO_FULL', + 179: 'TCP_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 180: 'TCP_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 181: 'TCP_PERF_SEL_UTCL1_UTCL2_INFLIGHT', + 182: 'TCP_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 183: 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGB', + 184: 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA', + 185: 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA1', + 186: 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_R', + 187: 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RG', + 188: 'TCP_PERF_SEL_IMG_READ_FMT_8_AS_32', + 189: 'TCP_PERF_SEL_IMG_READ_FMT_8_AS_64', + 190: 'TCP_PERF_SEL_IMG_READ_FMT_16_AS_64', + 191: 'TCP_PERF_SEL_IMG_READ_FMT_16_AS_128', + 192: 'TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_32', + 193: 'TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_64', + 194: 'TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_64', + 195: 'TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_128', +} +TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES = 0 +TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES = 1 +TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES = 2 +TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES = 3 +TCP_PERF_SEL_TD_TCP_STALL_CYCLES = 4 +TCP_PERF_SEL_TCR_TCP_STALL_CYCLES = 5 +TCP_PERF_SEL_LOD_STALL_CYCLES = 6 +TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES = 7 +TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES = 8 +TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES = 9 +TCP_PERF_SEL_ALLOC_STALL_CYCLES = 10 +TCP_PERF_SEL_LFIFO_STALL_CYCLES = 11 +TCP_PERF_SEL_RFIFO_STALL_CYCLES = 12 +TCP_PERF_SEL_TCR_RDRET_STALL = 13 +TCP_PERF_SEL_WRITE_CONFLICT_STALL = 14 +TCP_PERF_SEL_HOLE_READ_STALL = 15 +TCP_PERF_SEL_READCONFLICT_STALL_CYCLES = 16 +TCP_PERF_SEL_PENDING_STALL_CYCLES = 17 +TCP_PERF_SEL_READFIFO_STALL_CYCLES = 18 +TCP_PERF_SEL_TCP_LATENCY = 19 +TCP_PERF_SEL_TCC_READ_REQ_LATENCY = 20 +TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY = 21 +TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY = 22 +TCP_PERF_SEL_TCC_READ_REQ = 23 +TCP_PERF_SEL_TCC_WRITE_REQ = 24 +TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ = 25 +TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ = 26 +TCP_PERF_SEL_TOTAL_LOCAL_READ = 27 +TCP_PERF_SEL_TOTAL_GLOBAL_READ = 28 +TCP_PERF_SEL_TOTAL_LOCAL_WRITE = 29 +TCP_PERF_SEL_TOTAL_GLOBAL_WRITE = 30 +TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET = 31 +TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET = 32 +TCP_PERF_SEL_TOTAL_WBINVL1 = 33 +TCP_PERF_SEL_IMG_READ_FMT_1 = 34 +TCP_PERF_SEL_IMG_READ_FMT_8 = 35 +TCP_PERF_SEL_IMG_READ_FMT_16 = 36 +TCP_PERF_SEL_IMG_READ_FMT_32 = 37 +TCP_PERF_SEL_IMG_READ_FMT_32_AS_8 = 38 +TCP_PERF_SEL_IMG_READ_FMT_32_AS_16 = 39 +TCP_PERF_SEL_IMG_READ_FMT_32_AS_128 = 40 +TCP_PERF_SEL_IMG_READ_FMT_64_2_CYCLE = 41 +TCP_PERF_SEL_IMG_READ_FMT_64_1_CYCLE = 42 +TCP_PERF_SEL_IMG_READ_FMT_96 = 43 +TCP_PERF_SEL_IMG_READ_FMT_128_4_CYCLE = 44 +TCP_PERF_SEL_IMG_READ_FMT_128_1_CYCLE = 45 +TCP_PERF_SEL_IMG_READ_FMT_BC1 = 46 +TCP_PERF_SEL_IMG_READ_FMT_BC2 = 47 +TCP_PERF_SEL_IMG_READ_FMT_BC3 = 48 +TCP_PERF_SEL_IMG_READ_FMT_BC4 = 49 +TCP_PERF_SEL_IMG_READ_FMT_BC5 = 50 +TCP_PERF_SEL_IMG_READ_FMT_BC6 = 51 +TCP_PERF_SEL_IMG_READ_FMT_BC7 = 52 +TCP_PERF_SEL_IMG_READ_FMT_I8 = 53 +TCP_PERF_SEL_IMG_READ_FMT_I16 = 54 +TCP_PERF_SEL_IMG_READ_FMT_I32 = 55 +TCP_PERF_SEL_IMG_READ_FMT_I32_AS_8 = 56 +TCP_PERF_SEL_IMG_READ_FMT_I32_AS_16 = 57 +TCP_PERF_SEL_IMG_READ_FMT_D8 = 58 +TCP_PERF_SEL_IMG_READ_FMT_D16 = 59 +TCP_PERF_SEL_IMG_READ_FMT_D32 = 60 +TCP_PERF_SEL_IMG_WRITE_FMT_8 = 61 +TCP_PERF_SEL_IMG_WRITE_FMT_16 = 62 +TCP_PERF_SEL_IMG_WRITE_FMT_32 = 63 +TCP_PERF_SEL_IMG_WRITE_FMT_64 = 64 +TCP_PERF_SEL_IMG_WRITE_FMT_128 = 65 +TCP_PERF_SEL_IMG_WRITE_FMT_D8 = 66 +TCP_PERF_SEL_IMG_WRITE_FMT_D16 = 67 +TCP_PERF_SEL_IMG_WRITE_FMT_D32 = 68 +TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_32 = 69 +TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_32 = 70 +TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_64 = 71 +TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_64 = 72 +TCP_PERF_SEL_BUF_READ_FMT_8 = 73 +TCP_PERF_SEL_BUF_READ_FMT_16 = 74 +TCP_PERF_SEL_BUF_READ_FMT_32 = 75 +TCP_PERF_SEL_BUF_WRITE_FMT_8 = 76 +TCP_PERF_SEL_BUF_WRITE_FMT_16 = 77 +TCP_PERF_SEL_BUF_WRITE_FMT_32 = 78 +TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_32 = 79 +TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_32 = 80 +TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_64 = 81 +TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_64 = 82 +TCP_PERF_SEL_ARR_LINEAR_GENERAL = 83 +TCP_PERF_SEL_ARR_LINEAR_ALIGNED = 84 +TCP_PERF_SEL_ARR_1D_THIN1 = 85 +TCP_PERF_SEL_ARR_1D_THICK = 86 +TCP_PERF_SEL_ARR_2D_THIN1 = 87 +TCP_PERF_SEL_ARR_2D_THICK = 88 +TCP_PERF_SEL_ARR_2D_XTHICK = 89 +TCP_PERF_SEL_ARR_3D_THIN1 = 90 +TCP_PERF_SEL_ARR_3D_THICK = 91 +TCP_PERF_SEL_ARR_3D_XTHICK = 92 +TCP_PERF_SEL_DIM_1D = 93 +TCP_PERF_SEL_DIM_2D = 94 +TCP_PERF_SEL_DIM_3D = 95 +TCP_PERF_SEL_DIM_1D_ARRAY = 96 +TCP_PERF_SEL_DIM_2D_ARRAY = 97 +TCP_PERF_SEL_DIM_2D_MSAA = 98 +TCP_PERF_SEL_DIM_2D_ARRAY_MSAA = 99 +TCP_PERF_SEL_DIM_CUBE_ARRAY = 100 +TCP_PERF_SEL_CP_TCP_INVALIDATE = 101 +TCP_PERF_SEL_TA_TCP_STATE_READ = 102 +TCP_PERF_SEL_TAGRAM0_REQ = 103 +TCP_PERF_SEL_TAGRAM1_REQ = 104 +TCP_PERF_SEL_TAGRAM2_REQ = 105 +TCP_PERF_SEL_TAGRAM3_REQ = 106 +TCP_PERF_SEL_GATE_EN1 = 107 +TCP_PERF_SEL_GATE_EN2 = 108 +TCP_PERF_SEL_CORE_REG_SCLK_VLD = 109 +TCP_PERF_SEL_TCC_REQ = 110 +TCP_PERF_SEL_TCC_NON_READ_REQ = 111 +TCP_PERF_SEL_TCC_BYPASS_READ_REQ = 112 +TCP_PERF_SEL_TCC_MISS_EVICT_READ_REQ = 113 +TCP_PERF_SEL_TCC_VOLATILE_READ_REQ = 114 +TCP_PERF_SEL_TCC_VOLATILE_BYPASS_READ_REQ = 115 +TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_READ_REQ = 116 +TCP_PERF_SEL_TCC_BYPASS_WRITE_REQ = 117 +TCP_PERF_SEL_TCC_MISS_EVICT_WRITE_REQ = 118 +TCP_PERF_SEL_TCC_VOLATILE_BYPASS_WRITE_REQ = 119 +TCP_PERF_SEL_TCC_VOLATILE_WRITE_REQ = 120 +TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_WRITE_REQ = 121 +TCP_PERF_SEL_TCC_BYPASS_ATOMIC_REQ = 122 +TCP_PERF_SEL_TCC_ATOMIC_REQ = 123 +TCP_PERF_SEL_TCC_VOLATILE_ATOMIC_REQ = 124 +TCP_PERF_SEL_TCC_DATA_BUS_BUSY = 125 +TCP_PERF_SEL_TOTAL_ACCESSES = 126 +TCP_PERF_SEL_TOTAL_READ = 127 +TCP_PERF_SEL_TOTAL_HIT_LRU_READ = 128 +TCP_PERF_SEL_TOTAL_HIT_EVICT_READ = 129 +TCP_PERF_SEL_TOTAL_MISS_LRU_READ = 130 +TCP_PERF_SEL_TOTAL_MISS_EVICT_READ = 131 +TCP_PERF_SEL_TOTAL_NON_READ = 132 +TCP_PERF_SEL_TOTAL_WRITE = 133 +TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE = 134 +TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE = 135 +TCP_PERF_SEL_TOTAL_WBINVL1_VOL = 136 +TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES = 137 +TCP_PERF_SEL_DISPLAY_MICROTILING = 138 +TCP_PERF_SEL_THIN_MICROTILING = 139 +TCP_PERF_SEL_DEPTH_MICROTILING = 140 +TCP_PERF_SEL_ARR_PRT_THIN1 = 141 +TCP_PERF_SEL_ARR_PRT_2D_THIN1 = 142 +TCP_PERF_SEL_ARR_PRT_3D_THIN1 = 143 +TCP_PERF_SEL_ARR_PRT_THICK = 144 +TCP_PERF_SEL_ARR_PRT_2D_THICK = 145 +TCP_PERF_SEL_ARR_PRT_3D_THICK = 146 +TCP_PERF_SEL_CP_TCP_INVALIDATE_VOL = 147 +TCP_PERF_SEL_SQ_TCP_INVALIDATE_VOL = 148 +TCP_PERF_SEL_UNALIGNED = 149 +TCP_PERF_SEL_ROTATED_MICROTILING = 150 +TCP_PERF_SEL_THICK_MICROTILING = 151 +TCP_PERF_SEL_ATC = 152 +TCP_PERF_SEL_POWER_STALL = 153 +TCP_PERF_SEL_RESERVED_154 = 154 +TCP_PERF_SEL_TCC_LRU_REQ = 155 +TCP_PERF_SEL_TCC_STREAM_REQ = 156 +TCP_PERF_SEL_TCC_NC_READ_REQ = 157 +TCP_PERF_SEL_TCC_NC_WRITE_REQ = 158 +TCP_PERF_SEL_TCC_NC_ATOMIC_REQ = 159 +TCP_PERF_SEL_TCC_UC_READ_REQ = 160 +TCP_PERF_SEL_TCC_UC_WRITE_REQ = 161 +TCP_PERF_SEL_TCC_UC_ATOMIC_REQ = 162 +TCP_PERF_SEL_TCC_CC_READ_REQ = 163 +TCP_PERF_SEL_TCC_CC_WRITE_REQ = 164 +TCP_PERF_SEL_TCC_CC_ATOMIC_REQ = 165 +TCP_PERF_SEL_TCC_DCC_REQ = 166 +TCP_PERF_SEL_TCC_PHYSICAL_REQ = 167 +TCP_PERF_SEL_UNORDERED_MTYPE_STALL = 168 +TCP_PERF_SEL_VOLATILE = 169 +TCP_PERF_SEL_TC_TA_XNACK_STALL = 170 +TCP_PERF_SEL_UTCL1_SERIALIZATION_STALL = 171 +TCP_PERF_SEL_SHOOTDOWN = 172 +TCP_PERF_SEL_UTCL1_TRANSLATION_MISS = 173 +TCP_PERF_SEL_UTCL1_PERMISSION_MISS = 174 +TCP_PERF_SEL_UTCL1_REQUEST = 175 +TCP_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX = 176 +TCP_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT = 177 +TCP_PERF_SEL_UTCL1_LFIFO_FULL = 178 +TCP_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES = 179 +TCP_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS = 180 +TCP_PERF_SEL_UTCL1_UTCL2_INFLIGHT = 181 +TCP_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL = 182 +TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGB = 183 +TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA = 184 +TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA1 = 185 +TCP_PERF_SEL_IMG_READ_FMT_ETC2_R = 186 +TCP_PERF_SEL_IMG_READ_FMT_ETC2_RG = 187 +TCP_PERF_SEL_IMG_READ_FMT_8_AS_32 = 188 +TCP_PERF_SEL_IMG_READ_FMT_8_AS_64 = 189 +TCP_PERF_SEL_IMG_READ_FMT_16_AS_64 = 190 +TCP_PERF_SEL_IMG_READ_FMT_16_AS_128 = 191 +TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_32 = 192 +TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_64 = 193 +TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_64 = 194 +TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_128 = 195 +TCP_PERFCOUNT_SELECT = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_POLICIES' +TCP_CACHE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_POLICY_MISS_LRU', + 1: 'TCP_CACHE_POLICY_MISS_EVICT', + 2: 'TCP_CACHE_POLICY_HIT_LRU', + 3: 'TCP_CACHE_POLICY_HIT_EVICT', +} +TCP_CACHE_POLICY_MISS_LRU = 0 +TCP_CACHE_POLICY_MISS_EVICT = 1 +TCP_CACHE_POLICY_HIT_LRU = 2 +TCP_CACHE_POLICY_HIT_EVICT = 3 +TCP_CACHE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_CACHE_STORE_POLICIES' +TCP_CACHE_STORE_POLICIES__enumvalues = { + 0: 'TCP_CACHE_STORE_POLICY_WT_LRU', + 1: 'TCP_CACHE_STORE_POLICY_WT_EVICT', +} +TCP_CACHE_STORE_POLICY_WT_LRU = 0 +TCP_CACHE_STORE_POLICY_WT_EVICT = 1 +TCP_CACHE_STORE_POLICIES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_WATCH_MODES' +TCP_WATCH_MODES__enumvalues = { + 0: 'TCP_WATCH_MODE_READ', + 1: 'TCP_WATCH_MODE_NONREAD', + 2: 'TCP_WATCH_MODE_ATOMIC', + 3: 'TCP_WATCH_MODE_ALL', +} +TCP_WATCH_MODE_READ = 0 +TCP_WATCH_MODE_NONREAD = 1 +TCP_WATCH_MODE_ATOMIC = 2 +TCP_WATCH_MODE_ALL = 3 +TCP_WATCH_MODES = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_DATA_SEL' +TCP_DSM_DATA_SEL__enumvalues = { + 0: 'TCP_DSM_DISABLE', + 1: 'TCP_DSM_SEL0', + 2: 'TCP_DSM_SEL1', + 3: 'TCP_DSM_SEL_BOTH', +} +TCP_DSM_DISABLE = 0 +TCP_DSM_SEL0 = 1 +TCP_DSM_SEL1 = 2 +TCP_DSM_SEL_BOTH = 3 +TCP_DSM_DATA_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_SINGLE_WRITE' +TCP_DSM_SINGLE_WRITE__enumvalues = { + 0: 'TCP_DSM_SINGLE_WRITE_DIS', + 1: 'TCP_DSM_SINGLE_WRITE_EN', +} +TCP_DSM_SINGLE_WRITE_DIS = 0 +TCP_DSM_SINGLE_WRITE_EN = 1 +TCP_DSM_SINGLE_WRITE = ctypes.c_uint32 # enum + +# values for enumeration 'TCP_DSM_INJECT_SEL' +TCP_DSM_INJECT_SEL__enumvalues = { + 0: 'TCP_DSM_INJECT_SEL0', + 1: 'TCP_DSM_INJECT_SEL1', + 2: 'TCP_DSM_INJECT_SEL2', + 3: 'TCP_DSM_INJECT_SEL3', +} +TCP_DSM_INJECT_SEL0 = 0 +TCP_DSM_INJECT_SEL1 = 1 +TCP_DSM_INJECT_SEL2 = 2 +TCP_DSM_INJECT_SEL3 = 3 +TCP_DSM_INJECT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCC_PERF_SEL' +TCC_PERF_SEL__enumvalues = { + 0: 'TCC_PERF_SEL_NONE', + 1: 'TCC_PERF_SEL_CYCLE', + 2: 'TCC_PERF_SEL_BUSY', + 3: 'TCC_PERF_SEL_REQ', + 4: 'TCC_PERF_SEL_STREAMING_REQ', + 5: 'TCC_PERF_SEL_EXE_REQ', + 6: 'TCC_PERF_SEL_COMPRESSED_REQ', + 7: 'TCC_PERF_SEL_COMPRESSED_0_REQ', + 8: 'TCC_PERF_SEL_METADATA_REQ', + 9: 'TCC_PERF_SEL_NC_VIRTUAL_REQ', + 10: 'TCC_PERF_SEL_UC_VIRTUAL_REQ', + 11: 'TCC_PERF_SEL_CC_PHYSICAL_REQ', + 12: 'TCC_PERF_SEL_PROBE', + 13: 'TCC_PERF_SEL_PROBE_ALL', + 14: 'TCC_PERF_SEL_READ', + 15: 'TCC_PERF_SEL_WRITE', + 16: 'TCC_PERF_SEL_ATOMIC', + 17: 'TCC_PERF_SEL_HIT', + 18: 'TCC_PERF_SEL_SECTOR_HIT', + 19: 'TCC_PERF_SEL_MISS', + 20: 'TCC_PERF_SEL_DEWRITE_ALLOCATE_HIT', + 21: 'TCC_PERF_SEL_FULLY_WRITTEN_HIT', + 22: 'TCC_PERF_SEL_WRITEBACK', + 23: 'TCC_PERF_SEL_LATENCY_FIFO_FULL', + 24: 'TCC_PERF_SEL_SRC_FIFO_FULL', + 25: 'TCC_PERF_SEL_HOLE_FIFO_FULL', + 26: 'TCC_PERF_SEL_EA_WRREQ', + 27: 'TCC_PERF_SEL_EA_WRREQ_64B', + 28: 'TCC_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 29: 'TCC_PERF_SEL_EA_WR_UNCACHED_32B', + 30: 'TCC_PERF_SEL_EA_WRREQ_STALL', + 31: 'TCC_PERF_SEL_EA_WRREQ_CREDIT_STALL', + 32: 'TCC_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', + 33: 'TCC_PERF_SEL_EA_WRREQ_LEVEL', + 34: 'TCC_PERF_SEL_EA_ATOMIC', + 35: 'TCC_PERF_SEL_EA_ATOMIC_LEVEL', + 36: 'TCC_PERF_SEL_EA_RDREQ', + 37: 'TCC_PERF_SEL_EA_RDREQ_32B', + 38: 'TCC_PERF_SEL_EA_RD_UNCACHED_32B', + 39: 'TCC_PERF_SEL_EA_RD_MDC_32B', + 40: 'TCC_PERF_SEL_EA_RD_COMPRESSED_32B', + 41: 'TCC_PERF_SEL_EA_RDREQ_CREDIT_STALL', + 42: 'TCC_PERF_SEL_EA_RDREQ_LEVEL', + 43: 'TCC_PERF_SEL_TAG_STALL', + 44: 'TCC_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 45: 'TCC_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 46: 'TCC_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 47: 'TCC_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 48: 'TCC_PERF_SEL_TAG_PROBE_STALL', + 49: 'TCC_PERF_SEL_TAG_PROBE_FILTER_STALL', + 50: 'TCC_PERF_SEL_READ_RETURN_TIMEOUT', + 51: 'TCC_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 52: 'TCC_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 53: 'TCC_PERF_SEL_BUBBLE', + 54: 'TCC_PERF_SEL_RETURN_ACK', + 55: 'TCC_PERF_SEL_RETURN_DATA', + 56: 'TCC_PERF_SEL_RETURN_HOLE', + 57: 'TCC_PERF_SEL_RETURN_ACK_HOLE', + 58: 'TCC_PERF_SEL_IB_REQ', + 59: 'TCC_PERF_SEL_IB_STALL', + 60: 'TCC_PERF_SEL_IB_TAG_STALL', + 61: 'TCC_PERF_SEL_IB_MDC_STALL', + 62: 'TCC_PERF_SEL_TCA_LEVEL', + 63: 'TCC_PERF_SEL_HOLE_LEVEL', + 64: 'TCC_PERF_SEL_NORMAL_WRITEBACK', + 65: 'TCC_PERF_SEL_TC_OP_WBL2_NC_WRITEBACK', + 66: 'TCC_PERF_SEL_TC_OP_WBL2_WC_WRITEBACK', + 67: 'TCC_PERF_SEL_TC_OP_WBINVL2_WRITEBACK', + 68: 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_WRITEBACK', + 69: 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_WRITEBACK', + 70: 'TCC_PERF_SEL_ALL_TC_OP_WB_WRITEBACK', + 71: 'TCC_PERF_SEL_NORMAL_EVICT', + 72: 'TCC_PERF_SEL_TC_OP_WBL2_NC_EVICT', + 73: 'TCC_PERF_SEL_TC_OP_WBL2_WC_EVICT', + 74: 'TCC_PERF_SEL_TC_OP_INVL2_NC_EVICT', + 75: 'TCC_PERF_SEL_TC_OP_WBINVL2_EVICT', + 76: 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_EVICT', + 77: 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_EVICT', + 78: 'TCC_PERF_SEL_ALL_TC_OP_INV_EVICT', + 79: 'TCC_PERF_SEL_PROBE_EVICT', + 80: 'TCC_PERF_SEL_TC_OP_WBL2_NC_CYCLE', + 81: 'TCC_PERF_SEL_TC_OP_WBL2_WC_CYCLE', + 82: 'TCC_PERF_SEL_TC_OP_INVL2_NC_CYCLE', + 83: 'TCC_PERF_SEL_TC_OP_WBINVL2_CYCLE', + 84: 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_CYCLE', + 85: 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_CYCLE', + 86: 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_CYCLE', + 87: 'TCC_PERF_SEL_TC_OP_WBL2_NC_START', + 88: 'TCC_PERF_SEL_TC_OP_WBL2_WC_START', + 89: 'TCC_PERF_SEL_TC_OP_INVL2_NC_START', + 90: 'TCC_PERF_SEL_TC_OP_WBINVL2_START', + 91: 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_START', + 92: 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_START', + 93: 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 94: 'TCC_PERF_SEL_TC_OP_WBL2_NC_FINISH', + 95: 'TCC_PERF_SEL_TC_OP_WBL2_WC_FINISH', + 96: 'TCC_PERF_SEL_TC_OP_INVL2_NC_FINISH', + 97: 'TCC_PERF_SEL_TC_OP_WBINVL2_FINISH', + 98: 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_FINISH', + 99: 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_FINISH', + 100: 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_FINISH', + 101: 'TCC_PERF_SEL_MDC_REQ', + 102: 'TCC_PERF_SEL_MDC_LEVEL', + 103: 'TCC_PERF_SEL_MDC_TAG_HIT', + 104: 'TCC_PERF_SEL_MDC_SECTOR_HIT', + 105: 'TCC_PERF_SEL_MDC_SECTOR_MISS', + 106: 'TCC_PERF_SEL_MDC_TAG_STALL', + 107: 'TCC_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 108: 'TCC_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 109: 'TCC_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 110: 'TCC_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 111: 'TCC_PERF_SEL_PROBE_FILTER_DISABLED', + 128: 'TCC_PERF_SEL_CLIENT0_REQ', + 129: 'TCC_PERF_SEL_CLIENT1_REQ', + 130: 'TCC_PERF_SEL_CLIENT2_REQ', + 131: 'TCC_PERF_SEL_CLIENT3_REQ', + 132: 'TCC_PERF_SEL_CLIENT4_REQ', + 133: 'TCC_PERF_SEL_CLIENT5_REQ', + 134: 'TCC_PERF_SEL_CLIENT6_REQ', + 135: 'TCC_PERF_SEL_CLIENT7_REQ', + 136: 'TCC_PERF_SEL_CLIENT8_REQ', + 137: 'TCC_PERF_SEL_CLIENT9_REQ', + 138: 'TCC_PERF_SEL_CLIENT10_REQ', + 139: 'TCC_PERF_SEL_CLIENT11_REQ', + 140: 'TCC_PERF_SEL_CLIENT12_REQ', + 141: 'TCC_PERF_SEL_CLIENT13_REQ', + 142: 'TCC_PERF_SEL_CLIENT14_REQ', + 143: 'TCC_PERF_SEL_CLIENT15_REQ', + 144: 'TCC_PERF_SEL_CLIENT16_REQ', + 145: 'TCC_PERF_SEL_CLIENT17_REQ', + 146: 'TCC_PERF_SEL_CLIENT18_REQ', + 147: 'TCC_PERF_SEL_CLIENT19_REQ', + 148: 'TCC_PERF_SEL_CLIENT20_REQ', + 149: 'TCC_PERF_SEL_CLIENT21_REQ', + 150: 'TCC_PERF_SEL_CLIENT22_REQ', + 151: 'TCC_PERF_SEL_CLIENT23_REQ', + 152: 'TCC_PERF_SEL_CLIENT24_REQ', + 153: 'TCC_PERF_SEL_CLIENT25_REQ', + 154: 'TCC_PERF_SEL_CLIENT26_REQ', + 155: 'TCC_PERF_SEL_CLIENT27_REQ', + 156: 'TCC_PERF_SEL_CLIENT28_REQ', + 157: 'TCC_PERF_SEL_CLIENT29_REQ', + 158: 'TCC_PERF_SEL_CLIENT30_REQ', + 159: 'TCC_PERF_SEL_CLIENT31_REQ', + 160: 'TCC_PERF_SEL_CLIENT32_REQ', + 161: 'TCC_PERF_SEL_CLIENT33_REQ', + 162: 'TCC_PERF_SEL_CLIENT34_REQ', + 163: 'TCC_PERF_SEL_CLIENT35_REQ', + 164: 'TCC_PERF_SEL_CLIENT36_REQ', + 165: 'TCC_PERF_SEL_CLIENT37_REQ', + 166: 'TCC_PERF_SEL_CLIENT38_REQ', + 167: 'TCC_PERF_SEL_CLIENT39_REQ', + 168: 'TCC_PERF_SEL_CLIENT40_REQ', + 169: 'TCC_PERF_SEL_CLIENT41_REQ', + 170: 'TCC_PERF_SEL_CLIENT42_REQ', + 171: 'TCC_PERF_SEL_CLIENT43_REQ', + 172: 'TCC_PERF_SEL_CLIENT44_REQ', + 173: 'TCC_PERF_SEL_CLIENT45_REQ', + 174: 'TCC_PERF_SEL_CLIENT46_REQ', + 175: 'TCC_PERF_SEL_CLIENT47_REQ', + 176: 'TCC_PERF_SEL_CLIENT48_REQ', + 177: 'TCC_PERF_SEL_CLIENT49_REQ', + 178: 'TCC_PERF_SEL_CLIENT50_REQ', + 179: 'TCC_PERF_SEL_CLIENT51_REQ', + 180: 'TCC_PERF_SEL_CLIENT52_REQ', + 181: 'TCC_PERF_SEL_CLIENT53_REQ', + 182: 'TCC_PERF_SEL_CLIENT54_REQ', + 183: 'TCC_PERF_SEL_CLIENT55_REQ', + 184: 'TCC_PERF_SEL_CLIENT56_REQ', + 185: 'TCC_PERF_SEL_CLIENT57_REQ', + 186: 'TCC_PERF_SEL_CLIENT58_REQ', + 187: 'TCC_PERF_SEL_CLIENT59_REQ', + 188: 'TCC_PERF_SEL_CLIENT60_REQ', + 189: 'TCC_PERF_SEL_CLIENT61_REQ', + 190: 'TCC_PERF_SEL_CLIENT62_REQ', + 191: 'TCC_PERF_SEL_CLIENT63_REQ', + 192: 'TCC_PERF_SEL_CLIENT64_REQ', + 193: 'TCC_PERF_SEL_CLIENT65_REQ', + 194: 'TCC_PERF_SEL_CLIENT66_REQ', + 195: 'TCC_PERF_SEL_CLIENT67_REQ', + 196: 'TCC_PERF_SEL_CLIENT68_REQ', + 197: 'TCC_PERF_SEL_CLIENT69_REQ', + 198: 'TCC_PERF_SEL_CLIENT70_REQ', + 199: 'TCC_PERF_SEL_CLIENT71_REQ', + 200: 'TCC_PERF_SEL_CLIENT72_REQ', + 201: 'TCC_PERF_SEL_CLIENT73_REQ', + 202: 'TCC_PERF_SEL_CLIENT74_REQ', + 203: 'TCC_PERF_SEL_CLIENT75_REQ', + 204: 'TCC_PERF_SEL_CLIENT76_REQ', + 205: 'TCC_PERF_SEL_CLIENT77_REQ', + 206: 'TCC_PERF_SEL_CLIENT78_REQ', + 207: 'TCC_PERF_SEL_CLIENT79_REQ', + 208: 'TCC_PERF_SEL_CLIENT80_REQ', + 209: 'TCC_PERF_SEL_CLIENT81_REQ', + 210: 'TCC_PERF_SEL_CLIENT82_REQ', + 211: 'TCC_PERF_SEL_CLIENT83_REQ', + 212: 'TCC_PERF_SEL_CLIENT84_REQ', + 213: 'TCC_PERF_SEL_CLIENT85_REQ', + 214: 'TCC_PERF_SEL_CLIENT86_REQ', + 215: 'TCC_PERF_SEL_CLIENT87_REQ', + 216: 'TCC_PERF_SEL_CLIENT88_REQ', + 217: 'TCC_PERF_SEL_CLIENT89_REQ', + 218: 'TCC_PERF_SEL_CLIENT90_REQ', + 219: 'TCC_PERF_SEL_CLIENT91_REQ', + 220: 'TCC_PERF_SEL_CLIENT92_REQ', + 221: 'TCC_PERF_SEL_CLIENT93_REQ', + 222: 'TCC_PERF_SEL_CLIENT94_REQ', + 223: 'TCC_PERF_SEL_CLIENT95_REQ', + 224: 'TCC_PERF_SEL_CLIENT96_REQ', + 225: 'TCC_PERF_SEL_CLIENT97_REQ', + 226: 'TCC_PERF_SEL_CLIENT98_REQ', + 227: 'TCC_PERF_SEL_CLIENT99_REQ', + 228: 'TCC_PERF_SEL_CLIENT100_REQ', + 229: 'TCC_PERF_SEL_CLIENT101_REQ', + 230: 'TCC_PERF_SEL_CLIENT102_REQ', + 231: 'TCC_PERF_SEL_CLIENT103_REQ', + 232: 'TCC_PERF_SEL_CLIENT104_REQ', + 233: 'TCC_PERF_SEL_CLIENT105_REQ', + 234: 'TCC_PERF_SEL_CLIENT106_REQ', + 235: 'TCC_PERF_SEL_CLIENT107_REQ', + 236: 'TCC_PERF_SEL_CLIENT108_REQ', + 237: 'TCC_PERF_SEL_CLIENT109_REQ', + 238: 'TCC_PERF_SEL_CLIENT110_REQ', + 239: 'TCC_PERF_SEL_CLIENT111_REQ', + 240: 'TCC_PERF_SEL_CLIENT112_REQ', + 241: 'TCC_PERF_SEL_CLIENT113_REQ', + 242: 'TCC_PERF_SEL_CLIENT114_REQ', + 243: 'TCC_PERF_SEL_CLIENT115_REQ', + 244: 'TCC_PERF_SEL_CLIENT116_REQ', + 245: 'TCC_PERF_SEL_CLIENT117_REQ', + 246: 'TCC_PERF_SEL_CLIENT118_REQ', + 247: 'TCC_PERF_SEL_CLIENT119_REQ', + 248: 'TCC_PERF_SEL_CLIENT120_REQ', + 249: 'TCC_PERF_SEL_CLIENT121_REQ', + 250: 'TCC_PERF_SEL_CLIENT122_REQ', + 251: 'TCC_PERF_SEL_CLIENT123_REQ', + 252: 'TCC_PERF_SEL_CLIENT124_REQ', + 253: 'TCC_PERF_SEL_CLIENT125_REQ', + 254: 'TCC_PERF_SEL_CLIENT126_REQ', + 255: 'TCC_PERF_SEL_CLIENT127_REQ', +} +TCC_PERF_SEL_NONE = 0 +TCC_PERF_SEL_CYCLE = 1 +TCC_PERF_SEL_BUSY = 2 +TCC_PERF_SEL_REQ = 3 +TCC_PERF_SEL_STREAMING_REQ = 4 +TCC_PERF_SEL_EXE_REQ = 5 +TCC_PERF_SEL_COMPRESSED_REQ = 6 +TCC_PERF_SEL_COMPRESSED_0_REQ = 7 +TCC_PERF_SEL_METADATA_REQ = 8 +TCC_PERF_SEL_NC_VIRTUAL_REQ = 9 +TCC_PERF_SEL_UC_VIRTUAL_REQ = 10 +TCC_PERF_SEL_CC_PHYSICAL_REQ = 11 +TCC_PERF_SEL_PROBE = 12 +TCC_PERF_SEL_PROBE_ALL = 13 +TCC_PERF_SEL_READ = 14 +TCC_PERF_SEL_WRITE = 15 +TCC_PERF_SEL_ATOMIC = 16 +TCC_PERF_SEL_HIT = 17 +TCC_PERF_SEL_SECTOR_HIT = 18 +TCC_PERF_SEL_MISS = 19 +TCC_PERF_SEL_DEWRITE_ALLOCATE_HIT = 20 +TCC_PERF_SEL_FULLY_WRITTEN_HIT = 21 +TCC_PERF_SEL_WRITEBACK = 22 +TCC_PERF_SEL_LATENCY_FIFO_FULL = 23 +TCC_PERF_SEL_SRC_FIFO_FULL = 24 +TCC_PERF_SEL_HOLE_FIFO_FULL = 25 +TCC_PERF_SEL_EA_WRREQ = 26 +TCC_PERF_SEL_EA_WRREQ_64B = 27 +TCC_PERF_SEL_EA_WRREQ_PROBE_COMMAND = 28 +TCC_PERF_SEL_EA_WR_UNCACHED_32B = 29 +TCC_PERF_SEL_EA_WRREQ_STALL = 30 +TCC_PERF_SEL_EA_WRREQ_CREDIT_STALL = 31 +TCC_PERF_SEL_TOO_MANY_EA_WRREQS_STALL = 32 +TCC_PERF_SEL_EA_WRREQ_LEVEL = 33 +TCC_PERF_SEL_EA_ATOMIC = 34 +TCC_PERF_SEL_EA_ATOMIC_LEVEL = 35 +TCC_PERF_SEL_EA_RDREQ = 36 +TCC_PERF_SEL_EA_RDREQ_32B = 37 +TCC_PERF_SEL_EA_RD_UNCACHED_32B = 38 +TCC_PERF_SEL_EA_RD_MDC_32B = 39 +TCC_PERF_SEL_EA_RD_COMPRESSED_32B = 40 +TCC_PERF_SEL_EA_RDREQ_CREDIT_STALL = 41 +TCC_PERF_SEL_EA_RDREQ_LEVEL = 42 +TCC_PERF_SEL_TAG_STALL = 43 +TCC_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL = 44 +TCC_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL = 45 +TCC_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL = 46 +TCC_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL = 47 +TCC_PERF_SEL_TAG_PROBE_STALL = 48 +TCC_PERF_SEL_TAG_PROBE_FILTER_STALL = 49 +TCC_PERF_SEL_READ_RETURN_TIMEOUT = 50 +TCC_PERF_SEL_WRITEBACK_READ_TIMEOUT = 51 +TCC_PERF_SEL_READ_RETURN_FULL_BUBBLE = 52 +TCC_PERF_SEL_BUBBLE = 53 +TCC_PERF_SEL_RETURN_ACK = 54 +TCC_PERF_SEL_RETURN_DATA = 55 +TCC_PERF_SEL_RETURN_HOLE = 56 +TCC_PERF_SEL_RETURN_ACK_HOLE = 57 +TCC_PERF_SEL_IB_REQ = 58 +TCC_PERF_SEL_IB_STALL = 59 +TCC_PERF_SEL_IB_TAG_STALL = 60 +TCC_PERF_SEL_IB_MDC_STALL = 61 +TCC_PERF_SEL_TCA_LEVEL = 62 +TCC_PERF_SEL_HOLE_LEVEL = 63 +TCC_PERF_SEL_NORMAL_WRITEBACK = 64 +TCC_PERF_SEL_TC_OP_WBL2_NC_WRITEBACK = 65 +TCC_PERF_SEL_TC_OP_WBL2_WC_WRITEBACK = 66 +TCC_PERF_SEL_TC_OP_WBINVL2_WRITEBACK = 67 +TCC_PERF_SEL_TC_OP_WBINVL2_NC_WRITEBACK = 68 +TCC_PERF_SEL_TC_OP_WBINVL2_SD_WRITEBACK = 69 +TCC_PERF_SEL_ALL_TC_OP_WB_WRITEBACK = 70 +TCC_PERF_SEL_NORMAL_EVICT = 71 +TCC_PERF_SEL_TC_OP_WBL2_NC_EVICT = 72 +TCC_PERF_SEL_TC_OP_WBL2_WC_EVICT = 73 +TCC_PERF_SEL_TC_OP_INVL2_NC_EVICT = 74 +TCC_PERF_SEL_TC_OP_WBINVL2_EVICT = 75 +TCC_PERF_SEL_TC_OP_WBINVL2_NC_EVICT = 76 +TCC_PERF_SEL_TC_OP_WBINVL2_SD_EVICT = 77 +TCC_PERF_SEL_ALL_TC_OP_INV_EVICT = 78 +TCC_PERF_SEL_PROBE_EVICT = 79 +TCC_PERF_SEL_TC_OP_WBL2_NC_CYCLE = 80 +TCC_PERF_SEL_TC_OP_WBL2_WC_CYCLE = 81 +TCC_PERF_SEL_TC_OP_INVL2_NC_CYCLE = 82 +TCC_PERF_SEL_TC_OP_WBINVL2_CYCLE = 83 +TCC_PERF_SEL_TC_OP_WBINVL2_NC_CYCLE = 84 +TCC_PERF_SEL_TC_OP_WBINVL2_SD_CYCLE = 85 +TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_CYCLE = 86 +TCC_PERF_SEL_TC_OP_WBL2_NC_START = 87 +TCC_PERF_SEL_TC_OP_WBL2_WC_START = 88 +TCC_PERF_SEL_TC_OP_INVL2_NC_START = 89 +TCC_PERF_SEL_TC_OP_WBINVL2_START = 90 +TCC_PERF_SEL_TC_OP_WBINVL2_NC_START = 91 +TCC_PERF_SEL_TC_OP_WBINVL2_SD_START = 92 +TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_START = 93 +TCC_PERF_SEL_TC_OP_WBL2_NC_FINISH = 94 +TCC_PERF_SEL_TC_OP_WBL2_WC_FINISH = 95 +TCC_PERF_SEL_TC_OP_INVL2_NC_FINISH = 96 +TCC_PERF_SEL_TC_OP_WBINVL2_FINISH = 97 +TCC_PERF_SEL_TC_OP_WBINVL2_NC_FINISH = 98 +TCC_PERF_SEL_TC_OP_WBINVL2_SD_FINISH = 99 +TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_FINISH = 100 +TCC_PERF_SEL_MDC_REQ = 101 +TCC_PERF_SEL_MDC_LEVEL = 102 +TCC_PERF_SEL_MDC_TAG_HIT = 103 +TCC_PERF_SEL_MDC_SECTOR_HIT = 104 +TCC_PERF_SEL_MDC_SECTOR_MISS = 105 +TCC_PERF_SEL_MDC_TAG_STALL = 106 +TCC_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL = 107 +TCC_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL = 108 +TCC_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL = 109 +TCC_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION = 110 +TCC_PERF_SEL_PROBE_FILTER_DISABLED = 111 +TCC_PERF_SEL_CLIENT0_REQ = 128 +TCC_PERF_SEL_CLIENT1_REQ = 129 +TCC_PERF_SEL_CLIENT2_REQ = 130 +TCC_PERF_SEL_CLIENT3_REQ = 131 +TCC_PERF_SEL_CLIENT4_REQ = 132 +TCC_PERF_SEL_CLIENT5_REQ = 133 +TCC_PERF_SEL_CLIENT6_REQ = 134 +TCC_PERF_SEL_CLIENT7_REQ = 135 +TCC_PERF_SEL_CLIENT8_REQ = 136 +TCC_PERF_SEL_CLIENT9_REQ = 137 +TCC_PERF_SEL_CLIENT10_REQ = 138 +TCC_PERF_SEL_CLIENT11_REQ = 139 +TCC_PERF_SEL_CLIENT12_REQ = 140 +TCC_PERF_SEL_CLIENT13_REQ = 141 +TCC_PERF_SEL_CLIENT14_REQ = 142 +TCC_PERF_SEL_CLIENT15_REQ = 143 +TCC_PERF_SEL_CLIENT16_REQ = 144 +TCC_PERF_SEL_CLIENT17_REQ = 145 +TCC_PERF_SEL_CLIENT18_REQ = 146 +TCC_PERF_SEL_CLIENT19_REQ = 147 +TCC_PERF_SEL_CLIENT20_REQ = 148 +TCC_PERF_SEL_CLIENT21_REQ = 149 +TCC_PERF_SEL_CLIENT22_REQ = 150 +TCC_PERF_SEL_CLIENT23_REQ = 151 +TCC_PERF_SEL_CLIENT24_REQ = 152 +TCC_PERF_SEL_CLIENT25_REQ = 153 +TCC_PERF_SEL_CLIENT26_REQ = 154 +TCC_PERF_SEL_CLIENT27_REQ = 155 +TCC_PERF_SEL_CLIENT28_REQ = 156 +TCC_PERF_SEL_CLIENT29_REQ = 157 +TCC_PERF_SEL_CLIENT30_REQ = 158 +TCC_PERF_SEL_CLIENT31_REQ = 159 +TCC_PERF_SEL_CLIENT32_REQ = 160 +TCC_PERF_SEL_CLIENT33_REQ = 161 +TCC_PERF_SEL_CLIENT34_REQ = 162 +TCC_PERF_SEL_CLIENT35_REQ = 163 +TCC_PERF_SEL_CLIENT36_REQ = 164 +TCC_PERF_SEL_CLIENT37_REQ = 165 +TCC_PERF_SEL_CLIENT38_REQ = 166 +TCC_PERF_SEL_CLIENT39_REQ = 167 +TCC_PERF_SEL_CLIENT40_REQ = 168 +TCC_PERF_SEL_CLIENT41_REQ = 169 +TCC_PERF_SEL_CLIENT42_REQ = 170 +TCC_PERF_SEL_CLIENT43_REQ = 171 +TCC_PERF_SEL_CLIENT44_REQ = 172 +TCC_PERF_SEL_CLIENT45_REQ = 173 +TCC_PERF_SEL_CLIENT46_REQ = 174 +TCC_PERF_SEL_CLIENT47_REQ = 175 +TCC_PERF_SEL_CLIENT48_REQ = 176 +TCC_PERF_SEL_CLIENT49_REQ = 177 +TCC_PERF_SEL_CLIENT50_REQ = 178 +TCC_PERF_SEL_CLIENT51_REQ = 179 +TCC_PERF_SEL_CLIENT52_REQ = 180 +TCC_PERF_SEL_CLIENT53_REQ = 181 +TCC_PERF_SEL_CLIENT54_REQ = 182 +TCC_PERF_SEL_CLIENT55_REQ = 183 +TCC_PERF_SEL_CLIENT56_REQ = 184 +TCC_PERF_SEL_CLIENT57_REQ = 185 +TCC_PERF_SEL_CLIENT58_REQ = 186 +TCC_PERF_SEL_CLIENT59_REQ = 187 +TCC_PERF_SEL_CLIENT60_REQ = 188 +TCC_PERF_SEL_CLIENT61_REQ = 189 +TCC_PERF_SEL_CLIENT62_REQ = 190 +TCC_PERF_SEL_CLIENT63_REQ = 191 +TCC_PERF_SEL_CLIENT64_REQ = 192 +TCC_PERF_SEL_CLIENT65_REQ = 193 +TCC_PERF_SEL_CLIENT66_REQ = 194 +TCC_PERF_SEL_CLIENT67_REQ = 195 +TCC_PERF_SEL_CLIENT68_REQ = 196 +TCC_PERF_SEL_CLIENT69_REQ = 197 +TCC_PERF_SEL_CLIENT70_REQ = 198 +TCC_PERF_SEL_CLIENT71_REQ = 199 +TCC_PERF_SEL_CLIENT72_REQ = 200 +TCC_PERF_SEL_CLIENT73_REQ = 201 +TCC_PERF_SEL_CLIENT74_REQ = 202 +TCC_PERF_SEL_CLIENT75_REQ = 203 +TCC_PERF_SEL_CLIENT76_REQ = 204 +TCC_PERF_SEL_CLIENT77_REQ = 205 +TCC_PERF_SEL_CLIENT78_REQ = 206 +TCC_PERF_SEL_CLIENT79_REQ = 207 +TCC_PERF_SEL_CLIENT80_REQ = 208 +TCC_PERF_SEL_CLIENT81_REQ = 209 +TCC_PERF_SEL_CLIENT82_REQ = 210 +TCC_PERF_SEL_CLIENT83_REQ = 211 +TCC_PERF_SEL_CLIENT84_REQ = 212 +TCC_PERF_SEL_CLIENT85_REQ = 213 +TCC_PERF_SEL_CLIENT86_REQ = 214 +TCC_PERF_SEL_CLIENT87_REQ = 215 +TCC_PERF_SEL_CLIENT88_REQ = 216 +TCC_PERF_SEL_CLIENT89_REQ = 217 +TCC_PERF_SEL_CLIENT90_REQ = 218 +TCC_PERF_SEL_CLIENT91_REQ = 219 +TCC_PERF_SEL_CLIENT92_REQ = 220 +TCC_PERF_SEL_CLIENT93_REQ = 221 +TCC_PERF_SEL_CLIENT94_REQ = 222 +TCC_PERF_SEL_CLIENT95_REQ = 223 +TCC_PERF_SEL_CLIENT96_REQ = 224 +TCC_PERF_SEL_CLIENT97_REQ = 225 +TCC_PERF_SEL_CLIENT98_REQ = 226 +TCC_PERF_SEL_CLIENT99_REQ = 227 +TCC_PERF_SEL_CLIENT100_REQ = 228 +TCC_PERF_SEL_CLIENT101_REQ = 229 +TCC_PERF_SEL_CLIENT102_REQ = 230 +TCC_PERF_SEL_CLIENT103_REQ = 231 +TCC_PERF_SEL_CLIENT104_REQ = 232 +TCC_PERF_SEL_CLIENT105_REQ = 233 +TCC_PERF_SEL_CLIENT106_REQ = 234 +TCC_PERF_SEL_CLIENT107_REQ = 235 +TCC_PERF_SEL_CLIENT108_REQ = 236 +TCC_PERF_SEL_CLIENT109_REQ = 237 +TCC_PERF_SEL_CLIENT110_REQ = 238 +TCC_PERF_SEL_CLIENT111_REQ = 239 +TCC_PERF_SEL_CLIENT112_REQ = 240 +TCC_PERF_SEL_CLIENT113_REQ = 241 +TCC_PERF_SEL_CLIENT114_REQ = 242 +TCC_PERF_SEL_CLIENT115_REQ = 243 +TCC_PERF_SEL_CLIENT116_REQ = 244 +TCC_PERF_SEL_CLIENT117_REQ = 245 +TCC_PERF_SEL_CLIENT118_REQ = 246 +TCC_PERF_SEL_CLIENT119_REQ = 247 +TCC_PERF_SEL_CLIENT120_REQ = 248 +TCC_PERF_SEL_CLIENT121_REQ = 249 +TCC_PERF_SEL_CLIENT122_REQ = 250 +TCC_PERF_SEL_CLIENT123_REQ = 251 +TCC_PERF_SEL_CLIENT124_REQ = 252 +TCC_PERF_SEL_CLIENT125_REQ = 253 +TCC_PERF_SEL_CLIENT126_REQ = 254 +TCC_PERF_SEL_CLIENT127_REQ = 255 +TCC_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TCA_PERF_SEL' +TCA_PERF_SEL__enumvalues = { + 0: 'TCA_PERF_SEL_NONE', + 1: 'TCA_PERF_SEL_CYCLE', + 2: 'TCA_PERF_SEL_BUSY', + 3: 'TCA_PERF_SEL_FORCED_HOLE_TCC0', + 4: 'TCA_PERF_SEL_FORCED_HOLE_TCC1', + 5: 'TCA_PERF_SEL_FORCED_HOLE_TCC2', + 6: 'TCA_PERF_SEL_FORCED_HOLE_TCC3', + 7: 'TCA_PERF_SEL_FORCED_HOLE_TCC4', + 8: 'TCA_PERF_SEL_FORCED_HOLE_TCC5', + 9: 'TCA_PERF_SEL_FORCED_HOLE_TCC6', + 10: 'TCA_PERF_SEL_FORCED_HOLE_TCC7', + 11: 'TCA_PERF_SEL_REQ_TCC0', + 12: 'TCA_PERF_SEL_REQ_TCC1', + 13: 'TCA_PERF_SEL_REQ_TCC2', + 14: 'TCA_PERF_SEL_REQ_TCC3', + 15: 'TCA_PERF_SEL_REQ_TCC4', + 16: 'TCA_PERF_SEL_REQ_TCC5', + 17: 'TCA_PERF_SEL_REQ_TCC6', + 18: 'TCA_PERF_SEL_REQ_TCC7', + 19: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC0', + 20: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC1', + 21: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC2', + 22: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC3', + 23: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC4', + 24: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC5', + 25: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC6', + 26: 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC7', + 27: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC0', + 28: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC1', + 29: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC2', + 30: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC3', + 31: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC4', + 32: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC5', + 33: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC6', + 34: 'TCA_PERF_SEL_CROSSBAR_STALL_TCC7', +} +TCA_PERF_SEL_NONE = 0 +TCA_PERF_SEL_CYCLE = 1 +TCA_PERF_SEL_BUSY = 2 +TCA_PERF_SEL_FORCED_HOLE_TCC0 = 3 +TCA_PERF_SEL_FORCED_HOLE_TCC1 = 4 +TCA_PERF_SEL_FORCED_HOLE_TCC2 = 5 +TCA_PERF_SEL_FORCED_HOLE_TCC3 = 6 +TCA_PERF_SEL_FORCED_HOLE_TCC4 = 7 +TCA_PERF_SEL_FORCED_HOLE_TCC5 = 8 +TCA_PERF_SEL_FORCED_HOLE_TCC6 = 9 +TCA_PERF_SEL_FORCED_HOLE_TCC7 = 10 +TCA_PERF_SEL_REQ_TCC0 = 11 +TCA_PERF_SEL_REQ_TCC1 = 12 +TCA_PERF_SEL_REQ_TCC2 = 13 +TCA_PERF_SEL_REQ_TCC3 = 14 +TCA_PERF_SEL_REQ_TCC4 = 15 +TCA_PERF_SEL_REQ_TCC5 = 16 +TCA_PERF_SEL_REQ_TCC6 = 17 +TCA_PERF_SEL_REQ_TCC7 = 18 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC0 = 19 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC1 = 20 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC2 = 21 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC3 = 22 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC4 = 23 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC5 = 24 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC6 = 25 +TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC7 = 26 +TCA_PERF_SEL_CROSSBAR_STALL_TCC0 = 27 +TCA_PERF_SEL_CROSSBAR_STALL_TCC1 = 28 +TCA_PERF_SEL_CROSSBAR_STALL_TCC2 = 29 +TCA_PERF_SEL_CROSSBAR_STALL_TCC3 = 30 +TCA_PERF_SEL_CROSSBAR_STALL_TCC4 = 31 +TCA_PERF_SEL_CROSSBAR_STALL_TCC5 = 32 +TCA_PERF_SEL_CROSSBAR_STALL_TCC6 = 33 +TCA_PERF_SEL_CROSSBAR_STALL_TCC7 = 34 +TCA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_PERF_SEL' +GRBM_PERF_SEL__enumvalues = { + 0: 'GRBM_PERF_SEL_COUNT', + 1: 'GRBM_PERF_SEL_USER_DEFINED', + 2: 'GRBM_PERF_SEL_GUI_ACTIVE', + 3: 'GRBM_PERF_SEL_CP_BUSY', + 4: 'GRBM_PERF_SEL_CP_COHER_BUSY', + 5: 'GRBM_PERF_SEL_CP_DMA_BUSY', + 6: 'GRBM_PERF_SEL_CB_BUSY', + 7: 'GRBM_PERF_SEL_DB_BUSY', + 8: 'GRBM_PERF_SEL_PA_BUSY', + 9: 'GRBM_PERF_SEL_SC_BUSY', + 10: 'GRBM_PERF_SEL_RESERVED_6', + 11: 'GRBM_PERF_SEL_SPI_BUSY', + 12: 'GRBM_PERF_SEL_SX_BUSY', + 13: 'GRBM_PERF_SEL_TA_BUSY', + 14: 'GRBM_PERF_SEL_CB_CLEAN', + 15: 'GRBM_PERF_SEL_DB_CLEAN', + 16: 'GRBM_PERF_SEL_RESERVED_5', + 17: 'GRBM_PERF_SEL_VGT_BUSY', + 18: 'GRBM_PERF_SEL_RESERVED_4', + 19: 'GRBM_PERF_SEL_RESERVED_3', + 20: 'GRBM_PERF_SEL_RESERVED_2', + 21: 'GRBM_PERF_SEL_RESERVED_1', + 22: 'GRBM_PERF_SEL_RESERVED_0', + 23: 'GRBM_PERF_SEL_IA_BUSY', + 24: 'GRBM_PERF_SEL_IA_NO_DMA_BUSY', + 25: 'GRBM_PERF_SEL_GDS_BUSY', + 26: 'GRBM_PERF_SEL_BCI_BUSY', + 27: 'GRBM_PERF_SEL_RLC_BUSY', + 28: 'GRBM_PERF_SEL_TC_BUSY', + 29: 'GRBM_PERF_SEL_CPG_BUSY', + 30: 'GRBM_PERF_SEL_CPC_BUSY', + 31: 'GRBM_PERF_SEL_CPF_BUSY', + 32: 'GRBM_PERF_SEL_WD_BUSY', + 33: 'GRBM_PERF_SEL_WD_NO_DMA_BUSY', + 34: 'GRBM_PERF_SEL_UTCL2_BUSY', + 35: 'GRBM_PERF_SEL_EA_BUSY', + 36: 'GRBM_PERF_SEL_RMI_BUSY', + 37: 'GRBM_PERF_SEL_CPAXI_BUSY', +} +GRBM_PERF_SEL_COUNT = 0 +GRBM_PERF_SEL_USER_DEFINED = 1 +GRBM_PERF_SEL_GUI_ACTIVE = 2 +GRBM_PERF_SEL_CP_BUSY = 3 +GRBM_PERF_SEL_CP_COHER_BUSY = 4 +GRBM_PERF_SEL_CP_DMA_BUSY = 5 +GRBM_PERF_SEL_CB_BUSY = 6 +GRBM_PERF_SEL_DB_BUSY = 7 +GRBM_PERF_SEL_PA_BUSY = 8 +GRBM_PERF_SEL_SC_BUSY = 9 +GRBM_PERF_SEL_RESERVED_6 = 10 +GRBM_PERF_SEL_SPI_BUSY = 11 +GRBM_PERF_SEL_SX_BUSY = 12 +GRBM_PERF_SEL_TA_BUSY = 13 +GRBM_PERF_SEL_CB_CLEAN = 14 +GRBM_PERF_SEL_DB_CLEAN = 15 +GRBM_PERF_SEL_RESERVED_5 = 16 +GRBM_PERF_SEL_VGT_BUSY = 17 +GRBM_PERF_SEL_RESERVED_4 = 18 +GRBM_PERF_SEL_RESERVED_3 = 19 +GRBM_PERF_SEL_RESERVED_2 = 20 +GRBM_PERF_SEL_RESERVED_1 = 21 +GRBM_PERF_SEL_RESERVED_0 = 22 +GRBM_PERF_SEL_IA_BUSY = 23 +GRBM_PERF_SEL_IA_NO_DMA_BUSY = 24 +GRBM_PERF_SEL_GDS_BUSY = 25 +GRBM_PERF_SEL_BCI_BUSY = 26 +GRBM_PERF_SEL_RLC_BUSY = 27 +GRBM_PERF_SEL_TC_BUSY = 28 +GRBM_PERF_SEL_CPG_BUSY = 29 +GRBM_PERF_SEL_CPC_BUSY = 30 +GRBM_PERF_SEL_CPF_BUSY = 31 +GRBM_PERF_SEL_WD_BUSY = 32 +GRBM_PERF_SEL_WD_NO_DMA_BUSY = 33 +GRBM_PERF_SEL_UTCL2_BUSY = 34 +GRBM_PERF_SEL_EA_BUSY = 35 +GRBM_PERF_SEL_RMI_BUSY = 36 +GRBM_PERF_SEL_CPAXI_BUSY = 37 +GRBM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE0_PERF_SEL' +GRBM_SE0_PERF_SEL__enumvalues = { + 0: 'GRBM_SE0_PERF_SEL_COUNT', + 1: 'GRBM_SE0_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE0_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE0_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE0_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE0_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE0_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE0_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE0_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE0_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE0_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE0_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE0_PERF_SEL_VGT_BUSY', + 14: 'GRBM_SE0_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE0_PERF_SEL_RMI_BUSY', +} +GRBM_SE0_PERF_SEL_COUNT = 0 +GRBM_SE0_PERF_SEL_USER_DEFINED = 1 +GRBM_SE0_PERF_SEL_CB_BUSY = 2 +GRBM_SE0_PERF_SEL_DB_BUSY = 3 +GRBM_SE0_PERF_SEL_SC_BUSY = 4 +GRBM_SE0_PERF_SEL_RESERVED_1 = 5 +GRBM_SE0_PERF_SEL_SPI_BUSY = 6 +GRBM_SE0_PERF_SEL_SX_BUSY = 7 +GRBM_SE0_PERF_SEL_TA_BUSY = 8 +GRBM_SE0_PERF_SEL_CB_CLEAN = 9 +GRBM_SE0_PERF_SEL_DB_CLEAN = 10 +GRBM_SE0_PERF_SEL_RESERVED_0 = 11 +GRBM_SE0_PERF_SEL_PA_BUSY = 12 +GRBM_SE0_PERF_SEL_VGT_BUSY = 13 +GRBM_SE0_PERF_SEL_BCI_BUSY = 14 +GRBM_SE0_PERF_SEL_RMI_BUSY = 15 +GRBM_SE0_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE1_PERF_SEL' +GRBM_SE1_PERF_SEL__enumvalues = { + 0: 'GRBM_SE1_PERF_SEL_COUNT', + 1: 'GRBM_SE1_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE1_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE1_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE1_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE1_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE1_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE1_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE1_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE1_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE1_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE1_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE1_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE1_PERF_SEL_VGT_BUSY', + 14: 'GRBM_SE1_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE1_PERF_SEL_RMI_BUSY', +} +GRBM_SE1_PERF_SEL_COUNT = 0 +GRBM_SE1_PERF_SEL_USER_DEFINED = 1 +GRBM_SE1_PERF_SEL_CB_BUSY = 2 +GRBM_SE1_PERF_SEL_DB_BUSY = 3 +GRBM_SE1_PERF_SEL_SC_BUSY = 4 +GRBM_SE1_PERF_SEL_RESERVED_1 = 5 +GRBM_SE1_PERF_SEL_SPI_BUSY = 6 +GRBM_SE1_PERF_SEL_SX_BUSY = 7 +GRBM_SE1_PERF_SEL_TA_BUSY = 8 +GRBM_SE1_PERF_SEL_CB_CLEAN = 9 +GRBM_SE1_PERF_SEL_DB_CLEAN = 10 +GRBM_SE1_PERF_SEL_RESERVED_0 = 11 +GRBM_SE1_PERF_SEL_PA_BUSY = 12 +GRBM_SE1_PERF_SEL_VGT_BUSY = 13 +GRBM_SE1_PERF_SEL_BCI_BUSY = 14 +GRBM_SE1_PERF_SEL_RMI_BUSY = 15 +GRBM_SE1_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE2_PERF_SEL' +GRBM_SE2_PERF_SEL__enumvalues = { + 0: 'GRBM_SE2_PERF_SEL_COUNT', + 1: 'GRBM_SE2_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE2_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE2_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE2_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE2_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE2_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE2_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE2_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE2_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE2_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE2_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE2_PERF_SEL_VGT_BUSY', + 14: 'GRBM_SE2_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE2_PERF_SEL_RMI_BUSY', +} +GRBM_SE2_PERF_SEL_COUNT = 0 +GRBM_SE2_PERF_SEL_USER_DEFINED = 1 +GRBM_SE2_PERF_SEL_CB_BUSY = 2 +GRBM_SE2_PERF_SEL_DB_BUSY = 3 +GRBM_SE2_PERF_SEL_SC_BUSY = 4 +GRBM_SE2_PERF_SEL_RESERVED_1 = 5 +GRBM_SE2_PERF_SEL_SPI_BUSY = 6 +GRBM_SE2_PERF_SEL_SX_BUSY = 7 +GRBM_SE2_PERF_SEL_TA_BUSY = 8 +GRBM_SE2_PERF_SEL_CB_CLEAN = 9 +GRBM_SE2_PERF_SEL_DB_CLEAN = 10 +GRBM_SE2_PERF_SEL_RESERVED_0 = 11 +GRBM_SE2_PERF_SEL_PA_BUSY = 12 +GRBM_SE2_PERF_SEL_VGT_BUSY = 13 +GRBM_SE2_PERF_SEL_BCI_BUSY = 14 +GRBM_SE2_PERF_SEL_RMI_BUSY = 15 +GRBM_SE2_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'GRBM_SE3_PERF_SEL' +GRBM_SE3_PERF_SEL__enumvalues = { + 0: 'GRBM_SE3_PERF_SEL_COUNT', + 1: 'GRBM_SE3_PERF_SEL_USER_DEFINED', + 2: 'GRBM_SE3_PERF_SEL_CB_BUSY', + 3: 'GRBM_SE3_PERF_SEL_DB_BUSY', + 4: 'GRBM_SE3_PERF_SEL_SC_BUSY', + 5: 'GRBM_SE3_PERF_SEL_RESERVED_1', + 6: 'GRBM_SE3_PERF_SEL_SPI_BUSY', + 7: 'GRBM_SE3_PERF_SEL_SX_BUSY', + 8: 'GRBM_SE3_PERF_SEL_TA_BUSY', + 9: 'GRBM_SE3_PERF_SEL_CB_CLEAN', + 10: 'GRBM_SE3_PERF_SEL_DB_CLEAN', + 11: 'GRBM_SE3_PERF_SEL_RESERVED_0', + 12: 'GRBM_SE3_PERF_SEL_PA_BUSY', + 13: 'GRBM_SE3_PERF_SEL_VGT_BUSY', + 14: 'GRBM_SE3_PERF_SEL_BCI_BUSY', + 15: 'GRBM_SE3_PERF_SEL_RMI_BUSY', +} +GRBM_SE3_PERF_SEL_COUNT = 0 +GRBM_SE3_PERF_SEL_USER_DEFINED = 1 +GRBM_SE3_PERF_SEL_CB_BUSY = 2 +GRBM_SE3_PERF_SEL_DB_BUSY = 3 +GRBM_SE3_PERF_SEL_SC_BUSY = 4 +GRBM_SE3_PERF_SEL_RESERVED_1 = 5 +GRBM_SE3_PERF_SEL_SPI_BUSY = 6 +GRBM_SE3_PERF_SEL_SX_BUSY = 7 +GRBM_SE3_PERF_SEL_TA_BUSY = 8 +GRBM_SE3_PERF_SEL_CB_CLEAN = 9 +GRBM_SE3_PERF_SEL_DB_CLEAN = 10 +GRBM_SE3_PERF_SEL_RESERVED_0 = 11 +GRBM_SE3_PERF_SEL_PA_BUSY = 12 +GRBM_SE3_PERF_SEL_VGT_BUSY = 13 +GRBM_SE3_PERF_SEL_BCI_BUSY = 14 +GRBM_SE3_PERF_SEL_RMI_BUSY = 15 +GRBM_SE3_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_RING_ID' +CP_RING_ID__enumvalues = { + 0: 'RINGID0', + 1: 'RINGID1', + 2: 'RINGID2', + 3: 'RINGID3', +} +RINGID0 = 0 +RINGID1 = 1 +RINGID2 = 2 +RINGID3 = 3 +CP_RING_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PIPE_ID' +CP_PIPE_ID__enumvalues = { + 0: 'PIPE_ID0', + 1: 'PIPE_ID1', + 2: 'PIPE_ID2', + 3: 'PIPE_ID3', +} +PIPE_ID0 = 0 +PIPE_ID1 = 1 +PIPE_ID2 = 2 +PIPE_ID3 = 3 +CP_PIPE_ID = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ME_ID' +CP_ME_ID__enumvalues = { + 0: 'ME_ID0', + 1: 'ME_ID1', + 2: 'ME_ID2', + 3: 'ME_ID3', +} +ME_ID0 = 0 +ME_ID1 = 1 +ME_ID2 = 2 +ME_ID3 = 3 +CP_ME_ID = ctypes.c_uint32 # enum + +# values for enumeration 'SPM_PERFMON_STATE' +SPM_PERFMON_STATE__enumvalues = { + 0: 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'STRM_PERFMON_STATE_START_COUNTING', + 2: 'STRM_PERFMON_STATE_STOP_COUNTING', + 3: 'STRM_PERFMON_STATE_RESERVED_3', + 4: 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +STRM_PERFMON_STATE_DISABLE_AND_RESET = 0 +STRM_PERFMON_STATE_START_COUNTING = 1 +STRM_PERFMON_STATE_STOP_COUNTING = 2 +STRM_PERFMON_STATE_RESERVED_3 = 3 +STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +SPM_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_STATE' +CP_PERFMON_STATE__enumvalues = { + 0: 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 1: 'CP_PERFMON_STATE_START_COUNTING', + 2: 'CP_PERFMON_STATE_STOP_COUNTING', + 3: 'CP_PERFMON_STATE_RESERVED_3', + 4: 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 5: 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', +} +CP_PERFMON_STATE_DISABLE_AND_RESET = 0 +CP_PERFMON_STATE_START_COUNTING = 1 +CP_PERFMON_STATE_STOP_COUNTING = 2 +CP_PERFMON_STATE_RESERVED_3 = 3 +CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM = 4 +CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM = 5 +CP_PERFMON_STATE = ctypes.c_uint32 # enum + +# values for enumeration 'CP_PERFMON_ENABLE_MODE' +CP_PERFMON_ENABLE_MODE__enumvalues = { + 0: 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 1: 'CP_PERFMON_ENABLE_MODE_RESERVED_1', + 2: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 3: 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', +} +CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT = 0 +CP_PERFMON_ENABLE_MODE_RESERVED_1 = 1 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE = 2 +CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE = 3 +CP_PERFMON_ENABLE_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'CPG_PERFCOUNT_SEL' +CPG_PERFCOUNT_SEL__enumvalues = { + 0: 'CPG_PERF_SEL_ALWAYS_COUNT', + 1: 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 2: 'CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR', + 3: 'CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL', + 4: 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 5: 'CPG_PERF_SEL_ME_PARSER_BUSY', + 6: 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 7: 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', + 8: 'CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 9: 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 10: 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 11: 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 12: 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 13: 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 14: 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 15: 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 16: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 17: 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 18: 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 19: 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 20: 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 21: 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 22: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 23: 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 24: 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 25: 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 26: 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 27: 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 28: 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 29: 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 30: 'CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS', + 31: 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 32: 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 33: 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 34: 'CPG_PERF_SEL_MIU_WRITE_REQUEST_SENT', + 35: 'CPG_PERF_SEL_MIU_READ_REQUEST_SENT', + 36: 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 37: 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 38: 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 39: 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 40: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU', + 41: 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 42: 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 43: 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 44: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 45: 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 46: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 47: 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 48: 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', +} +CPG_PERF_SEL_ALWAYS_COUNT = 0 +CPG_PERF_SEL_RBIU_FIFO_FULL = 1 +CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR = 2 +CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL = 3 +CPG_PERF_SEL_CP_GRBM_DWORDS_SENT = 4 +CPG_PERF_SEL_ME_PARSER_BUSY = 5 +CPG_PERF_SEL_COUNT_TYPE0_PACKETS = 6 +CPG_PERF_SEL_COUNT_TYPE3_PACKETS = 7 +CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 8 +CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS = 9 +CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS = 10 +CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS = 11 +CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ = 12 +CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ = 13 +CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX = 14 +CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS = 15 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE = 16 +CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM = 17 +CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY = 18 +CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY = 19 +CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY = 20 +CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ = 21 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP = 22 +CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ = 23 +CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX = 24 +CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU = 25 +CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS = 26 +CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH = 27 +CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER = 28 +CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER = 29 +CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS = 30 +CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY = 31 +CPG_PERF_SEL_DYNAMIC_CLK_VALID = 32 +CPG_PERF_SEL_REGISTER_CLK_VALID = 33 +CPG_PERF_SEL_MIU_WRITE_REQUEST_SENT = 34 +CPG_PERF_SEL_MIU_READ_REQUEST_SENT = 35 +CPG_PERF_SEL_CE_STALL_RAM_DUMP = 36 +CPG_PERF_SEL_CE_STALL_RAM_WRITE = 37 +CPG_PERF_SEL_CE_STALL_ON_INC_FIFO = 38 +CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO = 39 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU = 40 +CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ = 41 +CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG = 42 +CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER = 43 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 44 +CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS = 45 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 46 +CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 47 +CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 48 +CPG_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPF_PERFCOUNT_SEL' +CPF_PERFCOUNT_SEL__enumvalues = { + 0: 'CPF_PERF_SEL_ALWAYS_COUNT', + 1: 'CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE', + 2: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 3: 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 4: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 5: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 6: 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 7: 'CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE', + 8: 'CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS', + 9: 'CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR', + 10: 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 11: 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 12: 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 13: 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 14: 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 15: 'CPF_PERF_SEL_MIU_WRITE_REQUEST_SEND', + 16: 'CPF_PERF_SEL_MIU_READ_REQUEST_SEND', + 17: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 18: 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 19: 'CPF_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 20: 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', +} +CPF_PERF_SEL_ALWAYS_COUNT = 0 +CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE = 1 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE = 2 +CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS = 3 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING = 4 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1 = 5 +CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2 = 6 +CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE = 7 +CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS = 8 +CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR = 9 +CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR = 10 +CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS = 11 +CPF_PERF_SEL_GRBM_DWORDS_SENT = 12 +CPF_PERF_SEL_DYNAMIC_CLOCK_VALID = 13 +CPF_PERF_SEL_REGISTER_CLOCK_VALID = 14 +CPF_PERF_SEL_MIU_WRITE_REQUEST_SEND = 15 +CPF_PERF_SEL_MIU_READ_REQUEST_SEND = 16 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 17 +CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 18 +CPF_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 19 +CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 20 +CPF_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CPC_PERFCOUNT_SEL' +CPC_PERFCOUNT_SEL__enumvalues = { + 0: 'CPC_PERF_SEL_ALWAYS_COUNT', + 1: 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 2: 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 3: 'CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE', + 4: 'CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE', + 5: 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 6: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 7: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 8: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 9: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_READ', + 10: 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_WRITE', + 11: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 12: 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 13: 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 14: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 15: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 16: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 17: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_READ', + 18: 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_WRITE', + 19: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 20: 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 21: 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 22: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 23: 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', + 24: 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', +} +CPC_PERF_SEL_ALWAYS_COUNT = 0 +CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE = 1 +CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION = 2 +CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE = 3 +CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE = 4 +CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE = 5 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY = 6 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF = 7 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ = 8 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_READ = 9 +CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_WRITE = 10 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ = 11 +CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF = 12 +CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE = 13 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY = 14 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF = 15 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ = 16 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_READ = 17 +CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_WRITE = 18 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ = 19 +CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF = 20 +CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE = 21 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE = 22 +CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS = 23 +CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION = 24 +CPC_PERFCOUNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'CP_ALPHA_TAG_RAM_SEL' +CP_ALPHA_TAG_RAM_SEL__enumvalues = { + 0: 'CPG_TAG_RAM', + 1: 'CPC_TAG_RAM', + 2: 'CPF_TAG_RAM', + 3: 'RSV_TAG_RAM', +} +CPG_TAG_RAM = 0 +CPC_TAG_RAM = 1 +CPF_TAG_RAM = 2 +RSV_TAG_RAM = 3 +CP_ALPHA_TAG_RAM_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SX_BLEND_OPT' +SX_BLEND_OPT__enumvalues = { + 0: 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 1: 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 2: 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 3: 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 4: 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 5: 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 6: 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 7: 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', +} +BLEND_OPT_PRESERVE_NONE_IGNORE_ALL = 0 +BLEND_OPT_PRESERVE_ALL_IGNORE_NONE = 1 +BLEND_OPT_PRESERVE_C1_IGNORE_C0 = 2 +BLEND_OPT_PRESERVE_C0_IGNORE_C1 = 3 +BLEND_OPT_PRESERVE_A1_IGNORE_A0 = 4 +BLEND_OPT_PRESERVE_A0_IGNORE_A1 = 5 +BLEND_OPT_PRESERVE_NONE_IGNORE_A0 = 6 +BLEND_OPT_PRESERVE_NONE_IGNORE_NONE = 7 +SX_BLEND_OPT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_OPT_COMB_FCN' +SX_OPT_COMB_FCN__enumvalues = { + 0: 'OPT_COMB_NONE', + 1: 'OPT_COMB_ADD', + 2: 'OPT_COMB_SUBTRACT', + 3: 'OPT_COMB_MIN', + 4: 'OPT_COMB_MAX', + 5: 'OPT_COMB_REVSUBTRACT', + 6: 'OPT_COMB_BLEND_DISABLED', + 7: 'OPT_COMB_SAFE_ADD', +} +OPT_COMB_NONE = 0 +OPT_COMB_ADD = 1 +OPT_COMB_SUBTRACT = 2 +OPT_COMB_MIN = 3 +OPT_COMB_MAX = 4 +OPT_COMB_REVSUBTRACT = 5 +OPT_COMB_BLEND_DISABLED = 6 +OPT_COMB_SAFE_ADD = 7 +SX_OPT_COMB_FCN = ctypes.c_uint32 # enum + +# values for enumeration 'SX_DOWNCONVERT_FORMAT' +SX_DOWNCONVERT_FORMAT__enumvalues = { + 0: 'SX_RT_EXPORT_NO_CONVERSION', + 1: 'SX_RT_EXPORT_32_R', + 2: 'SX_RT_EXPORT_32_A', + 3: 'SX_RT_EXPORT_10_11_11', + 4: 'SX_RT_EXPORT_2_10_10_10', + 5: 'SX_RT_EXPORT_8_8_8_8', + 6: 'SX_RT_EXPORT_5_6_5', + 7: 'SX_RT_EXPORT_1_5_5_5', + 8: 'SX_RT_EXPORT_4_4_4_4', + 9: 'SX_RT_EXPORT_16_16_GR', + 10: 'SX_RT_EXPORT_16_16_AR', +} +SX_RT_EXPORT_NO_CONVERSION = 0 +SX_RT_EXPORT_32_R = 1 +SX_RT_EXPORT_32_A = 2 +SX_RT_EXPORT_10_11_11 = 3 +SX_RT_EXPORT_2_10_10_10 = 4 +SX_RT_EXPORT_8_8_8_8 = 5 +SX_RT_EXPORT_5_6_5 = 6 +SX_RT_EXPORT_1_5_5_5 = 7 +SX_RT_EXPORT_4_4_4_4 = 8 +SX_RT_EXPORT_16_16_GR = 9 +SX_RT_EXPORT_16_16_AR = 10 +SX_DOWNCONVERT_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'SX_PERFCOUNTER_VALS' +SX_PERFCOUNTER_VALS__enumvalues = { + 0: 'SX_PERF_SEL_PA_IDLE_CYCLES', + 1: 'SX_PERF_SEL_PA_REQ', + 2: 'SX_PERF_SEL_PA_POS', + 3: 'SX_PERF_SEL_CLOCK', + 4: 'SX_PERF_SEL_GATE_EN1', + 5: 'SX_PERF_SEL_GATE_EN2', + 6: 'SX_PERF_SEL_GATE_EN3', + 7: 'SX_PERF_SEL_GATE_EN4', + 8: 'SX_PERF_SEL_SH_POS_STARVE', + 9: 'SX_PERF_SEL_SH_COLOR_STARVE', + 10: 'SX_PERF_SEL_SH_POS_STALL', + 11: 'SX_PERF_SEL_SH_COLOR_STALL', + 12: 'SX_PERF_SEL_DB0_PIXELS', + 13: 'SX_PERF_SEL_DB0_HALF_QUADS', + 14: 'SX_PERF_SEL_DB0_PIXEL_STALL', + 15: 'SX_PERF_SEL_DB0_PIXEL_IDLE', + 16: 'SX_PERF_SEL_DB0_PRED_PIXELS', + 17: 'SX_PERF_SEL_DB1_PIXELS', + 18: 'SX_PERF_SEL_DB1_HALF_QUADS', + 19: 'SX_PERF_SEL_DB1_PIXEL_STALL', + 20: 'SX_PERF_SEL_DB1_PIXEL_IDLE', + 21: 'SX_PERF_SEL_DB1_PRED_PIXELS', + 22: 'SX_PERF_SEL_DB2_PIXELS', + 23: 'SX_PERF_SEL_DB2_HALF_QUADS', + 24: 'SX_PERF_SEL_DB2_PIXEL_STALL', + 25: 'SX_PERF_SEL_DB2_PIXEL_IDLE', + 26: 'SX_PERF_SEL_DB2_PRED_PIXELS', + 27: 'SX_PERF_SEL_DB3_PIXELS', + 28: 'SX_PERF_SEL_DB3_HALF_QUADS', + 29: 'SX_PERF_SEL_DB3_PIXEL_STALL', + 30: 'SX_PERF_SEL_DB3_PIXEL_IDLE', + 31: 'SX_PERF_SEL_DB3_PRED_PIXELS', + 32: 'SX_PERF_SEL_COL_BUSY', + 33: 'SX_PERF_SEL_POS_BUSY', + 34: 'SX_PERF_SEL_DB0_A2M_DISCARD_QUADS', + 35: 'SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS', + 36: 'SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST', + 37: 'SX_PERF_SEL_DB0_MRT0_DISCARD_SRC', + 38: 'SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS', + 39: 'SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS', + 40: 'SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS', + 41: 'SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST', + 42: 'SX_PERF_SEL_DB0_MRT1_DISCARD_SRC', + 43: 'SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS', + 44: 'SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS', + 45: 'SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS', + 46: 'SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST', + 47: 'SX_PERF_SEL_DB0_MRT2_DISCARD_SRC', + 48: 'SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS', + 49: 'SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS', + 50: 'SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS', + 51: 'SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST', + 52: 'SX_PERF_SEL_DB0_MRT3_DISCARD_SRC', + 53: 'SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS', + 54: 'SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS', + 55: 'SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS', + 56: 'SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST', + 57: 'SX_PERF_SEL_DB0_MRT4_DISCARD_SRC', + 58: 'SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS', + 59: 'SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS', + 60: 'SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS', + 61: 'SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST', + 62: 'SX_PERF_SEL_DB0_MRT5_DISCARD_SRC', + 63: 'SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS', + 64: 'SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS', + 65: 'SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS', + 66: 'SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST', + 67: 'SX_PERF_SEL_DB0_MRT6_DISCARD_SRC', + 68: 'SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS', + 69: 'SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS', + 70: 'SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS', + 71: 'SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST', + 72: 'SX_PERF_SEL_DB0_MRT7_DISCARD_SRC', + 73: 'SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS', + 74: 'SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS', + 75: 'SX_PERF_SEL_DB1_A2M_DISCARD_QUADS', + 76: 'SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS', + 77: 'SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST', + 78: 'SX_PERF_SEL_DB1_MRT0_DISCARD_SRC', + 79: 'SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS', + 80: 'SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS', + 81: 'SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS', + 82: 'SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST', + 83: 'SX_PERF_SEL_DB1_MRT1_DISCARD_SRC', + 84: 'SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS', + 85: 'SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS', + 86: 'SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS', + 87: 'SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST', + 88: 'SX_PERF_SEL_DB1_MRT2_DISCARD_SRC', + 89: 'SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS', + 90: 'SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS', + 91: 'SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS', + 92: 'SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST', + 93: 'SX_PERF_SEL_DB1_MRT3_DISCARD_SRC', + 94: 'SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS', + 95: 'SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS', + 96: 'SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS', + 97: 'SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST', + 98: 'SX_PERF_SEL_DB1_MRT4_DISCARD_SRC', + 99: 'SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS', + 100: 'SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS', + 101: 'SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS', + 102: 'SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST', + 103: 'SX_PERF_SEL_DB1_MRT5_DISCARD_SRC', + 104: 'SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS', + 105: 'SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS', + 106: 'SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS', + 107: 'SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST', + 108: 'SX_PERF_SEL_DB1_MRT6_DISCARD_SRC', + 109: 'SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS', + 110: 'SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS', + 111: 'SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS', + 112: 'SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST', + 113: 'SX_PERF_SEL_DB1_MRT7_DISCARD_SRC', + 114: 'SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS', + 115: 'SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS', + 116: 'SX_PERF_SEL_DB2_A2M_DISCARD_QUADS', + 117: 'SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS', + 118: 'SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST', + 119: 'SX_PERF_SEL_DB2_MRT0_DISCARD_SRC', + 120: 'SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS', + 121: 'SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS', + 122: 'SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS', + 123: 'SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST', + 124: 'SX_PERF_SEL_DB2_MRT1_DISCARD_SRC', + 125: 'SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS', + 126: 'SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS', + 127: 'SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS', + 128: 'SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST', + 129: 'SX_PERF_SEL_DB2_MRT2_DISCARD_SRC', + 130: 'SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS', + 131: 'SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS', + 132: 'SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS', + 133: 'SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST', + 134: 'SX_PERF_SEL_DB2_MRT3_DISCARD_SRC', + 135: 'SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS', + 136: 'SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS', + 137: 'SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS', + 138: 'SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST', + 139: 'SX_PERF_SEL_DB2_MRT4_DISCARD_SRC', + 140: 'SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS', + 141: 'SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS', + 142: 'SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS', + 143: 'SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST', + 144: 'SX_PERF_SEL_DB2_MRT5_DISCARD_SRC', + 145: 'SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS', + 146: 'SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS', + 147: 'SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS', + 148: 'SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST', + 149: 'SX_PERF_SEL_DB2_MRT6_DISCARD_SRC', + 150: 'SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS', + 151: 'SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS', + 152: 'SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS', + 153: 'SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST', + 154: 'SX_PERF_SEL_DB2_MRT7_DISCARD_SRC', + 155: 'SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS', + 156: 'SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS', + 157: 'SX_PERF_SEL_DB3_A2M_DISCARD_QUADS', + 158: 'SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS', + 159: 'SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST', + 160: 'SX_PERF_SEL_DB3_MRT0_DISCARD_SRC', + 161: 'SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS', + 162: 'SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS', + 163: 'SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS', + 164: 'SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST', + 165: 'SX_PERF_SEL_DB3_MRT1_DISCARD_SRC', + 166: 'SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS', + 167: 'SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS', + 168: 'SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS', + 169: 'SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST', + 170: 'SX_PERF_SEL_DB3_MRT2_DISCARD_SRC', + 171: 'SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS', + 172: 'SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS', + 173: 'SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS', + 174: 'SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST', + 175: 'SX_PERF_SEL_DB3_MRT3_DISCARD_SRC', + 176: 'SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS', + 177: 'SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS', + 178: 'SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS', + 179: 'SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST', + 180: 'SX_PERF_SEL_DB3_MRT4_DISCARD_SRC', + 181: 'SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS', + 182: 'SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS', + 183: 'SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS', + 184: 'SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST', + 185: 'SX_PERF_SEL_DB3_MRT5_DISCARD_SRC', + 186: 'SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS', + 187: 'SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS', + 188: 'SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS', + 189: 'SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST', + 190: 'SX_PERF_SEL_DB3_MRT6_DISCARD_SRC', + 191: 'SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS', + 192: 'SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS', + 193: 'SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS', + 194: 'SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST', + 195: 'SX_PERF_SEL_DB3_MRT7_DISCARD_SRC', + 196: 'SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS', + 197: 'SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS', +} +SX_PERF_SEL_PA_IDLE_CYCLES = 0 +SX_PERF_SEL_PA_REQ = 1 +SX_PERF_SEL_PA_POS = 2 +SX_PERF_SEL_CLOCK = 3 +SX_PERF_SEL_GATE_EN1 = 4 +SX_PERF_SEL_GATE_EN2 = 5 +SX_PERF_SEL_GATE_EN3 = 6 +SX_PERF_SEL_GATE_EN4 = 7 +SX_PERF_SEL_SH_POS_STARVE = 8 +SX_PERF_SEL_SH_COLOR_STARVE = 9 +SX_PERF_SEL_SH_POS_STALL = 10 +SX_PERF_SEL_SH_COLOR_STALL = 11 +SX_PERF_SEL_DB0_PIXELS = 12 +SX_PERF_SEL_DB0_HALF_QUADS = 13 +SX_PERF_SEL_DB0_PIXEL_STALL = 14 +SX_PERF_SEL_DB0_PIXEL_IDLE = 15 +SX_PERF_SEL_DB0_PRED_PIXELS = 16 +SX_PERF_SEL_DB1_PIXELS = 17 +SX_PERF_SEL_DB1_HALF_QUADS = 18 +SX_PERF_SEL_DB1_PIXEL_STALL = 19 +SX_PERF_SEL_DB1_PIXEL_IDLE = 20 +SX_PERF_SEL_DB1_PRED_PIXELS = 21 +SX_PERF_SEL_DB2_PIXELS = 22 +SX_PERF_SEL_DB2_HALF_QUADS = 23 +SX_PERF_SEL_DB2_PIXEL_STALL = 24 +SX_PERF_SEL_DB2_PIXEL_IDLE = 25 +SX_PERF_SEL_DB2_PRED_PIXELS = 26 +SX_PERF_SEL_DB3_PIXELS = 27 +SX_PERF_SEL_DB3_HALF_QUADS = 28 +SX_PERF_SEL_DB3_PIXEL_STALL = 29 +SX_PERF_SEL_DB3_PIXEL_IDLE = 30 +SX_PERF_SEL_DB3_PRED_PIXELS = 31 +SX_PERF_SEL_COL_BUSY = 32 +SX_PERF_SEL_POS_BUSY = 33 +SX_PERF_SEL_DB0_A2M_DISCARD_QUADS = 34 +SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS = 35 +SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST = 36 +SX_PERF_SEL_DB0_MRT0_DISCARD_SRC = 37 +SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS = 38 +SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS = 39 +SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS = 40 +SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST = 41 +SX_PERF_SEL_DB0_MRT1_DISCARD_SRC = 42 +SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS = 43 +SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS = 44 +SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS = 45 +SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST = 46 +SX_PERF_SEL_DB0_MRT2_DISCARD_SRC = 47 +SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS = 48 +SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS = 49 +SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS = 50 +SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST = 51 +SX_PERF_SEL_DB0_MRT3_DISCARD_SRC = 52 +SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS = 53 +SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS = 54 +SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS = 55 +SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST = 56 +SX_PERF_SEL_DB0_MRT4_DISCARD_SRC = 57 +SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS = 58 +SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS = 59 +SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS = 60 +SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST = 61 +SX_PERF_SEL_DB0_MRT5_DISCARD_SRC = 62 +SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS = 63 +SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS = 64 +SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS = 65 +SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST = 66 +SX_PERF_SEL_DB0_MRT6_DISCARD_SRC = 67 +SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS = 68 +SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS = 69 +SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS = 70 +SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST = 71 +SX_PERF_SEL_DB0_MRT7_DISCARD_SRC = 72 +SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS = 73 +SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS = 74 +SX_PERF_SEL_DB1_A2M_DISCARD_QUADS = 75 +SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS = 76 +SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST = 77 +SX_PERF_SEL_DB1_MRT0_DISCARD_SRC = 78 +SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS = 79 +SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS = 80 +SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS = 81 +SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST = 82 +SX_PERF_SEL_DB1_MRT1_DISCARD_SRC = 83 +SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS = 84 +SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS = 85 +SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS = 86 +SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST = 87 +SX_PERF_SEL_DB1_MRT2_DISCARD_SRC = 88 +SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS = 89 +SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS = 90 +SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS = 91 +SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST = 92 +SX_PERF_SEL_DB1_MRT3_DISCARD_SRC = 93 +SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS = 94 +SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS = 95 +SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS = 96 +SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST = 97 +SX_PERF_SEL_DB1_MRT4_DISCARD_SRC = 98 +SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS = 99 +SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS = 100 +SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS = 101 +SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST = 102 +SX_PERF_SEL_DB1_MRT5_DISCARD_SRC = 103 +SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS = 104 +SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS = 105 +SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS = 106 +SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST = 107 +SX_PERF_SEL_DB1_MRT6_DISCARD_SRC = 108 +SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS = 109 +SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS = 110 +SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS = 111 +SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST = 112 +SX_PERF_SEL_DB1_MRT7_DISCARD_SRC = 113 +SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS = 114 +SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS = 115 +SX_PERF_SEL_DB2_A2M_DISCARD_QUADS = 116 +SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS = 117 +SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST = 118 +SX_PERF_SEL_DB2_MRT0_DISCARD_SRC = 119 +SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS = 120 +SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS = 121 +SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS = 122 +SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST = 123 +SX_PERF_SEL_DB2_MRT1_DISCARD_SRC = 124 +SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS = 125 +SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS = 126 +SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS = 127 +SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST = 128 +SX_PERF_SEL_DB2_MRT2_DISCARD_SRC = 129 +SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS = 130 +SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS = 131 +SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS = 132 +SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST = 133 +SX_PERF_SEL_DB2_MRT3_DISCARD_SRC = 134 +SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS = 135 +SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS = 136 +SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS = 137 +SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST = 138 +SX_PERF_SEL_DB2_MRT4_DISCARD_SRC = 139 +SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS = 140 +SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS = 141 +SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS = 142 +SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST = 143 +SX_PERF_SEL_DB2_MRT5_DISCARD_SRC = 144 +SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS = 145 +SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS = 146 +SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS = 147 +SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST = 148 +SX_PERF_SEL_DB2_MRT6_DISCARD_SRC = 149 +SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS = 150 +SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS = 151 +SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS = 152 +SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST = 153 +SX_PERF_SEL_DB2_MRT7_DISCARD_SRC = 154 +SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS = 155 +SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS = 156 +SX_PERF_SEL_DB3_A2M_DISCARD_QUADS = 157 +SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS = 158 +SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST = 159 +SX_PERF_SEL_DB3_MRT0_DISCARD_SRC = 160 +SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS = 161 +SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS = 162 +SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS = 163 +SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST = 164 +SX_PERF_SEL_DB3_MRT1_DISCARD_SRC = 165 +SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS = 166 +SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS = 167 +SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS = 168 +SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST = 169 +SX_PERF_SEL_DB3_MRT2_DISCARD_SRC = 170 +SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS = 171 +SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS = 172 +SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS = 173 +SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST = 174 +SX_PERF_SEL_DB3_MRT3_DISCARD_SRC = 175 +SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS = 176 +SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS = 177 +SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS = 178 +SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST = 179 +SX_PERF_SEL_DB3_MRT4_DISCARD_SRC = 180 +SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS = 181 +SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS = 182 +SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS = 183 +SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST = 184 +SX_PERF_SEL_DB3_MRT5_DISCARD_SRC = 185 +SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS = 186 +SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS = 187 +SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS = 188 +SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST = 189 +SX_PERF_SEL_DB3_MRT6_DISCARD_SRC = 190 +SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS = 191 +SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS = 192 +SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS = 193 +SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST = 194 +SX_PERF_SEL_DB3_MRT7_DISCARD_SRC = 195 +SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS = 196 +SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS = 197 +SX_PERFCOUNTER_VALS = ctypes.c_uint32 # enum + +# values for enumeration 'ForceControl' +ForceControl__enumvalues = { + 0: 'FORCE_OFF', + 1: 'FORCE_ENABLE', + 2: 'FORCE_DISABLE', + 3: 'FORCE_RESERVED', +} +FORCE_OFF = 0 +FORCE_ENABLE = 1 +FORCE_DISABLE = 2 +FORCE_RESERVED = 3 +ForceControl = ctypes.c_uint32 # enum + +# values for enumeration 'ZSamplePosition' +ZSamplePosition__enumvalues = { + 0: 'Z_SAMPLE_CENTER', + 1: 'Z_SAMPLE_CENTROID', +} +Z_SAMPLE_CENTER = 0 +Z_SAMPLE_CENTROID = 1 +ZSamplePosition = ctypes.c_uint32 # enum + +# values for enumeration 'ZOrder' +ZOrder__enumvalues = { + 0: 'LATE_Z', + 1: 'EARLY_Z_THEN_LATE_Z', + 2: 'RE_Z', + 3: 'EARLY_Z_THEN_RE_Z', +} +LATE_Z = 0 +EARLY_Z_THEN_LATE_Z = 1 +RE_Z = 2 +EARLY_Z_THEN_RE_Z = 3 +ZOrder = ctypes.c_uint32 # enum + +# values for enumeration 'ZpassControl' +ZpassControl__enumvalues = { + 0: 'ZPASS_DISABLE', + 1: 'ZPASS_SAMPLES', + 2: 'ZPASS_PIXELS', +} +ZPASS_DISABLE = 0 +ZPASS_SAMPLES = 1 +ZPASS_PIXELS = 2 +ZpassControl = ctypes.c_uint32 # enum + +# values for enumeration 'ZModeForce' +ZModeForce__enumvalues = { + 0: 'NO_FORCE', + 1: 'FORCE_EARLY_Z', + 2: 'FORCE_LATE_Z', + 3: 'FORCE_RE_Z', +} +NO_FORCE = 0 +FORCE_EARLY_Z = 1 +FORCE_LATE_Z = 2 +FORCE_RE_Z = 3 +ZModeForce = ctypes.c_uint32 # enum + +# values for enumeration 'ZLimitSumm' +ZLimitSumm__enumvalues = { + 0: 'FORCE_SUMM_OFF', + 1: 'FORCE_SUMM_MINZ', + 2: 'FORCE_SUMM_MAXZ', + 3: 'FORCE_SUMM_BOTH', +} +FORCE_SUMM_OFF = 0 +FORCE_SUMM_MINZ = 1 +FORCE_SUMM_MAXZ = 2 +FORCE_SUMM_BOTH = 3 +ZLimitSumm = ctypes.c_uint32 # enum + +# values for enumeration 'CompareFrag' +CompareFrag__enumvalues = { + 0: 'FRAG_NEVER', + 1: 'FRAG_LESS', + 2: 'FRAG_EQUAL', + 3: 'FRAG_LEQUAL', + 4: 'FRAG_GREATER', + 5: 'FRAG_NOTEQUAL', + 6: 'FRAG_GEQUAL', + 7: 'FRAG_ALWAYS', +} +FRAG_NEVER = 0 +FRAG_LESS = 1 +FRAG_EQUAL = 2 +FRAG_LEQUAL = 3 +FRAG_GREATER = 4 +FRAG_NOTEQUAL = 5 +FRAG_GEQUAL = 6 +FRAG_ALWAYS = 7 +CompareFrag = ctypes.c_uint32 # enum + +# values for enumeration 'StencilOp' +StencilOp__enumvalues = { + 0: 'STENCIL_KEEP', + 1: 'STENCIL_ZERO', + 2: 'STENCIL_ONES', + 3: 'STENCIL_REPLACE_TEST', + 4: 'STENCIL_REPLACE_OP', + 5: 'STENCIL_ADD_CLAMP', + 6: 'STENCIL_SUB_CLAMP', + 7: 'STENCIL_INVERT', + 8: 'STENCIL_ADD_WRAP', + 9: 'STENCIL_SUB_WRAP', + 10: 'STENCIL_AND', + 11: 'STENCIL_OR', + 12: 'STENCIL_XOR', + 13: 'STENCIL_NAND', + 14: 'STENCIL_NOR', + 15: 'STENCIL_XNOR', +} +STENCIL_KEEP = 0 +STENCIL_ZERO = 1 +STENCIL_ONES = 2 +STENCIL_REPLACE_TEST = 3 +STENCIL_REPLACE_OP = 4 +STENCIL_ADD_CLAMP = 5 +STENCIL_SUB_CLAMP = 6 +STENCIL_INVERT = 7 +STENCIL_ADD_WRAP = 8 +STENCIL_SUB_WRAP = 9 +STENCIL_AND = 10 +STENCIL_OR = 11 +STENCIL_XOR = 12 +STENCIL_NAND = 13 +STENCIL_NOR = 14 +STENCIL_XNOR = 15 +StencilOp = ctypes.c_uint32 # enum + +# values for enumeration 'ConservativeZExport' +ConservativeZExport__enumvalues = { + 0: 'EXPORT_ANY_Z', + 1: 'EXPORT_LESS_THAN_Z', + 2: 'EXPORT_GREATER_THAN_Z', + 3: 'EXPORT_RESERVED', +} +EXPORT_ANY_Z = 0 +EXPORT_LESS_THAN_Z = 1 +EXPORT_GREATER_THAN_Z = 2 +EXPORT_RESERVED = 3 +ConservativeZExport = ctypes.c_uint32 # enum + +# values for enumeration 'DbPSLControl' +DbPSLControl__enumvalues = { + 0: 'PSLC_AUTO', + 1: 'PSLC_ON_HANG_ONLY', + 2: 'PSLC_ASAP', + 3: 'PSLC_COUNTDOWN', +} +PSLC_AUTO = 0 +PSLC_ON_HANG_ONLY = 1 +PSLC_ASAP = 2 +PSLC_COUNTDOWN = 3 +DbPSLControl = ctypes.c_uint32 # enum + +# values for enumeration 'DbPRTFaultBehavior' +DbPRTFaultBehavior__enumvalues = { + 0: 'FAULT_ZERO', + 1: 'FAULT_ONE', + 2: 'FAULT_FAIL', + 3: 'FAULT_PASS', +} +FAULT_ZERO = 0 +FAULT_ONE = 1 +FAULT_FAIL = 2 +FAULT_PASS = 3 +DbPRTFaultBehavior = ctypes.c_uint32 # enum + +# values for enumeration 'PerfCounter_Vals' +PerfCounter_Vals__enumvalues = { + 0: 'DB_PERF_SEL_SC_DB_tile_sends', + 1: 'DB_PERF_SEL_SC_DB_tile_busy', + 2: 'DB_PERF_SEL_SC_DB_tile_stalls', + 3: 'DB_PERF_SEL_SC_DB_tile_events', + 4: 'DB_PERF_SEL_SC_DB_tile_tiles', + 5: 'DB_PERF_SEL_SC_DB_tile_covered', + 6: 'DB_PERF_SEL_hiz_tc_read_starved', + 7: 'DB_PERF_SEL_hiz_tc_write_stall', + 8: 'DB_PERF_SEL_hiz_qtiles_culled', + 9: 'DB_PERF_SEL_his_qtiles_culled', + 10: 'DB_PERF_SEL_DB_SC_tile_sends', + 11: 'DB_PERF_SEL_DB_SC_tile_busy', + 12: 'DB_PERF_SEL_DB_SC_tile_stalls', + 13: 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 14: 'DB_PERF_SEL_DB_SC_tile_tiles', + 15: 'DB_PERF_SEL_DB_SC_tile_culled', + 16: 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 17: 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 18: 'DB_PERF_SEL_DB_SC_tile_no_ops', + 19: 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 20: 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 21: 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 22: 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 23: 'DB_PERF_SEL_SC_DB_quad_sends', + 24: 'DB_PERF_SEL_SC_DB_quad_busy', + 25: 'DB_PERF_SEL_SC_DB_quad_squads', + 26: 'DB_PERF_SEL_SC_DB_quad_tiles', + 27: 'DB_PERF_SEL_SC_DB_quad_pixels', + 28: 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 29: 'DB_PERF_SEL_DB_SC_quad_sends', + 30: 'DB_PERF_SEL_DB_SC_quad_busy', + 31: 'DB_PERF_SEL_DB_SC_quad_stalls', + 32: 'DB_PERF_SEL_DB_SC_quad_tiles', + 33: 'DB_PERF_SEL_DB_SC_quad_lit_quad', + 34: 'DB_PERF_SEL_DB_CB_tile_sends', + 35: 'DB_PERF_SEL_DB_CB_tile_busy', + 36: 'DB_PERF_SEL_DB_CB_tile_stalls', + 37: 'DB_PERF_SEL_SX_DB_quad_sends', + 38: 'DB_PERF_SEL_SX_DB_quad_busy', + 39: 'DB_PERF_SEL_SX_DB_quad_stalls', + 40: 'DB_PERF_SEL_SX_DB_quad_quads', + 41: 'DB_PERF_SEL_SX_DB_quad_pixels', + 42: 'DB_PERF_SEL_SX_DB_quad_exports', + 43: 'DB_PERF_SEL_SH_quads_outstanding_sum', + 44: 'DB_PERF_SEL_DB_CB_lquad_sends', + 45: 'DB_PERF_SEL_DB_CB_lquad_busy', + 46: 'DB_PERF_SEL_DB_CB_lquad_stalls', + 47: 'DB_PERF_SEL_DB_CB_lquad_quads', + 48: 'DB_PERF_SEL_tile_rd_sends', + 49: 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 50: 'DB_PERF_SEL_quad_rd_sends', + 51: 'DB_PERF_SEL_quad_rd_busy', + 52: 'DB_PERF_SEL_quad_rd_mi_stall', + 53: 'DB_PERF_SEL_quad_rd_rw_collision', + 54: 'DB_PERF_SEL_quad_rd_tag_stall', + 55: 'DB_PERF_SEL_quad_rd_32byte_reqs', + 56: 'DB_PERF_SEL_quad_rd_panic', + 57: 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 58: 'DB_PERF_SEL_quad_rdret_sends', + 59: 'DB_PERF_SEL_quad_rdret_busy', + 60: 'DB_PERF_SEL_tile_wr_sends', + 61: 'DB_PERF_SEL_tile_wr_acks', + 62: 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 63: 'DB_PERF_SEL_quad_wr_sends', + 64: 'DB_PERF_SEL_quad_wr_busy', + 65: 'DB_PERF_SEL_quad_wr_mi_stall', + 66: 'DB_PERF_SEL_quad_wr_coherency_stall', + 67: 'DB_PERF_SEL_quad_wr_acks', + 68: 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 69: 'DB_PERF_SEL_Tile_Cache_misses', + 70: 'DB_PERF_SEL_Tile_Cache_hits', + 71: 'DB_PERF_SEL_Tile_Cache_flushes', + 72: 'DB_PERF_SEL_Tile_Cache_surface_stall', + 73: 'DB_PERF_SEL_Tile_Cache_starves', + 74: 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 75: 'DB_PERF_SEL_tcp_dispatcher_reads', + 76: 'DB_PERF_SEL_tcp_prefetcher_reads', + 77: 'DB_PERF_SEL_tcp_preloader_reads', + 78: 'DB_PERF_SEL_tcp_dispatcher_flushes', + 79: 'DB_PERF_SEL_tcp_prefetcher_flushes', + 80: 'DB_PERF_SEL_tcp_preloader_flushes', + 81: 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 82: 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 83: 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 84: 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 85: 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 86: 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 87: 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 88: 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 89: 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 90: 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 91: 'DB_PERF_SEL_Depth_Tile_Cache_event', + 92: 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 93: 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 94: 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 95: 'DB_PERF_SEL_Stencil_Cache_misses', + 96: 'DB_PERF_SEL_Stencil_Cache_hits', + 97: 'DB_PERF_SEL_Stencil_Cache_flushes', + 98: 'DB_PERF_SEL_Stencil_Cache_starves', + 99: 'DB_PERF_SEL_Stencil_Cache_frees', + 100: 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 101: 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 102: 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 103: 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 104: 'DB_PERF_SEL_Z_Cache_pmask_misses', + 105: 'DB_PERF_SEL_Z_Cache_pmask_hits', + 106: 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 107: 'DB_PERF_SEL_Z_Cache_pmask_starves', + 108: 'DB_PERF_SEL_Z_Cache_frees', + 109: 'DB_PERF_SEL_Plane_Cache_misses', + 110: 'DB_PERF_SEL_Plane_Cache_hits', + 111: 'DB_PERF_SEL_Plane_Cache_flushes', + 112: 'DB_PERF_SEL_Plane_Cache_starves', + 113: 'DB_PERF_SEL_Plane_Cache_frees', + 114: 'DB_PERF_SEL_flush_expanded_stencil', + 115: 'DB_PERF_SEL_flush_compressed_stencil', + 116: 'DB_PERF_SEL_flush_single_stencil', + 117: 'DB_PERF_SEL_planes_flushed', + 118: 'DB_PERF_SEL_flush_1plane', + 119: 'DB_PERF_SEL_flush_2plane', + 120: 'DB_PERF_SEL_flush_3plane', + 121: 'DB_PERF_SEL_flush_4plane', + 122: 'DB_PERF_SEL_flush_5plane', + 123: 'DB_PERF_SEL_flush_6plane', + 124: 'DB_PERF_SEL_flush_7plane', + 125: 'DB_PERF_SEL_flush_8plane', + 126: 'DB_PERF_SEL_flush_9plane', + 127: 'DB_PERF_SEL_flush_10plane', + 128: 'DB_PERF_SEL_flush_11plane', + 129: 'DB_PERF_SEL_flush_12plane', + 130: 'DB_PERF_SEL_flush_13plane', + 131: 'DB_PERF_SEL_flush_14plane', + 132: 'DB_PERF_SEL_flush_15plane', + 133: 'DB_PERF_SEL_flush_16plane', + 134: 'DB_PERF_SEL_flush_expanded_z', + 135: 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 136: 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 137: 'DB_PERF_SEL_dk_tile_sends', + 138: 'DB_PERF_SEL_dk_tile_busy', + 139: 'DB_PERF_SEL_dk_tile_quad_starves', + 140: 'DB_PERF_SEL_dk_tile_stalls', + 141: 'DB_PERF_SEL_dk_squad_sends', + 142: 'DB_PERF_SEL_dk_squad_busy', + 143: 'DB_PERF_SEL_dk_squad_stalls', + 144: 'DB_PERF_SEL_Op_Pipe_Busy', + 145: 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 146: 'DB_PERF_SEL_qc_busy', + 147: 'DB_PERF_SEL_qc_xfc', + 148: 'DB_PERF_SEL_qc_conflicts', + 149: 'DB_PERF_SEL_qc_full_stall', + 150: 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', + 151: 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 152: 'DB_PERF_SEL_tsc_insert_summarize_stall', + 153: 'DB_PERF_SEL_tl_busy', + 154: 'DB_PERF_SEL_tl_dtc_read_starved', + 155: 'DB_PERF_SEL_tl_z_fetch_stall', + 156: 'DB_PERF_SEL_tl_stencil_stall', + 157: 'DB_PERF_SEL_tl_z_decompress_stall', + 158: 'DB_PERF_SEL_tl_stencil_locked_stall', + 159: 'DB_PERF_SEL_tl_events', + 160: 'DB_PERF_SEL_tl_summarize_squads', + 161: 'DB_PERF_SEL_tl_flush_expand_squads', + 162: 'DB_PERF_SEL_tl_expand_squads', + 163: 'DB_PERF_SEL_tl_preZ_squads', + 164: 'DB_PERF_SEL_tl_postZ_squads', + 165: 'DB_PERF_SEL_tl_preZ_noop_squads', + 166: 'DB_PERF_SEL_tl_postZ_noop_squads', + 167: 'DB_PERF_SEL_tl_tile_ops', + 168: 'DB_PERF_SEL_tl_in_xfc', + 169: 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 170: 'DB_PERF_SEL_tl_in_fast_z_stall', + 171: 'DB_PERF_SEL_tl_out_xfc', + 172: 'DB_PERF_SEL_tl_out_squads', + 173: 'DB_PERF_SEL_zf_plane_multicycle', + 174: 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 175: 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 176: 'DB_PERF_SEL_PostZ_Samples_failing_S', + 177: 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 178: 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 179: 'DB_PERF_SEL_PreZ_Samples_failing_S', + 180: 'DB_PERF_SEL_ts_tc_update_stall', + 181: 'DB_PERF_SEL_sc_kick_start', + 182: 'DB_PERF_SEL_sc_kick_end', + 183: 'DB_PERF_SEL_clock_reg_active', + 184: 'DB_PERF_SEL_clock_main_active', + 185: 'DB_PERF_SEL_clock_mem_export_active', + 186: 'DB_PERF_SEL_esr_ps_out_busy', + 187: 'DB_PERF_SEL_esr_ps_lqf_busy', + 188: 'DB_PERF_SEL_esr_ps_lqf_stall', + 189: 'DB_PERF_SEL_etr_out_send', + 190: 'DB_PERF_SEL_etr_out_busy', + 191: 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 192: 'DB_PERF_SEL_etr_out_cb_tile_stall', + 193: 'DB_PERF_SEL_etr_out_esr_stall', + 194: 'DB_PERF_SEL_esr_ps_sqq_busy', + 195: 'DB_PERF_SEL_esr_ps_sqq_stall', + 196: 'DB_PERF_SEL_esr_eot_fwd_busy', + 197: 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 198: 'DB_PERF_SEL_esr_eot_fwd_forward', + 199: 'DB_PERF_SEL_esr_sqq_zi_busy', + 200: 'DB_PERF_SEL_esr_sqq_zi_stall', + 201: 'DB_PERF_SEL_postzl_sq_pt_busy', + 202: 'DB_PERF_SEL_postzl_sq_pt_stall', + 203: 'DB_PERF_SEL_postzl_se_busy', + 204: 'DB_PERF_SEL_postzl_se_stall', + 205: 'DB_PERF_SEL_postzl_partial_launch', + 206: 'DB_PERF_SEL_postzl_full_launch', + 207: 'DB_PERF_SEL_postzl_partial_waiting', + 208: 'DB_PERF_SEL_postzl_tile_mem_stall', + 209: 'DB_PERF_SEL_postzl_tile_init_stall', + 210: 'DB_PEFF_SEL_prezl_tile_mem_stall', + 211: 'DB_PERF_SEL_prezl_tile_init_stall', + 212: 'DB_PERF_SEL_dtt_sm_clash_stall', + 213: 'DB_PERF_SEL_dtt_sm_slot_stall', + 214: 'DB_PERF_SEL_dtt_sm_miss_stall', + 215: 'DB_PERF_SEL_mi_rdreq_busy', + 216: 'DB_PERF_SEL_mi_rdreq_stall', + 217: 'DB_PERF_SEL_mi_wrreq_busy', + 218: 'DB_PERF_SEL_mi_wrreq_stall', + 219: 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 220: 'DB_PERF_SEL_dkg_tile_rate_tile', + 221: 'DB_PERF_SEL_prezl_src_in_sends', + 222: 'DB_PERF_SEL_prezl_src_in_stall', + 223: 'DB_PERF_SEL_prezl_src_in_squads', + 224: 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 225: 'DB_PERF_SEL_prezl_src_in_tile_rate', + 226: 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 227: 'DB_PERF_SEL_prezl_src_out_stall', + 228: 'DB_PERF_SEL_postzl_src_in_sends', + 229: 'DB_PERF_SEL_postzl_src_in_stall', + 230: 'DB_PERF_SEL_postzl_src_in_squads', + 231: 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 232: 'DB_PERF_SEL_postzl_src_in_tile_rate', + 233: 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 234: 'DB_PERF_SEL_postzl_src_out_stall', + 235: 'DB_PERF_SEL_esr_ps_src_in_sends', + 236: 'DB_PERF_SEL_esr_ps_src_in_stall', + 237: 'DB_PERF_SEL_esr_ps_src_in_squads', + 238: 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 239: 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 240: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 241: 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 242: 'DB_PERF_SEL_esr_ps_src_out_stall', + 243: 'DB_PERF_SEL_depth_bounds_qtiles_culled', + 244: 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 245: 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 246: 'DB_PERF_SEL_flush_compressed', + 247: 'DB_PERF_SEL_flush_plane_le4', + 248: 'DB_PERF_SEL_tiles_z_fully_summarized', + 249: 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 250: 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 251: 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 252: 'DB_PERF_SEL_tiles_decomp_on_expclear', + 253: 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 254: 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 255: 'DB_PERF_SEL_Op_Pipe_Postz_Busy', + 256: 'DB_PERF_SEL_di_dt_stall', + 257: 'DB_PERF_SEL_DB_SC_quad_double_quad', + 258: 'DB_PERF_SEL_SX_DB_quad_export_quads', + 259: 'DB_PERF_SEL_SX_DB_quad_double_format', + 260: 'DB_PERF_SEL_SX_DB_quad_fast_format', + 261: 'DB_PERF_SEL_SX_DB_quad_slow_format', + 262: 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 263: 'DB_PERF_SEL_DB_CB_lquad_double_format', + 264: 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 265: 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 266: 'DB_PERF_SEL_CB_DB_rdreq_sends', + 267: 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 268: 'DB_PERF_SEL_CB_DB_wrreq_sends', + 269: 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 270: 'DB_PERF_SEL_DB_CB_rdret_ack', + 271: 'DB_PERF_SEL_DB_CB_rdret_nack', + 272: 'DB_PERF_SEL_DB_CB_wrret_ack', + 273: 'DB_PERF_SEL_DB_CB_wrret_nack', + 274: 'DB_PERF_SEL_DFSM_squads_in', + 275: 'DB_PERF_SEL_DFSM_full_cleared_squads_out', + 276: 'DB_PERF_SEL_DFSM_quads_in', + 277: 'DB_PERF_SEL_DFSM_fully_cleared_quads_out', + 278: 'DB_PERF_SEL_DFSM_lit_pixels_in', + 279: 'DB_PERF_SEL_DFSM_fully_cleared_pixels_out', + 280: 'DB_PERF_SEL_DFSM_lit_samples_in', + 281: 'DB_PERF_SEL_DFSM_lit_samples_out', + 282: 'DB_PERF_SEL_DFSM_cycles_above_watermark', + 283: 'DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream', + 284: 'DB_PERF_SEL_DFSM_stalled_by_downstream', + 285: 'DB_PERF_SEL_DFSM_evicted_squads_above_watermark', + 286: 'DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow', + 287: 'DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO', + 288: 'DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark', +} +DB_PERF_SEL_SC_DB_tile_sends = 0 +DB_PERF_SEL_SC_DB_tile_busy = 1 +DB_PERF_SEL_SC_DB_tile_stalls = 2 +DB_PERF_SEL_SC_DB_tile_events = 3 +DB_PERF_SEL_SC_DB_tile_tiles = 4 +DB_PERF_SEL_SC_DB_tile_covered = 5 +DB_PERF_SEL_hiz_tc_read_starved = 6 +DB_PERF_SEL_hiz_tc_write_stall = 7 +DB_PERF_SEL_hiz_qtiles_culled = 8 +DB_PERF_SEL_his_qtiles_culled = 9 +DB_PERF_SEL_DB_SC_tile_sends = 10 +DB_PERF_SEL_DB_SC_tile_busy = 11 +DB_PERF_SEL_DB_SC_tile_stalls = 12 +DB_PERF_SEL_DB_SC_tile_df_stalls = 13 +DB_PERF_SEL_DB_SC_tile_tiles = 14 +DB_PERF_SEL_DB_SC_tile_culled = 15 +DB_PERF_SEL_DB_SC_tile_hier_kill = 16 +DB_PERF_SEL_DB_SC_tile_fast_ops = 17 +DB_PERF_SEL_DB_SC_tile_no_ops = 18 +DB_PERF_SEL_DB_SC_tile_tile_rate = 19 +DB_PERF_SEL_DB_SC_tile_ssaa_kill = 20 +DB_PERF_SEL_DB_SC_tile_fast_z_ops = 21 +DB_PERF_SEL_DB_SC_tile_fast_stencil_ops = 22 +DB_PERF_SEL_SC_DB_quad_sends = 23 +DB_PERF_SEL_SC_DB_quad_busy = 24 +DB_PERF_SEL_SC_DB_quad_squads = 25 +DB_PERF_SEL_SC_DB_quad_tiles = 26 +DB_PERF_SEL_SC_DB_quad_pixels = 27 +DB_PERF_SEL_SC_DB_quad_killed_tiles = 28 +DB_PERF_SEL_DB_SC_quad_sends = 29 +DB_PERF_SEL_DB_SC_quad_busy = 30 +DB_PERF_SEL_DB_SC_quad_stalls = 31 +DB_PERF_SEL_DB_SC_quad_tiles = 32 +DB_PERF_SEL_DB_SC_quad_lit_quad = 33 +DB_PERF_SEL_DB_CB_tile_sends = 34 +DB_PERF_SEL_DB_CB_tile_busy = 35 +DB_PERF_SEL_DB_CB_tile_stalls = 36 +DB_PERF_SEL_SX_DB_quad_sends = 37 +DB_PERF_SEL_SX_DB_quad_busy = 38 +DB_PERF_SEL_SX_DB_quad_stalls = 39 +DB_PERF_SEL_SX_DB_quad_quads = 40 +DB_PERF_SEL_SX_DB_quad_pixels = 41 +DB_PERF_SEL_SX_DB_quad_exports = 42 +DB_PERF_SEL_SH_quads_outstanding_sum = 43 +DB_PERF_SEL_DB_CB_lquad_sends = 44 +DB_PERF_SEL_DB_CB_lquad_busy = 45 +DB_PERF_SEL_DB_CB_lquad_stalls = 46 +DB_PERF_SEL_DB_CB_lquad_quads = 47 +DB_PERF_SEL_tile_rd_sends = 48 +DB_PERF_SEL_mi_tile_rd_outstanding_sum = 49 +DB_PERF_SEL_quad_rd_sends = 50 +DB_PERF_SEL_quad_rd_busy = 51 +DB_PERF_SEL_quad_rd_mi_stall = 52 +DB_PERF_SEL_quad_rd_rw_collision = 53 +DB_PERF_SEL_quad_rd_tag_stall = 54 +DB_PERF_SEL_quad_rd_32byte_reqs = 55 +DB_PERF_SEL_quad_rd_panic = 56 +DB_PERF_SEL_mi_quad_rd_outstanding_sum = 57 +DB_PERF_SEL_quad_rdret_sends = 58 +DB_PERF_SEL_quad_rdret_busy = 59 +DB_PERF_SEL_tile_wr_sends = 60 +DB_PERF_SEL_tile_wr_acks = 61 +DB_PERF_SEL_mi_tile_wr_outstanding_sum = 62 +DB_PERF_SEL_quad_wr_sends = 63 +DB_PERF_SEL_quad_wr_busy = 64 +DB_PERF_SEL_quad_wr_mi_stall = 65 +DB_PERF_SEL_quad_wr_coherency_stall = 66 +DB_PERF_SEL_quad_wr_acks = 67 +DB_PERF_SEL_mi_quad_wr_outstanding_sum = 68 +DB_PERF_SEL_Tile_Cache_misses = 69 +DB_PERF_SEL_Tile_Cache_hits = 70 +DB_PERF_SEL_Tile_Cache_flushes = 71 +DB_PERF_SEL_Tile_Cache_surface_stall = 72 +DB_PERF_SEL_Tile_Cache_starves = 73 +DB_PERF_SEL_Tile_Cache_mem_return_starve = 74 +DB_PERF_SEL_tcp_dispatcher_reads = 75 +DB_PERF_SEL_tcp_prefetcher_reads = 76 +DB_PERF_SEL_tcp_preloader_reads = 77 +DB_PERF_SEL_tcp_dispatcher_flushes = 78 +DB_PERF_SEL_tcp_prefetcher_flushes = 79 +DB_PERF_SEL_tcp_preloader_flushes = 80 +DB_PERF_SEL_Depth_Tile_Cache_sends = 81 +DB_PERF_SEL_Depth_Tile_Cache_busy = 82 +DB_PERF_SEL_Depth_Tile_Cache_starves = 83 +DB_PERF_SEL_Depth_Tile_Cache_dtile_locked = 84 +DB_PERF_SEL_Depth_Tile_Cache_alloc_stall = 85 +DB_PERF_SEL_Depth_Tile_Cache_misses = 86 +DB_PERF_SEL_Depth_Tile_Cache_hits = 87 +DB_PERF_SEL_Depth_Tile_Cache_flushes = 88 +DB_PERF_SEL_Depth_Tile_Cache_noop_tile = 89 +DB_PERF_SEL_Depth_Tile_Cache_detailed_noop = 90 +DB_PERF_SEL_Depth_Tile_Cache_event = 91 +DB_PERF_SEL_Depth_Tile_Cache_tile_frees = 92 +DB_PERF_SEL_Depth_Tile_Cache_data_frees = 93 +DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve = 94 +DB_PERF_SEL_Stencil_Cache_misses = 95 +DB_PERF_SEL_Stencil_Cache_hits = 96 +DB_PERF_SEL_Stencil_Cache_flushes = 97 +DB_PERF_SEL_Stencil_Cache_starves = 98 +DB_PERF_SEL_Stencil_Cache_frees = 99 +DB_PERF_SEL_Z_Cache_separate_Z_misses = 100 +DB_PERF_SEL_Z_Cache_separate_Z_hits = 101 +DB_PERF_SEL_Z_Cache_separate_Z_flushes = 102 +DB_PERF_SEL_Z_Cache_separate_Z_starves = 103 +DB_PERF_SEL_Z_Cache_pmask_misses = 104 +DB_PERF_SEL_Z_Cache_pmask_hits = 105 +DB_PERF_SEL_Z_Cache_pmask_flushes = 106 +DB_PERF_SEL_Z_Cache_pmask_starves = 107 +DB_PERF_SEL_Z_Cache_frees = 108 +DB_PERF_SEL_Plane_Cache_misses = 109 +DB_PERF_SEL_Plane_Cache_hits = 110 +DB_PERF_SEL_Plane_Cache_flushes = 111 +DB_PERF_SEL_Plane_Cache_starves = 112 +DB_PERF_SEL_Plane_Cache_frees = 113 +DB_PERF_SEL_flush_expanded_stencil = 114 +DB_PERF_SEL_flush_compressed_stencil = 115 +DB_PERF_SEL_flush_single_stencil = 116 +DB_PERF_SEL_planes_flushed = 117 +DB_PERF_SEL_flush_1plane = 118 +DB_PERF_SEL_flush_2plane = 119 +DB_PERF_SEL_flush_3plane = 120 +DB_PERF_SEL_flush_4plane = 121 +DB_PERF_SEL_flush_5plane = 122 +DB_PERF_SEL_flush_6plane = 123 +DB_PERF_SEL_flush_7plane = 124 +DB_PERF_SEL_flush_8plane = 125 +DB_PERF_SEL_flush_9plane = 126 +DB_PERF_SEL_flush_10plane = 127 +DB_PERF_SEL_flush_11plane = 128 +DB_PERF_SEL_flush_12plane = 129 +DB_PERF_SEL_flush_13plane = 130 +DB_PERF_SEL_flush_14plane = 131 +DB_PERF_SEL_flush_15plane = 132 +DB_PERF_SEL_flush_16plane = 133 +DB_PERF_SEL_flush_expanded_z = 134 +DB_PERF_SEL_earlyZ_waiting_for_postZ_done = 135 +DB_PERF_SEL_reZ_waiting_for_postZ_done = 136 +DB_PERF_SEL_dk_tile_sends = 137 +DB_PERF_SEL_dk_tile_busy = 138 +DB_PERF_SEL_dk_tile_quad_starves = 139 +DB_PERF_SEL_dk_tile_stalls = 140 +DB_PERF_SEL_dk_squad_sends = 141 +DB_PERF_SEL_dk_squad_busy = 142 +DB_PERF_SEL_dk_squad_stalls = 143 +DB_PERF_SEL_Op_Pipe_Busy = 144 +DB_PERF_SEL_Op_Pipe_MC_Read_stall = 145 +DB_PERF_SEL_qc_busy = 146 +DB_PERF_SEL_qc_xfc = 147 +DB_PERF_SEL_qc_conflicts = 148 +DB_PERF_SEL_qc_full_stall = 149 +DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ = 150 +DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ = 151 +DB_PERF_SEL_tsc_insert_summarize_stall = 152 +DB_PERF_SEL_tl_busy = 153 +DB_PERF_SEL_tl_dtc_read_starved = 154 +DB_PERF_SEL_tl_z_fetch_stall = 155 +DB_PERF_SEL_tl_stencil_stall = 156 +DB_PERF_SEL_tl_z_decompress_stall = 157 +DB_PERF_SEL_tl_stencil_locked_stall = 158 +DB_PERF_SEL_tl_events = 159 +DB_PERF_SEL_tl_summarize_squads = 160 +DB_PERF_SEL_tl_flush_expand_squads = 161 +DB_PERF_SEL_tl_expand_squads = 162 +DB_PERF_SEL_tl_preZ_squads = 163 +DB_PERF_SEL_tl_postZ_squads = 164 +DB_PERF_SEL_tl_preZ_noop_squads = 165 +DB_PERF_SEL_tl_postZ_noop_squads = 166 +DB_PERF_SEL_tl_tile_ops = 167 +DB_PERF_SEL_tl_in_xfc = 168 +DB_PERF_SEL_tl_in_single_stencil_expand_stall = 169 +DB_PERF_SEL_tl_in_fast_z_stall = 170 +DB_PERF_SEL_tl_out_xfc = 171 +DB_PERF_SEL_tl_out_squads = 172 +DB_PERF_SEL_zf_plane_multicycle = 173 +DB_PERF_SEL_PostZ_Samples_passing_Z = 174 +DB_PERF_SEL_PostZ_Samples_failing_Z = 175 +DB_PERF_SEL_PostZ_Samples_failing_S = 176 +DB_PERF_SEL_PreZ_Samples_passing_Z = 177 +DB_PERF_SEL_PreZ_Samples_failing_Z = 178 +DB_PERF_SEL_PreZ_Samples_failing_S = 179 +DB_PERF_SEL_ts_tc_update_stall = 180 +DB_PERF_SEL_sc_kick_start = 181 +DB_PERF_SEL_sc_kick_end = 182 +DB_PERF_SEL_clock_reg_active = 183 +DB_PERF_SEL_clock_main_active = 184 +DB_PERF_SEL_clock_mem_export_active = 185 +DB_PERF_SEL_esr_ps_out_busy = 186 +DB_PERF_SEL_esr_ps_lqf_busy = 187 +DB_PERF_SEL_esr_ps_lqf_stall = 188 +DB_PERF_SEL_etr_out_send = 189 +DB_PERF_SEL_etr_out_busy = 190 +DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall = 191 +DB_PERF_SEL_etr_out_cb_tile_stall = 192 +DB_PERF_SEL_etr_out_esr_stall = 193 +DB_PERF_SEL_esr_ps_sqq_busy = 194 +DB_PERF_SEL_esr_ps_sqq_stall = 195 +DB_PERF_SEL_esr_eot_fwd_busy = 196 +DB_PERF_SEL_esr_eot_fwd_holding_squad = 197 +DB_PERF_SEL_esr_eot_fwd_forward = 198 +DB_PERF_SEL_esr_sqq_zi_busy = 199 +DB_PERF_SEL_esr_sqq_zi_stall = 200 +DB_PERF_SEL_postzl_sq_pt_busy = 201 +DB_PERF_SEL_postzl_sq_pt_stall = 202 +DB_PERF_SEL_postzl_se_busy = 203 +DB_PERF_SEL_postzl_se_stall = 204 +DB_PERF_SEL_postzl_partial_launch = 205 +DB_PERF_SEL_postzl_full_launch = 206 +DB_PERF_SEL_postzl_partial_waiting = 207 +DB_PERF_SEL_postzl_tile_mem_stall = 208 +DB_PERF_SEL_postzl_tile_init_stall = 209 +DB_PEFF_SEL_prezl_tile_mem_stall = 210 +DB_PERF_SEL_prezl_tile_init_stall = 211 +DB_PERF_SEL_dtt_sm_clash_stall = 212 +DB_PERF_SEL_dtt_sm_slot_stall = 213 +DB_PERF_SEL_dtt_sm_miss_stall = 214 +DB_PERF_SEL_mi_rdreq_busy = 215 +DB_PERF_SEL_mi_rdreq_stall = 216 +DB_PERF_SEL_mi_wrreq_busy = 217 +DB_PERF_SEL_mi_wrreq_stall = 218 +DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop = 219 +DB_PERF_SEL_dkg_tile_rate_tile = 220 +DB_PERF_SEL_prezl_src_in_sends = 221 +DB_PERF_SEL_prezl_src_in_stall = 222 +DB_PERF_SEL_prezl_src_in_squads = 223 +DB_PERF_SEL_prezl_src_in_squads_unrolled = 224 +DB_PERF_SEL_prezl_src_in_tile_rate = 225 +DB_PERF_SEL_prezl_src_in_tile_rate_unrolled = 226 +DB_PERF_SEL_prezl_src_out_stall = 227 +DB_PERF_SEL_postzl_src_in_sends = 228 +DB_PERF_SEL_postzl_src_in_stall = 229 +DB_PERF_SEL_postzl_src_in_squads = 230 +DB_PERF_SEL_postzl_src_in_squads_unrolled = 231 +DB_PERF_SEL_postzl_src_in_tile_rate = 232 +DB_PERF_SEL_postzl_src_in_tile_rate_unrolled = 233 +DB_PERF_SEL_postzl_src_out_stall = 234 +DB_PERF_SEL_esr_ps_src_in_sends = 235 +DB_PERF_SEL_esr_ps_src_in_stall = 236 +DB_PERF_SEL_esr_ps_src_in_squads = 237 +DB_PERF_SEL_esr_ps_src_in_squads_unrolled = 238 +DB_PERF_SEL_esr_ps_src_in_tile_rate = 239 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled = 240 +DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate = 241 +DB_PERF_SEL_esr_ps_src_out_stall = 242 +DB_PERF_SEL_depth_bounds_qtiles_culled = 243 +DB_PERF_SEL_PreZ_Samples_failing_DB = 244 +DB_PERF_SEL_PostZ_Samples_failing_DB = 245 +DB_PERF_SEL_flush_compressed = 246 +DB_PERF_SEL_flush_plane_le4 = 247 +DB_PERF_SEL_tiles_z_fully_summarized = 248 +DB_PERF_SEL_tiles_stencil_fully_summarized = 249 +DB_PERF_SEL_tiles_z_clear_on_expclear = 250 +DB_PERF_SEL_tiles_s_clear_on_expclear = 251 +DB_PERF_SEL_tiles_decomp_on_expclear = 252 +DB_PERF_SEL_tiles_compressed_to_decompressed = 253 +DB_PERF_SEL_Op_Pipe_Prez_Busy = 254 +DB_PERF_SEL_Op_Pipe_Postz_Busy = 255 +DB_PERF_SEL_di_dt_stall = 256 +DB_PERF_SEL_DB_SC_quad_double_quad = 257 +DB_PERF_SEL_SX_DB_quad_export_quads = 258 +DB_PERF_SEL_SX_DB_quad_double_format = 259 +DB_PERF_SEL_SX_DB_quad_fast_format = 260 +DB_PERF_SEL_SX_DB_quad_slow_format = 261 +DB_PERF_SEL_DB_CB_lquad_export_quads = 262 +DB_PERF_SEL_DB_CB_lquad_double_format = 263 +DB_PERF_SEL_DB_CB_lquad_fast_format = 264 +DB_PERF_SEL_DB_CB_lquad_slow_format = 265 +DB_PERF_SEL_CB_DB_rdreq_sends = 266 +DB_PERF_SEL_CB_DB_rdreq_prt_sends = 267 +DB_PERF_SEL_CB_DB_wrreq_sends = 268 +DB_PERF_SEL_CB_DB_wrreq_prt_sends = 269 +DB_PERF_SEL_DB_CB_rdret_ack = 270 +DB_PERF_SEL_DB_CB_rdret_nack = 271 +DB_PERF_SEL_DB_CB_wrret_ack = 272 +DB_PERF_SEL_DB_CB_wrret_nack = 273 +DB_PERF_SEL_DFSM_squads_in = 274 +DB_PERF_SEL_DFSM_full_cleared_squads_out = 275 +DB_PERF_SEL_DFSM_quads_in = 276 +DB_PERF_SEL_DFSM_fully_cleared_quads_out = 277 +DB_PERF_SEL_DFSM_lit_pixels_in = 278 +DB_PERF_SEL_DFSM_fully_cleared_pixels_out = 279 +DB_PERF_SEL_DFSM_lit_samples_in = 280 +DB_PERF_SEL_DFSM_lit_samples_out = 281 +DB_PERF_SEL_DFSM_cycles_above_watermark = 282 +DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream = 283 +DB_PERF_SEL_DFSM_stalled_by_downstream = 284 +DB_PERF_SEL_DFSM_evicted_squads_above_watermark = 285 +DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow = 286 +DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO = 287 +DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark = 288 +PerfCounter_Vals = ctypes.c_uint32 # enum + +# values for enumeration 'RingCounterControl' +RingCounterControl__enumvalues = { + 0: 'COUNTER_RING_SPLIT', + 1: 'COUNTER_RING_0', + 2: 'COUNTER_RING_1', +} +COUNTER_RING_SPLIT = 0 +COUNTER_RING_0 = 1 +COUNTER_RING_1 = 2 +RingCounterControl = ctypes.c_uint32 # enum + +# values for enumeration 'DbMemArbWatermarks' +DbMemArbWatermarks__enumvalues = { + 0: 'TRANSFERRED_64_BYTES', + 1: 'TRANSFERRED_128_BYTES', + 2: 'TRANSFERRED_256_BYTES', + 3: 'TRANSFERRED_512_BYTES', + 4: 'TRANSFERRED_1024_BYTES', + 5: 'TRANSFERRED_2048_BYTES', + 6: 'TRANSFERRED_4096_BYTES', + 7: 'TRANSFERRED_8192_BYTES', +} +TRANSFERRED_64_BYTES = 0 +TRANSFERRED_128_BYTES = 1 +TRANSFERRED_256_BYTES = 2 +TRANSFERRED_512_BYTES = 3 +TRANSFERRED_1024_BYTES = 4 +TRANSFERRED_2048_BYTES = 5 +TRANSFERRED_4096_BYTES = 6 +TRANSFERRED_8192_BYTES = 7 +DbMemArbWatermarks = ctypes.c_uint32 # enum + +# values for enumeration 'DFSMFlushEvents' +DFSMFlushEvents__enumvalues = { + 0: 'DB_FLUSH_AND_INV_DB_DATA_TS', + 1: 'DB_FLUSH_AND_INV_DB_META', + 2: 'DB_CACHE_FLUSH', + 3: 'DB_CACHE_FLUSH_TS', + 4: 'DB_CACHE_FLUSH_AND_INV_EVENT', + 5: 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', +} +DB_FLUSH_AND_INV_DB_DATA_TS = 0 +DB_FLUSH_AND_INV_DB_META = 1 +DB_CACHE_FLUSH = 2 +DB_CACHE_FLUSH_TS = 3 +DB_CACHE_FLUSH_AND_INV_EVENT = 4 +DB_CACHE_FLUSH_AND_INV_TS_EVENT = 5 +DFSMFlushEvents = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeCounterId' +PixelPipeCounterId__enumvalues = { + 0: 'PIXEL_PIPE_OCCLUSION_COUNT_0', + 1: 'PIXEL_PIPE_OCCLUSION_COUNT_1', + 2: 'PIXEL_PIPE_OCCLUSION_COUNT_2', + 3: 'PIXEL_PIPE_OCCLUSION_COUNT_3', + 4: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 5: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 6: 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', + 7: 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', +} +PIXEL_PIPE_OCCLUSION_COUNT_0 = 0 +PIXEL_PIPE_OCCLUSION_COUNT_1 = 1 +PIXEL_PIPE_OCCLUSION_COUNT_2 = 2 +PIXEL_PIPE_OCCLUSION_COUNT_3 = 3 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_0 = 4 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_0 = 5 +PIXEL_PIPE_SCREEN_MIN_EXTENTS_1 = 6 +PIXEL_PIPE_SCREEN_MAX_EXTENTS_1 = 7 +PixelPipeCounterId = ctypes.c_uint32 # enum + +# values for enumeration 'PixelPipeStride' +PixelPipeStride__enumvalues = { + 0: 'PIXEL_PIPE_STRIDE_32_BITS', + 1: 'PIXEL_PIPE_STRIDE_64_BITS', + 2: 'PIXEL_PIPE_STRIDE_128_BITS', + 3: 'PIXEL_PIPE_STRIDE_256_BITS', +} +PIXEL_PIPE_STRIDE_32_BITS = 0 +PIXEL_PIPE_STRIDE_64_BITS = 1 +PIXEL_PIPE_STRIDE_128_BITS = 2 +PIXEL_PIPE_STRIDE_256_BITS = 3 +PixelPipeStride = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_BORDER_COLOR_TYPE' +TEX_BORDER_COLOR_TYPE__enumvalues = { + 0: 'TEX_BorderColor_TransparentBlack', + 1: 'TEX_BorderColor_OpaqueBlack', + 2: 'TEX_BorderColor_OpaqueWhite', + 3: 'TEX_BorderColor_Register', +} +TEX_BorderColor_TransparentBlack = 0 +TEX_BorderColor_OpaqueBlack = 1 +TEX_BorderColor_OpaqueWhite = 2 +TEX_BorderColor_Register = 3 +TEX_BORDER_COLOR_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CHROMA_KEY' +TEX_CHROMA_KEY__enumvalues = { + 0: 'TEX_ChromaKey_Disabled', + 1: 'TEX_ChromaKey_Kill', + 2: 'TEX_ChromaKey_Blend', + 3: 'TEX_ChromaKey_RESERVED_3', +} +TEX_ChromaKey_Disabled = 0 +TEX_ChromaKey_Kill = 1 +TEX_ChromaKey_Blend = 2 +TEX_ChromaKey_RESERVED_3 = 3 +TEX_CHROMA_KEY = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_CLAMP' +TEX_CLAMP__enumvalues = { + 0: 'TEX_Clamp_Repeat', + 1: 'TEX_Clamp_Mirror', + 2: 'TEX_Clamp_ClampToLast', + 3: 'TEX_Clamp_MirrorOnceToLast', + 4: 'TEX_Clamp_ClampHalfToBorder', + 5: 'TEX_Clamp_MirrorOnceHalfToBorder', + 6: 'TEX_Clamp_ClampToBorder', + 7: 'TEX_Clamp_MirrorOnceToBorder', +} +TEX_Clamp_Repeat = 0 +TEX_Clamp_Mirror = 1 +TEX_Clamp_ClampToLast = 2 +TEX_Clamp_MirrorOnceToLast = 3 +TEX_Clamp_ClampHalfToBorder = 4 +TEX_Clamp_MirrorOnceHalfToBorder = 5 +TEX_Clamp_ClampToBorder = 6 +TEX_Clamp_MirrorOnceToBorder = 7 +TEX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_COORD_TYPE' +TEX_COORD_TYPE__enumvalues = { + 0: 'TEX_CoordType_Unnormalized', + 1: 'TEX_CoordType_Normalized', +} +TEX_CoordType_Unnormalized = 0 +TEX_CoordType_Normalized = 1 +TEX_COORD_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DEPTH_COMPARE_FUNCTION' +TEX_DEPTH_COMPARE_FUNCTION__enumvalues = { + 0: 'TEX_DepthCompareFunction_Never', + 1: 'TEX_DepthCompareFunction_Less', + 2: 'TEX_DepthCompareFunction_Equal', + 3: 'TEX_DepthCompareFunction_LessEqual', + 4: 'TEX_DepthCompareFunction_Greater', + 5: 'TEX_DepthCompareFunction_NotEqual', + 6: 'TEX_DepthCompareFunction_GreaterEqual', + 7: 'TEX_DepthCompareFunction_Always', +} +TEX_DepthCompareFunction_Never = 0 +TEX_DepthCompareFunction_Less = 1 +TEX_DepthCompareFunction_Equal = 2 +TEX_DepthCompareFunction_LessEqual = 3 +TEX_DepthCompareFunction_Greater = 4 +TEX_DepthCompareFunction_NotEqual = 5 +TEX_DepthCompareFunction_GreaterEqual = 6 +TEX_DepthCompareFunction_Always = 7 +TEX_DEPTH_COMPARE_FUNCTION = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_DIM' +TEX_DIM__enumvalues = { + 0: 'TEX_Dim_1D', + 1: 'TEX_Dim_2D', + 2: 'TEX_Dim_3D', + 3: 'TEX_Dim_CubeMap', + 4: 'TEX_Dim_1DArray', + 5: 'TEX_Dim_2DArray', + 6: 'TEX_Dim_2D_MSAA', + 7: 'TEX_Dim_2DArray_MSAA', +} +TEX_Dim_1D = 0 +TEX_Dim_2D = 1 +TEX_Dim_3D = 2 +TEX_Dim_CubeMap = 3 +TEX_Dim_1DArray = 4 +TEX_Dim_2DArray = 5 +TEX_Dim_2D_MSAA = 6 +TEX_Dim_2DArray_MSAA = 7 +TEX_DIM = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_FORMAT_COMP' +TEX_FORMAT_COMP__enumvalues = { + 0: 'TEX_FormatComp_Unsigned', + 1: 'TEX_FormatComp_Signed', + 2: 'TEX_FormatComp_UnsignedBiased', + 3: 'TEX_FormatComp_RESERVED_3', +} +TEX_FormatComp_Unsigned = 0 +TEX_FormatComp_Signed = 1 +TEX_FormatComp_UnsignedBiased = 2 +TEX_FormatComp_RESERVED_3 = 3 +TEX_FORMAT_COMP = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MAX_ANISO_RATIO' +TEX_MAX_ANISO_RATIO__enumvalues = { + 0: 'TEX_MaxAnisoRatio_1to1', + 1: 'TEX_MaxAnisoRatio_2to1', + 2: 'TEX_MaxAnisoRatio_4to1', + 3: 'TEX_MaxAnisoRatio_8to1', + 4: 'TEX_MaxAnisoRatio_16to1', + 5: 'TEX_MaxAnisoRatio_RESERVED_5', + 6: 'TEX_MaxAnisoRatio_RESERVED_6', + 7: 'TEX_MaxAnisoRatio_RESERVED_7', +} +TEX_MaxAnisoRatio_1to1 = 0 +TEX_MaxAnisoRatio_2to1 = 1 +TEX_MaxAnisoRatio_4to1 = 2 +TEX_MaxAnisoRatio_8to1 = 3 +TEX_MaxAnisoRatio_16to1 = 4 +TEX_MaxAnisoRatio_RESERVED_5 = 5 +TEX_MaxAnisoRatio_RESERVED_6 = 6 +TEX_MaxAnisoRatio_RESERVED_7 = 7 +TEX_MAX_ANISO_RATIO = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_MIP_FILTER' +TEX_MIP_FILTER__enumvalues = { + 0: 'TEX_MipFilter_None', + 1: 'TEX_MipFilter_Point', + 2: 'TEX_MipFilter_Linear', + 3: 'TEX_MipFilter_Point_Aniso_Adj', +} +TEX_MipFilter_None = 0 +TEX_MipFilter_Point = 1 +TEX_MipFilter_Linear = 2 +TEX_MipFilter_Point_Aniso_Adj = 3 +TEX_MIP_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_REQUEST_SIZE' +TEX_REQUEST_SIZE__enumvalues = { + 0: 'TEX_RequestSize_32B', + 1: 'TEX_RequestSize_64B', + 2: 'TEX_RequestSize_128B', + 3: 'TEX_RequestSize_2X64B', +} +TEX_RequestSize_32B = 0 +TEX_RequestSize_64B = 1 +TEX_RequestSize_128B = 2 +TEX_RequestSize_2X64B = 3 +TEX_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_SAMPLER_TYPE' +TEX_SAMPLER_TYPE__enumvalues = { + 0: 'TEX_SamplerType_Invalid', + 1: 'TEX_SamplerType_Valid', +} +TEX_SamplerType_Invalid = 0 +TEX_SamplerType_Valid = 1 +TEX_SAMPLER_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_XY_FILTER' +TEX_XY_FILTER__enumvalues = { + 0: 'TEX_XYFilter_Point', + 1: 'TEX_XYFilter_Linear', + 2: 'TEX_XYFilter_AnisoPoint', + 3: 'TEX_XYFilter_AnisoLinear', +} +TEX_XYFilter_Point = 0 +TEX_XYFilter_Linear = 1 +TEX_XYFilter_AnisoPoint = 2 +TEX_XYFilter_AnisoLinear = 3 +TEX_XY_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'TEX_Z_FILTER' +TEX_Z_FILTER__enumvalues = { + 0: 'TEX_ZFilter_None', + 1: 'TEX_ZFilter_Point', + 2: 'TEX_ZFilter_Linear', + 3: 'TEX_ZFilter_RESERVED_3', +} +TEX_ZFilter_None = 0 +TEX_ZFilter_Point = 1 +TEX_ZFilter_Linear = 2 +TEX_ZFilter_RESERVED_3 = 3 +TEX_Z_FILTER = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_CLAMP' +VTX_CLAMP__enumvalues = { + 0: 'VTX_Clamp_ClampToZero', + 1: 'VTX_Clamp_ClampToNAN', +} +VTX_Clamp_ClampToZero = 0 +VTX_Clamp_ClampToNAN = 1 +VTX_CLAMP = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_FETCH_TYPE' +VTX_FETCH_TYPE__enumvalues = { + 0: 'VTX_FetchType_VertexData', + 1: 'VTX_FetchType_InstanceData', + 2: 'VTX_FetchType_NoIndexOffset', + 3: 'VTX_FetchType_RESERVED_3', +} +VTX_FetchType_VertexData = 0 +VTX_FetchType_InstanceData = 1 +VTX_FetchType_NoIndexOffset = 2 +VTX_FetchType_RESERVED_3 = 3 +VTX_FETCH_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_FORMAT_COMP_ALL' +VTX_FORMAT_COMP_ALL__enumvalues = { + 0: 'VTX_FormatCompAll_Unsigned', + 1: 'VTX_FormatCompAll_Signed', +} +VTX_FormatCompAll_Unsigned = 0 +VTX_FormatCompAll_Signed = 1 +VTX_FORMAT_COMP_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'VTX_MEM_REQUEST_SIZE' +VTX_MEM_REQUEST_SIZE__enumvalues = { + 0: 'VTX_MemRequestSize_32B', + 1: 'VTX_MemRequestSize_64B', +} +VTX_MemRequestSize_32B = 0 +VTX_MemRequestSize_64B = 1 +VTX_MEM_REQUEST_SIZE = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_DATA_FORMAT' +TVX_DATA_FORMAT__enumvalues = { + 0: 'TVX_FMT_INVALID', + 1: 'TVX_FMT_8', + 2: 'TVX_FMT_4_4', + 3: 'TVX_FMT_3_3_2', + 4: 'TVX_FMT_RESERVED_4', + 5: 'TVX_FMT_16', + 6: 'TVX_FMT_16_FLOAT', + 7: 'TVX_FMT_8_8', + 8: 'TVX_FMT_5_6_5', + 9: 'TVX_FMT_6_5_5', + 10: 'TVX_FMT_1_5_5_5', + 11: 'TVX_FMT_4_4_4_4', + 12: 'TVX_FMT_5_5_5_1', + 13: 'TVX_FMT_32', + 14: 'TVX_FMT_32_FLOAT', + 15: 'TVX_FMT_16_16', + 16: 'TVX_FMT_16_16_FLOAT', + 17: 'TVX_FMT_8_24', + 18: 'TVX_FMT_8_24_FLOAT', + 19: 'TVX_FMT_24_8', + 20: 'TVX_FMT_24_8_FLOAT', + 21: 'TVX_FMT_10_11_11', + 22: 'TVX_FMT_10_11_11_FLOAT', + 23: 'TVX_FMT_11_11_10', + 24: 'TVX_FMT_11_11_10_FLOAT', + 25: 'TVX_FMT_2_10_10_10', + 26: 'TVX_FMT_8_8_8_8', + 27: 'TVX_FMT_10_10_10_2', + 28: 'TVX_FMT_X24_8_32_FLOAT', + 29: 'TVX_FMT_32_32', + 30: 'TVX_FMT_32_32_FLOAT', + 31: 'TVX_FMT_16_16_16_16', + 32: 'TVX_FMT_16_16_16_16_FLOAT', + 33: 'TVX_FMT_RESERVED_33', + 34: 'TVX_FMT_32_32_32_32', + 35: 'TVX_FMT_32_32_32_32_FLOAT', + 36: 'TVX_FMT_RESERVED_36', + 37: 'TVX_FMT_1', + 38: 'TVX_FMT_1_REVERSED', + 39: 'TVX_FMT_GB_GR', + 40: 'TVX_FMT_BG_RG', + 41: 'TVX_FMT_32_AS_8', + 42: 'TVX_FMT_32_AS_8_8', + 43: 'TVX_FMT_5_9_9_9_SHAREDEXP', + 44: 'TVX_FMT_8_8_8', + 45: 'TVX_FMT_16_16_16', + 46: 'TVX_FMT_16_16_16_FLOAT', + 47: 'TVX_FMT_32_32_32', + 48: 'TVX_FMT_32_32_32_FLOAT', + 49: 'TVX_FMT_BC1', + 50: 'TVX_FMT_BC2', + 51: 'TVX_FMT_BC3', + 52: 'TVX_FMT_BC4', + 53: 'TVX_FMT_BC5', + 54: 'TVX_FMT_APC0', + 55: 'TVX_FMT_APC1', + 56: 'TVX_FMT_APC2', + 57: 'TVX_FMT_APC3', + 58: 'TVX_FMT_APC4', + 59: 'TVX_FMT_APC5', + 60: 'TVX_FMT_APC6', + 61: 'TVX_FMT_APC7', + 62: 'TVX_FMT_CTX1', + 63: 'TVX_FMT_RESERVED_63', +} +TVX_FMT_INVALID = 0 +TVX_FMT_8 = 1 +TVX_FMT_4_4 = 2 +TVX_FMT_3_3_2 = 3 +TVX_FMT_RESERVED_4 = 4 +TVX_FMT_16 = 5 +TVX_FMT_16_FLOAT = 6 +TVX_FMT_8_8 = 7 +TVX_FMT_5_6_5 = 8 +TVX_FMT_6_5_5 = 9 +TVX_FMT_1_5_5_5 = 10 +TVX_FMT_4_4_4_4 = 11 +TVX_FMT_5_5_5_1 = 12 +TVX_FMT_32 = 13 +TVX_FMT_32_FLOAT = 14 +TVX_FMT_16_16 = 15 +TVX_FMT_16_16_FLOAT = 16 +TVX_FMT_8_24 = 17 +TVX_FMT_8_24_FLOAT = 18 +TVX_FMT_24_8 = 19 +TVX_FMT_24_8_FLOAT = 20 +TVX_FMT_10_11_11 = 21 +TVX_FMT_10_11_11_FLOAT = 22 +TVX_FMT_11_11_10 = 23 +TVX_FMT_11_11_10_FLOAT = 24 +TVX_FMT_2_10_10_10 = 25 +TVX_FMT_8_8_8_8 = 26 +TVX_FMT_10_10_10_2 = 27 +TVX_FMT_X24_8_32_FLOAT = 28 +TVX_FMT_32_32 = 29 +TVX_FMT_32_32_FLOAT = 30 +TVX_FMT_16_16_16_16 = 31 +TVX_FMT_16_16_16_16_FLOAT = 32 +TVX_FMT_RESERVED_33 = 33 +TVX_FMT_32_32_32_32 = 34 +TVX_FMT_32_32_32_32_FLOAT = 35 +TVX_FMT_RESERVED_36 = 36 +TVX_FMT_1 = 37 +TVX_FMT_1_REVERSED = 38 +TVX_FMT_GB_GR = 39 +TVX_FMT_BG_RG = 40 +TVX_FMT_32_AS_8 = 41 +TVX_FMT_32_AS_8_8 = 42 +TVX_FMT_5_9_9_9_SHAREDEXP = 43 +TVX_FMT_8_8_8 = 44 +TVX_FMT_16_16_16 = 45 +TVX_FMT_16_16_16_FLOAT = 46 +TVX_FMT_32_32_32 = 47 +TVX_FMT_32_32_32_FLOAT = 48 +TVX_FMT_BC1 = 49 +TVX_FMT_BC2 = 50 +TVX_FMT_BC3 = 51 +TVX_FMT_BC4 = 52 +TVX_FMT_BC5 = 53 +TVX_FMT_APC0 = 54 +TVX_FMT_APC1 = 55 +TVX_FMT_APC2 = 56 +TVX_FMT_APC3 = 57 +TVX_FMT_APC4 = 58 +TVX_FMT_APC5 = 59 +TVX_FMT_APC6 = 60 +TVX_FMT_APC7 = 61 +TVX_FMT_CTX1 = 62 +TVX_FMT_RESERVED_63 = 63 +TVX_DATA_FORMAT = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_DST_SEL' +TVX_DST_SEL__enumvalues = { + 0: 'TVX_DstSel_X', + 1: 'TVX_DstSel_Y', + 2: 'TVX_DstSel_Z', + 3: 'TVX_DstSel_W', + 4: 'TVX_DstSel_0f', + 5: 'TVX_DstSel_1f', + 6: 'TVX_DstSel_RESERVED_6', + 7: 'TVX_DstSel_Mask', +} +TVX_DstSel_X = 0 +TVX_DstSel_Y = 1 +TVX_DstSel_Z = 2 +TVX_DstSel_W = 3 +TVX_DstSel_0f = 4 +TVX_DstSel_1f = 5 +TVX_DstSel_RESERVED_6 = 6 +TVX_DstSel_Mask = 7 +TVX_DST_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_ENDIAN_SWAP' +TVX_ENDIAN_SWAP__enumvalues = { + 0: 'TVX_EndianSwap_None', + 1: 'TVX_EndianSwap_8in16', + 2: 'TVX_EndianSwap_8in32', + 3: 'TVX_EndianSwap_8in64', +} +TVX_EndianSwap_None = 0 +TVX_EndianSwap_8in16 = 1 +TVX_EndianSwap_8in32 = 2 +TVX_EndianSwap_8in64 = 3 +TVX_ENDIAN_SWAP = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_INST' +TVX_INST__enumvalues = { + 0: 'TVX_Inst_NormalVertexFetch', + 1: 'TVX_Inst_SemanticVertexFetch', + 2: 'TVX_Inst_RESERVED_2', + 3: 'TVX_Inst_LD', + 4: 'TVX_Inst_GetTextureResInfo', + 5: 'TVX_Inst_GetNumberOfSamples', + 6: 'TVX_Inst_GetLOD', + 7: 'TVX_Inst_GetGradientsH', + 8: 'TVX_Inst_GetGradientsV', + 9: 'TVX_Inst_SetTextureOffsets', + 10: 'TVX_Inst_KeepGradients', + 11: 'TVX_Inst_SetGradientsH', + 12: 'TVX_Inst_SetGradientsV', + 13: 'TVX_Inst_Pass', + 14: 'TVX_Inst_GetBufferResInfo', + 15: 'TVX_Inst_RESERVED_15', + 16: 'TVX_Inst_Sample', + 17: 'TVX_Inst_Sample_L', + 18: 'TVX_Inst_Sample_LB', + 19: 'TVX_Inst_Sample_LZ', + 20: 'TVX_Inst_Sample_G', + 21: 'TVX_Inst_Gather4', + 22: 'TVX_Inst_Sample_G_LB', + 23: 'TVX_Inst_Gather4_O', + 24: 'TVX_Inst_Sample_C', + 25: 'TVX_Inst_Sample_C_L', + 26: 'TVX_Inst_Sample_C_LB', + 27: 'TVX_Inst_Sample_C_LZ', + 28: 'TVX_Inst_Sample_C_G', + 29: 'TVX_Inst_Gather4_C', + 30: 'TVX_Inst_Sample_C_G_LB', + 31: 'TVX_Inst_Gather4_C_O', +} +TVX_Inst_NormalVertexFetch = 0 +TVX_Inst_SemanticVertexFetch = 1 +TVX_Inst_RESERVED_2 = 2 +TVX_Inst_LD = 3 +TVX_Inst_GetTextureResInfo = 4 +TVX_Inst_GetNumberOfSamples = 5 +TVX_Inst_GetLOD = 6 +TVX_Inst_GetGradientsH = 7 +TVX_Inst_GetGradientsV = 8 +TVX_Inst_SetTextureOffsets = 9 +TVX_Inst_KeepGradients = 10 +TVX_Inst_SetGradientsH = 11 +TVX_Inst_SetGradientsV = 12 +TVX_Inst_Pass = 13 +TVX_Inst_GetBufferResInfo = 14 +TVX_Inst_RESERVED_15 = 15 +TVX_Inst_Sample = 16 +TVX_Inst_Sample_L = 17 +TVX_Inst_Sample_LB = 18 +TVX_Inst_Sample_LZ = 19 +TVX_Inst_Sample_G = 20 +TVX_Inst_Gather4 = 21 +TVX_Inst_Sample_G_LB = 22 +TVX_Inst_Gather4_O = 23 +TVX_Inst_Sample_C = 24 +TVX_Inst_Sample_C_L = 25 +TVX_Inst_Sample_C_LB = 26 +TVX_Inst_Sample_C_LZ = 27 +TVX_Inst_Sample_C_G = 28 +TVX_Inst_Gather4_C = 29 +TVX_Inst_Sample_C_G_LB = 30 +TVX_Inst_Gather4_C_O = 31 +TVX_INST = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_NUM_FORMAT_ALL' +TVX_NUM_FORMAT_ALL__enumvalues = { + 0: 'TVX_NumFormatAll_Norm', + 1: 'TVX_NumFormatAll_Int', + 2: 'TVX_NumFormatAll_Scaled', + 3: 'TVX_NumFormatAll_RESERVED_3', +} +TVX_NumFormatAll_Norm = 0 +TVX_NumFormatAll_Int = 1 +TVX_NumFormatAll_Scaled = 2 +TVX_NumFormatAll_RESERVED_3 = 3 +TVX_NUM_FORMAT_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_SRC_SEL' +TVX_SRC_SEL__enumvalues = { + 0: 'TVX_SrcSel_X', + 1: 'TVX_SrcSel_Y', + 2: 'TVX_SrcSel_Z', + 3: 'TVX_SrcSel_W', + 4: 'TVX_SrcSel_0f', + 5: 'TVX_SrcSel_1f', +} +TVX_SrcSel_X = 0 +TVX_SrcSel_Y = 1 +TVX_SrcSel_Z = 2 +TVX_SrcSel_W = 3 +TVX_SrcSel_0f = 4 +TVX_SrcSel_1f = 5 +TVX_SRC_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_SRF_MODE_ALL' +TVX_SRF_MODE_ALL__enumvalues = { + 0: 'TVX_SRFModeAll_ZCMO', + 1: 'TVX_SRFModeAll_NZ', +} +TVX_SRFModeAll_ZCMO = 0 +TVX_SRFModeAll_NZ = 1 +TVX_SRF_MODE_ALL = ctypes.c_uint32 # enum + +# values for enumeration 'TVX_TYPE' +TVX_TYPE__enumvalues = { + 0: 'TVX_Type_InvalidTextureResource', + 1: 'TVX_Type_InvalidVertexBuffer', + 2: 'TVX_Type_ValidTextureResource', + 3: 'TVX_Type_ValidVertexBuffer', +} +TVX_Type_InvalidTextureResource = 0 +TVX_Type_InvalidVertexBuffer = 1 +TVX_Type_ValidTextureResource = 2 +TVX_Type_ValidVertexBuffer = 3 +TVX_TYPE = ctypes.c_uint32 # enum + +# values for enumeration 'SU_PERFCNT_SEL' +SU_PERFCNT_SEL__enumvalues = { + 0: 'PERF_PAPC_PASX_REQ', + 1: 'PERF_PAPC_PASX_DISABLE_PIPE', + 2: 'PERF_PAPC_PASX_FIRST_VECTOR', + 3: 'PERF_PAPC_PASX_SECOND_VECTOR', + 4: 'PERF_PAPC_PASX_FIRST_DEAD', + 5: 'PERF_PAPC_PASX_SECOND_DEAD', + 6: 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 7: 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 8: 'PERF_PAPC_PA_INPUT_PRIM', + 9: 'PERF_PAPC_PA_INPUT_NULL_PRIM', + 10: 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 11: 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 12: 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 13: 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 14: 'PERF_PAPC_CLPR_CULL_PRIM', + 15: 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', + 16: 'PERF_PAPC_CLPR_VV_CULL_PRIM', + 17: 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 18: 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 19: 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 20: 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 21: 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 22: 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 23: 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', + 24: 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 25: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 26: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 27: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 28: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 29: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 30: 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 31: 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 32: 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', + 33: 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 34: 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 35: 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', + 36: 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 37: 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 38: 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 39: 'PERF_PAPC_CLSM_NULL_PRIM', + 40: 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 41: 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', + 42: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', + 43: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 44: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', + 45: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 46: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 47: 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 48: 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', + 49: 'PERF_PAPC_SU_INPUT_PRIM', + 50: 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 51: 'PERF_PAPC_SU_INPUT_NULL_PRIM', + 52: 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 53: 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 54: 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 55: 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 56: 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 57: 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 58: 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 59: 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 60: 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 61: 'PERF_PAPC_SU_OUTPUT_PRIM', + 62: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 63: 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 64: 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 65: 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 66: 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', + 67: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 68: 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 69: 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', + 70: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 71: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 72: 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 73: 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 74: 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 75: 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 76: 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 77: 'PERF_PAPC_PASX_REQ_IDLE', + 78: 'PERF_PAPC_PASX_REQ_BUSY', + 79: 'PERF_PAPC_PASX_REQ_STALLED', + 80: 'PERF_PAPC_PASX_REC_IDLE', + 81: 'PERF_PAPC_PASX_REC_BUSY', + 82: 'PERF_PAPC_PASX_REC_STARVED_SX', + 83: 'PERF_PAPC_PASX_REC_STALLED', + 84: 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 85: 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 86: 'PERF_PAPC_CCGSM_IDLE', + 87: 'PERF_PAPC_CCGSM_BUSY', + 88: 'PERF_PAPC_CCGSM_STALLED', + 89: 'PERF_PAPC_CLPRIM_IDLE', + 90: 'PERF_PAPC_CLPRIM_BUSY', + 91: 'PERF_PAPC_CLPRIM_STALLED', + 92: 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 93: 'PERF_PAPC_CLIPSM_IDLE', + 94: 'PERF_PAPC_CLIPSM_BUSY', + 95: 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 96: 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', + 97: 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 98: 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 99: 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 100: 'PERF_PAPC_CLIPGA_IDLE', + 101: 'PERF_PAPC_CLIPGA_BUSY', + 102: 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 103: 'PERF_PAPC_CLIPGA_STALLED', + 104: 'PERF_PAPC_CLIP_IDLE', + 105: 'PERF_PAPC_CLIP_BUSY', + 106: 'PERF_PAPC_SU_IDLE', + 107: 'PERF_PAPC_SU_BUSY', + 108: 'PERF_PAPC_SU_STARVED_CLIP', + 109: 'PERF_PAPC_SU_STALLED_SC', + 110: 'PERF_PAPC_CL_DYN_SCLK_VLD', + 111: 'PERF_PAPC_SU_DYN_SCLK_VLD', + 112: 'PERF_PAPC_PA_REG_SCLK_VLD', + 113: 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 114: 'PERF_PAPC_PASX_SE0_REQ', + 115: 'PERF_PAPC_PASX_SE1_REQ', + 116: 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 117: 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 118: 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', + 119: 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', + 120: 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 121: 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 122: 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 123: 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 124: 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 125: 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 126: 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 127: 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 128: 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 129: 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 130: 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 131: 'PERF_PAPC_SU_SE0_STALLED_SC', + 132: 'PERF_PAPC_SU_SE1_STALLED_SC', + 133: 'PERF_PAPC_SU_SE01_STALLED_SC', + 134: 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 135: 'PERF_PAPC_SU_CULLED_PRIM', + 136: 'PERF_PAPC_SU_OUTPUT_EOPG', + 137: 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 138: 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 139: 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 140: 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 141: 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 142: 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 143: 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 144: 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 145: 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 146: 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 147: 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 148: 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 149: 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 150: 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 151: 'PERF_PAPC_SU_SE2_STALLED_SC', + 152: 'PERF_PAPC_SU_SE3_STALLED_SC', +} +PERF_PAPC_PASX_REQ = 0 +PERF_PAPC_PASX_DISABLE_PIPE = 1 +PERF_PAPC_PASX_FIRST_VECTOR = 2 +PERF_PAPC_PASX_SECOND_VECTOR = 3 +PERF_PAPC_PASX_FIRST_DEAD = 4 +PERF_PAPC_PASX_SECOND_DEAD = 5 +PERF_PAPC_PASX_VTX_KILL_DISCARD = 6 +PERF_PAPC_PASX_VTX_NAN_DISCARD = 7 +PERF_PAPC_PA_INPUT_PRIM = 8 +PERF_PAPC_PA_INPUT_NULL_PRIM = 9 +PERF_PAPC_PA_INPUT_EVENT_FLAG = 10 +PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT = 11 +PERF_PAPC_PA_INPUT_END_OF_PACKET = 12 +PERF_PAPC_PA_INPUT_EXTENDED_EVENT = 13 +PERF_PAPC_CLPR_CULL_PRIM = 14 +PERF_PAPC_CLPR_VVUCP_CULL_PRIM = 15 +PERF_PAPC_CLPR_VV_CULL_PRIM = 16 +PERF_PAPC_CLPR_UCP_CULL_PRIM = 17 +PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM = 18 +PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM = 19 +PERF_PAPC_CLPR_CULL_TO_NULL_PRIM = 20 +PERF_PAPC_CLPR_VVUCP_CLIP_PRIM = 21 +PERF_PAPC_CLPR_VV_CLIP_PRIM = 22 +PERF_PAPC_CLPR_UCP_CLIP_PRIM = 23 +PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE = 24 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_1 = 25 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_2 = 26 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_3 = 27 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_4 = 28 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8 = 29 +PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12 = 30 +PERF_PAPC_CLPR_CLIP_PLANE_NEAR = 31 +PERF_PAPC_CLPR_CLIP_PLANE_FAR = 32 +PERF_PAPC_CLPR_CLIP_PLANE_LEFT = 33 +PERF_PAPC_CLPR_CLIP_PLANE_RIGHT = 34 +PERF_PAPC_CLPR_CLIP_PLANE_TOP = 35 +PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM = 36 +PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM = 37 +PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM = 38 +PERF_PAPC_CLSM_NULL_PRIM = 39 +PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM = 40 +PERF_PAPC_CLSM_CULL_TO_NULL_PRIM = 41 +PERF_PAPC_CLSM_OUT_PRIM_CNT_1 = 42 +PERF_PAPC_CLSM_OUT_PRIM_CNT_2 = 43 +PERF_PAPC_CLSM_OUT_PRIM_CNT_3 = 44 +PERF_PAPC_CLSM_OUT_PRIM_CNT_4 = 45 +PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8 = 46 +PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13 = 47 +PERF_PAPC_CLIPGA_VTE_KILL_PRIM = 48 +PERF_PAPC_SU_INPUT_PRIM = 49 +PERF_PAPC_SU_INPUT_CLIP_PRIM = 50 +PERF_PAPC_SU_INPUT_NULL_PRIM = 51 +PERF_PAPC_SU_INPUT_PRIM_DUAL = 52 +PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL = 53 +PERF_PAPC_SU_ZERO_AREA_CULL_PRIM = 54 +PERF_PAPC_SU_BACK_FACE_CULL_PRIM = 55 +PERF_PAPC_SU_FRONT_FACE_CULL_PRIM = 56 +PERF_PAPC_SU_POLYMODE_FACE_CULL = 57 +PERF_PAPC_SU_POLYMODE_BACK_CULL = 58 +PERF_PAPC_SU_POLYMODE_FRONT_CULL = 59 +PERF_PAPC_SU_POLYMODE_INVALID_FILL = 60 +PERF_PAPC_SU_OUTPUT_PRIM = 61 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM = 62 +PERF_PAPC_SU_OUTPUT_NULL_PRIM = 63 +PERF_PAPC_SU_OUTPUT_EVENT_FLAG = 64 +PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT = 65 +PERF_PAPC_SU_OUTPUT_END_OF_PACKET = 66 +PERF_PAPC_SU_OUTPUT_POLYMODE_FACE = 67 +PERF_PAPC_SU_OUTPUT_POLYMODE_BACK = 68 +PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT = 69 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE = 70 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK = 71 +PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT = 72 +PERF_PAPC_SU_OUTPUT_PRIM_DUAL = 73 +PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL = 74 +PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL = 75 +PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL = 76 +PERF_PAPC_PASX_REQ_IDLE = 77 +PERF_PAPC_PASX_REQ_BUSY = 78 +PERF_PAPC_PASX_REQ_STALLED = 79 +PERF_PAPC_PASX_REC_IDLE = 80 +PERF_PAPC_PASX_REC_BUSY = 81 +PERF_PAPC_PASX_REC_STARVED_SX = 82 +PERF_PAPC_PASX_REC_STALLED = 83 +PERF_PAPC_PASX_REC_STALLED_POS_MEM = 84 +PERF_PAPC_PASX_REC_STALLED_CCGSM_IN = 85 +PERF_PAPC_CCGSM_IDLE = 86 +PERF_PAPC_CCGSM_BUSY = 87 +PERF_PAPC_CCGSM_STALLED = 88 +PERF_PAPC_CLPRIM_IDLE = 89 +PERF_PAPC_CLPRIM_BUSY = 90 +PERF_PAPC_CLPRIM_STALLED = 91 +PERF_PAPC_CLPRIM_STARVED_CCGSM = 92 +PERF_PAPC_CLIPSM_IDLE = 93 +PERF_PAPC_CLIPSM_BUSY = 94 +PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH = 95 +PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ = 96 +PERF_PAPC_CLIPSM_WAIT_CLIPGA = 97 +PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP = 98 +PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM = 99 +PERF_PAPC_CLIPGA_IDLE = 100 +PERF_PAPC_CLIPGA_BUSY = 101 +PERF_PAPC_CLIPGA_STARVED_VTE_CLIP = 102 +PERF_PAPC_CLIPGA_STALLED = 103 +PERF_PAPC_CLIP_IDLE = 104 +PERF_PAPC_CLIP_BUSY = 105 +PERF_PAPC_SU_IDLE = 106 +PERF_PAPC_SU_BUSY = 107 +PERF_PAPC_SU_STARVED_CLIP = 108 +PERF_PAPC_SU_STALLED_SC = 109 +PERF_PAPC_CL_DYN_SCLK_VLD = 110 +PERF_PAPC_SU_DYN_SCLK_VLD = 111 +PERF_PAPC_PA_REG_SCLK_VLD = 112 +PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL = 113 +PERF_PAPC_PASX_SE0_REQ = 114 +PERF_PAPC_PASX_SE1_REQ = 115 +PERF_PAPC_PASX_SE0_FIRST_VECTOR = 116 +PERF_PAPC_PASX_SE0_SECOND_VECTOR = 117 +PERF_PAPC_PASX_SE1_FIRST_VECTOR = 118 +PERF_PAPC_PASX_SE1_SECOND_VECTOR = 119 +PERF_PAPC_SU_SE0_PRIM_FILTER_CULL = 120 +PERF_PAPC_SU_SE1_PRIM_FILTER_CULL = 121 +PERF_PAPC_SU_SE01_PRIM_FILTER_CULL = 122 +PERF_PAPC_SU_SE0_OUTPUT_PRIM = 123 +PERF_PAPC_SU_SE1_OUTPUT_PRIM = 124 +PERF_PAPC_SU_SE01_OUTPUT_PRIM = 125 +PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM = 126 +PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM = 127 +PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM = 128 +PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT = 129 +PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT = 130 +PERF_PAPC_SU_SE0_STALLED_SC = 131 +PERF_PAPC_SU_SE1_STALLED_SC = 132 +PERF_PAPC_SU_SE01_STALLED_SC = 133 +PERF_PAPC_CLSM_CLIPPING_PRIM = 134 +PERF_PAPC_SU_CULLED_PRIM = 135 +PERF_PAPC_SU_OUTPUT_EOPG = 136 +PERF_PAPC_SU_SE2_PRIM_FILTER_CULL = 137 +PERF_PAPC_SU_SE3_PRIM_FILTER_CULL = 138 +PERF_PAPC_SU_SE2_OUTPUT_PRIM = 139 +PERF_PAPC_SU_SE3_OUTPUT_PRIM = 140 +PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM = 141 +PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM = 142 +PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET = 143 +PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET = 144 +PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET = 145 +PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET = 146 +PERF_PAPC_SU_SE0_OUTPUT_EOPG = 147 +PERF_PAPC_SU_SE1_OUTPUT_EOPG = 148 +PERF_PAPC_SU_SE2_OUTPUT_EOPG = 149 +PERF_PAPC_SU_SE3_OUTPUT_EOPG = 150 +PERF_PAPC_SU_SE2_STALLED_SC = 151 +PERF_PAPC_SU_SE3_STALLED_SC = 152 +SU_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SC_PERFCNT_SEL' +SC_PERFCNT_SEL__enumvalues = { + 0: 'SC_SRPS_WINDOW_VALID', + 1: 'SC_PSSW_WINDOW_VALID', + 2: 'SC_TPQZ_WINDOW_VALID', + 3: 'SC_QZQP_WINDOW_VALID', + 4: 'SC_TRPK_WINDOW_VALID', + 5: 'SC_SRPS_WINDOW_VALID_BUSY', + 6: 'SC_PSSW_WINDOW_VALID_BUSY', + 7: 'SC_TPQZ_WINDOW_VALID_BUSY', + 8: 'SC_QZQP_WINDOW_VALID_BUSY', + 9: 'SC_TRPK_WINDOW_VALID_BUSY', + 10: 'SC_STARVED_BY_PA', + 11: 'SC_STALLED_BY_PRIMFIFO', + 12: 'SC_STALLED_BY_DB_TILE', + 13: 'SC_STARVED_BY_DB_TILE', + 14: 'SC_STALLED_BY_TILEORDERFIFO', + 15: 'SC_STALLED_BY_TILEFIFO', + 16: 'SC_STALLED_BY_DB_QUAD', + 17: 'SC_STARVED_BY_DB_QUAD', + 18: 'SC_STALLED_BY_QUADFIFO', + 19: 'SC_STALLED_BY_BCI', + 20: 'SC_STALLED_BY_SPI', + 21: 'SC_SCISSOR_DISCARD', + 22: 'SC_BB_DISCARD', + 23: 'SC_SUPERTILE_COUNT', + 24: 'SC_SUPERTILE_PER_PRIM_H0', + 25: 'SC_SUPERTILE_PER_PRIM_H1', + 26: 'SC_SUPERTILE_PER_PRIM_H2', + 27: 'SC_SUPERTILE_PER_PRIM_H3', + 28: 'SC_SUPERTILE_PER_PRIM_H4', + 29: 'SC_SUPERTILE_PER_PRIM_H5', + 30: 'SC_SUPERTILE_PER_PRIM_H6', + 31: 'SC_SUPERTILE_PER_PRIM_H7', + 32: 'SC_SUPERTILE_PER_PRIM_H8', + 33: 'SC_SUPERTILE_PER_PRIM_H9', + 34: 'SC_SUPERTILE_PER_PRIM_H10', + 35: 'SC_SUPERTILE_PER_PRIM_H11', + 36: 'SC_SUPERTILE_PER_PRIM_H12', + 37: 'SC_SUPERTILE_PER_PRIM_H13', + 38: 'SC_SUPERTILE_PER_PRIM_H14', + 39: 'SC_SUPERTILE_PER_PRIM_H15', + 40: 'SC_SUPERTILE_PER_PRIM_H16', + 41: 'SC_TILE_PER_PRIM_H0', + 42: 'SC_TILE_PER_PRIM_H1', + 43: 'SC_TILE_PER_PRIM_H2', + 44: 'SC_TILE_PER_PRIM_H3', + 45: 'SC_TILE_PER_PRIM_H4', + 46: 'SC_TILE_PER_PRIM_H5', + 47: 'SC_TILE_PER_PRIM_H6', + 48: 'SC_TILE_PER_PRIM_H7', + 49: 'SC_TILE_PER_PRIM_H8', + 50: 'SC_TILE_PER_PRIM_H9', + 51: 'SC_TILE_PER_PRIM_H10', + 52: 'SC_TILE_PER_PRIM_H11', + 53: 'SC_TILE_PER_PRIM_H12', + 54: 'SC_TILE_PER_PRIM_H13', + 55: 'SC_TILE_PER_PRIM_H14', + 56: 'SC_TILE_PER_PRIM_H15', + 57: 'SC_TILE_PER_PRIM_H16', + 58: 'SC_TILE_PER_SUPERTILE_H0', + 59: 'SC_TILE_PER_SUPERTILE_H1', + 60: 'SC_TILE_PER_SUPERTILE_H2', + 61: 'SC_TILE_PER_SUPERTILE_H3', + 62: 'SC_TILE_PER_SUPERTILE_H4', + 63: 'SC_TILE_PER_SUPERTILE_H5', + 64: 'SC_TILE_PER_SUPERTILE_H6', + 65: 'SC_TILE_PER_SUPERTILE_H7', + 66: 'SC_TILE_PER_SUPERTILE_H8', + 67: 'SC_TILE_PER_SUPERTILE_H9', + 68: 'SC_TILE_PER_SUPERTILE_H10', + 69: 'SC_TILE_PER_SUPERTILE_H11', + 70: 'SC_TILE_PER_SUPERTILE_H12', + 71: 'SC_TILE_PER_SUPERTILE_H13', + 72: 'SC_TILE_PER_SUPERTILE_H14', + 73: 'SC_TILE_PER_SUPERTILE_H15', + 74: 'SC_TILE_PER_SUPERTILE_H16', + 75: 'SC_TILE_PICKED_H1', + 76: 'SC_TILE_PICKED_H2', + 77: 'SC_TILE_PICKED_H3', + 78: 'SC_TILE_PICKED_H4', + 79: 'SC_QZ0_MULTI_GPU_TILE_DISCARD', + 80: 'SC_QZ1_MULTI_GPU_TILE_DISCARD', + 81: 'SC_QZ2_MULTI_GPU_TILE_DISCARD', + 82: 'SC_QZ3_MULTI_GPU_TILE_DISCARD', + 83: 'SC_QZ0_TILE_COUNT', + 84: 'SC_QZ1_TILE_COUNT', + 85: 'SC_QZ2_TILE_COUNT', + 86: 'SC_QZ3_TILE_COUNT', + 87: 'SC_QZ0_TILE_COVERED_COUNT', + 88: 'SC_QZ1_TILE_COVERED_COUNT', + 89: 'SC_QZ2_TILE_COVERED_COUNT', + 90: 'SC_QZ3_TILE_COVERED_COUNT', + 91: 'SC_QZ0_TILE_NOT_COVERED_COUNT', + 92: 'SC_QZ1_TILE_NOT_COVERED_COUNT', + 93: 'SC_QZ2_TILE_NOT_COVERED_COUNT', + 94: 'SC_QZ3_TILE_NOT_COVERED_COUNT', + 95: 'SC_QZ0_QUAD_PER_TILE_H0', + 96: 'SC_QZ0_QUAD_PER_TILE_H1', + 97: 'SC_QZ0_QUAD_PER_TILE_H2', + 98: 'SC_QZ0_QUAD_PER_TILE_H3', + 99: 'SC_QZ0_QUAD_PER_TILE_H4', + 100: 'SC_QZ0_QUAD_PER_TILE_H5', + 101: 'SC_QZ0_QUAD_PER_TILE_H6', + 102: 'SC_QZ0_QUAD_PER_TILE_H7', + 103: 'SC_QZ0_QUAD_PER_TILE_H8', + 104: 'SC_QZ0_QUAD_PER_TILE_H9', + 105: 'SC_QZ0_QUAD_PER_TILE_H10', + 106: 'SC_QZ0_QUAD_PER_TILE_H11', + 107: 'SC_QZ0_QUAD_PER_TILE_H12', + 108: 'SC_QZ0_QUAD_PER_TILE_H13', + 109: 'SC_QZ0_QUAD_PER_TILE_H14', + 110: 'SC_QZ0_QUAD_PER_TILE_H15', + 111: 'SC_QZ0_QUAD_PER_TILE_H16', + 112: 'SC_QZ1_QUAD_PER_TILE_H0', + 113: 'SC_QZ1_QUAD_PER_TILE_H1', + 114: 'SC_QZ1_QUAD_PER_TILE_H2', + 115: 'SC_QZ1_QUAD_PER_TILE_H3', + 116: 'SC_QZ1_QUAD_PER_TILE_H4', + 117: 'SC_QZ1_QUAD_PER_TILE_H5', + 118: 'SC_QZ1_QUAD_PER_TILE_H6', + 119: 'SC_QZ1_QUAD_PER_TILE_H7', + 120: 'SC_QZ1_QUAD_PER_TILE_H8', + 121: 'SC_QZ1_QUAD_PER_TILE_H9', + 122: 'SC_QZ1_QUAD_PER_TILE_H10', + 123: 'SC_QZ1_QUAD_PER_TILE_H11', + 124: 'SC_QZ1_QUAD_PER_TILE_H12', + 125: 'SC_QZ1_QUAD_PER_TILE_H13', + 126: 'SC_QZ1_QUAD_PER_TILE_H14', + 127: 'SC_QZ1_QUAD_PER_TILE_H15', + 128: 'SC_QZ1_QUAD_PER_TILE_H16', + 129: 'SC_QZ2_QUAD_PER_TILE_H0', + 130: 'SC_QZ2_QUAD_PER_TILE_H1', + 131: 'SC_QZ2_QUAD_PER_TILE_H2', + 132: 'SC_QZ2_QUAD_PER_TILE_H3', + 133: 'SC_QZ2_QUAD_PER_TILE_H4', + 134: 'SC_QZ2_QUAD_PER_TILE_H5', + 135: 'SC_QZ2_QUAD_PER_TILE_H6', + 136: 'SC_QZ2_QUAD_PER_TILE_H7', + 137: 'SC_QZ2_QUAD_PER_TILE_H8', + 138: 'SC_QZ2_QUAD_PER_TILE_H9', + 139: 'SC_QZ2_QUAD_PER_TILE_H10', + 140: 'SC_QZ2_QUAD_PER_TILE_H11', + 141: 'SC_QZ2_QUAD_PER_TILE_H12', + 142: 'SC_QZ2_QUAD_PER_TILE_H13', + 143: 'SC_QZ2_QUAD_PER_TILE_H14', + 144: 'SC_QZ2_QUAD_PER_TILE_H15', + 145: 'SC_QZ2_QUAD_PER_TILE_H16', + 146: 'SC_QZ3_QUAD_PER_TILE_H0', + 147: 'SC_QZ3_QUAD_PER_TILE_H1', + 148: 'SC_QZ3_QUAD_PER_TILE_H2', + 149: 'SC_QZ3_QUAD_PER_TILE_H3', + 150: 'SC_QZ3_QUAD_PER_TILE_H4', + 151: 'SC_QZ3_QUAD_PER_TILE_H5', + 152: 'SC_QZ3_QUAD_PER_TILE_H6', + 153: 'SC_QZ3_QUAD_PER_TILE_H7', + 154: 'SC_QZ3_QUAD_PER_TILE_H8', + 155: 'SC_QZ3_QUAD_PER_TILE_H9', + 156: 'SC_QZ3_QUAD_PER_TILE_H10', + 157: 'SC_QZ3_QUAD_PER_TILE_H11', + 158: 'SC_QZ3_QUAD_PER_TILE_H12', + 159: 'SC_QZ3_QUAD_PER_TILE_H13', + 160: 'SC_QZ3_QUAD_PER_TILE_H14', + 161: 'SC_QZ3_QUAD_PER_TILE_H15', + 162: 'SC_QZ3_QUAD_PER_TILE_H16', + 163: 'SC_QZ0_QUAD_COUNT', + 164: 'SC_QZ1_QUAD_COUNT', + 165: 'SC_QZ2_QUAD_COUNT', + 166: 'SC_QZ3_QUAD_COUNT', + 167: 'SC_P0_HIZ_TILE_COUNT', + 168: 'SC_P1_HIZ_TILE_COUNT', + 169: 'SC_P2_HIZ_TILE_COUNT', + 170: 'SC_P3_HIZ_TILE_COUNT', + 171: 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 172: 'SC_P0_HIZ_QUAD_PER_TILE_H1', + 173: 'SC_P0_HIZ_QUAD_PER_TILE_H2', + 174: 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 175: 'SC_P0_HIZ_QUAD_PER_TILE_H4', + 176: 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 177: 'SC_P0_HIZ_QUAD_PER_TILE_H6', + 178: 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 179: 'SC_P0_HIZ_QUAD_PER_TILE_H8', + 180: 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 181: 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 182: 'SC_P0_HIZ_QUAD_PER_TILE_H11', + 183: 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 184: 'SC_P0_HIZ_QUAD_PER_TILE_H13', + 185: 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 186: 'SC_P0_HIZ_QUAD_PER_TILE_H15', + 187: 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 188: 'SC_P1_HIZ_QUAD_PER_TILE_H0', + 189: 'SC_P1_HIZ_QUAD_PER_TILE_H1', + 190: 'SC_P1_HIZ_QUAD_PER_TILE_H2', + 191: 'SC_P1_HIZ_QUAD_PER_TILE_H3', + 192: 'SC_P1_HIZ_QUAD_PER_TILE_H4', + 193: 'SC_P1_HIZ_QUAD_PER_TILE_H5', + 194: 'SC_P1_HIZ_QUAD_PER_TILE_H6', + 195: 'SC_P1_HIZ_QUAD_PER_TILE_H7', + 196: 'SC_P1_HIZ_QUAD_PER_TILE_H8', + 197: 'SC_P1_HIZ_QUAD_PER_TILE_H9', + 198: 'SC_P1_HIZ_QUAD_PER_TILE_H10', + 199: 'SC_P1_HIZ_QUAD_PER_TILE_H11', + 200: 'SC_P1_HIZ_QUAD_PER_TILE_H12', + 201: 'SC_P1_HIZ_QUAD_PER_TILE_H13', + 202: 'SC_P1_HIZ_QUAD_PER_TILE_H14', + 203: 'SC_P1_HIZ_QUAD_PER_TILE_H15', + 204: 'SC_P1_HIZ_QUAD_PER_TILE_H16', + 205: 'SC_P2_HIZ_QUAD_PER_TILE_H0', + 206: 'SC_P2_HIZ_QUAD_PER_TILE_H1', + 207: 'SC_P2_HIZ_QUAD_PER_TILE_H2', + 208: 'SC_P2_HIZ_QUAD_PER_TILE_H3', + 209: 'SC_P2_HIZ_QUAD_PER_TILE_H4', + 210: 'SC_P2_HIZ_QUAD_PER_TILE_H5', + 211: 'SC_P2_HIZ_QUAD_PER_TILE_H6', + 212: 'SC_P2_HIZ_QUAD_PER_TILE_H7', + 213: 'SC_P2_HIZ_QUAD_PER_TILE_H8', + 214: 'SC_P2_HIZ_QUAD_PER_TILE_H9', + 215: 'SC_P2_HIZ_QUAD_PER_TILE_H10', + 216: 'SC_P2_HIZ_QUAD_PER_TILE_H11', + 217: 'SC_P2_HIZ_QUAD_PER_TILE_H12', + 218: 'SC_P2_HIZ_QUAD_PER_TILE_H13', + 219: 'SC_P2_HIZ_QUAD_PER_TILE_H14', + 220: 'SC_P2_HIZ_QUAD_PER_TILE_H15', + 221: 'SC_P2_HIZ_QUAD_PER_TILE_H16', + 222: 'SC_P3_HIZ_QUAD_PER_TILE_H0', + 223: 'SC_P3_HIZ_QUAD_PER_TILE_H1', + 224: 'SC_P3_HIZ_QUAD_PER_TILE_H2', + 225: 'SC_P3_HIZ_QUAD_PER_TILE_H3', + 226: 'SC_P3_HIZ_QUAD_PER_TILE_H4', + 227: 'SC_P3_HIZ_QUAD_PER_TILE_H5', + 228: 'SC_P3_HIZ_QUAD_PER_TILE_H6', + 229: 'SC_P3_HIZ_QUAD_PER_TILE_H7', + 230: 'SC_P3_HIZ_QUAD_PER_TILE_H8', + 231: 'SC_P3_HIZ_QUAD_PER_TILE_H9', + 232: 'SC_P3_HIZ_QUAD_PER_TILE_H10', + 233: 'SC_P3_HIZ_QUAD_PER_TILE_H11', + 234: 'SC_P3_HIZ_QUAD_PER_TILE_H12', + 235: 'SC_P3_HIZ_QUAD_PER_TILE_H13', + 236: 'SC_P3_HIZ_QUAD_PER_TILE_H14', + 237: 'SC_P3_HIZ_QUAD_PER_TILE_H15', + 238: 'SC_P3_HIZ_QUAD_PER_TILE_H16', + 239: 'SC_P0_HIZ_QUAD_COUNT', + 240: 'SC_P1_HIZ_QUAD_COUNT', + 241: 'SC_P2_HIZ_QUAD_COUNT', + 242: 'SC_P3_HIZ_QUAD_COUNT', + 243: 'SC_P0_DETAIL_QUAD_COUNT', + 244: 'SC_P1_DETAIL_QUAD_COUNT', + 245: 'SC_P2_DETAIL_QUAD_COUNT', + 246: 'SC_P3_DETAIL_QUAD_COUNT', + 247: 'SC_P0_DETAIL_QUAD_WITH_1_PIX', + 248: 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 249: 'SC_P0_DETAIL_QUAD_WITH_3_PIX', + 250: 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 251: 'SC_P1_DETAIL_QUAD_WITH_1_PIX', + 252: 'SC_P1_DETAIL_QUAD_WITH_2_PIX', + 253: 'SC_P1_DETAIL_QUAD_WITH_3_PIX', + 254: 'SC_P1_DETAIL_QUAD_WITH_4_PIX', + 255: 'SC_P2_DETAIL_QUAD_WITH_1_PIX', + 256: 'SC_P2_DETAIL_QUAD_WITH_2_PIX', + 257: 'SC_P2_DETAIL_QUAD_WITH_3_PIX', + 258: 'SC_P2_DETAIL_QUAD_WITH_4_PIX', + 259: 'SC_P3_DETAIL_QUAD_WITH_1_PIX', + 260: 'SC_P3_DETAIL_QUAD_WITH_2_PIX', + 261: 'SC_P3_DETAIL_QUAD_WITH_3_PIX', + 262: 'SC_P3_DETAIL_QUAD_WITH_4_PIX', + 263: 'SC_EARLYZ_QUAD_COUNT', + 264: 'SC_EARLYZ_QUAD_WITH_1_PIX', + 265: 'SC_EARLYZ_QUAD_WITH_2_PIX', + 266: 'SC_EARLYZ_QUAD_WITH_3_PIX', + 267: 'SC_EARLYZ_QUAD_WITH_4_PIX', + 268: 'SC_PKR_QUAD_PER_ROW_H1', + 269: 'SC_PKR_QUAD_PER_ROW_H2', + 270: 'SC_PKR_4X2_QUAD_SPLIT', + 271: 'SC_PKR_4X2_FILL_QUAD', + 272: 'SC_PKR_END_OF_VECTOR', + 273: 'SC_PKR_CONTROL_XFER', + 274: 'SC_PKR_DBHANG_FORCE_EOV', + 275: 'SC_REG_SCLK_BUSY', + 276: 'SC_GRP0_DYN_SCLK_BUSY', + 277: 'SC_GRP1_DYN_SCLK_BUSY', + 278: 'SC_GRP2_DYN_SCLK_BUSY', + 279: 'SC_GRP3_DYN_SCLK_BUSY', + 280: 'SC_GRP4_DYN_SCLK_BUSY', + 281: 'SC_PA0_SC_DATA_FIFO_RD', + 282: 'SC_PA0_SC_DATA_FIFO_WE', + 283: 'SC_PA1_SC_DATA_FIFO_RD', + 284: 'SC_PA1_SC_DATA_FIFO_WE', + 285: 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 286: 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', + 287: 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 288: 'SC_PS_ARB_STALLED_FROM_BELOW', + 289: 'SC_PS_ARB_STARVED_FROM_ABOVE', + 290: 'SC_PS_ARB_SC_BUSY', + 291: 'SC_PS_ARB_PA_SC_BUSY', + 292: 'SC_PA2_SC_DATA_FIFO_RD', + 293: 'SC_PA2_SC_DATA_FIFO_WE', + 294: 'SC_PA3_SC_DATA_FIFO_RD', + 295: 'SC_PA3_SC_DATA_FIFO_WE', + 296: 'SC_PA_SC_DEALLOC_0_0_WE', + 297: 'SC_PA_SC_DEALLOC_0_1_WE', + 298: 'SC_PA_SC_DEALLOC_1_0_WE', + 299: 'SC_PA_SC_DEALLOC_1_1_WE', + 300: 'SC_PA_SC_DEALLOC_2_0_WE', + 301: 'SC_PA_SC_DEALLOC_2_1_WE', + 302: 'SC_PA_SC_DEALLOC_3_0_WE', + 303: 'SC_PA_SC_DEALLOC_3_1_WE', + 304: 'SC_PA0_SC_EOP_WE', + 305: 'SC_PA0_SC_EOPG_WE', + 306: 'SC_PA0_SC_EVENT_WE', + 307: 'SC_PA1_SC_EOP_WE', + 308: 'SC_PA1_SC_EOPG_WE', + 309: 'SC_PA1_SC_EVENT_WE', + 310: 'SC_PA2_SC_EOP_WE', + 311: 'SC_PA2_SC_EOPG_WE', + 312: 'SC_PA2_SC_EVENT_WE', + 313: 'SC_PA3_SC_EOP_WE', + 314: 'SC_PA3_SC_EOPG_WE', + 315: 'SC_PA3_SC_EVENT_WE', + 316: 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 317: 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 318: 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 319: 'SC_PS_ARB_EOP_POP_SYNC_POP', + 320: 'SC_PS_ARB_EVENT_SYNC_POP', + 321: 'SC_SC_PS_ENG_MULTICYCLE_BUBBLE', + 322: 'SC_PA0_SC_FPOV_WE', + 323: 'SC_PA1_SC_FPOV_WE', + 324: 'SC_PA2_SC_FPOV_WE', + 325: 'SC_PA3_SC_FPOV_WE', + 326: 'SC_PA0_SC_LPOV_WE', + 327: 'SC_PA1_SC_LPOV_WE', + 328: 'SC_PA2_SC_LPOV_WE', + 329: 'SC_PA3_SC_LPOV_WE', + 330: 'SC_SC_SPI_DEALLOC_0_0', + 331: 'SC_SC_SPI_DEALLOC_0_1', + 332: 'SC_SC_SPI_DEALLOC_0_2', + 333: 'SC_SC_SPI_DEALLOC_1_0', + 334: 'SC_SC_SPI_DEALLOC_1_1', + 335: 'SC_SC_SPI_DEALLOC_1_2', + 336: 'SC_SC_SPI_DEALLOC_2_0', + 337: 'SC_SC_SPI_DEALLOC_2_1', + 338: 'SC_SC_SPI_DEALLOC_2_2', + 339: 'SC_SC_SPI_DEALLOC_3_0', + 340: 'SC_SC_SPI_DEALLOC_3_1', + 341: 'SC_SC_SPI_DEALLOC_3_2', + 342: 'SC_SC_SPI_FPOV_0', + 343: 'SC_SC_SPI_FPOV_1', + 344: 'SC_SC_SPI_FPOV_2', + 345: 'SC_SC_SPI_FPOV_3', + 346: 'SC_SC_SPI_EVENT', + 347: 'SC_PS_TS_EVENT_FIFO_PUSH', + 348: 'SC_PS_TS_EVENT_FIFO_POP', + 349: 'SC_PS_CTX_DONE_FIFO_PUSH', + 350: 'SC_PS_CTX_DONE_FIFO_POP', + 351: 'SC_MULTICYCLE_BUBBLE_FREEZE', + 352: 'SC_EOP_SYNC_WINDOW', + 353: 'SC_PA0_SC_NULL_WE', + 354: 'SC_PA0_SC_NULL_DEALLOC_WE', + 355: 'SC_PA0_SC_DATA_FIFO_EOPG_RD', + 356: 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 357: 'SC_PA0_SC_DEALLOC_0_RD', + 358: 'SC_PA0_SC_DEALLOC_1_RD', + 359: 'SC_PA1_SC_DATA_FIFO_EOPG_RD', + 360: 'SC_PA1_SC_DATA_FIFO_EOP_RD', + 361: 'SC_PA1_SC_DEALLOC_0_RD', + 362: 'SC_PA1_SC_DEALLOC_1_RD', + 363: 'SC_PA1_SC_NULL_WE', + 364: 'SC_PA1_SC_NULL_DEALLOC_WE', + 365: 'SC_PA2_SC_DATA_FIFO_EOPG_RD', + 366: 'SC_PA2_SC_DATA_FIFO_EOP_RD', + 367: 'SC_PA2_SC_DEALLOC_0_RD', + 368: 'SC_PA2_SC_DEALLOC_1_RD', + 369: 'SC_PA2_SC_NULL_WE', + 370: 'SC_PA2_SC_NULL_DEALLOC_WE', + 371: 'SC_PA3_SC_DATA_FIFO_EOPG_RD', + 372: 'SC_PA3_SC_DATA_FIFO_EOP_RD', + 373: 'SC_PA3_SC_DEALLOC_0_RD', + 374: 'SC_PA3_SC_DEALLOC_1_RD', + 375: 'SC_PA3_SC_NULL_WE', + 376: 'SC_PA3_SC_NULL_DEALLOC_WE', + 377: 'SC_PS_PA0_SC_FIFO_EMPTY', + 378: 'SC_PS_PA0_SC_FIFO_FULL', + 379: 'SC_PA0_PS_DATA_SEND', + 380: 'SC_PS_PA1_SC_FIFO_EMPTY', + 381: 'SC_PS_PA1_SC_FIFO_FULL', + 382: 'SC_PA1_PS_DATA_SEND', + 383: 'SC_PS_PA2_SC_FIFO_EMPTY', + 384: 'SC_PS_PA2_SC_FIFO_FULL', + 385: 'SC_PA2_PS_DATA_SEND', + 386: 'SC_PS_PA3_SC_FIFO_EMPTY', + 387: 'SC_PS_PA3_SC_FIFO_FULL', + 388: 'SC_PA3_PS_DATA_SEND', + 389: 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', + 390: 'SC_BUSY_CNT_NOT_ZERO', + 391: 'SC_BM_BUSY', + 392: 'SC_BACKEND_BUSY', + 393: 'SC_SCF_SCB_INTERFACE_BUSY', + 394: 'SC_SCB_BUSY', + 395: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 396: 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 397: 'SC_PBB_BIN_HIST_NUM_PRIMS', + 398: 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 399: 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 400: 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 401: 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 402: 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 403: 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 404: 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 405: 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 406: 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 407: 'SC_PBB_BUSY', + 408: 'SC_PBB_BUSY_AND_RTR', + 409: 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 410: 'SC_PBB_NUM_BINS', + 411: 'SC_PBB_END_OF_BIN', + 412: 'SC_PBB_END_OF_BATCH', + 413: 'SC_PBB_PRIMBIN_PROCESSED', + 414: 'SC_PBB_PRIM_ADDED_TO_BATCH', + 415: 'SC_PBB_NONBINNED_PRIM', + 416: 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', + 417: 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 418: 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 419: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 420: 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 421: 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 422: 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 423: 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 424: 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 425: 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 426: 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 427: 'SC_POPS_INTRA_WAVE_OVERLAPS', + 428: 'SC_POPS_FORCE_EOV', + 429: 'SC_PKR_QUAD_OVERLAP_NOT_FOUND_IN_WAVE_TABLE', + 430: 'SC_PKR_QUAD_OVERLAP_FOUND_IN_WAVE_TABLE', +} +SC_SRPS_WINDOW_VALID = 0 +SC_PSSW_WINDOW_VALID = 1 +SC_TPQZ_WINDOW_VALID = 2 +SC_QZQP_WINDOW_VALID = 3 +SC_TRPK_WINDOW_VALID = 4 +SC_SRPS_WINDOW_VALID_BUSY = 5 +SC_PSSW_WINDOW_VALID_BUSY = 6 +SC_TPQZ_WINDOW_VALID_BUSY = 7 +SC_QZQP_WINDOW_VALID_BUSY = 8 +SC_TRPK_WINDOW_VALID_BUSY = 9 +SC_STARVED_BY_PA = 10 +SC_STALLED_BY_PRIMFIFO = 11 +SC_STALLED_BY_DB_TILE = 12 +SC_STARVED_BY_DB_TILE = 13 +SC_STALLED_BY_TILEORDERFIFO = 14 +SC_STALLED_BY_TILEFIFO = 15 +SC_STALLED_BY_DB_QUAD = 16 +SC_STARVED_BY_DB_QUAD = 17 +SC_STALLED_BY_QUADFIFO = 18 +SC_STALLED_BY_BCI = 19 +SC_STALLED_BY_SPI = 20 +SC_SCISSOR_DISCARD = 21 +SC_BB_DISCARD = 22 +SC_SUPERTILE_COUNT = 23 +SC_SUPERTILE_PER_PRIM_H0 = 24 +SC_SUPERTILE_PER_PRIM_H1 = 25 +SC_SUPERTILE_PER_PRIM_H2 = 26 +SC_SUPERTILE_PER_PRIM_H3 = 27 +SC_SUPERTILE_PER_PRIM_H4 = 28 +SC_SUPERTILE_PER_PRIM_H5 = 29 +SC_SUPERTILE_PER_PRIM_H6 = 30 +SC_SUPERTILE_PER_PRIM_H7 = 31 +SC_SUPERTILE_PER_PRIM_H8 = 32 +SC_SUPERTILE_PER_PRIM_H9 = 33 +SC_SUPERTILE_PER_PRIM_H10 = 34 +SC_SUPERTILE_PER_PRIM_H11 = 35 +SC_SUPERTILE_PER_PRIM_H12 = 36 +SC_SUPERTILE_PER_PRIM_H13 = 37 +SC_SUPERTILE_PER_PRIM_H14 = 38 +SC_SUPERTILE_PER_PRIM_H15 = 39 +SC_SUPERTILE_PER_PRIM_H16 = 40 +SC_TILE_PER_PRIM_H0 = 41 +SC_TILE_PER_PRIM_H1 = 42 +SC_TILE_PER_PRIM_H2 = 43 +SC_TILE_PER_PRIM_H3 = 44 +SC_TILE_PER_PRIM_H4 = 45 +SC_TILE_PER_PRIM_H5 = 46 +SC_TILE_PER_PRIM_H6 = 47 +SC_TILE_PER_PRIM_H7 = 48 +SC_TILE_PER_PRIM_H8 = 49 +SC_TILE_PER_PRIM_H9 = 50 +SC_TILE_PER_PRIM_H10 = 51 +SC_TILE_PER_PRIM_H11 = 52 +SC_TILE_PER_PRIM_H12 = 53 +SC_TILE_PER_PRIM_H13 = 54 +SC_TILE_PER_PRIM_H14 = 55 +SC_TILE_PER_PRIM_H15 = 56 +SC_TILE_PER_PRIM_H16 = 57 +SC_TILE_PER_SUPERTILE_H0 = 58 +SC_TILE_PER_SUPERTILE_H1 = 59 +SC_TILE_PER_SUPERTILE_H2 = 60 +SC_TILE_PER_SUPERTILE_H3 = 61 +SC_TILE_PER_SUPERTILE_H4 = 62 +SC_TILE_PER_SUPERTILE_H5 = 63 +SC_TILE_PER_SUPERTILE_H6 = 64 +SC_TILE_PER_SUPERTILE_H7 = 65 +SC_TILE_PER_SUPERTILE_H8 = 66 +SC_TILE_PER_SUPERTILE_H9 = 67 +SC_TILE_PER_SUPERTILE_H10 = 68 +SC_TILE_PER_SUPERTILE_H11 = 69 +SC_TILE_PER_SUPERTILE_H12 = 70 +SC_TILE_PER_SUPERTILE_H13 = 71 +SC_TILE_PER_SUPERTILE_H14 = 72 +SC_TILE_PER_SUPERTILE_H15 = 73 +SC_TILE_PER_SUPERTILE_H16 = 74 +SC_TILE_PICKED_H1 = 75 +SC_TILE_PICKED_H2 = 76 +SC_TILE_PICKED_H3 = 77 +SC_TILE_PICKED_H4 = 78 +SC_QZ0_MULTI_GPU_TILE_DISCARD = 79 +SC_QZ1_MULTI_GPU_TILE_DISCARD = 80 +SC_QZ2_MULTI_GPU_TILE_DISCARD = 81 +SC_QZ3_MULTI_GPU_TILE_DISCARD = 82 +SC_QZ0_TILE_COUNT = 83 +SC_QZ1_TILE_COUNT = 84 +SC_QZ2_TILE_COUNT = 85 +SC_QZ3_TILE_COUNT = 86 +SC_QZ0_TILE_COVERED_COUNT = 87 +SC_QZ1_TILE_COVERED_COUNT = 88 +SC_QZ2_TILE_COVERED_COUNT = 89 +SC_QZ3_TILE_COVERED_COUNT = 90 +SC_QZ0_TILE_NOT_COVERED_COUNT = 91 +SC_QZ1_TILE_NOT_COVERED_COUNT = 92 +SC_QZ2_TILE_NOT_COVERED_COUNT = 93 +SC_QZ3_TILE_NOT_COVERED_COUNT = 94 +SC_QZ0_QUAD_PER_TILE_H0 = 95 +SC_QZ0_QUAD_PER_TILE_H1 = 96 +SC_QZ0_QUAD_PER_TILE_H2 = 97 +SC_QZ0_QUAD_PER_TILE_H3 = 98 +SC_QZ0_QUAD_PER_TILE_H4 = 99 +SC_QZ0_QUAD_PER_TILE_H5 = 100 +SC_QZ0_QUAD_PER_TILE_H6 = 101 +SC_QZ0_QUAD_PER_TILE_H7 = 102 +SC_QZ0_QUAD_PER_TILE_H8 = 103 +SC_QZ0_QUAD_PER_TILE_H9 = 104 +SC_QZ0_QUAD_PER_TILE_H10 = 105 +SC_QZ0_QUAD_PER_TILE_H11 = 106 +SC_QZ0_QUAD_PER_TILE_H12 = 107 +SC_QZ0_QUAD_PER_TILE_H13 = 108 +SC_QZ0_QUAD_PER_TILE_H14 = 109 +SC_QZ0_QUAD_PER_TILE_H15 = 110 +SC_QZ0_QUAD_PER_TILE_H16 = 111 +SC_QZ1_QUAD_PER_TILE_H0 = 112 +SC_QZ1_QUAD_PER_TILE_H1 = 113 +SC_QZ1_QUAD_PER_TILE_H2 = 114 +SC_QZ1_QUAD_PER_TILE_H3 = 115 +SC_QZ1_QUAD_PER_TILE_H4 = 116 +SC_QZ1_QUAD_PER_TILE_H5 = 117 +SC_QZ1_QUAD_PER_TILE_H6 = 118 +SC_QZ1_QUAD_PER_TILE_H7 = 119 +SC_QZ1_QUAD_PER_TILE_H8 = 120 +SC_QZ1_QUAD_PER_TILE_H9 = 121 +SC_QZ1_QUAD_PER_TILE_H10 = 122 +SC_QZ1_QUAD_PER_TILE_H11 = 123 +SC_QZ1_QUAD_PER_TILE_H12 = 124 +SC_QZ1_QUAD_PER_TILE_H13 = 125 +SC_QZ1_QUAD_PER_TILE_H14 = 126 +SC_QZ1_QUAD_PER_TILE_H15 = 127 +SC_QZ1_QUAD_PER_TILE_H16 = 128 +SC_QZ2_QUAD_PER_TILE_H0 = 129 +SC_QZ2_QUAD_PER_TILE_H1 = 130 +SC_QZ2_QUAD_PER_TILE_H2 = 131 +SC_QZ2_QUAD_PER_TILE_H3 = 132 +SC_QZ2_QUAD_PER_TILE_H4 = 133 +SC_QZ2_QUAD_PER_TILE_H5 = 134 +SC_QZ2_QUAD_PER_TILE_H6 = 135 +SC_QZ2_QUAD_PER_TILE_H7 = 136 +SC_QZ2_QUAD_PER_TILE_H8 = 137 +SC_QZ2_QUAD_PER_TILE_H9 = 138 +SC_QZ2_QUAD_PER_TILE_H10 = 139 +SC_QZ2_QUAD_PER_TILE_H11 = 140 +SC_QZ2_QUAD_PER_TILE_H12 = 141 +SC_QZ2_QUAD_PER_TILE_H13 = 142 +SC_QZ2_QUAD_PER_TILE_H14 = 143 +SC_QZ2_QUAD_PER_TILE_H15 = 144 +SC_QZ2_QUAD_PER_TILE_H16 = 145 +SC_QZ3_QUAD_PER_TILE_H0 = 146 +SC_QZ3_QUAD_PER_TILE_H1 = 147 +SC_QZ3_QUAD_PER_TILE_H2 = 148 +SC_QZ3_QUAD_PER_TILE_H3 = 149 +SC_QZ3_QUAD_PER_TILE_H4 = 150 +SC_QZ3_QUAD_PER_TILE_H5 = 151 +SC_QZ3_QUAD_PER_TILE_H6 = 152 +SC_QZ3_QUAD_PER_TILE_H7 = 153 +SC_QZ3_QUAD_PER_TILE_H8 = 154 +SC_QZ3_QUAD_PER_TILE_H9 = 155 +SC_QZ3_QUAD_PER_TILE_H10 = 156 +SC_QZ3_QUAD_PER_TILE_H11 = 157 +SC_QZ3_QUAD_PER_TILE_H12 = 158 +SC_QZ3_QUAD_PER_TILE_H13 = 159 +SC_QZ3_QUAD_PER_TILE_H14 = 160 +SC_QZ3_QUAD_PER_TILE_H15 = 161 +SC_QZ3_QUAD_PER_TILE_H16 = 162 +SC_QZ0_QUAD_COUNT = 163 +SC_QZ1_QUAD_COUNT = 164 +SC_QZ2_QUAD_COUNT = 165 +SC_QZ3_QUAD_COUNT = 166 +SC_P0_HIZ_TILE_COUNT = 167 +SC_P1_HIZ_TILE_COUNT = 168 +SC_P2_HIZ_TILE_COUNT = 169 +SC_P3_HIZ_TILE_COUNT = 170 +SC_P0_HIZ_QUAD_PER_TILE_H0 = 171 +SC_P0_HIZ_QUAD_PER_TILE_H1 = 172 +SC_P0_HIZ_QUAD_PER_TILE_H2 = 173 +SC_P0_HIZ_QUAD_PER_TILE_H3 = 174 +SC_P0_HIZ_QUAD_PER_TILE_H4 = 175 +SC_P0_HIZ_QUAD_PER_TILE_H5 = 176 +SC_P0_HIZ_QUAD_PER_TILE_H6 = 177 +SC_P0_HIZ_QUAD_PER_TILE_H7 = 178 +SC_P0_HIZ_QUAD_PER_TILE_H8 = 179 +SC_P0_HIZ_QUAD_PER_TILE_H9 = 180 +SC_P0_HIZ_QUAD_PER_TILE_H10 = 181 +SC_P0_HIZ_QUAD_PER_TILE_H11 = 182 +SC_P0_HIZ_QUAD_PER_TILE_H12 = 183 +SC_P0_HIZ_QUAD_PER_TILE_H13 = 184 +SC_P0_HIZ_QUAD_PER_TILE_H14 = 185 +SC_P0_HIZ_QUAD_PER_TILE_H15 = 186 +SC_P0_HIZ_QUAD_PER_TILE_H16 = 187 +SC_P1_HIZ_QUAD_PER_TILE_H0 = 188 +SC_P1_HIZ_QUAD_PER_TILE_H1 = 189 +SC_P1_HIZ_QUAD_PER_TILE_H2 = 190 +SC_P1_HIZ_QUAD_PER_TILE_H3 = 191 +SC_P1_HIZ_QUAD_PER_TILE_H4 = 192 +SC_P1_HIZ_QUAD_PER_TILE_H5 = 193 +SC_P1_HIZ_QUAD_PER_TILE_H6 = 194 +SC_P1_HIZ_QUAD_PER_TILE_H7 = 195 +SC_P1_HIZ_QUAD_PER_TILE_H8 = 196 +SC_P1_HIZ_QUAD_PER_TILE_H9 = 197 +SC_P1_HIZ_QUAD_PER_TILE_H10 = 198 +SC_P1_HIZ_QUAD_PER_TILE_H11 = 199 +SC_P1_HIZ_QUAD_PER_TILE_H12 = 200 +SC_P1_HIZ_QUAD_PER_TILE_H13 = 201 +SC_P1_HIZ_QUAD_PER_TILE_H14 = 202 +SC_P1_HIZ_QUAD_PER_TILE_H15 = 203 +SC_P1_HIZ_QUAD_PER_TILE_H16 = 204 +SC_P2_HIZ_QUAD_PER_TILE_H0 = 205 +SC_P2_HIZ_QUAD_PER_TILE_H1 = 206 +SC_P2_HIZ_QUAD_PER_TILE_H2 = 207 +SC_P2_HIZ_QUAD_PER_TILE_H3 = 208 +SC_P2_HIZ_QUAD_PER_TILE_H4 = 209 +SC_P2_HIZ_QUAD_PER_TILE_H5 = 210 +SC_P2_HIZ_QUAD_PER_TILE_H6 = 211 +SC_P2_HIZ_QUAD_PER_TILE_H7 = 212 +SC_P2_HIZ_QUAD_PER_TILE_H8 = 213 +SC_P2_HIZ_QUAD_PER_TILE_H9 = 214 +SC_P2_HIZ_QUAD_PER_TILE_H10 = 215 +SC_P2_HIZ_QUAD_PER_TILE_H11 = 216 +SC_P2_HIZ_QUAD_PER_TILE_H12 = 217 +SC_P2_HIZ_QUAD_PER_TILE_H13 = 218 +SC_P2_HIZ_QUAD_PER_TILE_H14 = 219 +SC_P2_HIZ_QUAD_PER_TILE_H15 = 220 +SC_P2_HIZ_QUAD_PER_TILE_H16 = 221 +SC_P3_HIZ_QUAD_PER_TILE_H0 = 222 +SC_P3_HIZ_QUAD_PER_TILE_H1 = 223 +SC_P3_HIZ_QUAD_PER_TILE_H2 = 224 +SC_P3_HIZ_QUAD_PER_TILE_H3 = 225 +SC_P3_HIZ_QUAD_PER_TILE_H4 = 226 +SC_P3_HIZ_QUAD_PER_TILE_H5 = 227 +SC_P3_HIZ_QUAD_PER_TILE_H6 = 228 +SC_P3_HIZ_QUAD_PER_TILE_H7 = 229 +SC_P3_HIZ_QUAD_PER_TILE_H8 = 230 +SC_P3_HIZ_QUAD_PER_TILE_H9 = 231 +SC_P3_HIZ_QUAD_PER_TILE_H10 = 232 +SC_P3_HIZ_QUAD_PER_TILE_H11 = 233 +SC_P3_HIZ_QUAD_PER_TILE_H12 = 234 +SC_P3_HIZ_QUAD_PER_TILE_H13 = 235 +SC_P3_HIZ_QUAD_PER_TILE_H14 = 236 +SC_P3_HIZ_QUAD_PER_TILE_H15 = 237 +SC_P3_HIZ_QUAD_PER_TILE_H16 = 238 +SC_P0_HIZ_QUAD_COUNT = 239 +SC_P1_HIZ_QUAD_COUNT = 240 +SC_P2_HIZ_QUAD_COUNT = 241 +SC_P3_HIZ_QUAD_COUNT = 242 +SC_P0_DETAIL_QUAD_COUNT = 243 +SC_P1_DETAIL_QUAD_COUNT = 244 +SC_P2_DETAIL_QUAD_COUNT = 245 +SC_P3_DETAIL_QUAD_COUNT = 246 +SC_P0_DETAIL_QUAD_WITH_1_PIX = 247 +SC_P0_DETAIL_QUAD_WITH_2_PIX = 248 +SC_P0_DETAIL_QUAD_WITH_3_PIX = 249 +SC_P0_DETAIL_QUAD_WITH_4_PIX = 250 +SC_P1_DETAIL_QUAD_WITH_1_PIX = 251 +SC_P1_DETAIL_QUAD_WITH_2_PIX = 252 +SC_P1_DETAIL_QUAD_WITH_3_PIX = 253 +SC_P1_DETAIL_QUAD_WITH_4_PIX = 254 +SC_P2_DETAIL_QUAD_WITH_1_PIX = 255 +SC_P2_DETAIL_QUAD_WITH_2_PIX = 256 +SC_P2_DETAIL_QUAD_WITH_3_PIX = 257 +SC_P2_DETAIL_QUAD_WITH_4_PIX = 258 +SC_P3_DETAIL_QUAD_WITH_1_PIX = 259 +SC_P3_DETAIL_QUAD_WITH_2_PIX = 260 +SC_P3_DETAIL_QUAD_WITH_3_PIX = 261 +SC_P3_DETAIL_QUAD_WITH_4_PIX = 262 +SC_EARLYZ_QUAD_COUNT = 263 +SC_EARLYZ_QUAD_WITH_1_PIX = 264 +SC_EARLYZ_QUAD_WITH_2_PIX = 265 +SC_EARLYZ_QUAD_WITH_3_PIX = 266 +SC_EARLYZ_QUAD_WITH_4_PIX = 267 +SC_PKR_QUAD_PER_ROW_H1 = 268 +SC_PKR_QUAD_PER_ROW_H2 = 269 +SC_PKR_4X2_QUAD_SPLIT = 270 +SC_PKR_4X2_FILL_QUAD = 271 +SC_PKR_END_OF_VECTOR = 272 +SC_PKR_CONTROL_XFER = 273 +SC_PKR_DBHANG_FORCE_EOV = 274 +SC_REG_SCLK_BUSY = 275 +SC_GRP0_DYN_SCLK_BUSY = 276 +SC_GRP1_DYN_SCLK_BUSY = 277 +SC_GRP2_DYN_SCLK_BUSY = 278 +SC_GRP3_DYN_SCLK_BUSY = 279 +SC_GRP4_DYN_SCLK_BUSY = 280 +SC_PA0_SC_DATA_FIFO_RD = 281 +SC_PA0_SC_DATA_FIFO_WE = 282 +SC_PA1_SC_DATA_FIFO_RD = 283 +SC_PA1_SC_DATA_FIFO_WE = 284 +SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES = 285 +SC_PS_ARB_XFC_ONLY_PRIM_CYCLES = 286 +SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM = 287 +SC_PS_ARB_STALLED_FROM_BELOW = 288 +SC_PS_ARB_STARVED_FROM_ABOVE = 289 +SC_PS_ARB_SC_BUSY = 290 +SC_PS_ARB_PA_SC_BUSY = 291 +SC_PA2_SC_DATA_FIFO_RD = 292 +SC_PA2_SC_DATA_FIFO_WE = 293 +SC_PA3_SC_DATA_FIFO_RD = 294 +SC_PA3_SC_DATA_FIFO_WE = 295 +SC_PA_SC_DEALLOC_0_0_WE = 296 +SC_PA_SC_DEALLOC_0_1_WE = 297 +SC_PA_SC_DEALLOC_1_0_WE = 298 +SC_PA_SC_DEALLOC_1_1_WE = 299 +SC_PA_SC_DEALLOC_2_0_WE = 300 +SC_PA_SC_DEALLOC_2_1_WE = 301 +SC_PA_SC_DEALLOC_3_0_WE = 302 +SC_PA_SC_DEALLOC_3_1_WE = 303 +SC_PA0_SC_EOP_WE = 304 +SC_PA0_SC_EOPG_WE = 305 +SC_PA0_SC_EVENT_WE = 306 +SC_PA1_SC_EOP_WE = 307 +SC_PA1_SC_EOPG_WE = 308 +SC_PA1_SC_EVENT_WE = 309 +SC_PA2_SC_EOP_WE = 310 +SC_PA2_SC_EOPG_WE = 311 +SC_PA2_SC_EVENT_WE = 312 +SC_PA3_SC_EOP_WE = 313 +SC_PA3_SC_EOPG_WE = 314 +SC_PA3_SC_EVENT_WE = 315 +SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO = 316 +SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH = 317 +SC_PS_ARB_NULL_PRIM_BUBBLE_POP = 318 +SC_PS_ARB_EOP_POP_SYNC_POP = 319 +SC_PS_ARB_EVENT_SYNC_POP = 320 +SC_SC_PS_ENG_MULTICYCLE_BUBBLE = 321 +SC_PA0_SC_FPOV_WE = 322 +SC_PA1_SC_FPOV_WE = 323 +SC_PA2_SC_FPOV_WE = 324 +SC_PA3_SC_FPOV_WE = 325 +SC_PA0_SC_LPOV_WE = 326 +SC_PA1_SC_LPOV_WE = 327 +SC_PA2_SC_LPOV_WE = 328 +SC_PA3_SC_LPOV_WE = 329 +SC_SC_SPI_DEALLOC_0_0 = 330 +SC_SC_SPI_DEALLOC_0_1 = 331 +SC_SC_SPI_DEALLOC_0_2 = 332 +SC_SC_SPI_DEALLOC_1_0 = 333 +SC_SC_SPI_DEALLOC_1_1 = 334 +SC_SC_SPI_DEALLOC_1_2 = 335 +SC_SC_SPI_DEALLOC_2_0 = 336 +SC_SC_SPI_DEALLOC_2_1 = 337 +SC_SC_SPI_DEALLOC_2_2 = 338 +SC_SC_SPI_DEALLOC_3_0 = 339 +SC_SC_SPI_DEALLOC_3_1 = 340 +SC_SC_SPI_DEALLOC_3_2 = 341 +SC_SC_SPI_FPOV_0 = 342 +SC_SC_SPI_FPOV_1 = 343 +SC_SC_SPI_FPOV_2 = 344 +SC_SC_SPI_FPOV_3 = 345 +SC_SC_SPI_EVENT = 346 +SC_PS_TS_EVENT_FIFO_PUSH = 347 +SC_PS_TS_EVENT_FIFO_POP = 348 +SC_PS_CTX_DONE_FIFO_PUSH = 349 +SC_PS_CTX_DONE_FIFO_POP = 350 +SC_MULTICYCLE_BUBBLE_FREEZE = 351 +SC_EOP_SYNC_WINDOW = 352 +SC_PA0_SC_NULL_WE = 353 +SC_PA0_SC_NULL_DEALLOC_WE = 354 +SC_PA0_SC_DATA_FIFO_EOPG_RD = 355 +SC_PA0_SC_DATA_FIFO_EOP_RD = 356 +SC_PA0_SC_DEALLOC_0_RD = 357 +SC_PA0_SC_DEALLOC_1_RD = 358 +SC_PA1_SC_DATA_FIFO_EOPG_RD = 359 +SC_PA1_SC_DATA_FIFO_EOP_RD = 360 +SC_PA1_SC_DEALLOC_0_RD = 361 +SC_PA1_SC_DEALLOC_1_RD = 362 +SC_PA1_SC_NULL_WE = 363 +SC_PA1_SC_NULL_DEALLOC_WE = 364 +SC_PA2_SC_DATA_FIFO_EOPG_RD = 365 +SC_PA2_SC_DATA_FIFO_EOP_RD = 366 +SC_PA2_SC_DEALLOC_0_RD = 367 +SC_PA2_SC_DEALLOC_1_RD = 368 +SC_PA2_SC_NULL_WE = 369 +SC_PA2_SC_NULL_DEALLOC_WE = 370 +SC_PA3_SC_DATA_FIFO_EOPG_RD = 371 +SC_PA3_SC_DATA_FIFO_EOP_RD = 372 +SC_PA3_SC_DEALLOC_0_RD = 373 +SC_PA3_SC_DEALLOC_1_RD = 374 +SC_PA3_SC_NULL_WE = 375 +SC_PA3_SC_NULL_DEALLOC_WE = 376 +SC_PS_PA0_SC_FIFO_EMPTY = 377 +SC_PS_PA0_SC_FIFO_FULL = 378 +SC_PA0_PS_DATA_SEND = 379 +SC_PS_PA1_SC_FIFO_EMPTY = 380 +SC_PS_PA1_SC_FIFO_FULL = 381 +SC_PA1_PS_DATA_SEND = 382 +SC_PS_PA2_SC_FIFO_EMPTY = 383 +SC_PS_PA2_SC_FIFO_FULL = 384 +SC_PA2_PS_DATA_SEND = 385 +SC_PS_PA3_SC_FIFO_EMPTY = 386 +SC_PS_PA3_SC_FIFO_FULL = 387 +SC_PA3_PS_DATA_SEND = 388 +SC_BUSY_PROCESSING_MULTICYCLE_PRIM = 389 +SC_BUSY_CNT_NOT_ZERO = 390 +SC_BM_BUSY = 391 +SC_BACKEND_BUSY = 392 +SC_SCF_SCB_INTERFACE_BUSY = 393 +SC_SCB_BUSY = 394 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY = 395 +SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL = 396 +SC_PBB_BIN_HIST_NUM_PRIMS = 397 +SC_PBB_BATCH_HIST_NUM_PRIMS = 398 +SC_PBB_BIN_HIST_NUM_CONTEXTS = 399 +SC_PBB_BATCH_HIST_NUM_CONTEXTS = 400 +SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES = 401 +SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES = 402 +SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS = 403 +SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS = 404 +SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM = 405 +SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW = 406 +SC_PBB_BUSY = 407 +SC_PBB_BUSY_AND_RTR = 408 +SC_PBB_STALLS_PA_DUE_TO_NO_TILES = 409 +SC_PBB_NUM_BINS = 410 +SC_PBB_END_OF_BIN = 411 +SC_PBB_END_OF_BATCH = 412 +SC_PBB_PRIMBIN_PROCESSED = 413 +SC_PBB_PRIM_ADDED_TO_BATCH = 414 +SC_PBB_NONBINNED_PRIM = 415 +SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB = 416 +SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB = 417 +SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION = 418 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW = 419 +SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN = 420 +SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE = 421 +SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE = 422 +SC_PBB_BATCH_BREAK_DUE_TO_PRIM = 423 +SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE = 424 +SC_PBB_BATCH_BREAK_DUE_TO_EVENT = 425 +SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT = 426 +SC_POPS_INTRA_WAVE_OVERLAPS = 427 +SC_POPS_FORCE_EOV = 428 +SC_PKR_QUAD_OVERLAP_NOT_FOUND_IN_WAVE_TABLE = 429 +SC_PKR_QUAD_OVERLAP_FOUND_IN_WAVE_TABLE = 430 +SC_PERFCNT_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SePairXsel' +SePairXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', + 4: 'RASTER_CONFIG_SE_PAIR_XSEL_128_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE = 3 +RASTER_CONFIG_SE_PAIR_XSEL_128_WIDE_TILE = 4 +SePairXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairYsel' +SePairYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', + 4: 'RASTER_CONFIG_SE_PAIR_YSEL_128_WIDE_TILE', +} +RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE = 3 +RASTER_CONFIG_SE_PAIR_YSEL_128_WIDE_TILE = 4 +SePairYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SePairMap' +SePairMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_PAIR_MAP_0', + 1: 'RASTER_CONFIG_SE_PAIR_MAP_1', + 2: 'RASTER_CONFIG_SE_PAIR_MAP_2', + 3: 'RASTER_CONFIG_SE_PAIR_MAP_3', +} +RASTER_CONFIG_SE_PAIR_MAP_0 = 0 +RASTER_CONFIG_SE_PAIR_MAP_1 = 1 +RASTER_CONFIG_SE_PAIR_MAP_2 = 2 +RASTER_CONFIG_SE_PAIR_MAP_3 = 3 +SePairMap = ctypes.c_uint32 # enum + +# values for enumeration 'SeXsel' +SeXsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', + 4: 'RASTER_CONFIG_SE_XSEL_128_WIDE_TILE', +} +RASTER_CONFIG_SE_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_XSEL_64_WIDE_TILE = 3 +RASTER_CONFIG_SE_XSEL_128_WIDE_TILE = 4 +SeXsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeYsel' +SeYsel__enumvalues = { + 0: 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', + 4: 'RASTER_CONFIG_SE_YSEL_128_WIDE_TILE', +} +RASTER_CONFIG_SE_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SE_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SE_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SE_YSEL_64_WIDE_TILE = 3 +RASTER_CONFIG_SE_YSEL_128_WIDE_TILE = 4 +SeYsel = ctypes.c_uint32 # enum + +# values for enumeration 'SeMap' +SeMap__enumvalues = { + 0: 'RASTER_CONFIG_SE_MAP_0', + 1: 'RASTER_CONFIG_SE_MAP_1', + 2: 'RASTER_CONFIG_SE_MAP_2', + 3: 'RASTER_CONFIG_SE_MAP_3', +} +RASTER_CONFIG_SE_MAP_0 = 0 +RASTER_CONFIG_SE_MAP_1 = 1 +RASTER_CONFIG_SE_MAP_2 = 2 +RASTER_CONFIG_SE_MAP_3 = 3 +SeMap = ctypes.c_uint32 # enum + +# values for enumeration 'ScXsel' +ScXsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_XSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_XSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_XSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_XSEL_64_WIDE_TILE = 3 +ScXsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScYsel' +ScYsel__enumvalues = { + 0: 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', + 1: 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 2: 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 3: 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', +} +RASTER_CONFIG_SC_YSEL_8_WIDE_TILE = 0 +RASTER_CONFIG_SC_YSEL_16_WIDE_TILE = 1 +RASTER_CONFIG_SC_YSEL_32_WIDE_TILE = 2 +RASTER_CONFIG_SC_YSEL_64_WIDE_TILE = 3 +ScYsel = ctypes.c_uint32 # enum + +# values for enumeration 'ScMap' +ScMap__enumvalues = { + 0: 'RASTER_CONFIG_SC_MAP_0', + 1: 'RASTER_CONFIG_SC_MAP_1', + 2: 'RASTER_CONFIG_SC_MAP_2', + 3: 'RASTER_CONFIG_SC_MAP_3', +} +RASTER_CONFIG_SC_MAP_0 = 0 +RASTER_CONFIG_SC_MAP_1 = 1 +RASTER_CONFIG_SC_MAP_2 = 2 +RASTER_CONFIG_SC_MAP_3 = 3 +ScMap = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel2' +PkrXsel2__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL2_0', + 1: 'RASTER_CONFIG_PKR_XSEL2_1', + 2: 'RASTER_CONFIG_PKR_XSEL2_2', + 3: 'RASTER_CONFIG_PKR_XSEL2_3', +} +RASTER_CONFIG_PKR_XSEL2_0 = 0 +RASTER_CONFIG_PKR_XSEL2_1 = 1 +RASTER_CONFIG_PKR_XSEL2_2 = 2 +RASTER_CONFIG_PKR_XSEL2_3 = 3 +PkrXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'PkrXsel' +PkrXsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_XSEL_0', + 1: 'RASTER_CONFIG_PKR_XSEL_1', + 2: 'RASTER_CONFIG_PKR_XSEL_2', + 3: 'RASTER_CONFIG_PKR_XSEL_3', +} +RASTER_CONFIG_PKR_XSEL_0 = 0 +RASTER_CONFIG_PKR_XSEL_1 = 1 +RASTER_CONFIG_PKR_XSEL_2 = 2 +RASTER_CONFIG_PKR_XSEL_3 = 3 +PkrXsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrYsel' +PkrYsel__enumvalues = { + 0: 'RASTER_CONFIG_PKR_YSEL_0', + 1: 'RASTER_CONFIG_PKR_YSEL_1', + 2: 'RASTER_CONFIG_PKR_YSEL_2', + 3: 'RASTER_CONFIG_PKR_YSEL_3', +} +RASTER_CONFIG_PKR_YSEL_0 = 0 +RASTER_CONFIG_PKR_YSEL_1 = 1 +RASTER_CONFIG_PKR_YSEL_2 = 2 +RASTER_CONFIG_PKR_YSEL_3 = 3 +PkrYsel = ctypes.c_uint32 # enum + +# values for enumeration 'PkrMap' +PkrMap__enumvalues = { + 0: 'RASTER_CONFIG_PKR_MAP_0', + 1: 'RASTER_CONFIG_PKR_MAP_1', + 2: 'RASTER_CONFIG_PKR_MAP_2', + 3: 'RASTER_CONFIG_PKR_MAP_3', +} +RASTER_CONFIG_PKR_MAP_0 = 0 +RASTER_CONFIG_PKR_MAP_1 = 1 +RASTER_CONFIG_PKR_MAP_2 = 2 +RASTER_CONFIG_PKR_MAP_3 = 3 +PkrMap = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel' +RbXsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL_0', + 1: 'RASTER_CONFIG_RB_XSEL_1', +} +RASTER_CONFIG_RB_XSEL_0 = 0 +RASTER_CONFIG_RB_XSEL_1 = 1 +RbXsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbYsel' +RbYsel__enumvalues = { + 0: 'RASTER_CONFIG_RB_YSEL_0', + 1: 'RASTER_CONFIG_RB_YSEL_1', +} +RASTER_CONFIG_RB_YSEL_0 = 0 +RASTER_CONFIG_RB_YSEL_1 = 1 +RbYsel = ctypes.c_uint32 # enum + +# values for enumeration 'RbXsel2' +RbXsel2__enumvalues = { + 0: 'RASTER_CONFIG_RB_XSEL2_0', + 1: 'RASTER_CONFIG_RB_XSEL2_1', + 2: 'RASTER_CONFIG_RB_XSEL2_2', + 3: 'RASTER_CONFIG_RB_XSEL2_3', +} +RASTER_CONFIG_RB_XSEL2_0 = 0 +RASTER_CONFIG_RB_XSEL2_1 = 1 +RASTER_CONFIG_RB_XSEL2_2 = 2 +RASTER_CONFIG_RB_XSEL2_3 = 3 +RbXsel2 = ctypes.c_uint32 # enum + +# values for enumeration 'RbMap' +RbMap__enumvalues = { + 0: 'RASTER_CONFIG_RB_MAP_0', + 1: 'RASTER_CONFIG_RB_MAP_1', + 2: 'RASTER_CONFIG_RB_MAP_2', + 3: 'RASTER_CONFIG_RB_MAP_3', +} +RASTER_CONFIG_RB_MAP_0 = 0 +RASTER_CONFIG_RB_MAP_1 = 1 +RASTER_CONFIG_RB_MAP_2 = 2 +RASTER_CONFIG_RB_MAP_3 = 3 +RbMap = ctypes.c_uint32 # enum + +# values for enumeration 'BinningMode' +BinningMode__enumvalues = { + 0: 'BINNING_ALLOWED', + 1: 'FORCE_BINNING_ON', + 2: 'DISABLE_BINNING_USE_NEW_SC', + 3: 'DISABLE_BINNING_USE_LEGACY_SC', +} +BINNING_ALLOWED = 0 +FORCE_BINNING_ON = 1 +DISABLE_BINNING_USE_NEW_SC = 2 +DISABLE_BINNING_USE_LEGACY_SC = 3 +BinningMode = ctypes.c_uint32 # enum + +# values for enumeration 'BinEventCntl' +BinEventCntl__enumvalues = { + 0: 'BINNER_BREAK_BATCH', + 1: 'BINNER_PIPELINE', + 2: 'BINNER_DROP_ASSERT', +} +BINNER_BREAK_BATCH = 0 +BINNER_PIPELINE = 1 +BINNER_DROP_ASSERT = 2 +BinEventCntl = ctypes.c_uint32 # enum + +# values for enumeration 'CovToShaderSel' +CovToShaderSel__enumvalues = { + 0: 'INPUT_COVERAGE', + 1: 'INPUT_INNER_COVERAGE', + 2: 'INPUT_DEPTH_COVERAGE', + 3: 'RAW', +} +INPUT_COVERAGE = 0 +INPUT_INNER_COVERAGE = 1 +INPUT_DEPTH_COVERAGE = 2 +RAW = 3 +CovToShaderSel = ctypes.c_uint32 # enum + +# values for enumeration 'RMIPerfSel' +RMIPerfSel__enumvalues = { + 0: 'RMI_PERF_SEL_NONE', + 1: 'RMI_PERF_SEL_BUSY', + 2: 'RMI_PERF_SEL_REG_CLK_VLD', + 3: 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', + 4: 'RMI_PERF_SEL_DYN_CLK_RB_VLD', + 5: 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 6: 'RMI_PERF_SEL_PERF_WINDOW', + 7: 'RMI_PERF_SEL_EVENT_SEND', + 8: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0', + 9: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1', + 10: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2', + 11: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3', + 12: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4', + 13: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5', + 14: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6', + 15: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7', + 16: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8', + 17: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9', + 18: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10', + 19: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11', + 20: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12', + 21: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13', + 22: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14', + 23: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15', + 24: 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL', + 25: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0', + 26: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1', + 27: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2', + 28: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3', + 29: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4', + 30: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5', + 31: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6', + 32: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7', + 33: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8', + 34: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9', + 35: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10', + 36: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11', + 37: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12', + 38: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13', + 39: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14', + 40: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15', + 41: 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL', + 42: 'RMI_PERF_SEL_UTCL1_TRANSLATION_MISS', + 43: 'RMI_PERF_SEL_UTCL1_PERMISSION_MISS', + 44: 'RMI_PERF_SEL_UTCL1_REQUEST', + 45: 'RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 46: 'RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 47: 'RMI_PERF_SEL_UTCL1_LFIFO_FULL', + 48: 'RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 49: 'RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 50: 'RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 51: 'RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL', + 52: 'RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS', + 53: 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 54: 'RMI_PERF_SEL_RB_RMI_WRREQ_BUSY', + 55: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 56: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 57: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 58: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 59: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 60: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 61: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 62: 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 63: 'RMI_PERF_SEL_RB_RMI_WRREQ_INFLIGHT_ALL_ORONE_CID', + 64: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 65: 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 66: 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 67: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 68: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 69: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 70: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 71: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 72: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 73: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 74: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 75: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 76: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 77: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 78: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 79: 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 80: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 81: 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 82: 'RMI_PERF_SEL_RB_RMI_RDREQ_BUSY', + 83: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 84: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 85: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 86: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 87: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 88: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 89: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 90: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 91: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 92: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 93: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 94: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 95: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 96: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 97: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 98: 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 99: 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 100: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 101: 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 102: 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 103: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 104: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 105: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 106: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 107: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 108: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 109: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 110: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 111: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 112: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 113: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 114: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 115: 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 116: 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 117: 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 118: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 119: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 120: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 121: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 122: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 123: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 124: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 125: 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 126: 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 127: 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', + 128: 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 129: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 130: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 131: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 132: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 133: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 134: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 135: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 136: 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 137: 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 138: 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 139: 'RMI_PERF_SEL_UTCL1_BUSY', + 140: 'RMI_PERF_SEL_RMI_UTC_REQ', + 141: 'RMI_PERF_SEL_RMI_UTC_BUSY', + 142: 'RMI_PERF_SEL_UTCL1_UTCL2_REQ', + 143: 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY', + 144: 'RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT', + 145: 'RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT', + 146: 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT', + 147: 'RMI_PERF_SEL_XNACK_FIFO_NUM_USED', + 148: 'RMI_PERF_SEL_LAT_FIFO_NUM_USED', + 149: 'RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ', + 150: 'RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ', + 151: 'RMI_PERF_SEL_XNACK_FIFO_FULL', + 152: 'RMI_PERF_SEL_XNACK_FIFO_BUSY', + 153: 'RMI_PERF_SEL_LAT_FIFO_FULL', + 154: 'RMI_PERF_SEL_SKID_FIFO_DEPTH', + 155: 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 156: 'RMI_PERF_SEL_PRT_FIFO_NUM_USED', + 157: 'RMI_PERF_SEL_PRT_FIFO_REQ', + 158: 'RMI_PERF_SEL_PRT_FIFO_BUSY', + 159: 'RMI_PERF_SEL_TCIW_REQ', + 160: 'RMI_PERF_SEL_TCIW_BUSY', + 161: 'RMI_PERF_SEL_SKID_FIFO_REQ', + 162: 'RMI_PERF_SEL_SKID_FIFO_BUSY', + 163: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0', + 164: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1', + 165: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2', + 166: 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3', + 167: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR', + 168: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR', + 169: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB', + 170: 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB', + 171: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 172: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 173: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 174: 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 175: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR', + 176: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR', + 177: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB', + 178: 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB', + 179: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR', + 180: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR', + 181: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB', + 182: 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB', + 183: 'RMI_PERF_SEL_POP_DEMUX_RTS_RTR', + 184: 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTR', + 185: 'RMI_PERF_SEL_POP_DEMUX_RTS_RTRB', + 186: 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB', + 187: 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR', + 188: 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR', + 189: 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB', + 190: 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB', + 191: 'RMI_PERF_SEL_UTC_POP_RTS_RTR', + 192: 'RMI_PERF_SEL_UTC_POP_RTSB_RTR', + 193: 'RMI_PERF_SEL_UTC_POP_RTS_RTRB', + 194: 'RMI_PERF_SEL_UTC_POP_RTSB_RTRB', + 195: 'RMI_PERF_SEL_POP_XNACK_RTS_RTR', + 196: 'RMI_PERF_SEL_POP_XNACK_RTSB_RTR', + 197: 'RMI_PERF_SEL_POP_XNACK_RTS_RTRB', + 198: 'RMI_PERF_SEL_POP_XNACK_RTSB_RTRB', + 199: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR', + 200: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR', + 201: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB', + 202: 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB', + 203: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR', + 204: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR', + 205: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB', + 206: 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB', + 207: 'RMI_PERF_SEL_SKID_FIFO_IN_RTS', + 208: 'RMI_PERF_SEL_SKID_FIFO_IN_RTSB', + 209: 'RMI_PERF_SEL_SKID_FIFO_OUT_RTS', + 210: 'RMI_PERF_SEL_SKID_FIFO_OUT_RTSB', + 211: 'RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR', + 212: 'RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR', + 213: 'RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR', + 214: 'RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR', + 215: 'RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR', + 216: 'RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR', + 217: 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 218: 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 219: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 220: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 221: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 222: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 223: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 224: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 225: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 226: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 227: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 228: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0', + 229: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1', + 230: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2', + 231: 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3', +} +RMI_PERF_SEL_NONE = 0 +RMI_PERF_SEL_BUSY = 1 +RMI_PERF_SEL_REG_CLK_VLD = 2 +RMI_PERF_SEL_DYN_CLK_CMN_VLD = 3 +RMI_PERF_SEL_DYN_CLK_RB_VLD = 4 +RMI_PERF_SEL_DYN_CLK_PERF_VLD = 5 +RMI_PERF_SEL_PERF_WINDOW = 6 +RMI_PERF_SEL_EVENT_SEND = 7 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0 = 8 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1 = 9 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2 = 10 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3 = 11 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4 = 12 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5 = 13 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6 = 14 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7 = 15 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8 = 16 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9 = 17 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10 = 18 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11 = 19 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12 = 20 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13 = 21 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14 = 22 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15 = 23 +RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL = 24 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0 = 25 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1 = 26 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2 = 27 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3 = 28 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4 = 29 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5 = 30 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6 = 31 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7 = 32 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8 = 33 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9 = 34 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10 = 35 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11 = 36 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12 = 37 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13 = 38 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14 = 39 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15 = 40 +RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL = 41 +RMI_PERF_SEL_UTCL1_TRANSLATION_MISS = 42 +RMI_PERF_SEL_UTCL1_PERMISSION_MISS = 43 +RMI_PERF_SEL_UTCL1_REQUEST = 44 +RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX = 45 +RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT = 46 +RMI_PERF_SEL_UTCL1_LFIFO_FULL = 47 +RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES = 48 +RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS = 49 +RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL = 50 +RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL = 51 +RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS = 52 +RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID = 53 +RMI_PERF_SEL_RB_RMI_WRREQ_BUSY = 54 +RMI_PERF_SEL_RB_RMI_WRREQ_CID0 = 55 +RMI_PERF_SEL_RB_RMI_WRREQ_CID1 = 56 +RMI_PERF_SEL_RB_RMI_WRREQ_CID2 = 57 +RMI_PERF_SEL_RB_RMI_WRREQ_CID3 = 58 +RMI_PERF_SEL_RB_RMI_WRREQ_CID4 = 59 +RMI_PERF_SEL_RB_RMI_WRREQ_CID5 = 60 +RMI_PERF_SEL_RB_RMI_WRREQ_CID6 = 61 +RMI_PERF_SEL_RB_RMI_WRREQ_CID7 = 62 +RMI_PERF_SEL_RB_RMI_WRREQ_INFLIGHT_ALL_ORONE_CID = 63 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID = 64 +RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID = 65 +RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY = 66 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID = 67 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0 = 68 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1 = 69 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2 = 70 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3 = 71 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4 = 72 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5 = 73 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6 = 74 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7 = 75 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0 = 76 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1 = 77 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2 = 78 +RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3 = 79 +RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID = 80 +RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID = 81 +RMI_PERF_SEL_RB_RMI_RDREQ_BUSY = 82 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0 = 83 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1 = 84 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2 = 85 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3 = 86 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4 = 87 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5 = 88 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6 = 89 +RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7 = 90 +RMI_PERF_SEL_RB_RMI_RDREQ_CID0 = 91 +RMI_PERF_SEL_RB_RMI_RDREQ_CID1 = 92 +RMI_PERF_SEL_RB_RMI_RDREQ_CID2 = 93 +RMI_PERF_SEL_RB_RMI_RDREQ_CID3 = 94 +RMI_PERF_SEL_RB_RMI_RDREQ_CID4 = 95 +RMI_PERF_SEL_RB_RMI_RDREQ_CID5 = 96 +RMI_PERF_SEL_RB_RMI_RDREQ_CID6 = 97 +RMI_PERF_SEL_RB_RMI_RDREQ_CID7 = 98 +RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID = 99 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID = 100 +RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID = 101 +RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY = 102 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID = 103 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0 = 104 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1 = 105 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2 = 106 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3 = 107 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4 = 108 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5 = 109 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6 = 110 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7 = 111 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0 = 112 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1 = 113 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2 = 114 +RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3 = 115 +RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID = 116 +RMI_PERF_SEL_RMI_TC_REQ_BUSY = 117 +RMI_PERF_SEL_RMI_TC_WRREQ_CID0 = 118 +RMI_PERF_SEL_RMI_TC_WRREQ_CID1 = 119 +RMI_PERF_SEL_RMI_TC_WRREQ_CID2 = 120 +RMI_PERF_SEL_RMI_TC_WRREQ_CID3 = 121 +RMI_PERF_SEL_RMI_TC_WRREQ_CID4 = 122 +RMI_PERF_SEL_RMI_TC_WRREQ_CID5 = 123 +RMI_PERF_SEL_RMI_TC_WRREQ_CID6 = 124 +RMI_PERF_SEL_RMI_TC_WRREQ_CID7 = 125 +RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID = 126 +RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID = 127 +RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID = 128 +RMI_PERF_SEL_RMI_TC_RDREQ_CID0 = 129 +RMI_PERF_SEL_RMI_TC_RDREQ_CID1 = 130 +RMI_PERF_SEL_RMI_TC_RDREQ_CID2 = 131 +RMI_PERF_SEL_RMI_TC_RDREQ_CID3 = 132 +RMI_PERF_SEL_RMI_TC_RDREQ_CID4 = 133 +RMI_PERF_SEL_RMI_TC_RDREQ_CID5 = 134 +RMI_PERF_SEL_RMI_TC_RDREQ_CID6 = 135 +RMI_PERF_SEL_RMI_TC_RDREQ_CID7 = 136 +RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID = 137 +RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID = 138 +RMI_PERF_SEL_UTCL1_BUSY = 139 +RMI_PERF_SEL_RMI_UTC_REQ = 140 +RMI_PERF_SEL_RMI_UTC_BUSY = 141 +RMI_PERF_SEL_UTCL1_UTCL2_REQ = 142 +RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY = 143 +RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT = 144 +RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT = 145 +RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT = 146 +RMI_PERF_SEL_XNACK_FIFO_NUM_USED = 147 +RMI_PERF_SEL_LAT_FIFO_NUM_USED = 148 +RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ = 149 +RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ = 150 +RMI_PERF_SEL_XNACK_FIFO_FULL = 151 +RMI_PERF_SEL_XNACK_FIFO_BUSY = 152 +RMI_PERF_SEL_LAT_FIFO_FULL = 153 +RMI_PERF_SEL_SKID_FIFO_DEPTH = 154 +RMI_PERF_SEL_TCIW_INFLIGHT_COUNT = 155 +RMI_PERF_SEL_PRT_FIFO_NUM_USED = 156 +RMI_PERF_SEL_PRT_FIFO_REQ = 157 +RMI_PERF_SEL_PRT_FIFO_BUSY = 158 +RMI_PERF_SEL_TCIW_REQ = 159 +RMI_PERF_SEL_TCIW_BUSY = 160 +RMI_PERF_SEL_SKID_FIFO_REQ = 161 +RMI_PERF_SEL_SKID_FIFO_BUSY = 162 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0 = 163 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1 = 164 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2 = 165 +RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3 = 166 +RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR = 167 +RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR = 168 +RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB = 169 +RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB = 170 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR = 171 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR = 172 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB = 173 +RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB = 174 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR = 175 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR = 176 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB = 177 +RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB = 178 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR = 179 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR = 180 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB = 181 +RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB = 182 +RMI_PERF_SEL_POP_DEMUX_RTS_RTR = 183 +RMI_PERF_SEL_POP_DEMUX_RTSB_RTR = 184 +RMI_PERF_SEL_POP_DEMUX_RTS_RTRB = 185 +RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB = 186 +RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR = 187 +RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR = 188 +RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB = 189 +RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB = 190 +RMI_PERF_SEL_UTC_POP_RTS_RTR = 191 +RMI_PERF_SEL_UTC_POP_RTSB_RTR = 192 +RMI_PERF_SEL_UTC_POP_RTS_RTRB = 193 +RMI_PERF_SEL_UTC_POP_RTSB_RTRB = 194 +RMI_PERF_SEL_POP_XNACK_RTS_RTR = 195 +RMI_PERF_SEL_POP_XNACK_RTSB_RTR = 196 +RMI_PERF_SEL_POP_XNACK_RTS_RTRB = 197 +RMI_PERF_SEL_POP_XNACK_RTSB_RTRB = 198 +RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR = 199 +RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR = 200 +RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB = 201 +RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB = 202 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR = 203 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR = 204 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB = 205 +RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB = 206 +RMI_PERF_SEL_SKID_FIFO_IN_RTS = 207 +RMI_PERF_SEL_SKID_FIFO_IN_RTSB = 208 +RMI_PERF_SEL_SKID_FIFO_OUT_RTS = 209 +RMI_PERF_SEL_SKID_FIFO_OUT_RTSB = 210 +RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR = 211 +RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR = 212 +RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR = 213 +RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR = 214 +RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR = 215 +RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR = 216 +RMI_PERF_SEL_REORDER_FIFO_REQ = 217 +RMI_PERF_SEL_REORDER_FIFO_BUSY = 218 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID = 219 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0 = 220 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1 = 221 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2 = 222 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3 = 223 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4 = 224 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5 = 225 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6 = 226 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7 = 227 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0 = 228 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1 = 229 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2 = 230 +RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3 = 231 +RMIPerfSel = ctypes.c_uint32 # enum + +# values for enumeration 'IH_PERF_SEL' +IH_PERF_SEL__enumvalues = { + 0: 'IH_PERF_SEL_CYCLE', + 1: 'IH_PERF_SEL_IDLE', + 2: 'IH_PERF_SEL_INPUT_IDLE', + 3: 'IH_PERF_SEL_BUFFER_IDLE', + 4: 'IH_PERF_SEL_RB0_FULL', + 5: 'IH_PERF_SEL_RB0_OVERFLOW', + 6: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 7: 'IH_PERF_SEL_RB0_WPTR_WRAP', + 8: 'IH_PERF_SEL_RB0_RPTR_WRAP', + 9: 'IH_PERF_SEL_MC_WR_IDLE', + 10: 'IH_PERF_SEL_MC_WR_COUNT', + 11: 'IH_PERF_SEL_MC_WR_STALL', + 12: 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 13: 'IH_PERF_SEL_MC_WR_CLEAN_STALL', + 14: 'IH_PERF_SEL_BIF_LINE0_RISING', + 15: 'IH_PERF_SEL_BIF_LINE0_FALLING', + 16: 'IH_PERF_SEL_RB1_FULL', + 17: 'IH_PERF_SEL_RB1_OVERFLOW', + 18: 'Reserved18', + 19: 'IH_PERF_SEL_RB1_WPTR_WRAP', + 20: 'IH_PERF_SEL_RB1_RPTR_WRAP', + 21: 'IH_PERF_SEL_RB2_FULL', + 22: 'IH_PERF_SEL_RB2_OVERFLOW', + 23: 'Reserved23', + 24: 'IH_PERF_SEL_RB2_WPTR_WRAP', + 25: 'IH_PERF_SEL_RB2_RPTR_WRAP', + 26: 'Reserved26', + 27: 'Reserved27', + 28: 'Reserved28', + 29: 'Reserved29', + 30: 'IH_PERF_SEL_RB0_FULL_VF0', + 31: 'IH_PERF_SEL_RB0_FULL_VF1', + 32: 'IH_PERF_SEL_RB0_FULL_VF2', + 33: 'IH_PERF_SEL_RB0_FULL_VF3', + 34: 'IH_PERF_SEL_RB0_FULL_VF4', + 35: 'IH_PERF_SEL_RB0_FULL_VF5', + 36: 'IH_PERF_SEL_RB0_FULL_VF6', + 37: 'IH_PERF_SEL_RB0_FULL_VF7', + 38: 'IH_PERF_SEL_RB0_FULL_VF8', + 39: 'IH_PERF_SEL_RB0_FULL_VF9', + 40: 'IH_PERF_SEL_RB0_FULL_VF10', + 41: 'IH_PERF_SEL_RB0_FULL_VF11', + 42: 'IH_PERF_SEL_RB0_FULL_VF12', + 43: 'IH_PERF_SEL_RB0_FULL_VF13', + 44: 'IH_PERF_SEL_RB0_FULL_VF14', + 45: 'IH_PERF_SEL_RB0_FULL_VF15', + 46: 'IH_PERF_SEL_RB0_OVERFLOW_VF0', + 47: 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 48: 'IH_PERF_SEL_RB0_OVERFLOW_VF2', + 49: 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 50: 'IH_PERF_SEL_RB0_OVERFLOW_VF4', + 51: 'IH_PERF_SEL_RB0_OVERFLOW_VF5', + 52: 'IH_PERF_SEL_RB0_OVERFLOW_VF6', + 53: 'IH_PERF_SEL_RB0_OVERFLOW_VF7', + 54: 'IH_PERF_SEL_RB0_OVERFLOW_VF8', + 55: 'IH_PERF_SEL_RB0_OVERFLOW_VF9', + 56: 'IH_PERF_SEL_RB0_OVERFLOW_VF10', + 57: 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 58: 'IH_PERF_SEL_RB0_OVERFLOW_VF12', + 59: 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 60: 'IH_PERF_SEL_RB0_OVERFLOW_VF14', + 61: 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 62: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 63: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 64: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 65: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 66: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 67: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 68: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 69: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 70: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 71: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', + 72: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 73: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 74: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 75: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 76: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 77: 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 78: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', + 79: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 80: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 81: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', + 82: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 83: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', + 84: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 85: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', + 86: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 87: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', + 88: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 89: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 90: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 91: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 92: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 93: 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', + 94: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', + 95: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', + 96: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 97: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', + 98: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 99: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', + 100: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 101: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', + 102: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 103: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', + 104: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 105: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 106: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 107: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 108: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 109: 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', + 110: 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 111: 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 112: 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 113: 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 114: 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 115: 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 116: 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 117: 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 118: 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 119: 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', + 120: 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 121: 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 122: 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 123: 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 124: 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 125: 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 126: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 127: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 128: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 129: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 130: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 131: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 132: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 133: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 134: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 135: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 136: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 137: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 138: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 139: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 140: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 141: 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 142: 'Reserved142', + 143: 'Reserved143', + 144: 'Reserved144', + 145: 'Reserved145', + 146: 'Reserved146', + 147: 'Reserved147', + 148: 'Reserved148', + 149: 'Reserved149', + 150: 'IH_PERF_SEL_CLIENT0_INT', + 151: 'IH_PERF_SEL_CLIENT1_INT', + 152: 'IH_PERF_SEL_CLIENT2_INT', + 153: 'IH_PERF_SEL_CLIENT3_INT', + 154: 'IH_PERF_SEL_CLIENT4_INT', + 155: 'IH_PERF_SEL_CLIENT5_INT', + 156: 'IH_PERF_SEL_CLIENT6_INT', + 157: 'IH_PERF_SEL_CLIENT7_INT', + 158: 'IH_PERF_SEL_CLIENT8_INT', + 159: 'IH_PERF_SEL_CLIENT9_INT', + 160: 'IH_PERF_SEL_CLIENT10_INT', + 161: 'IH_PERF_SEL_CLIENT11_INT', + 162: 'IH_PERF_SEL_CLIENT12_INT', + 163: 'IH_PERF_SEL_CLIENT13_INT', + 164: 'IH_PERF_SEL_CLIENT14_INT', + 165: 'IH_PERF_SEL_CLIENT15_INT', + 166: 'IH_PERF_SEL_CLIENT16_INT', + 167: 'IH_PERF_SEL_CLIENT17_INT', + 168: 'IH_PERF_SEL_CLIENT18_INT', + 169: 'IH_PERF_SEL_CLIENT19_INT', + 170: 'IH_PERF_SEL_CLIENT20_INT', + 171: 'IH_PERF_SEL_CLIENT21_INT', + 172: 'IH_PERF_SEL_CLIENT22_INT', + 173: 'IH_PERF_SEL_CLIENT23_INT', + 174: 'IH_PERF_SEL_CLIENT24_INT', + 175: 'IH_PERF_SEL_CLIENT25_INT', + 176: 'IH_PERF_SEL_CLIENT26_INT', + 177: 'IH_PERF_SEL_CLIENT27_INT', + 178: 'IH_PERF_SEL_CLIENT28_INT', + 179: 'IH_PERF_SEL_CLIENT29_INT', + 180: 'IH_PERF_SEL_CLIENT30_INT', + 181: 'IH_PERF_SEL_CLIENT31_INT', + 182: 'Reserved182', + 183: 'Reserved183', + 184: 'Reserved184', + 185: 'Reserved185', + 186: 'Reserved186', + 187: 'Reserved187', + 188: 'Reserved188', + 189: 'Reserved189', + 190: 'Reserved190', + 191: 'Reserved191', + 192: 'Reserved192', + 193: 'Reserved193', + 194: 'Reserved194', + 195: 'Reserved195', + 196: 'Reserved196', + 197: 'Reserved197', + 198: 'Reserved198', + 199: 'Reserved199', + 200: 'Reserved200', + 201: 'Reserved201', + 202: 'Reserved202', + 203: 'Reserved203', + 204: 'Reserved204', + 205: 'Reserved205', + 206: 'Reserved206', + 207: 'Reserved207', + 208: 'Reserved208', + 209: 'Reserved209', + 210: 'Reserved210', + 211: 'Reserved211', + 212: 'Reserved212', + 213: 'Reserved213', + 214: 'Reserved214', + 215: 'Reserved215', + 216: 'Reserved216', + 217: 'Reserved217', + 218: 'Reserved218', + 219: 'Reserved219', + 220: 'IH_PERF_SEL_RB1_FULL_VF0', + 221: 'IH_PERF_SEL_RB1_FULL_VF1', + 222: 'IH_PERF_SEL_RB1_FULL_VF2', + 223: 'IH_PERF_SEL_RB1_FULL_VF3', + 224: 'IH_PERF_SEL_RB1_FULL_VF4', + 225: 'IH_PERF_SEL_RB1_FULL_VF5', + 226: 'IH_PERF_SEL_RB1_FULL_VF6', + 227: 'IH_PERF_SEL_RB1_FULL_VF7', + 228: 'IH_PERF_SEL_RB1_FULL_VF8', + 229: 'IH_PERF_SEL_RB1_FULL_VF9', + 230: 'IH_PERF_SEL_RB1_FULL_VF10', + 231: 'IH_PERF_SEL_RB1_FULL_VF11', + 232: 'IH_PERF_SEL_RB1_FULL_VF12', + 233: 'IH_PERF_SEL_RB1_FULL_VF13', + 234: 'IH_PERF_SEL_RB1_FULL_VF14', + 235: 'IH_PERF_SEL_RB1_FULL_VF15', + 236: 'IH_PERF_SEL_RB1_OVERFLOW_VF0', + 237: 'IH_PERF_SEL_RB1_OVERFLOW_VF1', + 238: 'IH_PERF_SEL_RB1_OVERFLOW_VF2', + 239: 'IH_PERF_SEL_RB1_OVERFLOW_VF3', + 240: 'IH_PERF_SEL_RB1_OVERFLOW_VF4', + 241: 'IH_PERF_SEL_RB1_OVERFLOW_VF5', + 242: 'IH_PERF_SEL_RB1_OVERFLOW_VF6', + 243: 'IH_PERF_SEL_RB1_OVERFLOW_VF7', + 244: 'IH_PERF_SEL_RB1_OVERFLOW_VF8', + 245: 'IH_PERF_SEL_RB1_OVERFLOW_VF9', + 246: 'IH_PERF_SEL_RB1_OVERFLOW_VF10', + 247: 'IH_PERF_SEL_RB1_OVERFLOW_VF11', + 248: 'IH_PERF_SEL_RB1_OVERFLOW_VF12', + 249: 'IH_PERF_SEL_RB1_OVERFLOW_VF13', + 250: 'IH_PERF_SEL_RB1_OVERFLOW_VF14', + 251: 'IH_PERF_SEL_RB1_OVERFLOW_VF15', + 252: 'Reserved252', + 253: 'Reserved253', + 254: 'Reserved254', + 255: 'Reserved255', + 256: 'Reserved256', + 257: 'Reserved257', + 258: 'Reserved258', + 259: 'Reserved259', + 260: 'Reserved260', + 261: 'Reserved261', + 262: 'Reserved262', + 263: 'Reserved263', + 264: 'Reserved264', + 265: 'Reserved265', + 266: 'Reserved266', + 267: 'Reserved267', + 268: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', + 269: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 270: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 271: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', + 272: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 273: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', + 274: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 275: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', + 276: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 277: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', + 278: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 279: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 280: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 281: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 282: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 283: 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', + 284: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', + 285: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', + 286: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 287: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', + 288: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 289: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', + 290: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 291: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', + 292: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 293: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', + 294: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 295: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 296: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 297: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 298: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 299: 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', + 300: 'Reserved300', + 301: 'Reserved301', + 302: 'Reserved302', + 303: 'Reserved303', + 304: 'Reserved304', + 305: 'Reserved305', + 306: 'Reserved306', + 307: 'Reserved307', + 308: 'Reserved308', + 309: 'Reserved309', + 310: 'Reserved310', + 311: 'Reserved311', + 312: 'Reserved312', + 313: 'Reserved313', + 314: 'Reserved314', + 315: 'Reserved315', + 316: 'Reserved316', + 317: 'Reserved317', + 318: 'Reserved318', + 319: 'Reserved319', + 320: 'Reserved320', + 321: 'Reserved321', + 322: 'Reserved322', + 323: 'Reserved323', + 324: 'Reserved324', + 325: 'Reserved325', + 326: 'Reserved326', + 327: 'Reserved327', + 328: 'Reserved328', + 329: 'Reserved329', + 330: 'Reserved330', + 331: 'Reserved331', + 332: 'IH_PERF_SEL_RB2_FULL_VF0', + 333: 'IH_PERF_SEL_RB2_FULL_VF1', + 334: 'IH_PERF_SEL_RB2_FULL_VF2', + 335: 'IH_PERF_SEL_RB2_FULL_VF3', + 336: 'IH_PERF_SEL_RB2_FULL_VF4', + 337: 'IH_PERF_SEL_RB2_FULL_VF5', + 338: 'IH_PERF_SEL_RB2_FULL_VF6', + 339: 'IH_PERF_SEL_RB2_FULL_VF7', + 340: 'IH_PERF_SEL_RB2_FULL_VF8', + 341: 'IH_PERF_SEL_RB2_FULL_VF9', + 342: 'IH_PERF_SEL_RB2_FULL_VF10', + 343: 'IH_PERF_SEL_RB2_FULL_VF11', + 344: 'IH_PERF_SEL_RB2_FULL_VF12', + 345: 'IH_PERF_SEL_RB2_FULL_VF13', + 346: 'IH_PERF_SEL_RB2_FULL_VF14', + 347: 'IH_PERF_SEL_RB2_FULL_VF15', + 348: 'IH_PERF_SEL_RB2_OVERFLOW_VF0', + 349: 'IH_PERF_SEL_RB2_OVERFLOW_VF1', + 350: 'IH_PERF_SEL_RB2_OVERFLOW_VF2', + 351: 'IH_PERF_SEL_RB2_OVERFLOW_VF3', + 352: 'IH_PERF_SEL_RB2_OVERFLOW_VF4', + 353: 'IH_PERF_SEL_RB2_OVERFLOW_VF5', + 354: 'IH_PERF_SEL_RB2_OVERFLOW_VF6', + 355: 'IH_PERF_SEL_RB2_OVERFLOW_VF7', + 356: 'IH_PERF_SEL_RB2_OVERFLOW_VF8', + 357: 'IH_PERF_SEL_RB2_OVERFLOW_VF9', + 358: 'IH_PERF_SEL_RB2_OVERFLOW_VF10', + 359: 'IH_PERF_SEL_RB2_OVERFLOW_VF11', + 360: 'IH_PERF_SEL_RB2_OVERFLOW_VF12', + 361: 'IH_PERF_SEL_RB2_OVERFLOW_VF13', + 362: 'IH_PERF_SEL_RB2_OVERFLOW_VF14', + 363: 'IH_PERF_SEL_RB2_OVERFLOW_VF15', + 364: 'Reserved364', + 365: 'Reserved365', + 366: 'Reserved366', + 367: 'Reserved367', + 368: 'Reserved368', + 369: 'Reserved369', + 370: 'Reserved370', + 371: 'Reserved371', + 372: 'Reserved372', + 373: 'Reserved373', + 374: 'Reserved374', + 375: 'Reserved375', + 376: 'Reserved376', + 377: 'Reserved377', + 378: 'Reserved378', + 379: 'Reserved379', + 380: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', + 381: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 382: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 383: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', + 384: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 385: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', + 386: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 387: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', + 388: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 389: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', + 390: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 391: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 392: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 393: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 394: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 395: 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', + 396: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', + 397: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', + 398: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 399: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', + 400: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 401: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', + 402: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 403: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', + 404: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 405: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', + 406: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 407: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 408: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 409: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 410: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 411: 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', + 412: 'Reserved412', + 413: 'Reserved413', + 414: 'Reserved414', + 415: 'Reserved415', + 416: 'Reserved416', + 417: 'Reserved417', + 418: 'Reserved418', + 419: 'Reserved419', + 420: 'Reserved420', + 421: 'Reserved421', + 422: 'Reserved422', + 423: 'Reserved423', + 424: 'Reserved424', + 425: 'Reserved425', + 426: 'Reserved426', + 427: 'Reserved427', + 428: 'Reserved428', + 429: 'Reserved429', + 430: 'Reserved430', + 431: 'Reserved431', + 432: 'Reserved432', + 433: 'Reserved433', + 434: 'Reserved434', + 435: 'Reserved435', + 436: 'Reserved436', + 437: 'Reserved437', + 438: 'Reserved438', + 439: 'Reserved439', + 440: 'Reserved440', + 441: 'Reserved441', + 442: 'Reserved442', + 443: 'Reserved443', + 444: 'Reserved444', + 445: 'Reserved445', + 446: 'Reserved446', + 447: 'Reserved447', + 448: 'Reserved448', + 449: 'Reserved449', + 450: 'Reserved450', + 451: 'Reserved451', + 452: 'Reserved452', + 453: 'Reserved453', + 454: 'Reserved454', + 455: 'Reserved455', + 456: 'Reserved456', + 457: 'Reserved457', + 458: 'Reserved458', + 459: 'Reserved459', + 460: 'Reserved460', + 461: 'Reserved461', + 462: 'Reserved462', + 463: 'Reserved463', + 464: 'Reserved464', + 465: 'Reserved465', + 466: 'Reserved466', + 467: 'Reserved467', + 468: 'Reserved468', + 469: 'Reserved469', + 470: 'Reserved470', + 471: 'Reserved471', + 472: 'Reserved472', + 473: 'Reserved473', + 474: 'Reserved474', + 475: 'Reserved475', + 476: 'Reserved476', + 477: 'Reserved477', + 478: 'Reserved478', + 479: 'Reserved479', + 480: 'Reserved480', + 481: 'Reserved481', + 482: 'Reserved482', + 483: 'Reserved483', + 484: 'Reserved484', + 485: 'Reserved485', + 486: 'Reserved486', + 487: 'Reserved487', + 488: 'Reserved488', + 489: 'Reserved489', + 490: 'Reserved490', + 491: 'Reserved491', + 492: 'Reserved492', + 493: 'Reserved493', + 494: 'Reserved494', + 495: 'Reserved495', + 496: 'Reserved496', + 497: 'Reserved497', + 498: 'Reserved498', + 499: 'Reserved499', + 500: 'Reserved500', + 501: 'Reserved501', + 502: 'Reserved502', + 503: 'Reserved503', + 504: 'Reserved504', + 505: 'Reserved505', + 506: 'Reserved506', + 507: 'Reserved507', + 508: 'Reserved508', + 509: 'Reserved509', + 510: 'Reserved510', + 511: 'Reserved511', +} +IH_PERF_SEL_CYCLE = 0 +IH_PERF_SEL_IDLE = 1 +IH_PERF_SEL_INPUT_IDLE = 2 +IH_PERF_SEL_BUFFER_IDLE = 3 +IH_PERF_SEL_RB0_FULL = 4 +IH_PERF_SEL_RB0_OVERFLOW = 5 +IH_PERF_SEL_RB0_WPTR_WRITEBACK = 6 +IH_PERF_SEL_RB0_WPTR_WRAP = 7 +IH_PERF_SEL_RB0_RPTR_WRAP = 8 +IH_PERF_SEL_MC_WR_IDLE = 9 +IH_PERF_SEL_MC_WR_COUNT = 10 +IH_PERF_SEL_MC_WR_STALL = 11 +IH_PERF_SEL_MC_WR_CLEAN_PENDING = 12 +IH_PERF_SEL_MC_WR_CLEAN_STALL = 13 +IH_PERF_SEL_BIF_LINE0_RISING = 14 +IH_PERF_SEL_BIF_LINE0_FALLING = 15 +IH_PERF_SEL_RB1_FULL = 16 +IH_PERF_SEL_RB1_OVERFLOW = 17 +Reserved18 = 18 +IH_PERF_SEL_RB1_WPTR_WRAP = 19 +IH_PERF_SEL_RB1_RPTR_WRAP = 20 +IH_PERF_SEL_RB2_FULL = 21 +IH_PERF_SEL_RB2_OVERFLOW = 22 +Reserved23 = 23 +IH_PERF_SEL_RB2_WPTR_WRAP = 24 +IH_PERF_SEL_RB2_RPTR_WRAP = 25 +Reserved26 = 26 +Reserved27 = 27 +Reserved28 = 28 +Reserved29 = 29 +IH_PERF_SEL_RB0_FULL_VF0 = 30 +IH_PERF_SEL_RB0_FULL_VF1 = 31 +IH_PERF_SEL_RB0_FULL_VF2 = 32 +IH_PERF_SEL_RB0_FULL_VF3 = 33 +IH_PERF_SEL_RB0_FULL_VF4 = 34 +IH_PERF_SEL_RB0_FULL_VF5 = 35 +IH_PERF_SEL_RB0_FULL_VF6 = 36 +IH_PERF_SEL_RB0_FULL_VF7 = 37 +IH_PERF_SEL_RB0_FULL_VF8 = 38 +IH_PERF_SEL_RB0_FULL_VF9 = 39 +IH_PERF_SEL_RB0_FULL_VF10 = 40 +IH_PERF_SEL_RB0_FULL_VF11 = 41 +IH_PERF_SEL_RB0_FULL_VF12 = 42 +IH_PERF_SEL_RB0_FULL_VF13 = 43 +IH_PERF_SEL_RB0_FULL_VF14 = 44 +IH_PERF_SEL_RB0_FULL_VF15 = 45 +IH_PERF_SEL_RB0_OVERFLOW_VF0 = 46 +IH_PERF_SEL_RB0_OVERFLOW_VF1 = 47 +IH_PERF_SEL_RB0_OVERFLOW_VF2 = 48 +IH_PERF_SEL_RB0_OVERFLOW_VF3 = 49 +IH_PERF_SEL_RB0_OVERFLOW_VF4 = 50 +IH_PERF_SEL_RB0_OVERFLOW_VF5 = 51 +IH_PERF_SEL_RB0_OVERFLOW_VF6 = 52 +IH_PERF_SEL_RB0_OVERFLOW_VF7 = 53 +IH_PERF_SEL_RB0_OVERFLOW_VF8 = 54 +IH_PERF_SEL_RB0_OVERFLOW_VF9 = 55 +IH_PERF_SEL_RB0_OVERFLOW_VF10 = 56 +IH_PERF_SEL_RB0_OVERFLOW_VF11 = 57 +IH_PERF_SEL_RB0_OVERFLOW_VF12 = 58 +IH_PERF_SEL_RB0_OVERFLOW_VF13 = 59 +IH_PERF_SEL_RB0_OVERFLOW_VF14 = 60 +IH_PERF_SEL_RB0_OVERFLOW_VF15 = 61 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0 = 62 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1 = 63 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2 = 64 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3 = 65 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4 = 66 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5 = 67 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6 = 68 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7 = 69 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8 = 70 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9 = 71 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10 = 72 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11 = 73 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12 = 74 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13 = 75 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14 = 76 +IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15 = 77 +IH_PERF_SEL_RB0_WPTR_WRAP_VF0 = 78 +IH_PERF_SEL_RB0_WPTR_WRAP_VF1 = 79 +IH_PERF_SEL_RB0_WPTR_WRAP_VF2 = 80 +IH_PERF_SEL_RB0_WPTR_WRAP_VF3 = 81 +IH_PERF_SEL_RB0_WPTR_WRAP_VF4 = 82 +IH_PERF_SEL_RB0_WPTR_WRAP_VF5 = 83 +IH_PERF_SEL_RB0_WPTR_WRAP_VF6 = 84 +IH_PERF_SEL_RB0_WPTR_WRAP_VF7 = 85 +IH_PERF_SEL_RB0_WPTR_WRAP_VF8 = 86 +IH_PERF_SEL_RB0_WPTR_WRAP_VF9 = 87 +IH_PERF_SEL_RB0_WPTR_WRAP_VF10 = 88 +IH_PERF_SEL_RB0_WPTR_WRAP_VF11 = 89 +IH_PERF_SEL_RB0_WPTR_WRAP_VF12 = 90 +IH_PERF_SEL_RB0_WPTR_WRAP_VF13 = 91 +IH_PERF_SEL_RB0_WPTR_WRAP_VF14 = 92 +IH_PERF_SEL_RB0_WPTR_WRAP_VF15 = 93 +IH_PERF_SEL_RB0_RPTR_WRAP_VF0 = 94 +IH_PERF_SEL_RB0_RPTR_WRAP_VF1 = 95 +IH_PERF_SEL_RB0_RPTR_WRAP_VF2 = 96 +IH_PERF_SEL_RB0_RPTR_WRAP_VF3 = 97 +IH_PERF_SEL_RB0_RPTR_WRAP_VF4 = 98 +IH_PERF_SEL_RB0_RPTR_WRAP_VF5 = 99 +IH_PERF_SEL_RB0_RPTR_WRAP_VF6 = 100 +IH_PERF_SEL_RB0_RPTR_WRAP_VF7 = 101 +IH_PERF_SEL_RB0_RPTR_WRAP_VF8 = 102 +IH_PERF_SEL_RB0_RPTR_WRAP_VF9 = 103 +IH_PERF_SEL_RB0_RPTR_WRAP_VF10 = 104 +IH_PERF_SEL_RB0_RPTR_WRAP_VF11 = 105 +IH_PERF_SEL_RB0_RPTR_WRAP_VF12 = 106 +IH_PERF_SEL_RB0_RPTR_WRAP_VF13 = 107 +IH_PERF_SEL_RB0_RPTR_WRAP_VF14 = 108 +IH_PERF_SEL_RB0_RPTR_WRAP_VF15 = 109 +IH_PERF_SEL_BIF_LINE0_RISING_VF0 = 110 +IH_PERF_SEL_BIF_LINE0_RISING_VF1 = 111 +IH_PERF_SEL_BIF_LINE0_RISING_VF2 = 112 +IH_PERF_SEL_BIF_LINE0_RISING_VF3 = 113 +IH_PERF_SEL_BIF_LINE0_RISING_VF4 = 114 +IH_PERF_SEL_BIF_LINE0_RISING_VF5 = 115 +IH_PERF_SEL_BIF_LINE0_RISING_VF6 = 116 +IH_PERF_SEL_BIF_LINE0_RISING_VF7 = 117 +IH_PERF_SEL_BIF_LINE0_RISING_VF8 = 118 +IH_PERF_SEL_BIF_LINE0_RISING_VF9 = 119 +IH_PERF_SEL_BIF_LINE0_RISING_VF10 = 120 +IH_PERF_SEL_BIF_LINE0_RISING_VF11 = 121 +IH_PERF_SEL_BIF_LINE0_RISING_VF12 = 122 +IH_PERF_SEL_BIF_LINE0_RISING_VF13 = 123 +IH_PERF_SEL_BIF_LINE0_RISING_VF14 = 124 +IH_PERF_SEL_BIF_LINE0_RISING_VF15 = 125 +IH_PERF_SEL_BIF_LINE0_FALLING_VF0 = 126 +IH_PERF_SEL_BIF_LINE0_FALLING_VF1 = 127 +IH_PERF_SEL_BIF_LINE0_FALLING_VF2 = 128 +IH_PERF_SEL_BIF_LINE0_FALLING_VF3 = 129 +IH_PERF_SEL_BIF_LINE0_FALLING_VF4 = 130 +IH_PERF_SEL_BIF_LINE0_FALLING_VF5 = 131 +IH_PERF_SEL_BIF_LINE0_FALLING_VF6 = 132 +IH_PERF_SEL_BIF_LINE0_FALLING_VF7 = 133 +IH_PERF_SEL_BIF_LINE0_FALLING_VF8 = 134 +IH_PERF_SEL_BIF_LINE0_FALLING_VF9 = 135 +IH_PERF_SEL_BIF_LINE0_FALLING_VF10 = 136 +IH_PERF_SEL_BIF_LINE0_FALLING_VF11 = 137 +IH_PERF_SEL_BIF_LINE0_FALLING_VF12 = 138 +IH_PERF_SEL_BIF_LINE0_FALLING_VF13 = 139 +IH_PERF_SEL_BIF_LINE0_FALLING_VF14 = 140 +IH_PERF_SEL_BIF_LINE0_FALLING_VF15 = 141 +Reserved142 = 142 +Reserved143 = 143 +Reserved144 = 144 +Reserved145 = 145 +Reserved146 = 146 +Reserved147 = 147 +Reserved148 = 148 +Reserved149 = 149 +IH_PERF_SEL_CLIENT0_INT = 150 +IH_PERF_SEL_CLIENT1_INT = 151 +IH_PERF_SEL_CLIENT2_INT = 152 +IH_PERF_SEL_CLIENT3_INT = 153 +IH_PERF_SEL_CLIENT4_INT = 154 +IH_PERF_SEL_CLIENT5_INT = 155 +IH_PERF_SEL_CLIENT6_INT = 156 +IH_PERF_SEL_CLIENT7_INT = 157 +IH_PERF_SEL_CLIENT8_INT = 158 +IH_PERF_SEL_CLIENT9_INT = 159 +IH_PERF_SEL_CLIENT10_INT = 160 +IH_PERF_SEL_CLIENT11_INT = 161 +IH_PERF_SEL_CLIENT12_INT = 162 +IH_PERF_SEL_CLIENT13_INT = 163 +IH_PERF_SEL_CLIENT14_INT = 164 +IH_PERF_SEL_CLIENT15_INT = 165 +IH_PERF_SEL_CLIENT16_INT = 166 +IH_PERF_SEL_CLIENT17_INT = 167 +IH_PERF_SEL_CLIENT18_INT = 168 +IH_PERF_SEL_CLIENT19_INT = 169 +IH_PERF_SEL_CLIENT20_INT = 170 +IH_PERF_SEL_CLIENT21_INT = 171 +IH_PERF_SEL_CLIENT22_INT = 172 +IH_PERF_SEL_CLIENT23_INT = 173 +IH_PERF_SEL_CLIENT24_INT = 174 +IH_PERF_SEL_CLIENT25_INT = 175 +IH_PERF_SEL_CLIENT26_INT = 176 +IH_PERF_SEL_CLIENT27_INT = 177 +IH_PERF_SEL_CLIENT28_INT = 178 +IH_PERF_SEL_CLIENT29_INT = 179 +IH_PERF_SEL_CLIENT30_INT = 180 +IH_PERF_SEL_CLIENT31_INT = 181 +Reserved182 = 182 +Reserved183 = 183 +Reserved184 = 184 +Reserved185 = 185 +Reserved186 = 186 +Reserved187 = 187 +Reserved188 = 188 +Reserved189 = 189 +Reserved190 = 190 +Reserved191 = 191 +Reserved192 = 192 +Reserved193 = 193 +Reserved194 = 194 +Reserved195 = 195 +Reserved196 = 196 +Reserved197 = 197 +Reserved198 = 198 +Reserved199 = 199 +Reserved200 = 200 +Reserved201 = 201 +Reserved202 = 202 +Reserved203 = 203 +Reserved204 = 204 +Reserved205 = 205 +Reserved206 = 206 +Reserved207 = 207 +Reserved208 = 208 +Reserved209 = 209 +Reserved210 = 210 +Reserved211 = 211 +Reserved212 = 212 +Reserved213 = 213 +Reserved214 = 214 +Reserved215 = 215 +Reserved216 = 216 +Reserved217 = 217 +Reserved218 = 218 +Reserved219 = 219 +IH_PERF_SEL_RB1_FULL_VF0 = 220 +IH_PERF_SEL_RB1_FULL_VF1 = 221 +IH_PERF_SEL_RB1_FULL_VF2 = 222 +IH_PERF_SEL_RB1_FULL_VF3 = 223 +IH_PERF_SEL_RB1_FULL_VF4 = 224 +IH_PERF_SEL_RB1_FULL_VF5 = 225 +IH_PERF_SEL_RB1_FULL_VF6 = 226 +IH_PERF_SEL_RB1_FULL_VF7 = 227 +IH_PERF_SEL_RB1_FULL_VF8 = 228 +IH_PERF_SEL_RB1_FULL_VF9 = 229 +IH_PERF_SEL_RB1_FULL_VF10 = 230 +IH_PERF_SEL_RB1_FULL_VF11 = 231 +IH_PERF_SEL_RB1_FULL_VF12 = 232 +IH_PERF_SEL_RB1_FULL_VF13 = 233 +IH_PERF_SEL_RB1_FULL_VF14 = 234 +IH_PERF_SEL_RB1_FULL_VF15 = 235 +IH_PERF_SEL_RB1_OVERFLOW_VF0 = 236 +IH_PERF_SEL_RB1_OVERFLOW_VF1 = 237 +IH_PERF_SEL_RB1_OVERFLOW_VF2 = 238 +IH_PERF_SEL_RB1_OVERFLOW_VF3 = 239 +IH_PERF_SEL_RB1_OVERFLOW_VF4 = 240 +IH_PERF_SEL_RB1_OVERFLOW_VF5 = 241 +IH_PERF_SEL_RB1_OVERFLOW_VF6 = 242 +IH_PERF_SEL_RB1_OVERFLOW_VF7 = 243 +IH_PERF_SEL_RB1_OVERFLOW_VF8 = 244 +IH_PERF_SEL_RB1_OVERFLOW_VF9 = 245 +IH_PERF_SEL_RB1_OVERFLOW_VF10 = 246 +IH_PERF_SEL_RB1_OVERFLOW_VF11 = 247 +IH_PERF_SEL_RB1_OVERFLOW_VF12 = 248 +IH_PERF_SEL_RB1_OVERFLOW_VF13 = 249 +IH_PERF_SEL_RB1_OVERFLOW_VF14 = 250 +IH_PERF_SEL_RB1_OVERFLOW_VF15 = 251 +Reserved252 = 252 +Reserved253 = 253 +Reserved254 = 254 +Reserved255 = 255 +Reserved256 = 256 +Reserved257 = 257 +Reserved258 = 258 +Reserved259 = 259 +Reserved260 = 260 +Reserved261 = 261 +Reserved262 = 262 +Reserved263 = 263 +Reserved264 = 264 +Reserved265 = 265 +Reserved266 = 266 +Reserved267 = 267 +IH_PERF_SEL_RB1_WPTR_WRAP_VF0 = 268 +IH_PERF_SEL_RB1_WPTR_WRAP_VF1 = 269 +IH_PERF_SEL_RB1_WPTR_WRAP_VF2 = 270 +IH_PERF_SEL_RB1_WPTR_WRAP_VF3 = 271 +IH_PERF_SEL_RB1_WPTR_WRAP_VF4 = 272 +IH_PERF_SEL_RB1_WPTR_WRAP_VF5 = 273 +IH_PERF_SEL_RB1_WPTR_WRAP_VF6 = 274 +IH_PERF_SEL_RB1_WPTR_WRAP_VF7 = 275 +IH_PERF_SEL_RB1_WPTR_WRAP_VF8 = 276 +IH_PERF_SEL_RB1_WPTR_WRAP_VF9 = 277 +IH_PERF_SEL_RB1_WPTR_WRAP_VF10 = 278 +IH_PERF_SEL_RB1_WPTR_WRAP_VF11 = 279 +IH_PERF_SEL_RB1_WPTR_WRAP_VF12 = 280 +IH_PERF_SEL_RB1_WPTR_WRAP_VF13 = 281 +IH_PERF_SEL_RB1_WPTR_WRAP_VF14 = 282 +IH_PERF_SEL_RB1_WPTR_WRAP_VF15 = 283 +IH_PERF_SEL_RB1_RPTR_WRAP_VF0 = 284 +IH_PERF_SEL_RB1_RPTR_WRAP_VF1 = 285 +IH_PERF_SEL_RB1_RPTR_WRAP_VF2 = 286 +IH_PERF_SEL_RB1_RPTR_WRAP_VF3 = 287 +IH_PERF_SEL_RB1_RPTR_WRAP_VF4 = 288 +IH_PERF_SEL_RB1_RPTR_WRAP_VF5 = 289 +IH_PERF_SEL_RB1_RPTR_WRAP_VF6 = 290 +IH_PERF_SEL_RB1_RPTR_WRAP_VF7 = 291 +IH_PERF_SEL_RB1_RPTR_WRAP_VF8 = 292 +IH_PERF_SEL_RB1_RPTR_WRAP_VF9 = 293 +IH_PERF_SEL_RB1_RPTR_WRAP_VF10 = 294 +IH_PERF_SEL_RB1_RPTR_WRAP_VF11 = 295 +IH_PERF_SEL_RB1_RPTR_WRAP_VF12 = 296 +IH_PERF_SEL_RB1_RPTR_WRAP_VF13 = 297 +IH_PERF_SEL_RB1_RPTR_WRAP_VF14 = 298 +IH_PERF_SEL_RB1_RPTR_WRAP_VF15 = 299 +Reserved300 = 300 +Reserved301 = 301 +Reserved302 = 302 +Reserved303 = 303 +Reserved304 = 304 +Reserved305 = 305 +Reserved306 = 306 +Reserved307 = 307 +Reserved308 = 308 +Reserved309 = 309 +Reserved310 = 310 +Reserved311 = 311 +Reserved312 = 312 +Reserved313 = 313 +Reserved314 = 314 +Reserved315 = 315 +Reserved316 = 316 +Reserved317 = 317 +Reserved318 = 318 +Reserved319 = 319 +Reserved320 = 320 +Reserved321 = 321 +Reserved322 = 322 +Reserved323 = 323 +Reserved324 = 324 +Reserved325 = 325 +Reserved326 = 326 +Reserved327 = 327 +Reserved328 = 328 +Reserved329 = 329 +Reserved330 = 330 +Reserved331 = 331 +IH_PERF_SEL_RB2_FULL_VF0 = 332 +IH_PERF_SEL_RB2_FULL_VF1 = 333 +IH_PERF_SEL_RB2_FULL_VF2 = 334 +IH_PERF_SEL_RB2_FULL_VF3 = 335 +IH_PERF_SEL_RB2_FULL_VF4 = 336 +IH_PERF_SEL_RB2_FULL_VF5 = 337 +IH_PERF_SEL_RB2_FULL_VF6 = 338 +IH_PERF_SEL_RB2_FULL_VF7 = 339 +IH_PERF_SEL_RB2_FULL_VF8 = 340 +IH_PERF_SEL_RB2_FULL_VF9 = 341 +IH_PERF_SEL_RB2_FULL_VF10 = 342 +IH_PERF_SEL_RB2_FULL_VF11 = 343 +IH_PERF_SEL_RB2_FULL_VF12 = 344 +IH_PERF_SEL_RB2_FULL_VF13 = 345 +IH_PERF_SEL_RB2_FULL_VF14 = 346 +IH_PERF_SEL_RB2_FULL_VF15 = 347 +IH_PERF_SEL_RB2_OVERFLOW_VF0 = 348 +IH_PERF_SEL_RB2_OVERFLOW_VF1 = 349 +IH_PERF_SEL_RB2_OVERFLOW_VF2 = 350 +IH_PERF_SEL_RB2_OVERFLOW_VF3 = 351 +IH_PERF_SEL_RB2_OVERFLOW_VF4 = 352 +IH_PERF_SEL_RB2_OVERFLOW_VF5 = 353 +IH_PERF_SEL_RB2_OVERFLOW_VF6 = 354 +IH_PERF_SEL_RB2_OVERFLOW_VF7 = 355 +IH_PERF_SEL_RB2_OVERFLOW_VF8 = 356 +IH_PERF_SEL_RB2_OVERFLOW_VF9 = 357 +IH_PERF_SEL_RB2_OVERFLOW_VF10 = 358 +IH_PERF_SEL_RB2_OVERFLOW_VF11 = 359 +IH_PERF_SEL_RB2_OVERFLOW_VF12 = 360 +IH_PERF_SEL_RB2_OVERFLOW_VF13 = 361 +IH_PERF_SEL_RB2_OVERFLOW_VF14 = 362 +IH_PERF_SEL_RB2_OVERFLOW_VF15 = 363 +Reserved364 = 364 +Reserved365 = 365 +Reserved366 = 366 +Reserved367 = 367 +Reserved368 = 368 +Reserved369 = 369 +Reserved370 = 370 +Reserved371 = 371 +Reserved372 = 372 +Reserved373 = 373 +Reserved374 = 374 +Reserved375 = 375 +Reserved376 = 376 +Reserved377 = 377 +Reserved378 = 378 +Reserved379 = 379 +IH_PERF_SEL_RB2_WPTR_WRAP_VF0 = 380 +IH_PERF_SEL_RB2_WPTR_WRAP_VF1 = 381 +IH_PERF_SEL_RB2_WPTR_WRAP_VF2 = 382 +IH_PERF_SEL_RB2_WPTR_WRAP_VF3 = 383 +IH_PERF_SEL_RB2_WPTR_WRAP_VF4 = 384 +IH_PERF_SEL_RB2_WPTR_WRAP_VF5 = 385 +IH_PERF_SEL_RB2_WPTR_WRAP_VF6 = 386 +IH_PERF_SEL_RB2_WPTR_WRAP_VF7 = 387 +IH_PERF_SEL_RB2_WPTR_WRAP_VF8 = 388 +IH_PERF_SEL_RB2_WPTR_WRAP_VF9 = 389 +IH_PERF_SEL_RB2_WPTR_WRAP_VF10 = 390 +IH_PERF_SEL_RB2_WPTR_WRAP_VF11 = 391 +IH_PERF_SEL_RB2_WPTR_WRAP_VF12 = 392 +IH_PERF_SEL_RB2_WPTR_WRAP_VF13 = 393 +IH_PERF_SEL_RB2_WPTR_WRAP_VF14 = 394 +IH_PERF_SEL_RB2_WPTR_WRAP_VF15 = 395 +IH_PERF_SEL_RB2_RPTR_WRAP_VF0 = 396 +IH_PERF_SEL_RB2_RPTR_WRAP_VF1 = 397 +IH_PERF_SEL_RB2_RPTR_WRAP_VF2 = 398 +IH_PERF_SEL_RB2_RPTR_WRAP_VF3 = 399 +IH_PERF_SEL_RB2_RPTR_WRAP_VF4 = 400 +IH_PERF_SEL_RB2_RPTR_WRAP_VF5 = 401 +IH_PERF_SEL_RB2_RPTR_WRAP_VF6 = 402 +IH_PERF_SEL_RB2_RPTR_WRAP_VF7 = 403 +IH_PERF_SEL_RB2_RPTR_WRAP_VF8 = 404 +IH_PERF_SEL_RB2_RPTR_WRAP_VF9 = 405 +IH_PERF_SEL_RB2_RPTR_WRAP_VF10 = 406 +IH_PERF_SEL_RB2_RPTR_WRAP_VF11 = 407 +IH_PERF_SEL_RB2_RPTR_WRAP_VF12 = 408 +IH_PERF_SEL_RB2_RPTR_WRAP_VF13 = 409 +IH_PERF_SEL_RB2_RPTR_WRAP_VF14 = 410 +IH_PERF_SEL_RB2_RPTR_WRAP_VF15 = 411 +Reserved412 = 412 +Reserved413 = 413 +Reserved414 = 414 +Reserved415 = 415 +Reserved416 = 416 +Reserved417 = 417 +Reserved418 = 418 +Reserved419 = 419 +Reserved420 = 420 +Reserved421 = 421 +Reserved422 = 422 +Reserved423 = 423 +Reserved424 = 424 +Reserved425 = 425 +Reserved426 = 426 +Reserved427 = 427 +Reserved428 = 428 +Reserved429 = 429 +Reserved430 = 430 +Reserved431 = 431 +Reserved432 = 432 +Reserved433 = 433 +Reserved434 = 434 +Reserved435 = 435 +Reserved436 = 436 +Reserved437 = 437 +Reserved438 = 438 +Reserved439 = 439 +Reserved440 = 440 +Reserved441 = 441 +Reserved442 = 442 +Reserved443 = 443 +Reserved444 = 444 +Reserved445 = 445 +Reserved446 = 446 +Reserved447 = 447 +Reserved448 = 448 +Reserved449 = 449 +Reserved450 = 450 +Reserved451 = 451 +Reserved452 = 452 +Reserved453 = 453 +Reserved454 = 454 +Reserved455 = 455 +Reserved456 = 456 +Reserved457 = 457 +Reserved458 = 458 +Reserved459 = 459 +Reserved460 = 460 +Reserved461 = 461 +Reserved462 = 462 +Reserved463 = 463 +Reserved464 = 464 +Reserved465 = 465 +Reserved466 = 466 +Reserved467 = 467 +Reserved468 = 468 +Reserved469 = 469 +Reserved470 = 470 +Reserved471 = 471 +Reserved472 = 472 +Reserved473 = 473 +Reserved474 = 474 +Reserved475 = 475 +Reserved476 = 476 +Reserved477 = 477 +Reserved478 = 478 +Reserved479 = 479 +Reserved480 = 480 +Reserved481 = 481 +Reserved482 = 482 +Reserved483 = 483 +Reserved484 = 484 +Reserved485 = 485 +Reserved486 = 486 +Reserved487 = 487 +Reserved488 = 488 +Reserved489 = 489 +Reserved490 = 490 +Reserved491 = 491 +Reserved492 = 492 +Reserved493 = 493 +Reserved494 = 494 +Reserved495 = 495 +Reserved496 = 496 +Reserved497 = 497 +Reserved498 = 498 +Reserved499 = 499 +Reserved500 = 500 +Reserved501 = 501 +Reserved502 = 502 +Reserved503 = 503 +Reserved504 = 504 +Reserved505 = 505 +Reserved506 = 506 +Reserved507 = 507 +Reserved508 = 508 +Reserved509 = 509 +Reserved510 = 510 +Reserved511 = 511 +IH_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SEM_PERF_SEL' +SEM_PERF_SEL__enumvalues = { + 0: 'SEM_PERF_SEL_CYCLE', + 1: 'SEM_PERF_SEL_IDLE', + 2: 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', + 3: 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', + 4: 'SEM_PERF_SEL_UVD_REQ_SIGNAL', + 5: 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', + 6: 'SEM_PERF_SEL_ACP_REQ_SIGNAL', + 7: 'SEM_PERF_SEL_ISP_REQ_SIGNAL', + 8: 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', + 9: 'SEM_PERF_SEL_VP8_REQ_SIGNAL', + 10: 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', + 11: 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', + 12: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 13: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 14: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 15: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 16: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 17: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 18: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 19: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 20: 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 21: 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 22: 'SEM_PERF_SEL_UVD_REQ_WAIT', + 23: 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 24: 'SEM_PERF_SEL_ACP_REQ_WAIT', + 25: 'SEM_PERF_SEL_ISP_REQ_WAIT', + 26: 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 27: 'SEM_PERF_SEL_VP8_REQ_WAIT', + 28: 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 29: 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 30: 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 31: 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 32: 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 33: 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 34: 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 35: 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 36: 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 37: 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 38: 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 39: 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 40: 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 41: 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 42: 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 43: 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 44: 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 45: 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 46: 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 47: 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 48: 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 49: 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 50: 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 51: 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 52: 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 53: 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 54: 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 55: 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 56: 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 57: 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 58: 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 59: 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 60: 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 61: 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 62: 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 63: 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 64: 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 65: 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 66: 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 67: 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 68: 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 69: 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 70: 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 71: 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 72: 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 73: 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 74: 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 75: 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 76: 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 77: 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 78: 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 79: 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 80: 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 81: 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 82: 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 83: 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 84: 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 85: 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 86: 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 87: 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 88: 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 89: 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 90: 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 91: 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 92: 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 93: 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 94: 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 95: 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 96: 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 97: 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 98: 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 99: 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 100: 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 101: 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 102: 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 103: 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 104: 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 105: 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 106: 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 107: 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 108: 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 109: 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 110: 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 111: 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 112: 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 113: 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 114: 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 115: 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 116: 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 117: 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 118: 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 119: 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 120: 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 121: 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 122: 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 123: 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 124: 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 125: 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 126: 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 127: 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 128: 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 129: 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 130: 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 131: 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 132: 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 133: 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 134: 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 135: 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 136: 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 137: 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 138: 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 139: 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 140: 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 141: 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 142: 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 143: 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 144: 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 145: 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 146: 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 147: 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 148: 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 149: 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 150: 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 151: 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 152: 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 153: 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 154: 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 155: 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 156: 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 157: 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 158: 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 159: 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 160: 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 161: 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 162: 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 163: 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 164: 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 165: 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 166: 'SEM_PERF_SEL_MC_RD_REQ', + 167: 'SEM_PERF_SEL_MC_RD_RET', + 168: 'SEM_PERF_SEL_MC_WR_REQ', + 169: 'SEM_PERF_SEL_MC_WR_RET', + 170: 'SEM_PERF_SEL_ATC_REQ', + 171: 'SEM_PERF_SEL_ATC_RET', + 172: 'SEM_PERF_SEL_ATC_XNACK', + 173: 'SEM_PERF_SEL_ATC_INVALIDATION', +} +SEM_PERF_SEL_CYCLE = 0 +SEM_PERF_SEL_IDLE = 1 +SEM_PERF_SEL_SDMA0_REQ_SIGNAL = 2 +SEM_PERF_SEL_SDMA1_REQ_SIGNAL = 3 +SEM_PERF_SEL_UVD_REQ_SIGNAL = 4 +SEM_PERF_SEL_VCE0_REQ_SIGNAL = 5 +SEM_PERF_SEL_ACP_REQ_SIGNAL = 6 +SEM_PERF_SEL_ISP_REQ_SIGNAL = 7 +SEM_PERF_SEL_VCE1_REQ_SIGNAL = 8 +SEM_PERF_SEL_VP8_REQ_SIGNAL = 9 +SEM_PERF_SEL_CPG_E0_REQ_SIGNAL = 10 +SEM_PERF_SEL_CPG_E1_REQ_SIGNAL = 11 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL = 12 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL = 13 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL = 14 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL = 15 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL = 16 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL = 17 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL = 18 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL = 19 +SEM_PERF_SEL_SDMA0_REQ_WAIT = 20 +SEM_PERF_SEL_SDMA1_REQ_WAIT = 21 +SEM_PERF_SEL_UVD_REQ_WAIT = 22 +SEM_PERF_SEL_VCE0_REQ_WAIT = 23 +SEM_PERF_SEL_ACP_REQ_WAIT = 24 +SEM_PERF_SEL_ISP_REQ_WAIT = 25 +SEM_PERF_SEL_VCE1_REQ_WAIT = 26 +SEM_PERF_SEL_VP8_REQ_WAIT = 27 +SEM_PERF_SEL_CPG_E0_REQ_WAIT = 28 +SEM_PERF_SEL_CPG_E1_REQ_WAIT = 29 +SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT = 30 +SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT = 31 +SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT = 32 +SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT = 33 +SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT = 34 +SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT = 35 +SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT = 36 +SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT = 37 +SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT = 38 +SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT = 39 +SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT = 40 +SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT = 41 +SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT = 42 +SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT = 43 +SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT = 44 +SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT = 45 +SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT = 46 +SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT = 47 +SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT = 48 +SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT = 49 +SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT = 50 +SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT = 51 +SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT = 52 +SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT = 53 +SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT = 54 +SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT = 55 +SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT = 56 +SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT = 57 +SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT = 58 +SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT = 59 +SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT = 60 +SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT = 61 +SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT = 62 +SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT = 63 +SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT = 64 +SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT = 65 +SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT = 66 +SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT = 67 +SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT = 68 +SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT = 69 +SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT = 70 +SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT = 71 +SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT = 72 +SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT = 73 +SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT = 74 +SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT = 75 +SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT = 76 +SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT = 77 +SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT = 78 +SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT = 79 +SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT = 80 +SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT = 81 +SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT = 82 +SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT = 83 +SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT = 84 +SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT = 85 +SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT = 86 +SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT = 87 +SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT = 88 +SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT = 89 +SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT = 90 +SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT = 91 +SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT = 92 +SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT = 93 +SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT = 94 +SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT = 95 +SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT = 96 +SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT = 97 +SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT = 98 +SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT = 99 +SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT = 100 +SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT = 101 +SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT = 102 +SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT = 103 +SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT = 104 +SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT = 105 +SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT = 106 +SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT = 107 +SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT = 108 +SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT = 109 +SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT = 110 +SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT = 111 +SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT = 112 +SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT = 113 +SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT = 114 +SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT = 115 +SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT = 116 +SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT = 117 +SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT = 118 +SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT = 119 +SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT = 120 +SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT = 121 +SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT = 122 +SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT = 123 +SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT = 124 +SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT = 125 +SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT = 126 +SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT = 127 +SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT = 128 +SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT = 129 +SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT = 130 +SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT = 131 +SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT = 132 +SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT = 133 +SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT = 134 +SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT = 135 +SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT = 136 +SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT = 137 +SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT = 138 +SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT = 139 +SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT = 140 +SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT = 141 +SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT = 142 +SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT = 143 +SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT = 144 +SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT = 145 +SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT = 146 +SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT = 147 +SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT = 148 +SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT = 149 +SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT = 150 +SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT = 151 +SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT = 152 +SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT = 153 +SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT = 154 +SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT = 155 +SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT = 156 +SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT = 157 +SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT = 158 +SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT = 159 +SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT = 160 +SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT = 161 +SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT = 162 +SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT = 163 +SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT = 164 +SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT = 165 +SEM_PERF_SEL_MC_RD_REQ = 166 +SEM_PERF_SEL_MC_RD_RET = 167 +SEM_PERF_SEL_MC_WR_REQ = 168 +SEM_PERF_SEL_MC_WR_RET = 169 +SEM_PERF_SEL_ATC_REQ = 170 +SEM_PERF_SEL_ATC_RET = 171 +SEM_PERF_SEL_ATC_XNACK = 172 +SEM_PERF_SEL_ATC_INVALIDATION = 173 +SEM_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'SDMA_PERF_SEL' +SDMA_PERF_SEL__enumvalues = { + 0: 'SDMA_PERF_SEL_CYCLE', + 1: 'SDMA_PERF_SEL_IDLE', + 2: 'SDMA_PERF_SEL_REG_IDLE', + 3: 'SDMA_PERF_SEL_RB_EMPTY', + 4: 'SDMA_PERF_SEL_RB_FULL', + 5: 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 6: 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 7: 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', + 8: 'SDMA_PERF_SEL_RB_RPTR_WB', + 9: 'SDMA_PERF_SEL_RB_CMD_IDLE', + 10: 'SDMA_PERF_SEL_RB_CMD_FULL', + 11: 'SDMA_PERF_SEL_IB_CMD_IDLE', + 12: 'SDMA_PERF_SEL_IB_CMD_FULL', + 13: 'SDMA_PERF_SEL_EX_IDLE', + 14: 'SDMA_PERF_SEL_SRBM_REG_SEND', + 15: 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 16: 'SDMA_PERF_SEL_MC_WR_IDLE', + 17: 'SDMA_PERF_SEL_MC_WR_COUNT', + 18: 'SDMA_PERF_SEL_MC_RD_IDLE', + 19: 'SDMA_PERF_SEL_MC_RD_COUNT', + 20: 'SDMA_PERF_SEL_MC_RD_RET_STALL', + 21: 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 24: 'SDMA_PERF_SEL_SEM_IDLE', + 25: 'SDMA_PERF_SEL_SEM_REQ_STALL', + 26: 'SDMA_PERF_SEL_SEM_REQ_COUNT', + 27: 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 28: 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 29: 'SDMA_PERF_SEL_SEM_RESP_PASS', + 30: 'SDMA_PERF_SEL_INT_IDLE', + 31: 'SDMA_PERF_SEL_INT_REQ_STALL', + 32: 'SDMA_PERF_SEL_INT_REQ_COUNT', + 33: 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', + 34: 'SDMA_PERF_SEL_INT_RESP_RETRY', + 35: 'SDMA_PERF_SEL_NUM_PACKET', + 37: 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 38: 'SDMA_PERF_SEL_CE_WR_IDLE', + 39: 'SDMA_PERF_SEL_CE_SPLIT_IDLE', + 40: 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 41: 'SDMA_PERF_SEL_CE_OUT_IDLE', + 42: 'SDMA_PERF_SEL_CE_IN_IDLE', + 43: 'SDMA_PERF_SEL_CE_DST_IDLE', + 46: 'SDMA_PERF_SEL_CE_AFIFO_FULL', + 49: 'SDMA_PERF_SEL_CE_INFO_FULL', + 50: 'SDMA_PERF_SEL_CE_INFO1_FULL', + 51: 'SDMA_PERF_SEL_CE_RD_STALL', + 52: 'SDMA_PERF_SEL_CE_WR_STALL', + 53: 'SDMA_PERF_SEL_GFX_SELECT', + 54: 'SDMA_PERF_SEL_RLC0_SELECT', + 55: 'SDMA_PERF_SEL_RLC1_SELECT', + 56: 'SDMA_PERF_SEL_PAGE_SELECT', + 57: 'SDMA_PERF_SEL_CTX_CHANGE', + 58: 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', + 59: 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 60: 'SDMA_PERF_SEL_DOORBELL', + 61: 'SDMA_PERF_SEL_RD_BA_RTR', + 62: 'SDMA_PERF_SEL_WR_BA_RTR', + 63: 'SDMA_PERF_SEL_F32_L1_WR_VLD', + 64: 'SDMA_PERF_SEL_CE_L1_WR_VLD', + 65: 'SDMA_PERF_SEL_CE_L1_STALL', + 66: 'SDMA_PERF_SEL_SDMA_INVACK_NFLUSH', + 67: 'SDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 68: 'SDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 69: 'SDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 70: 'SDMA_PERF_SEL_ATCL2_RET_XNACK', + 71: 'SDMA_PERF_SEL_ATCL2_RET_ACK', + 72: 'SDMA_PERF_SEL_ATCL2_FREE', + 73: 'SDMA_PERF_SEL_SDMA_ATCL2_SEND', + 74: 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 75: 'SDMA_PERF_SEL_DMA_L1_RD_SEND', + 76: 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 77: 'SDMA_PERF_SEL_DMA_MC_RD_SEND', + 78: 'SDMA_PERF_SEL_L1_WR_FIFO_IDLE', + 79: 'SDMA_PERF_SEL_L1_RD_FIFO_IDLE', + 80: 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 81: 'SDMA_PERF_SEL_L1_RDL2_IDLE', + 82: 'SDMA_PERF_SEL_L1_WRMC_IDLE', + 83: 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 84: 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 85: 'SDMA_PERF_SEL_L1_RD_INV_IDLE', + 86: 'SDMA_PERF_SEL_L1_WR_INV_EN', + 87: 'SDMA_PERF_SEL_L1_RD_INV_EN', + 88: 'SDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 89: 'SDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 90: 'SDMA_PERF_SEL_IS_INVREQ_ADDR_WR', + 91: 'SDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 92: 'SDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', + 93: 'SDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', + 94: 'SDMA_PERF_SEL_L1_INV_MIDDLE', + 254: 'SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER', + 255: 'SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER', +} +SDMA_PERF_SEL_CYCLE = 0 +SDMA_PERF_SEL_IDLE = 1 +SDMA_PERF_SEL_REG_IDLE = 2 +SDMA_PERF_SEL_RB_EMPTY = 3 +SDMA_PERF_SEL_RB_FULL = 4 +SDMA_PERF_SEL_RB_WPTR_WRAP = 5 +SDMA_PERF_SEL_RB_RPTR_WRAP = 6 +SDMA_PERF_SEL_RB_WPTR_POLL_READ = 7 +SDMA_PERF_SEL_RB_RPTR_WB = 8 +SDMA_PERF_SEL_RB_CMD_IDLE = 9 +SDMA_PERF_SEL_RB_CMD_FULL = 10 +SDMA_PERF_SEL_IB_CMD_IDLE = 11 +SDMA_PERF_SEL_IB_CMD_FULL = 12 +SDMA_PERF_SEL_EX_IDLE = 13 +SDMA_PERF_SEL_SRBM_REG_SEND = 14 +SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE = 15 +SDMA_PERF_SEL_MC_WR_IDLE = 16 +SDMA_PERF_SEL_MC_WR_COUNT = 17 +SDMA_PERF_SEL_MC_RD_IDLE = 18 +SDMA_PERF_SEL_MC_RD_COUNT = 19 +SDMA_PERF_SEL_MC_RD_RET_STALL = 20 +SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE = 21 +SDMA_PERF_SEL_SEM_IDLE = 24 +SDMA_PERF_SEL_SEM_REQ_STALL = 25 +SDMA_PERF_SEL_SEM_REQ_COUNT = 26 +SDMA_PERF_SEL_SEM_RESP_INCOMPLETE = 27 +SDMA_PERF_SEL_SEM_RESP_FAIL = 28 +SDMA_PERF_SEL_SEM_RESP_PASS = 29 +SDMA_PERF_SEL_INT_IDLE = 30 +SDMA_PERF_SEL_INT_REQ_STALL = 31 +SDMA_PERF_SEL_INT_REQ_COUNT = 32 +SDMA_PERF_SEL_INT_RESP_ACCEPTED = 33 +SDMA_PERF_SEL_INT_RESP_RETRY = 34 +SDMA_PERF_SEL_NUM_PACKET = 35 +SDMA_PERF_SEL_CE_WREQ_IDLE = 37 +SDMA_PERF_SEL_CE_WR_IDLE = 38 +SDMA_PERF_SEL_CE_SPLIT_IDLE = 39 +SDMA_PERF_SEL_CE_RREQ_IDLE = 40 +SDMA_PERF_SEL_CE_OUT_IDLE = 41 +SDMA_PERF_SEL_CE_IN_IDLE = 42 +SDMA_PERF_SEL_CE_DST_IDLE = 43 +SDMA_PERF_SEL_CE_AFIFO_FULL = 46 +SDMA_PERF_SEL_CE_INFO_FULL = 49 +SDMA_PERF_SEL_CE_INFO1_FULL = 50 +SDMA_PERF_SEL_CE_RD_STALL = 51 +SDMA_PERF_SEL_CE_WR_STALL = 52 +SDMA_PERF_SEL_GFX_SELECT = 53 +SDMA_PERF_SEL_RLC0_SELECT = 54 +SDMA_PERF_SEL_RLC1_SELECT = 55 +SDMA_PERF_SEL_PAGE_SELECT = 56 +SDMA_PERF_SEL_CTX_CHANGE = 57 +SDMA_PERF_SEL_CTX_CHANGE_EXPIRED = 58 +SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION = 59 +SDMA_PERF_SEL_DOORBELL = 60 +SDMA_PERF_SEL_RD_BA_RTR = 61 +SDMA_PERF_SEL_WR_BA_RTR = 62 +SDMA_PERF_SEL_F32_L1_WR_VLD = 63 +SDMA_PERF_SEL_CE_L1_WR_VLD = 64 +SDMA_PERF_SEL_CE_L1_STALL = 65 +SDMA_PERF_SEL_SDMA_INVACK_NFLUSH = 66 +SDMA_PERF_SEL_SDMA_INVACK_FLUSH = 67 +SDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH = 68 +SDMA_PERF_SEL_ATCL2_INVREQ_FLUSH = 69 +SDMA_PERF_SEL_ATCL2_RET_XNACK = 70 +SDMA_PERF_SEL_ATCL2_RET_ACK = 71 +SDMA_PERF_SEL_ATCL2_FREE = 72 +SDMA_PERF_SEL_SDMA_ATCL2_SEND = 73 +SDMA_PERF_SEL_DMA_L1_WR_SEND = 74 +SDMA_PERF_SEL_DMA_L1_RD_SEND = 75 +SDMA_PERF_SEL_DMA_MC_WR_SEND = 76 +SDMA_PERF_SEL_DMA_MC_RD_SEND = 77 +SDMA_PERF_SEL_L1_WR_FIFO_IDLE = 78 +SDMA_PERF_SEL_L1_RD_FIFO_IDLE = 79 +SDMA_PERF_SEL_L1_WRL2_IDLE = 80 +SDMA_PERF_SEL_L1_RDL2_IDLE = 81 +SDMA_PERF_SEL_L1_WRMC_IDLE = 82 +SDMA_PERF_SEL_L1_RDMC_IDLE = 83 +SDMA_PERF_SEL_L1_WR_INV_IDLE = 84 +SDMA_PERF_SEL_L1_RD_INV_IDLE = 85 +SDMA_PERF_SEL_L1_WR_INV_EN = 86 +SDMA_PERF_SEL_L1_RD_INV_EN = 87 +SDMA_PERF_SEL_L1_WR_WAIT_INVADR = 88 +SDMA_PERF_SEL_L1_RD_WAIT_INVADR = 89 +SDMA_PERF_SEL_IS_INVREQ_ADDR_WR = 90 +SDMA_PERF_SEL_IS_INVREQ_ADDR_RD = 91 +SDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT = 92 +SDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT = 93 +SDMA_PERF_SEL_L1_INV_MIDDLE = 94 +SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER = 254 +SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER = 255 +SDMA_PERF_SEL = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_XDMA_LOCAL_SW_MODE' +ENUM_XDMA_LOCAL_SW_MODE__enumvalues = { + 2: 'XDMA_LOCAL_SW_MODE_SW_256B_D', + 10: 'XDMA_LOCAL_SW_MODE_SW_64KB_D', + 26: 'XDMA_LOCAL_SW_MODE_SW_64KB_D_X', +} +XDMA_LOCAL_SW_MODE_SW_256B_D = 2 +XDMA_LOCAL_SW_MODE_SW_64KB_D = 10 +XDMA_LOCAL_SW_MODE_SW_64KB_D_X = 26 +ENUM_XDMA_LOCAL_SW_MODE = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_XDMA_SLV_ALPHA_POSITION' +ENUM_XDMA_SLV_ALPHA_POSITION__enumvalues = { + 0: 'XDMA_SLV_ALPHA_POSITION_7_0', + 1: 'XDMA_SLV_ALPHA_POSITION_15_8', + 2: 'XDMA_SLV_ALPHA_POSITION_23_16', + 3: 'XDMA_SLV_ALPHA_POSITION_31_24', +} +XDMA_SLV_ALPHA_POSITION_7_0 = 0 +XDMA_SLV_ALPHA_POSITION_15_8 = 1 +XDMA_SLV_ALPHA_POSITION_23_16 = 2 +XDMA_SLV_ALPHA_POSITION_31_24 = 3 +ENUM_XDMA_SLV_ALPHA_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_XDMA_MSTR_ALPHA_POSITION' +ENUM_XDMA_MSTR_ALPHA_POSITION__enumvalues = { + 0: 'XDMA_MSTR_ALPHA_POSITION_7_0', + 1: 'XDMA_MSTR_ALPHA_POSITION_15_8', + 2: 'XDMA_MSTR_ALPHA_POSITION_23_16', + 3: 'XDMA_MSTR_ALPHA_POSITION_31_24', +} +XDMA_MSTR_ALPHA_POSITION_7_0 = 0 +XDMA_MSTR_ALPHA_POSITION_15_8 = 1 +XDMA_MSTR_ALPHA_POSITION_23_16 = 2 +XDMA_MSTR_ALPHA_POSITION_31_24 = 3 +ENUM_XDMA_MSTR_ALPHA_POSITION = ctypes.c_uint32 # enum + +# values for enumeration 'ENUM_XDMA_MSTR_VSYNC_GSL_CHECK_SEL' +ENUM_XDMA_MSTR_VSYNC_GSL_CHECK_SEL__enumvalues = { + 0: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE0', + 1: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE1', + 2: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE2', + 3: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE3', + 4: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE4', + 5: 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE5', +} +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE0 = 0 +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE1 = 1 +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE2 = 2 +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE3 = 3 +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE4 = 4 +XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE5 = 5 +ENUM_XDMA_MSTR_VSYNC_GSL_CHECK_SEL = ctypes.c_uint32 # enum +__all__ = \ + ['ABGR_TO_A_BG_G_RB', 'ABM_SOFT_RESET', 'ABM_SOFT_RESET_0', + 'ABM_SOFT_RESET_1', 'ACCEPT_UNSOLICITED_RESPONSE_ENABLE', + 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', 'ADDR_CONFIG_16_BANK', + 'ADDR_CONFIG_16_PIPE', 'ADDR_CONFIG_1KB_ROW', + 'ADDR_CONFIG_1_BANK', 'ADDR_CONFIG_1_GPU', + 'ADDR_CONFIG_1_LOWER_PIPES', + 'ADDR_CONFIG_1_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_1_PIPE', + 'ADDR_CONFIG_1_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_1_SHADER_ENGINE', 'ADDR_CONFIG_2KB_ROW', + 'ADDR_CONFIG_2_BANK', 'ADDR_CONFIG_2_GPU', + 'ADDR_CONFIG_2_LOWER_PIPES', + 'ADDR_CONFIG_2_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_2_PIPE', + 'ADDR_CONFIG_2_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_2_SHADER_ENGINE', 'ADDR_CONFIG_32_PIPE', + 'ADDR_CONFIG_4KB_ROW', 'ADDR_CONFIG_4_BANK', 'ADDR_CONFIG_4_GPU', + 'ADDR_CONFIG_4_MAX_COMPRESSED_FRAGMENTS', 'ADDR_CONFIG_4_PIPE', + 'ADDR_CONFIG_4_RB_PER_SHADER_ENGINE', + 'ADDR_CONFIG_4_SHADER_ENGINE', 'ADDR_CONFIG_8_BANK', + 'ADDR_CONFIG_8_GPU', 'ADDR_CONFIG_8_MAX_COMPRESSED_FRAGMENTS', + 'ADDR_CONFIG_8_PIPE', 'ADDR_CONFIG_8_SHADER_ENGINE', + 'ADDR_CONFIG_BANK_INTERLEAVE_1', 'ADDR_CONFIG_BANK_INTERLEAVE_2', + 'ADDR_CONFIG_BANK_INTERLEAVE_4', 'ADDR_CONFIG_BANK_INTERLEAVE_8', + 'ADDR_CONFIG_DISABLE_SE', 'ADDR_CONFIG_ENABLE_SE', + 'ADDR_CONFIG_GPU_TILE_128', 'ADDR_CONFIG_GPU_TILE_16', + 'ADDR_CONFIG_GPU_TILE_32', 'ADDR_CONFIG_GPU_TILE_64', + 'ADDR_CONFIG_PIPE_INTERLEAVE_1KB', + 'ADDR_CONFIG_PIPE_INTERLEAVE_256B', + 'ADDR_CONFIG_PIPE_INTERLEAVE_2KB', + 'ADDR_CONFIG_PIPE_INTERLEAVE_512B', 'ADDR_CONFIG_SE_TILE_16', + 'ADDR_CONFIG_SE_TILE_32', 'ADDR_SURF_16_BANK', 'ADDR_SURF_2_BANK', + 'ADDR_SURF_4_BANK', 'ADDR_SURF_8_BANK', 'ADDR_SURF_BANK_HEIGHT_1', + 'ADDR_SURF_BANK_HEIGHT_2', 'ADDR_SURF_BANK_HEIGHT_4', + 'ADDR_SURF_BANK_HEIGHT_8', 'ADDR_SURF_BANK_WH_1', + 'ADDR_SURF_BANK_WH_2', 'ADDR_SURF_BANK_WH_4', + 'ADDR_SURF_BANK_WH_8', 'ADDR_SURF_BANK_WIDTH_1', + 'ADDR_SURF_BANK_WIDTH_2', 'ADDR_SURF_BANK_WIDTH_4', + 'ADDR_SURF_BANK_WIDTH_8', 'ADDR_SURF_DEPTH_MICRO_TILING', + 'ADDR_SURF_DISPLAY_MICRO_TILING', 'ADDR_SURF_MACRO_ASPECT_1', + 'ADDR_SURF_MACRO_ASPECT_2', 'ADDR_SURF_MACRO_ASPECT_4', + 'ADDR_SURF_MACRO_ASPECT_8', 'ADDR_SURF_MICRO_TILING_DISPLAY', + 'ADDR_SURF_MICRO_TILING_NON_DISPLAY', 'ADDR_SURF_P16_32x32_16x16', + 'ADDR_SURF_P16_32x32_8x16', 'ADDR_SURF_P2', + 'ADDR_SURF_P2_RESERVED0', 'ADDR_SURF_P2_RESERVED1', + 'ADDR_SURF_P2_RESERVED2', 'ADDR_SURF_P4_16x16', + 'ADDR_SURF_P4_16x32', 'ADDR_SURF_P4_32x32', 'ADDR_SURF_P4_8x16', + 'ADDR_SURF_P8_16x16_8x16', 'ADDR_SURF_P8_16x32_16x16', + 'ADDR_SURF_P8_16x32_8x16', 'ADDR_SURF_P8_32x32_16x16', + 'ADDR_SURF_P8_32x32_16x32', 'ADDR_SURF_P8_32x32_8x16', + 'ADDR_SURF_P8_32x64_32x32', 'ADDR_SURF_P8_RESERVED0', + 'ADDR_SURF_ROTATED_MICRO_TILING', 'ADDR_SURF_SAMPLE_SPLIT_1', + 'ADDR_SURF_SAMPLE_SPLIT_2', 'ADDR_SURF_SAMPLE_SPLIT_4', + 'ADDR_SURF_SAMPLE_SPLIT_8', 'ADDR_SURF_THICK_MICRO_TILING', + 'ADDR_SURF_THIN_MICRO_TILING', 'ADDR_SURF_TILE_SPLIT_128B', + 'ADDR_SURF_TILE_SPLIT_1KB', 'ADDR_SURF_TILE_SPLIT_256B', + 'ADDR_SURF_TILE_SPLIT_2KB', 'ADDR_SURF_TILE_SPLIT_4KB', + 'ADDR_SURF_TILE_SPLIT_512B', 'ADDR_SURF_TILE_SPLIT_64B', + 'AFMT_AUDIO_CRC_AUDIO_SAMPLE_COUNT', + 'AFMT_AUDIO_CRC_AUTO_RESTART', 'AFMT_AUDIO_CRC_CH0_SIG', + 'AFMT_AUDIO_CRC_CH1_SIG', 'AFMT_AUDIO_CRC_CH2_SIG', + 'AFMT_AUDIO_CRC_CH3_SIG', 'AFMT_AUDIO_CRC_CH4_SIG', + 'AFMT_AUDIO_CRC_CH5_SIG', 'AFMT_AUDIO_CRC_CH6_SIG', + 'AFMT_AUDIO_CRC_CH7_SIG', 'AFMT_AUDIO_CRC_CONTROL_CH_SEL', + 'AFMT_AUDIO_CRC_CONTROL_CONT', 'AFMT_AUDIO_CRC_CONTROL_SOURCE', + 'AFMT_AUDIO_CRC_ONESHOT', 'AFMT_AUDIO_CRC_RESERVED_10', + 'AFMT_AUDIO_CRC_RESERVED_11', 'AFMT_AUDIO_CRC_RESERVED_12', + 'AFMT_AUDIO_CRC_RESERVED_13', 'AFMT_AUDIO_CRC_RESERVED_14', + 'AFMT_AUDIO_CRC_RESERVED_8', 'AFMT_AUDIO_CRC_RESERVED_9', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_INPUT', + 'AFMT_AUDIO_CRC_SOURCE_FROM_FIFO_OUTPUT', + 'AFMT_AUDIO_LAYOUT_DETERMINED_BY_AZ_AUDIO_CHANNEL_STATUS', + 'AFMT_AUDIO_LAYOUT_OVRD_BY_REGISTER', + 'AFMT_AUDIO_PACKET_CONTROL2_AUDIO_LAYOUT_OVRD', + 'AFMT_AUDIO_PACKET_CONTROL_AUDIO_SAMPLE_SEND', + 'AFMT_AUDIO_PACKET_CONTROL_RESET_FIFO_WHEN_AUDIO_DIS', + 'AFMT_AUDIO_PACKET_SENT_DISABLED', + 'AFMT_AUDIO_PACKET_SENT_ENABLED', 'AFMT_AUDIO_SRC_CONTROL_SELECT', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM0', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM1', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM2', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM3', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM4', + 'AFMT_AUDIO_SRC_FROM_AZ_STREAM5', 'AFMT_AUDIO_SRC_RESERVED', + 'AFMT_INFOFRAME_CONTROL0_AUDIO_INFO_SOURCE', + 'AFMT_INFOFRAME_SOURCE_FROM_AFMT_REGISTERS', + 'AFMT_INFOFRAME_SOURCE_FROM_AZALIA_BLOCK', + 'AFMT_INTERRUPT_DISABLE', 'AFMT_INTERRUPT_ENABLE', + 'AFMT_INTERRUPT_STATUS_CHG_MASK', + 'AFMT_NOT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED_RESERVED', + 'AFMT_RAMP_CONTROL0_SIGN', 'AFMT_RAMP_SIGNED', + 'AFMT_RAMP_UNSIGNED', 'AFMT_RESET_AUDIO_FIFO_WHEN_AUDIO_DISABLED', + 'ALLOW_SR_ON_TRANS_REQ', 'ALLOW_SR_ON_TRANS_REQ_DISABLE', + 'ALLOW_SR_ON_TRANS_REQ_ENABLE', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'ALPHA_DP_AUX_DEFINITE_ERR_REACHED_NOT_ACK', + 'ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_MASTER', + 'ALPHA_LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE_SLAVE', + 'AOUT_CRC_CONT', 'AOUT_CRC_CONT_EN', 'AOUT_CRC_DISABLE', + 'AOUT_CRC_ENABLE', 'AOUT_CRC_NO_RESET', 'AOUT_CRC_ONE_SHOT', + 'AOUT_CRC_RESET', 'AOUT_CRC_SOFT_RESET', 'AOUT_CRC_TEST_EN', + 'AOUT_DISABLE', 'AOUT_EN', 'AOUT_ENABLE', 'AOUT_FIFO_START_ADDR', + 'AOUT_FIFO_START_ADDR_2', 'AOUT_FIFO_START_ADDR_3', 'ARRAY_1D', + 'ARRAY_1D_TILED_THICK', 'ARRAY_1D_TILED_THIN1', 'ARRAY_2D', + 'ARRAY_2D_ALT_COLOR', 'ARRAY_2D_ALT_DEPTH', 'ARRAY_2D_COLOR', + 'ARRAY_2D_DEPTH', 'ARRAY_2D_TILED_THICK', 'ARRAY_2D_TILED_THIN1', + 'ARRAY_2D_TILED_XTHICK', 'ARRAY_3D', 'ARRAY_3D_SLICE', + 'ARRAY_3D_SLICE_COLOR', 'ARRAY_3D_TILED_THICK', + 'ARRAY_3D_TILED_THIN1', 'ARRAY_3D_TILED_XTHICK', + 'ARRAY_COLOR_TILE', 'ARRAY_DEPTH_TILE', 'ARRAY_LINEAR', + 'ARRAY_LINEAR_ALIGNED', 'ARRAY_LINEAR_GENERAL', + 'ARRAY_PRT_2D_TILED_THICK', 'ARRAY_PRT_2D_TILED_THIN1', + 'ARRAY_PRT_3D_TILED_THICK', 'ARRAY_PRT_3D_TILED_THIN1', + 'ARRAY_PRT_TILED_THICK', 'ARRAY_PRT_TILED_THIN1', 'ARRAY_TILED', + 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', 'AUDIO_LAYOUT_SELECT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_STEREO', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CODEC_CONVERTER0_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NOT_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_FORMAT_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_CODEC_CONVERTER0_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESING_CAPABILITIES', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_DP_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HDMI_NOT_ENABLED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_I_O_PINS_NOT_BALANCED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_JACK_PRESENCE_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_INPUT_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HAVE_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_HBR_CAPABLE', + 'AZALIA_F0_CODEC_PIN_CONTROL_RESPONSE_HBR_NO_HBR_CAPABLILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_AMPLIFIER_PARAMETER_OVERRIDE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_INPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_HAVE_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_ANALOG', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_IS_DIGITAL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_LR_SWAP', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_AMPLIFIER_PARAMETER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_CONNECTION_LIST', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_INPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_LR_SWAP_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_OUTPUT_AMPLIFIER', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_POWER_CONTROL_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_NO_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_OUTPUT_AMPLIFIER_PRESENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_POWER_CONTROL', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_HAVE_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_PROCESSING_WIDGET_NO_PROCESSING_CAPABILITIES', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_STRIPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_SUPPORT_STRIPING', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_BEEP_GENERATOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_INPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_MIXER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_OUTPUT_CONVERTER_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_PIN_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_POWER_WIDGET_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_RESERVED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_SELECTOR_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VENDOR_DEFINED_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_TYPE_VOLUME_KNOB_RESERVED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_AUDIO_WIDGET_CAPABILITIES_UNSOLICITED_RESPONSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_BALANCED_I_O_PINS', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_EAPD_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HAVE_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_HEADPHONE_DRIVE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_IMPEDANCE_SENSE_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_INPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_I_O_PINS_ARE_NOT_BALANCED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_EAPD_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_HEADPHONE_DRIVE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_IMPEDANCE_SENSE_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_INPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_JACK_DETECTION_CAPABILITY', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_OUTPUT_PIN', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_NO_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_OUTPUT_CAPABLE', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED', + 'AZALIA_F0_CODEC_PIN_PARAMETER_CAPABILITIES_TRIGGER_REQUIRED_FOR_IMPEDANCE_MEASUREMENT', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_3_KEEPALIVE_SILENT_STREAM_NOT_ENABLE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_COPY_BIT_C_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_L_BIT7_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_NON_AUDIO_BIT_B_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRE_LSB_OF_D_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_IS_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_PRO_BIT_A_NOT_SET', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_NOT_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VALIDITY_CFG_ON', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_VCFG', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ONE', + 'AZALIA_F2_CODEC_CONVERTER_CONTROL_DIGITAL_CONVERTER_V_BIT28_IS_ZERO', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_DO_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_NOT_RESET', + 'AZALIA_F2_CODEC_FUNCTION_CONTROL_RESET_CODEC_RESET', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_16', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_20', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_24', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_5', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_6', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_7', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_8', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_NUMBER_OF_CHANNELS_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_NOT_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_CONVERTER_FORMAT_STREAM_TYPE_PCM', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_DISABLED', + 'AZALIA_F2_CODEC_INPUT_CONVERTER_CONTROL_DIGITAL_CONVERTER_DIGEN_DIGITAL_TRANSMISSION_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL0_ENABLE_MULTICHANNEL0_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL2_ENABLE_MULTICHANNEL2_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL4_ENABLE_MULTICHANNEL4_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL6_ENABLE_MULTICHANNEL6_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_INPUT_PIN_CONTROL_WIDGET_CONTROL_IN_ENABLE_PIN_SHUT_OFF', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_FORBIDDEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_INFO_DOWN_MIX_INHIBIT', + 'AZALIA_F2_CODEC_PIN_CONTROL_DOWN_MIX_NO_INFO_OR_PERMITTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL01_ENABLE_MULTICHANNEL01_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL1_ENABLE_MULTICHANNEL1_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL23_ENABLE_MULTICHANNEL23_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL3_ENABLE_MULTICHANNEL3_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL45_ENABLE_MULTICHANNEL45_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL5_ENABLE_MULTICHANNEL5_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL67_ENABLE_MULTICHANNEL67_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL7_ENABLE_MULTICHANNEL7_NOT_MUTED', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_PAIR_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_MULTICHANNEL_MODE_MULTICHANNEL_SINGLE_MODE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_DISABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_UNSOLICITED_RESPONSE_ENABLED', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_DRIVEN', + 'AZALIA_F2_CODEC_PIN_CONTROL_WIDGET_CONTROL_OUT_ENABLE_PIN_SHUT_OFF', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_NOT_RESET', + 'AZALIA_SOFT_RESET_REFCLK_SOFT_RESET_RESET_REFCLK_LOGIC', + 'AZ_CORB_SIZE', 'AZ_CORB_SIZE_16ENTRIES_RESERVED', + 'AZ_CORB_SIZE_256ENTRIES', 'AZ_CORB_SIZE_2ENTRIES_RESERVED', + 'AZ_CORB_SIZE_RESERVED', 'AZ_GLOBAL_CAPABILITIES', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_NOT_SUPPORTED', + 'AZ_GLOBAL_CAPABILITIES_SIXTY_FOUR_BIT_ADDRESS_SUPPORTED', + 'AZ_LATENCY_COUNTER_CONTROL', 'AZ_LATENCY_COUNTER_NO_RESET', + 'AZ_LATENCY_COUNTER_RESET_DONE', 'AZ_RIRB_SIZE', + 'AZ_RIRB_SIZE_16ENTRIES_RESERVED', 'AZ_RIRB_SIZE_256ENTRIES', + 'AZ_RIRB_SIZE_2ENTRIES_RESERVED', 'AZ_RIRB_SIZE_UNDEFINED', + 'AZ_RIRB_WRITE_POINTER_DO_RESET', + 'AZ_RIRB_WRITE_POINTER_NOT_RESET', 'AZ_RIRB_WRITE_POINTER_RESET', + 'AZ_STATE_CHANGE_STATUS', + 'AZ_STATE_CHANGE_STATUS_CODEC_NOT_PRESENT', + 'AZ_STATE_CHANGE_STATUS_CODEC_PRESENT', 'ArrayMode', + 'Available_0x1c', 'Available_0x1d', 'BGRA_TO_BG_G_RB_A', + 'BINNER_BREAK_BATCH', 'BINNER_DROP_ASSERT', 'BINNER_PIPELINE', + 'BINNING_ALLOWED', 'BLEND_BOTH_INV_SRC_ALPHA', + 'BLEND_BOTH_SRC_ALPHA', 'BLEND_CONSTANT_ALPHA', + 'BLEND_CONSTANT_COLOR', 'BLEND_DST_ALPHA', 'BLEND_DST_COLOR', + 'BLEND_INV_SRC1_ALPHA', 'BLEND_INV_SRC1_COLOR', 'BLEND_ONE', + 'BLEND_ONE_MINUS_CONSTANT_ALPHA', + 'BLEND_ONE_MINUS_CONSTANT_COLOR', 'BLEND_ONE_MINUS_DST_ALPHA', + 'BLEND_ONE_MINUS_DST_COLOR', 'BLEND_ONE_MINUS_SRC_ALPHA', + 'BLEND_ONE_MINUS_SRC_COLOR', 'BLEND_OPT_PRESERVE_A0_IGNORE_A1', + 'BLEND_OPT_PRESERVE_A1_IGNORE_A0', + 'BLEND_OPT_PRESERVE_ALL_IGNORE_NONE', + 'BLEND_OPT_PRESERVE_C0_IGNORE_C1', + 'BLEND_OPT_PRESERVE_C1_IGNORE_C0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_A0', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_ALL', + 'BLEND_OPT_PRESERVE_NONE_IGNORE_NONE', 'BLEND_SRC1_ALPHA', + 'BLEND_SRC1_COLOR', 'BLEND_SRC_ALPHA', 'BLEND_SRC_ALPHA_SATURATE', + 'BLEND_SRC_COLOR', 'BLEND_ZERO', + 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN', + 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE', + 'BLNDV_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE', + 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN', + 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE', + 'BLNDV_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE', + 'BLNDV_CONTROL2_PTI_ENABLE', 'BLNDV_CONTROL2_PTI_ENABLE_FALSE', + 'BLNDV_CONTROL2_PTI_ENABLE_TRUE', + 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY', + 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_FALSE', + 'BLNDV_CONTROL_BLND_ACTIVE_OVERLAP_ONLY_TRUE', + 'BLNDV_CONTROL_BLND_ALPHA_MODE', + 'BLNDV_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA', + 'BLNDV_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY', + 'BLNDV_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 'BLNDV_CONTROL_BLND_ALPHA_MODE_UNUSED', + 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN', + 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_FALSE', + 'BLNDV_CONTROL_BLND_FEEDTHROUGH_EN_TRUE', + 'BLNDV_CONTROL_BLND_MODE', + 'BLNDV_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE', + 'BLNDV_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY', + 'BLNDV_CONTROL_BLND_MODE_OTHER_PIPE_ONLY', + 'BLNDV_CONTROL_BLND_MODE_OTHER_STEREO_TYPE', + 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE', + 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE_FALSE', + 'BLNDV_CONTROL_BLND_MULTIPLIED_MODE_TRUE', + 'BLNDV_CONTROL_BLND_STEREO_POLARITY', + 'BLNDV_CONTROL_BLND_STEREO_POLARITY_HIGH', + 'BLNDV_CONTROL_BLND_STEREO_POLARITY_LOW', + 'BLNDV_CONTROL_BLND_STEREO_TYPE', + 'BLNDV_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO', + 'BLNDV_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO', + 'BLNDV_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO', + 'BLNDV_CONTROL_BLND_STEREO_TYPE_UNUSED', + 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT', + 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT_HIGH', + 'BLNDV_DEBUG_BLND_CNV_MUX_SELECT_LOW', + 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE', + 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE', + 'BLNDV_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 'BLNDV_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED', + 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE', + 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE', + 'BLNDV_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE', + 'BLNDV_SM_CONTROL2_SM_MODE', + 'BLNDV_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING', + 'BLNDV_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING', + 'BLNDV_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING', + 'BLNDV_SM_CONTROL2_SM_MODE_SINGLE_PLANE', + 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN', + 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE', + 'BLNDV_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE', + 'BLNDV_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK', + 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE', + 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE', + 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE', + 'BLNDV_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE', + 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN', + 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_FALSE', + 'BLND_CONTROL2_BLND_SUPERAA_DEGAMMA_EN_TRUE', + 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN', + 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_FALSE', + 'BLND_CONTROL2_BLND_SUPERAA_REGAMMA_EN_TRUE', + 'BLND_CONTROL2_PTI_ENABLE', 'BLND_CONTROL2_PTI_ENABLE_FALSE', + 'BLND_CONTROL2_PTI_ENABLE_TRUE', + 'BLND_CONTROL_BLND_ACTIVE_OVERLAP_ONLY', + 'BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_FALSE', + 'BLND_CONTROL_BLND_ACTIVE_OVERLAY_ONLY_TRUE', + 'BLND_CONTROL_BLND_ALPHA_MODE', + 'BLND_CONTROL_BLND_ALPHA_MODE_CURRENT_PIXEL_ALPHA', + 'BLND_CONTROL_BLND_ALPHA_MODE_GLOBAL_ALPHA_ONLY', + 'BLND_CONTROL_BLND_ALPHA_MODE_PIXEL_ALPHA_COMBINED_GLOBAL_GAIN', + 'BLND_CONTROL_BLND_ALPHA_MODE_UNUSED', + 'BLND_CONTROL_BLND_FEEDTHROUGH_EN', + 'BLND_CONTROL_BLND_FEEDTHROUGH_EN_FALSE', + 'BLND_CONTROL_BLND_FEEDTHROUGH_EN_TRUE', 'BLND_CONTROL_BLND_MODE', + 'BLND_CONTROL_BLND_MODE_ALPHA_BLENDING_MODE', + 'BLND_CONTROL_BLND_MODE_CURRENT_PIPE_ONLY', + 'BLND_CONTROL_BLND_MODE_OTHER_PIPE_ONLY', + 'BLND_CONTROL_BLND_MODE_OTHER_STEREO_TYPE', + 'BLND_CONTROL_BLND_MULTIPLIED_MODE', + 'BLND_CONTROL_BLND_MULTIPLIED_MODE_FALSE', + 'BLND_CONTROL_BLND_MULTIPLIED_MODE_TRUE', + 'BLND_CONTROL_BLND_STEREO_POLARITY', + 'BLND_CONTROL_BLND_STEREO_POLARITY_HIGH', + 'BLND_CONTROL_BLND_STEREO_POLARITY_LOW', + 'BLND_CONTROL_BLND_STEREO_TYPE', + 'BLND_CONTROL_BLND_STEREO_TYPE_NON_SINGLE_PIPE_STEREO', + 'BLND_CONTROL_BLND_STEREO_TYPE_SIDE_BY_SIDE_SINGLE_PIPE_STEREO', + 'BLND_CONTROL_BLND_STEREO_TYPE_TOP_BOTTOM_SINGLE_PIPE_STEREO', + 'BLND_CONTROL_BLND_STEREO_TYPE_UNUSED', + 'BLND_DEBUG_BLND_CNV_MUX_SELECT', + 'BLND_DEBUG_BLND_CNV_MUX_SELECT_HIGH', + 'BLND_DEBUG_BLND_CNV_MUX_SELECT_LOW', + 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE', + 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_FALSE', + 'BLND_SM_CONTROL2_SM_FIELD_ALTERNATE_TRUE', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_HIGH', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_FORCE_LOW', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_NO_FORCE', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_FRAME_POL_RESERVED', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_HIGH', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_FORCE_LOW', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_NO_FORCE', + 'BLND_SM_CONTROL2_SM_FORCE_NEXT_TOP_POL_RESERVED', + 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE', + 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_FALSE', + 'BLND_SM_CONTROL2_SM_FRAME_ALTERNATE_TRUE', + 'BLND_SM_CONTROL2_SM_MODE', + 'BLND_SM_CONTROL2_SM_MODE_CHECKERBOARD_SUBSAMPLING', + 'BLND_SM_CONTROL2_SM_MODE_COLUMN_SUBSAMPLING', + 'BLND_SM_CONTROL2_SM_MODE_ROW_SUBSAMPLING', + 'BLND_SM_CONTROL2_SM_MODE_SINGLE_PLANE', + 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN', + 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_FALSE', + 'BLND_TEST_DEBUG_INDEX_BLND_TEST_DEBUG_WRITE_EN_TRUE', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_FALSE', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_ACK_TRUE', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_FALSE', + 'BLND_UNDERFLOW_INTERRUPT_BLND_UNDERFLOW_INT_MASK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_BLND_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR2_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_CUR_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_SURF_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_DCP_GRPH_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK', + 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_SCL_V_UPDATE_LOCK_TRUE', + 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE', + 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_FALSE', + 'BLND_V_UPDATE_LOCK_BLND_V_UPDATE_LOCK_MODE_TRUE', + 'BLOCK_CONTEXT_DONE', 'BOTTOM_OF_PIPE_TS', 'BREAK_BATCH', + 'BUF_DATA_FORMAT', 'BUF_DATA_FORMAT_10_10_10_2', + 'BUF_DATA_FORMAT_10_11_11', 'BUF_DATA_FORMAT_11_11_10', + 'BUF_DATA_FORMAT_16', 'BUF_DATA_FORMAT_16_16', + 'BUF_DATA_FORMAT_16_16_16_16', 'BUF_DATA_FORMAT_2_10_10_10', + 'BUF_DATA_FORMAT_32', 'BUF_DATA_FORMAT_32_32', + 'BUF_DATA_FORMAT_32_32_32', 'BUF_DATA_FORMAT_32_32_32_32', + 'BUF_DATA_FORMAT_8', 'BUF_DATA_FORMAT_8_8', + 'BUF_DATA_FORMAT_8_8_8_8', 'BUF_DATA_FORMAT_INVALID', + 'BUF_DATA_FORMAT_RESERVED_15', 'BUF_NUM_FORMAT', + 'BUF_NUM_FORMAT_FLOAT', 'BUF_NUM_FORMAT_SINT', + 'BUF_NUM_FORMAT_SNORM', 'BUF_NUM_FORMAT_SSCALED', + 'BUF_NUM_FORMAT_UINT', 'BUF_NUM_FORMAT_UNORM', + 'BUF_NUM_FORMAT_UNORM_UINT', 'BUF_NUM_FORMAT_USCALED', + 'BankHeight', 'BankInterleaveSize', 'BankSwapBytes', 'BankTiling', + 'BankWidth', 'BankWidthHeight', 'BinEventCntl', 'BinningMode', + 'BlendOp', 'BlendOpt', 'CACHE_FLUSH', 'CACHE_FLUSH_AND_INV_EVENT', + 'CACHE_FLUSH_AND_INV_TS_EVENT', 'CACHE_FLUSH_TS', 'CBMode', + 'CBPerfClearFilterSel', 'CBPerfOpFilterSel', 'CBPerfSel', + 'CB_DCC_DECOMPRESS', 'CB_DECOMPRESS', 'CB_DISABLE', + 'CB_ELIMINATE_FAST_CLEAR', 'CB_FMASK_DECOMPRESS', 'CB_NORMAL', + 'CB_PERF_CLEAR_FILTER_SEL_CLEAR', + 'CB_PERF_CLEAR_FILTER_SEL_NONCLEAR', + 'CB_PERF_OP_FILTER_SEL_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_ELIMINATE_FAST_CLEAR', + 'CB_PERF_OP_FILTER_SEL_FMASK_DECOMPRESS', + 'CB_PERF_OP_FILTER_SEL_NEEDS_DESTINATION', + 'CB_PERF_OP_FILTER_SEL_RESOLVE', + 'CB_PERF_OP_FILTER_SEL_WRITE_ONLY', + 'CB_PERF_SEL_BLENDER_RAW_HAZARD_STALL', + 'CB_PERF_SEL_BLEND_OPT_PIXELS_RESULT_EQ_DEST', 'CB_PERF_SEL_BUSY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READY', + 'CB_PERF_SEL_CB_TAP_RDREQ_VALID_READYB', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READY', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALIDB_READYB', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READY', + 'CB_PERF_SEL_CB_TAP_WRREQ_VALID_READYB', + 'CB_PERF_SEL_CCR_TO_CCW_REGION_BUSY', + 'CB_PERF_SEL_CC_BC_CS_FRAG_VALID', + 'CB_PERF_SEL_CC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_CC_CACHE_FLUSH', 'CB_PERF_SEL_CC_CACHE_HIT', + 'CB_PERF_SEL_CC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_CC_CACHE_READS_SAVED_DUE_TO_DCC', + 'CB_PERF_SEL_CC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_CC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_CC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CC_CACHE_STALL', + 'CB_PERF_SEL_CC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_CC_CACHE_TAG_MISS', + 'CB_PERF_SEL_CC_CACHE_WA_TO_RMW_CONVERSION', + 'CB_PERF_SEL_CC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CC_DCC_BEYOND_TILE_SPLIT', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_2TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_4TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO4', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_6TO5', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO1', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO2', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO3', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO4', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO5', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO6', + 'CB_PERF_SEL_CC_DCC_COMPRESS_RATIO_8TO7', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_IN', + 'CB_PERF_SEL_CC_DCC_COMPRESS_TIDS_OUT', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_IN', + 'CB_PERF_SEL_CC_DCC_DECOMPRESS_TIDS_OUT', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_2TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_4TO4__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__1BLOCK_6TO6', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__2BLOCKS_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__3BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV0', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO1__INV1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_2TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_4TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__1BLOCK_6TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__2BLOCKS_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__3BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV0', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_2TO2__INV1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO2__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO3__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_4TO4__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO2__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO3__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO4__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO5__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_6TO6__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO5', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO6', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__1BLOCK_8TO7', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__1BLOCK_4TO4', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO1__2BLOCKS_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__1BLOCK_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_2TO2__2BLOCKS_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__2BLOCKS_4TO3', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__3BLOCKS_2TO2__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__4_BLOCKS__2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV0__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO1', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__INV1__1BLOCK_2TO2', + 'CB_PERF_SEL_CC_DCC_KEY_VALUE__UNCOMPRESSED', + 'CB_PERF_SEL_CC_DCC_RDREQ_STALL', + 'CB_PERF_SEL_CC_EVENFIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READY', + 'CB_PERF_SEL_CC_IB_SR_FRAG_VALID_READYB', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READY', + 'CB_PERF_SEL_CC_IB_TB_FRAG_VALID_READYB', + 'CB_PERF_SEL_CC_MC_READ_REQUEST', + 'CB_PERF_SEL_CC_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_MC_WRITE_REQUEST', + 'CB_PERF_SEL_CC_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CC_ODDFIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READY', + 'CB_PERF_SEL_CC_RB_BC_EVENFRAG_VALID_READYB', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READY', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALIDB_READYB', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READY', + 'CB_PERF_SEL_CC_RB_BC_ODDFRAG_VALID_READYB', + 'CB_PERF_SEL_CC_RB_FULL', 'CB_PERF_SEL_CC_SF_FULL', + 'CB_PERF_SEL_CC_SURFACE_SYNC', 'CB_PERF_SEL_CMASK_READ_DATA_0xC', + 'CB_PERF_SEL_CMASK_READ_DATA_0xD', + 'CB_PERF_SEL_CMASK_READ_DATA_0xE', + 'CB_PERF_SEL_CMASK_READ_DATA_0xF', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xC', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xD', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xE', + 'CB_PERF_SEL_CMASK_WRITE_DATA_0xF', + 'CB_PERF_SEL_CMR_TO_FCR_REGION_BUSY', + 'CB_PERF_SEL_CM_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_CM_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_CM_CACHE_FLUSH', 'CB_PERF_SEL_CM_CACHE_HIT', + 'CB_PERF_SEL_CM_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_CM_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_CM_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_CM_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_CM_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_SECTOR_MISS', 'CB_PERF_SEL_CM_CACHE_STALL', + 'CB_PERF_SEL_CM_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_CM_CACHE_TAG_MISS', + 'CB_PERF_SEL_CM_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READY', + 'CB_PERF_SEL_CM_FC_TILE_VALIDB_READYB', + 'CB_PERF_SEL_CM_FC_TILE_VALID_READY', + 'CB_PERF_SEL_CM_FC_TILE_VALID_READYB', + 'CB_PERF_SEL_CM_MC_READ_REQUEST', + 'CB_PERF_SEL_CM_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CM_MC_WRITE_REQUEST', + 'CB_PERF_SEL_CM_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_CM_TQ_FIFO_TILE_RESIDENCY_STALL', + 'CB_PERF_SEL_CM_TQ_FULL', 'CB_PERF_SEL_CORE_SCLK_VLD', + 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_LQUAD_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READY', + 'CB_PERF_SEL_DB_CB_LQUAD_VALID_READYB', + 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READY', + 'CB_PERF_SEL_DB_CB_TILE_VALIDB_READYB', + 'CB_PERF_SEL_DB_CB_TILE_VALID_READY', + 'CB_PERF_SEL_DB_CB_TILE_VALID_READYB', 'CB_PERF_SEL_DRAWN_BUSY', + 'CB_PERF_SEL_DRAWN_PIXEL', 'CB_PERF_SEL_DRAWN_QUAD', + 'CB_PERF_SEL_DRAWN_QUAD_FRAGMENT', 'CB_PERF_SEL_DRAWN_TILE', + 'CB_PERF_SEL_DUAL_SOURCE_COLOR_QUAD_FRAGMENT', + 'CB_PERF_SEL_EVENT', 'CB_PERF_SEL_EVENT_CACHE_FLUSH', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_AND_INV_TS_EVENT', + 'CB_PERF_SEL_EVENT_CACHE_FLUSH_TS', + 'CB_PERF_SEL_EVENT_CONTEXT_DONE', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_DATA_TS', + 'CB_PERF_SEL_EVENT_FLUSH_AND_INV_CB_META', + 'CB_PERF_SEL_EXPORT_32_ABGR_QUAD_FRAGMENT', + 'CB_PERF_SEL_FCR_TO_CCR_REGION_BUSY', + 'CB_PERF_SEL_FC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_FC_CACHE_FLUSH', 'CB_PERF_SEL_FC_CACHE_HIT', + 'CB_PERF_SEL_FC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_FC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_FC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_FC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_SECTOR_MISS', 'CB_PERF_SEL_FC_CACHE_STALL', + 'CB_PERF_SEL_FC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_FC_CACHE_TAG_MISS', + 'CB_PERF_SEL_FC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READY', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALIDB_READYB', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READY', + 'CB_PERF_SEL_FC_CC_QUADFRAG_VALID_READYB', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READY', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALIDB_READYB', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READY', + 'CB_PERF_SEL_FC_CLEAR_QUAD_VALID_READYB', + 'CB_PERF_SEL_FC_DCC_CACHE_ACK_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_DIRTY_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_EVICT_NONZERO_INFLIGHT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_FLUSH', 'CB_PERF_SEL_FC_DCC_CACHE_HIT', + 'CB_PERF_SEL_FC_DCC_CACHE_INFLIGHT_COUNTER_MAXIMUM_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_READ_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_REEVICTION_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_REPLACE_PENDING_EVICT_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_SECTORS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_SECTOR_MISS', + 'CB_PERF_SEL_FC_DCC_CACHE_STALL', + 'CB_PERF_SEL_FC_DCC_CACHE_TAGS_FLUSHED', + 'CB_PERF_SEL_FC_DCC_CACHE_TAG_MISS', + 'CB_PERF_SEL_FC_DCC_CACHE_WRITE_OUTPUT_STALL', + 'CB_PERF_SEL_FC_DCC_KEY_VALUE__CLEAR', + 'CB_PERF_SEL_FC_DOC_CLINE_CAM_HIT', + 'CB_PERF_SEL_FC_DOC_CLINE_CAM_MISS', + 'CB_PERF_SEL_FC_DOC_IS_STALLED', + 'CB_PERF_SEL_FC_DOC_MRTS_COMBINED', + 'CB_PERF_SEL_FC_DOC_MRTS_NOT_COMBINED', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_1_SECTOR', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_2_SECTORS', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_3_SECTORS', + 'CB_PERF_SEL_FC_DOC_OVERWROTE_4_SECTORS', + 'CB_PERF_SEL_FC_DOC_QTILE_CAM_HIT', + 'CB_PERF_SEL_FC_DOC_QTILE_CAM_MISS', + 'CB_PERF_SEL_FC_DOC_QUAD_PTR_FIFO_IS_FULL', + 'CB_PERF_SEL_FC_DOC_TOTAL_OVERWRITTEN_SECTORS', + 'CB_PERF_SEL_FC_KEYID_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FC_MC_DCC_READ_REQUEST', + 'CB_PERF_SEL_FC_MC_DCC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUEST', + 'CB_PERF_SEL_FC_MC_DCC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_READ_REQUEST', + 'CB_PERF_SEL_FC_MC_READ_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_MC_WRITE_REQUEST', + 'CB_PERF_SEL_FC_MC_WRITE_REQUESTS_IN_FLIGHT', + 'CB_PERF_SEL_FC_PF_SLOW_MODE_QUAD_EMPTY_HALF_DROPPED', + 'CB_PERF_SEL_FC_QUAD_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FC_RDLAT_FIFO_QUAD_RESIDENCY_STALL', + 'CB_PERF_SEL_FC_SEQUENCER_CLEAR', + 'CB_PERF_SEL_FC_SEQUENCER_ELIMINATE_FAST_CLEAR', + 'CB_PERF_SEL_FC_SEQUENCER_FMASK_COMPRESSION_DISABLE', + 'CB_PERF_SEL_FC_SEQUENCER_FMASK_DECOMPRESS', + 'CB_PERF_SEL_FC_TILE_RDLAT_FIFO_FULL', + 'CB_PERF_SEL_FOP_FMASK_BYPASS_STALL', + 'CB_PERF_SEL_FOP_FMASK_RAW_STALL', + 'CB_PERF_SEL_FOP_IN_VALIDB_READY', + 'CB_PERF_SEL_FOP_IN_VALIDB_READYB', + 'CB_PERF_SEL_FOP_IN_VALID_READY', + 'CB_PERF_SEL_FOP_IN_VALID_READYB', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_AR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_GR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_32_R', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_FP16_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_SIGNED16_ABGR', + 'CB_PERF_SEL_LQUAD_FORMAT_IS_EXPORT_UNSIGNED16_ABGR', + 'CB_PERF_SEL_LQUAD_NO_TILE', + 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READY', + 'CB_PERF_SEL_MERGE_TILE_ONLY_VALID_READYB', 'CB_PERF_SEL_NONE', + 'CB_PERF_SEL_QUAD_ADDED_1_FRAGMENT', + 'CB_PERF_SEL_QUAD_ADDED_2_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_3_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_4_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_5_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_6_FRAGMENTS', + 'CB_PERF_SEL_QUAD_ADDED_7_FRAGMENTS', + 'CB_PERF_SEL_QUAD_BLENDING_COULD_HAVE_BEEN_BYPASSED', + 'CB_PERF_SEL_QUAD_BLEND_OPT_BLEND_BYPASS', + 'CB_PERF_SEL_QUAD_BLEND_OPT_DISCARD_PIXELS', + 'CB_PERF_SEL_QUAD_BLEND_OPT_DONT_READ_DST', + 'CB_PERF_SEL_QUAD_COULD_HAVE_BEEN_DISCARDED', + 'CB_PERF_SEL_QUAD_DST_READ_COULD_HAVE_BEEN_OPTIMIZED', + 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_1_FRAGMENT_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_2_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_3_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_4_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_5_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_6_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_7_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_AFTER_UPDATE', + 'CB_PERF_SEL_QUAD_HAS_8_FRAGMENTS_BEFORE_UPDATE', + 'CB_PERF_SEL_QUAD_KILLED_BY_COLOR_INVALID', + 'CB_PERF_SEL_QUAD_KILLED_BY_DISCARD_PIXEL', + 'CB_PERF_SEL_QUAD_KILLED_BY_EXTRA_PIXEL_EXPORT', + 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_SAMPLE_MASK', + 'CB_PERF_SEL_QUAD_KILLED_BY_NULL_TARGET_SHADER_MASK', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_0', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_1', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_2', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_3', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_4', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_5', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_6', + 'CB_PERF_SEL_QUAD_READS_FRAGMENT_7', + 'CB_PERF_SEL_QUAD_REMOVED_1_FRAGMENT', + 'CB_PERF_SEL_QUAD_REMOVED_2_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_3_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_4_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_5_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_6_FRAGMENTS', + 'CB_PERF_SEL_QUAD_REMOVED_7_FRAGMENTS', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_0', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_1', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_2', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_3', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_4', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_5', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_6', + 'CB_PERF_SEL_QUAD_WRITES_FRAGMENT_7', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_BOTH', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_LEFT', + 'CB_PERF_SEL_RBP_EXPORT_8PIX_LIT_RIGHT', + 'CB_PERF_SEL_RBP_INSERT_MISSING_LAST_QUAD', + 'CB_PERF_SEL_RBP_SPLIT_AA_NO_FMASK_COMPRESS', + 'CB_PERF_SEL_RBP_SPLIT_AA_SAMPLE_MASK', + 'CB_PERF_SEL_RBP_SPLIT_LINEAR_ADDRESSING', + 'CB_PERF_SEL_RBP_SPLIT_MICROTILE', + 'CB_PERF_SEL_RBP_SPLIT_PARTIAL_TARGET_MASK', + 'CB_PERF_SEL_REG_SCLK0_VLD', 'CB_PERF_SEL_REG_SCLK1_VLD', + 'CB_PERF_SEL_TILE_TO_CMR_REGION_BUSY', + 'CB_PERF_SEL_TWO_PROBE_QUAD_FRAGMENT', 'CB_RESOLVE', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_INPUT_PORT_CONNECTIVITY_INPUT_PORT_CONNECTIVITY_ALL', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_0', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_1', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_2', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_3', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_4', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_5', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_6', + 'CC_RCU_DC_AUDIO_PORT_CONNECTIVITY_PORT_CONNECTIVITY_ALL', + 'CENTERS_ONLY', 'CENTROIDS_AND_CENTERS', 'CENTROIDS_ONLY', + 'CHUB_TC_RET_CREDITS', 'CHUB_TC_RET_CREDITS_ENUM', + 'CLEAR_SMU_INTR', 'CLKGATE_BASE_MODE', 'CLKGATE_SM_MODE', + 'CLOCK_BRANCH_SOFT_RESET', 'CLOCK_BRANCH_SOFT_RESET_FORCE', + 'CLOCK_BRANCH_SOFT_RESET_NOOP', 'CLOCK_GATING_DISABLED', + 'CLOCK_GATING_DISABLED_IN_DCO', 'CLOCK_GATING_ENABLED', + 'CLOCK_GATING_ENABLED_IN_DCO', 'CMASK_ADDR_COMPATIBLE', + 'CMASK_ADDR_LINEAR', 'CMASK_ADDR_TILED', 'CMASK_ALPHA0_FRAG1', + 'CMASK_ALPHA0_FRAG2', 'CMASK_ALPHA0_FRAG4', 'CMASK_ALPHA0_FRAGS', + 'CMASK_ALPHA1_FRAG1', 'CMASK_ALPHA1_FRAG2', 'CMASK_ALPHA1_FRAG4', + 'CMASK_ALPHA1_FRAGS', 'CMASK_ALPHAX_FRAG1', 'CMASK_ALPHAX_FRAG2', + 'CMASK_ALPHAX_FRAG4', 'CMASK_ALPHAX_FRAGS', 'CMASK_ANY_EXPANDED', + 'CMASK_CLEAR_ALL', 'CMASK_CLEAR_NONE', 'CMASK_CLEAR_ONE', + 'CMASK_CLR00_F0', 'CMASK_CLR00_F1', 'CMASK_CLR00_F2', + 'CMASK_CLR00_FX', 'CMASK_CLR01_F0', 'CMASK_CLR01_F1', + 'CMASK_CLR01_F2', 'CMASK_CLR01_FX', 'CMASK_CLR10_F0', + 'CMASK_CLR10_F1', 'CMASK_CLR10_F2', 'CMASK_CLR10_FX', + 'CMASK_CLR11_F0', 'CMASK_CLR11_F1', 'CMASK_CLR11_F2', + 'CMASK_CLR11_FX', 'CMD_EMBEDDED_MODE_DISABLE', + 'CMD_EMBEDDED_MODE_ENABLE', 'CM_GLOBAL_PASSTHROUGH_DISBALE', + 'CM_GLOBAL_PASSTHROUGH_ENABLE', 'COEF_UPDATE_COMPLETE', + 'COEF_UPDATE_NOT_COMPLETE', 'COLOR_10_10_10_2', 'COLOR_10_11_11', + 'COLOR_11_11_10', 'COLOR_16', 'COLOR_16_16', 'COLOR_16_16_16_16', + 'COLOR_1_5_5_5', 'COLOR_24_8', 'COLOR_2_10_10_10', + 'COLOR_2_10_10_10_6E4', 'COLOR_32', 'COLOR_32_32', + 'COLOR_32_32_32_32', 'COLOR_4_4_4_4', 'COLOR_5_5_5_1', + 'COLOR_5_6_5', 'COLOR_8', 'COLOR_8_24', 'COLOR_8_8', + 'COLOR_8_8_8_8', 'COLOR_INVALID', 'COLOR_RESERVED_13', + 'COLOR_RESERVED_15', 'COLOR_RESERVED_23', 'COLOR_RESERVED_24', + 'COLOR_RESERVED_25', 'COLOR_RESERVED_26', 'COLOR_RESERVED_27', + 'COLOR_RESERVED_28', 'COLOR_RESERVED_29', 'COLOR_RESERVED_30', + 'COLOR_X24_8_32_FLOAT', 'COL_MAN_DEGAMMA_MODE', + 'COL_MAN_DENORM_CLAMP_CONTROL', 'COL_MAN_DISABLE_MULTIPLE_UPDATE', + 'COL_MAN_GAMUT_REMAP_MODE', 'COL_MAN_GLOBAL_PASSTHROUGH_ENABLE', + 'COL_MAN_INPUTCSC_CONVERT', 'COL_MAN_INPUTCSC_MODE', + 'COL_MAN_INPUTCSC_TYPE', 'COL_MAN_INPUT_GAMMA_MODE', + 'COL_MAN_MULTIPLE_UPDATE', 'COL_MAN_MULTIPLE_UPDAT_EDISABLE', + 'COL_MAN_OUTPUT_CSC_A', 'COL_MAN_OUTPUT_CSC_B', + 'COL_MAN_OUTPUT_CSC_BYPASS', 'COL_MAN_OUTPUT_CSC_MODE', + 'COL_MAN_OUTPUT_CSC_RGB', 'COL_MAN_OUTPUT_CSC_UNITY', + 'COL_MAN_OUTPUT_CSC_YCrCb601', 'COL_MAN_OUTPUT_CSC_YCrCb709', + 'COL_MAN_PRESCALE_MODE', 'COL_MAN_REGAMMA_MODE_A', + 'COL_MAN_REGAMMA_MODE_B', 'COL_MAN_REGAMMA_MODE_BYPASS', + 'COL_MAN_REGAMMA_MODE_CONTROL', 'COL_MAN_REGAMMA_MODE_ROM_A', + 'COL_MAN_REGAMMA_MODE_ROM_B', 'COL_MAN_UPDATE_LOCK', + 'COL_MAN_UPDATE_LOCKED', 'COL_MAN_UPDATE_UNLOCKED', + 'COMB_DST_MINUS_SRC', 'COMB_DST_PLUS_SRC', 'COMB_MAX_DST_SRC', + 'COMB_MIN_DST_SRC', 'COMB_SRC_MINUS_DST', 'COMPONENT_DEPTH_10BPC', + 'COMPONENT_DEPTH_12BPC', 'COMPONENT_DEPTH_16BPC', + 'COMPONENT_DEPTH_6BPC', 'COMPONENT_DEPTH_8BPC', + 'CONFIG_128B_SWAPS', 'CONFIG_1KB_ROW', 'CONFIG_1KB_ROW_OPT', + 'CONFIG_1KB_SPLIT', 'CONFIG_1KB_SWAPS', 'CONFIG_1_PIPE', + 'CONFIG_256B_GROUP', 'CONFIG_256B_SWAPS', 'CONFIG_2KB_ROW', + 'CONFIG_2KB_ROW_OPT', 'CONFIG_2KB_SPLIT', 'CONFIG_2_PIPE', + 'CONFIG_4KB_ROW', 'CONFIG_4KB_ROW_OPT', 'CONFIG_4KB_SPLIT', + 'CONFIG_4_BANK', 'CONFIG_4_PIPE', 'CONFIG_512B_GROUP', + 'CONFIG_512B_SWAPS', 'CONFIG_8KB_ROW', 'CONFIG_8KB_ROW_OPT', + 'CONFIG_8KB_SPLIT', 'CONFIG_8_BANK', 'CONFIG_8_PIPE', + 'CONFIG_SPACE1_END', 'CONFIG_SPACE1_START', 'CONFIG_SPACE2_END', + 'CONFIG_SPACE2_START', 'CONFIG_SPACE_END', 'CONFIG_SPACE_START', + 'CONTEXT_DONE', 'CONTEXT_SPACE_END', 'CONTEXT_SPACE_START', + 'CONTEXT_SUSPEND', 'CONTROLLER_RESET_AZ_CONTROLLER_IN_RESET', + 'CONTROLLER_RESET_AZ_CONTROLLER_NOT_IN_RESET', + 'CORB_READ_POINTER_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_NOT_RESET', + 'CORB_READ_POINTER_RESET_CORB_DMA_IS_RESET', 'COUNTER_RING_0', + 'COUNTER_RING_1', 'COUNTER_RING_SPLIT', 'CPC_PERFCOUNT_SEL', + 'CPC_PERF_SEL_ALWAYS_COUNT', + 'CPC_PERF_SEL_ME1_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME1_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_MIU_WRITE', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME1_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_ME2_BUSY_FOR_PACKET_DECODE', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ', + 'CPC_PERF_SEL_ME2_STALL_ON_DATA_FROM_ROQ_PERF', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_MIU_WRITE', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READ', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY', + 'CPC_PERF_SEL_ME2_STALL_WAIT_ON_RCIU_READY_PERF', + 'CPC_PERF_SEL_MIU_STALL_ON_RDREQ_FREE', + 'CPC_PERF_SEL_MIU_STALL_ON_WRREQ_FREE', + 'CPC_PERF_SEL_RCIU_STALL_PRIV_VIOLATION', + 'CPC_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPC_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPC_TAG_RAM', + 'CPF_PERFCOUNT_SEL', 'CPF_PERF_SEL_ALWAYS_COUNT', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FECTHINC_STATE', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB1', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_IB2', + 'CPF_PERF_SEL_CSF_BUSY_FOR_FETCHING_RING', + 'CPF_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPF_PERF_SEL_CSF_RTS_MIU_NOT_RTR', + 'CPF_PERF_SEL_CSF_STATE_FIFO_NOT_RTR', + 'CPF_PERF_SEL_DYNAMIC_CLOCK_VALID', + 'CPF_PERF_SEL_GRBM_DWORDS_SENT', + 'CPF_PERF_SEL_MIU_BUSY_FOR_OUTSTANDING_TAGS', + 'CPF_PERF_SEL_MIU_READ_REQUEST_SEND', + 'CPF_PERF_SEL_MIU_STALLED_WAITING_RDREQ_FREE', + 'CPF_PERF_SEL_MIU_WRITE_REQUEST_SEND', + 'CPF_PERF_SEL_RCIU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_REGISTER_CLOCK_VALID', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_FREE', + 'CPF_PERF_SEL_TCIU_STALLED_WAITING_ON_TAGS', + 'CPF_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPF_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPF_TAG_RAM', + 'CPG_PERFCOUNT_SEL', 'CPG_PERF_SEL_ALWAYS_COUNT', + 'CPG_PERF_SEL_CE_STALL_ON_CE_BUFFER_FLAG', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_MIU', + 'CPG_PERF_SEL_CE_STALL_ON_DATA_FROM_ROQ', + 'CPG_PERF_SEL_CE_STALL_ON_DE_COUNTER', + 'CPG_PERF_SEL_CE_STALL_ON_INC_FIFO', + 'CPG_PERF_SEL_CE_STALL_ON_WR_RAM_FIFO', + 'CPG_PERF_SEL_CE_STALL_RAM_DUMP', + 'CPG_PERF_SEL_CE_STALL_RAM_WRITE', + 'CPG_PERF_SEL_COUNT_TYPE0_PACKETS', + 'CPG_PERF_SEL_COUNT_TYPE3_PACKETS', + 'CPG_PERF_SEL_CP_GDS_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_GRBM_DWORDS_SENT', + 'CPG_PERF_SEL_CP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CP_PFP_GRBM_OUT_OF_CREDITS', + 'CPG_PERF_SEL_CSF_FETCHING_CMD_BUFFERS', + 'CPG_PERF_SEL_CSF_RTS_BUT_MIU_NOT_RTR', + 'CPG_PERF_SEL_CSF_ST_BASE_SIZE_FIFO_FULL', + 'CPG_PERF_SEL_DYNAMIC_CLK_VALID', + 'CPG_PERF_SEL_LOAD_STALLED_ON_SET_COHERENCY', + 'CPG_PERF_SEL_ME_PARSER_BUSY', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_PFP', + 'CPG_PERF_SEL_ME_STALLED_FOR_DATA_FROM_STQ', + 'CPG_PERF_SEL_ME_STALLED_ON_NO_AVAIL_GFX_CNTX', + 'CPG_PERF_SEL_ME_STALLED_ON_PARTIAL_FLUSH', + 'CPG_PERF_SEL_ME_STALLED_WRITING_CONSTANTS', + 'CPG_PERF_SEL_ME_STALLED_WRITING_TO_RCIU', + 'CPG_PERF_SEL_ME_WAIT_ON_AVAIL_BUFFER', + 'CPG_PERF_SEL_ME_WAIT_ON_CE_COUNTER', + 'CPG_PERF_SEL_MIU_READ_REQUEST_SENT', + 'CPG_PERF_SEL_MIU_WRITE_REQUEST_SENT', + 'CPG_PERF_SEL_PFP_STALLED_FOR_DATA_FROM_ROQ', + 'CPG_PERF_SEL_PFP_STALLED_ON_CSF_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_MEQ_READY', + 'CPG_PERF_SEL_PFP_STALLED_ON_RCIU_READY', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_PULSE', + 'CPG_PERF_SEL_QU_STALLED_ON_EOP_DONE_WR_CONFIRM', + 'CPG_PERF_SEL_RBIU_FIFO_FULL', + 'CPG_PERF_SEL_RCIU_STALLED_ON_DMA_READ', + 'CPG_PERF_SEL_RCIU_STALLED_ON_ME_READ', + 'CPG_PERF_SEL_REGISTER_CLK_VALID', + 'CPG_PERF_SEL_SEMAPHORE_BUSY_POLLING_FOR_PASS', + 'CPG_PERF_SEL_SSU_STALLED_ON_ACTIVE_CNTX', + 'CPG_PERF_SEL_SSU_STALLED_ON_CLEAN_SIGNALS', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_TCIU_STALL_WAIT_ON_TAGS', + 'CPG_PERF_SEL_UTCL1_STALL_ON_TRANSLATION', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_FREE', + 'CPG_PERF_SEL_UTCL2IU_STALL_WAIT_ON_TAGS', 'CPG_TAG_RAM', + 'CP_ALPHA_TAG_RAM_SEL', 'CP_ME_ID', 'CP_PERFMON_ENABLE_MODE', + 'CP_PERFMON_ENABLE_MODE_ALWAYS_COUNT', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_FALSE', + 'CP_PERFMON_ENABLE_MODE_COUNT_CONTEXT_TRUE', + 'CP_PERFMON_ENABLE_MODE_RESERVED_1', 'CP_PERFMON_STATE', + 'CP_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'CP_PERFMON_STATE_DISABLE_AND_RESET', + 'CP_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'CP_PERFMON_STATE_RESERVED_3', 'CP_PERFMON_STATE_START_COUNTING', + 'CP_PERFMON_STATE_STOP_COUNTING', 'CP_PIPE_ID', 'CP_RING_ID', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_FALSE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_DB_TRUE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_FALSE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_EN_TRUE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_FALSE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_STEREO_SEL_OVR_TRUE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_BOTH', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_INTERLACE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_BLOCK_PROGRASSIVE', + 'CRTC_3D_STRUCTURE_CONTROL_CRTC_3D_STRUCTURE_V_UPDATE_MODE_RESERVED', + 'CRTC_ADD_PIXEL', 'CRTC_ADD_PIXEL_FORCE', 'CRTC_ADD_PIXEL_NOOP', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_FALSE', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DATA_EN_TRUE', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_FALSE', + 'CRTC_BLANK_CONTROL_CRTC_BLANK_DE_MODE_TRUE', + 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL', + 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE', + 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_CURRENT', + 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_DISABLE_FIRST', + 'CRTC_CONTROL_CRTC_DISABLE_POINT_CNTL_RESERVED', + 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE', + 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_FALSE', + 'CRTC_CONTROL_CRTC_DISP_READ_REQUEST_DISABLE_TRUE', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_DP', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_CNTL_NORMAL', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_FALSE', + 'CRTC_CONTROL_CRTC_FIELD_NUMBER_POLARITY_TRUE', + 'CRTC_CONTROL_CRTC_MASTER_EN', + 'CRTC_CONTROL_CRTC_MASTER_EN_FALSE', + 'CRTC_CONTROL_CRTC_MASTER_EN_TRUE', + 'CRTC_CONTROL_CRTC_SOF_PULL_EN', + 'CRTC_CONTROL_CRTC_SOF_PULL_EN_FALSE', + 'CRTC_CONTROL_CRTC_SOF_PULL_EN_TRUE', + 'CRTC_CONTROL_CRTC_START_POINT_CNTL', + 'CRTC_CONTROL_CRTC_START_POINT_CNTL_DP', + 'CRTC_CONTROL_CRTC_START_POINT_CNTL_NORMAL', + 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN', + 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_FALSE', + 'CRTC_COUNT_CONTROL_CRTC_HORZ_COUNT_BY2_EN_TRUE', + 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN', + 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_FALSE', + 'CRTC_CRC_CNTL_CRTC_CRC_CONT_EN_TRUE', + 'CRTC_CRC_CNTL_CRTC_CRC_EN', 'CRTC_CRC_CNTL_CRTC_CRC_EN_FALSE', + 'CRTC_CRC_CNTL_CRTC_CRC_EN_TRUE', + 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE', + 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_BOTTOM', + 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTH_FIELD', + 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_BOTTOM', + 'CRTC_CRC_CNTL_CRTC_CRC_INTERLACE_MODE_TOP', + 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE', + 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_EYES', + 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_BOTH_FIELDS', + 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_LEFT', + 'CRTC_CRC_CNTL_CRTC_CRC_STEREO_MODE_RIGHT', + 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS', + 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_FALSE', + 'CRTC_CRC_CNTL_CRTC_CRC_USE_NEW_AND_REPEATED_PIXELS_TRUE', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IAB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_IA_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_AB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_I_A_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UAB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_UA_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_AB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC0_SELECT_U_A_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IAB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_IA_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_AB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_I_A_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UAB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_UA_B', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_AB', + 'CRTC_CRC_CNTL_CRTC_CRTC_CRC1_SELECT_U_A_B', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_FALSE', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_BLANK_DATA_DOUBLE_BUFFER_EN_TRUE', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_0', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_RANGE_TIMING_DBUF_UPDATE_MODE_1', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_FALSE', + 'CRTC_DOUBLE_BUFFER_CONTROL_CRTC_UPDATE_INSTANTLY_TRUE', + 'CRTC_DROP_PIXEL', 'CRTC_DROP_PIXEL_FORCE', + 'CRTC_DROP_PIXEL_NOOP', 'CRTC_DRR_MODE_DBUF_UPDATE_MODE', + 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_00_IMMEDIATE', + 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_01_MANUAL', + 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_10_DBUF', + 'CRTC_DRR_MODE_DBUF_UPDATE_MODE_11_SYNCED_DBUF', + 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN', + 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_FALSE', + 'CRTC_DTMTEST_CNTL_CRTC_DTMTEST_CRTC_EN_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_CONTINUOUS', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_DISABLE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_ONESHOT', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_ENABLE_RESERVED', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HCOUNT_MODE_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_HSYNC_POLARITY_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_INTERLACE_MODE_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_1pixel', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_2pixel', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_3pixel', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_JITTER_FILTERING_WINDOW_4pixel', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_VSYNC_POLARITY_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_FALSE', + 'CRTC_EXT_TIMING_SYNC_CONTROL_CRTC_EXT_TIMING_SYNC_WINDOW_UPDATE_TRUE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_FALSE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_CLEAR_TRUE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_FALSE', + 'CRTC_EXT_TIMING_SYNC_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_INT_TYPE_TRUE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_FALSE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_CLEAR_TRUE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_128FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_16FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_1FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_2FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_32FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_4FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_64FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_FRAME_COUNT_8FRAME', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_FALSE', + 'CRTC_EXT_TIMING_SYNC_LOSS_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_LOSS_INT_TYPE_TRUE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_FALSE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_CLEAR_TRUE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_FALSE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_ENABLE_TRUE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_FALSE', + 'CRTC_EXT_TIMING_SYNC_SIGNAL_INTERRUPT_CONTROL_CRTC_EXT_TIMING_SYNC_SIGNAL_INT_TYPE_TRUE', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_FALSE', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_ALIGNMENT_TRUE', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_FALSE', + 'CRTC_FIELD_INDICATION_CONTROL_CRTC_FIELD_INDICATION_OUTPUT_POLARITY_TRUE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_FALSE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_GRANULARITY_TRUE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_FALSE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_POLARITY_TRUE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1CLK', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC1DATA', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2CLK', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DDC2DATA', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_DVOCLK', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICA', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICB', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICC', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICD', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICE', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_GENERICF', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD1', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_HPD2', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC0', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_LOGIC1', + 'CRTC_FLOW_CONTROL_CRTC_FLOW_CONTROL_SOURCE_SELECT_MANUAL', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_FALSE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CHECK_TRUE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_FALSE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_CLEAR_TRUE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_DISABLE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_HCOUNT_VCOUNT', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_MODE_RESERVED', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_FALSE', + 'CRTC_FORCE_COUNT_NOW_CNTL_CRTC_FORCE_COUNT_NOW_TRIG_SEL_TRUE', + 'CRTC_HORZ_REPETITION_COUNT', 'CRTC_HORZ_REPETITION_COUNT_0', + 'CRTC_HORZ_REPETITION_COUNT_1', 'CRTC_HORZ_REPETITION_COUNT_10', + 'CRTC_HORZ_REPETITION_COUNT_11', 'CRTC_HORZ_REPETITION_COUNT_12', + 'CRTC_HORZ_REPETITION_COUNT_13', 'CRTC_HORZ_REPETITION_COUNT_14', + 'CRTC_HORZ_REPETITION_COUNT_15', 'CRTC_HORZ_REPETITION_COUNT_2', + 'CRTC_HORZ_REPETITION_COUNT_3', 'CRTC_HORZ_REPETITION_COUNT_4', + 'CRTC_HORZ_REPETITION_COUNT_5', 'CRTC_HORZ_REPETITION_COUNT_6', + 'CRTC_HORZ_REPETITION_COUNT_7', 'CRTC_HORZ_REPETITION_COUNT_8', + 'CRTC_HORZ_REPETITION_COUNT_9', 'CRTC_H_SYNC_A_POL', + 'CRTC_H_SYNC_A_POL_HIGH', 'CRTC_H_SYNC_A_POL_LOW', + 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL', + 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_FALSE', + 'CRTC_H_SYNC_B_CNTL_CRTC_H_SYNC_B_POL_TRUE', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_FALSE', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_ENABLE_TRUE', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_EVEN', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_NOT2', + 'CRTC_INTERLACE_CONTROL_CRTC_INTERLACE_FORCE_NEXT_FIELD_ODD', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_COUNT_NOW_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_GSL_VSYNC_GAP_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_SNAPSHOT_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGA_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_TRIGB_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_VSYNC_NOM_INT_TYPE_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_MSK_TRUE', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_FALSE', + 'CRTC_INTERRUPT_CONTROL_CRTC_V_UPDATE_INT_TYPE_TRUE', + 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE', + 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_FALSE', + 'CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_CRTC_MANUAL_FORCE_VSYNC_NEXT_LINE_TRUE', + 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE', + 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DEBUG', + 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_DISABLE', + 'CRTC_MVP_INBAND_CNTL_INSERT_CRTC_MVP_INBAND_OUT_MODE_NORMAL', + 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR', + 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_FALSE', + 'CRTC_MVP_STATUS_CRTC_AFR_HSYNC_SWITCH_DONE_CLEAR_TRUE', + 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR', + 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_FALSE', + 'CRTC_MVP_STATUS_CRTC_FLIP_NOW_CLEAR_TRUE', + 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL', + 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_DISABLE', + 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_RESERVED', + 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERA', + 'CRTC_SNAPSHOT_CONTROL_CRTC_AUTO_SNAPSHOT_TRIG_SEL_TRIGGERB', + 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR', + 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_FALSE', + 'CRTC_SNAPSHOT_STATUS_CRTC_SNAPSHOT_CLEAR_TRUE', + 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY', + 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_FALSE', + 'CRTC_START_LINE_CONTROL_CRTC_INTERLACE_START_LINE_EARLY_TRUE', + 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN', + 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_FALSE', + 'CRTC_START_LINE_CONTROL_CRTC_LEGACY_REQUESTOR_EN_TRUE', + 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN', + 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_FALSE', + 'CRTC_START_LINE_CONTROL_CRTC_PREFETCH_EN_TRUE', + 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY', + 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_FALSE', + 'CRTC_START_LINE_CONTROL_CRTC_PROGRESSIVE_START_LINE_EARLY_TRUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_FALSE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_CLEAR_TRUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_FALSE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_ENABLE_TRUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_FALSE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_CPU_SS_INT_TYPE_TRUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_FALSE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_TRUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_OFF', + 'CRTC_STATIC_SCREEN_CONTROL_CRTC_STATIC_SCREEN_OVERRIDE_VALUE_ON', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN_FALSE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EN_TRUE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_FALSE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_EYE_FLAG_POLARITY_TRUE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_FALSE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_OUTPUT_POLARITY_TRUE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_FALSE', + 'CRTC_STEREO_CONTROL_CRTC_STEREO_SYNC_SELECT_POLARITY_TRUE', + 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE', + 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_LEFT', + 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_NO', + 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RESERVED', + 'CRTC_STEREO_FORCE_NEXT_EYE_CRTC_STEREO_FORCE_NEXT_EYE_RIGHT', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_10BPC', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_6BPC', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_8BPC', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_COLOR_FORMAT_RESERVED', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_FALSE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_DYNAMIC_RANGE_TRUE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_FALSE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_EN_TRUE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_DRRGB', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_HBARS', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_RGB', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_SRRGB', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_VBARS', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_XRBIAS', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR601', + 'CRTC_TEST_PATTERN_CONTROL_CRTC_TEST_PATTERN_MODE_YCBCR709', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_FALSE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_CLEAR_TRUE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICA', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICB', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_GENERICC', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCA', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_HSYNCB', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_INTERLACE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_POLARITY_SELECT_VIDEO', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_FALSE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_RESYNC_BYPASS_EN_TRUE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICA', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICB', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICC', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICD', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICE', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_GENERICF', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD1', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HPD2', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCA_OTHER', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_HSYNCB', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IBLON', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL0', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL1', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL2', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_IGSL_ALLOW', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_MANUAL_FLOW', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCA_OTHER', + 'CRTC_TRIGA_CNTL_CRTC_TRIGA_SOURCE_SELECT_VSYNCB', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_FALSE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_CLEAR_TRUE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICA', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICB', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_GENERICC', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCA', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_HSYNCB', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_INTERLACE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_POLARITY_SELECT_VIDEO', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_FALSE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_RESYNC_BYPASS_EN_TRUE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICA', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICB', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICC', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICD', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICE', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_GENERICF', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD1', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HPD2', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCA_OTHER', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_HSYNCB', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IBLON', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL0', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL1', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL2', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_IGSL_ALLOW', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_MANUAL_FLOW', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCA_OTHER', + 'CRTC_TRIGB_CNTL_CRTC_TRIGB_SOURCE_SELECT_VSYNCB', + 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK', + 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_FALSE', + 'CRTC_UPDATE_LOCK_CRTC_UPDATE_LOCK_TRUE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_FALSE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_CLEAR_TRUE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_FALSE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_ENABLE_TRUE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_FALSE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_INT_TYPE_TRUE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_FALSE', + 'CRTC_VERTICAL_INTERRUPT0_CONTROL_CRTC_VERTICAL_INTERRUPT0_OUTPUT_POLARITY_TRUE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_CLEAR_FALSE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_CLEAR_TRUE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_FALSE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_ENABLE_TRUE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_FALSE', + 'CRTC_VERTICAL_INTERRUPT1_CONTROL_CRTC_VERTICAL_INTERRUPT1_INT_TYPE_TRUE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_CLEAR_FALSE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_CLEAR_TRUE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_FALSE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_ENABLE_TRUE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_FALSE', + 'CRTC_VERTICAL_INTERRUPT2_CONTROL_CRTC_VERTICAL_INTERRUPT2_INT_TYPE_TRUE', + 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE', + 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_DISABLE', + 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_RESERVED', + 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERA', + 'CRTC_VERT_SYNC_CONTROL_CRTC_AUTO_FORCE_VSYNC_MODE_TRIGGERB', + 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR', + 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_FALSE', + 'CRTC_VERT_SYNC_CONTROL_CRTC_FORCE_VSYNC_NEXT_LINE_CLEAR_TRUE', + 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE', + 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_FALSE', + 'CRTC_VGA_PARAMETER_CAPTURE_MODE_CRTC_VGA_PARAMETER_CAPTURE_MODE_TRUE', + 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR', + 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_FALSE', + 'CRTC_VSYNC_NOM_INT_STATUS_CRTC_VSYNC_NOM_INT_CLEAR_TRUE', + 'CRTC_V_SYNC_A_POL', 'CRTC_V_SYNC_A_POL_HIGH', + 'CRTC_V_SYNC_A_POL_LOW', 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL', + 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_FALSE', + 'CRTC_V_SYNC_B_CNTL_CRTC_V_SYNC_B_POL_TRUE', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_DISABLE', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_ON_EVENT_ENABLE', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_DISABLE', + 'CRTC_V_TOTAL_CONTROL_CRTC_FORCE_LOCK_TO_MASTER_VSYNC_ENABLE', + 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN', + 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_FALSE', + 'CRTC_V_TOTAL_CONTROL_CRTC_SET_V_TOTAL_MIN_MASK_EN_TRUE', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_FALSE', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MAX_SEL_TRUE', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_FALSE', + 'CRTC_V_TOTAL_CONTROL_CRTC_V_TOTAL_MIN_SEL_TRUE', + 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK', + 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_FALSE', + 'CRTC_V_TOTAL_INT_STATUS_CRTC_SET_V_TOTAL_MIN_EVENT_OCCURED_ACK_TRUE', + 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR', + 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_FALSE', + 'CRTC_V_UPDATE_INT_STATUS_CRTC_V_UPDATE_INT_CLEAR_TRUE', + 'CSDATA_ADDR_WIDTH', 'CSDATA_DATA_WIDTH', 'CSDATA_TYPE', + 'CSDATA_TYPE_EVENT', 'CSDATA_TYPE_PRIVATE', 'CSDATA_TYPE_STATE', + 'CSDATA_TYPE_TG', 'CSDATA_TYPE_WIDTH', 'CS_CONTEXT_DONE', + 'CS_DONE', 'CS_PARTIAL_FLUSH', 'CS_STAGE_ON', 'CmaskAddr', + 'CmaskCode', 'CmaskMode', 'ColorArray', 'ColorFormat', + 'ColorTransform', 'CombFunc', 'CompareFrag', 'CompareRef', + 'ConservativeZExport', 'CovToShaderSel', 'DACA_SOFT_RESET', + 'DACA_SOFT_RESET_0', 'DACA_SOFT_RESET_1', 'DAC_MUX_SELECT', + 'DAC_MUX_SELECT_DACA', 'DAC_MUX_SELECT_DACB', 'DB_CACHE_FLUSH', + 'DB_CACHE_FLUSH_AND_INV', 'DB_CACHE_FLUSH_AND_INV_EVENT', + 'DB_CACHE_FLUSH_AND_INV_TS_EVENT', 'DB_CACHE_FLUSH_TS', + 'DB_CLK_SOFT_RESET', 'DB_CLK_SOFT_RESET_0', 'DB_CLK_SOFT_RESET_1', + 'DB_FLUSH_AND_INV_DB_DATA_TS', 'DB_FLUSH_AND_INV_DB_META', + 'DB_PEFF_SEL_prezl_tile_mem_stall', + 'DB_PERF_SEL_CB_DB_rdreq_prt_sends', + 'DB_PERF_SEL_CB_DB_rdreq_sends', + 'DB_PERF_SEL_CB_DB_wrreq_prt_sends', + 'DB_PERF_SEL_CB_DB_wrreq_sends', 'DB_PERF_SEL_DB_CB_lquad_busy', + 'DB_PERF_SEL_DB_CB_lquad_double_format', + 'DB_PERF_SEL_DB_CB_lquad_export_quads', + 'DB_PERF_SEL_DB_CB_lquad_fast_format', + 'DB_PERF_SEL_DB_CB_lquad_quads', 'DB_PERF_SEL_DB_CB_lquad_sends', + 'DB_PERF_SEL_DB_CB_lquad_slow_format', + 'DB_PERF_SEL_DB_CB_lquad_stalls', 'DB_PERF_SEL_DB_CB_rdret_ack', + 'DB_PERF_SEL_DB_CB_rdret_nack', 'DB_PERF_SEL_DB_CB_tile_busy', + 'DB_PERF_SEL_DB_CB_tile_sends', 'DB_PERF_SEL_DB_CB_tile_stalls', + 'DB_PERF_SEL_DB_CB_wrret_ack', 'DB_PERF_SEL_DB_CB_wrret_nack', + 'DB_PERF_SEL_DB_SC_quad_busy', + 'DB_PERF_SEL_DB_SC_quad_double_quad', + 'DB_PERF_SEL_DB_SC_quad_lit_quad', 'DB_PERF_SEL_DB_SC_quad_sends', + 'DB_PERF_SEL_DB_SC_quad_stalls', 'DB_PERF_SEL_DB_SC_quad_tiles', + 'DB_PERF_SEL_DB_SC_tile_busy', 'DB_PERF_SEL_DB_SC_tile_culled', + 'DB_PERF_SEL_DB_SC_tile_df_stalls', + 'DB_PERF_SEL_DB_SC_tile_fast_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_stencil_ops', + 'DB_PERF_SEL_DB_SC_tile_fast_z_ops', + 'DB_PERF_SEL_DB_SC_tile_hier_kill', + 'DB_PERF_SEL_DB_SC_tile_no_ops', 'DB_PERF_SEL_DB_SC_tile_sends', + 'DB_PERF_SEL_DB_SC_tile_ssaa_kill', + 'DB_PERF_SEL_DB_SC_tile_stalls', + 'DB_PERF_SEL_DB_SC_tile_tile_rate', + 'DB_PERF_SEL_DB_SC_tile_tiles', + 'DB_PERF_SEL_DFSM_cant_accept_squads_but_not_stalled_by_downstream', + 'DB_PERF_SEL_DFSM_collisions_detected_within_POPS_FIFO', + 'DB_PERF_SEL_DFSM_collisions_due_to_POPS_overflow', + 'DB_PERF_SEL_DFSM_cycles_above_watermark', + 'DB_PERF_SEL_DFSM_evicted_squads_above_watermark', + 'DB_PERF_SEL_DFSM_evicted_squads_due_to_prim_watermark', + 'DB_PERF_SEL_DFSM_full_cleared_squads_out', + 'DB_PERF_SEL_DFSM_fully_cleared_pixels_out', + 'DB_PERF_SEL_DFSM_fully_cleared_quads_out', + 'DB_PERF_SEL_DFSM_lit_pixels_in', + 'DB_PERF_SEL_DFSM_lit_samples_in', + 'DB_PERF_SEL_DFSM_lit_samples_out', 'DB_PERF_SEL_DFSM_quads_in', + 'DB_PERF_SEL_DFSM_squads_in', + 'DB_PERF_SEL_DFSM_stalled_by_downstream', + 'DB_PERF_SEL_Depth_Tile_Cache_alloc_stall', + 'DB_PERF_SEL_Depth_Tile_Cache_busy', + 'DB_PERF_SEL_Depth_Tile_Cache_data_frees', + 'DB_PERF_SEL_Depth_Tile_Cache_detailed_noop', + 'DB_PERF_SEL_Depth_Tile_Cache_dtile_locked', + 'DB_PERF_SEL_Depth_Tile_Cache_event', + 'DB_PERF_SEL_Depth_Tile_Cache_flushes', + 'DB_PERF_SEL_Depth_Tile_Cache_hits', + 'DB_PERF_SEL_Depth_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Depth_Tile_Cache_misses', + 'DB_PERF_SEL_Depth_Tile_Cache_noop_tile', + 'DB_PERF_SEL_Depth_Tile_Cache_sends', + 'DB_PERF_SEL_Depth_Tile_Cache_starves', + 'DB_PERF_SEL_Depth_Tile_Cache_tile_frees', + 'DB_PERF_SEL_Op_Pipe_Busy', 'DB_PERF_SEL_Op_Pipe_MC_Read_stall', + 'DB_PERF_SEL_Op_Pipe_Postz_Busy', 'DB_PERF_SEL_Op_Pipe_Prez_Busy', + 'DB_PERF_SEL_Plane_Cache_flushes', + 'DB_PERF_SEL_Plane_Cache_frees', 'DB_PERF_SEL_Plane_Cache_hits', + 'DB_PERF_SEL_Plane_Cache_misses', + 'DB_PERF_SEL_Plane_Cache_starves', + 'DB_PERF_SEL_PostZ_Samples_failing_DB', + 'DB_PERF_SEL_PostZ_Samples_failing_S', + 'DB_PERF_SEL_PostZ_Samples_failing_Z', + 'DB_PERF_SEL_PostZ_Samples_passing_Z', + 'DB_PERF_SEL_PreZ_Samples_failing_DB', + 'DB_PERF_SEL_PreZ_Samples_failing_S', + 'DB_PERF_SEL_PreZ_Samples_failing_Z', + 'DB_PERF_SEL_PreZ_Samples_passing_Z', + 'DB_PERF_SEL_SC_DB_quad_busy', + 'DB_PERF_SEL_SC_DB_quad_killed_tiles', + 'DB_PERF_SEL_SC_DB_quad_pixels', 'DB_PERF_SEL_SC_DB_quad_sends', + 'DB_PERF_SEL_SC_DB_quad_squads', 'DB_PERF_SEL_SC_DB_quad_tiles', + 'DB_PERF_SEL_SC_DB_tile_busy', 'DB_PERF_SEL_SC_DB_tile_covered', + 'DB_PERF_SEL_SC_DB_tile_events', 'DB_PERF_SEL_SC_DB_tile_sends', + 'DB_PERF_SEL_SC_DB_tile_stalls', 'DB_PERF_SEL_SC_DB_tile_tiles', + 'DB_PERF_SEL_SH_quads_outstanding_sum', + 'DB_PERF_SEL_SX_DB_quad_busy', + 'DB_PERF_SEL_SX_DB_quad_double_format', + 'DB_PERF_SEL_SX_DB_quad_export_quads', + 'DB_PERF_SEL_SX_DB_quad_exports', + 'DB_PERF_SEL_SX_DB_quad_fast_format', + 'DB_PERF_SEL_SX_DB_quad_pixels', 'DB_PERF_SEL_SX_DB_quad_quads', + 'DB_PERF_SEL_SX_DB_quad_sends', + 'DB_PERF_SEL_SX_DB_quad_slow_format', + 'DB_PERF_SEL_SX_DB_quad_stalls', + 'DB_PERF_SEL_Stencil_Cache_flushes', + 'DB_PERF_SEL_Stencil_Cache_frees', + 'DB_PERF_SEL_Stencil_Cache_hits', + 'DB_PERF_SEL_Stencil_Cache_misses', + 'DB_PERF_SEL_Stencil_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_flushes', 'DB_PERF_SEL_Tile_Cache_hits', + 'DB_PERF_SEL_Tile_Cache_mem_return_starve', + 'DB_PERF_SEL_Tile_Cache_misses', 'DB_PERF_SEL_Tile_Cache_starves', + 'DB_PERF_SEL_Tile_Cache_surface_stall', + 'DB_PERF_SEL_Z_Cache_frees', 'DB_PERF_SEL_Z_Cache_pmask_flushes', + 'DB_PERF_SEL_Z_Cache_pmask_hits', + 'DB_PERF_SEL_Z_Cache_pmask_misses', + 'DB_PERF_SEL_Z_Cache_pmask_starves', + 'DB_PERF_SEL_Z_Cache_separate_Z_flushes', + 'DB_PERF_SEL_Z_Cache_separate_Z_hits', + 'DB_PERF_SEL_Z_Cache_separate_Z_misses', + 'DB_PERF_SEL_Z_Cache_separate_Z_starves', + 'DB_PERF_SEL_clock_main_active', + 'DB_PERF_SEL_clock_mem_export_active', + 'DB_PERF_SEL_clock_reg_active', + 'DB_PERF_SEL_depth_bounds_qtiles_culled', + 'DB_PERF_SEL_di_dt_stall', 'DB_PERF_SEL_dk_squad_busy', + 'DB_PERF_SEL_dk_squad_sends', 'DB_PERF_SEL_dk_squad_stalls', + 'DB_PERF_SEL_dk_tile_busy', 'DB_PERF_SEL_dk_tile_quad_starves', + 'DB_PERF_SEL_dk_tile_sends', 'DB_PERF_SEL_dk_tile_stalls', + 'DB_PERF_SEL_dkg_tile_rate_tile', + 'DB_PERF_SEL_dtt_sm_clash_stall', 'DB_PERF_SEL_dtt_sm_miss_stall', + 'DB_PERF_SEL_dtt_sm_slot_stall', + 'DB_PERF_SEL_earlyZ_waiting_for_postZ_done', + 'DB_PERF_SEL_esr_eot_fwd_busy', 'DB_PERF_SEL_esr_eot_fwd_forward', + 'DB_PERF_SEL_esr_eot_fwd_holding_squad', + 'DB_PERF_SEL_esr_ps_lqf_busy', 'DB_PERF_SEL_esr_ps_lqf_stall', + 'DB_PERF_SEL_esr_ps_out_busy', 'DB_PERF_SEL_esr_ps_sqq_busy', + 'DB_PERF_SEL_esr_ps_sqq_stall', 'DB_PERF_SEL_esr_ps_src_in_sends', + 'DB_PERF_SEL_esr_ps_src_in_squads', + 'DB_PERF_SEL_esr_ps_src_in_squads_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_stall', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_esr_ps_src_in_tile_rate_unrolled_to_pixel_rate', + 'DB_PERF_SEL_esr_ps_src_out_stall', 'DB_PERF_SEL_esr_sqq_zi_busy', + 'DB_PERF_SEL_esr_sqq_zi_stall', 'DB_PERF_SEL_etr_out_busy', + 'DB_PERF_SEL_etr_out_cb_tile_stall', + 'DB_PERF_SEL_etr_out_esr_stall', + 'DB_PERF_SEL_etr_out_ltile_probe_fifo_full_stall', + 'DB_PERF_SEL_etr_out_send', 'DB_PERF_SEL_flush_10plane', + 'DB_PERF_SEL_flush_11plane', 'DB_PERF_SEL_flush_12plane', + 'DB_PERF_SEL_flush_13plane', 'DB_PERF_SEL_flush_14plane', + 'DB_PERF_SEL_flush_15plane', 'DB_PERF_SEL_flush_16plane', + 'DB_PERF_SEL_flush_1plane', 'DB_PERF_SEL_flush_2plane', + 'DB_PERF_SEL_flush_3plane', 'DB_PERF_SEL_flush_4plane', + 'DB_PERF_SEL_flush_5plane', 'DB_PERF_SEL_flush_6plane', + 'DB_PERF_SEL_flush_7plane', 'DB_PERF_SEL_flush_8plane', + 'DB_PERF_SEL_flush_9plane', 'DB_PERF_SEL_flush_compressed', + 'DB_PERF_SEL_flush_compressed_stencil', + 'DB_PERF_SEL_flush_expanded_stencil', + 'DB_PERF_SEL_flush_expanded_z', 'DB_PERF_SEL_flush_plane_le4', + 'DB_PERF_SEL_flush_single_stencil', + 'DB_PERF_SEL_his_qtiles_culled', 'DB_PERF_SEL_hiz_qtiles_culled', + 'DB_PERF_SEL_hiz_tc_read_starved', + 'DB_PERF_SEL_hiz_tc_write_stall', + 'DB_PERF_SEL_mi_quad_rd_outstanding_sum', + 'DB_PERF_SEL_mi_quad_wr_outstanding_sum', + 'DB_PERF_SEL_mi_rdreq_busy', 'DB_PERF_SEL_mi_rdreq_stall', + 'DB_PERF_SEL_mi_tile_rd_outstanding_sum', + 'DB_PERF_SEL_mi_tile_wr_outstanding_sum', + 'DB_PERF_SEL_mi_wrreq_busy', 'DB_PERF_SEL_mi_wrreq_stall', + 'DB_PERF_SEL_planes_flushed', 'DB_PERF_SEL_postzl_full_launch', + 'DB_PERF_SEL_postzl_partial_launch', + 'DB_PERF_SEL_postzl_partial_waiting', + 'DB_PERF_SEL_postzl_se_busy', 'DB_PERF_SEL_postzl_se_stall', + 'DB_PERF_SEL_postzl_sq_pt_busy', 'DB_PERF_SEL_postzl_sq_pt_stall', + 'DB_PERF_SEL_postzl_src_in_sends', + 'DB_PERF_SEL_postzl_src_in_squads', + 'DB_PERF_SEL_postzl_src_in_squads_unrolled', + 'DB_PERF_SEL_postzl_src_in_stall', + 'DB_PERF_SEL_postzl_src_in_tile_rate', + 'DB_PERF_SEL_postzl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_postzl_src_out_stall', + 'DB_PERF_SEL_postzl_tile_init_stall', + 'DB_PERF_SEL_postzl_tile_mem_stall', + 'DB_PERF_SEL_prezl_src_in_sends', + 'DB_PERF_SEL_prezl_src_in_squads', + 'DB_PERF_SEL_prezl_src_in_squads_unrolled', + 'DB_PERF_SEL_prezl_src_in_stall', + 'DB_PERF_SEL_prezl_src_in_tile_rate', + 'DB_PERF_SEL_prezl_src_in_tile_rate_unrolled', + 'DB_PERF_SEL_prezl_src_out_stall', + 'DB_PERF_SEL_prezl_tile_init_stall', 'DB_PERF_SEL_qc_busy', + 'DB_PERF_SEL_qc_conflicts', 'DB_PERF_SEL_qc_full_stall', + 'DB_PERF_SEL_qc_in_postZ_tile_stalls_preZ', + 'DB_PERF_SEL_qc_in_preZ_tile_stalls_postZ', 'DB_PERF_SEL_qc_xfc', + 'DB_PERF_SEL_quad_rd_32byte_reqs', 'DB_PERF_SEL_quad_rd_busy', + 'DB_PERF_SEL_quad_rd_mi_stall', 'DB_PERF_SEL_quad_rd_panic', + 'DB_PERF_SEL_quad_rd_rw_collision', 'DB_PERF_SEL_quad_rd_sends', + 'DB_PERF_SEL_quad_rd_tag_stall', 'DB_PERF_SEL_quad_rdret_busy', + 'DB_PERF_SEL_quad_rdret_sends', 'DB_PERF_SEL_quad_wr_acks', + 'DB_PERF_SEL_quad_wr_busy', 'DB_PERF_SEL_quad_wr_coherency_stall', + 'DB_PERF_SEL_quad_wr_mi_stall', 'DB_PERF_SEL_quad_wr_sends', + 'DB_PERF_SEL_reZ_waiting_for_postZ_done', + 'DB_PERF_SEL_recomp_tile_to_1zplane_no_fastop', + 'DB_PERF_SEL_sc_kick_end', 'DB_PERF_SEL_sc_kick_start', + 'DB_PERF_SEL_tcp_dispatcher_flushes', + 'DB_PERF_SEL_tcp_dispatcher_reads', + 'DB_PERF_SEL_tcp_prefetcher_flushes', + 'DB_PERF_SEL_tcp_prefetcher_reads', + 'DB_PERF_SEL_tcp_preloader_flushes', + 'DB_PERF_SEL_tcp_preloader_reads', 'DB_PERF_SEL_tile_rd_sends', + 'DB_PERF_SEL_tile_wr_acks', 'DB_PERF_SEL_tile_wr_sends', + 'DB_PERF_SEL_tiles_compressed_to_decompressed', + 'DB_PERF_SEL_tiles_decomp_on_expclear', + 'DB_PERF_SEL_tiles_s_clear_on_expclear', + 'DB_PERF_SEL_tiles_stencil_fully_summarized', + 'DB_PERF_SEL_tiles_z_clear_on_expclear', + 'DB_PERF_SEL_tiles_z_fully_summarized', 'DB_PERF_SEL_tl_busy', + 'DB_PERF_SEL_tl_dtc_read_starved', 'DB_PERF_SEL_tl_events', + 'DB_PERF_SEL_tl_expand_squads', + 'DB_PERF_SEL_tl_flush_expand_squads', + 'DB_PERF_SEL_tl_in_fast_z_stall', + 'DB_PERF_SEL_tl_in_single_stencil_expand_stall', + 'DB_PERF_SEL_tl_in_xfc', 'DB_PERF_SEL_tl_out_squads', + 'DB_PERF_SEL_tl_out_xfc', 'DB_PERF_SEL_tl_postZ_noop_squads', + 'DB_PERF_SEL_tl_postZ_squads', 'DB_PERF_SEL_tl_preZ_noop_squads', + 'DB_PERF_SEL_tl_preZ_squads', + 'DB_PERF_SEL_tl_stencil_locked_stall', + 'DB_PERF_SEL_tl_stencil_stall', 'DB_PERF_SEL_tl_summarize_squads', + 'DB_PERF_SEL_tl_tile_ops', 'DB_PERF_SEL_tl_z_decompress_stall', + 'DB_PERF_SEL_tl_z_fetch_stall', 'DB_PERF_SEL_ts_tc_update_stall', + 'DB_PERF_SEL_tsc_insert_summarize_stall', + 'DB_PERF_SEL_zf_plane_multicycle', 'DCCG_AUDIO_DTO0_SOURCE_SEL', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC0', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC1', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC2', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC3', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC4', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_CRTC5', + 'DCCG_AUDIO_DTO0_SOURCE_SEL_RESERVED', + 'DCCG_AUDIO_DTO2_SOURCE_SEL', 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK0', + 'DCCG_AUDIO_DTO2_SOURCE_SEL_AMCLK1', 'DCCG_AUDIO_DTO_SEL', + 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO0', 'DCCG_AUDIO_DTO_SEL_AUDIO_DTO1', + 'DCCG_AUDIO_DTO_SEL_NO_AUDIO_DTO', + 'DCCG_AUDIO_DTO_USE_128FBR_FOR_DP', + 'DCCG_AUDIO_DTO_USE_512FBR_DTO', + 'DCCG_AUDIO_DTO_USE_512FBR_FOR_DP', 'DCCG_DBG_BLOCK_SEL', + 'DCCG_DBG_BLOCK_SEL_DCCG', 'DCCG_DBG_BLOCK_SEL_PMON', + 'DCCG_DBG_BLOCK_SEL_PMON2', 'DCCG_DBG_EN', 'DCCG_DBG_EN_DISABLE', + 'DCCG_DBG_EN_ENABLE', 'DCCG_DEEP_COLOR_CNTL', + 'DCCG_DEEP_COLOR_DTO_2_1_RATIO', 'DCCG_DEEP_COLOR_DTO_3_2_RATIO', + 'DCCG_DEEP_COLOR_DTO_5_4_RATIO', 'DCCG_DEEP_COLOR_DTO_DISABLE', + 'DCCG_FIFO_ERRDET_OVR_DISABLE', 'DCCG_FIFO_ERRDET_OVR_EN', + 'DCCG_FIFO_ERRDET_OVR_ENABLE', 'DCCG_FIFO_ERRDET_RESET', + 'DCCG_FIFO_ERRDET_RESET_FORCE', 'DCCG_FIFO_ERRDET_RESET_NOOP', + 'DCCG_FIFO_ERRDET_STATE', 'DCCG_FIFO_ERRDET_STATE_CALIBRATION', + 'DCCG_FIFO_ERRDET_STATE_DETECTION', 'DCCG_PERF_CRTC_SELECT', + 'DCCG_PERF_MODE_HSYNC', 'DCCG_PERF_MODE_HSYNC_NOOP', + 'DCCG_PERF_MODE_HSYNC_START', 'DCCG_PERF_MODE_VSYNC', + 'DCCG_PERF_MODE_VSYNC_NOOP', 'DCCG_PERF_MODE_VSYNC_START', + 'DCCG_PERF_RUN', 'DCCG_PERF_RUN_NOOP', 'DCCG_PERF_RUN_START', + 'DCCG_PERF_SEL_CRTC0', 'DCCG_PERF_SEL_CRTC1', + 'DCCG_PERF_SEL_CRTC2', 'DCCG_PERF_SEL_CRTC3', + 'DCCG_PERF_SEL_CRTC4', 'DCCG_PERF_SEL_CRTC5', 'DCC_CT_AUTO', + 'DCC_CT_NONE', 'DCIOCHIP_2BIT_DISABLE', 'DCIOCHIP_2BIT_ENABLE', + 'DCIOCHIP_4BIT_DISABLE', 'DCIOCHIP_4BIT_ENABLE', + 'DCIOCHIP_5BIT_DISABLE', 'DCIOCHIP_5BIT_ENABLE', + 'DCIOCHIP_AUXSLAVE_PAD_MODE', 'DCIOCHIP_AUXSLAVE_PAD_MODE_AUX', + 'DCIOCHIP_AUXSLAVE_PAD_MODE_I2C', 'DCIOCHIP_AUX_CSEL0P9', + 'DCIOCHIP_AUX_CSEL1P1', 'DCIOCHIP_AUX_CSEL_DEC0P9', + 'DCIOCHIP_AUX_CSEL_DEC1P0', 'DCIOCHIP_AUX_CSEL_INC1P0', + 'DCIOCHIP_AUX_CSEL_INC1P1', 'DCIOCHIP_AUX_FALLSLEWSEL', + 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH0', + 'DCIOCHIP_AUX_FALLSLEWSEL_HIGH1', 'DCIOCHIP_AUX_FALLSLEWSEL_LOW', + 'DCIOCHIP_AUX_FALLSLEWSEL_ULTRAHIGH', 'DCIOCHIP_AUX_RSEL0P9', + 'DCIOCHIP_AUX_RSEL1P1', 'DCIOCHIP_AUX_RSEL_DEC0P9', + 'DCIOCHIP_AUX_RSEL_DEC1P0', 'DCIOCHIP_AUX_RSEL_INC1P0', + 'DCIOCHIP_AUX_RSEL_INC1P1', 'DCIOCHIP_AUX_SPIKESEL', + 'DCIOCHIP_AUX_SPIKESEL_10NS', 'DCIOCHIP_AUX_SPIKESEL_50NS', + 'DCIOCHIP_DVO_VREFPON', 'DCIOCHIP_DVO_VREFPON_DISABLE', + 'DCIOCHIP_DVO_VREFPON_ENABLE', 'DCIOCHIP_DVO_VREFSEL', + 'DCIOCHIP_DVO_VREFSEL_EXTERNAL', 'DCIOCHIP_DVO_VREFSEL_ONCHIP', + 'DCIOCHIP_ENABLE_2BIT', 'DCIOCHIP_ENABLE_4BIT', + 'DCIOCHIP_ENABLE_5BIT', 'DCIOCHIP_GPIO_I2C_DISABLE', + 'DCIOCHIP_GPIO_I2C_DRIVE', 'DCIOCHIP_GPIO_I2C_DRIVE_HIGH', + 'DCIOCHIP_GPIO_I2C_DRIVE_LOW', 'DCIOCHIP_GPIO_I2C_EN', + 'DCIOCHIP_GPIO_I2C_ENABLE', 'DCIOCHIP_GPIO_I2C_MASK', + 'DCIOCHIP_GPIO_I2C_MASK_DISABLE', 'DCIOCHIP_GPIO_I2C_MASK_ENABLE', + 'DCIOCHIP_GPIO_MASK_EN', 'DCIOCHIP_GPIO_MASK_EN_HARDWARE', + 'DCIOCHIP_GPIO_MASK_EN_SOFTWARE', 'DCIOCHIP_HPD_SEL', + 'DCIOCHIP_HPD_SEL_ASYNC', 'DCIOCHIP_HPD_SEL_CLOCKED', + 'DCIOCHIP_INVERT', 'DCIOCHIP_MASIK_5BIT_DISABLE', + 'DCIOCHIP_MASIK_5BIT_ENABLE', 'DCIOCHIP_MASK', + 'DCIOCHIP_MASK_2BIT', 'DCIOCHIP_MASK_2BIT_DISABLE', + 'DCIOCHIP_MASK_2BIT_ENABLE', 'DCIOCHIP_MASK_4BIT', + 'DCIOCHIP_MASK_4BIT_DISABLE', 'DCIOCHIP_MASK_4BIT_ENABLE', + 'DCIOCHIP_MASK_5BIT', 'DCIOCHIP_MASK_DISABLE', + 'DCIOCHIP_MASK_ENABLE', 'DCIOCHIP_PAD_MODE', + 'DCIOCHIP_PAD_MODE_DDC', 'DCIOCHIP_PAD_MODE_DP', 'DCIOCHIP_PD_EN', + 'DCIOCHIP_PD_EN_ALLOW', 'DCIOCHIP_PD_EN_NOTALLOW', + 'DCIOCHIP_POL_INVERT', 'DCIOCHIP_POL_NON_INVERT', + 'DCIOCHIP_REF_27_SRC_SEL', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_DISP_CLKIN2_DIVIDER', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_BYPASS', + 'DCIOCHIP_REF_27_SRC_SEL_XTAL_DIVIDER', 'DCIOCHIP_SPDIF1_IMODE', + 'DCIOCHIP_SPDIF1_IMODE_OE_A', 'DCIOCHIP_SPDIF1_IMODE_TSTE_TSTO', + 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'DCIO_BL_PWM_CNTL2_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN', + 'DCIO_BL_PWM_CNTL2_DBG_BL_PWM_INPUT_REFCLK_SELECT', + 'DCIO_BL_PWM_CNTL_BL_PWM_EN', + 'DCIO_BL_PWM_CNTL_BL_PWM_FRACTIONAL_EN', 'DCIO_BL_PWM_DISABLE', + 'DCIO_BL_PWM_ENABLE', 'DCIO_BL_PWM_FRACTIONAL_DISABLE', + 'DCIO_BL_PWM_FRACTIONAL_ENABLE', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER1', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER2', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER3', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER4', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER5', + 'DCIO_BL_PWM_GRP1_FRAME_START_DISP_SEL_CONTROLLER6', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_DISABLE', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_EN', + 'DCIO_BL_PWM_GRP1_IGNORE_MASTER_LOCK_ENABLE', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL1_PWM', + 'DCIO_BL_PWM_GRP1_READBACK_DB_REG_VALUE_EN_BL_PWM', + 'DCIO_BL_PWM_GRP1_REG_LOCK', 'DCIO_BL_PWM_GRP1_REG_LOCK_DISABLE', + 'DCIO_BL_PWM_GRP1_REG_LOCK_ENABLE', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_DISABLE', + 'DCIO_BL_PWM_GRP1_UPDATE_AT_FRAME_START_ENABLE', + 'DCIO_BL_PWM_OVERRIDE_BL_OUT_DISABLE', + 'DCIO_BL_PWM_OVERRIDE_BL_OUT_ENABLE', + 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_NORMAL', + 'DCIO_BL_PWM_OVERRIDE_LVTMA_PWRSEQ_EN_PWM', + 'DCIO_CLOCK_CNTL_DCIO_TEST_CLK_SEL', + 'DCIO_CLOCK_CNTL_DISPCLK_R_DCIO_GATE_DIS', 'DCIO_DACA_SOFT_RESET', + 'DCIO_DACA_SOFT_RESET_ASSERT', 'DCIO_DACA_SOFT_RESET_DEASSERT', + 'DCIO_DBG_ASYNC_4BIT_SEL', 'DCIO_DBG_ASYNC_4BIT_SEL_11TO8', + 'DCIO_DBG_ASYNC_4BIT_SEL_15TO12', + 'DCIO_DBG_ASYNC_4BIT_SEL_19TO16', + 'DCIO_DBG_ASYNC_4BIT_SEL_23TO20', + 'DCIO_DBG_ASYNC_4BIT_SEL_27TO24', + 'DCIO_DBG_ASYNC_4BIT_SEL_31TO28', 'DCIO_DBG_ASYNC_4BIT_SEL_3TO0', + 'DCIO_DBG_ASYNC_4BIT_SEL_7TO4', 'DCIO_DBG_ASYNC_BLOCK_SEL', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DCCG', 'DCIO_DBG_ASYNC_BLOCK_SEL_DCIO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_DCO', + 'DCIO_DBG_ASYNC_BLOCK_SEL_OVERRIDE', + 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG1', + 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG2', + 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_DEBUG3', + 'DCIO_DBG_BL_PWM_INPUT_REFCLK_SELECT_NORMAL', + 'DCIO_DCO_DCFE_EXT_VSYNC_MUX', 'DCIO_DCO_EXT_VSYNC_MASK', + 'DCIO_DCRXPHY_SOFT_RESET', 'DCIO_DCRXPHY_SOFT_RESET_ASSERT', + 'DCIO_DCRXPHY_SOFT_RESET_DEASSERT', + 'DCIO_DC_DVODATA_CONFIG_DVO_ALTER_MAPPING_EN', + 'DCIO_DC_DVODATA_CONFIG_VIP_ALTER_MAPPING_EN', + 'DCIO_DC_DVODATA_CONFIG_VIP_MUX_EN', 'DCIO_DC_GENERICA_SEL', + 'DCIO_DC_GENERICB_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_DIV2_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_FBDIV_SSC_CLK_SEL', + 'DCIO_DC_GENERIC_UNIPHY_REFDIV_CLK_SEL', + 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL', + 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_NORMAL', + 'DCIO_DC_GPIO_CHIP_DEBUG_OUT_PIN_SEL_SWAP', + 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN', + 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_BYPASS', + 'DCIO_DC_GPIO_DEBUG_BUS_FLOP_EN_ENABLE', + 'DCIO_DC_GPIO_DEBUG_DPRX_LOOPBACK_ENABLE', + 'DCIO_DC_GPIO_MACRO_DEBUG', 'DCIO_DC_GPIO_MACRO_DEBUG_CHIP_BIF', + 'DCIO_DC_GPIO_MACRO_DEBUG_NORMAL', + 'DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE2', + 'DCIO_DC_GPIO_MACRO_DEBUG_RESERVED_VALUE3', + 'DCIO_DC_GPIO_VIP_DEBUG', 'DCIO_DC_GPIO_VIP_DEBUG_CG_BIG', + 'DCIO_DC_GPIO_VIP_DEBUG_NORMAL', 'DCIO_DC_GPU_TIMER_READ_SELECT', + 'DCIO_DC_GPU_TIMER_START_POSITION', + 'DCIO_DC_PAD_EXTERN_SIG_MVP_PIXEL_SRC_STATUS', + 'DCIO_DC_PAD_EXTERN_SIG_SEL', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1CLK', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC1DATA', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2CLK', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_DDC2DATA', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICA', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICB', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENERICC', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_CLK', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_GENLK_VSYNC', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_HPD1', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_HPD2', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_MVP', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD0', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_VHAD1', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_VPHCTL', + 'DCIO_DC_PAD_EXTERN_SIG_SEL_VSYNCA', + 'DCIO_DC_REF_CLK_CNTL_GENLK_CLK_OUTPUT_SEL', + 'DCIO_DC_REF_CLK_CNTL_HSYNCA_OUTPUT_SEL', + 'DCIO_DISPCLK_R_DCIO_GATE_DISABLE', + 'DCIO_DISPCLK_R_DCIO_GATE_ENABLE', 'DCIO_DPCS_INTERRUPT_DISABLE', + 'DCIO_DPCS_INTERRUPT_ENABLE', 'DCIO_DPCS_INTERRUPT_MASK', + 'DCIO_DPCS_INTERRUPT_TYPE', + 'DCIO_DPCS_INTERRUPT_TYPE_LEVEL_BASED', + 'DCIO_DPCS_INTERRUPT_TYPE_PULSE_BASED', 'DCIO_DPHY_LANE_SEL', + 'DCIO_DPHY_LANE_SEL_LANE0', 'DCIO_DPHY_LANE_SEL_LANE1', + 'DCIO_DPHY_LANE_SEL_LANE2', 'DCIO_DPHY_LANE_SEL_LANE3', + 'DCIO_DPRX_LOOPBACK_ENABLE_LOOP', + 'DCIO_DPRX_LOOPBACK_ENABLE_NORMAL', 'DCIO_DSYNC_SOFT_RESET', + 'DCIO_DSYNC_SOFT_RESET_ASSERT', 'DCIO_DSYNC_SOFT_RESET_DEASSERT', + 'DCIO_DVO_ALTER_MAPPING_EN_ALTERNATIVE', + 'DCIO_DVO_ALTER_MAPPING_EN_DEFAULT', 'DCIO_EXT_VSYNC_MASK_NONE', + 'DCIO_EXT_VSYNC_MASK_NONE_DUPLICATE', 'DCIO_EXT_VSYNC_MASK_PIPE0', + 'DCIO_EXT_VSYNC_MASK_PIPE1', 'DCIO_EXT_VSYNC_MASK_PIPE2', + 'DCIO_EXT_VSYNC_MASK_PIPE3', 'DCIO_EXT_VSYNC_MASK_PIPE4', + 'DCIO_EXT_VSYNC_MASK_PIPE5', 'DCIO_EXT_VSYNC_MUX_CRTC0', + 'DCIO_EXT_VSYNC_MUX_CRTC1', 'DCIO_EXT_VSYNC_MUX_CRTC2', + 'DCIO_EXT_VSYNC_MUX_CRTC3', 'DCIO_EXT_VSYNC_MUX_CRTC4', + 'DCIO_EXT_VSYNC_MUX_CRTC5', 'DCIO_EXT_VSYNC_MUX_GENERICB', + 'DCIO_EXT_VSYNC_MUX_SWAPLOCKB', + 'DCIO_GENERICA_SEL_DACA_FIELD_NUMBER', + 'DCIO_GENERICA_SEL_DACA_PIXCLK', + 'DCIO_GENERICA_SEL_DACA_STEREOSYNC', + 'DCIO_GENERICA_SEL_DACB_FIELD_NUMBER', + 'DCIO_GENERICA_SEL_DACB_PIXCLK', 'DCIO_GENERICA_SEL_DVOA_CTL3', + 'DCIO_GENERICA_SEL_DVOA_STEREOSYNC', + 'DCIO_GENERICA_SEL_GENERICA_DCCG', + 'DCIO_GENERICA_SEL_GENERICA_DPRX', + 'DCIO_GENERICA_SEL_GENERICB_DPRX', 'DCIO_GENERICA_SEL_P1_PLLCLK', + 'DCIO_GENERICA_SEL_P2_PLLCLK', 'DCIO_GENERICA_SEL_STEREOSYNC', + 'DCIO_GENERICA_SEL_SYNCEN', 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK', + 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_CLK_DIV2', + 'DCIO_GENERICA_SEL_UNIPHY_FBDIV_SSC_CLK', + 'DCIO_GENERICA_SEL_UNIPHY_REFDIV_CLK', + 'DCIO_GENERICB_SEL_DACA_FIELD_NUMBER', + 'DCIO_GENERICB_SEL_DACA_PIXCLK', + 'DCIO_GENERICB_SEL_DACA_STEREOSYNC', + 'DCIO_GENERICB_SEL_DACB_FIELD_NUMBER', + 'DCIO_GENERICB_SEL_DACB_PIXCLK', 'DCIO_GENERICB_SEL_DVOA_CTL3', + 'DCIO_GENERICB_SEL_DVOA_STEREOSYNC', + 'DCIO_GENERICB_SEL_GENERICB_DCCG', 'DCIO_GENERICB_SEL_P1_PLLCLK', + 'DCIO_GENERICB_SEL_P2_PLLCLK', 'DCIO_GENERICB_SEL_STEREOSYNC', + 'DCIO_GENERICB_SEL_SYNCEN', 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK', + 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_CLK_DIV2', + 'DCIO_GENERICB_SEL_UNIPHY_FBDIV_SSC_CLK', + 'DCIO_GENERICB_SEL_UNIPHY_REFDIV_CLK', 'DCIO_GENLK_CLK_GSL_MASK', + 'DCIO_GENLK_CLK_GSL_MASK_NO', 'DCIO_GENLK_CLK_GSL_MASK_STEREO', + 'DCIO_GENLK_CLK_GSL_MASK_TIMING', + 'DCIO_GENLK_CLK_OUTPUT_SEL_DISABLE', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL1', + 'DCIO_GENLK_CLK_OUTPUT_SEL_PPLL2', + 'DCIO_GENLK_CLK_OUTPUT_SEL_RESERVED_VALUE3', + 'DCIO_GENLK_VSYNC_GSL_MASK', 'DCIO_GENLK_VSYNC_GSL_MASK_NO', + 'DCIO_GENLK_VSYNC_GSL_MASK_STEREO', + 'DCIO_GENLK_VSYNC_GSL_MASK_TIMING', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D2_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D3_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D4_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D5_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_LOWER_D6_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D1_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D2_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D3_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D4_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D5_V_UPDATE', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_P_FLIP', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_VSYNC_NOM', + 'DCIO_GPU_TIMER_READ_SELECT_UPPER_D6_V_UPDATE', + 'DCIO_GPU_TIMER_START_0_END_27', 'DCIO_GPU_TIMER_START_10_END_37', + 'DCIO_GPU_TIMER_START_1_END_28', 'DCIO_GPU_TIMER_START_2_END_29', + 'DCIO_GPU_TIMER_START_3_END_30', 'DCIO_GPU_TIMER_START_4_END_31', + 'DCIO_GPU_TIMER_START_6_END_33', 'DCIO_GPU_TIMER_START_8_END_35', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_INVERSION', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 'DCIO_GSL0_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', + 'DCIO_GSL0_TIMING_SYNC_SEL', + 'DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_CLK', + 'DCIO_GSL0_TIMING_SYNC_SEL_GENCLK_VSYNC', + 'DCIO_GSL0_TIMING_SYNC_SEL_PIPE', + 'DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_A', + 'DCIO_GSL0_TIMING_SYNC_SEL_SWAPLOCK_B', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_INVERSION', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 'DCIO_GSL1_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', + 'DCIO_GSL1_TIMING_SYNC_SEL', + 'DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_CLK', + 'DCIO_GSL1_TIMING_SYNC_SEL_GENCLK_VSYNC', + 'DCIO_GSL1_TIMING_SYNC_SEL_PIPE', + 'DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_A', + 'DCIO_GSL1_TIMING_SYNC_SEL_SWAPLOCK_B', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENCLK_VSYNC', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_GENLK_CLK', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_INVERSION', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_A', + 'DCIO_GSL2_GLOBAL_UNLOCK_SEL_SWAPLOCK_B', + 'DCIO_GSL2_TIMING_SYNC_SEL', + 'DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_CLK', + 'DCIO_GSL2_TIMING_SYNC_SEL_GENCLK_VSYNC', + 'DCIO_GSL2_TIMING_SYNC_SEL_PIPE', + 'DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_A', + 'DCIO_GSL2_TIMING_SYNC_SEL_SWAPLOCK_B', 'DCIO_GSL_SEL', + 'DCIO_GSL_SEL_GROUP_0', 'DCIO_GSL_SEL_GROUP_1', + 'DCIO_GSL_SEL_GROUP_2', 'DCIO_GSL_VSYNC_SEL', + 'DCIO_GSL_VSYNC_SEL_PIPE0', 'DCIO_GSL_VSYNC_SEL_PIPE1', + 'DCIO_GSL_VSYNC_SEL_PIPE2', 'DCIO_GSL_VSYNC_SEL_PIPE3', + 'DCIO_GSL_VSYNC_SEL_PIPE4', 'DCIO_GSL_VSYNC_SEL_PIPE5', + 'DCIO_HSYNCA_OUTPUT_SEL_DISABLE', 'DCIO_HSYNCA_OUTPUT_SEL_PPLL1', + 'DCIO_HSYNCA_OUTPUT_SEL_PPLL2', 'DCIO_HSYNCA_OUTPUT_SEL_RESERVED', + 'DCIO_IMPCAL_STEP_DELAY', 'DCIO_IMPCAL_STEP_DELAY_10us', + 'DCIO_IMPCAL_STEP_DELAY_11us', 'DCIO_IMPCAL_STEP_DELAY_12us', + 'DCIO_IMPCAL_STEP_DELAY_13us', 'DCIO_IMPCAL_STEP_DELAY_14us', + 'DCIO_IMPCAL_STEP_DELAY_15us', 'DCIO_IMPCAL_STEP_DELAY_16us', + 'DCIO_IMPCAL_STEP_DELAY_1us', 'DCIO_IMPCAL_STEP_DELAY_2us', + 'DCIO_IMPCAL_STEP_DELAY_3us', 'DCIO_IMPCAL_STEP_DELAY_4us', + 'DCIO_IMPCAL_STEP_DELAY_5us', 'DCIO_IMPCAL_STEP_DELAY_6us', + 'DCIO_IMPCAL_STEP_DELAY_7us', 'DCIO_IMPCAL_STEP_DELAY_8us', + 'DCIO_IMPCAL_STEP_DELAY_9us', 'DCIO_LVTMA_BLON_OFF', + 'DCIO_LVTMA_BLON_ON', 'DCIO_LVTMA_BLON_POL_INVERT', + 'DCIO_LVTMA_BLON_POL_NON_INVERT', 'DCIO_LVTMA_DIGON_OFF', + 'DCIO_LVTMA_DIGON_ON', 'DCIO_LVTMA_DIGON_POL_INVERT', + 'DCIO_LVTMA_DIGON_POL_NON_INVERT', + 'DCIO_LVTMA_PWRSEQ_CNTL_DISABLE_SYNCEN_CONTROL_OF_TX_EN', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_BLON_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_DIGON_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_LVTMA_SYNCEN_POL', + 'DCIO_LVTMA_PWRSEQ_CNTL_TARGET_STATE', + 'DCIO_LVTMA_PWRSEQ_DELAY2_LVTMA_VARY_BL_OVERRIDE_EN', + 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_DISABLE', + 'DCIO_LVTMA_PWRSEQ_DISABLE_SYNCEN_CONTROL_OF_TX_ENABLE', + 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_OFF', + 'DCIO_LVTMA_PWRSEQ_TARGET_STATE_LCD_ON', + 'DCIO_LVTMA_SYNCEN_POL_INVERT', + 'DCIO_LVTMA_SYNCEN_POL_NON_INVERT', + 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_BLON', + 'DCIO_LVTMA_VARY_BL_OVERRIDE_EN_SEPARATE', + 'DCIO_MVP_PIXEL_SRC_STATUS_CRTC', + 'DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA', + 'DCIO_MVP_PIXEL_SRC_STATUS_HSYNCA_DUPLICATE', + 'DCIO_MVP_PIXEL_SRC_STATUS_LB', 'DCIO_SWAPLOCK_A_GSL_MASK', + 'DCIO_SWAPLOCK_A_GSL_MASK_NO', 'DCIO_SWAPLOCK_A_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_A_GSL_MASK_TIMING', 'DCIO_SWAPLOCK_B_GSL_MASK', + 'DCIO_SWAPLOCK_B_GSL_MASK_NO', 'DCIO_SWAPLOCK_B_GSL_MASK_STEREO', + 'DCIO_SWAPLOCK_B_GSL_MASK_TIMING', 'DCIO_TEST_CLK_SEL_DISPCLK', + 'DCIO_TEST_CLK_SEL_GATED_DISPCLK', 'DCIO_TEST_CLK_SEL_SCLK', + 'DCIO_UNIPHYA_FBDIV_CLK', 'DCIO_UNIPHYA_FBDIV_SSC_CLK', + 'DCIO_UNIPHYA_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYA_TEST_REFDIV_CLK', 'DCIO_UNIPHYB_FBDIV_CLK', + 'DCIO_UNIPHYB_FBDIV_SSC_CLK', 'DCIO_UNIPHYB_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYB_TEST_REFDIV_CLK', 'DCIO_UNIPHYC_FBDIV_CLK', + 'DCIO_UNIPHYC_FBDIV_SSC_CLK', 'DCIO_UNIPHYC_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYC_TEST_REFDIV_CLK', 'DCIO_UNIPHYD_FBDIV_CLK', + 'DCIO_UNIPHYD_FBDIV_SSC_CLK', 'DCIO_UNIPHYD_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYD_TEST_REFDIV_CLK', 'DCIO_UNIPHYE_FBDIV_CLK', + 'DCIO_UNIPHYE_FBDIV_SSC_CLK', 'DCIO_UNIPHYE_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYE_TEST_REFDIV_CLK', 'DCIO_UNIPHYF_FBDIV_CLK', + 'DCIO_UNIPHYF_FBDIV_SSC_CLK', 'DCIO_UNIPHYF_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYF_TEST_REFDIV_CLK', 'DCIO_UNIPHYG_FBDIV_CLK', + 'DCIO_UNIPHYG_FBDIV_SSC_CLK', 'DCIO_UNIPHYG_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYG_TEST_REFDIV_CLK', 'DCIO_UNIPHYLPA_FBDIV_CLK', + 'DCIO_UNIPHYLPA_FBDIV_SSC_CLK', + 'DCIO_UNIPHYLPA_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYLPA_TEST_REFDIV_CLK', 'DCIO_UNIPHYLPB_FBDIV_CLK', + 'DCIO_UNIPHYLPB_FBDIV_SSC_CLK', + 'DCIO_UNIPHYLPB_TEST_FBDIV_CLK_DIV2', + 'DCIO_UNIPHYLPB_TEST_REFDIV_CLK', 'DCIO_UNIPHY_CHANNEL_INVERTED', + 'DCIO_UNIPHY_CHANNEL_NO_INVERSION', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH0', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH1', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH2', + 'DCIO_UNIPHY_CHANNEL_XBAR_SOURCE_CH3', 'DCIO_UNIPHY_IMPCAL_SEL', + 'DCIO_UNIPHY_IMPCAL_SEL_BINARY', + 'DCIO_UNIPHY_IMPCAL_SEL_TEMPERATURE', + 'DCIO_UNIPHY_LINK_CNTL_CHANNEL_INVERT', + 'DCIO_UNIPHY_LINK_CNTL_ENABLE_HPD_MASK', + 'DCIO_UNIPHY_LINK_CNTL_MINIMUM_PIXVLD_LOW_DURATION', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_11_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_15_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_19_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_23_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_27_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_31_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_3_CLOCKS', + 'DCIO_UNIPHY_MINIMUM_PIXVLD_LOW_DURATION_7_CLOCKS', + 'DCIO_VIP_ALTER_MAPPING_EN_ALTERNATIVE', + 'DCIO_VIP_ALTER_MAPPING_EN_DEFAULT', 'DCIO_VIP_MUX_EN_DVO', + 'DCIO_VIP_MUX_EN_VIP', 'DCO_DBG_BLOCK_SEL', + 'DCO_DBG_BLOCK_SEL_ABM', 'DCO_DBG_BLOCK_SEL_AUDIO_OUT', + 'DCO_DBG_BLOCK_SEL_AUX0', 'DCO_DBG_BLOCK_SEL_AUX1', + 'DCO_DBG_BLOCK_SEL_AUX2', 'DCO_DBG_BLOCK_SEL_AUX3', + 'DCO_DBG_BLOCK_SEL_AUX4', 'DCO_DBG_BLOCK_SEL_AUX5', + 'DCO_DBG_BLOCK_SEL_DAC', 'DCO_DBG_BLOCK_SEL_DCO', + 'DCO_DBG_BLOCK_SEL_DIGA', 'DCO_DBG_BLOCK_SEL_DIGB', + 'DCO_DBG_BLOCK_SEL_DIGC', 'DCO_DBG_BLOCK_SEL_DIGD', + 'DCO_DBG_BLOCK_SEL_DIGE', 'DCO_DBG_BLOCK_SEL_DIGF', + 'DCO_DBG_BLOCK_SEL_DIGFE_A', 'DCO_DBG_BLOCK_SEL_DIGFE_B', + 'DCO_DBG_BLOCK_SEL_DIGFE_C', 'DCO_DBG_BLOCK_SEL_DIGFE_D', + 'DCO_DBG_BLOCK_SEL_DIGFE_E', 'DCO_DBG_BLOCK_SEL_DIGFE_F', + 'DCO_DBG_BLOCK_SEL_DIGFE_G', 'DCO_DBG_BLOCK_SEL_DIGG', + 'DCO_DBG_BLOCK_SEL_DIGLPA', 'DCO_DBG_BLOCK_SEL_DIGLPB', + 'DCO_DBG_BLOCK_SEL_DIGLPFEA', 'DCO_DBG_BLOCK_SEL_DIGLPFEB', + 'DCO_DBG_BLOCK_SEL_DPA', 'DCO_DBG_BLOCK_SEL_DPB', + 'DCO_DBG_BLOCK_SEL_DPC', 'DCO_DBG_BLOCK_SEL_DPD', + 'DCO_DBG_BLOCK_SEL_DPE', 'DCO_DBG_BLOCK_SEL_DPF', + 'DCO_DBG_BLOCK_SEL_DPFE_A', 'DCO_DBG_BLOCK_SEL_DPFE_B', + 'DCO_DBG_BLOCK_SEL_DPFE_C', 'DCO_DBG_BLOCK_SEL_DPFE_D', + 'DCO_DBG_BLOCK_SEL_DPFE_E', 'DCO_DBG_BLOCK_SEL_DPFE_F', + 'DCO_DBG_BLOCK_SEL_DPFE_G', 'DCO_DBG_BLOCK_SEL_DPG', + 'DCO_DBG_BLOCK_SEL_DPLPA', 'DCO_DBG_BLOCK_SEL_DPLPB', + 'DCO_DBG_BLOCK_SEL_DPLPFEA', 'DCO_DBG_BLOCK_SEL_DPLPFEB', + 'DCO_DBG_BLOCK_SEL_DVO', 'DCO_DBG_BLOCK_SEL_FMT0', + 'DCO_DBG_BLOCK_SEL_FMT1', 'DCO_DBG_BLOCK_SEL_FMT2', + 'DCO_DBG_BLOCK_SEL_FMT3', 'DCO_DBG_BLOCK_SEL_FMT4', + 'DCO_DBG_BLOCK_SEL_FMT5', 'DCO_DBG_BLOCK_SEL_MVP', + 'DCO_DBG_BLOCK_SEL_PERFMON_DCO', + 'DCO_HDMI_RXSTATUS_TIMER_CONTROL_DCO_HDMI_RXSTATUS_TIMER_TYPE', + 'DCO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', + 'DCO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', + 'DCP_ALPHA_ROUND_TRUNC_MODE', 'DCP_ALPHA_ROUND_TRUNC_MODE_ROUND', + 'DCP_ALPHA_ROUND_TRUNC_MODE_TRUNC', 'DCP_CRC_ENABLE', + 'DCP_CRC_ENABLE_FALSE', 'DCP_CRC_ENABLE_TRUE', 'DCP_CRC_LINE_SEL', + 'DCP_CRC_LINE_SEL_BOTH', 'DCP_CRC_LINE_SEL_EVEN', + 'DCP_CRC_LINE_SEL_ODD', 'DCP_CRC_LINE_SEL_RESERVED', + 'DCP_CRC_SOURCE_SEL', 'DCP_CRC_SOURCE_SEL_INPUT_H32', + 'DCP_CRC_SOURCE_SEL_INPUT_L32', 'DCP_CRC_SOURCE_SEL_OUTPUT_CNTL', + 'DCP_CRC_SOURCE_SEL_OUTPUT_PIX', 'DCP_CUR2_INV_TRANS_CLAMP', + 'DCP_CUR2_INV_TRANS_CLAMP_FALSE', 'DCP_CUR2_INV_TRANS_CLAMP_TRUE', + 'DCP_CURSOR_2X_MAGNIFY', 'DCP_CURSOR_2X_MAGNIFY_FALSE', + 'DCP_CURSOR_2X_MAGNIFY_TRUE', 'DCP_CURSOR_ALPHA_BLND_ENA', + 'DCP_CURSOR_ALPHA_BLND_ENA_FALSE', + 'DCP_CURSOR_ALPHA_BLND_ENA_TRUE', 'DCP_CURSOR_DEGAMMA_MODE', + 'DCP_CURSOR_DEGAMMA_MODE_BYPASS', + 'DCP_CURSOR_DEGAMMA_MODE_RESERVED', + 'DCP_CURSOR_DEGAMMA_MODE_ROMA', 'DCP_CURSOR_DEGAMMA_MODE_ROMB', + 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE', + 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_FALSE', + 'DCP_CURSOR_DISABLE_MULTIPLE_UPDATE_TRUE', 'DCP_CURSOR_EN', + 'DCP_CURSOR_EN_FALSE', 'DCP_CURSOR_EN_TRUE', + 'DCP_CURSOR_FORCE_MC_ON', 'DCP_CURSOR_FORCE_MC_ON_FALSE', + 'DCP_CURSOR_FORCE_MC_ON_TRUE', + 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM', + 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_ONE', + 'DCP_CURSOR_MAX_OUTSTANDING_GROUP_NUM_TWO', 'DCP_CURSOR_MODE', + 'DCP_CURSOR_MODE_24BPP_1BIT', + 'DCP_CURSOR_MODE_24BPP_8BIT_PREMULTI', + 'DCP_CURSOR_MODE_24BPP_8BIT_UNPREMULTI', + 'DCP_CURSOR_MODE_MONO_2BPP', 'DCP_CURSOR_STEREO_EN', + 'DCP_CURSOR_STEREO_EN_FALSE', 'DCP_CURSOR_STEREO_EN_TRUE', + 'DCP_CURSOR_STEREO_OFFSET_YNX', + 'DCP_CURSOR_STEREO_OFFSET_YNX_X_POSITION', + 'DCP_CURSOR_STEREO_OFFSET_YNX_Y_POSITION', + 'DCP_CURSOR_UPDATE_LOCK', 'DCP_CURSOR_UPDATE_LOCK_FALSE', + 'DCP_CURSOR_UPDATE_LOCK_TRUE', 'DCP_CURSOR_UPDATE_PENDING', + 'DCP_CURSOR_UPDATE_PENDING_FALSE', + 'DCP_CURSOR_UPDATE_PENDING_TRUE', 'DCP_CURSOR_UPDATE_STEREO_MODE', + 'DCP_CURSOR_UPDATE_STEREO_MODE_BOTH', + 'DCP_CURSOR_UPDATE_STEREO_MODE_PRIMARY_ONLY', + 'DCP_CURSOR_UPDATE_STEREO_MODE_SECONDARY_ONLY', + 'DCP_CURSOR_UPDATE_STEREO_MODE_UNDEFINED', + 'DCP_CURSOR_UPDATE_TAKEN', 'DCP_CURSOR_UPDATE_TAKEN_FALSE', + 'DCP_CURSOR_UPDATE_TAKEN_TRUE', 'DCP_CURSOR_URGENT_CONTROL', + 'DCP_CURSOR_URGENT_CONTROL_MODE_0', + 'DCP_CURSOR_URGENT_CONTROL_MODE_1', + 'DCP_CURSOR_URGENT_CONTROL_MODE_2', + 'DCP_CURSOR_URGENT_CONTROL_MODE_3', + 'DCP_CURSOR_URGENT_CONTROL_MODE_4', 'DCP_CUR_INV_TRANS_CLAMP', + 'DCP_CUR_INV_TRANS_CLAMP_FALSE', 'DCP_CUR_INV_TRANS_CLAMP_TRUE', + 'DCP_CUR_REQUEST_FILTER_DIS', 'DCP_CUR_REQUEST_FILTER_DIS_FALSE', + 'DCP_CUR_REQUEST_FILTER_DIS_TRUE', 'DCP_DC_LUT_AUTOFILL', + 'DCP_DC_LUT_AUTOFILL_DONE', 'DCP_DC_LUT_AUTOFILL_DONE_FALSE', + 'DCP_DC_LUT_AUTOFILL_DONE_TRUE', 'DCP_DC_LUT_AUTOFILL_FALSE', + 'DCP_DC_LUT_AUTOFILL_TRUE', 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN', + 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_FALSE', + 'DCP_DC_LUT_DATA_B_FLOAT_POINT_EN_TRUE', + 'DCP_DC_LUT_DATA_B_FORMAT', 'DCP_DC_LUT_DATA_B_FORMAT_S1P10', + 'DCP_DC_LUT_DATA_B_FORMAT_U0P10', + 'DCP_DC_LUT_DATA_B_FORMAT_U0P12', + 'DCP_DC_LUT_DATA_B_FORMAT_U1P11', 'DCP_DC_LUT_DATA_B_SIGNED_EN', + 'DCP_DC_LUT_DATA_B_SIGNED_EN_FALSE', + 'DCP_DC_LUT_DATA_B_SIGNED_EN_TRUE', + 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN', + 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_FALSE', + 'DCP_DC_LUT_DATA_G_FLOAT_POINT_EN_TRUE', + 'DCP_DC_LUT_DATA_G_FORMAT', 'DCP_DC_LUT_DATA_G_FORMAT_S1P10', + 'DCP_DC_LUT_DATA_G_FORMAT_U0P10', + 'DCP_DC_LUT_DATA_G_FORMAT_U0P12', + 'DCP_DC_LUT_DATA_G_FORMAT_U1P11', 'DCP_DC_LUT_DATA_G_SIGNED_EN', + 'DCP_DC_LUT_DATA_G_SIGNED_EN_FALSE', + 'DCP_DC_LUT_DATA_G_SIGNED_EN_TRUE', + 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN', + 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_FALSE', + 'DCP_DC_LUT_DATA_R_FLOAT_POINT_EN_TRUE', + 'DCP_DC_LUT_DATA_R_FORMAT', 'DCP_DC_LUT_DATA_R_FORMAT_S1P10', + 'DCP_DC_LUT_DATA_R_FORMAT_U0P10', + 'DCP_DC_LUT_DATA_R_FORMAT_U0P12', + 'DCP_DC_LUT_DATA_R_FORMAT_U1P11', 'DCP_DC_LUT_DATA_R_SIGNED_EN', + 'DCP_DC_LUT_DATA_R_SIGNED_EN_FALSE', + 'DCP_DC_LUT_DATA_R_SIGNED_EN_TRUE', 'DCP_DC_LUT_INC_B', + 'DCP_DC_LUT_INC_B_128', 'DCP_DC_LUT_INC_B_16', + 'DCP_DC_LUT_INC_B_2', 'DCP_DC_LUT_INC_B_256', + 'DCP_DC_LUT_INC_B_32', 'DCP_DC_LUT_INC_B_4', + 'DCP_DC_LUT_INC_B_512', 'DCP_DC_LUT_INC_B_64', + 'DCP_DC_LUT_INC_B_8', 'DCP_DC_LUT_INC_B_NA', 'DCP_DC_LUT_INC_G', + 'DCP_DC_LUT_INC_G_128', 'DCP_DC_LUT_INC_G_16', + 'DCP_DC_LUT_INC_G_2', 'DCP_DC_LUT_INC_G_256', + 'DCP_DC_LUT_INC_G_32', 'DCP_DC_LUT_INC_G_4', + 'DCP_DC_LUT_INC_G_512', 'DCP_DC_LUT_INC_G_64', + 'DCP_DC_LUT_INC_G_8', 'DCP_DC_LUT_INC_G_NA', 'DCP_DC_LUT_INC_R', + 'DCP_DC_LUT_INC_R_128', 'DCP_DC_LUT_INC_R_16', + 'DCP_DC_LUT_INC_R_2', 'DCP_DC_LUT_INC_R_256', + 'DCP_DC_LUT_INC_R_32', 'DCP_DC_LUT_INC_R_4', + 'DCP_DC_LUT_INC_R_512', 'DCP_DC_LUT_INC_R_64', + 'DCP_DC_LUT_INC_R_8', 'DCP_DC_LUT_INC_R_NA', 'DCP_DC_LUT_RW_MODE', + 'DCP_DC_LUT_RW_MODE_256_ENTRY', 'DCP_DC_LUT_RW_MODE_PWL', + 'DCP_DC_LUT_VGA_ACCESS_ENABLE', + 'DCP_DC_LUT_VGA_ACCESS_ENABLE_FALSE', + 'DCP_DC_LUT_VGA_ACCESS_ENABLE_TRUE', 'DCP_DENORM_14BIT_OUT', + 'DCP_DENORM_14BIT_OUT_FALSE', 'DCP_DENORM_14BIT_OUT_TRUE', + 'DCP_DENORM_MODE', 'DCP_DENORM_MODE_10BIT', + 'DCP_DENORM_MODE_11BIT', 'DCP_DENORM_MODE_12BIT', + 'DCP_DENORM_MODE_6BIT', 'DCP_DENORM_MODE_8BIT', + 'DCP_DENORM_MODE_RESERVED0', 'DCP_DENORM_MODE_RESERVED1', + 'DCP_DENORM_MODE_UNITY', 'DCP_FRAME_RANDOM_ENABLE', + 'DCP_FRAME_RANDOM_ENABLE_FALSE', 'DCP_FRAME_RANDOM_ENABLE_TRUE', + 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE', + 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_FALSE', + 'DCP_GRPH_ADDRESS_TRANSLATION_ENABLE_TRUE', + 'DCP_GRPH_ALPHA_CROSSBAR', 'DCP_GRPH_ALPHA_CROSSBAR_FROM_A', + 'DCP_GRPH_ALPHA_CROSSBAR_FROM_B', + 'DCP_GRPH_ALPHA_CROSSBAR_FROM_G', + 'DCP_GRPH_ALPHA_CROSSBAR_FROM_R', 'DCP_GRPH_BLUE_CROSSBAR', + 'DCP_GRPH_BLUE_CROSSBAR_FROM_A', 'DCP_GRPH_BLUE_CROSSBAR_FROM_B', + 'DCP_GRPH_BLUE_CROSSBAR_FROM_G', 'DCP_GRPH_BLUE_CROSSBAR_FROM_R', + 'DCP_GRPH_COLOR_EXPANSION_MODE', + 'DCP_GRPH_COLOR_EXPANSION_MODE_DEXP', + 'DCP_GRPH_COLOR_EXPANSION_MODE_ZEXP', 'DCP_GRPH_DEGAMMA_MODE', + 'DCP_GRPH_DEGAMMA_MODE_BYPASS', 'DCP_GRPH_DEGAMMA_MODE_RESERVED', + 'DCP_GRPH_DEGAMMA_MODE_ROMA', 'DCP_GRPH_DEGAMMA_MODE_ROMB', + 'DCP_GRPH_DEPTH', 'DCP_GRPH_DEPTH_16BPP', 'DCP_GRPH_DEPTH_32BPP', + 'DCP_GRPH_DEPTH_64BPP', 'DCP_GRPH_DEPTH_8BPP', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_1', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_2', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_3', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_4', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_5', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_6', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_7', + 'DCP_GRPH_DFQ_MIN_FREE_ENTRIES_8', 'DCP_GRPH_DFQ_RESET', + 'DCP_GRPH_DFQ_RESET_ACK', 'DCP_GRPH_DFQ_RESET_ACK_FALSE', + 'DCP_GRPH_DFQ_RESET_ACK_TRUE', 'DCP_GRPH_DFQ_RESET_FALSE', + 'DCP_GRPH_DFQ_RESET_TRUE', 'DCP_GRPH_DFQ_SIZE', + 'DCP_GRPH_DFQ_SIZE_DEEP1', 'DCP_GRPH_DFQ_SIZE_DEEP2', + 'DCP_GRPH_DFQ_SIZE_DEEP3', 'DCP_GRPH_DFQ_SIZE_DEEP4', + 'DCP_GRPH_DFQ_SIZE_DEEP5', 'DCP_GRPH_DFQ_SIZE_DEEP6', + 'DCP_GRPH_DFQ_SIZE_DEEP7', 'DCP_GRPH_DFQ_SIZE_DEEP8', + 'DCP_GRPH_ENABLE', 'DCP_GRPH_ENABLE_FALSE', + 'DCP_GRPH_ENABLE_TRUE', 'DCP_GRPH_ENDIAN_SWAP', + 'DCP_GRPH_ENDIAN_SWAP_8IN16', 'DCP_GRPH_ENDIAN_SWAP_8IN32', + 'DCP_GRPH_ENDIAN_SWAP_8IN64', 'DCP_GRPH_ENDIAN_SWAP_NONE', + 'DCP_GRPH_FLIP_RATE', 'DCP_GRPH_FLIP_RATE_1FRAME', + 'DCP_GRPH_FLIP_RATE_2FRAME', 'DCP_GRPH_FLIP_RATE_3FRAME', + 'DCP_GRPH_FLIP_RATE_4FRAME', 'DCP_GRPH_FLIP_RATE_5FRAME', + 'DCP_GRPH_FLIP_RATE_6FRAME', 'DCP_GRPH_FLIP_RATE_7FRAME', + 'DCP_GRPH_FLIP_RATE_8FRAME', 'DCP_GRPH_FLIP_RATE_ENABLE', + 'DCP_GRPH_FLIP_RATE_ENABLE_FALSE', + 'DCP_GRPH_FLIP_RATE_ENABLE_TRUE', 'DCP_GRPH_FORMAT', + 'DCP_GRPH_FORMAT_16BPP', 'DCP_GRPH_FORMAT_32BPP', + 'DCP_GRPH_FORMAT_64BPP', 'DCP_GRPH_FORMAT_8BPP', + 'DCP_GRPH_GAMUT_REMAP_MODE', 'DCP_GRPH_GAMUT_REMAP_MODE_BYPASS', + 'DCP_GRPH_GAMUT_REMAP_MODE_RESERVED', + 'DCP_GRPH_GAMUT_REMAP_MODE_ROMA', + 'DCP_GRPH_GAMUT_REMAP_MODE_ROMB', 'DCP_GRPH_GREEN_CROSSBAR', + 'DCP_GRPH_GREEN_CROSSBAR_FROM_A', + 'DCP_GRPH_GREEN_CROSSBAR_FROM_B', + 'DCP_GRPH_GREEN_CROSSBAR_FROM_G', + 'DCP_GRPH_GREEN_CROSSBAR_FROM_R', 'DCP_GRPH_INPUT_GAMMA_MODE', + 'DCP_GRPH_INPUT_GAMMA_MODE_BYPASS', + 'DCP_GRPH_INPUT_GAMMA_MODE_LUT', 'DCP_GRPH_KEYER_ALPHA_SEL', + 'DCP_GRPH_KEYER_ALPHA_SEL_FALSE', 'DCP_GRPH_KEYER_ALPHA_SEL_TRUE', + 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN', + 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_FALSE', + 'DCP_GRPH_LUT_10BIT_BYPASS_DBL_BUF_EN_TRUE', + 'DCP_GRPH_LUT_10BIT_BYPASS_EN', + 'DCP_GRPH_LUT_10BIT_BYPASS_EN_FALSE', + 'DCP_GRPH_LUT_10BIT_BYPASS_EN_TRUE', + 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE', + 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_FALSE', + 'DCP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_TRUE', + 'DCP_GRPH_MODE_UPDATE_PENDING', + 'DCP_GRPH_MODE_UPDATE_PENDING_FALSE', + 'DCP_GRPH_MODE_UPDATE_PENDING_TRUE', 'DCP_GRPH_MODE_UPDATE_TAKEN', + 'DCP_GRPH_MODE_UPDATE_TAKEN_FALSE', + 'DCP_GRPH_MODE_UPDATE_TAKEN_TRUE', 'DCP_GRPH_NUM_BANKS', + 'DCP_GRPH_NUM_BANKS_16BANK', 'DCP_GRPH_NUM_BANKS_1BANK', + 'DCP_GRPH_NUM_BANKS_2BANK', 'DCP_GRPH_NUM_BANKS_4BANK', + 'DCP_GRPH_NUM_BANKS_8BANK', 'DCP_GRPH_NUM_PIPES', + 'DCP_GRPH_NUM_PIPES_1PIPE', 'DCP_GRPH_NUM_PIPES_2PIPE', + 'DCP_GRPH_NUM_PIPES_4PIPE', 'DCP_GRPH_NUM_PIPES_8PIPE', + 'DCP_GRPH_PFLIP_INT_CLEAR', 'DCP_GRPH_PFLIP_INT_CLEAR_FALSE', + 'DCP_GRPH_PFLIP_INT_CLEAR_TRUE', 'DCP_GRPH_PFLIP_INT_MASK', + 'DCP_GRPH_PFLIP_INT_MASK_FALSE', 'DCP_GRPH_PFLIP_INT_MASK_TRUE', + 'DCP_GRPH_PFLIP_INT_TYPE', 'DCP_GRPH_PFLIP_INT_TYPE_LEGACY_LEVEL', + 'DCP_GRPH_PFLIP_INT_TYPE_PULSE', 'DCP_GRPH_PRESCALE_BYPASS', + 'DCP_GRPH_PRESCALE_BYPASS_FALSE', 'DCP_GRPH_PRESCALE_BYPASS_TRUE', + 'DCP_GRPH_PRESCALE_B_SIGN', 'DCP_GRPH_PRESCALE_B_SIGN_SIGNED', + 'DCP_GRPH_PRESCALE_B_SIGN_UNSIGNED', 'DCP_GRPH_PRESCALE_G_SIGN', + 'DCP_GRPH_PRESCALE_G_SIGN_SIGNED', + 'DCP_GRPH_PRESCALE_G_SIGN_UNSIGNED', 'DCP_GRPH_PRESCALE_R_SIGN', + 'DCP_GRPH_PRESCALE_R_SIGN_SIGNED', + 'DCP_GRPH_PRESCALE_R_SIGN_UNSIGNED', 'DCP_GRPH_PRESCALE_SELECT', + 'DCP_GRPH_PRESCALE_SELECT_FIXED', + 'DCP_GRPH_PRESCALE_SELECT_FLOATING', + 'DCP_GRPH_PRIMARY_DFQ_ENABLE', + 'DCP_GRPH_PRIMARY_DFQ_ENABLE_FALSE', + 'DCP_GRPH_PRIMARY_DFQ_ENABLE_TRUE', 'DCP_GRPH_RED_CROSSBAR', + 'DCP_GRPH_RED_CROSSBAR_FROM_A', 'DCP_GRPH_RED_CROSSBAR_FROM_B', + 'DCP_GRPH_RED_CROSSBAR_FROM_G', 'DCP_GRPH_RED_CROSSBAR_FROM_R', + 'DCP_GRPH_REGAMMA_MODE', 'DCP_GRPH_REGAMMA_MODE_BYPASS', + 'DCP_GRPH_REGAMMA_MODE_PROGA', 'DCP_GRPH_REGAMMA_MODE_PROGB', + 'DCP_GRPH_REGAMMA_MODE_SRGB', 'DCP_GRPH_REGAMMA_MODE_XVYCC', + 'DCP_GRPH_ROTATION_ANGLE', 'DCP_GRPH_ROTATION_ANGLE_0', + 'DCP_GRPH_ROTATION_ANGLE_180', 'DCP_GRPH_ROTATION_ANGLE_270', + 'DCP_GRPH_ROTATION_ANGLE_90', 'DCP_GRPH_SECONDARY_DFQ_ENABLE', + 'DCP_GRPH_SECONDARY_DFQ_ENABLE_FALSE', + 'DCP_GRPH_SECONDARY_DFQ_ENABLE_TRUE', + 'DCP_GRPH_STEREOSYNC_FLIP_EN', + 'DCP_GRPH_STEREOSYNC_FLIP_EN_FALSE', + 'DCP_GRPH_STEREOSYNC_FLIP_EN_TRUE', + 'DCP_GRPH_STEREOSYNC_FLIP_MODE', + 'DCP_GRPH_STEREOSYNC_FLIP_MODE_FLIP', + 'DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE0', + 'DCP_GRPH_STEREOSYNC_FLIP_MODE_PHASE1', + 'DCP_GRPH_STEREOSYNC_FLIP_MODE_RESET', + 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE', + 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE_FALSE', + 'DCP_GRPH_STEREOSYNC_SELECT_DISABLE_TRUE', + 'DCP_GRPH_SURFACE_COUNTER_EN', + 'DCP_GRPH_SURFACE_COUNTER_EN_DISABLE', + 'DCP_GRPH_SURFACE_COUNTER_EN_ENABLE', + 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED', + 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_NO', + 'DCP_GRPH_SURFACE_COUNTER_ERR_WRAP_OCCURED_YES', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_0', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_1', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_10', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_11', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_2', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_3', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_4', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_5', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_6', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_7', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_8', + 'DCP_GRPH_SURFACE_COUNTER_EVENT_SELECT_9', + 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE', + 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_FALSE', + 'DCP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_TRUE', + 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK', + 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_FALSE', + 'DCP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_TRUE', + 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN', + 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_FALSE', + 'DCP_GRPH_SURFACE_UPDATE_H_RETRACE_EN_TRUE', + 'DCP_GRPH_SURFACE_UPDATE_PENDING', + 'DCP_GRPH_SURFACE_UPDATE_PENDING_FALSE', + 'DCP_GRPH_SURFACE_UPDATE_PENDING_TRUE', + 'DCP_GRPH_SURFACE_UPDATE_TAKEN', + 'DCP_GRPH_SURFACE_UPDATE_TAKEN_FALSE', + 'DCP_GRPH_SURFACE_UPDATE_TAKEN_TRUE', + 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE', + 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_FALSE', + 'DCP_GRPH_SURFACE_XDMA_PENDING_ENABLE_TRUE', 'DCP_GRPH_SW_MODE', + 'DCP_GRPH_SW_MODE_0', 'DCP_GRPH_SW_MODE_2', 'DCP_GRPH_SW_MODE_22', + 'DCP_GRPH_SW_MODE_23', 'DCP_GRPH_SW_MODE_26', + 'DCP_GRPH_SW_MODE_27', 'DCP_GRPH_SW_MODE_3', + 'DCP_GRPH_SW_MODE_30', 'DCP_GRPH_SW_MODE_31', + 'DCP_GRPH_UPDATE_LOCK', 'DCP_GRPH_UPDATE_LOCK_FALSE', + 'DCP_GRPH_UPDATE_LOCK_TRUE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_FALSE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_EN_TRUE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_ENABLE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_CNT_MODE_RELY_NUM', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_FALSE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_ACK_TRUE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_FALSE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_FRAME_MASK_TRUE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_FALSE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_ACK_TRUE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_FALSE', + 'DCP_GRPH_XDMA_CACHE_UNDERFLOW_INT_MASK_TRUE', + 'DCP_GRPH_XDMA_DRR_MODE_ENABLE', + 'DCP_GRPH_XDMA_DRR_MODE_ENABLE_DISABLE', + 'DCP_GRPH_XDMA_DRR_MODE_ENABLE_ENABLE', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_FALSE', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_ACK_TRUE', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_FALSE', + 'DCP_GRPH_XDMA_FLIP_TIMEOUT_MASK_TRUE', + 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR', + 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_DISABLE', + 'DCP_GRPH_XDMA_FLIP_TYPE_CLEAR_ENABLE', + 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE', + 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE_DISABLE', + 'DCP_GRPH_XDMA_MULTIFLIP_ENABLE_ENABLE', + 'DCP_GRPH_XDMA_SUPER_AA_EN', 'DCP_GRPH_XDMA_SUPER_AA_EN_FALSE', + 'DCP_GRPH_XDMA_SUPER_AA_EN_TRUE', 'DCP_GSL0_EN', + 'DCP_GSL0_EN_FALSE', 'DCP_GSL0_EN_TRUE', 'DCP_GSL1_EN', + 'DCP_GSL1_EN_FALSE', 'DCP_GSL1_EN_TRUE', 'DCP_GSL2_EN', + 'DCP_GSL2_EN_FALSE', 'DCP_GSL2_EN_TRUE', + 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING', + 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_FALSE', + 'DCP_GSL_DELAY_SURFACE_UPDATE_PENDING_TRUE', 'DCP_GSL_MASTER_EN', + 'DCP_GSL_MASTER_EN_FALSE', 'DCP_GSL_MASTER_EN_TRUE', + 'DCP_GSL_SYNC_SOURCE', 'DCP_GSL_SYNC_SOURCE_FLIP', + 'DCP_GSL_SYNC_SOURCE_PHASE0', 'DCP_GSL_SYNC_SOURCE_PHASE1', + 'DCP_GSL_SYNC_SOURCE_RESET', + 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC', + 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_DIS', + 'DCP_GSL_USE_CHECKPOINT_WINDOW_IN_VSYNC_EN', 'DCP_GSL_XDMA_GROUP', + 'DCP_GSL_XDMA_GROUP_HSYNC0', 'DCP_GSL_XDMA_GROUP_HSYNC1', + 'DCP_GSL_XDMA_GROUP_HSYNC2', 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN', + 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_FALSE', + 'DCP_GSL_XDMA_GROUP_UNDERFLOW_EN_TRUE', + 'DCP_GSL_XDMA_GROUP_VSYNC', 'DCP_HIGHPASS_RANDOM_ENABLE', + 'DCP_HIGHPASS_RANDOM_ENABLE_FALSE', + 'DCP_HIGHPASS_RANDOM_ENABLE_TRUE', 'DCP_INPUT_CSC_GRPH_MODE', + 'DCP_INPUT_CSC_GRPH_MODE_BYPASS', + 'DCP_INPUT_CSC_GRPH_MODE_INPUT_CSC_COEF', + 'DCP_INPUT_CSC_GRPH_MODE_RESERVED', + 'DCP_INPUT_CSC_GRPH_MODE_SHARED_COEF', 'DCP_KEY_MODE', + 'DCP_KEY_MODE_ALPHA0', 'DCP_KEY_MODE_ALPHA1', + 'DCP_KEY_MODE_IN_RANGE_ALPHA0', 'DCP_KEY_MODE_IN_RANGE_ALPHA1', + 'DCP_OUTPUT_CSC_GRPH_MODE', 'DCP_OUTPUT_CSC_GRPH_MODE_BYPASS', + 'DCP_OUTPUT_CSC_GRPH_MODE_OUTPUT_CSC_COEF', + 'DCP_OUTPUT_CSC_GRPH_MODE_RESERVED0', + 'DCP_OUTPUT_CSC_GRPH_MODE_RESERVED1', + 'DCP_OUTPUT_CSC_GRPH_MODE_RGB', + 'DCP_OUTPUT_CSC_GRPH_MODE_SHARED_COEF', + 'DCP_OUTPUT_CSC_GRPH_MODE_YCBCR601', + 'DCP_OUTPUT_CSC_GRPH_MODE_YCBCR709', 'DCP_OUT_ROUND_TRUNC_MODE', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_10', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_11', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_12', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_13', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_14', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_8', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_9', + 'DCP_OUT_ROUND_TRUNC_MODE_ROUND_RESERVED', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_10', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_11', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_12', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_13', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_14', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_8', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_9', + 'DCP_OUT_ROUND_TRUNC_MODE_TRUNCATE_RESERVED', + 'DCP_RGB_RANDOM_ENABLE', 'DCP_RGB_RANDOM_ENABLE_FALSE', + 'DCP_RGB_RANDOM_ENABLE_TRUE', 'DCP_SPATIAL_DITHER_DEPTH', + 'DCP_SPATIAL_DITHER_DEPTH_24BPP', + 'DCP_SPATIAL_DITHER_DEPTH_30BPP', + 'DCP_SPATIAL_DITHER_DEPTH_36BPP', + 'DCP_SPATIAL_DITHER_DEPTH_UNDEFINED', 'DCP_SPATIAL_DITHER_EN', + 'DCP_SPATIAL_DITHER_EN_FALSE', 'DCP_SPATIAL_DITHER_EN_TRUE', + 'DCP_SPATIAL_DITHER_MODE', 'DCP_SPATIAL_DITHER_MODE_BYPASS', + 'DCP_SPATIAL_DITHER_MODE_RESERVED', + 'DCP_SPATIAL_DITHER_MODE_ROMA', 'DCP_SPATIAL_DITHER_MODE_ROMB', + 'DCP_TEST_DEBUG_WRITE_EN', 'DCP_TEST_DEBUG_WRITE_EN_FALSE', + 'DCP_TEST_DEBUG_WRITE_EN_TRUE', 'DC_MEM_GLOBAL_PWR_REQ_DIS', + 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', + 'DEGAMMA_MODE_A', 'DEGAMMA_MODE_B', 'DEGAMMA_MODE_BYPASS', + 'DENORM_CLAMP_MODE_10', 'DENORM_CLAMP_MODE_12', + 'DENORM_CLAMP_MODE_8', 'DENORM_CLAMP_MODE_UNITY', 'DEPTH_16', + 'DEPTH_32_FLOAT', 'DEPTH_8_24', 'DEPTH_8_24_FLOAT', + 'DEPTH_INVALID', 'DEPTH_X24_8_32_FLOAT', 'DEPTH_X8_24', + 'DEPTH_X8_24_FLOAT', 'DFSMFlushEvents', 'DIGA_BE_SOFT_RESET', + 'DIGA_BE_SOFT_RESET_0', 'DIGA_BE_SOFT_RESET_1', + 'DIGA_FE_SOFT_RESET', 'DIGA_FE_SOFT_RESET_0', + 'DIGA_FE_SOFT_RESET_1', 'DIGB_BE_SOFT_RESET', + 'DIGB_BE_SOFT_RESET_0', 'DIGB_BE_SOFT_RESET_1', + 'DIGB_FE_SOFT_RESET', 'DIGB_FE_SOFT_RESET_0', + 'DIGB_FE_SOFT_RESET_1', 'DIGC_BE_SOFT_RESET', + 'DIGC_BE_SOFT_RESET_0', 'DIGC_BE_SOFT_RESET_1', + 'DIGC_FE_SOFT_RESET', 'DIGC_FE_SOFT_RESET_0', + 'DIGC_FE_SOFT_RESET_1', 'DIGD_BE_SOFT_RESET', + 'DIGD_BE_SOFT_RESET_0', 'DIGD_BE_SOFT_RESET_1', + 'DIGD_FE_SOFT_RESET', 'DIGD_FE_SOFT_RESET_0', + 'DIGD_FE_SOFT_RESET_1', 'DIGE_BE_SOFT_RESET', + 'DIGE_BE_SOFT_RESET_0', 'DIGE_BE_SOFT_RESET_1', + 'DIGE_FE_SOFT_RESET', 'DIGE_FE_SOFT_RESET_0', + 'DIGE_FE_SOFT_RESET_1', 'DIGF_BE_SOFT_RESET', + 'DIGF_BE_SOFT_RESET_0', 'DIGF_BE_SOFT_RESET_1', + 'DIGF_FE_SOFT_RESET', 'DIGF_FE_SOFT_RESET_0', + 'DIGF_FE_SOFT_RESET_1', 'DIGG_BE_SOFT_RESET', + 'DIGG_BE_SOFT_RESET_0', 'DIGG_BE_SOFT_RESET_1', + 'DIGG_FE_SOFT_RESET', 'DIGG_FE_SOFT_RESET_0', + 'DIGG_FE_SOFT_RESET_1', 'DIGLPA_BE_SOFT_RESET', + 'DIGLPA_BE_SOFT_RESET_0', 'DIGLPA_BE_SOFT_RESET_1', + 'DIGLPA_FE_SOFT_RESET', 'DIGLPA_FE_SOFT_RESET_0', + 'DIGLPA_FE_SOFT_RESET_1', 'DIGLPB_BE_SOFT_RESET', + 'DIGLPB_BE_SOFT_RESET_0', 'DIGLPB_BE_SOFT_RESET_1', + 'DIGLPB_FE_SOFT_RESET', 'DIGLPB_FE_SOFT_RESET_0', + 'DIGLPB_FE_SOFT_RESET_1', 'DIG_10BIT_TEST_PATTERN', + 'DIG_ALTERNATING_TEST_PATTERN', 'DIG_BE_CNTL_HPD1', + 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', 'DIG_BE_CNTL_HPD4', + 'DIG_BE_CNTL_HPD5', 'DIG_BE_CNTL_HPD6', 'DIG_BE_CNTL_HPD_SELECT', + 'DIG_BE_CNTL_MODE', 'DIG_BE_DP_MST_MODE', 'DIG_BE_DP_SST_MODE', + 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', 'DIG_BE_RESERVED3', + 'DIG_BE_SDVO_RESERVED', 'DIG_BE_TMDS_DVI_MODE', + 'DIG_BE_TMDS_HDMI_MODE', 'DIG_FE_CNTL_SOURCE_SELECT', + 'DIG_FE_CNTL_STEREOSYNC_SELECT', 'DIG_FE_SOURCE_FROM_FMT0', + 'DIG_FE_SOURCE_FROM_FMT1', 'DIG_FE_SOURCE_FROM_FMT2', + 'DIG_FE_SOURCE_FROM_FMT3', 'DIG_FE_SOURCE_FROM_FMT4', + 'DIG_FE_SOURCE_FROM_FMT5', 'DIG_FE_STEREOSYNC_FROM_FMT0', + 'DIG_FE_STEREOSYNC_FROM_FMT1', 'DIG_FE_STEREOSYNC_FROM_FMT2', + 'DIG_FE_STEREOSYNC_FROM_FMT3', 'DIG_FE_STEREOSYNC_FROM_FMT4', + 'DIG_FE_STEREOSYNC_FROM_FMT5', 'DIG_FIFO_ERROR_ACK', + 'DIG_FIFO_ERROR_ACK_INT', 'DIG_FIFO_ERROR_NOT_ACK', + 'DIG_FIFO_FORCE_RECAL_AVERAGE_LEVEL', + 'DIG_FIFO_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_NOT_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_NOT_FORCE_RECOMP_MINMAX', 'DIG_FIFO_READ_CLOCK_SRC', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DCCG', + 'DIG_FIFO_READ_CLOCK_SRC_FROM_DISPLAY_PIPE', + 'DIG_FIFO_STATUS_FORCE_RECAL_AVERAGE', + 'DIG_FIFO_STATUS_FORCE_RECOMP_MINMAX', + 'DIG_FIFO_STATUS_USE_OVERWRITE_LEVEL', + 'DIG_FIFO_USE_CAL_AVERAGE_LEVEL', 'DIG_FIFO_USE_OVERWRITE_LEVEL', + 'DIG_IN_DEBUG_MODE', 'DIG_IN_NORMAL_OPERATION', + 'DIG_OUTPUT_CRC_CNTL_LINK_SEL', 'DIG_OUTPUT_CRC_DATA_SEL', + 'DIG_OUTPUT_CRC_FOR_ACTIVEONLY', 'DIG_OUTPUT_CRC_FOR_AUDIO', + 'DIG_OUTPUT_CRC_FOR_FULLFRAME', 'DIG_OUTPUT_CRC_FOR_VBI', + 'DIG_OUTPUT_CRC_ON_LINK0', 'DIG_OUTPUT_CRC_ON_LINK1', + 'DIG_RANDOM_PATTERN_ENABLED', 'DIG_RANDOM_PATTERN_RESETED', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_ALL_PIXELS', + 'DIG_RANDOM_PATTERN_SEED_RAN_PAT_DE_HIGH', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_BY_EXT_SIG', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_EN', + 'DIG_TEST_PATTERN_EXTERNAL_RESET_ENABLE', + 'DIG_TEST_PATTERN_HALF_CLOCK_PATTERN_SEL', + 'DIG_TEST_PATTERN_NORMAL', 'DIG_TEST_PATTERN_RANDOM', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_OUT_EN', + 'DIG_TEST_PATTERN_RANDOM_PATTERN_RESET', + 'DIG_TEST_PATTERN_TEST_PATTERN_OUT_EN', + 'DISABLE_BINNING_USE_LEGACY_SC', 'DISABLE_BINNING_USE_NEW_SC', + 'DISABLE_CLOCK_GATING', 'DISABLE_CLOCK_GATING_IN_DCO', + 'DISABLE_JITTER_REMOVAL', 'DISABLE_MEM_PWR_CTRL', + 'DISABLE_THE_CLOCK', 'DISABLE_THE_FEATURE', + 'DISPCLK_CHG_FWD_CORR_DISABLE', + 'DISPCLK_CHG_FWD_CORR_DISABLE_AT_BEGINNING', + 'DISPCLK_CHG_FWD_CORR_ENABLE_AT_BEGINNING', + 'DISPCLK_FREQ_RAMP_COMPLETED', 'DISPCLK_FREQ_RAMP_DONE', + 'DISPCLK_FREQ_RAMP_IN_PROGRESS', 'DITHER_DIS', 'DITHER_EN', + 'DI_INDEX_SIZE_16_BIT', 'DI_INDEX_SIZE_32_BIT', + 'DI_INDEX_SIZE_8_BIT', 'DI_MAJOR_MODE_0', 'DI_MAJOR_MODE_1', + 'DI_PT_2D_RECTANGLE', 'DI_PT_LINELIST', 'DI_PT_LINELIST_ADJ', + 'DI_PT_LINELOOP', 'DI_PT_LINESTRIP', 'DI_PT_LINESTRIP_ADJ', + 'DI_PT_NONE', 'DI_PT_PATCH', 'DI_PT_POINTLIST', 'DI_PT_POLYGON', + 'DI_PT_QUADLIST', 'DI_PT_QUADSTRIP', 'DI_PT_RECTLIST', + 'DI_PT_TRIFAN', 'DI_PT_TRILIST', 'DI_PT_TRILIST_ADJ', + 'DI_PT_TRISTRIP', 'DI_PT_TRISTRIP_ADJ', 'DI_PT_TRI_WITH_WFLAGS', + 'DI_PT_UNUSED_1', 'DI_PT_UNUSED_3', 'DI_PT_UNUSED_4', + 'DI_SRC_SEL_AUTO_INDEX', 'DI_SRC_SEL_DMA', 'DI_SRC_SEL_IMMEDIATE', + 'DI_SRC_SEL_RESERVED', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_DISABLE', + 'DMA_POSITION_LOWER_BASE_ADDRESS_BUFFER_ENABLE_DMA_ENABLE', + 'DONUTS', 'DOUT_I2C_ACK', 'DOUT_I2C_ACK_TO_CLEAN', + 'DOUT_I2C_ARBITRATION_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_ABORT_XFER', + 'DOUT_I2C_ARBITRATION_DONE_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__NOT_USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_DONE__USING_I2C_REG', + 'DOUT_I2C_ARBITRATION_NOT_ABORT_CURRENT_TRANSFER', + 'DOUT_I2C_ARBITRATION_NO_QUEUED_SW_GO', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_0_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_1_RESERVED', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_HIGH', + 'DOUT_I2C_ARBITRATION_SW_PRIORITY_NORMAL', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_DISABLED', + 'DOUT_I2C_ARBITRATION_SW_QUEUE_ENABLED', + 'DOUT_I2C_ARBITRATION_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__NOT_USE_I2C_REG_REQ', + 'DOUT_I2C_ARBITRATION__USE_I2C_REG_REQ', + 'DOUT_I2C_CONTROL_DBG_REF_SEL', 'DOUT_I2C_CONTROL_DDC_SELECT', + 'DOUT_I2C_CONTROL_FAST_REFERENCE_DEBUG', 'DOUT_I2C_CONTROL_GO', + 'DOUT_I2C_CONTROL_NORMAL_DEBUG', + 'DOUT_I2C_CONTROL_NOT_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_NOT_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_RESET_I2C_CONTROLLER', + 'DOUT_I2C_CONTROL_RESET_SW_STATUS', + 'DOUT_I2C_CONTROL_SELECT_DDC1', 'DOUT_I2C_CONTROL_SELECT_DDC2', + 'DOUT_I2C_CONTROL_SELECT_DDC3', 'DOUT_I2C_CONTROL_SELECT_DDC4', + 'DOUT_I2C_CONTROL_SELECT_DDC5', 'DOUT_I2C_CONTROL_SELECT_DDC6', + 'DOUT_I2C_CONTROL_SELECT_DDCVGA', 'DOUT_I2C_CONTROL_SEND_RESET', + 'DOUT_I2C_CONTROL_SOFT_RESET', 'DOUT_I2C_CONTROL_START_TRANSFER', + 'DOUT_I2C_CONTROL_STOP_TRANSFER', + 'DOUT_I2C_CONTROL_SW_STATUS_RESET', 'DOUT_I2C_CONTROL_TRANS0', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2', + 'DOUT_I2C_CONTROL_TRANS0_TRANS1_TRANS2_TRANS3', + 'DOUT_I2C_CONTROL_TRANSACTION_COUNT', + 'DOUT_I2C_CONTROL__NOT_SEND_RESET', + 'DOUT_I2C_CONTROL__SEND_RESET', 'DOUT_I2C_DATA_INDEX_WRITE', + 'DOUT_I2C_DATA__INDEX_WRITE', 'DOUT_I2C_DATA__NOT_INDEX_WRITE', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_CLK_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_BY_EXTERNAL_RESISTOR', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_EN', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_10MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_FOR_20MCLKS', + 'DOUT_I2C_DDC_SETUP_DATA_DRIVE_SEL', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_CONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_DISCONNECT', + 'DOUT_I2C_DDC_SETUP_EDID_DETECT_MODE', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SCL', + 'DOUT_I2C_DDC_SETUP_I2C_PAD_DRIVE_SDA', + 'DOUT_I2C_DDC_SPEED_THRESHOLD', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_BIG_THAN_ZERO', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_HALF_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_QUATER_OF_TOTAL_SAMPLE', + 'DOUT_I2C_DDC_SPEED_THRESHOLD_THREE_QUATERS_OF_TOTAL_SAMPLE', + 'DOUT_I2C_EDID_DETECT_CTRL_SEND_RESET', + 'DOUT_I2C_EDID_NOT_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_EDID_SEND_RESET_BEFORE_EDID_READ_TRACTION', + 'DOUT_I2C_NO_ACK', 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__LEVEL', + 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', + 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', + 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DOWNSCALE_PREFETCH_DIS', + 'DOWNSCALE_PREFETCH_EN', 'DPCSRX_BPHY_PCS_RX0_CLK', + 'DPCSRX_BPHY_PCS_RX1_CLK', 'DPCSRX_BPHY_PCS_RX2_CLK', + 'DPCSRX_BPHY_PCS_RX3_CLK', 'DPCSRX_DBG_CFGCLK_SEL', + 'DPCSRX_DBG_CFGCLK_SEL_CBUS_MASTER', + 'DPCSRX_DBG_CFGCLK_SEL_CBUS_SLAVE', + 'DPCSRX_DBG_CFGCLK_SEL_DC_DPCS_INF', + 'DPCSRX_DBG_CFGCLK_SEL_DPCS_BPHY_INF', + 'DPCSRX_DBG_RX_SYMCLK_SEL_INT', 'DPCSRX_DBG_RX_SYMCLK_SEL_OUT0', + 'DPCSRX_DBG_RX_SYMCLK_SEL_OUT1', + 'DPCSRX_RX_CLOCK_CNTL_DPCS_SYMCLK_RX_SEL', 'DPCSRX_RX_SYMCLK_SEL', + 'DPCSTX_DBG_CFGCLK_SEL', 'DPCSTX_DBG_CFGCLK_SEL_CBUS_MASTER', + 'DPCSTX_DBG_CFGCLK_SEL_CBUS_SLAVE', + 'DPCSTX_DBG_CFGCLK_SEL_DC_DPCS_INF', + 'DPCSTX_DBG_CFGCLK_SEL_DPCS_BPHY_INF', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_FIFO_RD', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_INT', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT0', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT1', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT2', + 'DPCSTX_DBG_TX_SYMCLK_DIV2_SEL_OUT3', + 'DPCSTX_DBG_TX_SYMCLK_SEL_FIFO_WR', + 'DPCSTX_DBG_TX_SYMCLK_SEL_IN0', 'DPCSTX_DBG_TX_SYMCLK_SEL_IN1', + 'DPCSTX_TX_SYMCLK_DIV2_SEL', 'DPCSTX_TX_SYMCLK_SEL', + 'DPDBG_CLK_FORCE_EN', 'DPDBG_CLK_FORCE_EN_DISABLE', + 'DPDBG_CLK_FORCE_EN_ENABLE', 'DPDBG_DISABLE', 'DPDBG_EN', + 'DPDBG_ENABLE', 'DPDBG_ERROR_DETECTION_MODE', + 'DPDBG_ERROR_DETECTION_MODE_CSC', + 'DPDBG_ERROR_DETECTION_MODE_RS_ENCODING', + 'DPDBG_FIFO_OVERFLOW_INTERRUPT_ACK', + 'DPDBG_FIFO_OVERFLOW_INTERRUPT_MASK', + 'DPDBG_FIFO_OVERFLOW_INTERRUPT_TYPE', + 'DPDBG_FIFO_OVERFLOW_INT_CLEAR', + 'DPDBG_FIFO_OVERFLOW_INT_DISABLE', + 'DPDBG_FIFO_OVERFLOW_INT_ENABLE', + 'DPDBG_FIFO_OVERFLOW_INT_LEVEL_BASED', + 'DPDBG_FIFO_OVERFLOW_INT_NO_ACK', + 'DPDBG_FIFO_OVERFLOW_INT_PULSE_BASED', 'DPDBG_INPUT_DISABLE', + 'DPDBG_INPUT_EN', 'DPDBG_INPUT_ENABLE', 'DPDBG_SOFT_RESET', + 'DPDBG_SOFT_RESET_0', 'DPDBG_SOFT_RESET_1', 'DPHY_8B10B_CUR_DISP', + 'DPHY_8B10B_CUR_DISP_ONE', 'DPHY_8B10B_CUR_DISP_ZERO', + 'DPHY_8B10B_NOT_RESET', 'DPHY_8B10B_OUTPUT', 'DPHY_8B10B_RESET', + 'DPHY_8B10B_RESETET', + 'DPHY_ALT_SCRAMBLER_INTERNAL_RESET_SOLUTION', + 'DPHY_ALT_SCRAMBLER_REGULAR_RESET_VALUE', + 'DPHY_ALT_SCRAMBLER_RESET_EN', 'DPHY_ALT_SCRAMBLER_RESET_SEL', + 'DPHY_ALT_SCRAMBLER_RESET_SEL_CUSTOM_RESET_VALUE', + 'DPHY_ALT_SCRAMBLER_RESET_SEL_EDP_RESET_VALUE', + 'DPHY_ATEST_LANE0_PRBS_PATTERN', 'DPHY_ATEST_LANE0_REG_PATTERN', + 'DPHY_ATEST_LANE1_PRBS_PATTERN', 'DPHY_ATEST_LANE1_REG_PATTERN', + 'DPHY_ATEST_LANE2_PRBS_PATTERN', 'DPHY_ATEST_LANE2_REG_PATTERN', + 'DPHY_ATEST_LANE3_PRBS_PATTERN', 'DPHY_ATEST_LANE3_REG_PATTERN', + 'DPHY_ATEST_SEL_LANE0', 'DPHY_ATEST_SEL_LANE1', + 'DPHY_ATEST_SEL_LANE2', 'DPHY_ATEST_SEL_LANE3', 'DPHY_BYPASS', + 'DPHY_CRC_CONTINUOUS', 'DPHY_CRC_CONT_EN', 'DPHY_CRC_DISABLED', + 'DPHY_CRC_EN', 'DPHY_CRC_ENABLED', 'DPHY_CRC_FIELD', + 'DPHY_CRC_LANE0_SELECTED', 'DPHY_CRC_LANE1_SELECTED', + 'DPHY_CRC_LANE2_SELECTED', 'DPHY_CRC_LANE3_SELECTED', + 'DPHY_CRC_MST_PHASE_ERROR_ACK', 'DPHY_CRC_MST_PHASE_ERROR_ACKED', + 'DPHY_CRC_MST_PHASE_ERROR_NO_ACK', 'DPHY_CRC_ONE_SHOT', + 'DPHY_CRC_SEL', 'DPHY_CRC_START_FROM_BOTTOM_FIELD', + 'DPHY_CRC_START_FROM_TOP_FIELD', 'DPHY_DBG_OUTPUT', + 'DPHY_DPHY_SCRAMBLER_ADVANCE_ON_DATA_SYMBOL_ONLY', + 'DPHY_FAST_TRAINING_CAPABLE', 'DPHY_FAST_TRAINING_NOT_CAPABLE_0', + 'DPHY_LOAD_BS_COUNT_NOT_STARTED', 'DPHY_LOAD_BS_COUNT_START', + 'DPHY_LOAD_BS_COUNT_STARTED', 'DPHY_NO_SKEW', + 'DPHY_PRBS11_SELECTED', 'DPHY_PRBS23_SELECTED', + 'DPHY_PRBS7_SELECTED', 'DPHY_PRBS_DISABLE', 'DPHY_PRBS_EN', + 'DPHY_PRBS_ENABLE', 'DPHY_PRBS_SEL', + 'DPHY_RX_FAST_TRAINING_CAPABLE', 'DPHY_SCRAMBLER_ADVANCE', + 'DPHY_SCRAMBLER_ADVANCE_ON_BOTH_DATA_AND_CTRL', + 'DPHY_SCRAMBLER_DIS', 'DPHY_SCRAMBLER_KCODE', + 'DPHY_SCRAMBLER_KCODE_DISABLED', 'DPHY_SCRAMBLER_KCODE_ENABLED', + 'DPHY_SCRAMBLER_SEL', 'DPHY_SCRAMBLER_SEL_DBG_DATA', + 'DPHY_SCRAMBLER_SEL_LANE_DATA', 'DPHY_SCR_DISABLED', + 'DPHY_SCR_ENABLED', 'DPHY_SKEW_BYPASS', + 'DPHY_SW_FAST_TRAINING_NOT_STARTED', + 'DPHY_SW_FAST_TRAINING_START', 'DPHY_SW_FAST_TRAINING_STARTED', + 'DPHY_TRAINING_PATTERN_1', 'DPHY_TRAINING_PATTERN_2', + 'DPHY_TRAINING_PATTERN_3', 'DPHY_TRAINING_PATTERN_4', + 'DPHY_TRAINING_PATTERN_SEL', 'DPHY_WITH_SKEW', 'DPREFCLK_SRC_SEL', + 'DPREFCLK_SRC_SEL_CK', 'DPREFCLK_SRC_SEL_P0PLL', + 'DPREFCLK_SRC_SEL_P1PLL', 'DPREFCLK_SRC_SEL_P2PLL', + 'DPREFCLK_SRC_SEL_P3PLL', 'DPRX_SD_COMPONENT_DEPTH', + 'DPRX_SD_PIXEL_ENCODING', 'DP_AUX_ARB_CONTROL_ARB_PRIORITY', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__GTC_LS_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__LS_GTC_SW', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_GTC_LS', + 'DP_AUX_ARB_CONTROL_ARB_PRIORITY__SW_LS_GTC', + 'DP_AUX_ARB_CONTROL_DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__DONE_NOT_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__DONE_USING_AUX_REG', + 'DP_AUX_ARB_CONTROL__NOT_USE_AUX_REG_REQ', + 'DP_AUX_ARB_CONTROL__USE_AUX_REG_REQ', + 'DP_AUX_CONTROL_HPD1_SELECTED', 'DP_AUX_CONTROL_HPD2_SELECTED', + 'DP_AUX_CONTROL_HPD3_SELECTED', 'DP_AUX_CONTROL_HPD4_SELECTED', + 'DP_AUX_CONTROL_HPD5_SELECTED', 'DP_AUX_CONTROL_HPD6_SELECTED', + 'DP_AUX_CONTROL_HPD_SEL', 'DP_AUX_CONTROL_TEST_MODE', + 'DP_AUX_CONTROL_TEST_MODE_DISABLE', + 'DP_AUX_CONTROL_TEST_MODE_ENABLE', + 'DP_AUX_DEFINITE_ERR_REACHED_ACK', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__10_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__18_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__6_EDGES', + 'DP_AUX_DPHY_RX_CONTROL_HALF_SYM_DETECT_LEN__RESERVED', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__2_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__4_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__6_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_PHASE_DETECT_LEN__8_HALF_SYMBOLS', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_RECEIVE_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO128_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO16_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO256_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO2_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO32_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO4_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO64_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_START_WINDOW__1TO8_PERIOD', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_450US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_500US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_550US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_600US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_650US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_700US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_750US', + 'DP_AUX_DPHY_RX_CONTROL_TIMEOUT_LEN_800US', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_PHASE_DETECT', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_START', + 'DP_AUX_DPHY_RX_CONTROL__NOT_ALLOW_BELOW_THRESHOLD_STOP', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__127to128', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__15to16', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__1to2', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__255to256', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__31to32', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__3to4', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__63to64', + 'DP_AUX_DPHY_RX_DETECTION_THRESHOLD__7to8', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__0', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__128US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__16US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__256US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__32US', + 'DP_AUX_DPHY_TX_CONTROL_MODE_DET_CHECK_DELAY__64US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__0US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__16US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__24US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__32US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__40US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__48US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__56US', + 'DP_AUX_DPHY_TX_CONTROL_PRECHARGE_LEN__8US', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__1MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__2MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__4MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_RATE__8MHZ', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__DIVIDED_SYM_CLK', + 'DP_AUX_DPHY_TX_REF_CONTROL_TX_REF_SEL__FROM_DCCG_MICROSECOND_REF', + 'DP_AUX_ERR_OCCURRED_ACK', 'DP_AUX_ERR_OCCURRED__ACK', + 'DP_AUX_ERR_OCCURRED__NOT_ACK', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_ALLOW_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ', + 'DP_AUX_GTC_SYNC_CONTROL_GTC_SYNC_BLOCK_REQ_FROM_OTHER_AUX', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__300US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__400US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__500US', + 'DP_AUX_GTC_SYNC_CONTROL_INTERVAL_RESET_WINDOW__600US', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__16_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__4_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__8_ATTAMPS', + 'DP_AUX_GTC_SYNC_CONTROL_OFFSET_CALC_MAX_ATTEMPT__RESERVED', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__0', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__128', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__256', + 'DP_AUX_GTC_SYNC_ERROR_CONTROL_LOCK_ACQ_TIMEOUT_LEN__64', + 'DP_AUX_INT_ACK', 'DP_AUX_INT_LS_UPDATE_ACK', + 'DP_AUX_INT_LS_UPDATE_NOT_ACK', 'DP_AUX_INT__ACK', + 'DP_AUX_INT__NOT_ACK', 'DP_AUX_LS_UPDATE_ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED_ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__ACK', + 'DP_AUX_POTENTIAL_ERR_REACHED__NOT_ACK', 'DP_AUX_RESET', + 'DP_AUX_RESET_ASSERTED', 'DP_AUX_RESET_DEASSERTED', + 'DP_AUX_RESET_DONE', 'DP_AUX_RESET_SEQUENCE_DONE', + 'DP_AUX_RESET_SEQUENCE_NOT_DONE', + 'DP_AUX_SW_CONTROL_LS_READ_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__NOT_TRIG', + 'DP_AUX_SW_CONTROL_LS_READ__TRIG', 'DP_AUX_SW_CONTROL_SW_GO', + 'DP_AUX_SW_CONTROL_SW__GO', 'DP_AUX_SW_CONTROL_SW__NOT_GO', + 'DP_COMPONENT_DEPTH', 'DP_COMPONENT_DEPTH_10BPC', + 'DP_COMPONENT_DEPTH_12BPC', 'DP_COMPONENT_DEPTH_16BPC_RESERVED', + 'DP_COMPONENT_DEPTH_6BPC', 'DP_COMPONENT_DEPTH_8BPC', + 'DP_COMPONENT_DEPTH_RESERVED', 'DP_DPHY_8B10B_EXT_DISP', + 'DP_DPHY_8B10B_EXT_DISP_ONE', 'DP_DPHY_8B10B_EXT_DISP_ZERO', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASK', + 'DP_DPHY_FAST_TRAINING_COMPLETE_MASKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_ACKED', + 'DP_DPHY_FAST_TRAINING_COMPLETE_NOT_MASKED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_DISABLED', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_EN', + 'DP_DPHY_FAST_TRAINING_VBLANK_EDGE_DETECT_ENABLED', + 'DP_DPHY_HBR2_PASS_THROUGH', 'DP_DPHY_HBR2_PATTERN_1', + 'DP_DPHY_HBR2_PATTERN_2_NEG', 'DP_DPHY_HBR2_PATTERN_2_POS', + 'DP_DPHY_HBR2_PATTERN_3', 'DP_DPHY_HBR2_PATTERN_CONTROL_MODE', + 'DP_DTO_DESPREAD_DISABLE', 'DP_DTO_DESPREAD_ENABLE', + 'DP_DTO_DS_DISABLE', 'DP_DYN_CEA_RANGE', 'DP_DYN_RANGE', + 'DP_DYN_VESA_RANGE', 'DP_EMBEDDED_PANEL', + 'DP_EMBEDDED_PANEL_MODE', 'DP_EXTERNAL_PANEL', + 'DP_LINK_TRAINING_ALREADY_COMPLETE', 'DP_LINK_TRAINING_COMPLETE', + 'DP_LINK_TRAINING_NOT_COMPLETE', 'DP_MSA_MISC0_OVERRIDE_ENABLE', + 'DP_MSA_MISC1_BIT7_OVERRIDE_ENABLE', + 'DP_MSA_V_TIMING_OVERRIDE_EN', 'DP_MSE_BLANK_CODE', + 'DP_MSE_BLANK_CODE_SF_FILLED', 'DP_MSE_BLANK_CODE_ZERO_FILLED', + 'DP_MSE_LINK_LINE', 'DP_MSE_LINK_LINE_128_MTP_LONG', + 'DP_MSE_LINK_LINE_256_MTP_LONG', 'DP_MSE_LINK_LINE_32_MTP_LONG', + 'DP_MSE_LINK_LINE_64_MTP_LONG', 'DP_MSE_NOT_ZERO_FE_ENCODER', + 'DP_MSE_OUTPUT_DPDBG_DATA', 'DP_MSE_OUTPUT_DPDBG_DATA_DIS', + 'DP_MSE_OUTPUT_DPDBG_DATA_EN', 'DP_MSE_SAT_UPDATE_ACT', + 'DP_MSE_SAT_UPDATE_NO_ACTION', + 'DP_MSE_SAT_UPDATE_WITHOUT_TRIGGER', + 'DP_MSE_SAT_UPDATE_WITH_TRIGGER', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_LINK_RATE', + 'DP_MSE_TIMESTAMP_CALC_BASED_ON_VC_RATE', 'DP_MSE_TIMESTAMP_MODE', + 'DP_MSE_ZERO_ENCODER', 'DP_MSE_ZERO_FE_ENCODER', + 'DP_PIXEL_ENCODING', 'DP_PIXEL_ENCODING_RESERVED', + 'DP_PIXEL_ENCODING_RGB444', 'DP_PIXEL_ENCODING_RGB_WIDE_GAMUT', + 'DP_PIXEL_ENCODING_YCBCR420', 'DP_PIXEL_ENCODING_YCBCR422', + 'DP_PIXEL_ENCODING_YCBCR444', 'DP_PIXEL_ENCODING_Y_ONLY', + 'DP_SEC_ASP_CHANNEL_COUNT_FROM_AZ', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE', + 'DP_SEC_ASP_CHANNEL_COUNT_OVERRIDE_ENABLED', + 'DP_SEC_ASP_HIGH_PRIORITY', 'DP_SEC_ASP_LOW_PRIORITY', + 'DP_SEC_ASP_PRIORITY', 'DP_SEC_AUDIO_MUTE', + 'DP_SEC_AUDIO_MUTE_HW_CTRL', 'DP_SEC_AUDIO_MUTE_SW_CTRL', + 'DP_SEC_COLLISION_ACK', 'DP_SEC_COLLISION_ACK_CLR_FLAG', + 'DP_SEC_COLLISION_ACK_NO_EFFECT', 'DP_SEC_GSP0_PRIORITY', + 'DP_SEC_GSP0_SEND', 'DP_SEC_TIMESTAMP_AUTO_CALC_MODE', + 'DP_SEC_TIMESTAMP_MODE', 'DP_SEC_TIMESTAMP_PROGRAMMABLE_MODE', + 'DP_STEER_OVERFLOW_ACK', 'DP_STEER_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_STEER_OVERFLOW_ACK_NO_EFFECT', 'DP_STEER_OVERFLOW_MASK', + 'DP_STEER_OVERFLOW_MASKED', 'DP_STEER_OVERFLOW_UNMASK', + 'DP_TOP_FIELD_ONLY', 'DP_TOP_PLUS_BOTTOM_FIELD', + 'DP_TU_OVERFLOW_ACK', 'DP_TU_OVERFLOW_ACK_CLR_INTERRUPT', + 'DP_TU_OVERFLOW_ACK_NO_EFFECT', 'DP_UDI_1_LANE', 'DP_UDI_2_LANES', + 'DP_UDI_4_LANES', 'DP_UDI_LANES', 'DP_UDI_LANES_RESERVED', + 'DP_VID_ENHANCED_FRAME_MODE', 'DP_VID_MSA_TOP_FIELD_MODE', + 'DP_VID_M_DOUBLE_INPUT_PIXEL_RATE', 'DP_VID_M_DOUBLE_VALUE_EN', + 'DP_VID_M_INPUT_PIXEL_RATE', 'DP_VID_M_N_CALC_AUTO', + 'DP_VID_M_N_DOUBLE_BUFFER_AFTER_VID_M_UPDATE', + 'DP_VID_M_N_DOUBLE_BUFFER_AT_FRAME_START', + 'DP_VID_M_N_DOUBLE_BUFFER_MODE', 'DP_VID_M_N_GEN_EN', + 'DP_VID_M_N_PROGRAMMED_VIA_REG', 'DP_VID_STREAM_DISABLE_ACK', + 'DP_VID_STREAM_DISABLE_MASK', 'DP_VID_STREAM_DIS_DEFER', + 'DP_VID_STREAM_DIS_DEFER_TO_HBLANK', + 'DP_VID_STREAM_DIS_DEFER_TO_VBLANK', 'DP_VID_STREAM_DIS_NO_DEFER', + 'DP_VID_TIMING_MODE', 'DP_VID_TIMING_MODE_ASYNC', + 'DP_VID_TIMING_MODE_SYNC', 'DP_VID_VBID_FIELD_POL', + 'DP_VID_VBID_FIELD_POL_INV', 'DP_VID_VBID_FIELD_POL_NORMAL', + 'DP_YCBCR_RANGE', 'DP_YCBCR_RANGE_BT601_5', + 'DP_YCBCR_RANGE_BT709_5', 'DSI_BIT_SWAP', 'DSI_BIT_SWAP_DISABLE', + 'DSI_BIT_SWAP_ENABLE', 'DSI_CLK_GATING', 'DSI_CLK_GATING_DISABLE', + 'DSI_CLK_GATING_ENABLE', 'DSI_CLOCK_LANE_DISABLE', + 'DSI_CLOCK_LANE_EN', 'DSI_CLOCK_LANE_ENABLE', + 'DSI_CLOCK_LANE_HS_FORCE_REQUEST', + 'DSI_CLOCK_LANE_HS_FORCE_REQUEST_ASSERT', + 'DSI_CLOCK_LANE_HS_FORCE_REQUEST_DEASSERT', + 'DSI_CMD_EMBEDDED_MODE', 'DSI_CMD_MODE_DISABLE', + 'DSI_CMD_MODE_EN', 'DSI_CMD_MODE_ENABLE', 'DSI_CMD_ORDER', + 'DSI_CMD_ORDER_COMMAND_FIRST', 'DSI_CMD_ORDER_DATA_FIRST', + 'DSI_CMD_PACKET_TYPE', 'DSI_CMD_PACKET_TYPE_LONG', + 'DSI_CMD_PACKET_TYPE_SHORT', 'DSI_CMD_PWR_MODE', + 'DSI_CMD_PWR_MODE_HS', 'DSI_CMD_PWR_MODE_LP', + 'DSI_CMD_USE_CMDFIFO', 'DSI_CMD_USE_DMAFIFO', + 'DSI_COMMAND_DST_FORMAT_RGB111', 'DSI_COMMAND_DST_FORMAT_RGB332', + 'DSI_COMMAND_DST_FORMAT_RGB444', 'DSI_COMMAND_DST_FORMAT_RGB565', + 'DSI_COMMAND_DST_FORMAT_RGB666', 'DSI_COMMAND_DST_FORMAT_RGB888', + 'DSI_COMMAND_MODE_DST_FORMAT', 'DSI_COMMAND_MODE_SRC_FORMAT', + 'DSI_COMMAND_SRC_FORMAT_RGB332', 'DSI_COMMAND_SRC_FORMAT_RGB444', + 'DSI_COMMAND_SRC_FORMAT_RGB555', 'DSI_COMMAND_SRC_FORMAT_RGB565', + 'DSI_COMMAND_SRC_FORMAT_RGB888', 'DSI_COMMAND_SRC_FORMAT_RGB8BIT', + 'DSI_COMMAND_TRIGGER_MODE', 'DSI_COMMAND_TRIGGER_MODE_AUTO', + 'DSI_COMMAND_TRIGGER_MODE_MANUAL', 'DSI_COMMAND_TRIGGER_ORDER', + 'DSI_COMMAND_TRIGGER_ORDER_DENG', 'DSI_COMMAND_TRIGGER_ORDER_DMA', + 'DSI_COMMAND_TRIGGER_SEL', 'DSI_COMMAND_TRIGGER_SEL_CRTC', + 'DSI_COMMAND_TRIGGER_SEL_HW', 'DSI_COMMAND_TRIGGER_SEL_NONE', + 'DSI_COMMAND_TRIGGER_SEL_TE', 'DSI_CONTROLLER_DISABLE', + 'DSI_CONTROLLER_EN', 'DSI_CONTROLLER_ENABLE', + 'DSI_CRC_CAL_DISABLE', 'DSI_CRC_CAL_ENABLE', 'DSI_CRC_ENABLE', + 'DSI_CRTC_FREEZE_TRIG', 'DSI_CRTC_FREEZE_TRIG_ASSERT', + 'DSI_CRTC_FREEZE_TRIG_DEASSERT', 'DSI_CRTC_SEL', + 'DSI_DATA_BUFFER_ID', 'DSI_DATA_BUFFER_OFFSET0', + 'DSI_DATA_BUFFER_OFFSET1', 'DSI_DATA_LANE0_DISABLE', + 'DSI_DATA_LANE0_EN', 'DSI_DATA_LANE0_ENABLE', + 'DSI_DATA_LANE1_DISABLE', 'DSI_DATA_LANE1_EN', + 'DSI_DATA_LANE1_ENABLE', 'DSI_DATA_LANE2_DISABLE', + 'DSI_DATA_LANE2_EN', 'DSI_DATA_LANE2_ENABLE', + 'DSI_DATA_LANE3_DISABLE', 'DSI_DATA_LANE3_EN', + 'DSI_DATA_LANE3_ENABLE', 'DSI_DBG_CLK_SEL', + 'DSI_DEBUG_BYTECLK_SEL', 'DSI_DEBUG_BYTECLK_SEL_AFIFO', + 'DSI_DEBUG_BYTECLK_SEL_EOT', 'DSI_DEBUG_BYTECLK_SEL_LANEBUF0', + 'DSI_DEBUG_BYTECLK_SEL_LANEBUF1', + 'DSI_DEBUG_BYTECLK_SEL_LANEBUF2', + 'DSI_DEBUG_BYTECLK_SEL_LANEBUF3', + 'DSI_DEBUG_BYTECLK_SEL_LANECTRL', + 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO0', + 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO1', + 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO2', + 'DSI_DEBUG_BYTECLK_SEL_LANEFIFO3', + 'DSI_DEBUG_BYTECLK_SEL_PINGPING2', + 'DSI_DEBUG_BYTECLK_SEL_PINGPING3', + 'DSI_DEBUG_BYTECLK_SEL_PINGPONG0', + 'DSI_DEBUG_BYTECLK_SEL_PINGPONG1', 'DSI_DEBUG_DSICLK_SEL', + 'DSI_DEBUG_DSICLK_SEL_AFIFO', 'DSI_DEBUG_DSICLK_SEL_CMDBUFFER', + 'DSI_DEBUG_DSICLK_SEL_CMDFIFO', 'DSI_DEBUG_DSICLK_SEL_CMD_ENGINE', + 'DSI_DEBUG_DSICLK_SEL_LANECTRL', + 'DSI_DEBUG_DSICLK_SEL_RESYNC_FIFO', + 'DSI_DEBUG_DSICLK_SEL_VIDEO_ENGINE', + 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE', + 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_ASSERT', + 'DSI_DENG_FIFO_FORCE_RECAL_AVERAGE_DEASSERT', + 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX', + 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_ASSERT', + 'DSI_DENG_FIFO_FORCE_RECOMP_MINMAX_DEASSERT', + 'DSI_DENG_FIFO_LEVEL_CAL_AVERAGE', + 'DSI_DENG_FIFO_LEVEL_OVERWRITE', 'DSI_DENG_FIFO_START', + 'DSI_DENG_FIFO_START_ASSERT', 'DSI_DENG_FIFO_START_DEASSERT', + 'DSI_DENG_FIFO_USE_OVERWRITE_LEVEL', 'DSI_DMAFIFO_READ_WATERMARK', + 'DSI_DMAFIFO_READ_WATERMARK_EIGHTH', + 'DSI_DMAFIFO_READ_WATERMARK_FOURTH', + 'DSI_DMAFIFO_READ_WATERMARK_HALF', + 'DSI_DMAFIFO_READ_WATERMARK_SIXTEENTH', + 'DSI_DMAFIFO_WRITE_WATERMARK', + 'DSI_DMAFIFO_WRITE_WATERMARK_EIGHTH', + 'DSI_DMAFIFO_WRITE_WATERMARK_FOURTH', + 'DSI_DMAFIFO_WRITE_WATERMARK_HALF', + 'DSI_DMAFIFO_WRITE_WATERMARK_SIXTEENTH', 'DSI_DWORD_BYTE_SWAP', + 'DSI_EXT_RESET_POL', 'DSI_EXT_RESET_POL_HIGH', + 'DSI_EXT_RESET_POL_LOW', 'DSI_EXT_TE_MODE', + 'DSI_EXT_TE_MODE_HVSYNC_EDGE', 'DSI_EXT_TE_MODE_HVSYNC_WIDTH', + 'DSI_EXT_TE_MODE_VSYNC_EDGE', 'DSI_EXT_TE_MODE_VSYNC_WIDTH', + 'DSI_EXT_TE_MUX', 'DSI_EXT_TE_POL', 'DSI_EXT_TE_POL_FALLING', + 'DSI_EXT_TE_POL_RISING', 'DSI_FLAG_CLEAR', 'DSI_FLAG_CLR', + 'DSI_FLAG_NO_CLEAR', 'DSI_GET_PIXEL_STREAM_FROM_FMT0', + 'DSI_GET_PIXEL_STREAM_FROM_FMT1', + 'DSI_GET_PIXEL_STREAM_FROM_FMT2', + 'DSI_GET_PIXEL_STREAM_FROM_FMT3', + 'DSI_GET_PIXEL_STREAM_FROM_FMT4', + 'DSI_GET_PIXEL_STREAM_FROM_FMT5', 'DSI_HW_SOURCE_SEL', + 'DSI_INSERT_DCS_COMMAND', 'DSI_INSERT_DCS_COMMAND_DISABLE', + 'DSI_INSERT_DCS_COMMAND_ENABLE', 'DSI_LANE_FORCE_TX_STOP', + 'DSI_LANE_FORCE_TX_STOP_ASSERT', + 'DSI_LANE_FORCE_TX_STOP_DEASSERT', 'DSI_LANE_ULPS_EXIT', + 'DSI_LANE_ULPS_EXIT_ASSERT', 'DSI_LANE_ULPS_EXIT_DEASSERT', + 'DSI_LANE_ULPS_REQUEST', 'DSI_LANE_ULPS_REQUEST_ASSERT', + 'DSI_LANE_ULPS_REQUEST_DEASSERT', 'DSI_MIPI_BIST_RESET', + 'DSI_MIPI_BIST_RESET_ASSERT', 'DSI_MIPI_BIST_RESET_DEASSERT', + 'DSI_MIPI_BIST_START', 'DSI_MIPI_BIST_START_ASSERT', + 'DSI_MIPI_BIST_START_DEASSERT', 'DSI_MIPI_BIST_VIDEO_FRMT', + 'DSI_MIPI_BIST_VIDEO_FRMT_RAW8', + 'DSI_MIPI_BIST_VIDEO_FRMT_YUV422', + 'DSI_NO_RESET_ON_BYTECLK_DOMAIN_LOGIC', + 'DSI_NO_RESET_ON_DISPCLK_DOMAIN_LOGIC', + 'DSI_NO_RESET_ON_DSICLK_DOMAIN_LOGIC', + 'DSI_NO_RESET_ON_ESCCLK_DOMAIN_LOGIC', + 'DSI_PACKET_BYTE_MSB_LSB_FLIP', + 'DSI_PACKET_BYTE_MSB_LSB_FLIP_NO_SWAP', + 'DSI_PACKET_BYTE_MSB_LSB_FLIP_SWAP', 'DSI_PERF_LATENCY_SEL', + 'DSI_PERF_LATENCY_SEL_DATA_LANE0', + 'DSI_PERF_LATENCY_SEL_DATA_LANE1', + 'DSI_PERF_LATENCY_SEL_DATA_LANE2', + 'DSI_PERF_LATENCY_SEL_DATA_LANE3', 'DSI_PHY_DATA_LANE0_DISABLE', + 'DSI_PHY_DATA_LANE0_EN', 'DSI_PHY_DATA_LANE0_ENABLE', + 'DSI_PHY_DATA_LANE1_DISABLE', 'DSI_PHY_DATA_LANE1_EN', + 'DSI_PHY_DATA_LANE1_ENABLE', 'DSI_PHY_DATA_LANE2_DISABLE', + 'DSI_PHY_DATA_LANE2_EN', 'DSI_PHY_DATA_LANE2_ENABLE', + 'DSI_PHY_DATA_LANE3_DISABLE', 'DSI_PHY_DATA_LANE3_EN', + 'DSI_PHY_DATA_LANE3_ENABLE', 'DSI_RESET_BYTECLK', + 'DSI_RESET_DISPCLK', 'DSI_RESET_DSICLK', 'DSI_RESET_ESCCLK', + 'DSI_RESET_ON_BYTECLK_DOMAIN_LOGIC', + 'DSI_RESET_ON_DISPCLK_DOMAIN_LOGIC', + 'DSI_RESET_ON_DSICLK_DOMAIN_LOGIC', + 'DSI_RESET_ON_ESCCLK_DOMAIN_LOGIC', 'DSI_RESET_PANEL', + 'DSI_RESET_PANEL_ASSERT', 'DSI_RESET_PANEL_DEASSERT', + 'DSI_RGB_SWAP', 'DSI_RX_EOT_IGNORE', 'DSI_RX_EOT_IGNORE_DISABLE', + 'DSI_RX_EOT_IGNORE_ENABLE', 'DSI_SWAP_BGR', 'DSI_SWAP_BRG', + 'DSI_SWAP_GBR', 'DSI_SWAP_GRB', 'DSI_SWAP_RBG', 'DSI_SWAP_RGB', + 'DSI_TEST_CLK_SEL_BYTECLK_G', 'DSI_TEST_CLK_SEL_DISPCLK_G', + 'DSI_TEST_CLK_SEL_DISPCLK_P', 'DSI_TEST_CLK_SEL_DISPCLK_R', + 'DSI_TEST_CLK_SEL_DSICLK_G', 'DSI_TEST_CLK_SEL_DSICLK_P', + 'DSI_TEST_CLK_SEL_DSICLK_R', 'DSI_TEST_CLK_SEL_DSICLK_TRN', + 'DSI_TEST_CLK_SEL_ESCCLK_G', 'DSI_TE_SEL_LINK', 'DSI_TE_SEL_PIN', + 'DSI_TE_SRC_SEL', 'DSI_TRAFFIC_MODE_BURST', + 'DSI_TRAFFIC_MODE_RESERVED', 'DSI_TRAFFIC_MODE_SYNC_EVENTS', + 'DSI_TRAFFIC_MODE_SYNC_PULSES', 'DSI_TX_EOT_APPEND', + 'DSI_TX_EOT_APPEND_DISABLE', 'DSI_TX_EOT_APPEND_ENABLE', + 'DSI_USE_CMDFIFO', 'DSI_USE_DENG_LENGTH', + 'DSI_USE_DENG_LENGTH_DISABLE', 'DSI_USE_DENG_LENGTH_ENABLE', + 'DSI_VIDEO_BLLP_PWR_MODE', 'DSI_VIDEO_BLLP_PWR_MODE_HS', + 'DSI_VIDEO_BLLP_PWR_MODE_LP', 'DSI_VIDEO_DST_FORMAT_RGB565', + 'DSI_VIDEO_DST_FORMAT_RGB666_LOOSELY_PACKED', + 'DSI_VIDEO_DST_FORMAT_RGB666_PACKED', + 'DSI_VIDEO_DST_FORMAT_RGB888', 'DSI_VIDEO_EOF_BLLP_PWR_MODE', + 'DSI_VIDEO_EOF_BLLP_PWR_MODE_HS', + 'DSI_VIDEO_EOF_BLLP_PWR_MODE_LP', 'DSI_VIDEO_MODE_DISABLE', + 'DSI_VIDEO_MODE_DST_FORMAT', 'DSI_VIDEO_MODE_EN', + 'DSI_VIDEO_MODE_ENABLE', 'DSI_VIDEO_PULSE_MODE_OPT', + 'DSI_VIDEO_PWR_MODE', 'DSI_VIDEO_PWR_MODE_HS', + 'DSI_VIDEO_PWR_MODE_LP', 'DSI_VIDEO_TRAFFIC_MODE', + 'DSI_XT_TE_MUX_DCLK', 'DSI_XT_TE_MUX_DINV', 'DSI_XT_TE_MUX_FRAME', + 'DSI_XT_TE_MUX_GCLK', 'DSI_XT_TE_MUX_GOE', 'DSI_XT_TE_MUX_GPIO4', + 'DSI_XT_TE_MUX_GPIO5', 'DSI_XT_TE_MUX_LCDD17', 'DSI_XT_TE_MUX_SS', + 'DSM_ENABLE_ERROR_INJECT', 'DSM_ENABLE_ERROR_INJECT_DOUBLE', + 'DSM_ENABLE_ERROR_INJECT_DOUBLE_LIMITED', + 'DSM_ENABLE_ERROR_INJECT_FED_IN', + 'DSM_ENABLE_ERROR_INJECT_SINGLE', 'DSM_SELECT_INJECT_DELAY', + 'DSM_SELECT_INJECT_DELAY_DELAY_ERROR', + 'DSM_SELECT_INJECT_DELAY_NO_DELAY', 'DS_REF_IS_EXT_GENLOCK', + 'DS_REF_IS_PCIE', 'DS_REF_IS_XTALIN', 'DS_REF_SRC', + 'DVOACLKC_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', 'DVOACLKC_IN_PHASE', + 'DVOACLKC_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_IN_PHASE', 'DVOACLKC_MVP_IN_PHASE_WITH_PCLK_DVO', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_DISABLE', + 'DVOACLKC_MVP_SKEW_PHASE_OVERRIDE_ENABLE', + 'DVOACLKD_IN_OPPOSITE_PHASE_WITH_PCLK_DVO', 'DVOACLKD_IN_PHASE', + 'DVOACLKD_IN_PHASE_WITH_PCLK_DVO', 'DVOACLK_COARSE_SKEW_CNTL', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_DELAY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_10_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_11_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_12_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_13_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_14_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_15_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_5_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_6_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_7_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_8_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_EARLY_9_STEPS', + 'DVOACLK_COARSE_SKEW_CNTL_NO_ADJUSTMENT', + 'DVOACLK_FINE_SKEW_CNTL', 'DVOACLK_FINE_SKEW_CNTL_DELAY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_DELAY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_1_STEP', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_2_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_3_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_EARLY_4_STEPS', + 'DVOACLK_FINE_SKEW_CNTL_NO_ADJUSTMENT', 'DVO_ENABLE_RST', + 'DVO_ENABLE_RST_DISABLE', 'DVO_ENABLE_RST_ENABLE', + 'DVO_SOFT_RESET', 'DVO_SOFT_RESET_0', 'DVO_SOFT_RESET_1', + 'DWORD_BYTE_SWAP_BOTH_SWAP', 'DWORD_BYTE_SWAP_BYTE_SWAP', + 'DWORD_BYTE_SWAP_NO_SWAP', 'DWORD_BYTE_SWAP_WORD_SWAP', + 'DYNAMIC_DEEP_SLEEP_EN', 'DYNAMIC_DEEP_SLEEP_ENABLE', + 'DYNAMIC_LIGHT_SLEEP_EN', 'DYNAMIC_LIGHT_SLEEP_ENABLE', + 'DYNAMIC_PIXEL_DEPTH_30BPP', 'DYNAMIC_PIXEL_DEPTH_36BPP', + 'DYNAMIC_SHUT_DOWN_ENABLE', 'DbMemArbWatermarks', + 'DbPRTFaultBehavior', 'DbPSLControl', 'DepthArray', 'DepthFormat', + 'EARLY_Z_THEN_LATE_Z', 'EARLY_Z_THEN_RE_Z', 'ENABLE', + 'ENABLE_CLOCK', 'ENABLE_JITTER_REMOVAL', 'ENABLE_LEGACY_PIPELINE', + 'ENABLE_MEM_PWR_CTRL', 'ENABLE_NGG_PIPELINE', 'ENABLE_THE_CLOCK', + 'ENABLE_THE_FEATURE', 'ENDIAN_8IN16', 'ENDIAN_8IN32', + 'ENDIAN_8IN64', 'ENDIAN_NONE', 'END_OF_PIPE_IB_END', + 'END_OF_PIPE_INCR_DE', 'ENUMS_GDS_PERFCOUNT_SELECT_H', + 'ENUM_NUM_SIMD_PER_CU', 'ENUM_SQ_EXPORT_RAT_INST', + 'ENUM_XDMA_LOCAL_SW_MODE', 'ENUM_XDMA_MSTR_ALPHA_POSITION', + 'ENUM_XDMA_MSTR_VSYNC_GSL_CHECK_SEL', + 'ENUM_XDMA_SLV_ALPHA_POSITION', 'ES_STAGE_DS', 'ES_STAGE_OFF', + 'ES_STAGE_REAL', 'EXPORT_16_16_FLOAT_8PIX', + 'EXPORT_16_16_SIGNED_8PIX', 'EXPORT_16_16_UNSIGNED_8PIX', + 'EXPORT_2C_32BPC_AR', 'EXPORT_2C_32BPC_GR', + 'EXPORT_2P_32BPC_ABGR', 'EXPORT_32BPP_8PIX', 'EXPORT_32_ABGR', + 'EXPORT_32_AR', 'EXPORT_32_GR', 'EXPORT_32_R', 'EXPORT_4C_16BPC', + 'EXPORT_4C_32BPC', 'EXPORT_4P_16BPC_ABGR', 'EXPORT_4P_32BPC_ABGR', + 'EXPORT_4P_32BPC_AR', 'EXPORT_4P_32BPC_GR', 'EXPORT_8P_32BPC_R', + 'EXPORT_ANY_Z', 'EXPORT_FP16_ABGR', 'EXPORT_GREATER_THAN_Z', + 'EXPORT_LESS_THAN_Z', 'EXPORT_RESERVED', 'EXPORT_SIGNED16_ABGR', + 'EXPORT_UNSIGNED16_ABGR', 'EXPORT_UNUSED', 'FAULT_FAIL', + 'FAULT_ONE', 'FAULT_PASS', 'FAULT_ZERO', + 'FBC_IDLE_MASK_DISP_REG_UPDATE', + 'FBC_IDLE_MASK_FBC_ALPHA_COMP_EN', + 'FBC_IDLE_MASK_FBC_FORCE_COPY_TO_COMP_BUF', + 'FBC_IDLE_MASK_FBC_GRPH_COMP_EN', + 'FBC_IDLE_MASK_FBC_MIN_COMPRESSION', + 'FBC_IDLE_MASK_FBC_ZERO_ALPHA_CHUNK_SKIP_EN', + 'FBC_IDLE_MASK_MASK_BITS', 'FBC_IDLE_MASK_MC_HIT_REGION_0', + 'FBC_IDLE_MASK_MC_HIT_REGION_1', 'FBC_IDLE_MASK_MC_HIT_REGION_2', + 'FBC_IDLE_MASK_MC_HIT_REGION_3', 'FBC_IDLE_MASK_MC_WRITE', + 'FBC_IDLE_MASK_RESERVED1', 'FBC_IDLE_MASK_RESERVED10', + 'FBC_IDLE_MASK_RESERVED11', 'FBC_IDLE_MASK_RESERVED12', + 'FBC_IDLE_MASK_RESERVED13', 'FBC_IDLE_MASK_RESERVED14', + 'FBC_IDLE_MASK_RESERVED15', 'FBC_IDLE_MASK_RESERVED16', + 'FBC_IDLE_MASK_RESERVED17', 'FBC_IDLE_MASK_RESERVED18', + 'FBC_IDLE_MASK_RESERVED19', 'FBC_IDLE_MASK_RESERVED20', + 'FBC_IDLE_MASK_RESERVED21', 'FBC_IDLE_MASK_RESERVED22', + 'FBC_IDLE_MASK_RESERVED23', 'FBC_IDLE_MASK_RESERVED29', + 'FBC_IDLE_MASK_RESERVED30', 'FBC_IDLE_MASK_RESERVED31', + 'FBC_IDLE_MASK_RESERVED7', 'FBC_IDLE_MASK_RESERVED8', + 'FBC_IDLE_MASK_RESERVED9', 'FLUSH_AND_INV_CB_DATA_TS', + 'FLUSH_AND_INV_CB_META', 'FLUSH_AND_INV_CB_PIXEL_DATA', + 'FLUSH_AND_INV_DB_DATA_TS', 'FLUSH_AND_INV_DB_META', + 'FLUSH_CONTROL_FLUSH_NOT_STARTED', 'FLUSH_CONTROL_FLUSH_STARTED', + 'FLUSH_DFSM', 'FLUSH_HS_OUTPUT', 'FLUSH_SX_TS', 'FMT0_SOFT_RESET', + 'FMT0_SOFT_RESET_0', 'FMT0_SOFT_RESET_1', 'FMT1_SOFT_RESET', + 'FMT1_SOFT_RESET_0', 'FMT1_SOFT_RESET_1', 'FMT2_SOFT_RESET', + 'FMT2_SOFT_RESET_0', 'FMT2_SOFT_RESET_1', 'FMT3_SOFT_RESET', + 'FMT3_SOFT_RESET_0', 'FMT3_SOFT_RESET_1', + 'FMT420_MEMORY_SOURCE_SEL', 'FMT420_MEMORY_SOURCE_SEL_FMT0', + 'FMT420_MEMORY_SOURCE_SEL_FMT1', 'FMT420_MEMORY_SOURCE_SEL_FMT2', + 'FMT420_MEMORY_SOURCE_SEL_FMT3', 'FMT420_MEMORY_SOURCE_SEL_FMT4', + 'FMT420_MEMORY_SOURCE_SEL_FMT5', + 'FMT420_MEMORY_SOURCE_SEL_FMT_RESERVED', 'FMT4_SOFT_RESET', + 'FMT4_SOFT_RESET_0', 'FMT4_SOFT_RESET_1', 'FMT5_SOFT_RESET', + 'FMT5_SOFT_RESET_0', 'FMT5_SOFT_RESET_1', 'FMT_1', + 'FMT_10_10_10_2', 'FMT_10_11_11', 'FMT_10_11_11_FLOAT', + 'FMT_11_11_10', 'FMT_11_11_10_FLOAT', 'FMT_16', 'FMT_16_16', + 'FMT_16_16_16', 'FMT_16_16_16_16', 'FMT_16_16_16_16_FLOAT', + 'FMT_16_16_16_FLOAT', 'FMT_16_16_FLOAT', 'FMT_16_FLOAT', + 'FMT_1_5_5_5', 'FMT_1_REVERSED', 'FMT_24_8', 'FMT_24_8_FLOAT', + 'FMT_2_10_10_10', 'FMT_32', 'FMT_32_32', 'FMT_32_32_32', + 'FMT_32_32_32_32', 'FMT_32_32_32_32_FLOAT', 'FMT_32_32_32_FLOAT', + 'FMT_32_32_FLOAT', 'FMT_32_AS_32_32_32_32', 'FMT_32_AS_8', + 'FMT_32_AS_8_8', 'FMT_32_FLOAT', 'FMT_3_3_2', 'FMT_4_4', + 'FMT_4_4_4_4', 'FMT_5_5_5_1', 'FMT_5_6_5', + 'FMT_5_9_9_9_SHAREDEXP', 'FMT_6_5_5', 'FMT_8', 'FMT_8_24', + 'FMT_8_24_FLOAT', 'FMT_8_8', 'FMT_8_8_8', 'FMT_8_8_8_8', + 'FMT_APC3', 'FMT_APC4', 'FMT_APC5', 'FMT_APC6', 'FMT_APC7', + 'FMT_BC1', 'FMT_BC2', 'FMT_BC3', 'FMT_BC4', 'FMT_BC5', 'FMT_BC6', + 'FMT_BC7', 'FMT_BG_RG', 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Ei', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Fi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_Gi', + 'FMT_BIT_DEPTH_CONTROL_25FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_A', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_B', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_C', + 'FMT_BIT_DEPTH_CONTROL_50FRC_SEL_D', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_E', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_F', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_G', + 'FMT_BIT_DEPTH_CONTROL_75FRC_SEL_RESERVED', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_SPATIAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_DITHER_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL2', + 'FMT_BIT_DEPTH_CONTROL_TEMPORAL_LEVEL_GREY_LEVEL4', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_18BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_24BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_DEPTH_30BPP', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_ROUNDING', + 'FMT_BIT_DEPTH_CONTROL_TRUNCATE_MODE_TRUNCATION', + 'FMT_CLAMP_CNTL_COLOR_FORMAT', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_10BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_12BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_6BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_8BPC', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_PROGRAMMABLE', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED1', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED2', + 'FMT_CLAMP_CNTL_COLOR_FORMAT_RESERVED3', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_DISABLE', + 'FMT_CONTROL_CBCR_BIT_REDUCTION_BYPASS_ENABLE', + 'FMT_CONTROL_PIXEL_ENCODING', + 'FMT_CONTROL_PIXEL_ENCODING_RESERVED', + 'FMT_CONTROL_PIXEL_ENCODING_RGB444_OR_YCBCR444', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR420', + 'FMT_CONTROL_PIXEL_ENCODING_YCBCR422', + 'FMT_CONTROL_SUBSAMPLING_MODE', + 'FMT_CONTROL_SUBSAMPLING_MODE_AVERAGE', + 'FMT_CONTROL_SUBSAMPLING_MODE_DROP', + 'FMT_CONTROL_SUBSAMPLING_MOME_3_TAP', + 'FMT_CONTROL_SUBSAMPLING_MOME_RESERVED', + 'FMT_CONTROL_SUBSAMPLING_ORDER', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CB_BEFORE_CR', + 'FMT_CONTROL_SUBSAMPLING_ORDER_CR_BEFORE_CB', + 'FMT_CRC_CNTL_CONT_EN', 'FMT_CRC_CNTL_CONT_EN_CONT', + 'FMT_CRC_CNTL_CONT_EN_ONE_SHOT', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ALL', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_ENABLE_ODD_EVEN', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_EVEN', + 'FMT_CRC_CNTL_EVEN_ODD_PIX_SELECT_ODD', + 'FMT_CRC_CNTL_INCLUDE_OVERSCAN', + 'FMT_CRC_CNTL_INCLUDE_OVERSCAN_INCLUDE', + 'FMT_CRC_CNTL_INCLUDE_OVERSCAN_NOT_INCLUDE', + 'FMT_CRC_CNTL_INTERLACE_MODE', + 'FMT_CRC_CNTL_INTERLACE_MODE_BOTH_BOTTOM', + 'FMT_CRC_CNTL_INTERLACE_MODE_BOTH_EACH', + 'FMT_CRC_CNTL_INTERLACE_MODE_BOTTOM', + 'FMT_CRC_CNTL_INTERLACE_MODE_TOP', 'FMT_CRC_CNTL_ONLY_BLANKB', + 'FMT_CRC_CNTL_ONLY_BLANKB_ENTIRE_FIELD', + 'FMT_CRC_CNTL_ONLY_BLANKB_NON_BLANK', + 'FMT_CRC_CNTL_PSR_MODE_ENABLE', + 'FMT_CRC_CNTL_PSR_MODE_ENABLE_EDP_PSR_CRC', + 'FMT_CRC_CNTL_PSR_MODE_ENABLE_NORMAL', 'FMT_CTX1', + 'FMT_DEBUG_CNTL_COLOR_SELECT', 'FMT_DEBUG_CNTL_COLOR_SELECT_BLUE', + 'FMT_DEBUG_CNTL_COLOR_SELECT_GREEN', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED1', + 'FMT_DEBUG_CNTL_COLOR_SELECT_RED2', 'FMT_DYNAMIC_EXP_MODE', + 'FMT_DYNAMIC_EXP_MODE_10to12', 'FMT_DYNAMIC_EXP_MODE_8to12', + 'FMT_GB_GR', 'FMT_INVALID', 'FMT_RESERVED_33', 'FMT_RESERVED_36', + 'FMT_RESERVED_4', 'FMT_RESERVED_63', 'FMT_SPATIAL_DITHER_MODE', + 'FMT_SPATIAL_DITHER_MODE_0', 'FMT_SPATIAL_DITHER_MODE_1', + 'FMT_SPATIAL_DITHER_MODE_2', 'FMT_SPATIAL_DITHER_MODE_3', + 'FMT_STEREOSYNC_OVR_POL', 'FMT_STEREOSYNC_OVR_POL_INVERTED', + 'FMT_STEREOSYNC_OVR_POL_NOT_INVERTED', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_BGR', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_RGB1_BGR0_RGB', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_LEGACY_HARDCODED_PATTERN', + 'FMT_TEMPORAL_DITHER_PATTERN_CONTROL_SELECT_PROGRAMMABLE_PATTERN', + 'FMT_X24_8_32_FLOAT', 'FORCE_BINNING_ON', + 'FORCE_DEEP_SLEEP_REQUEST', 'FORCE_DISABLE', 'FORCE_EARLY_Z', + 'FORCE_ENABLE', 'FORCE_LATE_Z', 'FORCE_LIGHT_SLEEP_REQ', + 'FORCE_LIGHT_SLEEP_REQUEST', 'FORCE_OFF', 'FORCE_OPT_AUTO', + 'FORCE_OPT_DISABLE', 'FORCE_OPT_ENABLE_IF_SRC_ARGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_ARGB_1', 'FORCE_OPT_ENABLE_IF_SRC_A_0', + 'FORCE_OPT_ENABLE_IF_SRC_A_1', 'FORCE_OPT_ENABLE_IF_SRC_RGB_0', + 'FORCE_OPT_ENABLE_IF_SRC_RGB_1', 'FORCE_RESERVED', 'FORCE_RE_Z', + 'FORCE_SENT', 'FORCE_SHUT_DOWN_REQUEST', 'FORCE_SUMM_BOTH', + 'FORCE_SUMM_MAXZ', 'FORCE_SUMM_MINZ', 'FORCE_SUMM_OFF', + 'FORCE_VBI', 'FORCE_VBI_HIGH', 'FORCE_VBI_LOW', 'FRAG_ALWAYS', + 'FRAG_EQUAL', 'FRAG_GEQUAL', 'FRAG_GREATER', 'FRAG_LEQUAL', + 'FRAG_LESS', 'FRAG_NEVER', 'FRAG_NOTEQUAL', 'ForceControl', + 'GAMUT_REMAP_MODE_1', 'GAMUT_REMAP_MODE_2', 'GAMUT_REMAP_MODE_3', + 'GAMUT_REMAP_MODE_BYPASS', 'GATCL1RequestType', + 'GATCL1_TYPE_BYPASS', 'GATCL1_TYPE_NORMAL', + 'GATCL1_TYPE_SHOOTDOWN', 'GB_EDC_DED_MODE', + 'GB_EDC_DED_MODE_HALT', 'GB_EDC_DED_MODE_INT_HALT', + 'GB_EDC_DED_MODE_LOG', 'GB_TILING_CONFIG_MACROTABLE_SIZE', + 'GB_TILING_CONFIG_TABLE_SIZE', 'GDS_PERFCOUNT_SELECT', + 'GDS_PERF_SEL_DS_ADDR_CONFL', 'GDS_PERF_SEL_DS_BANK_CONFL', + 'GDS_PERF_SEL_GWS_BYPASS', 'GDS_PERF_SEL_GWS_RELEASED', + 'GDS_PERF_SEL_RBUF_HIT', 'GDS_PERF_SEL_RBUF_MISS', + 'GDS_PERF_SEL_SE0_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE0_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE0_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE0_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE0_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE0_SH0_NORET', + 'GDS_PERF_SEL_SE0_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE0_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_SH0_RET', + 'GDS_PERF_SEL_SE0_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE0_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE0_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE0_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE0_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE0_SH1_NORET', + 'GDS_PERF_SEL_SE0_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE0_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_SH1_RET', + 'GDS_PERF_SEL_SE1_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE1_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE1_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE1_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE1_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE1_SH0_NORET', + 'GDS_PERF_SEL_SE1_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE1_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE1_SH0_RET', + 'GDS_PERF_SEL_SE1_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE1_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE1_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE1_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE1_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE1_SH1_NORET', + 'GDS_PERF_SEL_SE1_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE1_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE1_SH1_RET', + 'GDS_PERF_SEL_SE2_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE2_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE2_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE2_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE2_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE2_SH0_NORET', + 'GDS_PERF_SEL_SE2_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE2_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE2_SH0_RET', + 'GDS_PERF_SEL_SE2_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE2_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE2_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE2_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE2_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE2_SH1_NORET', + 'GDS_PERF_SEL_SE2_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE2_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE2_SH1_RET', + 'GDS_PERF_SEL_SE3_SH0_2COMP_REQ', + 'GDS_PERF_SEL_SE3_SH0_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE3_SH0_GDS_RD_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_REL_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE3_SH0_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE3_SH0_GDS_WR_OP', 'GDS_PERF_SEL_SE3_SH0_NORET', + 'GDS_PERF_SEL_SE3_SH0_ORD_CNT', + 'GDS_PERF_SEL_SE3_SH0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE3_SH0_RET', + 'GDS_PERF_SEL_SE3_SH1_2COMP_REQ', + 'GDS_PERF_SEL_SE3_SH1_GDS_ATOM_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_CMPXCH_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_DATA_VALID', + 'GDS_PERF_SEL_SE3_SH1_GDS_RD_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_REL_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_SHORT_OP', + 'GDS_PERF_SEL_SE3_SH1_GDS_STALL_BY_ORD', + 'GDS_PERF_SEL_SE3_SH1_GDS_WR_OP', 'GDS_PERF_SEL_SE3_SH1_NORET', + 'GDS_PERF_SEL_SE3_SH1_ORD_CNT', + 'GDS_PERF_SEL_SE3_SH1_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE3_SH1_RET', + 'GDS_PERF_SEL_WBUF_FLUSH', 'GDS_PERF_SEL_WBUF_WR', + 'GDS_PERF_SEL_WR_COMP', 'GENERICA_STEREOSYNC_SEL', + 'GENERICA_STEREOSYNC_SEL_D1', 'GENERICA_STEREOSYNC_SEL_D2', + 'GENERICA_STEREOSYNC_SEL_D3', 'GENERICA_STEREOSYNC_SEL_D4', + 'GENERICA_STEREOSYNC_SEL_D5', 'GENERICA_STEREOSYNC_SEL_D6', + 'GENERICA_STEREOSYNC_SEL_RESERVED', 'GENERICB_STEREOSYNC_SEL', + 'GENERICB_STEREOSYNC_SEL_D1', 'GENERICB_STEREOSYNC_SEL_D2', + 'GENERICB_STEREOSYNC_SEL_D3', 'GENERICB_STEREOSYNC_SEL_D4', + 'GENERICB_STEREOSYNC_SEL_D5', 'GENERICB_STEREOSYNC_SEL_D6', + 'GENERICB_STEREOSYNC_SEL_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_DISABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_CONTROL_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_ENABLE_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_NOT_SET_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_RESERVED', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET', + 'GENERIC_AZ_CONTROLLER_REGISTER_STATUS_SET_RESERVED', + 'GLOBAL_CONTROL_ACCEPT_UNSOLICITED_RESPONSE', + 'GLOBAL_CONTROL_CONTROLLER_RESET', 'GLOBAL_CONTROL_FLUSH_CONTROL', + 'GLOBAL_STATUS_FLUSH_STATUS', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_ENDED', + 'GLOBAL_STATUS_FLUSH_STATUS_FLUSH_NOT_ENDED', + 'GL__CONSTANT_ALPHA', 'GL__CONSTANT_COLOR', 'GL__DST_ALPHA', + 'GL__DST_COLOR', 'GL__ONE', 'GL__ONE_MINUS_CONSTANT_ALPHA', + 'GL__ONE_MINUS_CONSTANT_COLOR', 'GL__ONE_MINUS_DST_ALPHA', + 'GL__ONE_MINUS_DST_COLOR', 'GL__ONE_MINUS_SRC_ALPHA', + 'GL__ONE_MINUS_SRC_COLOR', 'GL__SRC_ALPHA', + 'GL__SRC_ALPHA_SATURATE', 'GL__SRC_COLOR', 'GL__ZERO', + 'GRBM_PERF_SEL', 'GRBM_PERF_SEL_BCI_BUSY', + 'GRBM_PERF_SEL_CB_BUSY', 'GRBM_PERF_SEL_CB_CLEAN', + 'GRBM_PERF_SEL_COUNT', 'GRBM_PERF_SEL_CPAXI_BUSY', + 'GRBM_PERF_SEL_CPC_BUSY', 'GRBM_PERF_SEL_CPF_BUSY', + 'GRBM_PERF_SEL_CPG_BUSY', 'GRBM_PERF_SEL_CP_BUSY', + 'GRBM_PERF_SEL_CP_COHER_BUSY', 'GRBM_PERF_SEL_CP_DMA_BUSY', + 'GRBM_PERF_SEL_DB_BUSY', 'GRBM_PERF_SEL_DB_CLEAN', + 'GRBM_PERF_SEL_EA_BUSY', 'GRBM_PERF_SEL_GDS_BUSY', + 'GRBM_PERF_SEL_GUI_ACTIVE', 'GRBM_PERF_SEL_IA_BUSY', + 'GRBM_PERF_SEL_IA_NO_DMA_BUSY', 'GRBM_PERF_SEL_PA_BUSY', + 'GRBM_PERF_SEL_RESERVED_0', 'GRBM_PERF_SEL_RESERVED_1', + 'GRBM_PERF_SEL_RESERVED_2', 'GRBM_PERF_SEL_RESERVED_3', + 'GRBM_PERF_SEL_RESERVED_4', 'GRBM_PERF_SEL_RESERVED_5', + 'GRBM_PERF_SEL_RESERVED_6', 'GRBM_PERF_SEL_RLC_BUSY', + 'GRBM_PERF_SEL_RMI_BUSY', 'GRBM_PERF_SEL_SC_BUSY', + 'GRBM_PERF_SEL_SPI_BUSY', 'GRBM_PERF_SEL_SX_BUSY', + 'GRBM_PERF_SEL_TA_BUSY', 'GRBM_PERF_SEL_TC_BUSY', + 'GRBM_PERF_SEL_USER_DEFINED', 'GRBM_PERF_SEL_UTCL2_BUSY', + 'GRBM_PERF_SEL_VGT_BUSY', 'GRBM_PERF_SEL_WD_BUSY', + 'GRBM_PERF_SEL_WD_NO_DMA_BUSY', 'GRBM_SE0_PERF_SEL', + 'GRBM_SE0_PERF_SEL_BCI_BUSY', 'GRBM_SE0_PERF_SEL_CB_BUSY', + 'GRBM_SE0_PERF_SEL_CB_CLEAN', 'GRBM_SE0_PERF_SEL_COUNT', + 'GRBM_SE0_PERF_SEL_DB_BUSY', 'GRBM_SE0_PERF_SEL_DB_CLEAN', + 'GRBM_SE0_PERF_SEL_PA_BUSY', 'GRBM_SE0_PERF_SEL_RESERVED_0', + 'GRBM_SE0_PERF_SEL_RESERVED_1', 'GRBM_SE0_PERF_SEL_RMI_BUSY', + 'GRBM_SE0_PERF_SEL_SC_BUSY', 'GRBM_SE0_PERF_SEL_SPI_BUSY', + 'GRBM_SE0_PERF_SEL_SX_BUSY', 'GRBM_SE0_PERF_SEL_TA_BUSY', + 'GRBM_SE0_PERF_SEL_USER_DEFINED', 'GRBM_SE0_PERF_SEL_VGT_BUSY', + 'GRBM_SE1_PERF_SEL', 'GRBM_SE1_PERF_SEL_BCI_BUSY', + 'GRBM_SE1_PERF_SEL_CB_BUSY', 'GRBM_SE1_PERF_SEL_CB_CLEAN', + 'GRBM_SE1_PERF_SEL_COUNT', 'GRBM_SE1_PERF_SEL_DB_BUSY', + 'GRBM_SE1_PERF_SEL_DB_CLEAN', 'GRBM_SE1_PERF_SEL_PA_BUSY', + 'GRBM_SE1_PERF_SEL_RESERVED_0', 'GRBM_SE1_PERF_SEL_RESERVED_1', + 'GRBM_SE1_PERF_SEL_RMI_BUSY', 'GRBM_SE1_PERF_SEL_SC_BUSY', + 'GRBM_SE1_PERF_SEL_SPI_BUSY', 'GRBM_SE1_PERF_SEL_SX_BUSY', + 'GRBM_SE1_PERF_SEL_TA_BUSY', 'GRBM_SE1_PERF_SEL_USER_DEFINED', + 'GRBM_SE1_PERF_SEL_VGT_BUSY', 'GRBM_SE2_PERF_SEL', + 'GRBM_SE2_PERF_SEL_BCI_BUSY', 'GRBM_SE2_PERF_SEL_CB_BUSY', + 'GRBM_SE2_PERF_SEL_CB_CLEAN', 'GRBM_SE2_PERF_SEL_COUNT', + 'GRBM_SE2_PERF_SEL_DB_BUSY', 'GRBM_SE2_PERF_SEL_DB_CLEAN', + 'GRBM_SE2_PERF_SEL_PA_BUSY', 'GRBM_SE2_PERF_SEL_RESERVED_0', + 'GRBM_SE2_PERF_SEL_RESERVED_1', 'GRBM_SE2_PERF_SEL_RMI_BUSY', + 'GRBM_SE2_PERF_SEL_SC_BUSY', 'GRBM_SE2_PERF_SEL_SPI_BUSY', + 'GRBM_SE2_PERF_SEL_SX_BUSY', 'GRBM_SE2_PERF_SEL_TA_BUSY', + 'GRBM_SE2_PERF_SEL_USER_DEFINED', 'GRBM_SE2_PERF_SEL_VGT_BUSY', + 'GRBM_SE3_PERF_SEL', 'GRBM_SE3_PERF_SEL_BCI_BUSY', + 'GRBM_SE3_PERF_SEL_CB_BUSY', 'GRBM_SE3_PERF_SEL_CB_CLEAN', + 'GRBM_SE3_PERF_SEL_COUNT', 'GRBM_SE3_PERF_SEL_DB_BUSY', + 'GRBM_SE3_PERF_SEL_DB_CLEAN', 'GRBM_SE3_PERF_SEL_PA_BUSY', + 'GRBM_SE3_PERF_SEL_RESERVED_0', 'GRBM_SE3_PERF_SEL_RESERVED_1', + 'GRBM_SE3_PERF_SEL_RMI_BUSY', 'GRBM_SE3_PERF_SEL_SC_BUSY', + 'GRBM_SE3_PERF_SEL_SPI_BUSY', 'GRBM_SE3_PERF_SEL_SX_BUSY', + 'GRBM_SE3_PERF_SEL_TA_BUSY', 'GRBM_SE3_PERF_SEL_USER_DEFINED', + 'GRBM_SE3_PERF_SEL_VGT_BUSY', 'GSTHREADID_SIZE', 'GS_CUT_1024', + 'GS_CUT_128', 'GS_CUT_256', 'GS_CUT_512', 'GS_OFF', + 'GS_SCENARIO_A', 'GS_SCENARIO_B', 'GS_SCENARIO_C', + 'GS_SCENARIO_G', 'GS_STAGE_OFF', 'GS_STAGE_ON', 'GroupInterleave', + 'HDMI_ACR_0_MULTIPLE_RESERVED', 'HDMI_ACR_1_MULTIPLE', + 'HDMI_ACR_2_MULTIPLE', 'HDMI_ACR_3_MULTIPLE_RESERVED', + 'HDMI_ACR_4_MULTIPLE', 'HDMI_ACR_5_MULTIPLE_RESERVED', + 'HDMI_ACR_6_MULTIPLE_RESERVED', 'HDMI_ACR_7_MULTIPLE_RESERVED', + 'HDMI_ACR_AUDIO_PRIORITY', 'HDMI_ACR_CONT', + 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', + 'HDMI_ACR_NOT_SEND', 'HDMI_ACR_N_MULTIPLE', + 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', + 'HDMI_ACR_PKT_SEND', 'HDMI_ACR_SELECT', 'HDMI_ACR_SELECT_32K', + 'HDMI_ACR_SELECT_44K', 'HDMI_ACR_SELECT_48K', + 'HDMI_ACR_SELECT_HW', 'HDMI_ACR_SEND', 'HDMI_ACR_SOURCE', + 'HDMI_ACR_SOURCE_HW', 'HDMI_ACR_SOURCE_SW', + 'HDMI_AUDIO_DELAY_56CLK', 'HDMI_AUDIO_DELAY_58CLK', + 'HDMI_AUDIO_DELAY_DISABLE', 'HDMI_AUDIO_DELAY_EN', + 'HDMI_AUDIO_DELAY_RESERVED', 'HDMI_AUDIO_INFO_CONT', + 'HDMI_AUDIO_INFO_CONT_DISABLE', 'HDMI_AUDIO_INFO_CONT_ENABLE', + 'HDMI_AUDIO_INFO_NOT_SEND', 'HDMI_AUDIO_INFO_PKT_SEND', + 'HDMI_AUDIO_INFO_SEND', + 'HDMI_AUDIO_SAMPLE_HIGH_PRIORITY_THAN_ACR_PKT', + 'HDMI_AUDIO_SEND_MAX_PACKETS', 'HDMI_AVI_INFO_CONT', + 'HDMI_AVI_INFO_CONT_DISABLE', 'HDMI_AVI_INFO_CONT_ENABLE', + 'HDMI_AVI_INFO_NOT_SEND', 'HDMI_AVI_INFO_PKT_SEND', + 'HDMI_AVI_INFO_SEND', + 'HDMI_CLOCK_CHANNEL_FREQ_EQUAL_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_FREQ_QUARTER_TO_CHAR_RATE', + 'HDMI_CLOCK_CHANNEL_RATE', 'HDMI_DATA_SCRAMBLE_DISABLE', + 'HDMI_DATA_SCRAMBLE_EN', 'HDMI_DATA_SCRAMBLE_ENABLE', + 'HDMI_DEEP_COLOR_DEPTH', 'HDMI_DEEP_COLOR_DEPTH_24BPP', + 'HDMI_DEEP_COLOR_DEPTH_30BPP', 'HDMI_DEEP_COLOR_DEPTH_36BPP', + 'HDMI_DEEP_COLOR_DEPTH_RESERVED', 'HDMI_DEFAULT_PAHSE', + 'HDMI_DEFAULT_PHASE_IS_0', 'HDMI_DEFAULT_PHASE_IS_1', + 'HDMI_ERROR_ACK', 'HDMI_ERROR_ACK_INT', 'HDMI_ERROR_MASK', + 'HDMI_ERROR_MASK_INT', 'HDMI_ERROR_NOT_ACK', + 'HDMI_ERROR_NOT_MASK', 'HDMI_EXTRA_NULL_PACKET_FILLED_DISABLE', + 'HDMI_EXTRA_NULL_PACKET_FILLED_ENABLE', 'HDMI_GC_AVMUTE', + 'HDMI_GC_AVMUTE_CONT', 'HDMI_GC_AVMUTE_CONT_DISABLE', + 'HDMI_GC_AVMUTE_CONT_ENABLE', 'HDMI_GC_AVMUTE_SET', + 'HDMI_GC_AVMUTE_UNSET', 'HDMI_GC_CONT', 'HDMI_GC_CONT_DISABLE', + 'HDMI_GC_CONT_ENABLE', 'HDMI_GC_NOT_SEND', 'HDMI_GC_PKT_SEND', + 'HDMI_GC_SEND', 'HDMI_GENERIC0_CONT', + 'HDMI_GENERIC0_CONT_DISABLE', 'HDMI_GENERIC0_CONT_ENABLE', + 'HDMI_GENERIC0_NOT_SEND', 'HDMI_GENERIC0_PKT_SEND', + 'HDMI_GENERIC0_SEND', 'HDMI_GENERIC1_CONT', + 'HDMI_GENERIC1_CONT_DISABLE', 'HDMI_GENERIC1_CONT_ENABLE', + 'HDMI_GENERIC1_NOT_SEND', 'HDMI_GENERIC1_PKT_SEND', + 'HDMI_GENERIC1_SEND', 'HDMI_GENERIC2_CONT', + 'HDMI_GENERIC2_CONT_DISABLE', 'HDMI_GENERIC2_CONT_ENABLE', + 'HDMI_GENERIC2_NOT_SEND', 'HDMI_GENERIC2_PKT_SEND', + 'HDMI_GENERIC2_SEND', 'HDMI_GENERIC3_CONT', + 'HDMI_GENERIC3_CONT_DISABLE', 'HDMI_GENERIC3_CONT_ENABLE', + 'HDMI_GENERIC3_NOT_SEND', 'HDMI_GENERIC3_PKT_SEND', + 'HDMI_GENERIC3_SEND', 'HDMI_ISRC_CONT', 'HDMI_ISRC_CONT_DISABLE', + 'HDMI_ISRC_CONT_ENABLE', 'HDMI_ISRC_NOT_SEND', + 'HDMI_ISRC_PKT_SEND', 'HDMI_ISRC_SEND', + 'HDMI_KEEPOUT_0_650PIX_AFTER_VSYNC', + 'HDMI_KEEPOUT_509_650PIX_AFTER_VSYNC', 'HDMI_KEEPOUT_MODE', + 'HDMI_MPEG_INFO_CONT', 'HDMI_MPEG_INFO_CONT_DISABLE', + 'HDMI_MPEG_INFO_CONT_ENABLE', 'HDMI_MPEG_INFO_NOT_SEND', + 'HDMI_MPEG_INFO_PKT_SEND', 'HDMI_MPEG_INFO_SEND', + 'HDMI_NOT_SEND_MAX_AUDIO_PACKETS', + 'HDMI_NO_EXTRA_NULL_PACKET_FILLED', 'HDMI_NULL_NOT_SEND', + 'HDMI_NULL_PKT_SEND', 'HDMI_NULL_SEND', 'HDMI_PACKET_GEN_VERSION', + 'HDMI_PACKET_GEN_VERSION_NEW', 'HDMI_PACKET_GEN_VERSION_OLD', + 'HDMI_PACKING_PHASE_OVERRIDE', 'HDMI_PACKING_PHASE_SET_BY_HW', + 'HDMI_PACKING_PHASE_SET_BY_SW', 'HDMI_SEND_MAX_AUDIO_PACKETS', + 'HPD_INT_CONTROL_ACK', 'HPD_INT_CONTROL_ACK_0', + 'HPD_INT_CONTROL_ACK_1', 'HPD_INT_CONTROL_GEN_INT_ON_CON', + 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', 'HPD_INT_CONTROL_POLARITY', + 'HPD_INT_CONTROL_RX_INT_ACK', 'HPD_INT_CONTROL_RX_INT_ACK_0', + 'HPD_INT_CONTROL_RX_INT_ACK_1', 'HS_STAGE_OFF', 'HS_STAGE_ON', + 'HW_SOURCE_SEL_DSC_JPEG', 'HW_SOURCE_SEL_DSC_VLP', + 'HW_SOURCE_SEL_DSC_VUP', 'HW_SOURCE_SEL_NONE', + 'I2S0_SPDIF0_SOFT_RESET', 'I2S0_SPDIF0_SOFT_RESET_0', + 'I2S0_SPDIF0_SOFT_RESET_1', 'I2S1_SOFT_RESET', + 'I2S1_SOFT_RESET_0', 'I2S1_SOFT_RESET_1', 'I2S_LRCLK_HIGH_LEFT', + 'I2S_LRCLK_LOW_LEFT', 'I2S_LRCLK_POLARITY', + 'I2S_SAMPLE_ALIGNMENT', 'I2S_SAMPLE_BIT_ORDER', + 'I2S_SAMPLE_BIT_ORDER_LSB', 'I2S_SAMPLE_BIT_ORDER_MSB', + 'I2S_SAMPLE_LEFT_ALIGNED', 'I2S_SAMPLE_RIGHT_ALIGNED', + 'I2S_WORD_ALIGNMENT', 'I2S_WORD_ALTERNATE_ALIGNMENT', + 'I2S_WORD_I2S_ALIGNMENT', 'I2S_WORD_SIZE', 'I2S_WORD_SIZE_16', + 'I2S_WORD_SIZE_32', 'IA_PERFCOUNT_SELECT', + 'ID_STREAM_DISABLE_ACKED', 'ID_STREAM_DISABLE_NO_ACK', + 'IH_PERF_SEL', 'IH_PERF_SEL_BIF_LINE0_FALLING', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF0', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF1', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF10', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF11', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF12', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF13', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF14', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF15', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF2', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF3', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF4', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF5', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF6', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF7', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF8', + 'IH_PERF_SEL_BIF_LINE0_FALLING_VF9', + 'IH_PERF_SEL_BIF_LINE0_RISING', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF0', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF1', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF10', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF11', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF12', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF13', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF14', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF15', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF2', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF3', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF4', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF5', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF6', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF7', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF8', + 'IH_PERF_SEL_BIF_LINE0_RISING_VF9', 'IH_PERF_SEL_BUFFER_IDLE', + 'IH_PERF_SEL_CLIENT0_INT', 'IH_PERF_SEL_CLIENT10_INT', + 'IH_PERF_SEL_CLIENT11_INT', 'IH_PERF_SEL_CLIENT12_INT', + 'IH_PERF_SEL_CLIENT13_INT', 'IH_PERF_SEL_CLIENT14_INT', + 'IH_PERF_SEL_CLIENT15_INT', 'IH_PERF_SEL_CLIENT16_INT', + 'IH_PERF_SEL_CLIENT17_INT', 'IH_PERF_SEL_CLIENT18_INT', + 'IH_PERF_SEL_CLIENT19_INT', 'IH_PERF_SEL_CLIENT1_INT', + 'IH_PERF_SEL_CLIENT20_INT', 'IH_PERF_SEL_CLIENT21_INT', + 'IH_PERF_SEL_CLIENT22_INT', 'IH_PERF_SEL_CLIENT23_INT', + 'IH_PERF_SEL_CLIENT24_INT', 'IH_PERF_SEL_CLIENT25_INT', + 'IH_PERF_SEL_CLIENT26_INT', 'IH_PERF_SEL_CLIENT27_INT', + 'IH_PERF_SEL_CLIENT28_INT', 'IH_PERF_SEL_CLIENT29_INT', + 'IH_PERF_SEL_CLIENT2_INT', 'IH_PERF_SEL_CLIENT30_INT', + 'IH_PERF_SEL_CLIENT31_INT', 'IH_PERF_SEL_CLIENT3_INT', + 'IH_PERF_SEL_CLIENT4_INT', 'IH_PERF_SEL_CLIENT5_INT', + 'IH_PERF_SEL_CLIENT6_INT', 'IH_PERF_SEL_CLIENT7_INT', + 'IH_PERF_SEL_CLIENT8_INT', 'IH_PERF_SEL_CLIENT9_INT', + 'IH_PERF_SEL_CYCLE', 'IH_PERF_SEL_IDLE', 'IH_PERF_SEL_INPUT_IDLE', + 'IH_PERF_SEL_MC_WR_CLEAN_PENDING', + 'IH_PERF_SEL_MC_WR_CLEAN_STALL', 'IH_PERF_SEL_MC_WR_COUNT', + 'IH_PERF_SEL_MC_WR_IDLE', 'IH_PERF_SEL_MC_WR_STALL', + 'IH_PERF_SEL_RB0_FULL', 'IH_PERF_SEL_RB0_FULL_VF0', + 'IH_PERF_SEL_RB0_FULL_VF1', 'IH_PERF_SEL_RB0_FULL_VF10', + 'IH_PERF_SEL_RB0_FULL_VF11', 'IH_PERF_SEL_RB0_FULL_VF12', + 'IH_PERF_SEL_RB0_FULL_VF13', 'IH_PERF_SEL_RB0_FULL_VF14', + 'IH_PERF_SEL_RB0_FULL_VF15', 'IH_PERF_SEL_RB0_FULL_VF2', + 'IH_PERF_SEL_RB0_FULL_VF3', 'IH_PERF_SEL_RB0_FULL_VF4', + 'IH_PERF_SEL_RB0_FULL_VF5', 'IH_PERF_SEL_RB0_FULL_VF6', + 'IH_PERF_SEL_RB0_FULL_VF7', 'IH_PERF_SEL_RB0_FULL_VF8', + 'IH_PERF_SEL_RB0_FULL_VF9', 'IH_PERF_SEL_RB0_OVERFLOW', + 'IH_PERF_SEL_RB0_OVERFLOW_VF0', 'IH_PERF_SEL_RB0_OVERFLOW_VF1', + 'IH_PERF_SEL_RB0_OVERFLOW_VF10', 'IH_PERF_SEL_RB0_OVERFLOW_VF11', + 'IH_PERF_SEL_RB0_OVERFLOW_VF12', 'IH_PERF_SEL_RB0_OVERFLOW_VF13', + 'IH_PERF_SEL_RB0_OVERFLOW_VF14', 'IH_PERF_SEL_RB0_OVERFLOW_VF15', + 'IH_PERF_SEL_RB0_OVERFLOW_VF2', 'IH_PERF_SEL_RB0_OVERFLOW_VF3', + 'IH_PERF_SEL_RB0_OVERFLOW_VF4', 'IH_PERF_SEL_RB0_OVERFLOW_VF5', + 'IH_PERF_SEL_RB0_OVERFLOW_VF6', 'IH_PERF_SEL_RB0_OVERFLOW_VF7', + 'IH_PERF_SEL_RB0_OVERFLOW_VF8', 'IH_PERF_SEL_RB0_OVERFLOW_VF9', + 'IH_PERF_SEL_RB0_RPTR_WRAP', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF0', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF1', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRAP', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB0_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB0_WPTR_WRITEBACK', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF0', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF1', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF10', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF11', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF12', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF13', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF14', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF15', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF2', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF3', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF4', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF5', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF6', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF7', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF8', + 'IH_PERF_SEL_RB0_WPTR_WRITEBACK_VF9', 'IH_PERF_SEL_RB1_FULL', + 'IH_PERF_SEL_RB1_FULL_VF0', 'IH_PERF_SEL_RB1_FULL_VF1', + 'IH_PERF_SEL_RB1_FULL_VF10', 'IH_PERF_SEL_RB1_FULL_VF11', + 'IH_PERF_SEL_RB1_FULL_VF12', 'IH_PERF_SEL_RB1_FULL_VF13', + 'IH_PERF_SEL_RB1_FULL_VF14', 'IH_PERF_SEL_RB1_FULL_VF15', + 'IH_PERF_SEL_RB1_FULL_VF2', 'IH_PERF_SEL_RB1_FULL_VF3', + 'IH_PERF_SEL_RB1_FULL_VF4', 'IH_PERF_SEL_RB1_FULL_VF5', + 'IH_PERF_SEL_RB1_FULL_VF6', 'IH_PERF_SEL_RB1_FULL_VF7', + 'IH_PERF_SEL_RB1_FULL_VF8', 'IH_PERF_SEL_RB1_FULL_VF9', + 'IH_PERF_SEL_RB1_OVERFLOW', 'IH_PERF_SEL_RB1_OVERFLOW_VF0', + 'IH_PERF_SEL_RB1_OVERFLOW_VF1', 'IH_PERF_SEL_RB1_OVERFLOW_VF10', + 'IH_PERF_SEL_RB1_OVERFLOW_VF11', 'IH_PERF_SEL_RB1_OVERFLOW_VF12', + 'IH_PERF_SEL_RB1_OVERFLOW_VF13', 'IH_PERF_SEL_RB1_OVERFLOW_VF14', + 'IH_PERF_SEL_RB1_OVERFLOW_VF15', 'IH_PERF_SEL_RB1_OVERFLOW_VF2', + 'IH_PERF_SEL_RB1_OVERFLOW_VF3', 'IH_PERF_SEL_RB1_OVERFLOW_VF4', + 'IH_PERF_SEL_RB1_OVERFLOW_VF5', 'IH_PERF_SEL_RB1_OVERFLOW_VF6', + 'IH_PERF_SEL_RB1_OVERFLOW_VF7', 'IH_PERF_SEL_RB1_OVERFLOW_VF8', + 'IH_PERF_SEL_RB1_OVERFLOW_VF9', 'IH_PERF_SEL_RB1_RPTR_WRAP', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF0', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF1', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB1_WPTR_WRAP', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB1_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB1_WPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_FULL', + 'IH_PERF_SEL_RB2_FULL_VF0', 'IH_PERF_SEL_RB2_FULL_VF1', + 'IH_PERF_SEL_RB2_FULL_VF10', 'IH_PERF_SEL_RB2_FULL_VF11', + 'IH_PERF_SEL_RB2_FULL_VF12', 'IH_PERF_SEL_RB2_FULL_VF13', + 'IH_PERF_SEL_RB2_FULL_VF14', 'IH_PERF_SEL_RB2_FULL_VF15', + 'IH_PERF_SEL_RB2_FULL_VF2', 'IH_PERF_SEL_RB2_FULL_VF3', + 'IH_PERF_SEL_RB2_FULL_VF4', 'IH_PERF_SEL_RB2_FULL_VF5', + 'IH_PERF_SEL_RB2_FULL_VF6', 'IH_PERF_SEL_RB2_FULL_VF7', + 'IH_PERF_SEL_RB2_FULL_VF8', 'IH_PERF_SEL_RB2_FULL_VF9', + 'IH_PERF_SEL_RB2_OVERFLOW', 'IH_PERF_SEL_RB2_OVERFLOW_VF0', + 'IH_PERF_SEL_RB2_OVERFLOW_VF1', 'IH_PERF_SEL_RB2_OVERFLOW_VF10', + 'IH_PERF_SEL_RB2_OVERFLOW_VF11', 'IH_PERF_SEL_RB2_OVERFLOW_VF12', + 'IH_PERF_SEL_RB2_OVERFLOW_VF13', 'IH_PERF_SEL_RB2_OVERFLOW_VF14', + 'IH_PERF_SEL_RB2_OVERFLOW_VF15', 'IH_PERF_SEL_RB2_OVERFLOW_VF2', + 'IH_PERF_SEL_RB2_OVERFLOW_VF3', 'IH_PERF_SEL_RB2_OVERFLOW_VF4', + 'IH_PERF_SEL_RB2_OVERFLOW_VF5', 'IH_PERF_SEL_RB2_OVERFLOW_VF6', + 'IH_PERF_SEL_RB2_OVERFLOW_VF7', 'IH_PERF_SEL_RB2_OVERFLOW_VF8', + 'IH_PERF_SEL_RB2_OVERFLOW_VF9', 'IH_PERF_SEL_RB2_RPTR_WRAP', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF0', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF1', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF15', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF3', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_RPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_RPTR_WRAP_VF9', 'IH_PERF_SEL_RB2_WPTR_WRAP', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF0', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF1', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF10', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF11', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF12', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF13', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF14', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF15', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF2', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF3', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF4', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF5', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF6', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF7', 'IH_PERF_SEL_RB2_WPTR_WRAP_VF8', + 'IH_PERF_SEL_RB2_WPTR_WRAP_VF9', 'IMG_DATA_FORMAT', + 'IMG_DATA_FORMAT_10_10_10_2', 'IMG_DATA_FORMAT_10_11_11', + 'IMG_DATA_FORMAT_11_11_10', 'IMG_DATA_FORMAT_16', + 'IMG_DATA_FORMAT_16_16', 'IMG_DATA_FORMAT_16_16_16_16', + 'IMG_DATA_FORMAT_16_AS_16_16_16_16', + 'IMG_DATA_FORMAT_16_AS_32_32', + 'IMG_DATA_FORMAT_16_AS_32_32_32_32', 'IMG_DATA_FORMAT_1_5_5_5', + 'IMG_DATA_FORMAT_24_8', 'IMG_DATA_FORMAT_2_10_10_10', + 'IMG_DATA_FORMAT_32', 'IMG_DATA_FORMAT_32_32', + 'IMG_DATA_FORMAT_32_32_32', 'IMG_DATA_FORMAT_32_32_32_32', + 'IMG_DATA_FORMAT_32_AS_32_32_32_32', 'IMG_DATA_FORMAT_4_4', + 'IMG_DATA_FORMAT_4_4_4_4', 'IMG_DATA_FORMAT_5_5_5_1', + 'IMG_DATA_FORMAT_5_6_5', 'IMG_DATA_FORMAT_5_9_9_9', + 'IMG_DATA_FORMAT_6E4', 'IMG_DATA_FORMAT_6_5_5', + 'IMG_DATA_FORMAT_8', 'IMG_DATA_FORMAT_8_24', + 'IMG_DATA_FORMAT_8_8', 'IMG_DATA_FORMAT_8_8_8_8', + 'IMG_DATA_FORMAT_8_AS_32', 'IMG_DATA_FORMAT_8_AS_32_32', + 'IMG_DATA_FORMAT_8_AS_8_8_8_8', 'IMG_DATA_FORMAT_ASTC_2D_HDR', + 'IMG_DATA_FORMAT_ASTC_2D_LDR', 'IMG_DATA_FORMAT_ASTC_2D_LDR_SRGB', + 'IMG_DATA_FORMAT_ASTC_3D_HDR', 'IMG_DATA_FORMAT_ASTC_3D_LDR', + 'IMG_DATA_FORMAT_ASTC_3D_LDR_SRGB', 'IMG_DATA_FORMAT_BC1', + 'IMG_DATA_FORMAT_BC2', 'IMG_DATA_FORMAT_BC3', + 'IMG_DATA_FORMAT_BC4', 'IMG_DATA_FORMAT_BC5', + 'IMG_DATA_FORMAT_BC6', 'IMG_DATA_FORMAT_BC7', + 'IMG_DATA_FORMAT_BG_RG', 'IMG_DATA_FORMAT_ETC2_R', + 'IMG_DATA_FORMAT_ETC2_RG', 'IMG_DATA_FORMAT_ETC2_RGB', + 'IMG_DATA_FORMAT_ETC2_RGBA', 'IMG_DATA_FORMAT_ETC2_RGBA1', + 'IMG_DATA_FORMAT_FMASK', 'IMG_DATA_FORMAT_GB_GR', + 'IMG_DATA_FORMAT_INVALID', 'IMG_DATA_FORMAT_N_IN_16', + 'IMG_DATA_FORMAT_N_IN_16_16', 'IMG_DATA_FORMAT_N_IN_16_16_16_16', + 'IMG_DATA_FORMAT_N_IN_16_AS_16_16_16_16', + 'IMG_DATA_FORMAT_RESERVED_15', 'IMG_DATA_FORMAT_RESERVED_29', + 'IMG_DATA_FORMAT_RESERVED_30', 'IMG_DATA_FORMAT_RESERVED_56', + 'IMG_DATA_FORMAT_RESERVED_59', 'IMG_DATA_FORMAT_RESERVED_60', + 'IMG_DATA_FORMAT_X24_8_32', 'IMG_NUM_FORMAT', + 'IMG_NUM_FORMAT_ASTC_2D', 'IMG_NUM_FORMAT_ASTC_2D_10x10', + 'IMG_NUM_FORMAT_ASTC_2D_10x5', 'IMG_NUM_FORMAT_ASTC_2D_10x6', + 'IMG_NUM_FORMAT_ASTC_2D_10x8', 'IMG_NUM_FORMAT_ASTC_2D_12x10', + 'IMG_NUM_FORMAT_ASTC_2D_12x12', 'IMG_NUM_FORMAT_ASTC_2D_4x4', + 'IMG_NUM_FORMAT_ASTC_2D_5x4', 'IMG_NUM_FORMAT_ASTC_2D_5x5', + 'IMG_NUM_FORMAT_ASTC_2D_6x5', 'IMG_NUM_FORMAT_ASTC_2D_6x6', + 'IMG_NUM_FORMAT_ASTC_2D_8x5', 'IMG_NUM_FORMAT_ASTC_2D_8x6', + 'IMG_NUM_FORMAT_ASTC_2D_8x8', + 'IMG_NUM_FORMAT_ASTC_2D_RESERVED_14', + 'IMG_NUM_FORMAT_ASTC_2D_RESERVED_15', 'IMG_NUM_FORMAT_ASTC_3D', + 'IMG_NUM_FORMAT_ASTC_3D_3x3x3', 'IMG_NUM_FORMAT_ASTC_3D_4x3x3', + 'IMG_NUM_FORMAT_ASTC_3D_4x4x3', 'IMG_NUM_FORMAT_ASTC_3D_4x4x4', + 'IMG_NUM_FORMAT_ASTC_3D_5x4x4', 'IMG_NUM_FORMAT_ASTC_3D_5x5x4', + 'IMG_NUM_FORMAT_ASTC_3D_5x5x5', 'IMG_NUM_FORMAT_ASTC_3D_6x5x5', + 'IMG_NUM_FORMAT_ASTC_3D_6x6x5', 'IMG_NUM_FORMAT_ASTC_3D_6x6x6', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_10', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_11', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_12', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_13', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_14', + 'IMG_NUM_FORMAT_ASTC_3D_RESERVED_15', 'IMG_NUM_FORMAT_FLOAT', + 'IMG_NUM_FORMAT_FMASK', 'IMG_NUM_FORMAT_FMASK_16_16_1', + 'IMG_NUM_FORMAT_FMASK_16_8_2', 'IMG_NUM_FORMAT_FMASK_32_16_2', + 'IMG_NUM_FORMAT_FMASK_32_8_4', 'IMG_NUM_FORMAT_FMASK_32_8_8', + 'IMG_NUM_FORMAT_FMASK_64_16_4', 'IMG_NUM_FORMAT_FMASK_64_16_8', + 'IMG_NUM_FORMAT_FMASK_8_2_1', 'IMG_NUM_FORMAT_FMASK_8_2_2', + 'IMG_NUM_FORMAT_FMASK_8_4_1', 'IMG_NUM_FORMAT_FMASK_8_4_2', + 'IMG_NUM_FORMAT_FMASK_8_4_4', 'IMG_NUM_FORMAT_FMASK_8_8_1', + 'IMG_NUM_FORMAT_FMASK_RESERVED_13', + 'IMG_NUM_FORMAT_FMASK_RESERVED_14', + 'IMG_NUM_FORMAT_FMASK_RESERVED_15', 'IMG_NUM_FORMAT_N_IN_16', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_0', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_10', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_11', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_12', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_13', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_14', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_15', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_3', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_6', + 'IMG_NUM_FORMAT_N_IN_16_RESERVED_9', + 'IMG_NUM_FORMAT_N_IN_16_UINT_10', 'IMG_NUM_FORMAT_N_IN_16_UINT_9', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_10', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_9', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_10', + 'IMG_NUM_FORMAT_N_IN_16_UNORM_UINT_9', + 'IMG_NUM_FORMAT_RESERVED_10', 'IMG_NUM_FORMAT_RESERVED_11', + 'IMG_NUM_FORMAT_RESERVED_12', 'IMG_NUM_FORMAT_RESERVED_13', + 'IMG_NUM_FORMAT_RESERVED_14', 'IMG_NUM_FORMAT_RESERVED_15', + 'IMG_NUM_FORMAT_RESERVED_8', 'IMG_NUM_FORMAT_SINT', + 'IMG_NUM_FORMAT_SNORM', 'IMG_NUM_FORMAT_SRGB', + 'IMG_NUM_FORMAT_SSCALED', 'IMG_NUM_FORMAT_UINT', + 'IMG_NUM_FORMAT_UNORM', 'IMG_NUM_FORMAT_UNORM_UINT', + 'IMG_NUM_FORMAT_USCALED', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_IS_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_COMMAND_NOT_BUSY', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_IMMEDIATE_RESPONSE_VALID', + 'IMMEDIATE_COMMAND_STATUS_IMMEDIATE_RESULT_VALID_NO_IMMEDIATE_RESPONSE_VALID', + 'INGAMMA_MODE_BYPASS', 'INGAMMA_MODE_FIX', 'INGAMMA_MODE_FLOAT', + 'INPUTCSC_MODE_A', 'INPUTCSC_MODE_B', 'INPUTCSC_MODE_BYPASS', + 'INPUTCSC_MODE_UNITY', 'INPUTCSC_ROUND', 'INPUTCSC_TRUNCATE', + 'INPUTCSC_TYPE_10_2', 'INPUTCSC_TYPE_12_0', 'INPUTCSC_TYPE_8_4', + 'INPUT_COVERAGE', 'INPUT_DEPTH_COVERAGE', 'INPUT_INNER_COVERAGE', + 'INST_ID_ECC_INTERRUPT_MSG', 'INST_ID_HOST_REG_TRAP_MSG', + 'INST_ID_HW_TRAP', 'INST_ID_KILL_SEQ', 'INST_ID_PRIV_START', + 'INST_ID_SPI_WREXEC', 'INST_ID_TTRACE_NEW_PC_MSG', + 'INTERLACE_SOURCE_INTERLEAVE', 'INTERLACE_SOURCE_PROGRESSIVE', + 'INTERLACE_SOURCE_STACK', 'INTERLEAVE_DIS', 'INTERLEAVE_EN', + 'IQ_DEQUEUE_RETRY', 'IQ_INTR_TYPE_IB', 'IQ_INTR_TYPE_MQD', + 'IQ_INTR_TYPE_PQ', 'IQ_OFFLOAD_RETRY', 'IQ_QUEUE_SLEEP', + 'IQ_SCH_WAVE_MSG', 'IQ_SEM_REARM', 'JITTER_REMOVE_DISABLE', + 'LATE_Z', 'LBV_DITHER_EN', 'LBV_DOWNSCALE_PREFETCH_EN', + 'LBV_DYNAMIC_PIXEL_DEPTH', 'LBV_INTERLEAVE_EN', + 'LBV_MEMORY_CONFIG', 'LBV_PIXEL_DEPTH', 'LBV_PIXEL_EXPAN_MODE', + 'LBV_PIXEL_REDUCE_MODE', 'LBV_SYNC_DURATION', + 'LBV_SYNC_RESET_SEL2', 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_ACK', + 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_NORMAL', + 'LB_BUFFER_STATUS_LB_BUFFER_EMPTY_RESET', + 'LB_BUFFER_STATUS_LB_BUFFER_FULL_ACK', + 'LB_BUFFER_STATUS_LB_BUFFER_FULL_NORMAL', + 'LB_BUFFER_STATUS_LB_BUFFER_FULL_RESET', + 'LB_DATA_FORMAT_ALPHA_DISABLE', 'LB_DATA_FORMAT_ALPHA_EN', + 'LB_DATA_FORMAT_ALPHA_ENABLE', + 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH', + 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_30BPP', + 'LB_DATA_FORMAT_DYNAMIC_PIXEL_DEPTH_36BPP', + 'LB_DATA_FORMAT_INTERLEAVE_DISABLE', + 'LB_DATA_FORMAT_INTERLEAVE_EN', + 'LB_DATA_FORMAT_INTERLEAVE_ENABLE', 'LB_DATA_FORMAT_PIXEL_DEPTH', + 'LB_DATA_FORMAT_PIXEL_DEPTH_18BPP', + 'LB_DATA_FORMAT_PIXEL_DEPTH_24BPP', + 'LB_DATA_FORMAT_PIXEL_DEPTH_30BPP', + 'LB_DATA_FORMAT_PIXEL_DEPTH_36BPP', + 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE', + 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE_DYNAMIC_PIXEL_EXPANSION', + 'LB_DATA_FORMAT_PIXEL_EXPAN_MODE_ZERO_PIXEL_EXPANSION', + 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE', + 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE_ROUNDING', + 'LB_DATA_FORMAT_PIXEL_REDUCE_MODE_TRUNCATION', + 'LB_DATA_FORMAT_REQUEST_MODE', + 'LB_DATA_FORMAT_REQUEST_MODE_NORMAL', + 'LB_DATA_FORMAT_REQUEST_MODE_START_OF_LINE', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ONE', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ONE', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_TO_ZERO', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_FORCE_ZERO', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ONE', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_NO_FORCE_ZERO', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED0', + 'LB_DC_MVP_LB_CONTROL_DC_MVP_SWAP_LOCK_OUT_SEL_NOT_USED1', + 'LB_DC_MVP_LB_CONTROL_MVP_SWAP_LOCK_IN_MODE', + 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_DISABLE', + 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_ENABLE', + 'LB_INTERRUPT_MASK_VBLANK_INTERRUPT_MASK', + 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_DISABLE', + 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_ENABLE', + 'LB_INTERRUPT_MASK_VLINE2_INTERRUPT_MASK', + 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_DISABLE', + 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_ENABLE', + 'LB_INTERRUPT_MASK_VLINE_INTERRUPT_MASK', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_DISABLE', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_EN', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_ENABLE', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_DISABLE', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REPLACEMENT_ENABLE', + 'LB_KEYER_COLOR_CTRL_LB_KEYER_COLOR_REP_EN', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_NORMAL', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED0', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACK_NOT_USED1', + 'LB_MVP_AFR_FLIP_FIFO_CNTL_MVP_AFR_FLIP_FIFO_RESET_ACTIVE', + 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE', + 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_DUMMY_FLIP', + 'LB_MVP_AFR_FLIP_MODE_MVP_AFR_FLIP_MODE_REAL_FLIP', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_DISABLE', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_EN', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_AUTO_ENABLE', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_DEBUG', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_HSYNC_MODE', + 'LB_MVP_FLIP_LINE_NUM_INSERT_MVP_FLIP_LINE_NUM_INSERT_MODE_NO_INSERT', + 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION', + 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_128_CLOCKS', + 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_16_CLOCKS', + 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_32_CLOCKS', + 'LB_SYNC_RESET_SEL_LB_SYNC_DURATION_64_CLOCKS', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VBLANK', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL2_USE_VSYNC', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_DISABLE', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_POWERDOWN_RESET', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK', + 'LB_SYNC_RESET_SEL_LB_SYNC_RESET_SEL_FROM_VSYNC_VBLANK_POWERDOWN_RESET', + 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN', + 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED0', + 'LB_TEST_DEBUG_INDEX_LB_TEST_DEBUG_WRITE_EN_NOT_USED1', + 'LB_VBLANK_STATUS_VBLANK_ACK', 'LB_VBLANK_STATUS_VBLANK_CLEAR', + 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE', + 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_LEVEL_BASED', + 'LB_VBLANK_STATUS_VBLANK_INTERRUPT_TYPE_PULSE_BASED', + 'LB_VBLANK_STATUS_VBLANK_NORMAL', + 'LB_VLINE2_START_END_VLINE2_INV', + 'LB_VLINE2_START_END_VLINE2_INVERSE', + 'LB_VLINE2_START_END_VLINE2_NORMAL', + 'LB_VLINE2_STATUS_VLINE2_ACK', 'LB_VLINE2_STATUS_VLINE2_CLEAR', + 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE', + 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_LEVEL_BASED', + 'LB_VLINE2_STATUS_VLINE2_INTERRUPT_TYPE_PULSE_BASED', + 'LB_VLINE2_STATUS_VLINE2_NORMAL', 'LB_VLINE_START_END_VLINE_INV', + 'LB_VLINE_START_END_VLINE_INVERSE', + 'LB_VLINE_START_END_VLINE_NORMAL', 'LB_VLINE_STATUS_VLINE_ACK', + 'LB_VLINE_STATUS_VLINE_CLEAR', + 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE', + 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_LEVEL_BASED', + 'LB_VLINE_STATUS_VLINE_INTERRUPT_TYPE_PULSE_BASED', + 'LB_VLINE_STATUS_VLINE_NORMAL', 'LINESTRIP', + 'LPT_NUM_BANKS_16BANK', 'LPT_NUM_BANKS_2BANK', + 'LPT_NUM_BANKS_32BANK', 'LPT_NUM_BANKS_4BANK', + 'LPT_NUM_BANKS_8BANK', 'LPT_NUM_PIPES_1CH', 'LPT_NUM_PIPES_2CH', + 'LPT_NUM_PIPES_4CH', 'LPT_NUM_PIPES_8CH', 'LS_STAGE_OFF', + 'LS_STAGE_ON', 'LVTMA_RANDOM_PATTERN_SEED_ALL_PIXELS', + 'LVTMA_RANDOM_PATTERN_SEED_ONLY_DE_HIGH', + 'LVTMA_RANDOM_PATTERN_SEED_RAN_PAT', 'LptNumBanks', 'LptNumPipes', + 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_GSL_CONTROL_MASTER_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_MASTER_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_FALSE', + 'MASTER_UPDATE_LOCK_UNDERFLOW_UPDATE_LOCK_TRUE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTH', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_EVEN', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_ODD', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BEFORE', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_BETWEEN', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_HSYNCA', + 'MASTER_UPDATE_MODE_MASTER_UPDATE_MODE_VSYNCA', 'MEMORY_CONFIG_0', + 'MEMORY_CONFIG_1', 'MEMORY_CONFIG_2', 'MEMORY_CONFIG_3', + 'MEM_ARB_MODE_AGE', 'MEM_ARB_MODE_BOTH', 'MEM_ARB_MODE_FIXED', + 'MEM_ARB_MODE_WEIGHT', 'MEM_PWR_DIS_CTRL', 'MEM_PWR_FORCE_CTRL', + 'MEM_PWR_FORCE_CTRL2', 'MEM_PWR_SEL_CTRL', 'MEM_PWR_SEL_CTRL2', + 'ME_ID0', 'ME_ID1', 'ME_ID2', 'ME_ID3', + 'MICROSECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK', + 'MICROSECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MICROSECOND_TIME_BASE_CLOCK_SOURCE_SEL', + 'MICRO_TILE_MODE_DISPLAY_2D', 'MICRO_TILE_MODE_DISPLAY_3D', + 'MICRO_TILE_MODE_LINEAR', 'MICRO_TILE_MODE_ROTATED', + 'MICRO_TILE_MODE_STD_2D', 'MICRO_TILE_MODE_STD_3D', + 'MICRO_TILE_MODE_Z_2D', 'MICRO_TILE_MODE_Z_3D', + 'MILLISECOND_TIME_BASE_CLOCK_IS_PPLL_REFCLK', + 'MILLISECOND_TIME_BASE_CLOCK_IS_XTALIN', + 'MILLISECOND_TIME_BASE_CLOCK_SOURCE_SEL', + 'MSA_MISC0_OVERRIDE_DISABLE', 'MSA_MISC0_OVERRIDE_ENABLE', + 'MSA_MISC1_BIT7_OVERRIDE_DISABLE', + 'MSA_MISC1_BIT7_OVERRIDE_ENABLE', + 'MSA_V_TIMING_OVERRIDE_DISABLED', 'MSA_V_TIMING_OVERRIDE_ENABLED', + 'MTYPE', 'MTYPE_CC', 'MTYPE_NC', 'MTYPE_RW', 'MTYPE_UC', + 'MTYPE_WC', 'MULT_16', 'MULT_8', 'MVP_CLK_SRC_SEL', + 'MVP_CLK_SRC_SEL_IO_1', 'MVP_CLK_SRC_SEL_IO_2', + 'MVP_CLK_SRC_SEL_REFCLK', 'MVP_CLK_SRC_SEL_RSRV', + 'MVP_SOFT_RESET', 'MVP_SOFT_RESET_0', 'MVP_SOFT_RESET_1', + 'MacroTileAspect', 'MemArbMode', 'MicroTileMode', + 'MultiGPUTileSize', 'NOT_SENT', 'NO_DIST', 'NO_FORCE', + 'NO_FORCE_REQ', 'NO_FORCE_REQUEST', 'NUMBER_FLOAT', 'NUMBER_SINT', + 'NUMBER_SNORM', 'NUMBER_SRGB', 'NUMBER_SSCALED', 'NUMBER_UINT', + 'NUMBER_UNORM', 'NUMBER_USCALED', 'NUM_SIMD_PER_CU', + 'NonDispTilingOrder', 'NumBanks', 'NumBanksConfig', 'NumGPUs', + 'NumLowerPipes', 'NumMaxCompressedFragments', 'NumPipes', + 'NumRbPerShaderEngine', 'NumShaderEngines', 'OFFCHIP_HS_DEALLOC', + 'OFF_SEQ', 'ON_SEQ', 'OPT_COMB_ADD', 'OPT_COMB_BLEND_DISABLED', + 'OPT_COMB_MAX', 'OPT_COMB_MIN', 'OPT_COMB_NONE', + 'OPT_COMB_REVSUBTRACT', 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', + 'OUTPUT_LINE', 'OUTPUT_POINT', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_BUFFER_COMPLETION_INTERRUPT_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_DESCRIPTOR_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_NOT_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_FIFO_ERROR_STATUS_SET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_DISABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_INTERRUPT_ON_COMPLETION_ENABLE_INTERRUPT_ENABLED', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_NO_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_DO_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_IS_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_NOT_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RESET', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_STREAM_RUN', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_CONTROL_AND_STATUS_YES_TRAFFIC_PRIORITY', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_16', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_20', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_24', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_32_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_BITS_PER_SAMPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_10_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_11_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_12_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_13_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_14_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_15_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_16_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_5', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_6', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_7', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_8', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_NUMBER_OF_CHANNELS_9_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY2_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY3', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY4_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY5_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY6_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY7_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_DIVISOR_BY8_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY1', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY2', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY3_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_BY4', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_MULTIPLE_RESERVED', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_44P1KHZ', + 'OUTPUT_STREAM_DESCRIPTOR_FORMAT_SAMPLE_BASE_RATE_48KHZ', + 'OUTPUT_TRIANGLE_CCW', 'OUTPUT_TRIANGLE_CW', + 'OVERRIDE_CGTT_DCEFCLK', 'OVERRIDE_CGTT_DCEFCLK_NOOP', + 'OVERRIDE_CGTT_SCLK', 'OVERRIDE_CGTT_SCLK_NOOP', 'PART_FRAC_EVEN', + 'PART_FRAC_ODD', 'PART_INTEGER', 'PART_POW2', 'PATCHES', + 'PERFCOUNTER_ACTIVE', 'PERFCOUNTER_CNT0_STATE', + 'PERFCOUNTER_CNT0_STATE_FREEZE', 'PERFCOUNTER_CNT0_STATE_HW', + 'PERFCOUNTER_CNT0_STATE_RESET', 'PERFCOUNTER_CNT0_STATE_START', + 'PERFCOUNTER_CNT1_STATE', 'PERFCOUNTER_CNT1_STATE_FREEZE', + 'PERFCOUNTER_CNT1_STATE_HW', 'PERFCOUNTER_CNT1_STATE_RESET', + 'PERFCOUNTER_CNT1_STATE_START', 'PERFCOUNTER_CNT2_STATE', + 'PERFCOUNTER_CNT2_STATE_FREEZE', 'PERFCOUNTER_CNT2_STATE_HW', + 'PERFCOUNTER_CNT2_STATE_RESET', 'PERFCOUNTER_CNT2_STATE_START', + 'PERFCOUNTER_CNT3_STATE', 'PERFCOUNTER_CNT3_STATE_FREEZE', + 'PERFCOUNTER_CNT3_STATE_HW', 'PERFCOUNTER_CNT3_STATE_RESET', + 'PERFCOUNTER_CNT3_STATE_START', 'PERFCOUNTER_CNT4_STATE', + 'PERFCOUNTER_CNT4_STATE_FREEZE', 'PERFCOUNTER_CNT4_STATE_HW', + 'PERFCOUNTER_CNT4_STATE_RESET', 'PERFCOUNTER_CNT4_STATE_START', + 'PERFCOUNTER_CNT5_STATE', 'PERFCOUNTER_CNT5_STATE_FREEZE', + 'PERFCOUNTER_CNT5_STATE_HW', 'PERFCOUNTER_CNT5_STATE_RESET', + 'PERFCOUNTER_CNT5_STATE_START', 'PERFCOUNTER_CNT6_STATE', + 'PERFCOUNTER_CNT6_STATE_FREEZE', 'PERFCOUNTER_CNT6_STATE_HW', + 'PERFCOUNTER_CNT6_STATE_RESET', 'PERFCOUNTER_CNT6_STATE_START', + 'PERFCOUNTER_CNT7_STATE', 'PERFCOUNTER_CNT7_STATE_FREEZE', + 'PERFCOUNTER_CNT7_STATE_HW', 'PERFCOUNTER_CNT7_STATE_RESET', + 'PERFCOUNTER_CNT7_STATE_START', 'PERFCOUNTER_CNTL_SEL', + 'PERFCOUNTER_CNTL_SEL_0', 'PERFCOUNTER_CNTL_SEL_1', + 'PERFCOUNTER_CNTL_SEL_2', 'PERFCOUNTER_CNTL_SEL_3', + 'PERFCOUNTER_CNTL_SEL_4', 'PERFCOUNTER_CNTL_SEL_5', + 'PERFCOUNTER_CNTL_SEL_6', 'PERFCOUNTER_CNTL_SEL_7', + 'PERFCOUNTER_CNTOFF_START_DIS', + 'PERFCOUNTER_CNTOFF_START_DISABLE', + 'PERFCOUNTER_CNTOFF_START_ENABLE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_ACC', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MAX', + 'PERFCOUNTER_COUNTED_VALUE_TYPE_MIN', 'PERFCOUNTER_CVALUE_SEL', + 'PERFCOUNTER_CVALUE_SEL_11_0', 'PERFCOUNTER_CVALUE_SEL_15_0', + 'PERFCOUNTER_CVALUE_SEL_23_12', 'PERFCOUNTER_CVALUE_SEL_31_16', + 'PERFCOUNTER_CVALUE_SEL_35_24', 'PERFCOUNTER_CVALUE_SEL_47_0', + 'PERFCOUNTER_CVALUE_SEL_47_32', 'PERFCOUNTER_CVALUE_SEL_47_36', + 'PERFCOUNTER_HW_CNTL_SEL', 'PERFCOUNTER_HW_CNTL_SEL_CNTOFF', + 'PERFCOUNTER_HW_CNTL_SEL_RUNEN', 'PERFCOUNTER_INC_MODE', + 'PERFCOUNTER_INC_MODE_BOTH_EDGE', 'PERFCOUNTER_INC_MODE_LSB', + 'PERFCOUNTER_INC_MODE_MULTI_BIT', 'PERFCOUNTER_INC_MODE_NEG_EDGE', + 'PERFCOUNTER_INC_MODE_POS_EDGE', 'PERFCOUNTER_INT_DISABLE', + 'PERFCOUNTER_INT_EN', 'PERFCOUNTER_INT_ENABLE', + 'PERFCOUNTER_INT_TYPE', 'PERFCOUNTER_INT_TYPE_LEVEL', + 'PERFCOUNTER_INT_TYPE_PULSE', 'PERFCOUNTER_IS_ACTIVE', + 'PERFCOUNTER_IS_IDLE', 'PERFCOUNTER_OFF_MASK', + 'PERFCOUNTER_OFF_MASK_DISABLE', 'PERFCOUNTER_OFF_MASK_ENABLE', + 'PERFCOUNTER_RESTART_DISABLE', 'PERFCOUNTER_RESTART_EN', + 'PERFCOUNTER_RESTART_ENABLE', 'PERFCOUNTER_RUNEN_MODE', + 'PERFCOUNTER_RUNEN_MODE_EDGE', 'PERFCOUNTER_RUNEN_MODE_LEVEL', + 'PERFCOUNTER_SAMPLE', 'PERFCOUNTER_START', + 'PERFCOUNTER_STATE_SEL0', 'PERFCOUNTER_STATE_SEL0_GLOBAL', + 'PERFCOUNTER_STATE_SEL0_LOCAL', 'PERFCOUNTER_STATE_SEL1', + 'PERFCOUNTER_STATE_SEL1_GLOBAL', 'PERFCOUNTER_STATE_SEL1_LOCAL', + 'PERFCOUNTER_STATE_SEL2', 'PERFCOUNTER_STATE_SEL2_GLOBAL', + 'PERFCOUNTER_STATE_SEL2_LOCAL', 'PERFCOUNTER_STATE_SEL3', + 'PERFCOUNTER_STATE_SEL3_GLOBAL', 'PERFCOUNTER_STATE_SEL3_LOCAL', + 'PERFCOUNTER_STATE_SEL4', 'PERFCOUNTER_STATE_SEL4_GLOBAL', + 'PERFCOUNTER_STATE_SEL4_LOCAL', 'PERFCOUNTER_STATE_SEL5', + 'PERFCOUNTER_STATE_SEL5_GLOBAL', 'PERFCOUNTER_STATE_SEL5_LOCAL', + 'PERFCOUNTER_STATE_SEL6', 'PERFCOUNTER_STATE_SEL6_GLOBAL', + 'PERFCOUNTER_STATE_SEL6_LOCAL', 'PERFCOUNTER_STATE_SEL7', + 'PERFCOUNTER_STATE_SEL7_GLOBAL', 'PERFCOUNTER_STATE_SEL7_LOCAL', + 'PERFCOUNTER_STOP', 'PERFMON_CNTOFF_AND', 'PERFMON_CNTOFF_AND_OR', + 'PERFMON_CNTOFF_INT_DISABLE', 'PERFMON_CNTOFF_INT_EN', + 'PERFMON_CNTOFF_INT_ENABLE', 'PERFMON_CNTOFF_INT_TYPE', + 'PERFMON_CNTOFF_INT_TYPE_LEVEL', 'PERFMON_CNTOFF_INT_TYPE_PULSE', + 'PERFMON_CNTOFF_OR', 'PERFMON_COUNTER_MODE', + 'PERFMON_COUNTER_MODE_ACCUM', + 'PERFMON_COUNTER_MODE_ACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_CYCLES_EQ_HI', + 'PERFMON_COUNTER_MODE_CYCLES_GE_HI', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_FIRST_EVENT', + 'PERFMON_COUNTER_MODE_CYCLES_SINCE_LAST_EVENT', + 'PERFMON_COUNTER_MODE_DIRTY', + 'PERFMON_COUNTER_MODE_INACTIVE_CYCLES', + 'PERFMON_COUNTER_MODE_MAX', 'PERFMON_COUNTER_MODE_RESERVED', + 'PERFMON_COUNTER_MODE_SAMPLE', 'PERFMON_SPM_MODE', + 'PERFMON_SPM_MODE_16BIT_CLAMP', 'PERFMON_SPM_MODE_16BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_32BIT_CLAMP', 'PERFMON_SPM_MODE_32BIT_NO_CLAMP', + 'PERFMON_SPM_MODE_OFF', 'PERFMON_SPM_MODE_RESERVED_5', + 'PERFMON_SPM_MODE_RESERVED_6', 'PERFMON_SPM_MODE_RESERVED_7', + 'PERFMON_SPM_MODE_TEST_MODE_0', 'PERFMON_SPM_MODE_TEST_MODE_1', + 'PERFMON_SPM_MODE_TEST_MODE_2', 'PERFMON_STATE', + 'PERFMON_STATE_FREEZE', 'PERFMON_STATE_HW', 'PERFMON_STATE_RESET', + 'PERFMON_STATE_START', 'PERF_PAPC_CCGSM_BUSY', + 'PERF_PAPC_CCGSM_IDLE', 'PERF_PAPC_CCGSM_STALLED', + 'PERF_PAPC_CLIPGA_BUSY', 'PERF_PAPC_CLIPGA_IDLE', + 'PERF_PAPC_CLIPGA_STALLED', 'PERF_PAPC_CLIPGA_STARVED_VTE_CLIP', + 'PERF_PAPC_CLIPGA_VTE_KILL_PRIM', 'PERF_PAPC_CLIPSM_BUSY', + 'PERF_PAPC_CLIPSM_IDLE', 'PERF_PAPC_CLIPSM_WAIT_AVAIL_VTE_CLIP', + 'PERF_PAPC_CLIPSM_WAIT_CLIPGA', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_OUTSM', + 'PERF_PAPC_CLIPSM_WAIT_CLIP_VERT_ENGH', + 'PERF_PAPC_CLIPSM_WAIT_HIGH_PRI_SEQ', 'PERF_PAPC_CLIP_BUSY', + 'PERF_PAPC_CLIP_IDLE', 'PERF_PAPC_CLPRIM_BUSY', + 'PERF_PAPC_CLPRIM_IDLE', 'PERF_PAPC_CLPRIM_STALLED', + 'PERF_PAPC_CLPRIM_STARVED_CCGSM', + 'PERF_PAPC_CLPR_CLIP_PLANE_BOTTOM', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_1', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_2', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_3', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_4', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_5_8', + 'PERF_PAPC_CLPR_CLIP_PLANE_CNT_9_12', + 'PERF_PAPC_CLPR_CLIP_PLANE_FAR', 'PERF_PAPC_CLPR_CLIP_PLANE_LEFT', + 'PERF_PAPC_CLPR_CLIP_PLANE_NEAR', + 'PERF_PAPC_CLPR_CLIP_PLANE_RIGHT', + 'PERF_PAPC_CLPR_CLIP_PLANE_TOP', 'PERF_PAPC_CLPR_CULL_PRIM', + 'PERF_PAPC_CLPR_CULL_TO_NULL_PRIM', + 'PERF_PAPC_CLPR_GSC_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_POINT_CLIP_CANDIDATE', + 'PERF_PAPC_CLPR_RASTER_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_UCP_CLIP_PRIM', 'PERF_PAPC_CLPR_UCP_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_KILL_CULL_PRIM', + 'PERF_PAPC_CLPR_VTX_NAN_CULL_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CLIP_PRIM', + 'PERF_PAPC_CLPR_VVUCP_CULL_PRIM', 'PERF_PAPC_CLPR_VV_CLIP_PRIM', + 'PERF_PAPC_CLPR_VV_CULL_PRIM', 'PERF_PAPC_CLSM_CLIPPING_PRIM', + 'PERF_PAPC_CLSM_CULL_TO_NULL_PRIM', 'PERF_PAPC_CLSM_NULL_PRIM', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_1', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_2', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_3', 'PERF_PAPC_CLSM_OUT_PRIM_CNT_4', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_5_8', + 'PERF_PAPC_CLSM_OUT_PRIM_CNT_9_13', + 'PERF_PAPC_CLSM_TOTALLY_VISIBLE_PRIM', + 'PERF_PAPC_CL_DYN_SCLK_VLD', 'PERF_PAPC_PASX_DISABLE_PIPE', + 'PERF_PAPC_PASX_FIRST_DEAD', 'PERF_PAPC_PASX_FIRST_VECTOR', + 'PERF_PAPC_PASX_REC_BUSY', 'PERF_PAPC_PASX_REC_IDLE', + 'PERF_PAPC_PASX_REC_STALLED', + 'PERF_PAPC_PASX_REC_STALLED_CCGSM_IN', + 'PERF_PAPC_PASX_REC_STALLED_POS_MEM', + 'PERF_PAPC_PASX_REC_STARVED_SX', 'PERF_PAPC_PASX_REQ', + 'PERF_PAPC_PASX_REQ_BUSY', 'PERF_PAPC_PASX_REQ_IDLE', + 'PERF_PAPC_PASX_REQ_STALLED', 'PERF_PAPC_PASX_SE0_FIRST_VECTOR', + 'PERF_PAPC_PASX_SE0_REQ', 'PERF_PAPC_PASX_SE0_SECOND_VECTOR', + 'PERF_PAPC_PASX_SE1_FIRST_VECTOR', 'PERF_PAPC_PASX_SE1_REQ', + 'PERF_PAPC_PASX_SE1_SECOND_VECTOR', 'PERF_PAPC_PASX_SECOND_DEAD', + 'PERF_PAPC_PASX_SECOND_VECTOR', 'PERF_PAPC_PASX_VTX_KILL_DISCARD', + 'PERF_PAPC_PASX_VTX_NAN_DISCARD', + 'PERF_PAPC_PA_INPUT_END_OF_PACKET', + 'PERF_PAPC_PA_INPUT_EVENT_FLAG', + 'PERF_PAPC_PA_INPUT_EXTENDED_EVENT', + 'PERF_PAPC_PA_INPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_PA_INPUT_NULL_PRIM', 'PERF_PAPC_PA_INPUT_PRIM', + 'PERF_PAPC_PA_REG_SCLK_VLD', 'PERF_PAPC_SU_BACK_FACE_CULL_PRIM', + 'PERF_PAPC_SU_BUSY', 'PERF_PAPC_SU_CULLED_PRIM', + 'PERF_PAPC_SU_DYN_SCLK_VLD', 'PERF_PAPC_SU_FRONT_FACE_CULL_PRIM', + 'PERF_PAPC_SU_IDLE', 'PERF_PAPC_SU_INPUT_CLIP_PRIM', + 'PERF_PAPC_SU_INPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_INPUT_NULL_PRIM', 'PERF_PAPC_SU_INPUT_PRIM', + 'PERF_PAPC_SU_INPUT_PRIM_DUAL', + 'PERF_PAPC_SU_MULTI_GPU_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_OUTPUT_CLIP_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM', + 'PERF_PAPC_SU_OUTPUT_CLIP_PRIM_DUAL', + 'PERF_PAPC_SU_OUTPUT_END_OF_PACKET', 'PERF_PAPC_SU_OUTPUT_EOPG', + 'PERF_PAPC_SU_OUTPUT_EVENT_FLAG', + 'PERF_PAPC_SU_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_BACK', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_DUAL', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FACE', + 'PERF_PAPC_SU_OUTPUT_POLYMODE_FRONT', 'PERF_PAPC_SU_OUTPUT_PRIM', + 'PERF_PAPC_SU_OUTPUT_PRIM_DUAL', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_BACK', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FACE', + 'PERF_PAPC_SU_OUT_CLIP_POLYMODE_FRONT', + 'PERF_PAPC_SU_POLYMODE_BACK_CULL', + 'PERF_PAPC_SU_POLYMODE_FACE_CULL', + 'PERF_PAPC_SU_POLYMODE_FRONT_CULL', + 'PERF_PAPC_SU_POLYMODE_INVALID_FILL', + 'PERF_PAPC_SU_SE01_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE01_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE01_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE01_STALLED_SC', + 'PERF_PAPC_SU_SE0_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE0_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE0_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE0_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE0_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE0_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE0_STALLED_SC', + 'PERF_PAPC_SU_SE1_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE1_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE1_OUTPUT_FIRST_PRIM_SLOT', + 'PERF_PAPC_SU_SE1_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE1_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE1_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE1_STALLED_SC', + 'PERF_PAPC_SU_SE2_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE2_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE2_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE2_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE2_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE2_STALLED_SC', + 'PERF_PAPC_SU_SE3_OUTPUT_END_OF_PACKET', + 'PERF_PAPC_SU_SE3_OUTPUT_EOPG', + 'PERF_PAPC_SU_SE3_OUTPUT_NULL_PRIM', + 'PERF_PAPC_SU_SE3_OUTPUT_PRIM', + 'PERF_PAPC_SU_SE3_PRIM_FILTER_CULL', + 'PERF_PAPC_SU_SE3_STALLED_SC', 'PERF_PAPC_SU_STALLED_SC', + 'PERF_PAPC_SU_STARVED_CLIP', 'PERF_PAPC_SU_ZERO_AREA_CULL_PRIM', + 'PERSISTENT_SPACE_END', 'PERSISTENT_SPACE_START', + 'PIPELINESTAT_START', 'PIPELINESTAT_STOP', 'PIPE_ID0', 'PIPE_ID1', + 'PIPE_ID2', 'PIPE_ID3', 'PIPE_PHYPLL_PIXEL_RATE_SOURCE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYA', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYB', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYC', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYD', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYE', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYF', + 'PIPE_PHYPLL_PIXEL_RATE_SOURCE_UNIPHYG', + 'PIPE_PIXEL_RATE_PLL_SOURCE', + 'PIPE_PIXEL_RATE_PLL_SOURCE_DISPPLL', + 'PIPE_PIXEL_RATE_PLL_SOURCE_PHYPLL', 'PIPE_PIXEL_RATE_SOURCE', + 'PIPE_PIXEL_RATE_SOURCE_P0PLL', 'PIPE_PIXEL_RATE_SOURCE_P1PLL', + 'PIPE_PIXEL_RATE_SOURCE_P2PLL', 'PIXEL_DEPTH_18BPP', + 'PIXEL_DEPTH_24BPP', 'PIXEL_DEPTH_30BPP', 'PIXEL_DEPTH_38BPP', + 'PIXEL_EXPAN_MODE_DYN_EXP', 'PIXEL_EXPAN_MODE_ZERO_EXP', + 'PIXEL_FORMAT_RGB_444', 'PIXEL_FORMAT_YCBCR_422', + 'PIXEL_FORMAT_YCBCR_444', 'PIXEL_FORMAT_Y_ONLY', + 'PIXEL_PIPE_OCCLUSION_COUNT_0', 'PIXEL_PIPE_OCCLUSION_COUNT_1', + 'PIXEL_PIPE_OCCLUSION_COUNT_2', 'PIXEL_PIPE_OCCLUSION_COUNT_3', + 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MAX_EXTENTS_1', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_0', + 'PIXEL_PIPE_SCREEN_MIN_EXTENTS_1', 'PIXEL_PIPE_STAT_CONTROL', + 'PIXEL_PIPE_STAT_DUMP', 'PIXEL_PIPE_STAT_RESET', + 'PIXEL_PIPE_STRIDE_128_BITS', 'PIXEL_PIPE_STRIDE_256_BITS', + 'PIXEL_PIPE_STRIDE_32_BITS', 'PIXEL_PIPE_STRIDE_64_BITS', + 'PIXEL_REDUCE_MODE_ROUNDING', 'PIXEL_REDUCE_MODE_TRUNCATION', + 'PLL_CFG_IF_SOFT_RESET', 'PLL_CFG_IF_SOFT_RESET_FORCE', + 'PLL_CFG_IF_SOFT_RESET_NOOP', 'PM_ASSERT_RESET', + 'PM_ASSERT_RESET_0', 'PM_ASSERT_RESET_1', 'POINTLIST', + 'PRESCALE_MODE_BYPASS', 'PRESCALE_MODE_PROGRAM', + 'PRESCALE_MODE_UNITY', 'PROG_SEQ', 'PSLC_ASAP', 'PSLC_AUTO', + 'PSLC_COUNTDOWN', 'PSLC_ON_HANG_ONLY', 'PS_DONE', + 'PS_PARTIAL_FLUSH', 'PULSE_MODE_OPT_NO_HSA', + 'PULSE_MODE_OPT_SEND', 'PerfCounter_Vals', 'PipeConfig', + 'PipeInterleaveSize', 'PipeTiling', 'PixelPipeCounterId', + 'PixelPipeStride', 'PkrMap', 'PkrXsel', 'PkrXsel2', 'PkrYsel', + 'QuadExportFormat', 'QuadExportFormatOld', + 'RASTER_CONFIG_PKR_MAP_0', 'RASTER_CONFIG_PKR_MAP_1', + 'RASTER_CONFIG_PKR_MAP_2', 'RASTER_CONFIG_PKR_MAP_3', + 'RASTER_CONFIG_PKR_XSEL2_0', 'RASTER_CONFIG_PKR_XSEL2_1', + 'RASTER_CONFIG_PKR_XSEL2_2', 'RASTER_CONFIG_PKR_XSEL2_3', + 'RASTER_CONFIG_PKR_XSEL_0', 'RASTER_CONFIG_PKR_XSEL_1', + 'RASTER_CONFIG_PKR_XSEL_2', 'RASTER_CONFIG_PKR_XSEL_3', + 'RASTER_CONFIG_PKR_YSEL_0', 'RASTER_CONFIG_PKR_YSEL_1', + 'RASTER_CONFIG_PKR_YSEL_2', 'RASTER_CONFIG_PKR_YSEL_3', + 'RASTER_CONFIG_RB_MAP_0', 'RASTER_CONFIG_RB_MAP_1', + 'RASTER_CONFIG_RB_MAP_2', 'RASTER_CONFIG_RB_MAP_3', + 'RASTER_CONFIG_RB_XSEL2_0', 'RASTER_CONFIG_RB_XSEL2_1', + 'RASTER_CONFIG_RB_XSEL2_2', 'RASTER_CONFIG_RB_XSEL2_3', + 'RASTER_CONFIG_RB_XSEL_0', 'RASTER_CONFIG_RB_XSEL_1', + 'RASTER_CONFIG_RB_YSEL_0', 'RASTER_CONFIG_RB_YSEL_1', + 'RASTER_CONFIG_SC_MAP_0', 'RASTER_CONFIG_SC_MAP_1', + 'RASTER_CONFIG_SC_MAP_2', 'RASTER_CONFIG_SC_MAP_3', + 'RASTER_CONFIG_SC_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SC_YSEL_8_WIDE_TILE', 'RASTER_CONFIG_SE_MAP_0', + 'RASTER_CONFIG_SE_MAP_1', 'RASTER_CONFIG_SE_MAP_2', + 'RASTER_CONFIG_SE_MAP_3', 'RASTER_CONFIG_SE_PAIR_MAP_0', + 'RASTER_CONFIG_SE_PAIR_MAP_1', 'RASTER_CONFIG_SE_PAIR_MAP_2', + 'RASTER_CONFIG_SE_PAIR_MAP_3', + 'RASTER_CONFIG_SE_PAIR_XSEL_128_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_128_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_PAIR_YSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_128_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_XSEL_8_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_128_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_16_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_32_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_64_WIDE_TILE', + 'RASTER_CONFIG_SE_YSEL_8_WIDE_TILE', 'RAW', 'READ_256_BITS', + 'READ_512_BITS', 'READ_SEQ', 'RECTLIST', 'REFCLK_CLOCK_EN', + 'REFCLK_CLOCK_EN_ALLOW_SRC_SEL', 'REFCLK_CLOCK_EN_XTALIN_CLK', + 'REFCLK_SRC_SEL', 'REFCLK_SRC_SEL_CPL_REFCLK', + 'REFCLK_SRC_SEL_PCIE_REFCLK', 'REF_ALWAYS', 'REF_EQUAL', + 'REF_GEQUAL', 'REF_GREATER', 'REF_LEQUAL', 'REF_LESS', + 'REF_NEVER', 'REF_NOTEQUAL', 'RESERVED_ES', 'RESERVED_LS', + 'RESERVED_VS', 'RESET_TO_LOWEST_VGT', 'RESET_VTX_CNT', 'RE_Z', + 'RINGID0', 'RINGID1', 'RINGID2', 'RINGID3', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_DISABLED', + 'RIRB_CONTROL_RESPONSE_OVERRUN_INTERRUPT_CONTROL_INTERRUPT_ENABLED', + 'RMIPerfSel', 'RMI_CID', 'RMI_CID_CC', 'RMI_CID_CM', 'RMI_CID_DC', + 'RMI_CID_FC', 'RMI_CID_S', 'RMI_CID_TILE', 'RMI_CID_Z', + 'RMI_CID_ZPCPSD', 'RMI_PERF_SEL_BUSY', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTSB_RTRB', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTR', + 'RMI_PERF_SEL_DEMUX_TCIW_FORMATTER_RTS_RTRB', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK0', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK1', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK2', + 'RMI_PERF_SEL_DEMUX_TCIW_RESIDENCY_NACK3', + 'RMI_PERF_SEL_DYN_CLK_CMN_VLD', 'RMI_PERF_SEL_DYN_CLK_PERF_VLD', + 'RMI_PERF_SEL_DYN_CLK_RB_VLD', 'RMI_PERF_SEL_EVENT_SEND', + 'RMI_PERF_SEL_LAT_FIFO_BLOCKING_REQ', + 'RMI_PERF_SEL_LAT_FIFO_FULL', + 'RMI_PERF_SEL_LAT_FIFO_NONBLOCKING_REQ', + 'RMI_PERF_SEL_LAT_FIFO_NUM_USED', 'RMI_PERF_SEL_NONE', + 'RMI_PERF_SEL_PERF_WINDOW', 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTR', + 'RMI_PERF_SEL_POP_DEMUX_RTSB_RTRB', + 'RMI_PERF_SEL_POP_DEMUX_RTS_RTR', + 'RMI_PERF_SEL_POP_DEMUX_RTS_RTRB', + 'RMI_PERF_SEL_POP_XNACK_RTSB_RTR', + 'RMI_PERF_SEL_POP_XNACK_RTSB_RTRB', + 'RMI_PERF_SEL_POP_XNACK_RTS_RTR', + 'RMI_PERF_SEL_POP_XNACK_RTS_RTRB', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTR', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTSB_RTRB', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTR', + 'RMI_PERF_SEL_PROBEGEN_UTC_RTS_RTRB', + 'RMI_PERF_SEL_PROBE_UTCL1_ALL_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_PRT_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_NORETRY_FAULT', + 'RMI_PERF_SEL_PROBE_UTCL1_XNACK_RETRY', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTR', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTSB_RTRB', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTR', + 'RMI_PERF_SEL_PRTFIFO_RTNFORMATTER_RTS_RTRB', + 'RMI_PERF_SEL_PRT_FIFO_BUSY', 'RMI_PERF_SEL_PRT_FIFO_NUM_USED', + 'RMI_PERF_SEL_PRT_FIFO_REQ', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_32BRDREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_RDREQ_BUSY', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_RDREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_RDREQ_RESIDENCY', + 'RMI_PERF_SEL_RB_RMI_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BURST_LENGTH_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_BUSY', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID0', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID1', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID2', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID3', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID4', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID5', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID6', + 'RMI_PERF_SEL_RB_RMI_WRREQ_CID7', + 'RMI_PERF_SEL_RB_RMI_WRREQ_INFLIGHT_ALL_ORONE_CID', + 'RMI_PERF_SEL_RB_RMI_WRREQ_RESIDENCY', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTR', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTSB_RTRB', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTR', + 'RMI_PERF_SEL_RDREQCONSUMER_XBAR_RDREQ_RTS_RTRB', + 'RMI_PERF_SEL_REG_CLK_VLD', 'RMI_PERF_SEL_REORDER_FIFO_BUSY', + 'RMI_PERF_SEL_REORDER_FIFO_REQ', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID0', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID1', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID10', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID11', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID12', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID13', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID14', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID15', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID2', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID3', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID4', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID5', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID6', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID7', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID8', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID9', + 'RMI_PERF_SEL_RMI_INVALIDATION_ATC_REQ_VMID_ALL', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID0', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID1', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID10', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID11', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID12', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID13', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID14', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID15', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID2', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID3', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID4', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID5', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID6', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID7', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID8', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID9', + 'RMI_PERF_SEL_RMI_INVALIDATION_REQ_START_FINISH_VMID_ALL', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_32BRDRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID0', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID1', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID2', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID3', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID4', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID5', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID6', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_CID7', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK0', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK1', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK2', + 'RMI_PERF_SEL_RMI_RB_EARLY_WRACK_NACK3', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_ALL_CID', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID3', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID4', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID5', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID6', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_CID7', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK0', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK1', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK2', + 'RMI_PERF_SEL_RMI_RB_WRRET_VALID_NACK3', + 'RMI_PERF_SEL_RMI_TC_RDREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_RDREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_RDREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_REQ_BUSY', + 'RMI_PERF_SEL_RMI_TC_WRREQ_ALL_CID', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID0', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID1', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID2', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID3', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID4', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID5', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID6', + 'RMI_PERF_SEL_RMI_TC_WRREQ_CID7', + 'RMI_PERF_SEL_RMI_TC_WRREQ_INFLIGHT_ALL_CID', + 'RMI_PERF_SEL_RMI_UTC_BUSY', 'RMI_PERF_SEL_RMI_UTC_REQ', + 'RMI_PERF_SEL_SKID_FIFO_BUSY', 'RMI_PERF_SEL_SKID_FIFO_DEPTH', + 'RMI_PERF_SEL_SKID_FIFO_IN_RTS', 'RMI_PERF_SEL_SKID_FIFO_IN_RTSB', + 'RMI_PERF_SEL_SKID_FIFO_OUT_RTS', + 'RMI_PERF_SEL_SKID_FIFO_OUT_RTSB', 'RMI_PERF_SEL_SKID_FIFO_REQ', + 'RMI_PERF_SEL_TCIW_BUSY', 'RMI_PERF_SEL_TCIW_INFLIGHT_COUNT', + 'RMI_PERF_SEL_TCIW_REQ', + 'RMI_PERF_SEL_TC_RMI_RDRET_VALID_ALL_CID', + 'RMI_PERF_SEL_TC_RMI_WRRET_VALID_ALL_CID', + 'RMI_PERF_SEL_UTCL1_BUSY', 'RMI_PERF_SEL_UTCL1_HIT_FIFO_FULL', + 'RMI_PERF_SEL_UTCL1_LFIFO_FULL', + 'RMI_PERF_SEL_UTCL1_PERMISSION_MISS', + 'RMI_PERF_SEL_UTCL1_REQUEST', + 'RMI_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 'RMI_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 'RMI_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 'RMI_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 'RMI_PERF_SEL_UTCL1_STALL_MULTI_MISS', + 'RMI_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'RMI_PERF_SEL_UTCL1_TRANSLATION_MISS', + 'RMI_PERF_SEL_UTCL1_UTCL2_REQ', 'RMI_PERF_SEL_UTC_POP_RTSB_RTR', + 'RMI_PERF_SEL_UTC_POP_RTSB_RTRB', 'RMI_PERF_SEL_UTC_POP_RTS_RTR', + 'RMI_PERF_SEL_UTC_POP_RTS_RTRB', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTR', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTSB_RTRB', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTR', + 'RMI_PERF_SEL_WRREQCONSUMER_XBAR_WRREQ_RTS_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_CB_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_DB_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_IN0_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_IN1_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_READ_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTSB_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTR', + 'RMI_PERF_SEL_XBAR_PROBEGEN_RTS_RTRB', + 'RMI_PERF_SEL_XBAR_PROBEGEN_WRITE_RTS_RTR', + 'RMI_PERF_SEL_XNACK_FIFO_BUSY', 'RMI_PERF_SEL_XNACK_FIFO_FULL', + 'RMI_PERF_SEL_XNACK_FIFO_NUM_USED', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTR', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTSB_RTRB', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTR', + 'RMI_PERF_SEL_XNACK_PROBEGEN_RTS_RTRB', 'ROM_SIGNATURE', + 'ROUND_BY_HALF', 'ROUND_TRUNCATE', 'RST_PIX_CNT', 'RSV_TAG_RAM', + 'RbMap', 'RbXsel', 'RbXsel2', 'RbYsel', 'ReadSize', 'Reserved142', + 'Reserved143', 'Reserved144', 'Reserved145', 'Reserved146', + 'Reserved147', 'Reserved148', 'Reserved149', 'Reserved18', + 'Reserved182', 'Reserved183', 'Reserved184', 'Reserved185', + 'Reserved186', 'Reserved187', 'Reserved188', 'Reserved189', + 'Reserved190', 'Reserved191', 'Reserved192', 'Reserved193', + 'Reserved194', 'Reserved195', 'Reserved196', 'Reserved197', + 'Reserved198', 'Reserved199', 'Reserved200', 'Reserved201', + 'Reserved202', 'Reserved203', 'Reserved204', 'Reserved205', + 'Reserved206', 'Reserved207', 'Reserved208', 'Reserved209', + 'Reserved210', 'Reserved211', 'Reserved212', 'Reserved213', + 'Reserved214', 'Reserved215', 'Reserved216', 'Reserved217', + 'Reserved218', 'Reserved219', 'Reserved23', 'Reserved252', + 'Reserved253', 'Reserved254', 'Reserved255', 'Reserved256', + 'Reserved257', 'Reserved258', 'Reserved259', 'Reserved26', + 'Reserved260', 'Reserved261', 'Reserved262', 'Reserved263', + 'Reserved264', 'Reserved265', 'Reserved266', 'Reserved267', + 'Reserved27', 'Reserved28', 'Reserved29', 'Reserved300', + 'Reserved301', 'Reserved302', 'Reserved303', 'Reserved304', + 'Reserved305', 'Reserved306', 'Reserved307', 'Reserved308', + 'Reserved309', 'Reserved310', 'Reserved311', 'Reserved312', + 'Reserved313', 'Reserved314', 'Reserved315', 'Reserved316', + 'Reserved317', 'Reserved318', 'Reserved319', 'Reserved320', + 'Reserved321', 'Reserved322', 'Reserved323', 'Reserved324', + 'Reserved325', 'Reserved326', 'Reserved327', 'Reserved328', + 'Reserved329', 'Reserved330', 'Reserved331', 'Reserved364', + 'Reserved365', 'Reserved366', 'Reserved367', 'Reserved368', + 'Reserved369', 'Reserved370', 'Reserved371', 'Reserved372', + 'Reserved373', 'Reserved374', 'Reserved375', 'Reserved376', + 'Reserved377', 'Reserved378', 'Reserved379', 'Reserved412', + 'Reserved413', 'Reserved414', 'Reserved415', 'Reserved416', + 'Reserved417', 'Reserved418', 'Reserved419', 'Reserved420', + 'Reserved421', 'Reserved422', 'Reserved423', 'Reserved424', + 'Reserved425', 'Reserved426', 'Reserved427', 'Reserved428', + 'Reserved429', 'Reserved430', 'Reserved431', 'Reserved432', + 'Reserved433', 'Reserved434', 'Reserved435', 'Reserved436', + 'Reserved437', 'Reserved438', 'Reserved439', 'Reserved440', + 'Reserved441', 'Reserved442', 'Reserved443', 'Reserved444', + 'Reserved445', 'Reserved446', 'Reserved447', 'Reserved448', + 'Reserved449', 'Reserved450', 'Reserved451', 'Reserved452', + 'Reserved453', 'Reserved454', 'Reserved455', 'Reserved456', + 'Reserved457', 'Reserved458', 'Reserved459', 'Reserved460', + 'Reserved461', 'Reserved462', 'Reserved463', 'Reserved464', + 'Reserved465', 'Reserved466', 'Reserved467', 'Reserved468', + 'Reserved469', 'Reserved470', 'Reserved471', 'Reserved472', + 'Reserved473', 'Reserved474', 'Reserved475', 'Reserved476', + 'Reserved477', 'Reserved478', 'Reserved479', 'Reserved480', + 'Reserved481', 'Reserved482', 'Reserved483', 'Reserved484', + 'Reserved485', 'Reserved486', 'Reserved487', 'Reserved488', + 'Reserved489', 'Reserved490', 'Reserved491', 'Reserved492', + 'Reserved493', 'Reserved494', 'Reserved495', 'Reserved496', + 'Reserved497', 'Reserved498', 'Reserved499', 'Reserved500', + 'Reserved501', 'Reserved502', 'Reserved503', 'Reserved504', + 'Reserved505', 'Reserved506', 'Reserved507', 'Reserved508', + 'Reserved509', 'Reserved510', 'Reserved511', 'Reserved_0x00', + 'Reserved_0x09', 'Reserved_0x3f', 'RingCounterControl', + 'RoundMode', 'RowSize', 'RowTiling', 'SAMPLE_PIPELINESTAT', + 'SAMPLE_STREAMOUTSTATS', 'SAMPLE_STREAMOUTSTATS1', + 'SAMPLE_STREAMOUTSTATS2', 'SAMPLE_STREAMOUTSTATS3', + 'SCLV_COEF_UPDATE_COMPLETE', 'SCLV_INTERLACE_SOURCE', + 'SCLV_MODE_RGB_BYPASS', 'SCLV_MODE_RGB_SCALING', 'SCLV_MODE_SEL', + 'SCLV_MODE_YCBCR_BYPASS', 'SCLV_MODE_YCBCR_SCALING', + 'SCLV_UPDATE_LOCK', 'SCL_ALU_DISABLE', 'SCL_ALU_DISABLED', + 'SCL_ALU_ENABLED', 'SCL_BOUNDARY_MODE', 'SCL_BOUNDARY_MODE_BLACK', + 'SCL_BOUNDARY_MODE_EDGE', 'SCL_BYPASS_MODE', + 'SCL_BYPASS_MODE_AC_AR', 'SCL_BYPASS_MODE_AC_NR', + 'SCL_BYPASS_MODE_MC_MR', 'SCL_BYPASS_MODE_RESERVED', + 'SCL_COEF_UPDATE_COMPLETE', 'SCL_COEF_UPDATE_COMPLETED', + 'SCL_COEF_UPDATE_NOT_COMPLETED', 'SCL_C_RAM_FILTER_TYPE', + 'SCL_C_RAM_FILTER_TYPE_HORI_CHROMA_LUT', + 'SCL_C_RAM_FILTER_TYPE_HORI_LUMA_RGB_LUT', + 'SCL_C_RAM_FILTER_TYPE_VERT_CHROMA_LUT', + 'SCL_C_RAM_FILTER_TYPE_VERT_LUMA_RGB_LUT', 'SCL_C_RAM_PHASE', + 'SCL_C_RAM_PHASE_0', 'SCL_C_RAM_PHASE_1', 'SCL_C_RAM_PHASE_2', + 'SCL_C_RAM_PHASE_3', 'SCL_C_RAM_PHASE_4', 'SCL_C_RAM_PHASE_5', + 'SCL_C_RAM_PHASE_6', 'SCL_C_RAM_PHASE_7', 'SCL_C_RAM_PHASE_8', + 'SCL_C_RAM_TAP_PAIR_ID0', 'SCL_C_RAM_TAP_PAIR_ID1', + 'SCL_C_RAM_TAP_PAIR_ID2', 'SCL_C_RAM_TAP_PAIR_ID3', + 'SCL_C_RAM_TAP_PAIR_ID4', 'SCL_C_RAM_TAP_PAIR_IDX', + 'SCL_EARLY_EOL_MOD', 'SCL_EARLY_EOL_MODE_CRTC', + 'SCL_EARLY_EOL_MODE_INTERNAL', 'SCL_HF_SHARP_DISABLE', + 'SCL_HF_SHARP_EN', 'SCL_HF_SHARP_ENABLE', + 'SCL_HF_SHARP_SCALE_FACTOR', 'SCL_HF_SHARP_SCALE_FACTOR_0', + 'SCL_HF_SHARP_SCALE_FACTOR_1', 'SCL_HF_SHARP_SCALE_FACTOR_2', + 'SCL_HF_SHARP_SCALE_FACTOR_3', 'SCL_HF_SHARP_SCALE_FACTOR_4', + 'SCL_HF_SHARP_SCALE_FACTOR_5', 'SCL_HF_SHARP_SCALE_FACTOR_6', + 'SCL_HF_SHARP_SCALE_FACTOR_7', + 'SCL_HOST_CONFLICT_DISABLE_INTERRUPT', + 'SCL_HOST_CONFLICT_ENABLE_INTERRUPT', 'SCL_HOST_CONFLICT_MASK', + 'SCL_H_2TAP_HARDCODE_COEF_DISABLE', 'SCL_H_2TAP_HARDCODE_COEF_EN', + 'SCL_H_2TAP_HARDCODE_COEF_ENABLE', + 'SCL_H_CALC_AUTO_RATIO_DISABLE', 'SCL_H_CALC_AUTO_RATIO_EN', + 'SCL_H_CALC_AUTO_RATIO_ENABLE', 'SCL_H_FILTER_PICK_NEAREST', + 'SCL_H_FILTER_PICK_NEAREST_DISABLE', + 'SCL_H_FILTER_PICK_NEAREST_ENABLE', + 'SCL_H_MANUAL_REPLICATE_FACTOR', + 'SCL_H_MANUAL_REPLICATE_FACTOR_1', + 'SCL_H_MANUAL_REPLICATE_FACTOR_10', + 'SCL_H_MANUAL_REPLICATE_FACTOR_11', + 'SCL_H_MANUAL_REPLICATE_FACTOR_12', + 'SCL_H_MANUAL_REPLICATE_FACTOR_13', + 'SCL_H_MANUAL_REPLICATE_FACTOR_14', + 'SCL_H_MANUAL_REPLICATE_FACTOR_15', + 'SCL_H_MANUAL_REPLICATE_FACTOR_16', + 'SCL_H_MANUAL_REPLICATE_FACTOR_2', + 'SCL_H_MANUAL_REPLICATE_FACTOR_3', + 'SCL_H_MANUAL_REPLICATE_FACTOR_4', + 'SCL_H_MANUAL_REPLICATE_FACTOR_5', + 'SCL_H_MANUAL_REPLICATE_FACTOR_6', + 'SCL_H_MANUAL_REPLICATE_FACTOR_7', + 'SCL_H_MANUAL_REPLICATE_FACTOR_8', + 'SCL_H_MANUAL_REPLICATE_FACTOR_9', 'SCL_H_NUM_OF_TAPS', + 'SCL_H_NUM_OF_TAPS_1', 'SCL_H_NUM_OF_TAPS_10', + 'SCL_H_NUM_OF_TAPS_2', 'SCL_H_NUM_OF_TAPS_4', + 'SCL_H_NUM_OF_TAPS_6', 'SCL_H_NUM_OF_TAPS_8', + 'SCL_MODE_CHANGE_DISABLE_INTERRUPT', + 'SCL_MODE_CHANGE_ENABLE_INTERRUPT', 'SCL_MODE_RGB_BYPASS', + 'SCL_MODE_RGB_SCALING', 'SCL_MODE_SEL', 'SCL_MODE_YCBCR_BYPASS', + 'SCL_MODE_YCBCR_SCALING', 'SCL_PSCL_DISABLE', 'SCL_PSCL_EN', + 'SCL_PSCL_ENANBLE', 'SCL_SCL_MODE_CHANGE_MASK', 'SCL_UPDATE_LOCK', + 'SCL_UPDATE_LOCKED', 'SCL_UPDATE_TAKEN', 'SCL_UPDATE_TAKEN_NO', + 'SCL_UPDATE_TAKEN_YES', 'SCL_UPDATE_UNLOCKED', + 'SCL_VF_SHARP_DISABLE', 'SCL_VF_SHARP_EN', 'SCL_VF_SHARP_ENABLE', + 'SCL_VF_SHARP_SCALE_FACTOR', 'SCL_VF_SHARP_SCALE_FACTOR_0', + 'SCL_VF_SHARP_SCALE_FACTOR_1', 'SCL_VF_SHARP_SCALE_FACTOR_2', + 'SCL_VF_SHARP_SCALE_FACTOR_3', 'SCL_VF_SHARP_SCALE_FACTOR_4', + 'SCL_VF_SHARP_SCALE_FACTOR_5', 'SCL_VF_SHARP_SCALE_FACTOR_6', + 'SCL_VF_SHARP_SCALE_FACTOR_7', 'SCL_V_2TAP_HARDCODE_COEF_DISABLE', + 'SCL_V_2TAP_HARDCODE_COEF_EN', 'SCL_V_2TAP_HARDCODE_COEF_ENABLE', + 'SCL_V_CALC_AUTO_RATIO_DISABLE', 'SCL_V_CALC_AUTO_RATIO_EN', + 'SCL_V_CALC_AUTO_RATIO_ENABLE', 'SCL_V_FILTER_PICK_NEAREST', + 'SCL_V_FILTER_PICK_NEAREST_DISABLE', + 'SCL_V_FILTER_PICK_NEAREST_ENABLE', + 'SCL_V_MANUAL_REPLICATE_FACTOR', + 'SCL_V_MANUAL_REPLICATE_FACTOR_1', + 'SCL_V_MANUAL_REPLICATE_FACTOR_10', + 'SCL_V_MANUAL_REPLICATE_FACTOR_11', + 'SCL_V_MANUAL_REPLICATE_FACTOR_12', + 'SCL_V_MANUAL_REPLICATE_FACTOR_13', + 'SCL_V_MANUAL_REPLICATE_FACTOR_14', + 'SCL_V_MANUAL_REPLICATE_FACTOR_15', + 'SCL_V_MANUAL_REPLICATE_FACTOR_16', + 'SCL_V_MANUAL_REPLICATE_FACTOR_2', + 'SCL_V_MANUAL_REPLICATE_FACTOR_3', + 'SCL_V_MANUAL_REPLICATE_FACTOR_4', + 'SCL_V_MANUAL_REPLICATE_FACTOR_5', + 'SCL_V_MANUAL_REPLICATE_FACTOR_6', + 'SCL_V_MANUAL_REPLICATE_FACTOR_7', + 'SCL_V_MANUAL_REPLICATE_FACTOR_8', + 'SCL_V_MANUAL_REPLICATE_FACTOR_9', 'SCL_V_NUM_OF_TAPS', + 'SCL_V_NUM_OF_TAPS_1', 'SCL_V_NUM_OF_TAPS_2', + 'SCL_V_NUM_OF_TAPS_3', 'SCL_V_NUM_OF_TAPS_4', + 'SCL_V_NUM_OF_TAPS_5', 'SCL_V_NUM_OF_TAPS_6', 'SC_BACKEND_BUSY', + 'SC_BB_DISCARD', 'SC_BM_BUSY', 'SC_BUSY_CNT_NOT_ZERO', + 'SC_BUSY_PROCESSING_MULTICYCLE_PRIM', 'SC_EARLYZ_QUAD_COUNT', + 'SC_EARLYZ_QUAD_WITH_1_PIX', 'SC_EARLYZ_QUAD_WITH_2_PIX', + 'SC_EARLYZ_QUAD_WITH_3_PIX', 'SC_EARLYZ_QUAD_WITH_4_PIX', + 'SC_EOP_SYNC_WINDOW', 'SC_GRP0_DYN_SCLK_BUSY', + 'SC_GRP1_DYN_SCLK_BUSY', 'SC_GRP2_DYN_SCLK_BUSY', + 'SC_GRP3_DYN_SCLK_BUSY', 'SC_GRP4_DYN_SCLK_BUSY', + 'SC_MULTICYCLE_BUBBLE_FREEZE', 'SC_P0_DETAIL_QUAD_COUNT', + 'SC_P0_DETAIL_QUAD_WITH_1_PIX', 'SC_P0_DETAIL_QUAD_WITH_2_PIX', + 'SC_P0_DETAIL_QUAD_WITH_3_PIX', 'SC_P0_DETAIL_QUAD_WITH_4_PIX', + 'SC_P0_HIZ_QUAD_COUNT', 'SC_P0_HIZ_QUAD_PER_TILE_H0', + 'SC_P0_HIZ_QUAD_PER_TILE_H1', 'SC_P0_HIZ_QUAD_PER_TILE_H10', + 'SC_P0_HIZ_QUAD_PER_TILE_H11', 'SC_P0_HIZ_QUAD_PER_TILE_H12', + 'SC_P0_HIZ_QUAD_PER_TILE_H13', 'SC_P0_HIZ_QUAD_PER_TILE_H14', + 'SC_P0_HIZ_QUAD_PER_TILE_H15', 'SC_P0_HIZ_QUAD_PER_TILE_H16', + 'SC_P0_HIZ_QUAD_PER_TILE_H2', 'SC_P0_HIZ_QUAD_PER_TILE_H3', + 'SC_P0_HIZ_QUAD_PER_TILE_H4', 'SC_P0_HIZ_QUAD_PER_TILE_H5', + 'SC_P0_HIZ_QUAD_PER_TILE_H6', 'SC_P0_HIZ_QUAD_PER_TILE_H7', + 'SC_P0_HIZ_QUAD_PER_TILE_H8', 'SC_P0_HIZ_QUAD_PER_TILE_H9', + 'SC_P0_HIZ_TILE_COUNT', 'SC_P1_DETAIL_QUAD_COUNT', + 'SC_P1_DETAIL_QUAD_WITH_1_PIX', 'SC_P1_DETAIL_QUAD_WITH_2_PIX', + 'SC_P1_DETAIL_QUAD_WITH_3_PIX', 'SC_P1_DETAIL_QUAD_WITH_4_PIX', + 'SC_P1_HIZ_QUAD_COUNT', 'SC_P1_HIZ_QUAD_PER_TILE_H0', + 'SC_P1_HIZ_QUAD_PER_TILE_H1', 'SC_P1_HIZ_QUAD_PER_TILE_H10', + 'SC_P1_HIZ_QUAD_PER_TILE_H11', 'SC_P1_HIZ_QUAD_PER_TILE_H12', + 'SC_P1_HIZ_QUAD_PER_TILE_H13', 'SC_P1_HIZ_QUAD_PER_TILE_H14', + 'SC_P1_HIZ_QUAD_PER_TILE_H15', 'SC_P1_HIZ_QUAD_PER_TILE_H16', + 'SC_P1_HIZ_QUAD_PER_TILE_H2', 'SC_P1_HIZ_QUAD_PER_TILE_H3', + 'SC_P1_HIZ_QUAD_PER_TILE_H4', 'SC_P1_HIZ_QUAD_PER_TILE_H5', + 'SC_P1_HIZ_QUAD_PER_TILE_H6', 'SC_P1_HIZ_QUAD_PER_TILE_H7', + 'SC_P1_HIZ_QUAD_PER_TILE_H8', 'SC_P1_HIZ_QUAD_PER_TILE_H9', + 'SC_P1_HIZ_TILE_COUNT', 'SC_P2_DETAIL_QUAD_COUNT', + 'SC_P2_DETAIL_QUAD_WITH_1_PIX', 'SC_P2_DETAIL_QUAD_WITH_2_PIX', + 'SC_P2_DETAIL_QUAD_WITH_3_PIX', 'SC_P2_DETAIL_QUAD_WITH_4_PIX', + 'SC_P2_HIZ_QUAD_COUNT', 'SC_P2_HIZ_QUAD_PER_TILE_H0', + 'SC_P2_HIZ_QUAD_PER_TILE_H1', 'SC_P2_HIZ_QUAD_PER_TILE_H10', + 'SC_P2_HIZ_QUAD_PER_TILE_H11', 'SC_P2_HIZ_QUAD_PER_TILE_H12', + 'SC_P2_HIZ_QUAD_PER_TILE_H13', 'SC_P2_HIZ_QUAD_PER_TILE_H14', + 'SC_P2_HIZ_QUAD_PER_TILE_H15', 'SC_P2_HIZ_QUAD_PER_TILE_H16', + 'SC_P2_HIZ_QUAD_PER_TILE_H2', 'SC_P2_HIZ_QUAD_PER_TILE_H3', + 'SC_P2_HIZ_QUAD_PER_TILE_H4', 'SC_P2_HIZ_QUAD_PER_TILE_H5', + 'SC_P2_HIZ_QUAD_PER_TILE_H6', 'SC_P2_HIZ_QUAD_PER_TILE_H7', + 'SC_P2_HIZ_QUAD_PER_TILE_H8', 'SC_P2_HIZ_QUAD_PER_TILE_H9', + 'SC_P2_HIZ_TILE_COUNT', 'SC_P3_DETAIL_QUAD_COUNT', + 'SC_P3_DETAIL_QUAD_WITH_1_PIX', 'SC_P3_DETAIL_QUAD_WITH_2_PIX', + 'SC_P3_DETAIL_QUAD_WITH_3_PIX', 'SC_P3_DETAIL_QUAD_WITH_4_PIX', + 'SC_P3_HIZ_QUAD_COUNT', 'SC_P3_HIZ_QUAD_PER_TILE_H0', + 'SC_P3_HIZ_QUAD_PER_TILE_H1', 'SC_P3_HIZ_QUAD_PER_TILE_H10', + 'SC_P3_HIZ_QUAD_PER_TILE_H11', 'SC_P3_HIZ_QUAD_PER_TILE_H12', + 'SC_P3_HIZ_QUAD_PER_TILE_H13', 'SC_P3_HIZ_QUAD_PER_TILE_H14', + 'SC_P3_HIZ_QUAD_PER_TILE_H15', 'SC_P3_HIZ_QUAD_PER_TILE_H16', + 'SC_P3_HIZ_QUAD_PER_TILE_H2', 'SC_P3_HIZ_QUAD_PER_TILE_H3', + 'SC_P3_HIZ_QUAD_PER_TILE_H4', 'SC_P3_HIZ_QUAD_PER_TILE_H5', + 'SC_P3_HIZ_QUAD_PER_TILE_H6', 'SC_P3_HIZ_QUAD_PER_TILE_H7', + 'SC_P3_HIZ_QUAD_PER_TILE_H8', 'SC_P3_HIZ_QUAD_PER_TILE_H9', + 'SC_P3_HIZ_TILE_COUNT', 'SC_PA0_PS_DATA_SEND', + 'SC_PA0_SC_DATA_FIFO_EOPG_RD', 'SC_PA0_SC_DATA_FIFO_EOP_RD', + 'SC_PA0_SC_DATA_FIFO_RD', 'SC_PA0_SC_DATA_FIFO_WE', + 'SC_PA0_SC_DEALLOC_0_RD', 'SC_PA0_SC_DEALLOC_1_RD', + 'SC_PA0_SC_EOPG_WE', 'SC_PA0_SC_EOP_WE', 'SC_PA0_SC_EVENT_WE', + 'SC_PA0_SC_FPOV_WE', 'SC_PA0_SC_LPOV_WE', + 'SC_PA0_SC_NULL_DEALLOC_WE', 'SC_PA0_SC_NULL_WE', + 'SC_PA1_PS_DATA_SEND', 'SC_PA1_SC_DATA_FIFO_EOPG_RD', + 'SC_PA1_SC_DATA_FIFO_EOP_RD', 'SC_PA1_SC_DATA_FIFO_RD', + 'SC_PA1_SC_DATA_FIFO_WE', 'SC_PA1_SC_DEALLOC_0_RD', + 'SC_PA1_SC_DEALLOC_1_RD', 'SC_PA1_SC_EOPG_WE', 'SC_PA1_SC_EOP_WE', + 'SC_PA1_SC_EVENT_WE', 'SC_PA1_SC_FPOV_WE', 'SC_PA1_SC_LPOV_WE', + 'SC_PA1_SC_NULL_DEALLOC_WE', 'SC_PA1_SC_NULL_WE', + 'SC_PA2_PS_DATA_SEND', 'SC_PA2_SC_DATA_FIFO_EOPG_RD', + 'SC_PA2_SC_DATA_FIFO_EOP_RD', 'SC_PA2_SC_DATA_FIFO_RD', + 'SC_PA2_SC_DATA_FIFO_WE', 'SC_PA2_SC_DEALLOC_0_RD', + 'SC_PA2_SC_DEALLOC_1_RD', 'SC_PA2_SC_EOPG_WE', 'SC_PA2_SC_EOP_WE', + 'SC_PA2_SC_EVENT_WE', 'SC_PA2_SC_FPOV_WE', 'SC_PA2_SC_LPOV_WE', + 'SC_PA2_SC_NULL_DEALLOC_WE', 'SC_PA2_SC_NULL_WE', + 'SC_PA3_PS_DATA_SEND', 'SC_PA3_SC_DATA_FIFO_EOPG_RD', + 'SC_PA3_SC_DATA_FIFO_EOP_RD', 'SC_PA3_SC_DATA_FIFO_RD', + 'SC_PA3_SC_DATA_FIFO_WE', 'SC_PA3_SC_DEALLOC_0_RD', + 'SC_PA3_SC_DEALLOC_1_RD', 'SC_PA3_SC_EOPG_WE', 'SC_PA3_SC_EOP_WE', + 'SC_PA3_SC_EVENT_WE', 'SC_PA3_SC_FPOV_WE', 'SC_PA3_SC_LPOV_WE', + 'SC_PA3_SC_NULL_DEALLOC_WE', 'SC_PA3_SC_NULL_WE', + 'SC_PA_SC_DEALLOC_0_0_WE', 'SC_PA_SC_DEALLOC_0_1_WE', + 'SC_PA_SC_DEALLOC_1_0_WE', 'SC_PA_SC_DEALLOC_1_1_WE', + 'SC_PA_SC_DEALLOC_2_0_WE', 'SC_PA_SC_DEALLOC_2_1_WE', + 'SC_PA_SC_DEALLOC_3_0_WE', 'SC_PA_SC_DEALLOC_3_1_WE', + 'SC_PBB_BATCH_BREAK_DUE_TO_CONTEXT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_EVENT', + 'SC_PBB_BATCH_BREAK_DUE_TO_FPOV_LIMIT', + 'SC_PBB_BATCH_BREAK_DUE_TO_PC_STORAGE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PERSISTENT_STATE', + 'SC_PBB_BATCH_BREAK_DUE_TO_PRIM', + 'SC_PBB_BATCH_HIST_NUM_COLUMNS_PER_ROW', + 'SC_PBB_BATCH_HIST_NUM_CONTEXTS', + 'SC_PBB_BATCH_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BATCH_HIST_NUM_PRIMS', + 'SC_PBB_BATCH_HIST_NUM_PS_WAVE_BREAKS', + 'SC_PBB_BATCH_HIST_NUM_ROWS_PER_PRIM', + 'SC_PBB_BATCH_HIST_NUM_TRIV_REJECTED_PRIMS', + 'SC_PBB_BIN_HIST_NUM_CONTEXTS', + 'SC_PBB_BIN_HIST_NUM_PERSISTENT_STATES', + 'SC_PBB_BIN_HIST_NUM_PRIMS', 'SC_PBB_BUSY', 'SC_PBB_BUSY_AND_RTR', + 'SC_PBB_END_OF_BATCH', 'SC_PBB_END_OF_BIN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_COLUMN', + 'SC_PBB_IDLE_CLK_DUE_TO_FALSE_POSITIVE_ON_ROW', + 'SC_PBB_IDLE_CLK_DUE_TO_ROW_TO_COLUMN_TRANSITION', + 'SC_PBB_NONBINNED_PRIM', 'SC_PBB_NUM_BINS', + 'SC_PBB_PRIMBIN_PROCESSED', 'SC_PBB_PRIM_ADDED_TO_BATCH', + 'SC_PBB_STALLS_PA_DUE_TO_NO_TILES', + 'SC_PBB_TOTAL_NULL_PRIMS_OUT_OF_PBB', + 'SC_PBB_TOTAL_REAL_PRIMS_OUT_OF_PBB', 'SC_PERFCNT_SEL', + 'SC_PKR_4X2_FILL_QUAD', 'SC_PKR_4X2_QUAD_SPLIT', + 'SC_PKR_CONTROL_XFER', 'SC_PKR_DBHANG_FORCE_EOV', + 'SC_PKR_END_OF_VECTOR', 'SC_PKR_QUAD_OVERLAP_FOUND_IN_WAVE_TABLE', + 'SC_PKR_QUAD_OVERLAP_NOT_FOUND_IN_WAVE_TABLE', + 'SC_PKR_QUAD_PER_ROW_H1', 'SC_PKR_QUAD_PER_ROW_H2', + 'SC_POPS_FORCE_EOV', 'SC_POPS_INTRA_WAVE_OVERLAPS', + 'SC_PSSW_WINDOW_VALID', 'SC_PSSW_WINDOW_VALID_BUSY', + 'SC_PS_ARB_EOP_POP_SYNC_POP', 'SC_PS_ARB_EVENT_SYNC_POP', + 'SC_PS_ARB_NULL_PRIM_BUBBLE_POP', + 'SC_PS_ARB_OOO_FIFO_EMPTY_SWITCH', + 'SC_PS_ARB_OOO_THRESHOLD_SWITCH_TO_DESIRED_FIFO', + 'SC_PS_ARB_PA_SC_BUSY', 'SC_PS_ARB_SC_BUSY', + 'SC_PS_ARB_STALLED_FROM_BELOW', 'SC_PS_ARB_STARVED_FROM_ABOVE', + 'SC_PS_ARB_XFC_ALL_EVENT_OR_PRIM_CYCLES', + 'SC_PS_ARB_XFC_ONLY_ONE_INC_PER_PRIM', + 'SC_PS_ARB_XFC_ONLY_PRIM_CYCLES', 'SC_PS_CTX_DONE_FIFO_POP', + 'SC_PS_CTX_DONE_FIFO_PUSH', 'SC_PS_PA0_SC_FIFO_EMPTY', + 'SC_PS_PA0_SC_FIFO_FULL', 'SC_PS_PA1_SC_FIFO_EMPTY', + 'SC_PS_PA1_SC_FIFO_FULL', 'SC_PS_PA2_SC_FIFO_EMPTY', + 'SC_PS_PA2_SC_FIFO_FULL', 'SC_PS_PA3_SC_FIFO_EMPTY', + 'SC_PS_PA3_SC_FIFO_FULL', 'SC_PS_TS_EVENT_FIFO_POP', + 'SC_PS_TS_EVENT_FIFO_PUSH', 'SC_QZ0_MULTI_GPU_TILE_DISCARD', + 'SC_QZ0_QUAD_COUNT', 'SC_QZ0_QUAD_PER_TILE_H0', + 'SC_QZ0_QUAD_PER_TILE_H1', 'SC_QZ0_QUAD_PER_TILE_H10', + 'SC_QZ0_QUAD_PER_TILE_H11', 'SC_QZ0_QUAD_PER_TILE_H12', + 'SC_QZ0_QUAD_PER_TILE_H13', 'SC_QZ0_QUAD_PER_TILE_H14', + 'SC_QZ0_QUAD_PER_TILE_H15', 'SC_QZ0_QUAD_PER_TILE_H16', + 'SC_QZ0_QUAD_PER_TILE_H2', 'SC_QZ0_QUAD_PER_TILE_H3', + 'SC_QZ0_QUAD_PER_TILE_H4', 'SC_QZ0_QUAD_PER_TILE_H5', + 'SC_QZ0_QUAD_PER_TILE_H6', 'SC_QZ0_QUAD_PER_TILE_H7', + 'SC_QZ0_QUAD_PER_TILE_H8', 'SC_QZ0_QUAD_PER_TILE_H9', + 'SC_QZ0_TILE_COUNT', 'SC_QZ0_TILE_COVERED_COUNT', + 'SC_QZ0_TILE_NOT_COVERED_COUNT', 'SC_QZ1_MULTI_GPU_TILE_DISCARD', + 'SC_QZ1_QUAD_COUNT', 'SC_QZ1_QUAD_PER_TILE_H0', + 'SC_QZ1_QUAD_PER_TILE_H1', 'SC_QZ1_QUAD_PER_TILE_H10', + 'SC_QZ1_QUAD_PER_TILE_H11', 'SC_QZ1_QUAD_PER_TILE_H12', + 'SC_QZ1_QUAD_PER_TILE_H13', 'SC_QZ1_QUAD_PER_TILE_H14', + 'SC_QZ1_QUAD_PER_TILE_H15', 'SC_QZ1_QUAD_PER_TILE_H16', + 'SC_QZ1_QUAD_PER_TILE_H2', 'SC_QZ1_QUAD_PER_TILE_H3', + 'SC_QZ1_QUAD_PER_TILE_H4', 'SC_QZ1_QUAD_PER_TILE_H5', + 'SC_QZ1_QUAD_PER_TILE_H6', 'SC_QZ1_QUAD_PER_TILE_H7', + 'SC_QZ1_QUAD_PER_TILE_H8', 'SC_QZ1_QUAD_PER_TILE_H9', + 'SC_QZ1_TILE_COUNT', 'SC_QZ1_TILE_COVERED_COUNT', + 'SC_QZ1_TILE_NOT_COVERED_COUNT', 'SC_QZ2_MULTI_GPU_TILE_DISCARD', + 'SC_QZ2_QUAD_COUNT', 'SC_QZ2_QUAD_PER_TILE_H0', + 'SC_QZ2_QUAD_PER_TILE_H1', 'SC_QZ2_QUAD_PER_TILE_H10', + 'SC_QZ2_QUAD_PER_TILE_H11', 'SC_QZ2_QUAD_PER_TILE_H12', + 'SC_QZ2_QUAD_PER_TILE_H13', 'SC_QZ2_QUAD_PER_TILE_H14', + 'SC_QZ2_QUAD_PER_TILE_H15', 'SC_QZ2_QUAD_PER_TILE_H16', + 'SC_QZ2_QUAD_PER_TILE_H2', 'SC_QZ2_QUAD_PER_TILE_H3', + 'SC_QZ2_QUAD_PER_TILE_H4', 'SC_QZ2_QUAD_PER_TILE_H5', + 'SC_QZ2_QUAD_PER_TILE_H6', 'SC_QZ2_QUAD_PER_TILE_H7', + 'SC_QZ2_QUAD_PER_TILE_H8', 'SC_QZ2_QUAD_PER_TILE_H9', + 'SC_QZ2_TILE_COUNT', 'SC_QZ2_TILE_COVERED_COUNT', + 'SC_QZ2_TILE_NOT_COVERED_COUNT', 'SC_QZ3_MULTI_GPU_TILE_DISCARD', + 'SC_QZ3_QUAD_COUNT', 'SC_QZ3_QUAD_PER_TILE_H0', + 'SC_QZ3_QUAD_PER_TILE_H1', 'SC_QZ3_QUAD_PER_TILE_H10', + 'SC_QZ3_QUAD_PER_TILE_H11', 'SC_QZ3_QUAD_PER_TILE_H12', + 'SC_QZ3_QUAD_PER_TILE_H13', 'SC_QZ3_QUAD_PER_TILE_H14', + 'SC_QZ3_QUAD_PER_TILE_H15', 'SC_QZ3_QUAD_PER_TILE_H16', + 'SC_QZ3_QUAD_PER_TILE_H2', 'SC_QZ3_QUAD_PER_TILE_H3', + 'SC_QZ3_QUAD_PER_TILE_H4', 'SC_QZ3_QUAD_PER_TILE_H5', + 'SC_QZ3_QUAD_PER_TILE_H6', 'SC_QZ3_QUAD_PER_TILE_H7', + 'SC_QZ3_QUAD_PER_TILE_H8', 'SC_QZ3_QUAD_PER_TILE_H9', + 'SC_QZ3_TILE_COUNT', 'SC_QZ3_TILE_COVERED_COUNT', + 'SC_QZ3_TILE_NOT_COVERED_COUNT', 'SC_QZQP_WINDOW_VALID', + 'SC_QZQP_WINDOW_VALID_BUSY', 'SC_REG_SCLK_BUSY', 'SC_SCB_BUSY', + 'SC_SCF_SCB_INTERFACE_BUSY', 'SC_SCISSOR_DISCARD', + 'SC_SC_PS_ENG_MULTICYCLE_BUBBLE', 'SC_SC_SPI_DEALLOC_0_0', + 'SC_SC_SPI_DEALLOC_0_1', 'SC_SC_SPI_DEALLOC_0_2', + 'SC_SC_SPI_DEALLOC_1_0', 'SC_SC_SPI_DEALLOC_1_1', + 'SC_SC_SPI_DEALLOC_1_2', 'SC_SC_SPI_DEALLOC_2_0', + 'SC_SC_SPI_DEALLOC_2_1', 'SC_SC_SPI_DEALLOC_2_2', + 'SC_SC_SPI_DEALLOC_3_0', 'SC_SC_SPI_DEALLOC_3_1', + 'SC_SC_SPI_DEALLOC_3_2', 'SC_SC_SPI_EVENT', 'SC_SC_SPI_FPOV_0', + 'SC_SC_SPI_FPOV_1', 'SC_SC_SPI_FPOV_2', 'SC_SC_SPI_FPOV_3', + 'SC_SEND_DB_VPZ', 'SC_SRPS_WINDOW_VALID', + 'SC_SRPS_WINDOW_VALID_BUSY', 'SC_STALLED_BY_BCI', + 'SC_STALLED_BY_DB_QUAD', 'SC_STALLED_BY_DB_TILE', + 'SC_STALLED_BY_PRIMFIFO', 'SC_STALLED_BY_QUADFIFO', + 'SC_STALLED_BY_SPI', 'SC_STALLED_BY_TILEFIFO', + 'SC_STALLED_BY_TILEORDERFIFO', 'SC_STARVED_BY_DB_QUAD', + 'SC_STARVED_BY_DB_TILE', 'SC_STARVED_BY_PA', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_FULL', + 'SC_STARVED_BY_PA_WITH_UNSELECTED_PA_NOT_EMPTY', + 'SC_SUPERTILE_COUNT', 'SC_SUPERTILE_PER_PRIM_H0', + 'SC_SUPERTILE_PER_PRIM_H1', 'SC_SUPERTILE_PER_PRIM_H10', + 'SC_SUPERTILE_PER_PRIM_H11', 'SC_SUPERTILE_PER_PRIM_H12', + 'SC_SUPERTILE_PER_PRIM_H13', 'SC_SUPERTILE_PER_PRIM_H14', + 'SC_SUPERTILE_PER_PRIM_H15', 'SC_SUPERTILE_PER_PRIM_H16', + 'SC_SUPERTILE_PER_PRIM_H2', 'SC_SUPERTILE_PER_PRIM_H3', + 'SC_SUPERTILE_PER_PRIM_H4', 'SC_SUPERTILE_PER_PRIM_H5', + 'SC_SUPERTILE_PER_PRIM_H6', 'SC_SUPERTILE_PER_PRIM_H7', + 'SC_SUPERTILE_PER_PRIM_H8', 'SC_SUPERTILE_PER_PRIM_H9', + 'SC_TILE_PER_PRIM_H0', 'SC_TILE_PER_PRIM_H1', + 'SC_TILE_PER_PRIM_H10', 'SC_TILE_PER_PRIM_H11', + 'SC_TILE_PER_PRIM_H12', 'SC_TILE_PER_PRIM_H13', + 'SC_TILE_PER_PRIM_H14', 'SC_TILE_PER_PRIM_H15', + 'SC_TILE_PER_PRIM_H16', 'SC_TILE_PER_PRIM_H2', + 'SC_TILE_PER_PRIM_H3', 'SC_TILE_PER_PRIM_H4', + 'SC_TILE_PER_PRIM_H5', 'SC_TILE_PER_PRIM_H6', + 'SC_TILE_PER_PRIM_H7', 'SC_TILE_PER_PRIM_H8', + 'SC_TILE_PER_PRIM_H9', 'SC_TILE_PER_SUPERTILE_H0', + 'SC_TILE_PER_SUPERTILE_H1', 'SC_TILE_PER_SUPERTILE_H10', + 'SC_TILE_PER_SUPERTILE_H11', 'SC_TILE_PER_SUPERTILE_H12', + 'SC_TILE_PER_SUPERTILE_H13', 'SC_TILE_PER_SUPERTILE_H14', + 'SC_TILE_PER_SUPERTILE_H15', 'SC_TILE_PER_SUPERTILE_H16', + 'SC_TILE_PER_SUPERTILE_H2', 'SC_TILE_PER_SUPERTILE_H3', + 'SC_TILE_PER_SUPERTILE_H4', 'SC_TILE_PER_SUPERTILE_H5', + 'SC_TILE_PER_SUPERTILE_H6', 'SC_TILE_PER_SUPERTILE_H7', + 'SC_TILE_PER_SUPERTILE_H8', 'SC_TILE_PER_SUPERTILE_H9', + 'SC_TILE_PICKED_H1', 'SC_TILE_PICKED_H2', 'SC_TILE_PICKED_H3', + 'SC_TILE_PICKED_H4', 'SC_TPQZ_WINDOW_VALID', + 'SC_TPQZ_WINDOW_VALID_BUSY', 'SC_TRPK_WINDOW_VALID', + 'SC_TRPK_WINDOW_VALID_BUSY', 'SDMA_PERF_SEL', + 'SDMA_PERF_SEL_ATCL2_FREE', 'SDMA_PERF_SEL_ATCL2_INVREQ_FLUSH', + 'SDMA_PERF_SEL_ATCL2_INVREQ_NFLUSH', + 'SDMA_PERF_SEL_ATCL2_RET_ACK', 'SDMA_PERF_SEL_ATCL2_RET_XNACK', + 'SDMA_PERF_SEL_CE_AFIFO_FULL', 'SDMA_PERF_SEL_CE_DST_IDLE', + 'SDMA_PERF_SEL_CE_INFO1_FULL', 'SDMA_PERF_SEL_CE_INFO_FULL', + 'SDMA_PERF_SEL_CE_IN_IDLE', 'SDMA_PERF_SEL_CE_L1_STALL', + 'SDMA_PERF_SEL_CE_L1_WR_VLD', 'SDMA_PERF_SEL_CE_OUT_IDLE', + 'SDMA_PERF_SEL_CE_RD_STALL', 'SDMA_PERF_SEL_CE_RREQ_IDLE', + 'SDMA_PERF_SEL_CE_SPLIT_IDLE', 'SDMA_PERF_SEL_CE_WREQ_IDLE', + 'SDMA_PERF_SEL_CE_WR_IDLE', 'SDMA_PERF_SEL_CE_WR_STALL', + 'SDMA_PERF_SEL_CTX_CHANGE', 'SDMA_PERF_SEL_CTX_CHANGE_EXCEPTION', + 'SDMA_PERF_SEL_CTX_CHANGE_EXPIRED', 'SDMA_PERF_SEL_CYCLE', + 'SDMA_PERF_SEL_DMA_L1_RD_SEND', 'SDMA_PERF_SEL_DMA_L1_WR_SEND', + 'SDMA_PERF_SEL_DMA_MC_RD_SEND', 'SDMA_PERF_SEL_DMA_MC_WR_SEND', + 'SDMA_PERF_SEL_DOORBELL', 'SDMA_PERF_SEL_EX_IDLE', + 'SDMA_PERF_SEL_EX_IDLE_POLL_TIMER_EXPIRE', + 'SDMA_PERF_SEL_F32_L1_WR_VLD', 'SDMA_PERF_SEL_GFX_SELECT', + 'SDMA_PERF_SEL_IB_CMD_FULL', 'SDMA_PERF_SEL_IB_CMD_IDLE', + 'SDMA_PERF_SEL_IDLE', 'SDMA_PERF_SEL_INT_IDLE', + 'SDMA_PERF_SEL_INT_REQ_COUNT', 'SDMA_PERF_SEL_INT_REQ_STALL', + 'SDMA_PERF_SEL_INT_RESP_ACCEPTED', 'SDMA_PERF_SEL_INT_RESP_RETRY', + 'SDMA_PERF_SEL_IS_INVREQ_ADDR_RD', + 'SDMA_PERF_SEL_IS_INVREQ_ADDR_WR', 'SDMA_PERF_SEL_L1_INV_MIDDLE', + 'SDMA_PERF_SEL_L1_RDL2_IDLE', 'SDMA_PERF_SEL_L1_RDMC_IDLE', + 'SDMA_PERF_SEL_L1_RD_FIFO_IDLE', 'SDMA_PERF_SEL_L1_RD_INV_EN', + 'SDMA_PERF_SEL_L1_RD_INV_IDLE', 'SDMA_PERF_SEL_L1_RD_WAIT_INVADR', + 'SDMA_PERF_SEL_L1_RD_XNACK_TIMEOUT', 'SDMA_PERF_SEL_L1_WRL2_IDLE', + 'SDMA_PERF_SEL_L1_WRMC_IDLE', 'SDMA_PERF_SEL_L1_WR_FIFO_IDLE', + 'SDMA_PERF_SEL_L1_WR_INV_EN', 'SDMA_PERF_SEL_L1_WR_INV_IDLE', + 'SDMA_PERF_SEL_L1_WR_WAIT_INVADR', + 'SDMA_PERF_SEL_L1_WR_XNACK_TIMEOUT', 'SDMA_PERF_SEL_MC_RD_COUNT', + 'SDMA_PERF_SEL_MC_RD_IDLE', 'SDMA_PERF_SEL_MC_RD_NO_POLL_IDLE', + 'SDMA_PERF_SEL_MC_RD_RET_STALL', 'SDMA_PERF_SEL_MC_WR_COUNT', + 'SDMA_PERF_SEL_MC_WR_IDLE', + 'SDMA_PERF_SEL_MMHUB_TAG_DELAY_COUNTER', + 'SDMA_PERF_SEL_NUM_PACKET', 'SDMA_PERF_SEL_PAGE_SELECT', + 'SDMA_PERF_SEL_RB_CMD_FULL', 'SDMA_PERF_SEL_RB_CMD_IDLE', + 'SDMA_PERF_SEL_RB_EMPTY', 'SDMA_PERF_SEL_RB_FULL', + 'SDMA_PERF_SEL_RB_RPTR_WB', 'SDMA_PERF_SEL_RB_RPTR_WRAP', + 'SDMA_PERF_SEL_RB_WPTR_POLL_READ', 'SDMA_PERF_SEL_RB_WPTR_WRAP', + 'SDMA_PERF_SEL_RD_BA_RTR', 'SDMA_PERF_SEL_REG_IDLE', + 'SDMA_PERF_SEL_RLC0_SELECT', 'SDMA_PERF_SEL_RLC1_SELECT', + 'SDMA_PERF_SEL_SDMA_ATCL2_SEND', + 'SDMA_PERF_SEL_SDMA_INVACK_FLUSH', + 'SDMA_PERF_SEL_SDMA_INVACK_NFLUSH', 'SDMA_PERF_SEL_SEM_IDLE', + 'SDMA_PERF_SEL_SEM_REQ_COUNT', 'SDMA_PERF_SEL_SEM_REQ_STALL', + 'SDMA_PERF_SEL_SEM_RESP_FAIL', + 'SDMA_PERF_SEL_SEM_RESP_INCOMPLETE', + 'SDMA_PERF_SEL_SEM_RESP_PASS', 'SDMA_PERF_SEL_SRBM_REG_SEND', + 'SDMA_PERF_SEL_UTCL1_TAG_DELAY_COUNTER', + 'SDMA_PERF_SEL_WR_BA_RTR', 'SEC_GSP0_PRIORITY_HIGH', + 'SEC_GSP0_PRIORITY_LOW', 'SEM_ECC_ERROR', 'SEM_FAILED', + 'SEM_PASSED', 'SEM_PERF_SEL', 'SEM_PERF_SEL_ACP_REQ_SIGNAL', + 'SEM_PERF_SEL_ACP_REQ_WAIT', 'SEM_PERF_SEL_ATC_INVALIDATION', + 'SEM_PERF_SEL_ATC_REQ', 'SEM_PERF_SEL_ATC_RET', + 'SEM_PERF_SEL_ATC_XNACK', 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC1_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC1_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_SIGNAL', + 'SEM_PERF_SEL_CPC2_IMME_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E10_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E11_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E12_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E13_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E14_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E15_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E16_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E17_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E18_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E19_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E1_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E20_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E21_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E22_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E23_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E24_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E25_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E26_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E27_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E28_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E29_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E2_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E30_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E31_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E3_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E4_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E5_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E6_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E7_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E8_REQ_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_POLL_WAIT', + 'SEM_PERF_SEL_CPC2_OFFL_E9_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E0_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E0_REQ_WAIT', + 'SEM_PERF_SEL_CPG_E1_REQ_SIGNAL', 'SEM_PERF_SEL_CPG_E1_REQ_WAIT', + 'SEM_PERF_SEL_CYCLE', 'SEM_PERF_SEL_IDLE', + 'SEM_PERF_SEL_ISP_REQ_SIGNAL', 'SEM_PERF_SEL_ISP_REQ_WAIT', + 'SEM_PERF_SEL_MC_RD_REQ', 'SEM_PERF_SEL_MC_RD_RET', + 'SEM_PERF_SEL_MC_WR_REQ', 'SEM_PERF_SEL_MC_WR_RET', + 'SEM_PERF_SEL_SDMA0_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA0_REQ_WAIT', + 'SEM_PERF_SEL_SDMA1_REQ_SIGNAL', 'SEM_PERF_SEL_SDMA1_REQ_WAIT', + 'SEM_PERF_SEL_UVD_REQ_SIGNAL', 'SEM_PERF_SEL_UVD_REQ_WAIT', + 'SEM_PERF_SEL_VCE0_REQ_SIGNAL', 'SEM_PERF_SEL_VCE0_REQ_WAIT', + 'SEM_PERF_SEL_VCE1_REQ_SIGNAL', 'SEM_PERF_SEL_VCE1_REQ_WAIT', + 'SEM_PERF_SEL_VP8_REQ_SIGNAL', 'SEM_PERF_SEL_VP8_REQ_WAIT', + 'SEM_TRANS_ERROR', 'SET_OVERRIDE_CGTT_DCEFCLK', + 'SET_OVERRIDE_CGTT_SCLK', 'SET_STATIC_SCREEN_SMU_INTR', + 'SH_MEM_ADDRESS_MODE', 'SH_MEM_ADDRESS_MODE_32', + 'SH_MEM_ADDRESS_MODE_64', 'SH_MEM_ALIGNMENT_MODE', + 'SH_MEM_ALIGNMENT_MODE_DWORD', + 'SH_MEM_ALIGNMENT_MODE_DWORD_STRICT', + 'SH_MEM_ALIGNMENT_MODE_STRICT', 'SH_MEM_ALIGNMENT_MODE_UNALIGNED', + 'SIMM16_WAITCNT_EXP_CNT_SIZE', 'SIMM16_WAITCNT_EXP_CNT_START', + 'SIMM16_WAITCNT_LGKM_CNT_SIZE', 'SIMM16_WAITCNT_LGKM_CNT_START', + 'SIMM16_WAITCNT_VM_CNT_HI_SIZE', 'SIMM16_WAITCNT_VM_CNT_HI_START', + 'SIMM16_WAITCNT_VM_CNT_SIZE', 'SIMM16_WAITCNT_VM_CNT_START', + 'SMU_INTR_STATUS_CLEAR', 'SMU_INTR_STATUS_NOOP', + 'SM_MODE_RESERVED', 'SO_VGTSTREAMOUT_FLUSH', 'SPDIF1_SOFT_RESET', + 'SPDIF1_SOFT_RESET_0', 'SPDIF1_SOFT_RESET_1', + 'SPDIF_INVERT_DISABLE', 'SPDIF_INVERT_EN', 'SPDIF_INVERT_ENABLE', + 'SPI_FOG_EXP', 'SPI_FOG_EXP2', 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', + 'SPI_FOG_NONE', 'SPI_PERFCNT_SEL', + 'SPI_PERF_CLKGATE_ACTIVE_STALL', 'SPI_PERF_CLKGATE_ALL_CLOCKS_ON', + 'SPI_PERF_CLKGATE_BUSY_STALL', 'SPI_PERF_CLKGATE_CGTT_DYN_ON', + 'SPI_PERF_CLKGATE_CGTT_REG_ON', 'SPI_PERF_CSG_BUSY', + 'SPI_PERF_CSG_CRAWLER_STALL', 'SPI_PERF_CSG_EVENT_WAVE', + 'SPI_PERF_CSG_NUM_THREADGROUPS', 'SPI_PERF_CSG_WAVE', + 'SPI_PERF_CSG_WINDOW_VALID', 'SPI_PERF_CSN_BUSY', + 'SPI_PERF_CSN_CRAWLER_STALL', 'SPI_PERF_CSN_EVENT_WAVE', + 'SPI_PERF_CSN_NUM_THREADGROUPS', 'SPI_PERF_CSN_WAVE', + 'SPI_PERF_CSN_WINDOW_VALID', 'SPI_PERF_ES_BUSY', + 'SPI_PERF_ES_CRAWLER_STALL', 'SPI_PERF_ES_EVENT_WAVE', + 'SPI_PERF_ES_FIRST_SUBGRP', 'SPI_PERF_ES_FIRST_WAVE', + 'SPI_PERF_ES_GRP_FIFO_FULL', 'SPI_PERF_ES_LAST_SUBGRP', + 'SPI_PERF_ES_LAST_WAVE', 'SPI_PERF_ES_LSHS_DEALLOC', + 'SPI_PERF_ES_PERS_UPD_FULL0', 'SPI_PERF_ES_PERS_UPD_FULL1', + 'SPI_PERF_ES_WAVE', 'SPI_PERF_ES_WINDOW_VALID', + 'SPI_PERF_EXP_ARB_COL_CNT', 'SPI_PERF_EXP_ARB_GDS_CNT', + 'SPI_PERF_EXP_ARB_PAR_CNT', 'SPI_PERF_EXP_ARB_POS_CNT', + 'SPI_PERF_GS_BUSY', 'SPI_PERF_GS_CRAWLER_STALL', + 'SPI_PERF_GS_EVENT_WAVE', 'SPI_PERF_GS_FIRST_SUBGRP', + 'SPI_PERF_GS_GRP_FIFO_FULL', 'SPI_PERF_GS_LAST_SUBGRP', + 'SPI_PERF_GS_PERS_UPD_FULL0', 'SPI_PERF_GS_PERS_UPD_FULL1', + 'SPI_PERF_GS_WAVE', 'SPI_PERF_GS_WINDOW_VALID', + 'SPI_PERF_HS_BUSY', 'SPI_PERF_HS_CRAWLER_STALL', + 'SPI_PERF_HS_EVENT_WAVE', 'SPI_PERF_HS_FIRST_WAVE', + 'SPI_PERF_HS_GRP_FIFO_FULL', 'SPI_PERF_HS_LAST_WAVE', + 'SPI_PERF_HS_LSHS_DEALLOC', 'SPI_PERF_HS_PERS_UPD_FULL0', + 'SPI_PERF_HS_PERS_UPD_FULL1', 'SPI_PERF_HS_WAVE', + 'SPI_PERF_HS_WINDOW_VALID', 'SPI_PERF_LDS0_PC_VALID', + 'SPI_PERF_LDS1_PC_VALID', 'SPI_PERF_LS_BUSY', + 'SPI_PERF_LS_CRAWLER_STALL', 'SPI_PERF_LS_EVENT_WAVE', + 'SPI_PERF_LS_FIRST_WAVE', 'SPI_PERF_LS_GRP_FIFO_FULL', + 'SPI_PERF_LS_LAST_WAVE', 'SPI_PERF_LS_PERS_UPD_FULL0', + 'SPI_PERF_LS_PERS_UPD_FULL1', 'SPI_PERF_LS_WAVE', + 'SPI_PERF_LS_WINDOW_VALID', 'SPI_PERF_NUM_PS_COL_EXPORTS', + 'SPI_PERF_NUM_VS_PARAM_EXPORTS', 'SPI_PERF_NUM_VS_POS_EXPORTS', + 'SPI_PERF_OFFCHIP_LDS_STALL_LS', 'SPI_PERF_PC_ALLOC_ACCUM', + 'SPI_PERF_PC_ALLOC_CNT', 'SPI_PERF_PIX_ALLOC_DB0_STALL', + 'SPI_PERF_PIX_ALLOC_DB1_STALL', 'SPI_PERF_PIX_ALLOC_DB2_STALL', + 'SPI_PERF_PIX_ALLOC_DB3_STALL', 'SPI_PERF_PIX_ALLOC_PEND_CNT', + 'SPI_PERF_PIX_ALLOC_SCB_STALL', 'SPI_PERF_PS_CTL_ACTIVE', + 'SPI_PERF_PS_CTL_BUSY', 'SPI_PERF_PS_CTL_CNF_BIN2', + 'SPI_PERF_PS_CTL_CNF_BIN3', 'SPI_PERF_PS_CTL_CRAWLER_STALL', + 'SPI_PERF_PS_CTL_DEALLOC_BIN0', 'SPI_PERF_PS_CTL_EVENT_WAVE', + 'SPI_PERF_PS_CTL_FPOS_BIN1_STALL', 'SPI_PERF_PS_CTL_FPOS_BIN2', + 'SPI_PERF_PS_CTL_LDS_RES_FULL', 'SPI_PERF_PS_CTL_OPT_WAVE', + 'SPI_PERF_PS_CTL_PASS_BIN0', 'SPI_PERF_PS_CTL_PASS_BIN1', + 'SPI_PERF_PS_CTL_PRIM_BIN0', 'SPI_PERF_PS_CTL_PRIM_BIN1', + 'SPI_PERF_PS_CTL_WAVE', 'SPI_PERF_PS_CTL_WINDOW_VALID', + 'SPI_PERF_PS_PERS_UPD_FULL0', 'SPI_PERF_PS_PERS_UPD_FULL1', + 'SPI_PERF_RA_BAR_CU_FULL_CSG', 'SPI_PERF_RA_BAR_CU_FULL_CSN', + 'SPI_PERF_RA_BAR_CU_FULL_HS', 'SPI_PERF_RA_BULKY_CU_FULL_CSG', + 'SPI_PERF_RA_BULKY_CU_FULL_CSN', 'SPI_PERF_RA_CSG_LOCK', + 'SPI_PERF_RA_CSN_LOCK', 'SPI_PERF_RA_ES_LOCK', + 'SPI_PERF_RA_GS_LOCK', 'SPI_PERF_RA_HS_LOCK', + 'SPI_PERF_RA_LDS_CU_FULL_CSG', 'SPI_PERF_RA_LDS_CU_FULL_CSN', + 'SPI_PERF_RA_LDS_CU_FULL_ES', 'SPI_PERF_RA_LDS_CU_FULL_LS', + 'SPI_PERF_RA_LDS_CU_FULL_PS', 'SPI_PERF_RA_LS_LOCK', + 'SPI_PERF_RA_PIPE_REQ_BIN2', 'SPI_PERF_RA_PS_LOCK_NA', + 'SPI_PERF_RA_REQ_NO_ALLOC', 'SPI_PERF_RA_REQ_NO_ALLOC_CSG', + 'SPI_PERF_RA_REQ_NO_ALLOC_CSN', 'SPI_PERF_RA_REQ_NO_ALLOC_ES', + 'SPI_PERF_RA_REQ_NO_ALLOC_GS', 'SPI_PERF_RA_REQ_NO_ALLOC_HS', + 'SPI_PERF_RA_REQ_NO_ALLOC_LS', 'SPI_PERF_RA_REQ_NO_ALLOC_PS', + 'SPI_PERF_RA_REQ_NO_ALLOC_VS', 'SPI_PERF_RA_RES_STALL_CSG', + 'SPI_PERF_RA_RES_STALL_CSN', 'SPI_PERF_RA_RES_STALL_ES', + 'SPI_PERF_RA_RES_STALL_GS', 'SPI_PERF_RA_RES_STALL_HS', + 'SPI_PERF_RA_RES_STALL_LS', 'SPI_PERF_RA_RES_STALL_PS', + 'SPI_PERF_RA_RES_STALL_VS', 'SPI_PERF_RA_RSV_UPD', + 'SPI_PERF_RA_SGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_SGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_SGPR_SIMD_FULL_ES', + 'SPI_PERF_RA_SGPR_SIMD_FULL_GS', 'SPI_PERF_RA_SGPR_SIMD_FULL_HS', + 'SPI_PERF_RA_SGPR_SIMD_FULL_LS', 'SPI_PERF_RA_SGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_SGPR_SIMD_FULL_VS', 'SPI_PERF_RA_TASK_REQ_BIN3', + 'SPI_PERF_RA_TGLIM_CU_FULL_CSG', 'SPI_PERF_RA_TGLIM_CU_FULL_CSN', + 'SPI_PERF_RA_TMP_STALL_CSG', 'SPI_PERF_RA_TMP_STALL_CSN', + 'SPI_PERF_RA_TMP_STALL_ES', 'SPI_PERF_RA_TMP_STALL_GS', + 'SPI_PERF_RA_TMP_STALL_HS', 'SPI_PERF_RA_TMP_STALL_LS', + 'SPI_PERF_RA_TMP_STALL_PS', 'SPI_PERF_RA_TMP_STALL_VS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSG', + 'SPI_PERF_RA_VGPR_SIMD_FULL_CSN', 'SPI_PERF_RA_VGPR_SIMD_FULL_ES', + 'SPI_PERF_RA_VGPR_SIMD_FULL_GS', 'SPI_PERF_RA_VGPR_SIMD_FULL_HS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_LS', 'SPI_PERF_RA_VGPR_SIMD_FULL_PS', + 'SPI_PERF_RA_VGPR_SIMD_FULL_VS', 'SPI_PERF_RA_VS_LOCK', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSG', + 'SPI_PERF_RA_WAVE_SIMD_FULL_CSN', 'SPI_PERF_RA_WAVE_SIMD_FULL_ES', + 'SPI_PERF_RA_WAVE_SIMD_FULL_GS', 'SPI_PERF_RA_WAVE_SIMD_FULL_HS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_LS', 'SPI_PERF_RA_WAVE_SIMD_FULL_PS', + 'SPI_PERF_RA_WAVE_SIMD_FULL_VS', 'SPI_PERF_RA_WR_CTL_FULL', + 'SPI_PERF_RA_WVLIM_STALL_CSG', 'SPI_PERF_RA_WVLIM_STALL_CSN', + 'SPI_PERF_RA_WVLIM_STALL_ES', 'SPI_PERF_RA_WVLIM_STALL_GS', + 'SPI_PERF_RA_WVLIM_STALL_HS', 'SPI_PERF_RA_WVLIM_STALL_LS', + 'SPI_PERF_RA_WVLIM_STALL_PS', 'SPI_PERF_RA_WVLIM_STALL_VS', + 'SPI_PERF_VS_ALLOC_CNT', 'SPI_PERF_VS_BUSY', + 'SPI_PERF_VS_CRAWLER_STALL', 'SPI_PERF_VS_EVENT_WAVE', + 'SPI_PERF_VS_FIRST_SUBGRP', 'SPI_PERF_VS_FIRST_WAVE', + 'SPI_PERF_VS_LAST_SUBGRP', 'SPI_PERF_VS_LAST_WAVE', + 'SPI_PERF_VS_LATE_ALLOC_ACCUM', 'SPI_PERF_VS_LATE_ALLOC_FULL', + 'SPI_PERF_VS_LSHS_DEALLOC', 'SPI_PERF_VS_PC_STALL', + 'SPI_PERF_VS_PERS_UPD_FULL0', 'SPI_PERF_VS_PERS_UPD_FULL1', + 'SPI_PERF_VS_POS0_STALL', 'SPI_PERF_VS_POS1_STALL', + 'SPI_PERF_VS_WAVE', 'SPI_PERF_VS_WINDOW_VALID', + 'SPI_PNT_SPRITE_OVERRIDE', 'SPI_PNT_SPRITE_SEL_0', + 'SPI_PNT_SPRITE_SEL_1', 'SPI_PNT_SPRITE_SEL_NONE', + 'SPI_PNT_SPRITE_SEL_S', 'SPI_PNT_SPRITE_SEL_T', 'SPI_SAMPLE_CNTL', + 'SPI_SHADER_1COMP', 'SPI_SHADER_2COMP', 'SPI_SHADER_32_ABGR', + 'SPI_SHADER_32_AR', 'SPI_SHADER_32_GR', 'SPI_SHADER_32_R', + 'SPI_SHADER_4COMP', 'SPI_SHADER_4COMPRESS', + 'SPI_SHADER_EX_FORMAT', 'SPI_SHADER_FORMAT', + 'SPI_SHADER_FP16_ABGR', 'SPI_SHADER_NONE', + 'SPI_SHADER_SINT16_ABGR', 'SPI_SHADER_SNORM16_ABGR', + 'SPI_SHADER_UINT16_ABGR', 'SPI_SHADER_UNORM16_ABGR', + 'SPI_SHADER_ZERO', 'SPM_PERFMON_STATE', 'SPRITE_EN', + 'SQC_PERF_SEL_DCACHE_ATOMIC', 'SQC_PERF_SEL_DCACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_DCACHE_CACHE_STALLED', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_ALLOC_UNAVAILABLE', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_EVICT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FLUSH_DONE', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_FORCE_EVICT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_MULTI_FLUSH', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_OUTPUT_TC_IF', + 'SQC_PERF_SEL_DCACHE_CACHE_STALL_UNORDERED', + 'SQC_PERF_SEL_DCACHE_FLAT_REQ', + 'SQC_PERF_SEL_DCACHE_GATCL1_ATCL2_INFLIGHT', + 'SQC_PERF_SEL_DCACHE_GATCL1_HIT_FIFO_FULL', + 'SQC_PERF_SEL_DCACHE_GATCL1_LFIFO_FULL', + 'SQC_PERF_SEL_DCACHE_GATCL1_PERMISSION_MISS', + 'SQC_PERF_SEL_DCACHE_GATCL1_REQUEST', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_LFIFO_NOT_RES', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_LRU_INFLIGHT', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_MISSFIFO_FULL', + 'SQC_PERF_SEL_DCACHE_GATCL1_STALL_MULTI_MISS', + 'SQC_PERF_SEL_DCACHE_GATCL1_TRANSLATION_MISS', + 'SQC_PERF_SEL_DCACHE_HITS', 'SQC_PERF_SEL_DCACHE_HIT_LRU_READ', + 'SQC_PERF_SEL_DCACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALIDB', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READY', + 'SQC_PERF_SEL_DCACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_DCACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_DCACHE_INVAL_INST', + 'SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_ASYNC', + 'SQC_PERF_SEL_DCACHE_INVAL_VOLATILE_INST', + 'SQC_PERF_SEL_DCACHE_MISSES', + 'SQC_PERF_SEL_DCACHE_MISSES_DUPLICATE', + 'SQC_PERF_SEL_DCACHE_MISS_EVICT_READ', + 'SQC_PERF_SEL_DCACHE_NONFLAT_REQ', 'SQC_PERF_SEL_DCACHE_REQ', + 'SQC_PERF_SEL_DCACHE_REQ_ATC_PROBE', + 'SQC_PERF_SEL_DCACHE_REQ_READ_1', + 'SQC_PERF_SEL_DCACHE_REQ_READ_16', + 'SQC_PERF_SEL_DCACHE_REQ_READ_2', + 'SQC_PERF_SEL_DCACHE_REQ_READ_4', + 'SQC_PERF_SEL_DCACHE_REQ_READ_8', 'SQC_PERF_SEL_DCACHE_REQ_TIME', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_1', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_2', + 'SQC_PERF_SEL_DCACHE_REQ_WRITE_4', + 'SQC_PERF_SEL_DCACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_DCACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_DCACHE_VOLATILE', 'SQC_PERF_SEL_DCACHE_WB_ASYNC', + 'SQC_PERF_SEL_DCACHE_WB_INST', + 'SQC_PERF_SEL_DCACHE_WB_VOLATILE_ASYNC', + 'SQC_PERF_SEL_DCACHE_WB_VOLATILE_INST', + 'SQC_PERF_SEL_DCACHE_WC_LRU_WRITE', + 'SQC_PERF_SEL_DCACHE_WT_EVICT_WRITE', 'SQC_PERF_SEL_DUMMY_LAST', + 'SQC_PERF_SEL_ICACHE_BUSY_CYCLES', + 'SQC_PERF_SEL_ICACHE_CACHE_STALLED', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_INFLIGHT_NONZERO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_HIT_FIFO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_MISS_FIFO', + 'SQC_PERF_SEL_ICACHE_CACHE_STALL_OUTPUT_TC_IF', + 'SQC_PERF_SEL_ICACHE_GATCL1_ATCL2_INFLIGHT', + 'SQC_PERF_SEL_ICACHE_GATCL1_LFIFO_FULL', + 'SQC_PERF_SEL_ICACHE_GATCL1_PERMISSION_MISS', + 'SQC_PERF_SEL_ICACHE_GATCL1_REQUEST', + 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_ATCL2_REQ_OUT_OF_CREDITS', + 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_INFLIGHT_MAX', + 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_LFIFO_NOT_RES', + 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_LRU_INFLIGHT', + 'SQC_PERF_SEL_ICACHE_GATCL1_STALL_MISSFIFO_FULL', + 'SQC_PERF_SEL_ICACHE_GATCL1_TRANSLATION_MISS', + 'SQC_PERF_SEL_ICACHE_HITS', 'SQC_PERF_SEL_ICACHE_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_INPUT_STALL_BANK_READYB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALIDB', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READY', + 'SQC_PERF_SEL_ICACHE_INPUT_VALID_READYB', + 'SQC_PERF_SEL_ICACHE_INVAL_ASYNC', + 'SQC_PERF_SEL_ICACHE_INVAL_INST', 'SQC_PERF_SEL_ICACHE_MISSES', + 'SQC_PERF_SEL_ICACHE_MISSES_DUPLICATE', + 'SQC_PERF_SEL_ICACHE_PREFETCH_1', + 'SQC_PERF_SEL_ICACHE_PREFETCH_2', + 'SQC_PERF_SEL_ICACHE_PREFETCH_FILTERED', + 'SQC_PERF_SEL_ICACHE_REQ', + 'SQC_PERF_SEL_ICACHE_STALL_OUTXBAR_ARB_NO_GRANT', + 'SQC_PERF_SEL_ICACHE_TC_INFLIGHT_LEVEL', + 'SQC_PERF_SEL_SQ_DCACHE_REQS', 'SQC_PERF_SEL_TC_DATA_ATOMIC_REQ', + 'SQC_PERF_SEL_TC_DATA_READ_REQ', 'SQC_PERF_SEL_TC_DATA_WRITE_REQ', + 'SQC_PERF_SEL_TC_INFLIGHT_LEVEL', 'SQC_PERF_SEL_TC_INST_REQ', + 'SQC_PERF_SEL_TC_REQ', 'SQC_PERF_SEL_TC_STALL', + 'SQC_PERF_SEL_TC_STARVE', 'SQDEC_BEGIN', 'SQDEC_END', + 'SQGFXUDEC_BEGIN', 'SQGFXUDEC_END', 'SQIND_GLOBAL_REGS_OFFSET', + 'SQIND_GLOBAL_REGS_SIZE', 'SQIND_LOCAL_REGS_OFFSET', + 'SQIND_LOCAL_REGS_SIZE', 'SQIND_WAVE_HWREGS_OFFSET', + 'SQIND_WAVE_HWREGS_SIZE', 'SQIND_WAVE_SGPRS_OFFSET', + 'SQIND_WAVE_SGPRS_SIZE', 'SQIND_WAVE_VGPRS_OFFSET', + 'SQIND_WAVE_VGPRS_SIZE', 'SQPERFDDEC_BEGIN', 'SQPERFDDEC_END', + 'SQPERFSDEC_BEGIN', 'SQPERFSDEC_END', 'SQPWRDEC_BEGIN', + 'SQPWRDEC_END', 'SQ_ATTR0', 'SQ_BUFFER_ATOMIC_ADD', + 'SQ_BUFFER_ATOMIC_ADD_X2', 'SQ_BUFFER_ATOMIC_AND', + 'SQ_BUFFER_ATOMIC_AND_X2', 'SQ_BUFFER_ATOMIC_CMPSWAP', + 'SQ_BUFFER_ATOMIC_CMPSWAP_X2', 'SQ_BUFFER_ATOMIC_DEC', + 'SQ_BUFFER_ATOMIC_DEC_X2', 'SQ_BUFFER_ATOMIC_INC', + 'SQ_BUFFER_ATOMIC_INC_X2', 'SQ_BUFFER_ATOMIC_OR', + 'SQ_BUFFER_ATOMIC_OR_X2', 'SQ_BUFFER_ATOMIC_SMAX', + 'SQ_BUFFER_ATOMIC_SMAX_X2', 'SQ_BUFFER_ATOMIC_SMIN', + 'SQ_BUFFER_ATOMIC_SMIN_X2', 'SQ_BUFFER_ATOMIC_SUB', + 'SQ_BUFFER_ATOMIC_SUB_X2', 'SQ_BUFFER_ATOMIC_SWAP', + 'SQ_BUFFER_ATOMIC_SWAP_X2', 'SQ_BUFFER_ATOMIC_UMAX', + 'SQ_BUFFER_ATOMIC_UMAX_X2', 'SQ_BUFFER_ATOMIC_UMIN', + 'SQ_BUFFER_ATOMIC_UMIN_X2', 'SQ_BUFFER_ATOMIC_XOR', + 'SQ_BUFFER_ATOMIC_XOR_X2', 'SQ_BUFFER_LOAD_DWORD', + 'SQ_BUFFER_LOAD_DWORDX2', 'SQ_BUFFER_LOAD_DWORDX3', + 'SQ_BUFFER_LOAD_DWORDX4', 'SQ_BUFFER_LOAD_FORMAT_D16_X', + 'SQ_BUFFER_LOAD_FORMAT_D16_XY', 'SQ_BUFFER_LOAD_FORMAT_D16_XYZ', + 'SQ_BUFFER_LOAD_FORMAT_D16_XYZW', 'SQ_BUFFER_LOAD_FORMAT_X', + 'SQ_BUFFER_LOAD_FORMAT_XY', 'SQ_BUFFER_LOAD_FORMAT_XYZ', + 'SQ_BUFFER_LOAD_FORMAT_XYZW', 'SQ_BUFFER_LOAD_SBYTE', + 'SQ_BUFFER_LOAD_SSHORT', 'SQ_BUFFER_LOAD_UBYTE', + 'SQ_BUFFER_LOAD_USHORT', 'SQ_BUFFER_STORE_BYTE', + 'SQ_BUFFER_STORE_DWORD', 'SQ_BUFFER_STORE_DWORDX2', + 'SQ_BUFFER_STORE_DWORDX3', 'SQ_BUFFER_STORE_DWORDX4', + 'SQ_BUFFER_STORE_FORMAT_D16_X', 'SQ_BUFFER_STORE_FORMAT_D16_XY', + 'SQ_BUFFER_STORE_FORMAT_D16_XYZ', + 'SQ_BUFFER_STORE_FORMAT_D16_XYZW', 'SQ_BUFFER_STORE_FORMAT_X', + 'SQ_BUFFER_STORE_FORMAT_XY', 'SQ_BUFFER_STORE_FORMAT_XYZ', + 'SQ_BUFFER_STORE_FORMAT_XYZW', 'SQ_BUFFER_STORE_LDS_DWORD', + 'SQ_BUFFER_STORE_SHORT', 'SQ_BUFFER_WBINVL1', + 'SQ_BUFFER_WBINVL1_VOL', 'SQ_CAC_POWER_ALU_BUSY', + 'SQ_CAC_POWER_GPR_RD', 'SQ_CAC_POWER_GPR_WR', + 'SQ_CAC_POWER_LDS_BUSY', 'SQ_CAC_POWER_SEL', + 'SQ_CAC_POWER_TEX_BUSY', 'SQ_CAC_POWER_VALU', + 'SQ_CAC_POWER_VALU0', 'SQ_CAC_POWER_VALU1', 'SQ_CAC_POWER_VALU2', + 'SQ_CHAN_W', 'SQ_CHAN_X', 'SQ_CHAN_Y', 'SQ_CHAN_Z', 'SQ_CNT1', + 'SQ_CNT2', 'SQ_CNT3', 'SQ_CNT4', 'SQ_DISPATCHER_GFX_CNT_PER_RING', + 'SQ_DISPATCHER_GFX_MIN', 'SQ_DPP_BOUND_OFF', 'SQ_DPP_BOUND_ZERO', + 'SQ_DPP_QUAD_PERM', 'SQ_DPP_ROW_BCAST15', 'SQ_DPP_ROW_BCAST31', + 'SQ_DPP_ROW_HALF_MIRROR', 'SQ_DPP_ROW_MIRROR', 'SQ_DPP_ROW_RR1', + 'SQ_DPP_ROW_RR10', 'SQ_DPP_ROW_RR11', 'SQ_DPP_ROW_RR12', + 'SQ_DPP_ROW_RR13', 'SQ_DPP_ROW_RR14', 'SQ_DPP_ROW_RR15', + 'SQ_DPP_ROW_RR2', 'SQ_DPP_ROW_RR3', 'SQ_DPP_ROW_RR4', + 'SQ_DPP_ROW_RR5', 'SQ_DPP_ROW_RR6', 'SQ_DPP_ROW_RR7', + 'SQ_DPP_ROW_RR8', 'SQ_DPP_ROW_RR9', 'SQ_DPP_ROW_SL1', + 'SQ_DPP_ROW_SL10', 'SQ_DPP_ROW_SL11', 'SQ_DPP_ROW_SL12', + 'SQ_DPP_ROW_SL13', 'SQ_DPP_ROW_SL14', 'SQ_DPP_ROW_SL15', + 'SQ_DPP_ROW_SL2', 'SQ_DPP_ROW_SL3', 'SQ_DPP_ROW_SL4', + 'SQ_DPP_ROW_SL5', 'SQ_DPP_ROW_SL6', 'SQ_DPP_ROW_SL7', + 'SQ_DPP_ROW_SL8', 'SQ_DPP_ROW_SL9', 'SQ_DPP_ROW_SR1', + 'SQ_DPP_ROW_SR10', 'SQ_DPP_ROW_SR11', 'SQ_DPP_ROW_SR12', + 'SQ_DPP_ROW_SR13', 'SQ_DPP_ROW_SR14', 'SQ_DPP_ROW_SR15', + 'SQ_DPP_ROW_SR2', 'SQ_DPP_ROW_SR3', 'SQ_DPP_ROW_SR4', + 'SQ_DPP_ROW_SR5', 'SQ_DPP_ROW_SR6', 'SQ_DPP_ROW_SR7', + 'SQ_DPP_ROW_SR8', 'SQ_DPP_ROW_SR9', 'SQ_DPP_WF_RL1', + 'SQ_DPP_WF_RR1', 'SQ_DPP_WF_SL1', 'SQ_DPP_WF_SR1', + 'SQ_DS_ADD_F32', 'SQ_DS_ADD_RTN_F32', 'SQ_DS_ADD_RTN_U32', + 'SQ_DS_ADD_RTN_U64', 'SQ_DS_ADD_SRC2_F32', 'SQ_DS_ADD_SRC2_U32', + 'SQ_DS_ADD_SRC2_U64', 'SQ_DS_ADD_U32', 'SQ_DS_ADD_U64', + 'SQ_DS_AND_B32', 'SQ_DS_AND_B64', 'SQ_DS_AND_RTN_B32', + 'SQ_DS_AND_RTN_B64', 'SQ_DS_AND_SRC2_B32', 'SQ_DS_AND_SRC2_B64', + 'SQ_DS_APPEND', 'SQ_DS_BPERMUTE_B32', 'SQ_DS_CMPST_B32', + 'SQ_DS_CMPST_B64', 'SQ_DS_CMPST_F32', 'SQ_DS_CMPST_F64', + 'SQ_DS_CMPST_RTN_B32', 'SQ_DS_CMPST_RTN_B64', + 'SQ_DS_CMPST_RTN_F32', 'SQ_DS_CMPST_RTN_F64', + 'SQ_DS_CONDXCHG32_RTN_B128', 'SQ_DS_CONDXCHG32_RTN_B64', + 'SQ_DS_CONSUME', 'SQ_DS_DEC_RTN_U32', 'SQ_DS_DEC_RTN_U64', + 'SQ_DS_DEC_SRC2_U32', 'SQ_DS_DEC_SRC2_U64', 'SQ_DS_DEC_U32', + 'SQ_DS_DEC_U64', 'SQ_DS_GWS_BARRIER', 'SQ_DS_GWS_INIT', + 'SQ_DS_GWS_SEMA_BR', 'SQ_DS_GWS_SEMA_P', + 'SQ_DS_GWS_SEMA_RELEASE_ALL', 'SQ_DS_GWS_SEMA_V', + 'SQ_DS_INC_RTN_U32', 'SQ_DS_INC_RTN_U64', 'SQ_DS_INC_SRC2_U32', + 'SQ_DS_INC_SRC2_U64', 'SQ_DS_INC_U32', 'SQ_DS_INC_U64', + 'SQ_DS_MAX_F32', 'SQ_DS_MAX_F64', 'SQ_DS_MAX_I32', + 'SQ_DS_MAX_I64', 'SQ_DS_MAX_RTN_F32', 'SQ_DS_MAX_RTN_F64', + 'SQ_DS_MAX_RTN_I32', 'SQ_DS_MAX_RTN_I64', 'SQ_DS_MAX_RTN_U32', + 'SQ_DS_MAX_RTN_U64', 'SQ_DS_MAX_SRC2_F32', 'SQ_DS_MAX_SRC2_F64', + 'SQ_DS_MAX_SRC2_I32', 'SQ_DS_MAX_SRC2_I64', 'SQ_DS_MAX_SRC2_U32', + 'SQ_DS_MAX_SRC2_U64', 'SQ_DS_MAX_U32', 'SQ_DS_MAX_U64', + 'SQ_DS_MIN_F32', 'SQ_DS_MIN_F64', 'SQ_DS_MIN_I32', + 'SQ_DS_MIN_I64', 'SQ_DS_MIN_RTN_F32', 'SQ_DS_MIN_RTN_F64', + 'SQ_DS_MIN_RTN_I32', 'SQ_DS_MIN_RTN_I64', 'SQ_DS_MIN_RTN_U32', + 'SQ_DS_MIN_RTN_U64', 'SQ_DS_MIN_SRC2_F32', 'SQ_DS_MIN_SRC2_F64', + 'SQ_DS_MIN_SRC2_I32', 'SQ_DS_MIN_SRC2_I64', 'SQ_DS_MIN_SRC2_U32', + 'SQ_DS_MIN_SRC2_U64', 'SQ_DS_MIN_U32', 'SQ_DS_MIN_U64', + 'SQ_DS_MSKOR_B32', 'SQ_DS_MSKOR_B64', 'SQ_DS_MSKOR_RTN_B32', + 'SQ_DS_MSKOR_RTN_B64', 'SQ_DS_NOP', 'SQ_DS_ORDERED_COUNT', + 'SQ_DS_OR_B32', 'SQ_DS_OR_B64', 'SQ_DS_OR_RTN_B32', + 'SQ_DS_OR_RTN_B64', 'SQ_DS_OR_SRC2_B32', 'SQ_DS_OR_SRC2_B64', + 'SQ_DS_PERMUTE_B32', 'SQ_DS_READ2ST64_B32', 'SQ_DS_READ2ST64_B64', + 'SQ_DS_READ2_B32', 'SQ_DS_READ2_B64', 'SQ_DS_READ_ADDTID_B32', + 'SQ_DS_READ_B128', 'SQ_DS_READ_B32', 'SQ_DS_READ_B64', + 'SQ_DS_READ_B96', 'SQ_DS_READ_I16', 'SQ_DS_READ_I8', + 'SQ_DS_READ_U16', 'SQ_DS_READ_U8', 'SQ_DS_RSUB_RTN_U32', + 'SQ_DS_RSUB_RTN_U64', 'SQ_DS_RSUB_SRC2_U32', + 'SQ_DS_RSUB_SRC2_U64', 'SQ_DS_RSUB_U32', 'SQ_DS_RSUB_U64', + 'SQ_DS_SUB_RTN_U32', 'SQ_DS_SUB_RTN_U64', 'SQ_DS_SUB_SRC2_U32', + 'SQ_DS_SUB_SRC2_U64', 'SQ_DS_SUB_U32', 'SQ_DS_SUB_U64', + 'SQ_DS_SWIZZLE_B32', 'SQ_DS_WRAP_RTN_B32', 'SQ_DS_WRITE2ST64_B32', + 'SQ_DS_WRITE2ST64_B64', 'SQ_DS_WRITE2_B32', 'SQ_DS_WRITE2_B64', + 'SQ_DS_WRITE_ADDTID_B32', 'SQ_DS_WRITE_B128', 'SQ_DS_WRITE_B16', + 'SQ_DS_WRITE_B32', 'SQ_DS_WRITE_B64', 'SQ_DS_WRITE_B8', + 'SQ_DS_WRITE_B96', 'SQ_DS_WRITE_SRC2_B32', 'SQ_DS_WRITE_SRC2_B64', + 'SQ_DS_WRXCHG2ST64_RTN_B32', 'SQ_DS_WRXCHG2ST64_RTN_B64', + 'SQ_DS_WRXCHG2_RTN_B32', 'SQ_DS_WRXCHG2_RTN_B64', + 'SQ_DS_WRXCHG_RTN_B32', 'SQ_DS_WRXCHG_RTN_B64', 'SQ_DS_XOR_B32', + 'SQ_DS_XOR_B64', 'SQ_DS_XOR_RTN_B32', 'SQ_DS_XOR_RTN_B64', + 'SQ_DS_XOR_SRC2_B32', 'SQ_DS_XOR_SRC2_B64', 'SQ_EDC_FUE_CNTL_LDS', + 'SQ_EDC_FUE_CNTL_SIMD0', 'SQ_EDC_FUE_CNTL_SIMD1', + 'SQ_EDC_FUE_CNTL_SIMD2', 'SQ_EDC_FUE_CNTL_SIMD3', + 'SQ_EDC_FUE_CNTL_SQ', 'SQ_EDC_FUE_CNTL_TA', 'SQ_EDC_FUE_CNTL_TCP', + 'SQ_EDC_FUE_CNTL_TD', 'SQ_EDC_INFO_SOURCE', + 'SQ_EDC_INFO_SOURCE_GDS', 'SQ_EDC_INFO_SOURCE_INST', + 'SQ_EDC_INFO_SOURCE_INVALID', 'SQ_EDC_INFO_SOURCE_LDS', + 'SQ_EDC_INFO_SOURCE_SGPR', 'SQ_EDC_INFO_SOURCE_TA', + 'SQ_EDC_INFO_SOURCE_VGPR', 'SQ_ENC_DS_BITS', 'SQ_ENC_DS_FIELD', + 'SQ_ENC_DS_MASK', 'SQ_ENC_EXP_BITS', 'SQ_ENC_EXP_FIELD', + 'SQ_ENC_EXP_MASK', 'SQ_ENC_FLAT_BITS', 'SQ_ENC_FLAT_FIELD', + 'SQ_ENC_FLAT_MASK', 'SQ_ENC_MIMG_BITS', 'SQ_ENC_MIMG_FIELD', + 'SQ_ENC_MIMG_MASK', 'SQ_ENC_MTBUF_BITS', 'SQ_ENC_MTBUF_FIELD', + 'SQ_ENC_MTBUF_MASK', 'SQ_ENC_MUBUF_BITS', 'SQ_ENC_MUBUF_FIELD', + 'SQ_ENC_MUBUF_MASK', 'SQ_ENC_SMEM_BITS', 'SQ_ENC_SMEM_FIELD', + 'SQ_ENC_SMEM_MASK', 'SQ_ENC_SOP1_BITS', 'SQ_ENC_SOP1_FIELD', + 'SQ_ENC_SOP1_MASK', 'SQ_ENC_SOP2_BITS', 'SQ_ENC_SOP2_FIELD', + 'SQ_ENC_SOP2_MASK', 'SQ_ENC_SOPC_BITS', 'SQ_ENC_SOPC_FIELD', + 'SQ_ENC_SOPC_MASK', 'SQ_ENC_SOPK_BITS', 'SQ_ENC_SOPK_FIELD', + 'SQ_ENC_SOPK_MASK', 'SQ_ENC_SOPP_BITS', 'SQ_ENC_SOPP_FIELD', + 'SQ_ENC_SOPP_MASK', 'SQ_ENC_VINTRP_BITS', 'SQ_ENC_VINTRP_FIELD', + 'SQ_ENC_VINTRP_MASK', 'SQ_ENC_VOP1_BITS', 'SQ_ENC_VOP1_FIELD', + 'SQ_ENC_VOP1_MASK', 'SQ_ENC_VOP2_BITS', 'SQ_ENC_VOP2_FIELD', + 'SQ_ENC_VOP2_MASK', 'SQ_ENC_VOP3P_BITS', 'SQ_ENC_VOP3P_FIELD', + 'SQ_ENC_VOP3P_MASK', 'SQ_ENC_VOP3_BITS', 'SQ_ENC_VOP3_FIELD', + 'SQ_ENC_VOP3_MASK', 'SQ_ENC_VOPC_BITS', 'SQ_ENC_VOPC_FIELD', + 'SQ_ENC_VOPC_MASK', 'SQ_EQ', 'SQ_EXEC_HI', 'SQ_EXEC_LO', 'SQ_EXP', + 'SQ_EXPORT_RAT_INST_ADD', 'SQ_EXPORT_RAT_INST_ADD_RTN', + 'SQ_EXPORT_RAT_INST_AND', 'SQ_EXPORT_RAT_INST_AND_RTN', + 'SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM', + 'SQ_EXPORT_RAT_INST_CMPXCHG_FDENORM_RTN', + 'SQ_EXPORT_RAT_INST_CMPXCHG_FLT', + 'SQ_EXPORT_RAT_INST_CMPXCHG_FLT_RTN', + 'SQ_EXPORT_RAT_INST_CMPXCHG_INT', + 'SQ_EXPORT_RAT_INST_CMPXCHG_INT_RTN', + 'SQ_EXPORT_RAT_INST_DEC_UINT', 'SQ_EXPORT_RAT_INST_DEC_UINT_RTN', + 'SQ_EXPORT_RAT_INST_INC_UINT', 'SQ_EXPORT_RAT_INST_INC_UINT_RTN', + 'SQ_EXPORT_RAT_INST_MAX_INT', 'SQ_EXPORT_RAT_INST_MAX_INT_RTN', + 'SQ_EXPORT_RAT_INST_MAX_UINT', 'SQ_EXPORT_RAT_INST_MAX_UINT_RTN', + 'SQ_EXPORT_RAT_INST_MIN_INT', 'SQ_EXPORT_RAT_INST_MIN_INT_RTN', + 'SQ_EXPORT_RAT_INST_MIN_UINT', 'SQ_EXPORT_RAT_INST_MIN_UINT_RTN', + 'SQ_EXPORT_RAT_INST_MSKOR', 'SQ_EXPORT_RAT_INST_MSKOR_RTN', + 'SQ_EXPORT_RAT_INST_NOP', 'SQ_EXPORT_RAT_INST_NOP_RTN', + 'SQ_EXPORT_RAT_INST_OR', 'SQ_EXPORT_RAT_INST_OR_RTN', + 'SQ_EXPORT_RAT_INST_RSUB', 'SQ_EXPORT_RAT_INST_RSUB_RTN', + 'SQ_EXPORT_RAT_INST_STORE_BYTE', 'SQ_EXPORT_RAT_INST_STORE_DWORD', + 'SQ_EXPORT_RAT_INST_STORE_RAW', + 'SQ_EXPORT_RAT_INST_STORE_RAW_FDENORM', + 'SQ_EXPORT_RAT_INST_STORE_SHORT', + 'SQ_EXPORT_RAT_INST_STORE_TYPED', 'SQ_EXPORT_RAT_INST_SUB', + 'SQ_EXPORT_RAT_INST_SUB_RTN', + 'SQ_EXPORT_RAT_INST_XCHG_FDENORM_RTN', + 'SQ_EXPORT_RAT_INST_XCHG_RTN', 'SQ_EXPORT_RAT_INST_XOR', + 'SQ_EXPORT_RAT_INST_XOR_RTN', 'SQ_EXP_GDS0', 'SQ_EXP_MRT0', + 'SQ_EXP_MRTZ', 'SQ_EXP_NULL', 'SQ_EXP_NUM_GDS', 'SQ_EXP_NUM_MRT', + 'SQ_EXP_NUM_PARAM', 'SQ_EXP_NUM_POS', 'SQ_EXP_PARAM0', + 'SQ_EXP_POS0', 'SQ_EX_MODE_EXCP_ADDR_WATCH0', + 'SQ_EX_MODE_EXCP_DIV0', 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH1', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH2', + 'SQ_EX_MODE_EXCP_HI_ADDR_WATCH3', 'SQ_EX_MODE_EXCP_INEXACT', + 'SQ_EX_MODE_EXCP_INPUT_DENORM', 'SQ_EX_MODE_EXCP_INT_DIV0', + 'SQ_EX_MODE_EXCP_INVALID', 'SQ_EX_MODE_EXCP_MEM_VIOL', + 'SQ_EX_MODE_EXCP_OVERFLOW', 'SQ_EX_MODE_EXCP_UNDERFLOW', + 'SQ_EX_MODE_EXCP_VALU_BASE', 'SQ_EX_MODE_EXCP_VALU_SIZE', 'SQ_F', + 'SQ_FLAT', 'SQ_FLAT_ATOMIC_ADD', 'SQ_FLAT_ATOMIC_ADD_X2', + 'SQ_FLAT_ATOMIC_AND', 'SQ_FLAT_ATOMIC_AND_X2', + 'SQ_FLAT_ATOMIC_CMPSWAP', 'SQ_FLAT_ATOMIC_CMPSWAP_X2', + 'SQ_FLAT_ATOMIC_DEC', 'SQ_FLAT_ATOMIC_DEC_X2', + 'SQ_FLAT_ATOMIC_INC', 'SQ_FLAT_ATOMIC_INC_X2', + 'SQ_FLAT_ATOMIC_OR', 'SQ_FLAT_ATOMIC_OR_X2', + 'SQ_FLAT_ATOMIC_SMAX', 'SQ_FLAT_ATOMIC_SMAX_X2', + 'SQ_FLAT_ATOMIC_SMIN', 'SQ_FLAT_ATOMIC_SMIN_X2', + 'SQ_FLAT_ATOMIC_SUB', 'SQ_FLAT_ATOMIC_SUB_X2', + 'SQ_FLAT_ATOMIC_SWAP', 'SQ_FLAT_ATOMIC_SWAP_X2', + 'SQ_FLAT_ATOMIC_UMAX', 'SQ_FLAT_ATOMIC_UMAX_X2', + 'SQ_FLAT_ATOMIC_UMIN', 'SQ_FLAT_ATOMIC_UMIN_X2', + 'SQ_FLAT_ATOMIC_XOR', 'SQ_FLAT_ATOMIC_XOR_X2', + 'SQ_FLAT_LOAD_DWORD', 'SQ_FLAT_LOAD_DWORDX2', + 'SQ_FLAT_LOAD_DWORDX3', 'SQ_FLAT_LOAD_DWORDX4', + 'SQ_FLAT_LOAD_SBYTE', 'SQ_FLAT_LOAD_SSHORT', 'SQ_FLAT_LOAD_UBYTE', + 'SQ_FLAT_LOAD_USHORT', 'SQ_FLAT_SCRATCH_HI', 'SQ_FLAT_SCRATCH_LO', + 'SQ_FLAT_STORE_BYTE', 'SQ_FLAT_STORE_DWORD', + 'SQ_FLAT_STORE_DWORDX2', 'SQ_FLAT_STORE_DWORDX3', + 'SQ_FLAT_STORE_DWORDX4', 'SQ_FLAT_STORE_SHORT', 'SQ_GE', + 'SQ_GFXDEC_BEGIN', 'SQ_GFXDEC_END', 'SQ_GFXDEC_STATE_ID_SHIFT', + 'SQ_GLOBAL', 'SQ_GLOBAL_ATOMIC_ADD', 'SQ_GLOBAL_ATOMIC_ADD_X2', + 'SQ_GLOBAL_ATOMIC_AND', 'SQ_GLOBAL_ATOMIC_AND_X2', + 'SQ_GLOBAL_ATOMIC_CMPSWAP', 'SQ_GLOBAL_ATOMIC_CMPSWAP_X2', + 'SQ_GLOBAL_ATOMIC_DEC', 'SQ_GLOBAL_ATOMIC_DEC_X2', + 'SQ_GLOBAL_ATOMIC_INC', 'SQ_GLOBAL_ATOMIC_INC_X2', + 'SQ_GLOBAL_ATOMIC_OR', 'SQ_GLOBAL_ATOMIC_OR_X2', + 'SQ_GLOBAL_ATOMIC_SMAX', 'SQ_GLOBAL_ATOMIC_SMAX_X2', + 'SQ_GLOBAL_ATOMIC_SMIN', 'SQ_GLOBAL_ATOMIC_SMIN_X2', + 'SQ_GLOBAL_ATOMIC_SUB', 'SQ_GLOBAL_ATOMIC_SUB_X2', + 'SQ_GLOBAL_ATOMIC_SWAP', 'SQ_GLOBAL_ATOMIC_SWAP_X2', + 'SQ_GLOBAL_ATOMIC_UMAX', 'SQ_GLOBAL_ATOMIC_UMAX_X2', + 'SQ_GLOBAL_ATOMIC_UMIN', 'SQ_GLOBAL_ATOMIC_UMIN_X2', + 'SQ_GLOBAL_ATOMIC_XOR', 'SQ_GLOBAL_ATOMIC_XOR_X2', + 'SQ_GLOBAL_LOAD_DWORD', 'SQ_GLOBAL_LOAD_DWORDX2', + 'SQ_GLOBAL_LOAD_DWORDX3', 'SQ_GLOBAL_LOAD_DWORDX4', + 'SQ_GLOBAL_LOAD_SBYTE', 'SQ_GLOBAL_LOAD_SSHORT', + 'SQ_GLOBAL_LOAD_UBYTE', 'SQ_GLOBAL_LOAD_USHORT', + 'SQ_GLOBAL_STORE_BYTE', 'SQ_GLOBAL_STORE_DWORD', + 'SQ_GLOBAL_STORE_DWORDX2', 'SQ_GLOBAL_STORE_DWORDX3', + 'SQ_GLOBAL_STORE_DWORDX4', 'SQ_GLOBAL_STORE_SHORT', + 'SQ_GS_OP_CUT', 'SQ_GS_OP_EMIT', 'SQ_GS_OP_EMIT_CUT', + 'SQ_GS_OP_NOP', 'SQ_GT', 'SQ_HWREG_ID_SHIFT', 'SQ_HWREG_ID_SIZE', + 'SQ_HWREG_OFFSET_SHIFT', 'SQ_HWREG_OFFSET_SIZE', + 'SQ_HWREG_SIZE_SHIFT', 'SQ_HWREG_SIZE_SIZE', 'SQ_HW_REG_FLUSH_IB', + 'SQ_HW_REG_GPR_ALLOC', 'SQ_HW_REG_HW_ID', 'SQ_HW_REG_IB_DBG0', + 'SQ_HW_REG_IB_DBG1', 'SQ_HW_REG_IB_STS', 'SQ_HW_REG_INST_DW0', + 'SQ_HW_REG_INST_DW1', 'SQ_HW_REG_LDS_ALLOC', 'SQ_HW_REG_MODE', + 'SQ_HW_REG_PC_HI', 'SQ_HW_REG_PC_LO', 'SQ_HW_REG_SH_MEM_BASES', + 'SQ_HW_REG_SQ_SHADER_TBA_HI', 'SQ_HW_REG_SQ_SHADER_TBA_LO', + 'SQ_HW_REG_SQ_SHADER_TMA_HI', 'SQ_HW_REG_SQ_SHADER_TMA_LO', + 'SQ_HW_REG_STATUS', 'SQ_HW_REG_TRAPSTS', 'SQ_IBUF_IB_DRET', + 'SQ_IBUF_IB_EMPTY_WAIT_DRET', 'SQ_IBUF_IB_EMPTY_WAIT_GNT', + 'SQ_IBUF_IB_IDLE', 'SQ_IBUF_IB_INI_WAIT_DRET', + 'SQ_IBUF_IB_INI_WAIT_GNT', 'SQ_IBUF_IB_LE_4DW', + 'SQ_IBUF_IB_WAIT_DRET', 'SQ_IBUF_ST', 'SQ_IMAGE_ATOMIC_ADD', + 'SQ_IMAGE_ATOMIC_AND', 'SQ_IMAGE_ATOMIC_CMPSWAP', + 'SQ_IMAGE_ATOMIC_DEC', 'SQ_IMAGE_ATOMIC_INC', + 'SQ_IMAGE_ATOMIC_OR', 'SQ_IMAGE_ATOMIC_SMAX', + 'SQ_IMAGE_ATOMIC_SMIN', 'SQ_IMAGE_ATOMIC_SUB', + 'SQ_IMAGE_ATOMIC_SWAP', 'SQ_IMAGE_ATOMIC_UMAX', + 'SQ_IMAGE_ATOMIC_UMIN', 'SQ_IMAGE_ATOMIC_XOR', 'SQ_IMAGE_GATHER4', + 'SQ_IMAGE_GATHER4H', 'SQ_IMAGE_GATHER4H_PCK', + 'SQ_IMAGE_GATHER4_B', 'SQ_IMAGE_GATHER4_B_CL', + 'SQ_IMAGE_GATHER4_B_CL_O', 'SQ_IMAGE_GATHER4_B_O', + 'SQ_IMAGE_GATHER4_C', 'SQ_IMAGE_GATHER4_CL', + 'SQ_IMAGE_GATHER4_CL_O', 'SQ_IMAGE_GATHER4_C_B', + 'SQ_IMAGE_GATHER4_C_B_CL', 'SQ_IMAGE_GATHER4_C_B_CL_O', + 'SQ_IMAGE_GATHER4_C_B_O', 'SQ_IMAGE_GATHER4_C_CL', + 'SQ_IMAGE_GATHER4_C_CL_O', 'SQ_IMAGE_GATHER4_C_L', + 'SQ_IMAGE_GATHER4_C_LZ', 'SQ_IMAGE_GATHER4_C_LZ_O', + 'SQ_IMAGE_GATHER4_C_L_O', 'SQ_IMAGE_GATHER4_C_O', + 'SQ_IMAGE_GATHER4_L', 'SQ_IMAGE_GATHER4_LZ', + 'SQ_IMAGE_GATHER4_LZ_O', 'SQ_IMAGE_GATHER4_L_O', + 'SQ_IMAGE_GATHER4_O', 'SQ_IMAGE_GATHER8H_PCK', 'SQ_IMAGE_GET_LOD', + 'SQ_IMAGE_GET_RESINFO', 'SQ_IMAGE_LOAD', 'SQ_IMAGE_LOAD_MIP', + 'SQ_IMAGE_LOAD_MIP_PCK', 'SQ_IMAGE_LOAD_MIP_PCK_SGN', + 'SQ_IMAGE_LOAD_PCK', 'SQ_IMAGE_LOAD_PCK_SGN', 'SQ_IMAGE_RSRC256', + 'SQ_IMAGE_SAMPLE', 'SQ_IMAGE_SAMPLER', 'SQ_IMAGE_SAMPLE_B', + 'SQ_IMAGE_SAMPLE_B_CL', 'SQ_IMAGE_SAMPLE_B_CL_O', + 'SQ_IMAGE_SAMPLE_B_O', 'SQ_IMAGE_SAMPLE_C', 'SQ_IMAGE_SAMPLE_CD', + 'SQ_IMAGE_SAMPLE_CD_CL', 'SQ_IMAGE_SAMPLE_CD_CL_O', + 'SQ_IMAGE_SAMPLE_CD_O', 'SQ_IMAGE_SAMPLE_CL', + 'SQ_IMAGE_SAMPLE_CL_O', 'SQ_IMAGE_SAMPLE_C_B', + 'SQ_IMAGE_SAMPLE_C_B_CL', 'SQ_IMAGE_SAMPLE_C_B_CL_O', + 'SQ_IMAGE_SAMPLE_C_B_O', 'SQ_IMAGE_SAMPLE_C_CD', + 'SQ_IMAGE_SAMPLE_C_CD_CL', 'SQ_IMAGE_SAMPLE_C_CD_CL_O', + 'SQ_IMAGE_SAMPLE_C_CD_O', 'SQ_IMAGE_SAMPLE_C_CL', + 'SQ_IMAGE_SAMPLE_C_CL_O', 'SQ_IMAGE_SAMPLE_C_D', + 'SQ_IMAGE_SAMPLE_C_D_CL', 'SQ_IMAGE_SAMPLE_C_D_CL_O', + 'SQ_IMAGE_SAMPLE_C_D_O', 'SQ_IMAGE_SAMPLE_C_L', + 'SQ_IMAGE_SAMPLE_C_LZ', 'SQ_IMAGE_SAMPLE_C_LZ_O', + 'SQ_IMAGE_SAMPLE_C_L_O', 'SQ_IMAGE_SAMPLE_C_O', + 'SQ_IMAGE_SAMPLE_D', 'SQ_IMAGE_SAMPLE_D_CL', + 'SQ_IMAGE_SAMPLE_D_CL_O', 'SQ_IMAGE_SAMPLE_D_O', + 'SQ_IMAGE_SAMPLE_L', 'SQ_IMAGE_SAMPLE_LZ', 'SQ_IMAGE_SAMPLE_LZ_O', + 'SQ_IMAGE_SAMPLE_L_O', 'SQ_IMAGE_SAMPLE_O', 'SQ_IMAGE_STORE', + 'SQ_IMAGE_STORE_MIP', 'SQ_IMAGE_STORE_MIP_PCK', + 'SQ_IMAGE_STORE_PCK', 'SQ_IMG_FILTER_MODE_BLEND', + 'SQ_IMG_FILTER_MODE_MAX', 'SQ_IMG_FILTER_MODE_MIN', + 'SQ_IMG_FILTER_TYPE', 'SQ_IND_CMD_CMD', 'SQ_IND_CMD_CMD_DEBUG', + 'SQ_IND_CMD_CMD_KILL', 'SQ_IND_CMD_CMD_NULL', + 'SQ_IND_CMD_CMD_SAVECTX', 'SQ_IND_CMD_CMD_SETFATALHALT', + 'SQ_IND_CMD_CMD_SETHALT', 'SQ_IND_CMD_CMD_SET_SPI_PRIO', + 'SQ_IND_CMD_CMD_TRAP', 'SQ_IND_CMD_MODE', + 'SQ_IND_CMD_MODE_BROADCAST', 'SQ_IND_CMD_MODE_BROADCAST_ME', + 'SQ_IND_CMD_MODE_BROADCAST_PIPE', + 'SQ_IND_CMD_MODE_BROADCAST_QUEUE', 'SQ_IND_CMD_MODE_SINGLE', + 'SQ_INST_STR_IB_WAVE2ID_NORMAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_INST_SKIP_AV', + 'SQ_INST_STR_IB_WAVE_INTERNAL_INST_AV', + 'SQ_INST_STR_IB_WAVE_NOP_SLEEP_WAIT', 'SQ_INST_STR_IB_WAVE_NORML', + 'SQ_INST_STR_IB_WAVE_PC_FROM_SGPR_MSG_WAIT', + 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST0', + 'SQ_INST_STR_IB_WAVE_SETVSKIP_ST1', 'SQ_INST_STR_ST', + 'SQ_INTERRUPT_WORD_ENCODING', 'SQ_INTERRUPT_WORD_ENCODING_AUTO', + 'SQ_INTERRUPT_WORD_ENCODING_ERROR', + 'SQ_INTERRUPT_WORD_ENCODING_INST', 'SQ_L1', 'SQ_L10', 'SQ_L11', + 'SQ_L12', 'SQ_L13', 'SQ_L14', 'SQ_L15', 'SQ_L2', 'SQ_L3', 'SQ_L4', + 'SQ_L5', 'SQ_L6', 'SQ_L7', 'SQ_L8', 'SQ_L9', + 'SQ_LB_CTR_SEL_ALU_CYCLES', 'SQ_LB_CTR_SEL_ALU_STALLS', + 'SQ_LB_CTR_SEL_DCACHE_STALLS', 'SQ_LB_CTR_SEL_ICACHE_STALLS', + 'SQ_LB_CTR_SEL_RESERVED0', 'SQ_LB_CTR_SEL_RESERVED1', + 'SQ_LB_CTR_SEL_RESERVED2', 'SQ_LB_CTR_SEL_RESERVED3', + 'SQ_LB_CTR_SEL_RESERVED4', 'SQ_LB_CTR_SEL_RESERVED5', + 'SQ_LB_CTR_SEL_RESERVED6', 'SQ_LB_CTR_SEL_SALU_CYCLES', + 'SQ_LB_CTR_SEL_SCALAR_STALLS', 'SQ_LB_CTR_SEL_SMEM_CYCLES', + 'SQ_LB_CTR_SEL_TEX_CYCLES', 'SQ_LB_CTR_SEL_TEX_STALLS', + 'SQ_LB_CTR_SEL_VALUES', 'SQ_LE', 'SQ_LG', 'SQ_LT', 'SQ_M0', + 'SQ_MAX_PGM_SGPRS', 'SQ_MAX_PGM_VGPRS', + 'SQ_MSG_EARLY_PRIM_DEALLOC', 'SQ_MSG_GS', 'SQ_MSG_GS_ALLOC_REQ', + 'SQ_MSG_GS_DONE', 'SQ_MSG_HALT_WAVES', 'SQ_MSG_INTERRUPT', + 'SQ_MSG_ORDERED_PS_DONE', 'SQ_MSG_SAVEWAVE', + 'SQ_MSG_STALL_WAVE_GEN', 'SQ_MSG_SYSMSG', 'SQ_NE', 'SQ_NEQ', + 'SQ_NGE', 'SQ_NGT', 'SQ_NLE', 'SQ_NLG', 'SQ_NLT', 'SQ_NON_EVENT', + 'SQ_NUM_ATTR', 'SQ_NUM_SGPR', 'SQ_NUM_TTMP', 'SQ_NUM_VGPR', + 'SQ_O', 'SQ_OMOD_D2', 'SQ_OMOD_M2', 'SQ_OMOD_M4', 'SQ_OMOD_OFF', + 'SQ_PARAM_P0', 'SQ_PARAM_P10', 'SQ_PARAM_P20', 'SQ_PERF_SEL', + 'SQ_PERF_SEL_ACCUM_PREV', 'SQ_PERF_SEL_ACCUM_PREV_HIRES', + 'SQ_PERF_SEL_ACTIVE_INST_ANY', 'SQ_PERF_SEL_ACTIVE_INST_EXP_GDS', + 'SQ_PERF_SEL_ACTIVE_INST_FLAT', 'SQ_PERF_SEL_ACTIVE_INST_LDS', + 'SQ_PERF_SEL_ACTIVE_INST_MISC', 'SQ_PERF_SEL_ACTIVE_INST_SCA', + 'SQ_PERF_SEL_ACTIVE_INST_VALU', 'SQ_PERF_SEL_ACTIVE_INST_VMEM', + 'SQ_PERF_SEL_ATC_INSTS_SMEM', 'SQ_PERF_SEL_ATC_INSTS_SMEM_REPLAY', + 'SQ_PERF_SEL_ATC_INSTS_VMEM', 'SQ_PERF_SEL_ATC_INSTS_VMEM_REPLAY', + 'SQ_PERF_SEL_ATC_INST_LEVEL_SMEM', + 'SQ_PERF_SEL_ATC_INST_LEVEL_VMEM', 'SQ_PERF_SEL_ATC_XNACK_ALL', + 'SQ_PERF_SEL_ATC_XNACK_FIFO_FULL', 'SQ_PERF_SEL_ATC_XNACK_FIRST', + 'SQ_PERF_SEL_BUSY_CU_CYCLES', 'SQ_PERF_SEL_BUSY_CYCLES', + 'SQ_PERF_SEL_CBRANCH_FORK', 'SQ_PERF_SEL_CBRANCH_FORK_SPLIT', + 'SQ_PERF_SEL_CYCLES', 'SQ_PERF_SEL_DUMMY_END', + 'SQ_PERF_SEL_DUMMY_LAST', 'SQ_PERF_SEL_EVENTS', + 'SQ_PERF_SEL_EXP_REQ_FIFO_FULL', + 'SQ_PERF_SEL_FLAT_SRC_CD_CONFLICT', 'SQ_PERF_SEL_IFETCH', + 'SQ_PERF_SEL_IFETCH_LEVEL', 'SQ_PERF_SEL_IFETCH_XNACK', + 'SQ_PERF_SEL_INSTS', 'SQ_PERF_SEL_INSTS_BRANCH', + 'SQ_PERF_SEL_INSTS_EXP', 'SQ_PERF_SEL_INSTS_EXP_GDS', + 'SQ_PERF_SEL_INSTS_FLAT', 'SQ_PERF_SEL_INSTS_FLAT_LDS_ONLY', + 'SQ_PERF_SEL_INSTS_FLAT_REPLAY', 'SQ_PERF_SEL_INSTS_GDS', + 'SQ_PERF_SEL_INSTS_LDS', 'SQ_PERF_SEL_INSTS_SALU', + 'SQ_PERF_SEL_INSTS_SENDMSG', 'SQ_PERF_SEL_INSTS_SMEM', + 'SQ_PERF_SEL_INSTS_SMEM_NORM', + 'SQ_PERF_SEL_INSTS_SMEM_NORM_REPLAY', + 'SQ_PERF_SEL_INSTS_SMEM_REPLAY', 'SQ_PERF_SEL_INSTS_VALU', + 'SQ_PERF_SEL_INSTS_VMEM', 'SQ_PERF_SEL_INSTS_VMEM_RD', + 'SQ_PERF_SEL_INSTS_VMEM_RD_REPLAY', + 'SQ_PERF_SEL_INSTS_VMEM_REPLAY', 'SQ_PERF_SEL_INSTS_VMEM_WR', + 'SQ_PERF_SEL_INSTS_VMEM_WR_REPLAY', 'SQ_PERF_SEL_INSTS_VSKIPPED', + 'SQ_PERF_SEL_INST_CYCLES_EXP', 'SQ_PERF_SEL_INST_CYCLES_GDS', + 'SQ_PERF_SEL_INST_CYCLES_SALU', 'SQ_PERF_SEL_INST_CYCLES_SMEM', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_ADDR', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_CMD', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_DATA', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_RD', + 'SQ_PERF_SEL_INST_CYCLES_VMEM_WR', 'SQ_PERF_SEL_INST_LEVEL_EXP', + 'SQ_PERF_SEL_INST_LEVEL_GDS', 'SQ_PERF_SEL_INST_LEVEL_LDS', + 'SQ_PERF_SEL_INST_LEVEL_SMEM', 'SQ_PERF_SEL_INST_LEVEL_VMEM', + 'SQ_PERF_SEL_ITEMS', 'SQ_PERF_SEL_LDS_ADDR_CONFLICT', + 'SQ_PERF_SEL_LDS_ATOMIC_RETURN', 'SQ_PERF_SEL_LDS_BANK_CONFLICT', + 'SQ_PERF_SEL_LDS_CMD_FIFO_FULL', 'SQ_PERF_SEL_LDS_DATA_FIFO_FULL', + 'SQ_PERF_SEL_LDS_IDX_ACTIVE', 'SQ_PERF_SEL_LDS_MEM_VIOLATIONS', + 'SQ_PERF_SEL_LDS_SRC_CD_CONFLICT', + 'SQ_PERF_SEL_LDS_UNALIGNED_STALL', 'SQ_PERF_SEL_LEVEL_WAVES', + 'SQ_PERF_SEL_LEVEL_WAVES_CU', 'SQ_PERF_SEL_MSG_CNTR', + 'SQ_PERF_SEL_MSG_GSCNT', 'SQ_PERF_SEL_MSG_INTERRUPT', + 'SQ_PERF_SEL_MSG_PERF', 'SQ_PERF_SEL_NONE', + 'SQ_PERF_SEL_POWER_ALU_BUSY', 'SQ_PERF_SEL_POWER_GPR_RD', + 'SQ_PERF_SEL_POWER_GPR_WR', 'SQ_PERF_SEL_POWER_LDS_BUSY', + 'SQ_PERF_SEL_POWER_TEX_BUSY', 'SQ_PERF_SEL_POWER_VALU', + 'SQ_PERF_SEL_POWER_VALU0', 'SQ_PERF_SEL_POWER_VALU1', + 'SQ_PERF_SEL_POWER_VALU2', 'SQ_PERF_SEL_PT_POWER_STALL', + 'SQ_PERF_SEL_QUADS', 'SQ_PERF_SEL_SRC_CD_BUSY', + 'SQ_PERF_SEL_SURF_SYNCS', 'SQ_PERF_SEL_THREAD_CYCLES_VALU', + 'SQ_PERF_SEL_THREAD_CYCLES_VALU_MAX', 'SQ_PERF_SEL_TLB_SHOOTDOWN', + 'SQ_PERF_SEL_TLB_SHOOTDOWN_CYCLES', + 'SQ_PERF_SEL_TTRACE_INFLIGHT_REQS', 'SQ_PERF_SEL_TTRACE_REQS', + 'SQ_PERF_SEL_TTRACE_STALL', 'SQ_PERF_SEL_USER0', + 'SQ_PERF_SEL_USER1', 'SQ_PERF_SEL_USER10', 'SQ_PERF_SEL_USER11', + 'SQ_PERF_SEL_USER12', 'SQ_PERF_SEL_USER13', 'SQ_PERF_SEL_USER14', + 'SQ_PERF_SEL_USER15', 'SQ_PERF_SEL_USER2', 'SQ_PERF_SEL_USER3', + 'SQ_PERF_SEL_USER4', 'SQ_PERF_SEL_USER5', 'SQ_PERF_SEL_USER6', + 'SQ_PERF_SEL_USER7', 'SQ_PERF_SEL_USER8', 'SQ_PERF_SEL_USER9', + 'SQ_PERF_SEL_USER_LEVEL0', 'SQ_PERF_SEL_USER_LEVEL1', + 'SQ_PERF_SEL_USER_LEVEL10', 'SQ_PERF_SEL_USER_LEVEL11', + 'SQ_PERF_SEL_USER_LEVEL12', 'SQ_PERF_SEL_USER_LEVEL13', + 'SQ_PERF_SEL_USER_LEVEL14', 'SQ_PERF_SEL_USER_LEVEL15', + 'SQ_PERF_SEL_USER_LEVEL2', 'SQ_PERF_SEL_USER_LEVEL3', + 'SQ_PERF_SEL_USER_LEVEL4', 'SQ_PERF_SEL_USER_LEVEL5', + 'SQ_PERF_SEL_USER_LEVEL6', 'SQ_PERF_SEL_USER_LEVEL7', + 'SQ_PERF_SEL_USER_LEVEL8', 'SQ_PERF_SEL_USER_LEVEL9', + 'SQ_PERF_SEL_UTCL1_LFIFO_FULL', + 'SQ_PERF_SEL_UTCL1_PERMISSION_MISS', 'SQ_PERF_SEL_UTCL1_REQUEST', + 'SQ_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 'SQ_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 'SQ_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 'SQ_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 'SQ_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'SQ_PERF_SEL_UTCL1_TRANSLATION_MISS', + 'SQ_PERF_SEL_VALU_DEP_STALL', 'SQ_PERF_SEL_VALU_LDS_DIRECT_RD', + 'SQ_PERF_SEL_VALU_LDS_INTERP_OP', + 'SQ_PERF_SEL_VALU_SRC_C_CONFLICT', 'SQ_PERF_SEL_VALU_STARVE', + 'SQ_PERF_SEL_VMEM_EX_DATA_REG_BUSY', + 'SQ_PERF_SEL_VMEM_RD_SRC_CD_CONFLICT', + 'SQ_PERF_SEL_VMEM_TA_ADDR_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_TA_CMD_FIFO_FULL', + 'SQ_PERF_SEL_VMEM_WR_SRC_CD_CONFLICT', + 'SQ_PERF_SEL_VMEM_WR_TA_DATA_FIFO_FULL', 'SQ_PERF_SEL_WAIT_ANY', + 'SQ_PERF_SEL_WAIT_BARRIER', 'SQ_PERF_SEL_WAIT_CNT_ANY', + 'SQ_PERF_SEL_WAIT_CNT_EXP', 'SQ_PERF_SEL_WAIT_CNT_LGKM', + 'SQ_PERF_SEL_WAIT_CNT_VM', 'SQ_PERF_SEL_WAIT_EXP_ALLOC', + 'SQ_PERF_SEL_WAIT_IFETCH', 'SQ_PERF_SEL_WAIT_INST_ANY', + 'SQ_PERF_SEL_WAIT_INST_EXP_GDS', 'SQ_PERF_SEL_WAIT_INST_FLAT', + 'SQ_PERF_SEL_WAIT_INST_LDS', 'SQ_PERF_SEL_WAIT_INST_MISC', + 'SQ_PERF_SEL_WAIT_INST_SCA', 'SQ_PERF_SEL_WAIT_INST_VALU', + 'SQ_PERF_SEL_WAIT_INST_VMEM', 'SQ_PERF_SEL_WAIT_OTHER', + 'SQ_PERF_SEL_WAIT_SLEEP', 'SQ_PERF_SEL_WAIT_SLEEP_XNACK', + 'SQ_PERF_SEL_WAIT_TTRACE', 'SQ_PERF_SEL_WAVES', + 'SQ_PERF_SEL_WAVES_CU', 'SQ_PERF_SEL_WAVES_EQ_64', + 'SQ_PERF_SEL_WAVES_LT_16', 'SQ_PERF_SEL_WAVES_LT_32', + 'SQ_PERF_SEL_WAVES_LT_48', 'SQ_PERF_SEL_WAVES_LT_64', + 'SQ_PERF_SEL_WAVES_RESTORED', 'SQ_PERF_SEL_WAVES_SAVED', + 'SQ_PERF_SEL_WAVE_CYCLES', 'SQ_PERF_SEL_WAVE_READY', 'SQ_R1', + 'SQ_R10', 'SQ_R11', 'SQ_R12', 'SQ_R13', 'SQ_R14', 'SQ_R15', + 'SQ_R2', 'SQ_R3', 'SQ_R4', 'SQ_R5', 'SQ_R6', 'SQ_R7', 'SQ_R8', + 'SQ_R9', 'SQ_ROUND_MINUS_INFINITY', 'SQ_ROUND_MODE', + 'SQ_ROUND_NEAREST_EVEN', 'SQ_ROUND_PLUS_INFINITY', + 'SQ_ROUND_TO_ZERO', 'SQ_RSRC_BUF', 'SQ_RSRC_BUF_RSVD_1', + 'SQ_RSRC_BUF_RSVD_2', 'SQ_RSRC_BUF_RSVD_3', 'SQ_RSRC_BUF_TYPE', + 'SQ_RSRC_FLAT', 'SQ_RSRC_FLAT_RSVD_0', 'SQ_RSRC_FLAT_RSVD_2', + 'SQ_RSRC_FLAT_RSVD_3', 'SQ_RSRC_FLAT_TYPE', 'SQ_RSRC_IMG_1D', + 'SQ_RSRC_IMG_1D_ARRAY', 'SQ_RSRC_IMG_2D', 'SQ_RSRC_IMG_2D_ARRAY', + 'SQ_RSRC_IMG_2D_MSAA', 'SQ_RSRC_IMG_2D_MSAA_ARRAY', + 'SQ_RSRC_IMG_3D', 'SQ_RSRC_IMG_CUBE', 'SQ_RSRC_IMG_RSVD_0', + 'SQ_RSRC_IMG_RSVD_1', 'SQ_RSRC_IMG_RSVD_2', 'SQ_RSRC_IMG_RSVD_3', + 'SQ_RSRC_IMG_RSVD_4', 'SQ_RSRC_IMG_RSVD_5', 'SQ_RSRC_IMG_RSVD_6', + 'SQ_RSRC_IMG_RSVD_7', 'SQ_RSRC_IMG_TYPE', 'SQ_SCRATCH', + 'SQ_SCRATCH_LOAD_DWORD', 'SQ_SCRATCH_LOAD_DWORDX2', + 'SQ_SCRATCH_LOAD_DWORDX3', 'SQ_SCRATCH_LOAD_DWORDX4', + 'SQ_SCRATCH_LOAD_SBYTE', 'SQ_SCRATCH_LOAD_SSHORT', + 'SQ_SCRATCH_LOAD_UBYTE', 'SQ_SCRATCH_LOAD_USHORT', + 'SQ_SCRATCH_STORE_BYTE', 'SQ_SCRATCH_STORE_DWORD', + 'SQ_SCRATCH_STORE_DWORDX2', 'SQ_SCRATCH_STORE_DWORDX3', + 'SQ_SCRATCH_STORE_DWORDX4', 'SQ_SCRATCH_STORE_SHORT', + 'SQ_SDWA_BYTE_0', 'SQ_SDWA_BYTE_1', 'SQ_SDWA_BYTE_2', + 'SQ_SDWA_BYTE_3', 'SQ_SDWA_DWORD', 'SQ_SDWA_UNUSED_PAD', + 'SQ_SDWA_UNUSED_PRESERVE', 'SQ_SDWA_UNUSED_SEXT', + 'SQ_SDWA_WORD_0', 'SQ_SDWA_WORD_1', 'SQ_SEL_0', 'SQ_SEL_1', + 'SQ_SEL_RESERVED_0', 'SQ_SEL_RESERVED_1', 'SQ_SEL_W', 'SQ_SEL_X', + 'SQ_SEL_XYZW01', 'SQ_SEL_Y', 'SQ_SEL_Z', 'SQ_SENDMSG_GSOP_SHIFT', + 'SQ_SENDMSG_GSOP_SIZE', 'SQ_SENDMSG_MSG_SHIFT', + 'SQ_SENDMSG_MSG_SIZE', 'SQ_SENDMSG_STREAMID_SHIFT', + 'SQ_SENDMSG_STREAMID_SIZE', 'SQ_SENDMSG_SYSTEM_SHIFT', + 'SQ_SENDMSG_SYSTEM_SIZE', 'SQ_SGPR0', 'SQ_SRC_0', 'SQ_SRC_0_5', + 'SQ_SRC_1', 'SQ_SRC_10_INT', 'SQ_SRC_11_INT', 'SQ_SRC_12_INT', + 'SQ_SRC_13_INT', 'SQ_SRC_14_INT', 'SQ_SRC_15_INT', + 'SQ_SRC_16_INT', 'SQ_SRC_17_INT', 'SQ_SRC_18_INT', + 'SQ_SRC_19_INT', 'SQ_SRC_1_INT', 'SQ_SRC_2', 'SQ_SRC_20_INT', + 'SQ_SRC_21_INT', 'SQ_SRC_22_INT', 'SQ_SRC_23_INT', + 'SQ_SRC_24_INT', 'SQ_SRC_25_INT', 'SQ_SRC_26_INT', + 'SQ_SRC_27_INT', 'SQ_SRC_28_INT', 'SQ_SRC_29_INT', 'SQ_SRC_2_INT', + 'SQ_SRC_30_INT', 'SQ_SRC_31_INT', 'SQ_SRC_32_INT', + 'SQ_SRC_33_INT', 'SQ_SRC_34_INT', 'SQ_SRC_35_INT', + 'SQ_SRC_36_INT', 'SQ_SRC_37_INT', 'SQ_SRC_38_INT', + 'SQ_SRC_39_INT', 'SQ_SRC_3_INT', 'SQ_SRC_4', 'SQ_SRC_40_INT', + 'SQ_SRC_41_INT', 'SQ_SRC_42_INT', 'SQ_SRC_43_INT', + 'SQ_SRC_44_INT', 'SQ_SRC_45_INT', 'SQ_SRC_46_INT', + 'SQ_SRC_47_INT', 'SQ_SRC_48_INT', 'SQ_SRC_49_INT', 'SQ_SRC_4_INT', + 'SQ_SRC_50_INT', 'SQ_SRC_51_INT', 'SQ_SRC_52_INT', + 'SQ_SRC_53_INT', 'SQ_SRC_54_INT', 'SQ_SRC_55_INT', + 'SQ_SRC_56_INT', 'SQ_SRC_57_INT', 'SQ_SRC_58_INT', + 'SQ_SRC_59_INT', 'SQ_SRC_5_INT', 'SQ_SRC_60_INT', 'SQ_SRC_61_INT', + 'SQ_SRC_62_INT', 'SQ_SRC_63_INT', 'SQ_SRC_64_INT', 'SQ_SRC_6_INT', + 'SQ_SRC_7_INT', 'SQ_SRC_8_INT', 'SQ_SRC_9_INT', 'SQ_SRC_DPP', + 'SQ_SRC_EXECZ', 'SQ_SRC_INV_2PI', 'SQ_SRC_LDS_DIRECT', + 'SQ_SRC_LITERAL', 'SQ_SRC_M_0_5', 'SQ_SRC_M_1', 'SQ_SRC_M_10_INT', + 'SQ_SRC_M_11_INT', 'SQ_SRC_M_12_INT', 'SQ_SRC_M_13_INT', + 'SQ_SRC_M_14_INT', 'SQ_SRC_M_15_INT', 'SQ_SRC_M_16_INT', + 'SQ_SRC_M_1_INT', 'SQ_SRC_M_2', 'SQ_SRC_M_2_INT', + 'SQ_SRC_M_3_INT', 'SQ_SRC_M_4', 'SQ_SRC_M_4_INT', + 'SQ_SRC_M_5_INT', 'SQ_SRC_M_6_INT', 'SQ_SRC_M_7_INT', + 'SQ_SRC_M_8_INT', 'SQ_SRC_M_9_INT', 'SQ_SRC_POPS_EXITING_WAVE_ID', + 'SQ_SRC_PRIVATE_BASE', 'SQ_SRC_PRIVATE_LIMIT', 'SQ_SRC_SCC', + 'SQ_SRC_SDWA', 'SQ_SRC_SHARED_BASE', 'SQ_SRC_SHARED_LIMIT', + 'SQ_SRC_VCCZ', 'SQ_SRC_VGPR0', 'SQ_SRC_VGPR_BIT', + 'SQ_SYSMSG_OP_ECC_ERR_INTERRUPT', 'SQ_SYSMSG_OP_HOST_TRAP_ACK', + 'SQ_SYSMSG_OP_ILLEGAL_INST_INTERRUPT', + 'SQ_SYSMSG_OP_MEMVIOL_INTERRUPT', 'SQ_SYSMSG_OP_REG_RD', + 'SQ_SYSMSG_OP_TTRACE_PC', 'SQ_S_ABSDIFF_I32', 'SQ_S_ABS_I32', + 'SQ_S_ADDC_U32', 'SQ_S_ADDK_I32', 'SQ_S_ADD_I32', 'SQ_S_ADD_U32', + 'SQ_S_ANDN1_SAVEEXEC_B64', 'SQ_S_ANDN1_WREXEC_B64', + 'SQ_S_ANDN2_B32', 'SQ_S_ANDN2_B64', 'SQ_S_ANDN2_SAVEEXEC_B64', + 'SQ_S_ANDN2_WREXEC_B64', 'SQ_S_AND_B32', 'SQ_S_AND_B64', + 'SQ_S_AND_SAVEEXEC_B64', 'SQ_S_ASHR_I32', 'SQ_S_ASHR_I64', + 'SQ_S_ATC_PROBE', 'SQ_S_ATC_PROBE_BUFFER', 'SQ_S_ATOMIC_ADD', + 'SQ_S_ATOMIC_ADD_X2', 'SQ_S_ATOMIC_AND', 'SQ_S_ATOMIC_AND_X2', + 'SQ_S_ATOMIC_CMPSWAP', 'SQ_S_ATOMIC_CMPSWAP_X2', + 'SQ_S_ATOMIC_DEC', 'SQ_S_ATOMIC_DEC_X2', 'SQ_S_ATOMIC_INC', + 'SQ_S_ATOMIC_INC_X2', 'SQ_S_ATOMIC_OR', 'SQ_S_ATOMIC_OR_X2', + 'SQ_S_ATOMIC_SMAX', 'SQ_S_ATOMIC_SMAX_X2', 'SQ_S_ATOMIC_SMIN', + 'SQ_S_ATOMIC_SMIN_X2', 'SQ_S_ATOMIC_SUB', 'SQ_S_ATOMIC_SUB_X2', + 'SQ_S_ATOMIC_SWAP', 'SQ_S_ATOMIC_SWAP_X2', 'SQ_S_ATOMIC_UMAX', + 'SQ_S_ATOMIC_UMAX_X2', 'SQ_S_ATOMIC_UMIN', 'SQ_S_ATOMIC_UMIN_X2', + 'SQ_S_ATOMIC_XOR', 'SQ_S_ATOMIC_XOR_X2', 'SQ_S_BARRIER', + 'SQ_S_BCNT0_I32_B32', 'SQ_S_BCNT0_I32_B64', 'SQ_S_BCNT1_I32_B32', + 'SQ_S_BCNT1_I32_B64', 'SQ_S_BFE_I32', 'SQ_S_BFE_I64', + 'SQ_S_BFE_U32', 'SQ_S_BFE_U64', 'SQ_S_BFM_B32', 'SQ_S_BFM_B64', + 'SQ_S_BITCMP0_B32', 'SQ_S_BITCMP0_B64', 'SQ_S_BITCMP1_B32', + 'SQ_S_BITCMP1_B64', 'SQ_S_BITREPLICATE_B64_B32', + 'SQ_S_BITSET0_B32', 'SQ_S_BITSET0_B64', 'SQ_S_BITSET1_B32', + 'SQ_S_BITSET1_B64', 'SQ_S_BRANCH', 'SQ_S_BREV_B32', + 'SQ_S_BREV_B64', 'SQ_S_BUFFER_ATOMIC_ADD', + 'SQ_S_BUFFER_ATOMIC_ADD_X2', 'SQ_S_BUFFER_ATOMIC_AND', + 'SQ_S_BUFFER_ATOMIC_AND_X2', 'SQ_S_BUFFER_ATOMIC_CMPSWAP', + 'SQ_S_BUFFER_ATOMIC_CMPSWAP_X2', 'SQ_S_BUFFER_ATOMIC_DEC', + 'SQ_S_BUFFER_ATOMIC_DEC_X2', 'SQ_S_BUFFER_ATOMIC_INC', + 'SQ_S_BUFFER_ATOMIC_INC_X2', 'SQ_S_BUFFER_ATOMIC_OR', + 'SQ_S_BUFFER_ATOMIC_OR_X2', 'SQ_S_BUFFER_ATOMIC_SMAX', + 'SQ_S_BUFFER_ATOMIC_SMAX_X2', 'SQ_S_BUFFER_ATOMIC_SMIN', + 'SQ_S_BUFFER_ATOMIC_SMIN_X2', 'SQ_S_BUFFER_ATOMIC_SUB', + 'SQ_S_BUFFER_ATOMIC_SUB_X2', 'SQ_S_BUFFER_ATOMIC_SWAP', + 'SQ_S_BUFFER_ATOMIC_SWAP_X2', 'SQ_S_BUFFER_ATOMIC_UMAX', + 'SQ_S_BUFFER_ATOMIC_UMAX_X2', 'SQ_S_BUFFER_ATOMIC_UMIN', + 'SQ_S_BUFFER_ATOMIC_UMIN_X2', 'SQ_S_BUFFER_ATOMIC_XOR', + 'SQ_S_BUFFER_ATOMIC_XOR_X2', 'SQ_S_BUFFER_LOAD_DWORD', + 'SQ_S_BUFFER_LOAD_DWORDX16', 'SQ_S_BUFFER_LOAD_DWORDX2', + 'SQ_S_BUFFER_LOAD_DWORDX4', 'SQ_S_BUFFER_LOAD_DWORDX8', + 'SQ_S_BUFFER_STORE_DWORD', 'SQ_S_BUFFER_STORE_DWORDX2', + 'SQ_S_BUFFER_STORE_DWORDX4', 'SQ_S_CALL_B64', + 'SQ_S_CBRANCH_CDBGSYS', 'SQ_S_CBRANCH_CDBGSYS_AND_USER', + 'SQ_S_CBRANCH_CDBGSYS_OR_USER', 'SQ_S_CBRANCH_CDBGUSER', + 'SQ_S_CBRANCH_EXECNZ', 'SQ_S_CBRANCH_EXECZ', + 'SQ_S_CBRANCH_G_FORK', 'SQ_S_CBRANCH_I_FORK', 'SQ_S_CBRANCH_JOIN', + 'SQ_S_CBRANCH_SCC0', 'SQ_S_CBRANCH_SCC1', 'SQ_S_CBRANCH_VCCNZ', + 'SQ_S_CBRANCH_VCCZ', 'SQ_S_CMOVK_I32', 'SQ_S_CMOV_B32', + 'SQ_S_CMOV_B64', 'SQ_S_CMPK_EQ_I32', 'SQ_S_CMPK_EQ_U32', + 'SQ_S_CMPK_GE_I32', 'SQ_S_CMPK_GE_U32', 'SQ_S_CMPK_GT_I32', + 'SQ_S_CMPK_GT_U32', 'SQ_S_CMPK_LE_I32', 'SQ_S_CMPK_LE_U32', + 'SQ_S_CMPK_LG_I32', 'SQ_S_CMPK_LG_U32', 'SQ_S_CMPK_LT_I32', + 'SQ_S_CMPK_LT_U32', 'SQ_S_CMP_EQ_I32', 'SQ_S_CMP_EQ_U32', + 'SQ_S_CMP_EQ_U64', 'SQ_S_CMP_GE_I32', 'SQ_S_CMP_GE_U32', + 'SQ_S_CMP_GT_I32', 'SQ_S_CMP_GT_U32', 'SQ_S_CMP_LE_I32', + 'SQ_S_CMP_LE_U32', 'SQ_S_CMP_LG_I32', 'SQ_S_CMP_LG_U32', + 'SQ_S_CMP_LG_U64', 'SQ_S_CMP_LT_I32', 'SQ_S_CMP_LT_U32', + 'SQ_S_CSELECT_B32', 'SQ_S_CSELECT_B64', 'SQ_S_DCACHE_INV', + 'SQ_S_DCACHE_INV_VOL', 'SQ_S_DCACHE_WB', 'SQ_S_DCACHE_WB_VOL', + 'SQ_S_DECPERFLEVEL', 'SQ_S_ENDPGM', 'SQ_S_ENDPGM_ORDERED_PS_DONE', + 'SQ_S_ENDPGM_SAVED', 'SQ_S_FF0_I32_B32', 'SQ_S_FF0_I32_B64', + 'SQ_S_FF1_I32_B32', 'SQ_S_FF1_I32_B64', 'SQ_S_FLBIT_I32', + 'SQ_S_FLBIT_I32_B32', 'SQ_S_FLBIT_I32_B64', 'SQ_S_FLBIT_I32_I64', + 'SQ_S_GETPC_B64', 'SQ_S_GETREG_B32', 'SQ_S_GETREG_REGRD_B32', + 'SQ_S_ICACHE_INV', 'SQ_S_INCPERFLEVEL', 'SQ_S_LOAD_DWORD', + 'SQ_S_LOAD_DWORDX16', 'SQ_S_LOAD_DWORDX2', 'SQ_S_LOAD_DWORDX4', + 'SQ_S_LOAD_DWORDX8', 'SQ_S_LSHL1_ADD_U32', 'SQ_S_LSHL2_ADD_U32', + 'SQ_S_LSHL3_ADD_U32', 'SQ_S_LSHL4_ADD_U32', 'SQ_S_LSHL_B32', + 'SQ_S_LSHL_B64', 'SQ_S_LSHR_B32', 'SQ_S_LSHR_B64', 'SQ_S_MAX_I32', + 'SQ_S_MAX_U32', 'SQ_S_MEMREALTIME', 'SQ_S_MEMTIME', + 'SQ_S_MIN_I32', 'SQ_S_MIN_U32', 'SQ_S_MOVK_I32', + 'SQ_S_MOVRELD_B32', 'SQ_S_MOVRELD_B64', 'SQ_S_MOVRELS_B32', + 'SQ_S_MOVRELS_B64', 'SQ_S_MOV_B32', 'SQ_S_MOV_B64', + 'SQ_S_MOV_FED_B32', 'SQ_S_MOV_REGRD_B32', 'SQ_S_MULK_I32', + 'SQ_S_MUL_HI_I32', 'SQ_S_MUL_HI_U32', 'SQ_S_MUL_I32', + 'SQ_S_NAND_B32', 'SQ_S_NAND_B64', 'SQ_S_NAND_SAVEEXEC_B64', + 'SQ_S_NOP', 'SQ_S_NOR_B32', 'SQ_S_NOR_B64', + 'SQ_S_NOR_SAVEEXEC_B64', 'SQ_S_NOT_B32', 'SQ_S_NOT_B64', + 'SQ_S_ORN1_SAVEEXEC_B64', 'SQ_S_ORN2_B32', 'SQ_S_ORN2_B64', + 'SQ_S_ORN2_SAVEEXEC_B64', 'SQ_S_OR_B32', 'SQ_S_OR_B64', + 'SQ_S_OR_SAVEEXEC_B64', 'SQ_S_PACK_HH_B32_B16', + 'SQ_S_PACK_LH_B32_B16', 'SQ_S_PACK_LL_B32_B16', + 'SQ_S_QUADMASK_B32', 'SQ_S_QUADMASK_B64', 'SQ_S_RFE_B64', + 'SQ_S_RFE_RESTORE_B64', 'SQ_S_SCRATCH_LOAD_DWORD', + 'SQ_S_SCRATCH_LOAD_DWORDX2', 'SQ_S_SCRATCH_LOAD_DWORDX4', + 'SQ_S_SCRATCH_STORE_DWORD', 'SQ_S_SCRATCH_STORE_DWORDX2', + 'SQ_S_SCRATCH_STORE_DWORDX4', 'SQ_S_SENDMSG', 'SQ_S_SENDMSGHALT', + 'SQ_S_SETHALT', 'SQ_S_SETKILL', 'SQ_S_SETPC_B64', 'SQ_S_SETPRIO', + 'SQ_S_SETREG_B32', 'SQ_S_SETREG_IMM32_B32', 'SQ_S_SETVSKIP', + 'SQ_S_SET_GPR_IDX_IDX', 'SQ_S_SET_GPR_IDX_MODE', + 'SQ_S_SET_GPR_IDX_OFF', 'SQ_S_SET_GPR_IDX_ON', + 'SQ_S_SEXT_I32_I16', 'SQ_S_SEXT_I32_I8', 'SQ_S_SLEEP', + 'SQ_S_STORE_DWORD', 'SQ_S_STORE_DWORDX2', 'SQ_S_STORE_DWORDX4', + 'SQ_S_SUBB_U32', 'SQ_S_SUB_I32', 'SQ_S_SUB_U32', + 'SQ_S_SWAPPC_B64', 'SQ_S_TRAP', 'SQ_S_TTRACEDATA', 'SQ_S_WAITCNT', + 'SQ_S_WAKEUP', 'SQ_S_WQM_B32', 'SQ_S_WQM_B64', 'SQ_S_XNOR_B32', + 'SQ_S_XNOR_B64', 'SQ_S_XNOR_SAVEEXEC_B64', 'SQ_S_XOR_B32', + 'SQ_S_XOR_B64', 'SQ_S_XOR_SAVEEXEC_B64', 'SQ_T', + 'SQ_TBUFFER_LOAD_FORMAT_D16_X', 'SQ_TBUFFER_LOAD_FORMAT_D16_XY', + 'SQ_TBUFFER_LOAD_FORMAT_D16_XYZ', + 'SQ_TBUFFER_LOAD_FORMAT_D16_XYZW', 'SQ_TBUFFER_LOAD_FORMAT_X', + 'SQ_TBUFFER_LOAD_FORMAT_XY', 'SQ_TBUFFER_LOAD_FORMAT_XYZ', + 'SQ_TBUFFER_LOAD_FORMAT_XYZW', 'SQ_TBUFFER_STORE_FORMAT_D16_X', + 'SQ_TBUFFER_STORE_FORMAT_D16_XY', + 'SQ_TBUFFER_STORE_FORMAT_D16_XYZ', + 'SQ_TBUFFER_STORE_FORMAT_D16_XYZW', 'SQ_TBUFFER_STORE_FORMAT_X', + 'SQ_TBUFFER_STORE_FORMAT_XY', 'SQ_TBUFFER_STORE_FORMAT_XYZ', + 'SQ_TBUFFER_STORE_FORMAT_XYZW', 'SQ_TEX_ANISO_RATIO', + 'SQ_TEX_ANISO_RATIO_1', 'SQ_TEX_ANISO_RATIO_16', + 'SQ_TEX_ANISO_RATIO_2', 'SQ_TEX_ANISO_RATIO_4', + 'SQ_TEX_ANISO_RATIO_8', 'SQ_TEX_BORDER_COLOR', + 'SQ_TEX_BORDER_COLOR_OPAQUE_BLACK', + 'SQ_TEX_BORDER_COLOR_OPAQUE_WHITE', + 'SQ_TEX_BORDER_COLOR_REGISTER', 'SQ_TEX_BORDER_COLOR_TRANS_BLACK', + 'SQ_TEX_CLAMP', 'SQ_TEX_CLAMP_BORDER', 'SQ_TEX_CLAMP_HALF_BORDER', + 'SQ_TEX_CLAMP_LAST_TEXEL', 'SQ_TEX_DEPTH_COMPARE', + 'SQ_TEX_DEPTH_COMPARE_ALWAYS', 'SQ_TEX_DEPTH_COMPARE_EQUAL', + 'SQ_TEX_DEPTH_COMPARE_GREATER', + 'SQ_TEX_DEPTH_COMPARE_GREATEREQUAL', 'SQ_TEX_DEPTH_COMPARE_LESS', + 'SQ_TEX_DEPTH_COMPARE_LESSEQUAL', 'SQ_TEX_DEPTH_COMPARE_NEVER', + 'SQ_TEX_DEPTH_COMPARE_NOTEQUAL', 'SQ_TEX_MIP_FILTER', + 'SQ_TEX_MIP_FILTER_LINEAR', 'SQ_TEX_MIP_FILTER_NONE', + 'SQ_TEX_MIP_FILTER_POINT', 'SQ_TEX_MIP_FILTER_POINT_ANISO_ADJ', + 'SQ_TEX_MIRROR', 'SQ_TEX_MIRROR_ONCE_BORDER', + 'SQ_TEX_MIRROR_ONCE_HALF_BORDER', 'SQ_TEX_MIRROR_ONCE_LAST_TEXEL', + 'SQ_TEX_WRAP', 'SQ_TEX_XY_FILTER', + 'SQ_TEX_XY_FILTER_ANISO_BILINEAR', 'SQ_TEX_XY_FILTER_ANISO_POINT', + 'SQ_TEX_XY_FILTER_BILINEAR', 'SQ_TEX_XY_FILTER_POINT', + 'SQ_TEX_Z_FILTER', 'SQ_TEX_Z_FILTER_LINEAR', + 'SQ_TEX_Z_FILTER_NONE', 'SQ_TEX_Z_FILTER_POINT', + 'SQ_THREAD_TRACE_CAPTURE_MODE', + 'SQ_THREAD_TRACE_CAPTURE_MODE_ALL', + 'SQ_THREAD_TRACE_CAPTURE_MODE_SELECT', + 'SQ_THREAD_TRACE_CAPTURE_MODE_SELECT_DETAIL', + 'SQ_THREAD_TRACE_INST_TYPE', + 'SQ_THREAD_TRACE_INST_TYPE_EXPGNT_PAR_COL', + 'SQ_THREAD_TRACE_INST_TYPE_EXPGNT_POS_GDS', + 'SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GDS', + 'SQ_THREAD_TRACE_INST_TYPE_EXPREQ_GFX', + 'SQ_THREAD_TRACE_INST_TYPE_FATAL_HALT', + 'SQ_THREAD_TRACE_INST_TYPE_FLAT_RD', + 'SQ_THREAD_TRACE_INST_TYPE_FLAT_RD_REPLAY', + 'SQ_THREAD_TRACE_INST_TYPE_FLAT_WR', + 'SQ_THREAD_TRACE_INST_TYPE_FLAT_WR_REPLAY', + 'SQ_THREAD_TRACE_INST_TYPE_JUMP', 'SQ_THREAD_TRACE_INST_TYPE_LDS', + 'SQ_THREAD_TRACE_INST_TYPE_NEXT', + 'SQ_THREAD_TRACE_INST_TYPE_OTHER_MSG', + 'SQ_THREAD_TRACE_INST_TYPE_PC', + 'SQ_THREAD_TRACE_INST_TYPE_SALU_32', + 'SQ_THREAD_TRACE_INST_TYPE_SALU_64', + 'SQ_THREAD_TRACE_INST_TYPE_SMEM_RD', + 'SQ_THREAD_TRACE_INST_TYPE_SMEM_RD_REPLAY', + 'SQ_THREAD_TRACE_INST_TYPE_SMEM_WR', + 'SQ_THREAD_TRACE_INST_TYPE_SMEM_WR_REPLAY', + 'SQ_THREAD_TRACE_INST_TYPE_VALU_32', + 'SQ_THREAD_TRACE_INST_TYPE_VALU_64', + 'SQ_THREAD_TRACE_INST_TYPE_VMEM_RD', + 'SQ_THREAD_TRACE_INST_TYPE_VMEM_RD_REPLAY', + 'SQ_THREAD_TRACE_INST_TYPE_VMEM_WR', + 'SQ_THREAD_TRACE_INST_TYPE_VMEM_WR_REPLAY', + 'SQ_THREAD_TRACE_ISSUE', 'SQ_THREAD_TRACE_ISSUE_IMMED', + 'SQ_THREAD_TRACE_ISSUE_INST', 'SQ_THREAD_TRACE_ISSUE_MASK', + 'SQ_THREAD_TRACE_ISSUE_MASK_ALL', + 'SQ_THREAD_TRACE_ISSUE_MASK_IMMED', + 'SQ_THREAD_TRACE_ISSUE_MASK_STALLED', + 'SQ_THREAD_TRACE_ISSUE_MASK_STALLED_AND_IMMED', + 'SQ_THREAD_TRACE_ISSUE_NULL', 'SQ_THREAD_TRACE_ISSUE_STALL', + 'SQ_THREAD_TRACE_MISC_TOKEN_PACKET_LOST', + 'SQ_THREAD_TRACE_MISC_TOKEN_SAVECTX', + 'SQ_THREAD_TRACE_MISC_TOKEN_SHOOT_DOWN', + 'SQ_THREAD_TRACE_MISC_TOKEN_SURF_SYNC', + 'SQ_THREAD_TRACE_MISC_TOKEN_TIME', + 'SQ_THREAD_TRACE_MISC_TOKEN_TIME_RESET', + 'SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_BEGIN', + 'SQ_THREAD_TRACE_MISC_TOKEN_TTRACE_STALL_END', + 'SQ_THREAD_TRACE_MISC_TOKEN_TYPE', 'SQ_THREAD_TRACE_MODE_OFF', + 'SQ_THREAD_TRACE_MODE_ON', 'SQ_THREAD_TRACE_MODE_SEL', + 'SQ_THREAD_TRACE_REG_OP', 'SQ_THREAD_TRACE_REG_OP_READ', + 'SQ_THREAD_TRACE_REG_OP_WRITE', 'SQ_THREAD_TRACE_REG_TYPE', + 'SQ_THREAD_TRACE_REG_TYPE_DISPATCH', + 'SQ_THREAD_TRACE_REG_TYPE_DRAW', 'SQ_THREAD_TRACE_REG_TYPE_EVENT', + 'SQ_THREAD_TRACE_REG_TYPE_GFXDEC', + 'SQ_THREAD_TRACE_REG_TYPE_MARKER', + 'SQ_THREAD_TRACE_REG_TYPE_OTHER', + 'SQ_THREAD_TRACE_REG_TYPE_SHDEC', + 'SQ_THREAD_TRACE_REG_TYPE_USERDATA', 'SQ_THREAD_TRACE_TIME_UNIT', + 'SQ_THREAD_TRACE_TOKEN_EVENT', 'SQ_THREAD_TRACE_TOKEN_EVENT_CS', + 'SQ_THREAD_TRACE_TOKEN_EVENT_GFX1', 'SQ_THREAD_TRACE_TOKEN_INST', + 'SQ_THREAD_TRACE_TOKEN_INST_PC', + 'SQ_THREAD_TRACE_TOKEN_INST_USERDATA', + 'SQ_THREAD_TRACE_TOKEN_ISSUE', 'SQ_THREAD_TRACE_TOKEN_MISC', + 'SQ_THREAD_TRACE_TOKEN_PERF', 'SQ_THREAD_TRACE_TOKEN_REG', + 'SQ_THREAD_TRACE_TOKEN_REG_CS', + 'SQ_THREAD_TRACE_TOKEN_REG_CSPRIV', + 'SQ_THREAD_TRACE_TOKEN_TIMESTAMP', 'SQ_THREAD_TRACE_TOKEN_TYPE', + 'SQ_THREAD_TRACE_TOKEN_WAVE_ALLOC', + 'SQ_THREAD_TRACE_TOKEN_WAVE_END', + 'SQ_THREAD_TRACE_TOKEN_WAVE_START', 'SQ_THREAD_TRACE_VM_ID_MASK', + 'SQ_THREAD_TRACE_VM_ID_MASK_ALL', + 'SQ_THREAD_TRACE_VM_ID_MASK_SINGLE', + 'SQ_THREAD_TRACE_VM_ID_MASK_SINGLE_DETAIL', + 'SQ_THREAD_TRACE_WAVE_MASK', 'SQ_THREAD_TRACE_WAVE_MASK_ALL', + 'SQ_THREAD_TRACE_WAVE_MASK_NONE', + 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX', + 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_RESTORE', + 'SQ_THREAD_TRACE_WAVE_START_COUNT_PREFIX_WREXEC', 'SQ_TRU', + 'SQ_TTMP0', 'SQ_TTMP1', 'SQ_TTMP10', 'SQ_TTMP11', 'SQ_TTMP12', + 'SQ_TTMP13', 'SQ_TTMP14', 'SQ_TTMP15', 'SQ_TTMP2', 'SQ_TTMP3', + 'SQ_TTMP4', 'SQ_TTMP5', 'SQ_TTMP6', 'SQ_TTMP7', 'SQ_TTMP8', + 'SQ_TTMP9', 'SQ_U', 'SQ_VCC_ALL', 'SQ_VCC_HI', 'SQ_VCC_LO', + 'SQ_VGPR0', 'SQ_V_ADD3_U32', 'SQ_V_ADDC_CO_U32', + 'SQ_V_ADD_CO_U32', 'SQ_V_ADD_F16', 'SQ_V_ADD_F32', 'SQ_V_ADD_F64', + 'SQ_V_ADD_I16', 'SQ_V_ADD_I32', 'SQ_V_ADD_LSHL_U32', + 'SQ_V_ADD_U16', 'SQ_V_ADD_U32', 'SQ_V_ALIGNBIT_B32', + 'SQ_V_ALIGNBYTE_B32', 'SQ_V_AND_B32', 'SQ_V_AND_OR_B32', + 'SQ_V_ASHRREV_I16', 'SQ_V_ASHRREV_I32', 'SQ_V_ASHRREV_I64', + 'SQ_V_BCNT_U32_B32', 'SQ_V_BFE_I32', 'SQ_V_BFE_U32', + 'SQ_V_BFI_B32', 'SQ_V_BFM_B32', 'SQ_V_BFREV_B32', 'SQ_V_CEIL_F16', + 'SQ_V_CEIL_F32', 'SQ_V_CEIL_F64', 'SQ_V_CLREXCP', + 'SQ_V_CMPX_CLASS_F16', 'SQ_V_CMPX_CLASS_F32', + 'SQ_V_CMPX_CLASS_F64', 'SQ_V_CMPX_EQ_F16', 'SQ_V_CMPX_EQ_F32', + 'SQ_V_CMPX_EQ_F64', 'SQ_V_CMPX_EQ_I16', 'SQ_V_CMPX_EQ_I32', + 'SQ_V_CMPX_EQ_I64', 'SQ_V_CMPX_EQ_U16', 'SQ_V_CMPX_EQ_U32', + 'SQ_V_CMPX_EQ_U64', 'SQ_V_CMPX_F_F16', 'SQ_V_CMPX_F_F32', + 'SQ_V_CMPX_F_F64', 'SQ_V_CMPX_F_I16', 'SQ_V_CMPX_F_I32', + 'SQ_V_CMPX_F_I64', 'SQ_V_CMPX_F_U16', 'SQ_V_CMPX_F_U32', + 'SQ_V_CMPX_F_U64', 'SQ_V_CMPX_GE_F16', 'SQ_V_CMPX_GE_F32', + 'SQ_V_CMPX_GE_F64', 'SQ_V_CMPX_GE_I16', 'SQ_V_CMPX_GE_I32', + 'SQ_V_CMPX_GE_I64', 'SQ_V_CMPX_GE_U16', 'SQ_V_CMPX_GE_U32', + 'SQ_V_CMPX_GE_U64', 'SQ_V_CMPX_GT_F16', 'SQ_V_CMPX_GT_F32', + 'SQ_V_CMPX_GT_F64', 'SQ_V_CMPX_GT_I16', 'SQ_V_CMPX_GT_I32', + 'SQ_V_CMPX_GT_I64', 'SQ_V_CMPX_GT_U16', 'SQ_V_CMPX_GT_U32', + 'SQ_V_CMPX_GT_U64', 'SQ_V_CMPX_LE_F16', 'SQ_V_CMPX_LE_F32', + 'SQ_V_CMPX_LE_F64', 'SQ_V_CMPX_LE_I16', 'SQ_V_CMPX_LE_I32', + 'SQ_V_CMPX_LE_I64', 'SQ_V_CMPX_LE_U16', 'SQ_V_CMPX_LE_U32', + 'SQ_V_CMPX_LE_U64', 'SQ_V_CMPX_LG_F16', 'SQ_V_CMPX_LG_F32', + 'SQ_V_CMPX_LG_F64', 'SQ_V_CMPX_LT_F16', 'SQ_V_CMPX_LT_F32', + 'SQ_V_CMPX_LT_F64', 'SQ_V_CMPX_LT_I16', 'SQ_V_CMPX_LT_I32', + 'SQ_V_CMPX_LT_I64', 'SQ_V_CMPX_LT_U16', 'SQ_V_CMPX_LT_U32', + 'SQ_V_CMPX_LT_U64', 'SQ_V_CMPX_NEQ_F16', 'SQ_V_CMPX_NEQ_F32', + 'SQ_V_CMPX_NEQ_F64', 'SQ_V_CMPX_NE_I16', 'SQ_V_CMPX_NE_I32', + 'SQ_V_CMPX_NE_I64', 'SQ_V_CMPX_NE_U16', 'SQ_V_CMPX_NE_U32', + 'SQ_V_CMPX_NE_U64', 'SQ_V_CMPX_NGE_F16', 'SQ_V_CMPX_NGE_F32', + 'SQ_V_CMPX_NGE_F64', 'SQ_V_CMPX_NGT_F16', 'SQ_V_CMPX_NGT_F32', + 'SQ_V_CMPX_NGT_F64', 'SQ_V_CMPX_NLE_F16', 'SQ_V_CMPX_NLE_F32', + 'SQ_V_CMPX_NLE_F64', 'SQ_V_CMPX_NLG_F16', 'SQ_V_CMPX_NLG_F32', + 'SQ_V_CMPX_NLG_F64', 'SQ_V_CMPX_NLT_F16', 'SQ_V_CMPX_NLT_F32', + 'SQ_V_CMPX_NLT_F64', 'SQ_V_CMPX_O_F16', 'SQ_V_CMPX_O_F32', + 'SQ_V_CMPX_O_F64', 'SQ_V_CMPX_TRU_F16', 'SQ_V_CMPX_TRU_F32', + 'SQ_V_CMPX_TRU_F64', 'SQ_V_CMPX_T_I16', 'SQ_V_CMPX_T_I32', + 'SQ_V_CMPX_T_I64', 'SQ_V_CMPX_T_U16', 'SQ_V_CMPX_T_U32', + 'SQ_V_CMPX_T_U64', 'SQ_V_CMPX_U_F16', 'SQ_V_CMPX_U_F32', + 'SQ_V_CMPX_U_F64', 'SQ_V_CMP_CLASS_F16', 'SQ_V_CMP_CLASS_F32', + 'SQ_V_CMP_CLASS_F64', 'SQ_V_CMP_EQ_F16', 'SQ_V_CMP_EQ_F32', + 'SQ_V_CMP_EQ_F64', 'SQ_V_CMP_EQ_I16', 'SQ_V_CMP_EQ_I32', + 'SQ_V_CMP_EQ_I64', 'SQ_V_CMP_EQ_U16', 'SQ_V_CMP_EQ_U32', + 'SQ_V_CMP_EQ_U64', 'SQ_V_CMP_F_F16', 'SQ_V_CMP_F_F32', + 'SQ_V_CMP_F_F64', 'SQ_V_CMP_F_I16', 'SQ_V_CMP_F_I32', + 'SQ_V_CMP_F_I64', 'SQ_V_CMP_F_U16', 'SQ_V_CMP_F_U32', + 'SQ_V_CMP_F_U64', 'SQ_V_CMP_GE_F16', 'SQ_V_CMP_GE_F32', + 'SQ_V_CMP_GE_F64', 'SQ_V_CMP_GE_I16', 'SQ_V_CMP_GE_I32', + 'SQ_V_CMP_GE_I64', 'SQ_V_CMP_GE_U16', 'SQ_V_CMP_GE_U32', + 'SQ_V_CMP_GE_U64', 'SQ_V_CMP_GT_F16', 'SQ_V_CMP_GT_F32', + 'SQ_V_CMP_GT_F64', 'SQ_V_CMP_GT_I16', 'SQ_V_CMP_GT_I32', + 'SQ_V_CMP_GT_I64', 'SQ_V_CMP_GT_U16', 'SQ_V_CMP_GT_U32', + 'SQ_V_CMP_GT_U64', 'SQ_V_CMP_LE_F16', 'SQ_V_CMP_LE_F32', + 'SQ_V_CMP_LE_F64', 'SQ_V_CMP_LE_I16', 'SQ_V_CMP_LE_I32', + 'SQ_V_CMP_LE_I64', 'SQ_V_CMP_LE_U16', 'SQ_V_CMP_LE_U32', + 'SQ_V_CMP_LE_U64', 'SQ_V_CMP_LG_F16', 'SQ_V_CMP_LG_F32', + 'SQ_V_CMP_LG_F64', 'SQ_V_CMP_LT_F16', 'SQ_V_CMP_LT_F32', + 'SQ_V_CMP_LT_F64', 'SQ_V_CMP_LT_I16', 'SQ_V_CMP_LT_I32', + 'SQ_V_CMP_LT_I64', 'SQ_V_CMP_LT_U16', 'SQ_V_CMP_LT_U32', + 'SQ_V_CMP_LT_U64', 'SQ_V_CMP_NEQ_F16', 'SQ_V_CMP_NEQ_F32', + 'SQ_V_CMP_NEQ_F64', 'SQ_V_CMP_NE_I16', 'SQ_V_CMP_NE_I32', + 'SQ_V_CMP_NE_I64', 'SQ_V_CMP_NE_U16', 'SQ_V_CMP_NE_U32', + 'SQ_V_CMP_NE_U64', 'SQ_V_CMP_NGE_F16', 'SQ_V_CMP_NGE_F32', + 'SQ_V_CMP_NGE_F64', 'SQ_V_CMP_NGT_F16', 'SQ_V_CMP_NGT_F32', + 'SQ_V_CMP_NGT_F64', 'SQ_V_CMP_NLE_F16', 'SQ_V_CMP_NLE_F32', + 'SQ_V_CMP_NLE_F64', 'SQ_V_CMP_NLG_F16', 'SQ_V_CMP_NLG_F32', + 'SQ_V_CMP_NLG_F64', 'SQ_V_CMP_NLT_F16', 'SQ_V_CMP_NLT_F32', + 'SQ_V_CMP_NLT_F64', 'SQ_V_CMP_O_F16', 'SQ_V_CMP_O_F32', + 'SQ_V_CMP_O_F64', 'SQ_V_CMP_TRU_F16', 'SQ_V_CMP_TRU_F32', + 'SQ_V_CMP_TRU_F64', 'SQ_V_CMP_T_I16', 'SQ_V_CMP_T_I32', + 'SQ_V_CMP_T_I64', 'SQ_V_CMP_T_U16', 'SQ_V_CMP_T_U32', + 'SQ_V_CMP_T_U64', 'SQ_V_CMP_U_F16', 'SQ_V_CMP_U_F32', + 'SQ_V_CMP_U_F64', 'SQ_V_CNDMASK_B32', 'SQ_V_COS_F16', + 'SQ_V_COS_F32', 'SQ_V_CUBEID_F32', 'SQ_V_CUBEMA_F32', + 'SQ_V_CUBESC_F32', 'SQ_V_CUBETC_F32', 'SQ_V_CVT_F16_F32', + 'SQ_V_CVT_F16_I16', 'SQ_V_CVT_F16_U16', 'SQ_V_CVT_F32_F16', + 'SQ_V_CVT_F32_F64', 'SQ_V_CVT_F32_I32', 'SQ_V_CVT_F32_U32', + 'SQ_V_CVT_F32_UBYTE0', 'SQ_V_CVT_F32_UBYTE1', + 'SQ_V_CVT_F32_UBYTE2', 'SQ_V_CVT_F32_UBYTE3', 'SQ_V_CVT_F64_F32', + 'SQ_V_CVT_F64_I32', 'SQ_V_CVT_F64_U32', 'SQ_V_CVT_FLR_I32_F32', + 'SQ_V_CVT_I16_F16', 'SQ_V_CVT_I32_F32', 'SQ_V_CVT_I32_F64', + 'SQ_V_CVT_NORM_I16_F16', 'SQ_V_CVT_NORM_U16_F16', + 'SQ_V_CVT_OFF_F32_I4', 'SQ_V_CVT_PKACCUM_U8_F32', + 'SQ_V_CVT_PKNORM_I16_F16', 'SQ_V_CVT_PKNORM_I16_F32', + 'SQ_V_CVT_PKNORM_U16_F16', 'SQ_V_CVT_PKNORM_U16_F32', + 'SQ_V_CVT_PKRTZ_F16_F32', 'SQ_V_CVT_PK_I16_I32', + 'SQ_V_CVT_PK_U16_U32', 'SQ_V_CVT_PK_U8_F32', + 'SQ_V_CVT_RPI_I32_F32', 'SQ_V_CVT_U16_F16', 'SQ_V_CVT_U32_F32', + 'SQ_V_CVT_U32_F64', 'SQ_V_DIV_FIXUP_F16', 'SQ_V_DIV_FIXUP_F32', + 'SQ_V_DIV_FIXUP_F64', 'SQ_V_DIV_FIXUP_LEGACY_F16', + 'SQ_V_DIV_FMAS_F32', 'SQ_V_DIV_FMAS_F64', 'SQ_V_DIV_SCALE_F32', + 'SQ_V_DIV_SCALE_F64', 'SQ_V_EXP_F16', 'SQ_V_EXP_F32', + 'SQ_V_EXP_LEGACY_F32', 'SQ_V_FFBH_I32', 'SQ_V_FFBH_U32', + 'SQ_V_FFBL_B32', 'SQ_V_FLOOR_F16', 'SQ_V_FLOOR_F32', + 'SQ_V_FLOOR_F64', 'SQ_V_FMA_F16', 'SQ_V_FMA_F32', 'SQ_V_FMA_F64', + 'SQ_V_FMA_LEGACY_F16', 'SQ_V_FRACT_F16', 'SQ_V_FRACT_F32', + 'SQ_V_FRACT_F64', 'SQ_V_FREXP_EXP_I16_F16', + 'SQ_V_FREXP_EXP_I32_F32', 'SQ_V_FREXP_EXP_I32_F64', + 'SQ_V_FREXP_MANT_F16', 'SQ_V_FREXP_MANT_F32', + 'SQ_V_FREXP_MANT_F64', 'SQ_V_INTERP_MOV_F32', + 'SQ_V_INTERP_P1LL_F16', 'SQ_V_INTERP_P1LV_F16', + 'SQ_V_INTERP_P1_F32', 'SQ_V_INTERP_P2_F16', 'SQ_V_INTERP_P2_F32', + 'SQ_V_INTERP_P2_LEGACY_F16', 'SQ_V_INTRP_COUNT', + 'SQ_V_INTRP_OFFSET', 'SQ_V_LDEXP_F16', 'SQ_V_LDEXP_F32', + 'SQ_V_LDEXP_F64', 'SQ_V_LERP_U8', 'SQ_V_LOG_F16', 'SQ_V_LOG_F32', + 'SQ_V_LOG_LEGACY_F32', 'SQ_V_LSHLREV_B16', 'SQ_V_LSHLREV_B32', + 'SQ_V_LSHLREV_B64', 'SQ_V_LSHL_ADD_U32', 'SQ_V_LSHL_OR_B32', + 'SQ_V_LSHRREV_B16', 'SQ_V_LSHRREV_B32', 'SQ_V_LSHRREV_B64', + 'SQ_V_MAC_F16', 'SQ_V_MAC_F32', 'SQ_V_MAC_LEGACY_F32', + 'SQ_V_MADAK_F16', 'SQ_V_MADAK_F32', 'SQ_V_MADMK_F16', + 'SQ_V_MADMK_F32', 'SQ_V_MAD_F16', 'SQ_V_MAD_F32', 'SQ_V_MAD_I16', + 'SQ_V_MAD_I32_I16', 'SQ_V_MAD_I32_I24', 'SQ_V_MAD_I64_I32', + 'SQ_V_MAD_LEGACY_F16', 'SQ_V_MAD_LEGACY_F32', + 'SQ_V_MAD_LEGACY_I16', 'SQ_V_MAD_LEGACY_U16', + 'SQ_V_MAD_MIXHI_F16', 'SQ_V_MAD_MIXLO_F16', 'SQ_V_MAD_MIX_F32', + 'SQ_V_MAD_U16', 'SQ_V_MAD_U32_U16', 'SQ_V_MAD_U32_U24', + 'SQ_V_MAD_U64_U32', 'SQ_V_MAX3_F16', 'SQ_V_MAX3_F32', + 'SQ_V_MAX3_I16', 'SQ_V_MAX3_I32', 'SQ_V_MAX3_U16', + 'SQ_V_MAX3_U32', 'SQ_V_MAX_F16', 'SQ_V_MAX_F32', 'SQ_V_MAX_F64', + 'SQ_V_MAX_I16', 'SQ_V_MAX_I32', 'SQ_V_MAX_U16', 'SQ_V_MAX_U32', + 'SQ_V_MBCNT_HI_U32_B32', 'SQ_V_MBCNT_LO_U32_B32', 'SQ_V_MED3_F16', + 'SQ_V_MED3_F32', 'SQ_V_MED3_I16', 'SQ_V_MED3_I32', + 'SQ_V_MED3_U16', 'SQ_V_MED3_U32', 'SQ_V_MIN3_F16', + 'SQ_V_MIN3_F32', 'SQ_V_MIN3_I16', 'SQ_V_MIN3_I32', + 'SQ_V_MIN3_U16', 'SQ_V_MIN3_U32', 'SQ_V_MIN_F16', 'SQ_V_MIN_F32', + 'SQ_V_MIN_F64', 'SQ_V_MIN_I16', 'SQ_V_MIN_I32', 'SQ_V_MIN_U16', + 'SQ_V_MIN_U32', 'SQ_V_MOV_B32', 'SQ_V_MOV_FED_B32', + 'SQ_V_MOV_PRSV_B32', 'SQ_V_MQSAD_PK_U16_U8', 'SQ_V_MQSAD_U32_U8', + 'SQ_V_MSAD_U8', 'SQ_V_MUL_F16', 'SQ_V_MUL_F32', 'SQ_V_MUL_F64', + 'SQ_V_MUL_HI_I32', 'SQ_V_MUL_HI_I32_I24', 'SQ_V_MUL_HI_U32', + 'SQ_V_MUL_HI_U32_U24', 'SQ_V_MUL_I32_I24', 'SQ_V_MUL_LEGACY_F32', + 'SQ_V_MUL_LO_U16', 'SQ_V_MUL_LO_U32', 'SQ_V_MUL_U32_U24', + 'SQ_V_NOP', 'SQ_V_NOT_B32', 'SQ_V_OP1_COUNT', 'SQ_V_OP1_OFFSET', + 'SQ_V_OP2_COUNT', 'SQ_V_OP2_OFFSET', 'SQ_V_OP3P_COUNT', + 'SQ_V_OP3P_OFFSET', 'SQ_V_OP3_2IN_COUNT', 'SQ_V_OP3_2IN_OFFSET', + 'SQ_V_OP3_3IN_COUNT', 'SQ_V_OP3_3IN_OFFSET', + 'SQ_V_OP3_INTRP_COUNT', 'SQ_V_OP3_INTRP_OFFSET', 'SQ_V_OPC_COUNT', + 'SQ_V_OPC_OFFSET', 'SQ_V_OR3_B32', 'SQ_V_OR_B32', + 'SQ_V_PACK_B32_F16', 'SQ_V_PERM_B32', 'SQ_V_PK_ADD_F16', + 'SQ_V_PK_ADD_I16', 'SQ_V_PK_ADD_U16', 'SQ_V_PK_ASHRREV_I16', + 'SQ_V_PK_LSHLREV_B16', 'SQ_V_PK_LSHRREV_B16', 'SQ_V_PK_MAD_F16', + 'SQ_V_PK_MAD_I16', 'SQ_V_PK_MAD_U16', 'SQ_V_PK_MAX_F16', + 'SQ_V_PK_MAX_I16', 'SQ_V_PK_MAX_U16', 'SQ_V_PK_MIN_F16', + 'SQ_V_PK_MIN_I16', 'SQ_V_PK_MIN_U16', 'SQ_V_PK_MUL_F16', + 'SQ_V_PK_MUL_LO_U16', 'SQ_V_PK_SUB_I16', 'SQ_V_PK_SUB_U16', + 'SQ_V_QSAD_PK_U16_U8', 'SQ_V_RCP_F16', 'SQ_V_RCP_F32', + 'SQ_V_RCP_F64', 'SQ_V_RCP_IFLAG_F32', 'SQ_V_READFIRSTLANE_B32', + 'SQ_V_READLANE_B32', 'SQ_V_READLANE_REGRD_B32', 'SQ_V_RNDNE_F16', + 'SQ_V_RNDNE_F32', 'SQ_V_RNDNE_F64', 'SQ_V_RSQ_F16', + 'SQ_V_RSQ_F32', 'SQ_V_RSQ_F64', 'SQ_V_SAD_HI_U8', 'SQ_V_SAD_U16', + 'SQ_V_SAD_U32', 'SQ_V_SAD_U8', 'SQ_V_SAT_PK_U8_I16', + 'SQ_V_SIN_F16', 'SQ_V_SIN_F32', 'SQ_V_SQRT_F16', 'SQ_V_SQRT_F32', + 'SQ_V_SQRT_F64', 'SQ_V_SUBBREV_CO_U32', 'SQ_V_SUBB_CO_U32', + 'SQ_V_SUBREV_CO_U32', 'SQ_V_SUBREV_F16', 'SQ_V_SUBREV_F32', + 'SQ_V_SUBREV_U16', 'SQ_V_SUBREV_U32', 'SQ_V_SUB_CO_U32', + 'SQ_V_SUB_F16', 'SQ_V_SUB_F32', 'SQ_V_SUB_I16', 'SQ_V_SUB_I32', + 'SQ_V_SUB_U16', 'SQ_V_SUB_U32', 'SQ_V_SWAP_B32', + 'SQ_V_TRIG_PREOP_F64', 'SQ_V_TRUNC_F16', 'SQ_V_TRUNC_F32', + 'SQ_V_TRUNC_F64', 'SQ_V_WRITELANE_B32', 'SQ_V_WRITELANE_IMM32', + 'SQ_V_XAD_U32', 'SQ_V_XOR_B32', 'SQ_WAITCNT_EXP_SHIFT', + 'SQ_WAITCNT_EXP_SIZE', 'SQ_WAITCNT_LGKM_SHIFT', + 'SQ_WAITCNT_LGKM_SIZE', 'SQ_WAITCNT_VM_SHIFT', + 'SQ_WAITCNT_VM_SIZE', 'SQ_WAVE_IB_ECC_CLEAN', + 'SQ_WAVE_IB_ECC_ERR_CONTINUE', 'SQ_WAVE_IB_ECC_ERR_HALT', + 'SQ_WAVE_IB_ECC_ST', 'SQ_WAVE_IB_ECC_WITH_ERR_MSG', + 'SQ_WAVE_TYPE', 'SQ_WAVE_TYPE_CS', 'SQ_WAVE_TYPE_ES', + 'SQ_WAVE_TYPE_GS', 'SQ_WAVE_TYPE_HS', 'SQ_WAVE_TYPE_LS', + 'SQ_WAVE_TYPE_PS', 'SQ_WAVE_TYPE_PS0', 'SQ_WAVE_TYPE_PS1', + 'SQ_WAVE_TYPE_VS', 'SQ_XLATE_VOP3_TO_VINTRP_COUNT', + 'SQ_XLATE_VOP3_TO_VINTRP_OFFSET', 'SQ_XLATE_VOP3_TO_VOP1_COUNT', + 'SQ_XLATE_VOP3_TO_VOP1_OFFSET', 'SQ_XLATE_VOP3_TO_VOP2_COUNT', + 'SQ_XLATE_VOP3_TO_VOP2_OFFSET', 'SQ_XLATE_VOP3_TO_VOP3P_COUNT', + 'SQ_XLATE_VOP3_TO_VOP3P_OFFSET', 'SQ_XLATE_VOP3_TO_VOPC_COUNT', + 'SQ_XLATE_VOP3_TO_VOPC_OFFSET', 'SQ_XNACK_MASK_HI', + 'SQ_XNACK_MASK_LO', 'STATIC_SCREEN_SMU_INTR', + 'STATIC_SCREEN_SMU_INTR_NOOP', 'STENCIL_8', 'STENCIL_ADD_CLAMP', + 'STENCIL_ADD_WRAP', 'STENCIL_AND', 'STENCIL_INVALID', + 'STENCIL_INVERT', 'STENCIL_KEEP', 'STENCIL_NAND', 'STENCIL_NOR', + 'STENCIL_ONES', 'STENCIL_OR', 'STENCIL_REPLACE_OP', + 'STENCIL_REPLACE_TEST', 'STENCIL_SUB_CLAMP', 'STENCIL_SUB_WRAP', + 'STENCIL_XNOR', 'STENCIL_XOR', 'STENCIL_ZERO', + 'STREAM_0_SYNCHRONIZATION', + 'STREAM_0_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_0_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_10_SYNCHRONIZATION', + 'STREAM_10_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_10_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION', + 'STREAM_11_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_11_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION', + 'STREAM_12_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_12_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION', + 'STREAM_13_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_13_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION', + 'STREAM_14_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_14_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION', + 'STREAM_15_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_15_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_1_SYNCHRONIZATION', + 'STREAM_1_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_1_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_2_SYNCHRONIZATION', + 'STREAM_2_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_2_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_3_SYNCHRONIZATION', + 'STREAM_3_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_3_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_4_SYNCHRONIZATION', + 'STREAM_4_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_4_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_5_SYNCHRONIZATION', + 'STREAM_5_SYNCHRONIZATION_STEAM_NOT_STOPPED', + 'STREAM_5_SYNCHRONIZATION_STEAM_STOPPED', + 'STREAM_6_SYNCHRONIZATION', + 'STREAM_6_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_6_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION', + 'STREAM_7_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_7_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION', + 'STREAM_8_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_8_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION', + 'STREAM_9_SYNCHRONIZATION_STEAM_NOT_STOPPED_RESERVED', + 'STREAM_9_SYNCHRONIZATION_STEAM_STOPPED_RESERVED', + 'STRM_PERFMON_STATE_COUNT_AND_DUMP_PHANTOM', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET', + 'STRM_PERFMON_STATE_DISABLE_AND_RESET_PHANTOM', + 'STRM_PERFMON_STATE_RESERVED_3', + 'STRM_PERFMON_STATE_START_COUNTING', + 'STRM_PERFMON_STATE_STOP_COUNTING', 'SU_PERFCNT_SEL', 'SWAP_ALT', + 'SWAP_ALT_REV', 'SWAP_STD', 'SWAP_STD_REV', 'SWIZZLE_MODE_ENUM', + 'SWIZZLE_TYPE_ENUM', 'SW_256B_D', 'SW_256B_R', 'SW_256B_S', + 'SW_4KB_D', 'SW_4KB_D_X', 'SW_4KB_R', 'SW_4KB_R_X', 'SW_4KB_S', + 'SW_4KB_S_X', 'SW_4KB_Z', 'SW_4KB_Z_X', 'SW_64KB_D', + 'SW_64KB_D_X', 'SW_64KB_R', 'SW_64KB_R_X', 'SW_64KB_S', + 'SW_64KB_S_X', 'SW_64KB_Z', 'SW_64KB_Z_X', 'SW_D', 'SW_L', + 'SW_LINEAR', 'SW_R', 'SW_RESERVED_12', 'SW_RESERVED_13', + 'SW_RESERVED_14', 'SW_RESERVED_15', 'SW_RESERVED_16', + 'SW_RESERVED_17', 'SW_RESERVED_18', 'SW_RESERVED_19', 'SW_S', + 'SW_VAR_D', 'SW_VAR_D_X', 'SW_VAR_R', 'SW_VAR_R_X', 'SW_VAR_S', + 'SW_VAR_S_X', 'SW_VAR_Z', 'SW_VAR_Z_X', 'SW_Z', 'SX_BLEND_OPT', + 'SX_CB_RAT_ACK_REQUEST', 'SX_DOWNCONVERT_FORMAT', + 'SX_OPT_COMB_FCN', 'SX_PERFCOUNTER_VALS', 'SX_PERF_SEL_CLOCK', + 'SX_PERF_SEL_COL_BUSY', 'SX_PERF_SEL_DB0_A2M_DISCARD_QUADS', + 'SX_PERF_SEL_DB0_HALF_QUADS', 'SX_PERF_SEL_DB0_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB0_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB0_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB0_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB0_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB0_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB0_PIXELS', + 'SX_PERF_SEL_DB0_PIXEL_IDLE', 'SX_PERF_SEL_DB0_PIXEL_STALL', + 'SX_PERF_SEL_DB0_PRED_PIXELS', + 'SX_PERF_SEL_DB1_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB1_HALF_QUADS', + 'SX_PERF_SEL_DB1_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB1_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB1_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB1_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB1_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB1_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB1_PIXELS', + 'SX_PERF_SEL_DB1_PIXEL_IDLE', 'SX_PERF_SEL_DB1_PIXEL_STALL', + 'SX_PERF_SEL_DB1_PRED_PIXELS', + 'SX_PERF_SEL_DB2_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB2_HALF_QUADS', + 'SX_PERF_SEL_DB2_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB2_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB2_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB2_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB2_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB2_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB2_PIXELS', + 'SX_PERF_SEL_DB2_PIXEL_IDLE', 'SX_PERF_SEL_DB2_PIXEL_STALL', + 'SX_PERF_SEL_DB2_PRED_PIXELS', + 'SX_PERF_SEL_DB3_A2M_DISCARD_QUADS', 'SX_PERF_SEL_DB3_HALF_QUADS', + 'SX_PERF_SEL_DB3_MRT0_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT0_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT0_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT0_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT0_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT1_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT1_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT1_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT1_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT1_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT2_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT2_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT2_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT2_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT2_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT3_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT3_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT3_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT3_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT3_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT4_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT4_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT4_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT4_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT4_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT5_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT5_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT5_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT5_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT5_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT6_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT6_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT6_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT6_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT6_SINGLE_QUADS', + 'SX_PERF_SEL_DB3_MRT7_BLEND_BYPASS', + 'SX_PERF_SEL_DB3_MRT7_DISCARD_SRC', + 'SX_PERF_SEL_DB3_MRT7_DONT_RD_DEST', + 'SX_PERF_SEL_DB3_MRT7_DOUBLE_QUADS', + 'SX_PERF_SEL_DB3_MRT7_SINGLE_QUADS', 'SX_PERF_SEL_DB3_PIXELS', + 'SX_PERF_SEL_DB3_PIXEL_IDLE', 'SX_PERF_SEL_DB3_PIXEL_STALL', + 'SX_PERF_SEL_DB3_PRED_PIXELS', 'SX_PERF_SEL_GATE_EN1', + 'SX_PERF_SEL_GATE_EN2', 'SX_PERF_SEL_GATE_EN3', + 'SX_PERF_SEL_GATE_EN4', 'SX_PERF_SEL_PA_IDLE_CYCLES', + 'SX_PERF_SEL_PA_POS', 'SX_PERF_SEL_PA_REQ', + 'SX_PERF_SEL_POS_BUSY', 'SX_PERF_SEL_SH_COLOR_STALL', + 'SX_PERF_SEL_SH_COLOR_STARVE', 'SX_PERF_SEL_SH_POS_STALL', + 'SX_PERF_SEL_SH_POS_STARVE', 'SX_RT_EXPORT_10_11_11', + 'SX_RT_EXPORT_16_16_AR', 'SX_RT_EXPORT_16_16_GR', + 'SX_RT_EXPORT_1_5_5_5', 'SX_RT_EXPORT_2_10_10_10', + 'SX_RT_EXPORT_32_A', 'SX_RT_EXPORT_32_R', 'SX_RT_EXPORT_4_4_4_4', + 'SX_RT_EXPORT_5_6_5', 'SX_RT_EXPORT_8_8_8_8', + 'SX_RT_EXPORT_NO_CONVERSION', 'SYMCLK_FE_FORCE_EN', + 'SYMCLK_FE_FORCE_EN_DISABLE', 'SYMCLK_FE_FORCE_EN_ENABLE', + 'SYMCLK_FE_FORCE_SRC', 'SYMCLK_FE_FORCE_SRC_UNIPHYA', + 'SYMCLK_FE_FORCE_SRC_UNIPHYB', 'SYMCLK_FE_FORCE_SRC_UNIPHYC', + 'SYMCLK_FE_FORCE_SRC_UNIPHYD', 'SYMCLK_FE_FORCE_SRC_UNIPHYE', + 'SYMCLK_FE_FORCE_SRC_UNIPHYF', 'SYMCLK_FE_FORCE_SRC_UNIPHYG', + 'SYNC_DURATION_128', 'SYNC_DURATION_16', 'SYNC_DURATION_32', + 'SYNC_DURATION_64', 'SYNC_RESET_SEL2_VBLANK', + 'SYNC_RESET_SEL2_VSYNC', 'SampleSplit', 'SampleSplitBytes', + 'ScMap', 'ScXsel', 'ScYsel', 'SeEnable', 'SeMap', 'SePairMap', + 'SePairXsel', 'SePairYsel', 'SeXsel', 'SeYsel', + 'ShaderEngineTileSize', 'SourceFormat', 'StencilFormat', + 'StencilOp', 'SurfaceArray', 'SurfaceEndian', 'SurfaceFormat', + 'SurfaceNumber', 'SurfaceSwap', 'SurfaceTiling', + 'TA_PERFCOUNT_SEL', 'TA_PERF_SEL_NULL', 'TA_PERF_SEL_RESERVED_28', + 'TA_PERF_SEL_RESERVED_29', 'TA_PERF_SEL_RESERVED_41', + 'TA_PERF_SEL_RESERVED_42', 'TA_PERF_SEL_RESERVED_43', + 'TA_PERF_SEL_addr_stalled_by_tc_cycles', + 'TA_PERF_SEL_addr_stalled_by_td_cycles', + 'TA_PERF_SEL_addresser_busy', 'TA_PERF_SEL_addresser_fifo_busy', + 'TA_PERF_SEL_addresser_stalled_by_aligner_only_cycles', + 'TA_PERF_SEL_addresser_stalled_cycles', + 'TA_PERF_SEL_aligner_busy', 'TA_PERF_SEL_aligner_cycles', + 'TA_PERF_SEL_aniso_10_cycle_quads', + 'TA_PERF_SEL_aniso_12_cycle_quads', + 'TA_PERF_SEL_aniso_14_cycle_quads', + 'TA_PERF_SEL_aniso_16_cycle_quads', + 'TA_PERF_SEL_aniso_1_cycle_quads', + 'TA_PERF_SEL_aniso_2_cycle_quads', + 'TA_PERF_SEL_aniso_4_cycle_quads', + 'TA_PERF_SEL_aniso_6_cycle_quads', + 'TA_PERF_SEL_aniso_8_cycle_quads', + 'TA_PERF_SEL_aniso_gt1_cycle_quads', + 'TA_PERF_SEL_aniso_stalled_by_addresser_only_cycles', + 'TA_PERF_SEL_aniso_stalled_cycles', + 'TA_PERF_SEL_bilin_point_1_cycle_pixels', + 'TA_PERF_SEL_buffer_atomic_wavefronts', + 'TA_PERF_SEL_buffer_coalescable_addr_multicycled_cycles', + 'TA_PERF_SEL_buffer_coalescable_clamp_16kdword_multicycled_cycles', + 'TA_PERF_SEL_buffer_coalescable_wavefronts', + 'TA_PERF_SEL_buffer_coalesced_read_cycles', + 'TA_PERF_SEL_buffer_coalesced_write_cycles', + 'TA_PERF_SEL_buffer_read_wavefronts', + 'TA_PERF_SEL_buffer_total_cycles', + 'TA_PERF_SEL_buffer_wavefronts', + 'TA_PERF_SEL_buffer_write_wavefronts', + 'TA_PERF_SEL_color_1_cycle_pixels', + 'TA_PERF_SEL_color_2_cycle_pixels', + 'TA_PERF_SEL_color_3_cycle_pixels', + 'TA_PERF_SEL_color_4_cycle_pixels', + 'TA_PERF_SEL_data_stalled_by_tc_cycles', + 'TA_PERF_SEL_deriv_stalled_by_aniso_only_cycles', + 'TA_PERF_SEL_deriv_stalled_cycles', + 'TA_PERF_SEL_first_xnack_on_phase0', + 'TA_PERF_SEL_first_xnack_on_phase1', + 'TA_PERF_SEL_first_xnack_on_phase2', + 'TA_PERF_SEL_first_xnack_on_phase3', + 'TA_PERF_SEL_flat_atomic_wavefronts', + 'TA_PERF_SEL_flat_coalesceable_wavefronts', + 'TA_PERF_SEL_flat_read_wavefronts', 'TA_PERF_SEL_flat_wavefronts', + 'TA_PERF_SEL_flat_write_wavefronts', 'TA_PERF_SEL_gradient_busy', + 'TA_PERF_SEL_gradient_cycles', 'TA_PERF_SEL_gradient_fifo_busy', + 'TA_PERF_SEL_image_atomic_wavefronts', + 'TA_PERF_SEL_image_read_wavefronts', + 'TA_PERF_SEL_image_total_cycles', 'TA_PERF_SEL_image_wavefronts', + 'TA_PERF_SEL_image_write_wavefronts', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp1_mems_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 'TA_PERF_SEL_local_cg_dyn_sclk_grp5_en', 'TA_PERF_SEL_lod_busy', + 'TA_PERF_SEL_lod_fifo_busy', 'TA_PERF_SEL_mip_1_cycle_pixels', + 'TA_PERF_SEL_mip_2_cycle_pixels', + 'TA_PERF_SEL_mipmap_invalid_samples', + 'TA_PERF_SEL_mipmap_lod_0_samples', + 'TA_PERF_SEL_mipmap_lod_10_samples', + 'TA_PERF_SEL_mipmap_lod_11_samples', + 'TA_PERF_SEL_mipmap_lod_12_samples', + 'TA_PERF_SEL_mipmap_lod_13_samples', + 'TA_PERF_SEL_mipmap_lod_14_samples', + 'TA_PERF_SEL_mipmap_lod_1_samples', + 'TA_PERF_SEL_mipmap_lod_2_samples', + 'TA_PERF_SEL_mipmap_lod_3_samples', + 'TA_PERF_SEL_mipmap_lod_4_samples', + 'TA_PERF_SEL_mipmap_lod_5_samples', + 'TA_PERF_SEL_mipmap_lod_6_samples', + 'TA_PERF_SEL_mipmap_lod_7_samples', + 'TA_PERF_SEL_mipmap_lod_8_samples', + 'TA_PERF_SEL_mipmap_lod_9_samples', 'TA_PERF_SEL_reg_sclk_vld', + 'TA_PERF_SEL_sh_fifo_addr_busy', + 'TA_PERF_SEL_sh_fifo_addr_cycles', + 'TA_PERF_SEL_sh_fifo_addr_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_addr_waiting_on_cmd_cycles', + 'TA_PERF_SEL_sh_fifo_busy', 'TA_PERF_SEL_sh_fifo_cmd_busy', + 'TA_PERF_SEL_sh_fifo_cmd_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_cmd_waiting_on_addr_cycles', + 'TA_PERF_SEL_sh_fifo_data_busy', + 'TA_PERF_SEL_sh_fifo_data_cycles', + 'TA_PERF_SEL_sh_fifo_data_sfifo_busy', + 'TA_PERF_SEL_sh_fifo_data_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_data_state_starved_while_busy_cycles', + 'TA_PERF_SEL_sh_fifo_data_state_waiting_on_data_cycles', + 'TA_PERF_SEL_sh_fifo_data_tfifo_busy', + 'TA_PERF_SEL_sh_fifo_data_waiting_on_data_state_cycles', + 'TA_PERF_SEL_sp_ta_addr_cycles', 'TA_PERF_SEL_sp_ta_data_cycles', + 'TA_PERF_SEL_sq_ta_cmd_cycles', 'TA_PERF_SEL_ta_busy', + 'TA_PERF_SEL_ta_fa_data_state_cycles', + 'TA_PERF_SEL_total_wavefronts', 'TA_PERF_SEL_vol_1_cycle_pixels', + 'TA_PERF_SEL_vol_2_cycle_pixels', 'TA_PERF_SEL_walker_cycles', + 'TA_PERF_SEL_write_path_busy', + 'TA_PERF_SEL_write_path_input_cycles', + 'TA_PERF_SEL_write_path_output_cycles', + 'TA_PERF_SEL_xnack_on_phase0', 'TA_PERF_SEL_xnack_on_phase1', + 'TA_PERF_SEL_xnack_on_phase2', 'TA_PERF_SEL_xnack_on_phase3', + 'TA_TC_ADDR_MODES', 'TA_TC_ADDR_MODE_BORDER_COLOR', + 'TA_TC_ADDR_MODE_COMP0', 'TA_TC_ADDR_MODE_COMP1', + 'TA_TC_ADDR_MODE_COMP2', 'TA_TC_ADDR_MODE_COMP3', + 'TA_TC_ADDR_MODE_DEFAULT', 'TA_TC_ADDR_MODE_UNALIGNED', + 'TCA_PERF_SEL', 'TCA_PERF_SEL_BUSY', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC0', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC1', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC2', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC3', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC4', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC5', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC6', + 'TCA_PERF_SEL_CROSSBAR_DOUBLE_ARB_TCC7', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC0', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC1', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC2', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC3', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC4', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC5', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC6', + 'TCA_PERF_SEL_CROSSBAR_STALL_TCC7', 'TCA_PERF_SEL_CYCLE', + 'TCA_PERF_SEL_FORCED_HOLE_TCC0', 'TCA_PERF_SEL_FORCED_HOLE_TCC1', + 'TCA_PERF_SEL_FORCED_HOLE_TCC2', 'TCA_PERF_SEL_FORCED_HOLE_TCC3', + 'TCA_PERF_SEL_FORCED_HOLE_TCC4', 'TCA_PERF_SEL_FORCED_HOLE_TCC5', + 'TCA_PERF_SEL_FORCED_HOLE_TCC6', 'TCA_PERF_SEL_FORCED_HOLE_TCC7', + 'TCA_PERF_SEL_NONE', 'TCA_PERF_SEL_REQ_TCC0', + 'TCA_PERF_SEL_REQ_TCC1', 'TCA_PERF_SEL_REQ_TCC2', + 'TCA_PERF_SEL_REQ_TCC3', 'TCA_PERF_SEL_REQ_TCC4', + 'TCA_PERF_SEL_REQ_TCC5', 'TCA_PERF_SEL_REQ_TCC6', + 'TCA_PERF_SEL_REQ_TCC7', 'TCC_CACHE_POLICIES', + 'TCC_CACHE_POLICY_LRU', 'TCC_CACHE_POLICY_STREAM', 'TCC_PERF_SEL', + 'TCC_PERF_SEL_ALL_TC_OP_INV_EVICT', + 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_CYCLE', + 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_FINISH', + 'TCC_PERF_SEL_ALL_TC_OP_WB_OR_INV_START', + 'TCC_PERF_SEL_ALL_TC_OP_WB_WRITEBACK', 'TCC_PERF_SEL_ATOMIC', + 'TCC_PERF_SEL_BUBBLE', 'TCC_PERF_SEL_BUSY', + 'TCC_PERF_SEL_CC_PHYSICAL_REQ', 'TCC_PERF_SEL_CLIENT0_REQ', + 'TCC_PERF_SEL_CLIENT100_REQ', 'TCC_PERF_SEL_CLIENT101_REQ', + 'TCC_PERF_SEL_CLIENT102_REQ', 'TCC_PERF_SEL_CLIENT103_REQ', + 'TCC_PERF_SEL_CLIENT104_REQ', 'TCC_PERF_SEL_CLIENT105_REQ', + 'TCC_PERF_SEL_CLIENT106_REQ', 'TCC_PERF_SEL_CLIENT107_REQ', + 'TCC_PERF_SEL_CLIENT108_REQ', 'TCC_PERF_SEL_CLIENT109_REQ', + 'TCC_PERF_SEL_CLIENT10_REQ', 'TCC_PERF_SEL_CLIENT110_REQ', + 'TCC_PERF_SEL_CLIENT111_REQ', 'TCC_PERF_SEL_CLIENT112_REQ', + 'TCC_PERF_SEL_CLIENT113_REQ', 'TCC_PERF_SEL_CLIENT114_REQ', + 'TCC_PERF_SEL_CLIENT115_REQ', 'TCC_PERF_SEL_CLIENT116_REQ', + 'TCC_PERF_SEL_CLIENT117_REQ', 'TCC_PERF_SEL_CLIENT118_REQ', + 'TCC_PERF_SEL_CLIENT119_REQ', 'TCC_PERF_SEL_CLIENT11_REQ', + 'TCC_PERF_SEL_CLIENT120_REQ', 'TCC_PERF_SEL_CLIENT121_REQ', + 'TCC_PERF_SEL_CLIENT122_REQ', 'TCC_PERF_SEL_CLIENT123_REQ', + 'TCC_PERF_SEL_CLIENT124_REQ', 'TCC_PERF_SEL_CLIENT125_REQ', + 'TCC_PERF_SEL_CLIENT126_REQ', 'TCC_PERF_SEL_CLIENT127_REQ', + 'TCC_PERF_SEL_CLIENT12_REQ', 'TCC_PERF_SEL_CLIENT13_REQ', + 'TCC_PERF_SEL_CLIENT14_REQ', 'TCC_PERF_SEL_CLIENT15_REQ', + 'TCC_PERF_SEL_CLIENT16_REQ', 'TCC_PERF_SEL_CLIENT17_REQ', + 'TCC_PERF_SEL_CLIENT18_REQ', 'TCC_PERF_SEL_CLIENT19_REQ', + 'TCC_PERF_SEL_CLIENT1_REQ', 'TCC_PERF_SEL_CLIENT20_REQ', + 'TCC_PERF_SEL_CLIENT21_REQ', 'TCC_PERF_SEL_CLIENT22_REQ', + 'TCC_PERF_SEL_CLIENT23_REQ', 'TCC_PERF_SEL_CLIENT24_REQ', + 'TCC_PERF_SEL_CLIENT25_REQ', 'TCC_PERF_SEL_CLIENT26_REQ', + 'TCC_PERF_SEL_CLIENT27_REQ', 'TCC_PERF_SEL_CLIENT28_REQ', + 'TCC_PERF_SEL_CLIENT29_REQ', 'TCC_PERF_SEL_CLIENT2_REQ', + 'TCC_PERF_SEL_CLIENT30_REQ', 'TCC_PERF_SEL_CLIENT31_REQ', + 'TCC_PERF_SEL_CLIENT32_REQ', 'TCC_PERF_SEL_CLIENT33_REQ', + 'TCC_PERF_SEL_CLIENT34_REQ', 'TCC_PERF_SEL_CLIENT35_REQ', + 'TCC_PERF_SEL_CLIENT36_REQ', 'TCC_PERF_SEL_CLIENT37_REQ', + 'TCC_PERF_SEL_CLIENT38_REQ', 'TCC_PERF_SEL_CLIENT39_REQ', + 'TCC_PERF_SEL_CLIENT3_REQ', 'TCC_PERF_SEL_CLIENT40_REQ', + 'TCC_PERF_SEL_CLIENT41_REQ', 'TCC_PERF_SEL_CLIENT42_REQ', + 'TCC_PERF_SEL_CLIENT43_REQ', 'TCC_PERF_SEL_CLIENT44_REQ', + 'TCC_PERF_SEL_CLIENT45_REQ', 'TCC_PERF_SEL_CLIENT46_REQ', + 'TCC_PERF_SEL_CLIENT47_REQ', 'TCC_PERF_SEL_CLIENT48_REQ', + 'TCC_PERF_SEL_CLIENT49_REQ', 'TCC_PERF_SEL_CLIENT4_REQ', + 'TCC_PERF_SEL_CLIENT50_REQ', 'TCC_PERF_SEL_CLIENT51_REQ', + 'TCC_PERF_SEL_CLIENT52_REQ', 'TCC_PERF_SEL_CLIENT53_REQ', + 'TCC_PERF_SEL_CLIENT54_REQ', 'TCC_PERF_SEL_CLIENT55_REQ', + 'TCC_PERF_SEL_CLIENT56_REQ', 'TCC_PERF_SEL_CLIENT57_REQ', + 'TCC_PERF_SEL_CLIENT58_REQ', 'TCC_PERF_SEL_CLIENT59_REQ', + 'TCC_PERF_SEL_CLIENT5_REQ', 'TCC_PERF_SEL_CLIENT60_REQ', + 'TCC_PERF_SEL_CLIENT61_REQ', 'TCC_PERF_SEL_CLIENT62_REQ', + 'TCC_PERF_SEL_CLIENT63_REQ', 'TCC_PERF_SEL_CLIENT64_REQ', + 'TCC_PERF_SEL_CLIENT65_REQ', 'TCC_PERF_SEL_CLIENT66_REQ', + 'TCC_PERF_SEL_CLIENT67_REQ', 'TCC_PERF_SEL_CLIENT68_REQ', + 'TCC_PERF_SEL_CLIENT69_REQ', 'TCC_PERF_SEL_CLIENT6_REQ', + 'TCC_PERF_SEL_CLIENT70_REQ', 'TCC_PERF_SEL_CLIENT71_REQ', + 'TCC_PERF_SEL_CLIENT72_REQ', 'TCC_PERF_SEL_CLIENT73_REQ', + 'TCC_PERF_SEL_CLIENT74_REQ', 'TCC_PERF_SEL_CLIENT75_REQ', + 'TCC_PERF_SEL_CLIENT76_REQ', 'TCC_PERF_SEL_CLIENT77_REQ', + 'TCC_PERF_SEL_CLIENT78_REQ', 'TCC_PERF_SEL_CLIENT79_REQ', + 'TCC_PERF_SEL_CLIENT7_REQ', 'TCC_PERF_SEL_CLIENT80_REQ', + 'TCC_PERF_SEL_CLIENT81_REQ', 'TCC_PERF_SEL_CLIENT82_REQ', + 'TCC_PERF_SEL_CLIENT83_REQ', 'TCC_PERF_SEL_CLIENT84_REQ', + 'TCC_PERF_SEL_CLIENT85_REQ', 'TCC_PERF_SEL_CLIENT86_REQ', + 'TCC_PERF_SEL_CLIENT87_REQ', 'TCC_PERF_SEL_CLIENT88_REQ', + 'TCC_PERF_SEL_CLIENT89_REQ', 'TCC_PERF_SEL_CLIENT8_REQ', + 'TCC_PERF_SEL_CLIENT90_REQ', 'TCC_PERF_SEL_CLIENT91_REQ', + 'TCC_PERF_SEL_CLIENT92_REQ', 'TCC_PERF_SEL_CLIENT93_REQ', + 'TCC_PERF_SEL_CLIENT94_REQ', 'TCC_PERF_SEL_CLIENT95_REQ', + 'TCC_PERF_SEL_CLIENT96_REQ', 'TCC_PERF_SEL_CLIENT97_REQ', + 'TCC_PERF_SEL_CLIENT98_REQ', 'TCC_PERF_SEL_CLIENT99_REQ', + 'TCC_PERF_SEL_CLIENT9_REQ', 'TCC_PERF_SEL_COMPRESSED_0_REQ', + 'TCC_PERF_SEL_COMPRESSED_REQ', 'TCC_PERF_SEL_CYCLE', + 'TCC_PERF_SEL_DEWRITE_ALLOCATE_HIT', 'TCC_PERF_SEL_EA_ATOMIC', + 'TCC_PERF_SEL_EA_ATOMIC_LEVEL', 'TCC_PERF_SEL_EA_RDREQ', + 'TCC_PERF_SEL_EA_RDREQ_32B', 'TCC_PERF_SEL_EA_RDREQ_CREDIT_STALL', + 'TCC_PERF_SEL_EA_RDREQ_LEVEL', + 'TCC_PERF_SEL_EA_RD_COMPRESSED_32B', 'TCC_PERF_SEL_EA_RD_MDC_32B', + 'TCC_PERF_SEL_EA_RD_UNCACHED_32B', 'TCC_PERF_SEL_EA_WRREQ', + 'TCC_PERF_SEL_EA_WRREQ_64B', 'TCC_PERF_SEL_EA_WRREQ_CREDIT_STALL', + 'TCC_PERF_SEL_EA_WRREQ_LEVEL', + 'TCC_PERF_SEL_EA_WRREQ_PROBE_COMMAND', + 'TCC_PERF_SEL_EA_WRREQ_STALL', 'TCC_PERF_SEL_EA_WR_UNCACHED_32B', + 'TCC_PERF_SEL_EXE_REQ', 'TCC_PERF_SEL_FULLY_WRITTEN_HIT', + 'TCC_PERF_SEL_HIT', 'TCC_PERF_SEL_HOLE_FIFO_FULL', + 'TCC_PERF_SEL_HOLE_LEVEL', 'TCC_PERF_SEL_IB_MDC_STALL', + 'TCC_PERF_SEL_IB_REQ', 'TCC_PERF_SEL_IB_STALL', + 'TCC_PERF_SEL_IB_TAG_STALL', 'TCC_PERF_SEL_LATENCY_FIFO_FULL', + 'TCC_PERF_SEL_MDC_LEVEL', 'TCC_PERF_SEL_MDC_REQ', + 'TCC_PERF_SEL_MDC_SECTOR_HIT', 'TCC_PERF_SEL_MDC_SECTOR_MISS', + 'TCC_PERF_SEL_MDC_TAG_DESECTORIZATION_FIFO_FULL_STALL', + 'TCC_PERF_SEL_MDC_TAG_HIT', + 'TCC_PERF_SEL_MDC_TAG_REPLACEMENT_LINE_IN_USE_STALL', + 'TCC_PERF_SEL_MDC_TAG_STALL', + 'TCC_PERF_SEL_MDC_TAG_WAITING_FOR_INVALIDATE_COMPLETION_STALL', + 'TCC_PERF_SEL_METADATA_REQ', 'TCC_PERF_SEL_MISS', + 'TCC_PERF_SEL_NC_VIRTUAL_REQ', 'TCC_PERF_SEL_NONE', + 'TCC_PERF_SEL_NORMAL_EVICT', 'TCC_PERF_SEL_NORMAL_WRITEBACK', + 'TCC_PERF_SEL_PROBE', 'TCC_PERF_SEL_PROBE_ALL', + 'TCC_PERF_SEL_PROBE_EVICT', 'TCC_PERF_SEL_PROBE_FILTER_DISABLED', + 'TCC_PERF_SEL_PROBE_FILTER_DISABLE_TRANSITION', + 'TCC_PERF_SEL_READ', 'TCC_PERF_SEL_READ_RETURN_FULL_BUBBLE', + 'TCC_PERF_SEL_READ_RETURN_TIMEOUT', 'TCC_PERF_SEL_REQ', + 'TCC_PERF_SEL_RETURN_ACK', 'TCC_PERF_SEL_RETURN_ACK_HOLE', + 'TCC_PERF_SEL_RETURN_DATA', 'TCC_PERF_SEL_RETURN_HOLE', + 'TCC_PERF_SEL_SECTOR_HIT', 'TCC_PERF_SEL_SRC_FIFO_FULL', + 'TCC_PERF_SEL_STREAMING_REQ', + 'TCC_PERF_SEL_TAG_MISS_NOTHING_REPLACEABLE_STALL', + 'TCC_PERF_SEL_TAG_NO_UNCACHED_WRITE_ATOMIC_ENTRIES_STALL', + 'TCC_PERF_SEL_TAG_PROBE_FILTER_STALL', + 'TCC_PERF_SEL_TAG_PROBE_STALL', 'TCC_PERF_SEL_TAG_STALL', + 'TCC_PERF_SEL_TAG_UNCACHED_WRITE_ATOMIC_FIFO_FULL_STALL', + 'TCC_PERF_SEL_TAG_WRITEBACK_FIFO_FULL_STALL', + 'TCC_PERF_SEL_TCA_LEVEL', 'TCC_PERF_SEL_TC_OP_INVL2_NC_CYCLE', + 'TCC_PERF_SEL_TC_OP_INVL2_NC_EVICT', + 'TCC_PERF_SEL_TC_OP_INVL2_NC_FINISH', + 'TCC_PERF_SEL_TC_OP_INVL2_NC_START', + 'TCC_PERF_SEL_TC_OP_WBINVL2_CYCLE', + 'TCC_PERF_SEL_TC_OP_WBINVL2_EVICT', + 'TCC_PERF_SEL_TC_OP_WBINVL2_FINISH', + 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_CYCLE', + 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_EVICT', + 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_FINISH', + 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_START', + 'TCC_PERF_SEL_TC_OP_WBINVL2_NC_WRITEBACK', + 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_CYCLE', + 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_EVICT', + 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_FINISH', + 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_START', + 'TCC_PERF_SEL_TC_OP_WBINVL2_SD_WRITEBACK', + 'TCC_PERF_SEL_TC_OP_WBINVL2_START', + 'TCC_PERF_SEL_TC_OP_WBINVL2_WRITEBACK', + 'TCC_PERF_SEL_TC_OP_WBL2_NC_CYCLE', + 'TCC_PERF_SEL_TC_OP_WBL2_NC_EVICT', + 'TCC_PERF_SEL_TC_OP_WBL2_NC_FINISH', + 'TCC_PERF_SEL_TC_OP_WBL2_NC_START', + 'TCC_PERF_SEL_TC_OP_WBL2_NC_WRITEBACK', + 'TCC_PERF_SEL_TC_OP_WBL2_WC_CYCLE', + 'TCC_PERF_SEL_TC_OP_WBL2_WC_EVICT', + 'TCC_PERF_SEL_TC_OP_WBL2_WC_FINISH', + 'TCC_PERF_SEL_TC_OP_WBL2_WC_START', + 'TCC_PERF_SEL_TC_OP_WBL2_WC_WRITEBACK', + 'TCC_PERF_SEL_TOO_MANY_EA_WRREQS_STALL', + 'TCC_PERF_SEL_UC_VIRTUAL_REQ', 'TCC_PERF_SEL_WRITE', + 'TCC_PERF_SEL_WRITEBACK', 'TCC_PERF_SEL_WRITEBACK_READ_TIMEOUT', + 'TCP_CACHE_POLICIES', 'TCP_CACHE_POLICY_HIT_EVICT', + 'TCP_CACHE_POLICY_HIT_LRU', 'TCP_CACHE_POLICY_MISS_EVICT', + 'TCP_CACHE_POLICY_MISS_LRU', 'TCP_CACHE_STORE_POLICIES', + 'TCP_CACHE_STORE_POLICY_WT_EVICT', + 'TCP_CACHE_STORE_POLICY_WT_LRU', 'TCP_DSM_DATA_SEL', + 'TCP_DSM_DISABLE', 'TCP_DSM_INJECT_SEL', 'TCP_DSM_INJECT_SEL0', + 'TCP_DSM_INJECT_SEL1', 'TCP_DSM_INJECT_SEL2', + 'TCP_DSM_INJECT_SEL3', 'TCP_DSM_SEL0', 'TCP_DSM_SEL1', + 'TCP_DSM_SEL_BOTH', 'TCP_DSM_SINGLE_WRITE', + 'TCP_DSM_SINGLE_WRITE_DIS', 'TCP_DSM_SINGLE_WRITE_EN', + 'TCP_PERFCOUNT_SELECT', 'TCP_PERF_SEL_ALLOC_STALL_CYCLES', + 'TCP_PERF_SEL_ARR_1D_THICK', 'TCP_PERF_SEL_ARR_1D_THIN1', + 'TCP_PERF_SEL_ARR_2D_THICK', 'TCP_PERF_SEL_ARR_2D_THIN1', + 'TCP_PERF_SEL_ARR_2D_XTHICK', 'TCP_PERF_SEL_ARR_3D_THICK', + 'TCP_PERF_SEL_ARR_3D_THIN1', 'TCP_PERF_SEL_ARR_3D_XTHICK', + 'TCP_PERF_SEL_ARR_LINEAR_ALIGNED', + 'TCP_PERF_SEL_ARR_LINEAR_GENERAL', + 'TCP_PERF_SEL_ARR_PRT_2D_THICK', 'TCP_PERF_SEL_ARR_PRT_2D_THIN1', + 'TCP_PERF_SEL_ARR_PRT_3D_THICK', 'TCP_PERF_SEL_ARR_PRT_3D_THIN1', + 'TCP_PERF_SEL_ARR_PRT_THICK', 'TCP_PERF_SEL_ARR_PRT_THIN1', + 'TCP_PERF_SEL_ATC', + 'TCP_PERF_SEL_ATOMIC_TAGCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_32', + 'TCP_PERF_SEL_BUF_ATOMIC_WITHOUT_RET_FMT_64', + 'TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_32', + 'TCP_PERF_SEL_BUF_ATOMIC_WITH_RET_FMT_64', + 'TCP_PERF_SEL_BUF_READ_FMT_16', 'TCP_PERF_SEL_BUF_READ_FMT_32', + 'TCP_PERF_SEL_BUF_READ_FMT_8', 'TCP_PERF_SEL_BUF_WRITE_FMT_16', + 'TCP_PERF_SEL_BUF_WRITE_FMT_32', 'TCP_PERF_SEL_BUF_WRITE_FMT_8', + 'TCP_PERF_SEL_CORE_REG_SCLK_VLD', + 'TCP_PERF_SEL_CP_TCP_INVALIDATE', + 'TCP_PERF_SEL_CP_TCP_INVALIDATE_VOL', + 'TCP_PERF_SEL_DEPTH_MICROTILING', 'TCP_PERF_SEL_DIM_1D', + 'TCP_PERF_SEL_DIM_1D_ARRAY', 'TCP_PERF_SEL_DIM_2D', + 'TCP_PERF_SEL_DIM_2D_ARRAY', 'TCP_PERF_SEL_DIM_2D_ARRAY_MSAA', + 'TCP_PERF_SEL_DIM_2D_MSAA', 'TCP_PERF_SEL_DIM_3D', + 'TCP_PERF_SEL_DIM_CUBE_ARRAY', 'TCP_PERF_SEL_DISPLAY_MICROTILING', + 'TCP_PERF_SEL_GATE_EN1', 'TCP_PERF_SEL_GATE_EN2', + 'TCP_PERF_SEL_HOLE_READ_STALL', + 'TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_32', + 'TCP_PERF_SEL_IMG_ATOMIC_WITHOUT_RET_FMT_64', + 'TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_32', + 'TCP_PERF_SEL_IMG_ATOMIC_WITH_RET_FMT_64', + 'TCP_PERF_SEL_IMG_READ_FMT_1', + 'TCP_PERF_SEL_IMG_READ_FMT_128_1_CYCLE', + 'TCP_PERF_SEL_IMG_READ_FMT_128_4_CYCLE', + 'TCP_PERF_SEL_IMG_READ_FMT_16', + 'TCP_PERF_SEL_IMG_READ_FMT_16_AS_128', + 'TCP_PERF_SEL_IMG_READ_FMT_16_AS_64', + 'TCP_PERF_SEL_IMG_READ_FMT_32', + 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_128', + 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_16', + 'TCP_PERF_SEL_IMG_READ_FMT_32_AS_8', + 'TCP_PERF_SEL_IMG_READ_FMT_64_1_CYCLE', + 'TCP_PERF_SEL_IMG_READ_FMT_64_2_CYCLE', + 'TCP_PERF_SEL_IMG_READ_FMT_8', + 'TCP_PERF_SEL_IMG_READ_FMT_8_AS_32', + 'TCP_PERF_SEL_IMG_READ_FMT_8_AS_64', + 'TCP_PERF_SEL_IMG_READ_FMT_96', 'TCP_PERF_SEL_IMG_READ_FMT_BC1', + 'TCP_PERF_SEL_IMG_READ_FMT_BC2', 'TCP_PERF_SEL_IMG_READ_FMT_BC3', + 'TCP_PERF_SEL_IMG_READ_FMT_BC4', 'TCP_PERF_SEL_IMG_READ_FMT_BC5', + 'TCP_PERF_SEL_IMG_READ_FMT_BC6', 'TCP_PERF_SEL_IMG_READ_FMT_BC7', + 'TCP_PERF_SEL_IMG_READ_FMT_D16', 'TCP_PERF_SEL_IMG_READ_FMT_D32', + 'TCP_PERF_SEL_IMG_READ_FMT_D8', + 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_R', + 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RG', + 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGB', + 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA', + 'TCP_PERF_SEL_IMG_READ_FMT_ETC2_RGBA1', + 'TCP_PERF_SEL_IMG_READ_FMT_I16', 'TCP_PERF_SEL_IMG_READ_FMT_I32', + 'TCP_PERF_SEL_IMG_READ_FMT_I32_AS_16', + 'TCP_PERF_SEL_IMG_READ_FMT_I32_AS_8', + 'TCP_PERF_SEL_IMG_READ_FMT_I8', 'TCP_PERF_SEL_IMG_WRITE_FMT_128', + 'TCP_PERF_SEL_IMG_WRITE_FMT_16', + 'TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_128', + 'TCP_PERF_SEL_IMG_WRITE_FMT_16_AS_64', + 'TCP_PERF_SEL_IMG_WRITE_FMT_32', 'TCP_PERF_SEL_IMG_WRITE_FMT_64', + 'TCP_PERF_SEL_IMG_WRITE_FMT_8', + 'TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_32', + 'TCP_PERF_SEL_IMG_WRITE_FMT_8_AS_64', + 'TCP_PERF_SEL_IMG_WRITE_FMT_D16', + 'TCP_PERF_SEL_IMG_WRITE_FMT_D32', 'TCP_PERF_SEL_IMG_WRITE_FMT_D8', + 'TCP_PERF_SEL_LFIFO_STALL_CYCLES', + 'TCP_PERF_SEL_LOD_STALL_CYCLES', + 'TCP_PERF_SEL_PENDING_STALL_CYCLES', 'TCP_PERF_SEL_POWER_STALL', + 'TCP_PERF_SEL_READCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_READFIFO_STALL_CYCLES', + 'TCP_PERF_SEL_READ_TAGCONFLICT_STALL_CYCLES', + 'TCP_PERF_SEL_RESERVED_154', 'TCP_PERF_SEL_RFIFO_STALL_CYCLES', + 'TCP_PERF_SEL_ROTATED_MICROTILING', 'TCP_PERF_SEL_SHOOTDOWN', + 'TCP_PERF_SEL_SQ_TCP_INVALIDATE_VOL', 'TCP_PERF_SEL_TAGRAM0_REQ', + 'TCP_PERF_SEL_TAGRAM1_REQ', 'TCP_PERF_SEL_TAGRAM2_REQ', + 'TCP_PERF_SEL_TAGRAM3_REQ', + 'TCP_PERF_SEL_TA_TCP_ADDR_STARVE_CYCLES', + 'TCP_PERF_SEL_TA_TCP_DATA_STARVE_CYCLES', + 'TCP_PERF_SEL_TA_TCP_STATE_READ', 'TCP_PERF_SEL_TCC_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_ATOMIC_WITHOUT_RET_REQ', + 'TCP_PERF_SEL_TCC_ATOMIC_WITH_RET_REQ', + 'TCP_PERF_SEL_TCC_BYPASS_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_BYPASS_READ_REQ', + 'TCP_PERF_SEL_TCC_BYPASS_WRITE_REQ', + 'TCP_PERF_SEL_TCC_CC_ATOMIC_REQ', 'TCP_PERF_SEL_TCC_CC_READ_REQ', + 'TCP_PERF_SEL_TCC_CC_WRITE_REQ', 'TCP_PERF_SEL_TCC_DATA_BUS_BUSY', + 'TCP_PERF_SEL_TCC_DCC_REQ', 'TCP_PERF_SEL_TCC_LRU_REQ', + 'TCP_PERF_SEL_TCC_MISS_EVICT_READ_REQ', + 'TCP_PERF_SEL_TCC_MISS_EVICT_WRITE_REQ', + 'TCP_PERF_SEL_TCC_NC_ATOMIC_REQ', 'TCP_PERF_SEL_TCC_NC_READ_REQ', + 'TCP_PERF_SEL_TCC_NC_WRITE_REQ', 'TCP_PERF_SEL_TCC_NON_READ_REQ', + 'TCP_PERF_SEL_TCC_PHYSICAL_REQ', 'TCP_PERF_SEL_TCC_READ_REQ', + 'TCP_PERF_SEL_TCC_READ_REQ_LATENCY', 'TCP_PERF_SEL_TCC_REQ', + 'TCP_PERF_SEL_TCC_STREAM_REQ', 'TCP_PERF_SEL_TCC_UC_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_UC_READ_REQ', 'TCP_PERF_SEL_TCC_UC_WRITE_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_ATOMIC_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_BYPASS_READ_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_BYPASS_WRITE_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_READ_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_MISS_EVICT_WRITE_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_READ_REQ', + 'TCP_PERF_SEL_TCC_VOLATILE_WRITE_REQ', + 'TCP_PERF_SEL_TCC_WRITE_REQ', + 'TCP_PERF_SEL_TCC_WRITE_REQ_HOLE_LATENCY', + 'TCP_PERF_SEL_TCC_WRITE_REQ_LATENCY', 'TCP_PERF_SEL_TCP_LATENCY', + 'TCP_PERF_SEL_TCP_TA_ADDR_STALL_CYCLES', + 'TCP_PERF_SEL_TCP_TA_DATA_STALL_CYCLES', + 'TCP_PERF_SEL_TCR_RDRET_STALL', + 'TCP_PERF_SEL_TCR_TCP_STALL_CYCLES', + 'TCP_PERF_SEL_TC_TA_XNACK_STALL', + 'TCP_PERF_SEL_TD_TCP_STALL_CYCLES', + 'TCP_PERF_SEL_THICK_MICROTILING', 'TCP_PERF_SEL_THIN_MICROTILING', + 'TCP_PERF_SEL_TOTAL_ACCESSES', + 'TCP_PERF_SEL_TOTAL_ATOMIC_WITHOUT_RET', + 'TCP_PERF_SEL_TOTAL_ATOMIC_WITH_RET', + 'TCP_PERF_SEL_TOTAL_GLOBAL_READ', + 'TCP_PERF_SEL_TOTAL_GLOBAL_WRITE', + 'TCP_PERF_SEL_TOTAL_HIT_EVICT_READ', + 'TCP_PERF_SEL_TOTAL_HIT_LRU_READ', + 'TCP_PERF_SEL_TOTAL_LOCAL_READ', 'TCP_PERF_SEL_TOTAL_LOCAL_WRITE', + 'TCP_PERF_SEL_TOTAL_MISS_EVICT_READ', + 'TCP_PERF_SEL_TOTAL_MISS_EVICT_WRITE', + 'TCP_PERF_SEL_TOTAL_MISS_LRU_READ', + 'TCP_PERF_SEL_TOTAL_MISS_LRU_WRITE', + 'TCP_PERF_SEL_TOTAL_NON_READ', 'TCP_PERF_SEL_TOTAL_READ', + 'TCP_PERF_SEL_TOTAL_WBINVL1', 'TCP_PERF_SEL_TOTAL_WBINVL1_VOL', + 'TCP_PERF_SEL_TOTAL_WRITE', + 'TCP_PERF_SEL_TOTAL_WRITEBACK_INVALIDATES', + 'TCP_PERF_SEL_UNALIGNED', 'TCP_PERF_SEL_UNORDERED_MTYPE_STALL', + 'TCP_PERF_SEL_UTCL1_LFIFO_FULL', + 'TCP_PERF_SEL_UTCL1_PERMISSION_MISS', + 'TCP_PERF_SEL_UTCL1_REQUEST', + 'TCP_PERF_SEL_UTCL1_SERIALIZATION_STALL', + 'TCP_PERF_SEL_UTCL1_STALL_INFLIGHT_MAX', + 'TCP_PERF_SEL_UTCL1_STALL_LFIFO_NOT_RES', + 'TCP_PERF_SEL_UTCL1_STALL_LRU_INFLIGHT', + 'TCP_PERF_SEL_UTCL1_STALL_MISSFIFO_FULL', + 'TCP_PERF_SEL_UTCL1_STALL_UTCL2_REQ_OUT_OF_CREDITS', + 'TCP_PERF_SEL_UTCL1_TRANSLATION_MISS', + 'TCP_PERF_SEL_UTCL1_UTCL2_INFLIGHT', 'TCP_PERF_SEL_VOLATILE', + 'TCP_PERF_SEL_WRITE_CONFLICT_STALL', + 'TCP_PERF_SEL_WRITE_TAGCONFLICT_STALL_CYCLES', 'TCP_WATCH_MODES', + 'TCP_WATCH_MODE_ALL', 'TCP_WATCH_MODE_ATOMIC', + 'TCP_WATCH_MODE_NONREAD', 'TCP_WATCH_MODE_READ', + 'TC_CHUB_REQ_CREDITS', 'TC_CHUB_REQ_CREDITS_ENUM', 'TC_EA_CID', + 'TC_EA_CID_CPF', 'TC_EA_CID_CPG', 'TC_EA_CID_DCC', + 'TC_EA_CID_FMASK', 'TC_EA_CID_HTILE', 'TC_EA_CID_IA', + 'TC_EA_CID_MISC', 'TC_EA_CID_PA', 'TC_EA_CID_RT', 'TC_EA_CID_SQC', + 'TC_EA_CID_STENCIL', 'TC_EA_CID_TCP', 'TC_EA_CID_TCPMETA', + 'TC_EA_CID_UTCL2_TPI', 'TC_EA_CID_WD', 'TC_EA_CID_Z', + 'TC_MICRO_TILE_MODE', 'TC_NACKS', 'TC_NACK_DATA_ERROR', + 'TC_NACK_NO_FAULT', 'TC_NACK_PAGE_FAULT', + 'TC_NACK_PROTECTION_FAULT', 'TC_ONLY', 'TC_OP', + 'TC_OP_ATOMIC_ADD_32', 'TC_OP_ATOMIC_ADD_64', + 'TC_OP_ATOMIC_ADD_RTN_32', 'TC_OP_ATOMIC_ADD_RTN_64', + 'TC_OP_ATOMIC_AND_32', 'TC_OP_ATOMIC_AND_64', + 'TC_OP_ATOMIC_AND_RTN_32', 'TC_OP_ATOMIC_AND_RTN_64', + 'TC_OP_ATOMIC_CMPSWAP_32', 'TC_OP_ATOMIC_CMPSWAP_64', + 'TC_OP_ATOMIC_CMPSWAP_RTN_32', 'TC_OP_ATOMIC_CMPSWAP_RTN_64', + 'TC_OP_ATOMIC_DEC_32', 'TC_OP_ATOMIC_DEC_64', + 'TC_OP_ATOMIC_DEC_RTN_32', 'TC_OP_ATOMIC_DEC_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_32', 'TC_OP_ATOMIC_FCMPSWAP_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FCMPSWAP_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FCMPSWAP_RTN_32', 'TC_OP_ATOMIC_FCMPSWAP_RTN_64', + 'TC_OP_ATOMIC_FMAX_32', 'TC_OP_ATOMIC_FMAX_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMAX_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMAX_RTN_32', 'TC_OP_ATOMIC_FMAX_RTN_64', + 'TC_OP_ATOMIC_FMIN_32', 'TC_OP_ATOMIC_FMIN_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_64', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_32', + 'TC_OP_ATOMIC_FMIN_FLUSH_DENORM_RTN_64', + 'TC_OP_ATOMIC_FMIN_RTN_32', 'TC_OP_ATOMIC_FMIN_RTN_64', + 'TC_OP_ATOMIC_INC_32', 'TC_OP_ATOMIC_INC_64', + 'TC_OP_ATOMIC_INC_RTN_32', 'TC_OP_ATOMIC_INC_RTN_64', + 'TC_OP_ATOMIC_OR_32', 'TC_OP_ATOMIC_OR_64', + 'TC_OP_ATOMIC_OR_RTN_32', 'TC_OP_ATOMIC_OR_RTN_64', + 'TC_OP_ATOMIC_SMAX_32', 'TC_OP_ATOMIC_SMAX_64', + 'TC_OP_ATOMIC_SMAX_RTN_32', 'TC_OP_ATOMIC_SMAX_RTN_64', + 'TC_OP_ATOMIC_SMIN_32', 'TC_OP_ATOMIC_SMIN_64', + 'TC_OP_ATOMIC_SMIN_RTN_32', 'TC_OP_ATOMIC_SMIN_RTN_64', + 'TC_OP_ATOMIC_SUB_32', 'TC_OP_ATOMIC_SUB_64', + 'TC_OP_ATOMIC_SUB_RTN_32', 'TC_OP_ATOMIC_SUB_RTN_64', + 'TC_OP_ATOMIC_SWAP_32', 'TC_OP_ATOMIC_SWAP_64', + 'TC_OP_ATOMIC_SWAP_RTN_32', 'TC_OP_ATOMIC_SWAP_RTN_64', + 'TC_OP_ATOMIC_UMAX_32', 'TC_OP_ATOMIC_UMAX_64', + 'TC_OP_ATOMIC_UMAX_RTN_32', 'TC_OP_ATOMIC_UMAX_RTN_64', + 'TC_OP_ATOMIC_UMIN_32', 'TC_OP_ATOMIC_UMIN_64', + 'TC_OP_ATOMIC_UMIN_RTN_32', 'TC_OP_ATOMIC_UMIN_RTN_64', + 'TC_OP_ATOMIC_XOR_32', 'TC_OP_ATOMIC_XOR_64', + 'TC_OP_ATOMIC_XOR_RTN_32', 'TC_OP_ATOMIC_XOR_RTN_64', + 'TC_OP_INVL2_NC', 'TC_OP_INV_METADATA', 'TC_OP_MASKS', + 'TC_OP_MASK_64', 'TC_OP_MASK_FLUSH_DENROM', 'TC_OP_MASK_NO_RTN', + 'TC_OP_NOP_ACK', 'TC_OP_NOP_RTN0', 'TC_OP_PROBE_FILTER', + 'TC_OP_READ', 'TC_OP_RESERVED_FOP_32_0', + 'TC_OP_RESERVED_FOP_32_1', 'TC_OP_RESERVED_FOP_32_2', + 'TC_OP_RESERVED_FOP_64_0', 'TC_OP_RESERVED_FOP_64_1', + 'TC_OP_RESERVED_FOP_64_2', 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_64_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_1', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_32_2', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_0', + 'TC_OP_RESERVED_FOP_FLUSH_DENORM_RTN_64_1', + 'TC_OP_RESERVED_FOP_RTN_32_0', 'TC_OP_RESERVED_FOP_RTN_32_1', + 'TC_OP_RESERVED_FOP_RTN_32_2', 'TC_OP_RESERVED_FOP_RTN_64_0', + 'TC_OP_RESERVED_FOP_RTN_64_1', 'TC_OP_RESERVED_FOP_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_32_1', 'TC_OP_RESERVED_NON_FLOAT_32_2', + 'TC_OP_RESERVED_NON_FLOAT_32_3', 'TC_OP_RESERVED_NON_FLOAT_32_4', + 'TC_OP_RESERVED_NON_FLOAT_64_1', 'TC_OP_RESERVED_NON_FLOAT_64_2', + 'TC_OP_RESERVED_NON_FLOAT_64_3', 'TC_OP_RESERVED_NON_FLOAT_64_4', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_0', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_32_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_1', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_2', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_3', + 'TC_OP_RESERVED_NON_FLOAT_RTN_64_4', 'TC_OP_WBINVL1', + 'TC_OP_WBINVL1_SD', 'TC_OP_WBINVL1_VOL', 'TC_OP_WBINVL2', + 'TC_OP_WBINVL2_NC', 'TC_OP_WBINVL2_SD', 'TC_OP_WBL2_NC', + 'TC_OP_WBL2_WC', 'TC_OP_WRITE', 'TD_PERFCOUNT_SEL', + 'TD_PERF_SEL_RESERVED_14', 'TD_PERF_SEL_RESERVED_18', + 'TD_PERF_SEL_RESERVED_19', 'TD_PERF_SEL_RESERVED_39', + 'TD_PERF_SEL_RESERVED_43', 'TD_PERF_SEL_RESERVED_44', + 'TD_PERF_SEL_addresscmd_poison', 'TD_PERF_SEL_atomic_wavefront', + 'TD_PERF_SEL_bypass_filter_wavefront', + 'TD_PERF_SEL_coalescable_wavefront', + 'TD_PERF_SEL_coalesced_phase', 'TD_PERF_SEL_constant_state_full', + 'TD_PERF_SEL_consume_gds_traffic', 'TD_PERF_SEL_d16_data_packed', + 'TD_PERF_SEL_d16_en_wavefront', 'TD_PERF_SEL_data_poison', + 'TD_PERF_SEL_eight_phase_wavefront', + 'TD_PERF_SEL_four_phase_forward_wavefront', + 'TD_PERF_SEL_four_phase_wavefront', + 'TD_PERF_SEL_gather4_wavefront', + 'TD_PERF_SEL_gather4h_packed_wavefront', + 'TD_PERF_SEL_gather4h_wavefront', + 'TD_PERF_SEL_gather8h_packed_wavefront', 'TD_PERF_SEL_gds_stall', + 'TD_PERF_SEL_input_busy', 'TD_PERF_SEL_ldfptr_wavefront', + 'TD_PERF_SEL_lerp_busy', 'TD_PERF_SEL_load_wavefront', + 'TD_PERF_SEL_local_cg_dyn_sclk_grp0_en', + 'TD_PERF_SEL_local_cg_dyn_sclk_grp1_en', + 'TD_PERF_SEL_local_cg_dyn_sclk_grp4_en', + 'TD_PERF_SEL_local_cg_dyn_sclk_grp5_en', + 'TD_PERF_SEL_min_max_filter_wavefront', 'TD_PERF_SEL_nack', + 'TD_PERF_SEL_none', 'TD_PERF_SEL_null_cycle_output', + 'TD_PERF_SEL_opaque_black_border', 'TD_PERF_SEL_output_busy', + 'TD_PERF_SEL_output_fifo_full', 'TD_PERF_SEL_pc_stall', + 'TD_PERF_SEL_reg_sclk_vld', 'TD_PERF_SEL_sample_c_wavefront', + 'TD_PERF_SEL_sample_state_full', + 'TD_PERF_SEL_sixteen_phase_wavefront', + 'TD_PERF_SEL_start_cycle_0', 'TD_PERF_SEL_start_cycle_1', + 'TD_PERF_SEL_start_cycle_2', 'TD_PERF_SEL_start_cycle_3', + 'TD_PERF_SEL_store_wavefront', 'TD_PERF_SEL_tc_stall', + 'TD_PERF_SEL_tc_td_fifo_full', 'TD_PERF_SEL_td_busy', + 'TD_PERF_SEL_td_sp_traffic', + 'TD_PERF_SEL_texels_zeroed_out_by_blend_zero_prt', + 'TD_PERF_SEL_user_defined_border', 'TD_PERF_SEL_white_border', + 'TD_PERF_SEL_write_ack_wavefront', 'TESS_ISOLINE', 'TESS_QUAD', + 'TESS_TRIANGLE', 'TEX_BORDER_COLOR_TYPE', + 'TEX_BorderColor_OpaqueBlack', 'TEX_BorderColor_OpaqueWhite', + 'TEX_BorderColor_Register', 'TEX_BorderColor_TransparentBlack', + 'TEX_CHROMA_KEY', 'TEX_CLAMP', 'TEX_COORD_TYPE', + 'TEX_ChromaKey_Blend', 'TEX_ChromaKey_Disabled', + 'TEX_ChromaKey_Kill', 'TEX_ChromaKey_RESERVED_3', + 'TEX_Clamp_ClampHalfToBorder', 'TEX_Clamp_ClampToBorder', + 'TEX_Clamp_ClampToLast', 'TEX_Clamp_Mirror', + 'TEX_Clamp_MirrorOnceHalfToBorder', + 'TEX_Clamp_MirrorOnceToBorder', 'TEX_Clamp_MirrorOnceToLast', + 'TEX_Clamp_Repeat', 'TEX_CoordType_Normalized', + 'TEX_CoordType_Unnormalized', 'TEX_DEPTH_COMPARE_FUNCTION', + 'TEX_DIM', 'TEX_DepthCompareFunction_Always', + 'TEX_DepthCompareFunction_Equal', + 'TEX_DepthCompareFunction_Greater', + 'TEX_DepthCompareFunction_GreaterEqual', + 'TEX_DepthCompareFunction_Less', + 'TEX_DepthCompareFunction_LessEqual', + 'TEX_DepthCompareFunction_Never', + 'TEX_DepthCompareFunction_NotEqual', 'TEX_Dim_1D', + 'TEX_Dim_1DArray', 'TEX_Dim_2D', 'TEX_Dim_2DArray', + 'TEX_Dim_2DArray_MSAA', 'TEX_Dim_2D_MSAA', 'TEX_Dim_3D', + 'TEX_Dim_CubeMap', 'TEX_FORMAT_COMP', 'TEX_FormatComp_RESERVED_3', + 'TEX_FormatComp_Signed', 'TEX_FormatComp_Unsigned', + 'TEX_FormatComp_UnsignedBiased', 'TEX_MAX_ANISO_RATIO', + 'TEX_MIP_FILTER', 'TEX_MaxAnisoRatio_16to1', + 'TEX_MaxAnisoRatio_1to1', 'TEX_MaxAnisoRatio_2to1', + 'TEX_MaxAnisoRatio_4to1', 'TEX_MaxAnisoRatio_8to1', + 'TEX_MaxAnisoRatio_RESERVED_5', 'TEX_MaxAnisoRatio_RESERVED_6', + 'TEX_MaxAnisoRatio_RESERVED_7', 'TEX_MipFilter_Linear', + 'TEX_MipFilter_None', 'TEX_MipFilter_Point', + 'TEX_MipFilter_Point_Aniso_Adj', 'TEX_REQUEST_SIZE', + 'TEX_RequestSize_128B', 'TEX_RequestSize_2X64B', + 'TEX_RequestSize_32B', 'TEX_RequestSize_64B', 'TEX_SAMPLER_TYPE', + 'TEX_SamplerType_Invalid', 'TEX_SamplerType_Valid', + 'TEX_XYFilter_AnisoLinear', 'TEX_XYFilter_AnisoPoint', + 'TEX_XYFilter_Linear', 'TEX_XYFilter_Point', 'TEX_XY_FILTER', + 'TEX_ZFilter_Linear', 'TEX_ZFilter_None', 'TEX_ZFilter_Point', + 'TEX_ZFilter_RESERVED_3', 'TEX_Z_FILTER', 'TGID_ROLLOVER', + 'THREAD_TRACE_FINISH', 'THREAD_TRACE_FLUSH', + 'THREAD_TRACE_MARKER', 'THREAD_TRACE_START', 'THREAD_TRACE_STOP', + 'TMDS_COLOR_FORMAT', 'TMDS_COLOR_FORMAT_DUAL30BPP', + 'TMDS_COLOR_FORMAT_RESERVED', 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', + 'TMDS_COLOR_FORMAT__24BPP__TWIN30BPP_MSB__DUAL48BPP', + 'TMDS_CTL0_DATA_INVERT', 'TMDS_CTL0_DATA_INVERT_EN', + 'TMDS_CTL0_DATA_MODULATION', 'TMDS_CTL0_DATA_MODULATION_BIT0', + 'TMDS_CTL0_DATA_MODULATION_BIT1', + 'TMDS_CTL0_DATA_MODULATION_BIT2', + 'TMDS_CTL0_DATA_MODULATION_DISABLE', 'TMDS_CTL0_DATA_NORMAL', + 'TMDS_CTL0_DATA_SEL', 'TMDS_CTL0_DATA_SEL0_RESERVED', + 'TMDS_CTL0_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL0_DATA_SEL2_VSYNC', + 'TMDS_CTL0_DATA_SEL3_RESERVED', 'TMDS_CTL0_DATA_SEL4_HSYNC', + 'TMDS_CTL0_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL0_DATA_SEL8_RANDOM_DATA', + 'TMDS_CTL0_DATA_SEL9_SEL15_RANDOM_DATA', + 'TMDS_CTL0_PATTERN_OUT_DISABLE', 'TMDS_CTL0_PATTERN_OUT_EN', + 'TMDS_CTL0_PATTERN_OUT_ENABLE', 'TMDS_CTL1_DATA_INVERT', + 'TMDS_CTL1_DATA_INVERT_EN', 'TMDS_CTL1_DATA_MODULATION', + 'TMDS_CTL1_DATA_MODULATION_BIT0', + 'TMDS_CTL1_DATA_MODULATION_BIT1', + 'TMDS_CTL1_DATA_MODULATION_BIT2', + 'TMDS_CTL1_DATA_MODULATION_DISABLE', 'TMDS_CTL1_DATA_NORMAL', + 'TMDS_CTL1_DATA_SEL', 'TMDS_CTL1_DATA_SEL0_RESERVED', + 'TMDS_CTL1_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL1_DATA_SEL2_VSYNC', + 'TMDS_CTL1_DATA_SEL3_RESERVED', 'TMDS_CTL1_DATA_SEL4_HSYNC', + 'TMDS_CTL1_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL1_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL1_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL1_PATTERN_OUT_DISABLE', 'TMDS_CTL1_PATTERN_OUT_EN', + 'TMDS_CTL1_PATTERN_OUT_ENABLE', 'TMDS_CTL2_DATA_INVERT', + 'TMDS_CTL2_DATA_INVERT_EN', 'TMDS_CTL2_DATA_MODULATION', + 'TMDS_CTL2_DATA_MODULATION_BIT0', + 'TMDS_CTL2_DATA_MODULATION_BIT1', + 'TMDS_CTL2_DATA_MODULATION_BIT2', + 'TMDS_CTL2_DATA_MODULATION_DISABLE', 'TMDS_CTL2_DATA_NORMAL', + 'TMDS_CTL2_DATA_SEL', 'TMDS_CTL2_DATA_SEL0_RESERVED', + 'TMDS_CTL2_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL2_DATA_SEL2_VSYNC', + 'TMDS_CTL2_DATA_SEL3_RESERVED', 'TMDS_CTL2_DATA_SEL4_HSYNC', + 'TMDS_CTL2_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL2_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL2_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL2_PATTERN_OUT_DISABLE', 'TMDS_CTL2_PATTERN_OUT_EN', + 'TMDS_CTL2_PATTERN_OUT_ENABLE', 'TMDS_CTL3_DATA_INVERT', + 'TMDS_CTL3_DATA_INVERT_EN', 'TMDS_CTL3_DATA_MODULATION', + 'TMDS_CTL3_DATA_MODULATION_BIT0', + 'TMDS_CTL3_DATA_MODULATION_BIT1', + 'TMDS_CTL3_DATA_MODULATION_BIT2', + 'TMDS_CTL3_DATA_MODULATION_DISABLE', 'TMDS_CTL3_DATA_NORMAL', + 'TMDS_CTL3_DATA_SEL', 'TMDS_CTL3_DATA_SEL0_RESERVED', + 'TMDS_CTL3_DATA_SEL1_DISPLAY_ENABLE', 'TMDS_CTL3_DATA_SEL2_VSYNC', + 'TMDS_CTL3_DATA_SEL3_RESERVED', 'TMDS_CTL3_DATA_SEL4_HSYNC', + 'TMDS_CTL3_DATA_SEL5_SEL7_RESERVED', + 'TMDS_CTL3_DATA_SEL8_BLANK_TIME', + 'TMDS_CTL3_DATA_SEL9_SEL15_RESERVED', + 'TMDS_CTL3_PATTERN_OUT_DISABLE', 'TMDS_CTL3_PATTERN_OUT_EN', + 'TMDS_CTL3_PATTERN_OUT_ENABLE', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_PCLK_TMDS', + 'TMDS_DATA_SYNCHRONIZATION_DSINTSEL_TMDS_PLL', + 'TMDS_DVO_MUX_SELECT', 'TMDS_DVO_MUX_SELECT_B', + 'TMDS_DVO_MUX_SELECT_G', 'TMDS_DVO_MUX_SELECT_R', + 'TMDS_DVO_MUX_SELECT_RESERVED', + 'TMDS_NOT_SYNC_PHASE_ON_FRAME_START', 'TMDS_PIXEL_ENCODING', + 'TMDS_PIXEL_ENCODING_422', 'TMDS_PIXEL_ENCODING_444_OR_420', + 'TMDS_REG_TEST_OUTPUTA_CNTLA', 'TMDS_REG_TEST_OUTPUTA_CNTLA_NA', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA0', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA1', + 'TMDS_REG_TEST_OUTPUTA_CNTLA_OTDATA2', + 'TMDS_REG_TEST_OUTPUTB_CNTLB', 'TMDS_REG_TEST_OUTPUTB_CNTLB_NA', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB0', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB1', + 'TMDS_REG_TEST_OUTPUTB_CNTLB_OTDATB2', 'TMDS_STEREOSYNC_CTL0', + 'TMDS_STEREOSYNC_CTL1', 'TMDS_STEREOSYNC_CTL2', + 'TMDS_STEREOSYNC_CTL3', 'TMDS_STEREOSYNC_CTL_SEL_REG', + 'TMDS_SYNC_PHASE', 'TMDS_SYNC_PHASE_ON_FRAME_START', + 'TMDS_TRANSMITTER_BYPASS_PLLA_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLA_INCOHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_COHERENT', + 'TMDS_TRANSMITTER_BYPASS_PLLB_INCOHERENT', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLA', + 'TMDS_TRANSMITTER_CONTROL_BYPASS_PLLB', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELA', + 'TMDS_TRANSMITTER_CONTROL_IDSCKSELB', + 'TMDS_TRANSMITTER_CONTROL_PLLSEL_OVERWRITE_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_PLL_PWRUP_SEQ_EN', + 'TMDS_TRANSMITTER_CONTROL_PLL_RESET_HPD_MASK', + 'TMDS_TRANSMITTER_CONTROL_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_CONTROL_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_ENABLE_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKCEN_HPD_MASK', + 'TMDS_TRANSMITTER_ENABLE_LNKDEN_HPD_MASK', + 'TMDS_TRANSMITTER_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_HPD_NOT_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_CON', + 'TMDS_TRANSMITTER_HPD_OVERRIDE_PLL_ENABLE_ON_DISCON', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELA_USE_IPIXCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IDCLK', + 'TMDS_TRANSMITTER_IDSCKSELB_USE_IPIXCLK', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKCEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_NOT_OVERRIDE', + 'TMDS_TRANSMITTER_LNKDEN_HPD_MASK_OVERRIDE', + 'TMDS_TRANSMITTER_PLLSEL_BY_HW', + 'TMDS_TRANSMITTER_PLLSEL_OVERWRITE_BY_SW', + 'TMDS_TRANSMITTER_PLL_NOT_RST_ON_HPD', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_DISABLE', + 'TMDS_TRANSMITTER_PLL_PWRUP_SEQ_ENABLE', + 'TMDS_TRANSMITTER_PLL_RST_ON_HPD', + 'TMDS_TRANSMITTER_TDCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TDCLK_FROM_TMDS_TDCLK', + 'TMDS_TRANSMITTER_TMCLK_FROM_PADS', + 'TMDS_TRANSMITTER_TMCLK_FROM_TMDS_TMCLK', + 'TRANSFERRED_1024_BYTES', 'TRANSFERRED_128_BYTES', + 'TRANSFERRED_2048_BYTES', 'TRANSFERRED_256_BYTES', + 'TRANSFERRED_4096_BYTES', 'TRANSFERRED_512_BYTES', + 'TRANSFERRED_64_BYTES', 'TRANSFERRED_8192_BYTES', 'TRAPEZOIDS', + 'TRISTRIP', 'TVX_DATA_FORMAT', 'TVX_DST_SEL', 'TVX_DstSel_0f', + 'TVX_DstSel_1f', 'TVX_DstSel_Mask', 'TVX_DstSel_RESERVED_6', + 'TVX_DstSel_W', 'TVX_DstSel_X', 'TVX_DstSel_Y', 'TVX_DstSel_Z', + 'TVX_ENDIAN_SWAP', 'TVX_EndianSwap_8in16', 'TVX_EndianSwap_8in32', + 'TVX_EndianSwap_8in64', 'TVX_EndianSwap_None', 'TVX_FMT_1', + 'TVX_FMT_10_10_10_2', 'TVX_FMT_10_11_11', + 'TVX_FMT_10_11_11_FLOAT', 'TVX_FMT_11_11_10', + 'TVX_FMT_11_11_10_FLOAT', 'TVX_FMT_16', 'TVX_FMT_16_16', + 'TVX_FMT_16_16_16', 'TVX_FMT_16_16_16_16', + 'TVX_FMT_16_16_16_16_FLOAT', 'TVX_FMT_16_16_16_FLOAT', + 'TVX_FMT_16_16_FLOAT', 'TVX_FMT_16_FLOAT', 'TVX_FMT_1_5_5_5', + 'TVX_FMT_1_REVERSED', 'TVX_FMT_24_8', 'TVX_FMT_24_8_FLOAT', + 'TVX_FMT_2_10_10_10', 'TVX_FMT_32', 'TVX_FMT_32_32', + 'TVX_FMT_32_32_32', 'TVX_FMT_32_32_32_32', + 'TVX_FMT_32_32_32_32_FLOAT', 'TVX_FMT_32_32_32_FLOAT', + 'TVX_FMT_32_32_FLOAT', 'TVX_FMT_32_AS_8', 'TVX_FMT_32_AS_8_8', + 'TVX_FMT_32_FLOAT', 'TVX_FMT_3_3_2', 'TVX_FMT_4_4', + 'TVX_FMT_4_4_4_4', 'TVX_FMT_5_5_5_1', 'TVX_FMT_5_6_5', + 'TVX_FMT_5_9_9_9_SHAREDEXP', 'TVX_FMT_6_5_5', 'TVX_FMT_8', + 'TVX_FMT_8_24', 'TVX_FMT_8_24_FLOAT', 'TVX_FMT_8_8', + 'TVX_FMT_8_8_8', 'TVX_FMT_8_8_8_8', 'TVX_FMT_APC0', + 'TVX_FMT_APC1', 'TVX_FMT_APC2', 'TVX_FMT_APC3', 'TVX_FMT_APC4', + 'TVX_FMT_APC5', 'TVX_FMT_APC6', 'TVX_FMT_APC7', 'TVX_FMT_BC1', + 'TVX_FMT_BC2', 'TVX_FMT_BC3', 'TVX_FMT_BC4', 'TVX_FMT_BC5', + 'TVX_FMT_BG_RG', 'TVX_FMT_CTX1', 'TVX_FMT_GB_GR', + 'TVX_FMT_INVALID', 'TVX_FMT_RESERVED_33', 'TVX_FMT_RESERVED_36', + 'TVX_FMT_RESERVED_4', 'TVX_FMT_RESERVED_63', + 'TVX_FMT_X24_8_32_FLOAT', 'TVX_INST', 'TVX_Inst_Gather4', + 'TVX_Inst_Gather4_C', 'TVX_Inst_Gather4_C_O', + 'TVX_Inst_Gather4_O', 'TVX_Inst_GetBufferResInfo', + 'TVX_Inst_GetGradientsH', 'TVX_Inst_GetGradientsV', + 'TVX_Inst_GetLOD', 'TVX_Inst_GetNumberOfSamples', + 'TVX_Inst_GetTextureResInfo', 'TVX_Inst_KeepGradients', + 'TVX_Inst_LD', 'TVX_Inst_NormalVertexFetch', 'TVX_Inst_Pass', + 'TVX_Inst_RESERVED_15', 'TVX_Inst_RESERVED_2', 'TVX_Inst_Sample', + 'TVX_Inst_Sample_C', 'TVX_Inst_Sample_C_G', + 'TVX_Inst_Sample_C_G_LB', 'TVX_Inst_Sample_C_L', + 'TVX_Inst_Sample_C_LB', 'TVX_Inst_Sample_C_LZ', + 'TVX_Inst_Sample_G', 'TVX_Inst_Sample_G_LB', 'TVX_Inst_Sample_L', + 'TVX_Inst_Sample_LB', 'TVX_Inst_Sample_LZ', + 'TVX_Inst_SemanticVertexFetch', 'TVX_Inst_SetGradientsH', + 'TVX_Inst_SetGradientsV', 'TVX_Inst_SetTextureOffsets', + 'TVX_NUM_FORMAT_ALL', 'TVX_NumFormatAll_Int', + 'TVX_NumFormatAll_Norm', 'TVX_NumFormatAll_RESERVED_3', + 'TVX_NumFormatAll_Scaled', 'TVX_SRC_SEL', 'TVX_SRFModeAll_NZ', + 'TVX_SRFModeAll_ZCMO', 'TVX_SRF_MODE_ALL', 'TVX_SrcSel_0f', + 'TVX_SrcSel_1f', 'TVX_SrcSel_W', 'TVX_SrcSel_X', 'TVX_SrcSel_Y', + 'TVX_SrcSel_Z', 'TVX_TYPE', 'TVX_Type_InvalidTextureResource', + 'TVX_Type_InvalidVertexBuffer', 'TVX_Type_ValidTextureResource', + 'TVX_Type_ValidVertexBuffer', 'TileSplit', 'TileType', + 'UCONFIG_SPACE_END', 'UCONFIG_SPACE_START', 'UNDEF', + 'UNP_ADDR_SURF_MACRO_ASPECT_1', 'UNP_ADDR_SURF_MACRO_ASPECT_2', + 'UNP_ADDR_SURF_MACRO_ASPECT_4', 'UNP_ADDR_SURF_MACRO_ASPECT_8', + 'UNP_ADDR_SURF_TILE_SPLIT_128B', 'UNP_ADDR_SURF_TILE_SPLIT_1KB', + 'UNP_ADDR_SURF_TILE_SPLIT_256B', 'UNP_ADDR_SURF_TILE_SPLIT_2KB', + 'UNP_ADDR_SURF_TILE_SPLIT_4KB', 'UNP_ADDR_SURF_TILE_SPLIT_512B', + 'UNP_ADDR_SURF_TILE_SPLIT_64B', 'UNP_BUFFER_MODE', + 'UNP_BUFFER_MODE_LUMA', 'UNP_BUFFER_MODE_LUMA_CHROMA', + 'UNP_CRC_LINE_SEL', 'UNP_CRC_LINE_SEL_EVEN_ONLY', + 'UNP_CRC_LINE_SEL_ODD_EVEN', 'UNP_CRC_LINE_SEL_ODD_ONLY', + 'UNP_CRC_LINE_SEL_RESERVED', 'UNP_CRC_SOURCE_SEL', + 'UNP_CRC_SOURCE_SEL_LOWER16', 'UNP_CRC_SOURCE_SEL_LOWER32', + 'UNP_CRC_SOURCE_SEL_NP_TO_LBV', 'UNP_CRC_SOURCE_SEL_RESERVED', + 'UNP_CRC_SOURCE_SEL_UNP_TO_LBV', 'UNP_GRPH_16BPP', + 'UNP_GRPH_32BPP', 'UNP_GRPH_8BPP', + 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE', + 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE0', + 'UNP_GRPH_ADDRESS_TRANSLATION_ENABLE1', + 'UNP_GRPH_ADDR_SURF_16_BANK', 'UNP_GRPH_ADDR_SURF_2_BANK', + 'UNP_GRPH_ADDR_SURF_4_BANK', 'UNP_GRPH_ADDR_SURF_8_BANK', + 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_1', + 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_2', + 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_4', + 'UNP_GRPH_ADDR_SURF_BANK_HEIGHT_8', + 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_1', + 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_2', + 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_4', + 'UNP_GRPH_ADDR_SURF_BANK_WIDTH_8', 'UNP_GRPH_BANK_HEIGHT', + 'UNP_GRPH_BANK_WIDTH', 'UNP_GRPH_BLUE_CROSSBAR', + 'UNP_GRPH_BLUE_CROSSBAR_A', 'UNP_GRPH_BLUE_CROSSBAR_B_Cb_AND_C', + 'UNP_GRPH_BLUE_CROSSBAR_GY_AND_Y', 'UNP_GRPH_BLUE_CROSSBAR_R_Cr', + 'UNP_GRPH_COLOR_EXPANSION_MODE', 'UNP_GRPH_DEPTH', + 'UNP_GRPH_DISABLED', 'UNP_GRPH_DYNAMIC_EXPANSION', 'UNP_GRPH_EN', + 'UNP_GRPH_ENABLED', 'UNP_GRPH_ENDIAN_SWAP', + 'UNP_GRPH_ENDIAN_SWAP_8IN16', 'UNP_GRPH_ENDIAN_SWAP_8IN32', + 'UNP_GRPH_ENDIAN_SWAP_8IN43', 'UNP_GRPH_ENDIAN_SWAP_NONE', + 'UNP_GRPH_GREEN_CROSSBAR', 'UNP_GRPH_MACRO_TILE_ASPECT', + 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE', + 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_0', + 'UNP_GRPH_MODE_DISABLE_MULTIPLE_UPDATE_1', + 'UNP_GRPH_MODE_UPDATE_LOCKG', 'UNP_GRPH_NUM_BANKS', + 'UNP_GRPH_RED_CROSSBAR', 'UNP_GRPH_RED_CROSSBAR_A', + 'UNP_GRPH_RED_CROSSBAR_B_Cb', 'UNP_GRPH_RED_CROSSBAR_G_Y', + 'UNP_GRPH_RED_CROSSBAR_R_Cr', + 'UNP_GRPH_STACK_INTERLACE_FLIP_DISABLE', + 'UNP_GRPH_STACK_INTERLACE_FLIP_EN', + 'UNP_GRPH_STACK_INTERLACE_FLIP_ENABLE', + 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE', + 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_0', + 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_1', + 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_2', + 'UNP_GRPH_STACK_INTERLACE_FLIP_MODE_3', + 'UNP_GRPH_STEREOSYNC_FLIP_DISABLE', 'UNP_GRPH_STEREOSYNC_FLIP_EN', + 'UNP_GRPH_STEREOSYNC_FLIP_ENABLE', + 'UNP_GRPH_STEREOSYNC_FLIP_MODE', + 'UNP_GRPH_STEREOSYNC_FLIP_MODE_0', + 'UNP_GRPH_STEREOSYNC_FLIP_MODE_1', + 'UNP_GRPH_STEREOSYNC_FLIP_MODE_2', + 'UNP_GRPH_STEREOSYNC_FLIP_MODE_3', + 'UNP_GRPH_STEREOSYNC_SELECT_DIS', + 'UNP_GRPH_STEREOSYNC_SELECT_DISABLE', + 'UNP_GRPH_STEREOSYNC_SELECT_EN', + 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE', + 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_0', + 'UNP_GRPH_SURFACE_DISABLE_MULTIPLE_UPDATE_1', + 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK', + 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_0', + 'UNP_GRPH_SURFACE_IGNORE_UPDATE_LOCK_1', 'UNP_GRPH_TILE_SPLIT', + 'UNP_GRPH_UPDATE_LOCK_0', 'UNP_GRPH_UPDATE_LOCK_1', + 'UNP_GRPH_ZERO_EXPANSION', 'UNP_PIXEL_DROP', 'UNP_PIXEL_DROPPING', + 'UNP_PIXEL_NO_DROP', 'UNP_ROTATION_ANGLE', 'UNP_ROTATION_ANGLE_0', + 'UNP_ROTATION_ANGLE_0m', 'UNP_ROTATION_ANGLE_180', + 'UNP_ROTATION_ANGLE_180m', 'UNP_ROTATION_ANGLE_270', + 'UNP_ROTATION_ANGLE_270m', 'UNP_ROTATION_ANGLE_90', + 'UNP_ROTATION_ANGLE_90m', 'UNP_UNP_GRPH_GREEN_CROSSBAR_A', + 'UNP_UNP_GRPH_GREEN_CROSSBAR_B_Cb_AND_C', + 'UNP_UNP_GRPH_GREEN_CROSSBAR_GY_AND_Y', + 'UNP_UNP_GRPH_GREEN_CROSSBAR_R_Cr', 'UNP_VIDEO_FORMAT', + 'UNP_VIDEO_FORMAT0', 'UNP_VIDEO_FORMAT1', + 'UNP_VIDEO_FORMAT_YUV420_YCbCr', 'UNP_VIDEO_FORMAT_YUV420_YCrCb', + 'UNP_VIDEO_FORMAT_YUV422_CbY', 'UNP_VIDEO_FORMAT_YUV422_CrY', + 'UNP_VIDEO_FORMAT_YUV422_YCb', 'UNP_VIDEO_FORMAT_YUV422_YCr', + 'UPDATE_LOCKED', 'UPDATE_UNLOCKED', 'UTCL1FaultType', + 'UTCL1RequestType', 'UTCL1_TYPE_BYPASS', 'UTCL1_TYPE_NORMAL', + 'UTCL1_TYPE_SHOOTDOWN', 'UTCL1_XNACK_NO_RETRY', 'UTCL1_XNACK_PRT', + 'UTCL1_XNACK_RETRY', 'UTCL1_XNACK_SUCCESS', 'VC_AND_TC', + 'VC_ONLY', 'VGT_CACHE_INVALID_MODE', 'VGT_DIST_MODE', + 'VGT_DI_INDEX_SIZE', 'VGT_DI_MAJOR_MODE_SELECT', + 'VGT_DI_PRIM_TYPE', 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', + 'VGT_DMA_BUF_RING', 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', + 'VGT_DMA_PTR_UPDATE', 'VGT_DMA_SWAP_16_BIT', + 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', 'VGT_DMA_SWAP_NONE', + 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', 'VGT_FLUSH', + 'VGT_GROUP_CONV_SEL', 'VGT_GRP_2D_COPY_RECT_V0', + 'VGT_GRP_2D_COPY_RECT_V1', 'VGT_GRP_2D_COPY_RECT_V2', + 'VGT_GRP_2D_COPY_RECT_V3', 'VGT_GRP_2D_FILL_RECT', + 'VGT_GRP_2D_LINE', 'VGT_GRP_2D_RECT', 'VGT_GRP_2D_TRI', + 'VGT_GRP_3D_LINE', 'VGT_GRP_3D_LINE_ADJ', 'VGT_GRP_3D_PATCH', + 'VGT_GRP_3D_POINT', 'VGT_GRP_3D_QUAD', 'VGT_GRP_3D_RECT', + 'VGT_GRP_3D_TRI', 'VGT_GRP_3D_TRI_ADJ', 'VGT_GRP_AUTO_PRIM', + 'VGT_GRP_FAN', 'VGT_GRP_FIX_1_23_TO_FLOAT', 'VGT_GRP_FLOAT_32', + 'VGT_GRP_INDEX_16', 'VGT_GRP_INDEX_32', 'VGT_GRP_LIST', + 'VGT_GRP_LOOP', 'VGT_GRP_POLYGON', 'VGT_GRP_PRIM_INDEX_LINE', + 'VGT_GRP_PRIM_INDEX_QUAD', 'VGT_GRP_PRIM_INDEX_TRI', + 'VGT_GRP_PRIM_ORDER', 'VGT_GRP_PRIM_TYPE', 'VGT_GRP_SINT_16', + 'VGT_GRP_SINT_32', 'VGT_GRP_STRIP', 'VGT_GRP_UINT_16', + 'VGT_GRP_UINT_32', 'VGT_GS_CUT_MODE', 'VGT_GS_MODE_TYPE', + 'VGT_GS_OUTPRIM_TYPE', 'VGT_INDEX_16', 'VGT_INDEX_32', + 'VGT_INDEX_8', 'VGT_INDEX_TYPE_MODE', 'VGT_OUTPATH_GS_BLOCK', + 'VGT_OUTPATH_HS_BLOCK', 'VGT_OUTPATH_PASSTHRU', + 'VGT_OUTPATH_PRIM_GEN', 'VGT_OUTPATH_SELECT', + 'VGT_OUTPATH_TESS_EN', 'VGT_OUTPATH_VTX_REUSE', 'VGT_OUT_2D_RECT', + 'VGT_OUT_LINE', 'VGT_OUT_LINE_ADJ', 'VGT_OUT_PATCH', + 'VGT_OUT_POINT', 'VGT_OUT_PRIM_TYPE', 'VGT_OUT_RECT_V0', + 'VGT_OUT_RECT_V1', 'VGT_OUT_RECT_V2', 'VGT_OUT_RECT_V3', + 'VGT_OUT_TRI', 'VGT_OUT_TRI_ADJ', 'VGT_PERFCOUNT_SELECT', + 'VGT_POLICY_LRU', 'VGT_POLICY_STREAM', 'VGT_RDREQ_POLICY', + 'VGT_STAGES_ES_EN', 'VGT_STAGES_GS_EN', 'VGT_STAGES_HS_EN', + 'VGT_STAGES_LS_EN', 'VGT_STAGES_VS_EN', 'VGT_STREAMOUT_RESET', + 'VGT_STREAMOUT_SYNC', 'VGT_TESS_PARTITION', 'VGT_TESS_TOPOLOGY', + 'VGT_TESS_TYPE', 'VGT_TE_PRIM_INDEX_LINE', + 'VGT_TE_PRIM_INDEX_QUAD', 'VGT_TE_PRIM_INDEX_TRI', 'VGT_TE_QUAD', + 'VID_ENHANCED_MODE', 'VID_NORMAL_FRAME_MODE', + 'VID_STREAM_DISABLE_MASKED', 'VID_STREAM_DISABLE_UNMASK', + 'VMID_SZ', 'VS_PARTIAL_FLUSH', 'VS_STAGE_COPY_SHADER', + 'VS_STAGE_DS', 'VS_STAGE_REAL', 'VTX_CLAMP', + 'VTX_Clamp_ClampToNAN', 'VTX_Clamp_ClampToZero', 'VTX_FETCH_TYPE', + 'VTX_FORMAT_COMP_ALL', 'VTX_FetchType_InstanceData', + 'VTX_FetchType_NoIndexOffset', 'VTX_FetchType_RESERVED_3', + 'VTX_FetchType_VertexData', 'VTX_FormatCompAll_Signed', + 'VTX_FormatCompAll_Unsigned', 'VTX_MEM_REQUEST_SIZE', + 'VTX_MemRequestSize_32B', 'VTX_MemRequestSize_64B', + 'WD_IA_DRAW_REG_XFER', 'WD_IA_DRAW_REG_XFER_IA_MULTI_VGT_PARAM', + 'WD_IA_DRAW_REG_XFER_VGT_MULTI_PRIM_IB_RESET_EN', + 'WD_IA_DRAW_SOURCE', 'WD_IA_DRAW_SOURCE_AUTO', + 'WD_IA_DRAW_SOURCE_DMA', 'WD_IA_DRAW_SOURCE_IMMD', + 'WD_IA_DRAW_SOURCE_OPAQ', 'WD_IA_DRAW_TYPE', + 'WD_IA_DRAW_TYPE_DI_MM0', 'WD_IA_DRAW_TYPE_EVENT_ADDR', + 'WD_IA_DRAW_TYPE_EVENT_INIT', 'WD_IA_DRAW_TYPE_IMM_DATA', + 'WD_IA_DRAW_TYPE_INDX_OFF', 'WD_IA_DRAW_TYPE_MAX_INDX', + 'WD_IA_DRAW_TYPE_MIN_INDX', 'WD_IA_DRAW_TYPE_REG_XFER', + 'WD_PERFCOUNT_SELECT', 'XDMA_LOCAL_SW_MODE_SW_256B_D', + 'XDMA_LOCAL_SW_MODE_SW_64KB_D', 'XDMA_LOCAL_SW_MODE_SW_64KB_D_X', + 'XDMA_MSTR_ALPHA_POSITION_15_8', 'XDMA_MSTR_ALPHA_POSITION_23_16', + 'XDMA_MSTR_ALPHA_POSITION_31_24', 'XDMA_MSTR_ALPHA_POSITION_7_0', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE0', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE1', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE2', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE3', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE4', + 'XDMA_MSTR_VSYNC_GSL_CHECK_SEL_PIPE5', + 'XDMA_SLV_ALPHA_POSITION_15_8', 'XDMA_SLV_ALPHA_POSITION_23_16', + 'XDMA_SLV_ALPHA_POSITION_31_24', 'XDMA_SLV_ALPHA_POSITION_7_0', + 'XTAL_REF_CLOCK_SOURCE_SEL', 'XTAL_REF_CLOCK_SOURCE_SEL_PPLL', + 'XTAL_REF_CLOCK_SOURCE_SEL_XTALIN', 'XTAL_REF_SEL', + 'XTAL_REF_SEL_1X', 'XTAL_REF_SEL_2X', 'ZFormat', 'ZLimitSumm', + 'ZModeForce', 'ZOrder', 'ZPASS_DISABLE', 'ZPASS_DONE', + 'ZPASS_PIXELS', 'ZPASS_SAMPLES', 'ZSamplePosition', 'Z_16', + 'Z_24', 'Z_32_FLOAT', 'Z_INVALID', 'Z_SAMPLE_CENTER', + 'Z_SAMPLE_CENTROID', 'ZpassControl', '_vega10_ENUM_HEADER', + 'ia_perf_GRP_INPUT_EVENT_WINDOW_ACTIVE', 'ia_perf_MC_LAT_BIN_0', + 'ia_perf_MC_LAT_BIN_1', 'ia_perf_MC_LAT_BIN_2', + 'ia_perf_MC_LAT_BIN_3', 'ia_perf_MC_LAT_BIN_4', + 'ia_perf_MC_LAT_BIN_5', 'ia_perf_MC_LAT_BIN_6', + 'ia_perf_MC_LAT_BIN_7', 'ia_perf_RESERVED1', 'ia_perf_RESERVED2', + 'ia_perf_RESERVED3', 'ia_perf_RESERVED4', 'ia_perf_RESERVED5', + 'ia_perf_RESERVED6', 'ia_perf_RESERVED7', + 'ia_perf_dma_data_fifo_full', 'ia_perf_ia_busy', + 'ia_perf_ia_dma_return', 'ia_perf_ia_sclk_core_vld_event', + 'ia_perf_ia_sclk_reg_vld_event', 'ia_perf_ia_stalled', + 'ia_perf_shift_starved_pipe0_event', + 'ia_perf_shift_starved_pipe1_event', 'vgt_perf_VGT_PA_CLIPP_EOP', + 'vgt_perf_VGT_PA_CLIPP_IS_EVENT', + 'vgt_perf_VGT_PA_CLIPP_NEW_VTX_VECT', + 'vgt_perf_VGT_PA_CLIPP_NULL_PRIM', 'vgt_perf_VGT_PA_CLIPP_SEND', + 'vgt_perf_VGT_PA_CLIPP_STALLED', + 'vgt_perf_VGT_PA_CLIPP_STARVED_BUSY', + 'vgt_perf_VGT_PA_CLIPP_STARVED_IDLE', + 'vgt_perf_VGT_PA_CLIPP_STATIC', 'vgt_perf_VGT_PA_CLIPS_SEND', + 'vgt_perf_VGT_PA_CLIPS_STALLED', + 'vgt_perf_VGT_PA_CLIPS_STARVED_BUSY', + 'vgt_perf_VGT_PA_CLIPS_STARVED_IDLE', + 'vgt_perf_VGT_PA_CLIPS_STATIC', 'vgt_perf_VGT_PA_CLIPV_FIRSTVERT', + 'vgt_perf_VGT_PA_CLIPV_SEND', 'vgt_perf_VGT_PA_CLIPV_STALLED', + 'vgt_perf_VGT_PA_CLIPV_STARVED_BUSY', + 'vgt_perf_VGT_PA_CLIPV_STARVED_IDLE', + 'vgt_perf_VGT_PA_CLIPV_STATIC', + 'vgt_perf_VGT_PA_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_ESTHREAD_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_ESTHREAD_IS_EVENT', + 'vgt_perf_VGT_SPI_ESTHREAD_SEND', 'vgt_perf_VGT_SPI_ESVERT_EOV', + 'vgt_perf_VGT_SPI_ESVERT_STALLED', + 'vgt_perf_VGT_SPI_ESVERT_STARVED_BUSY', + 'vgt_perf_VGT_SPI_ESVERT_STARVED_IDLE', + 'vgt_perf_VGT_SPI_ESVERT_STATIC', 'vgt_perf_VGT_SPI_ESVERT_VALID', + 'vgt_perf_VGT_SPI_GSPRIM_CONT', 'vgt_perf_VGT_SPI_GSPRIM_EOV', + 'vgt_perf_VGT_SPI_GSPRIM_STALLED', + 'vgt_perf_VGT_SPI_GSPRIM_STARVED_BUSY', + 'vgt_perf_VGT_SPI_GSPRIM_STARVED_IDLE', + 'vgt_perf_VGT_SPI_GSPRIM_STATIC', 'vgt_perf_VGT_SPI_GSPRIM_VALID', + 'vgt_perf_VGT_SPI_GSTHREAD_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_GSTHREAD_IS_EVENT', + 'vgt_perf_VGT_SPI_GSTHREAD_SEND', 'vgt_perf_VGT_SPI_HSVERT_EOV', + 'vgt_perf_VGT_SPI_HSVERT_STALLED', + 'vgt_perf_VGT_SPI_HSVERT_STARVED_BUSY', + 'vgt_perf_VGT_SPI_HSVERT_STARVED_IDLE', + 'vgt_perf_VGT_SPI_HSVERT_STATIC', 'vgt_perf_VGT_SPI_HSVERT_VALID', + 'vgt_perf_VGT_SPI_HSWAVE_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_HSWAVE_IS_EVENT', + 'vgt_perf_VGT_SPI_HSWAVE_SEND', 'vgt_perf_VGT_SPI_LSVERT_EOV', + 'vgt_perf_VGT_SPI_LSVERT_STALLED', + 'vgt_perf_VGT_SPI_LSVERT_STARVED_BUSY', + 'vgt_perf_VGT_SPI_LSVERT_STARVED_IDLE', + 'vgt_perf_VGT_SPI_LSVERT_STATIC', 'vgt_perf_VGT_SPI_LSVERT_VALID', + 'vgt_perf_VGT_SPI_LSWAVE_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_LSWAVE_IS_EVENT', + 'vgt_perf_VGT_SPI_LSWAVE_SEND', + 'vgt_perf_VGT_SPI_VSTHREAD_EVENT_WINDOW_ACTIVE', + 'vgt_perf_VGT_SPI_VSTHREAD_IS_EVENT', + 'vgt_perf_VGT_SPI_VSTHREAD_SEND', 'vgt_perf_VGT_SPI_VSVERT_EOV', + 'vgt_perf_VGT_SPI_VSVERT_SEND', 'vgt_perf_VGT_SPI_VSVERT_STALLED', + 'vgt_perf_VGT_SPI_VSVERT_STARVED_BUSY', + 'vgt_perf_VGT_SPI_VSVERT_STARVED_IDLE', + 'vgt_perf_VGT_SPI_VSVERT_STATIC', 'vgt_perf_cm_reading_stalled', + 'vgt_perf_cm_stalled_by_gog', + 'vgt_perf_cm_stalled_by_gsfetch_done', + 'vgt_perf_counters_avail_stalled', + 'vgt_perf_cut_mem_flush_stalled', 'vgt_perf_ds_RESERVED', + 'vgt_perf_ds_cache_hits', 'vgt_perf_ds_prims', 'vgt_perf_es_done', + 'vgt_perf_es_done_latency', 'vgt_perf_es_flush', + 'vgt_perf_es_ring_high_water_mark', 'vgt_perf_es_thread_groups', + 'vgt_perf_esthread_stalled_es_rb_full', + 'vgt_perf_esthread_stalled_spi_bp', + 'vgt_perf_esvert_stalled_es_tbl', + 'vgt_perf_esvert_stalled_gs_event', + 'vgt_perf_esvert_stalled_gs_tbl', + 'vgt_perf_esvert_stalled_gsprim', 'vgt_perf_gog_busy', + 'vgt_perf_gog_out_indx_stalled', 'vgt_perf_gog_out_prim_stalled', + 'vgt_perf_gog_vs_tbl_stalled', 'vgt_perf_gs_cache_hits', + 'vgt_perf_gs_done', 'vgt_perf_gs_done_latency', + 'vgt_perf_gs_done_received', 'vgt_perf_gs_event_stall', + 'vgt_perf_gs_issue_rtr_stalled', + 'vgt_perf_gs_rb_space_avail_stalled', + 'vgt_perf_gs_ring_high_water_mark', + 'vgt_perf_gsprim_stalled_es_tbl', + 'vgt_perf_gsprim_stalled_esvert', + 'vgt_perf_gsprim_stalled_gs_event', + 'vgt_perf_gsprim_stalled_gs_tbl', 'vgt_perf_gsthread_stalled', + 'vgt_perf_hs_done', 'vgt_perf_hs_done_latency', + 'vgt_perf_hs_flush', 'vgt_perf_hs_input_stall', + 'vgt_perf_hs_interface_stall', 'vgt_perf_hs_tfm_stall', + 'vgt_perf_hs_tgs_active_high_water_mark', + 'vgt_perf_hs_thread_groups', 'vgt_perf_hs_tif_stall', + 'vgt_perf_hs_waiting_on_ls_done_stall', 'vgt_perf_hswave_stalled', + 'vgt_perf_ls_done', 'vgt_perf_ls_done_latency', + 'vgt_perf_ls_flush', 'vgt_perf_ls_thread_groups', + 'vgt_perf_pa_clipp_dealloc', 'vgt_perf_reused_es_indices', + 'vgt_perf_reused_vs_indices', 'vgt_perf_sclk_core_vld_event', + 'vgt_perf_sclk_gs_vld_event', 'vgt_perf_sclk_reg_vld_event', + 'vgt_perf_strmout_stalled', + 'vgt_perf_te11_con_starved_after_work', 'vgt_perf_te11_starved', + 'vgt_perf_total_cache_hits', 'vgt_perf_vgt_busy', + 'vgt_perf_vgt_gs_busy', 'vgt_perf_vgt_hs_busy', + 'vgt_perf_vgt_pa_clipp_eopg', + 'vgt_perf_vgt_pa_clipp_send_not_event', + 'vgt_perf_vgt_pa_clipp_starved_after_work', + 'vgt_perf_vgt_pa_clipp_valid_prim', 'vgt_perf_vgt_te11_busy', + 'vgt_perf_vs_cache_hits', 'vgt_perf_vs_conflicting_indices', + 'vgt_perf_vs_table_high_water_mark', 'vgt_perf_vs_thread_groups', + 'vgt_perf_vsfetch_done', 'vgt_perf_vsvert_api_send', + 'vgt_perf_vsvert_ds_send', 'vgt_perf_vsvert_work_received', + 'vgt_perf_wait_for_es_done_stalled', 'vgt_perf_waveid_stalled', + 'vgt_spi_vsvert_valid', 'wd_perf_RBIU_DI_FIFO_STALLED', + 'wd_perf_RBIU_DI_FIFO_STARVED', 'wd_perf_RBIU_DR_FIFO_STALLED', + 'wd_perf_RBIU_DR_FIFO_STARVED', + 'wd_perf_RBIU_FIFOS_EVENT_WINDOW_ACTIVE', 'wd_perf_hs_done_se0', + 'wd_perf_hs_done_se1', 'wd_perf_hs_done_se2', + 'wd_perf_hs_done_se3', 'wd_perf_inside_tf_bin_0', + 'wd_perf_inside_tf_bin_1', 'wd_perf_inside_tf_bin_2', + 'wd_perf_inside_tf_bin_3', 'wd_perf_inside_tf_bin_4', + 'wd_perf_inside_tf_bin_5', 'wd_perf_inside_tf_bin_6', + 'wd_perf_inside_tf_bin_7', 'wd_perf_inside_tf_bin_8', + 'wd_perf_null_patches', 'wd_perf_se0_hs_done_latency', + 'wd_perf_se1_hs_done_latency', 'wd_perf_se2_hs_done_latency', + 'wd_perf_se3_hs_done_latency', 'wd_perf_tfreq_lat_bin_0', + 'wd_perf_tfreq_lat_bin_1', 'wd_perf_tfreq_lat_bin_2', + 'wd_perf_tfreq_lat_bin_3', 'wd_perf_tfreq_lat_bin_4', + 'wd_perf_tfreq_lat_bin_5', 'wd_perf_tfreq_lat_bin_6', + 'wd_perf_tfreq_lat_bin_7', 'wd_perf_wd_busy', + 'wd_perf_wd_sclk_core_vld_event', + 'wd_perf_wd_sclk_input_vld_event', + 'wd_perf_wd_sclk_reg_vld_event', 'wd_perf_wd_stalled', + 'wd_starved_on_hs_done'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/amd_gpu.py b/tinygrad_repo/tinygrad/runtime/autogen/amd_gpu.py index b008a8bafa..9ea5e6d9fd 100644 --- a/tinygrad_repo/tinygrad/runtime/autogen/amd_gpu.py +++ b/tinygrad_repo/tinygrad/runtime/autogen/amd_gpu.py @@ -60943,6 +60943,852 @@ ixDIDT_SQ_STALL_EVENT_COUNTER = 0x00c0 # macro ixDIDT_DB_STALL_EVENT_COUNTER = 0x00c1 # macro ixDIDT_TD_STALL_EVENT_COUNTER = 0x00c2 # macro ixDIDT_TCP_STALL_EVENT_COUNTER = 0x00c3 # macro +_sienna_cichlid_ip_offset_HEADER = True # macro +MAX_INSTANCE = 7 # macro +MAX_SEGMENT = 5 # macro +ATHUB_BASE__INST0_SEG0 = 0x00000C00 # macro +ATHUB_BASE__INST0_SEG1 = 0x02408C00 # macro +ATHUB_BASE__INST0_SEG2 = 0 # macro +ATHUB_BASE__INST0_SEG3 = 0 # macro +ATHUB_BASE__INST0_SEG4 = 0 # macro +ATHUB_BASE__INST1_SEG0 = 0 # macro +ATHUB_BASE__INST1_SEG1 = 0 # macro +ATHUB_BASE__INST1_SEG2 = 0 # macro +ATHUB_BASE__INST1_SEG3 = 0 # macro +ATHUB_BASE__INST1_SEG4 = 0 # macro +ATHUB_BASE__INST2_SEG0 = 0 # macro +ATHUB_BASE__INST2_SEG1 = 0 # macro +ATHUB_BASE__INST2_SEG2 = 0 # macro +ATHUB_BASE__INST2_SEG3 = 0 # macro +ATHUB_BASE__INST2_SEG4 = 0 # macro +ATHUB_BASE__INST3_SEG0 = 0 # macro +ATHUB_BASE__INST3_SEG1 = 0 # macro +ATHUB_BASE__INST3_SEG2 = 0 # macro +ATHUB_BASE__INST3_SEG3 = 0 # macro +ATHUB_BASE__INST3_SEG4 = 0 # macro +ATHUB_BASE__INST4_SEG0 = 0 # macro +ATHUB_BASE__INST4_SEG1 = 0 # macro +ATHUB_BASE__INST4_SEG2 = 0 # macro +ATHUB_BASE__INST4_SEG3 = 0 # macro +ATHUB_BASE__INST4_SEG4 = 0 # macro +ATHUB_BASE__INST5_SEG0 = 0 # macro +ATHUB_BASE__INST5_SEG1 = 0 # macro +ATHUB_BASE__INST5_SEG2 = 0 # macro +ATHUB_BASE__INST5_SEG3 = 0 # macro +ATHUB_BASE__INST5_SEG4 = 0 # macro +ATHUB_BASE__INST6_SEG0 = 0 # macro +ATHUB_BASE__INST6_SEG1 = 0 # macro +ATHUB_BASE__INST6_SEG2 = 0 # macro +ATHUB_BASE__INST6_SEG3 = 0 # macro +ATHUB_BASE__INST6_SEG4 = 0 # macro +CLK_BASE__INST0_SEG0 = 0x00016C00 # macro +CLK_BASE__INST0_SEG1 = 0x02401800 # macro +CLK_BASE__INST0_SEG2 = 0 # macro +CLK_BASE__INST0_SEG3 = 0 # macro +CLK_BASE__INST0_SEG4 = 0 # macro +CLK_BASE__INST1_SEG0 = 0x00016E00 # macro +CLK_BASE__INST1_SEG1 = 0x02401C00 # macro +CLK_BASE__INST1_SEG2 = 0 # macro +CLK_BASE__INST1_SEG3 = 0 # macro +CLK_BASE__INST1_SEG4 = 0 # macro +CLK_BASE__INST2_SEG0 = 0x00017000 # macro +CLK_BASE__INST2_SEG1 = 0x02402000 # macro +CLK_BASE__INST2_SEG2 = 0 # macro +CLK_BASE__INST2_SEG3 = 0 # macro +CLK_BASE__INST2_SEG4 = 0 # macro +CLK_BASE__INST3_SEG0 = 0x00017200 # macro +CLK_BASE__INST3_SEG1 = 0x02402400 # macro +CLK_BASE__INST3_SEG2 = 0 # macro +CLK_BASE__INST3_SEG3 = 0 # macro +CLK_BASE__INST3_SEG4 = 0 # macro +CLK_BASE__INST4_SEG0 = 0x0001B000 # macro +CLK_BASE__INST4_SEG1 = 0x0242D800 # macro +CLK_BASE__INST4_SEG2 = 0 # macro +CLK_BASE__INST4_SEG3 = 0 # macro +CLK_BASE__INST4_SEG4 = 0 # macro +CLK_BASE__INST5_SEG0 = 0x0001B200 # macro +CLK_BASE__INST5_SEG1 = 0x0242DC00 # macro +CLK_BASE__INST5_SEG2 = 0 # macro +CLK_BASE__INST5_SEG3 = 0 # macro +CLK_BASE__INST5_SEG4 = 0 # macro +CLK_BASE__INST6_SEG0 = 0x0001B400 # macro +CLK_BASE__INST6_SEG1 = 0x0242E000 # macro +CLK_BASE__INST6_SEG2 = 0 # macro +CLK_BASE__INST6_SEG3 = 0 # macro +CLK_BASE__INST6_SEG4 = 0 # macro +DF_BASE__INST0_SEG0 = 0x00007000 # macro +DF_BASE__INST0_SEG1 = 0x0240B800 # macro +DF_BASE__INST0_SEG2 = 0 # macro +DF_BASE__INST0_SEG3 = 0 # macro +DF_BASE__INST0_SEG4 = 0 # macro +DF_BASE__INST1_SEG0 = 0 # macro +DF_BASE__INST1_SEG1 = 0 # macro +DF_BASE__INST1_SEG2 = 0 # macro +DF_BASE__INST1_SEG3 = 0 # macro +DF_BASE__INST1_SEG4 = 0 # macro +DF_BASE__INST2_SEG0 = 0 # macro +DF_BASE__INST2_SEG1 = 0 # macro +DF_BASE__INST2_SEG2 = 0 # macro +DF_BASE__INST2_SEG3 = 0 # macro +DF_BASE__INST2_SEG4 = 0 # macro +DF_BASE__INST3_SEG0 = 0 # macro +DF_BASE__INST3_SEG1 = 0 # macro +DF_BASE__INST3_SEG2 = 0 # macro +DF_BASE__INST3_SEG3 = 0 # macro +DF_BASE__INST3_SEG4 = 0 # macro +DF_BASE__INST4_SEG0 = 0 # macro +DF_BASE__INST4_SEG1 = 0 # macro +DF_BASE__INST4_SEG2 = 0 # macro +DF_BASE__INST4_SEG3 = 0 # macro +DF_BASE__INST4_SEG4 = 0 # macro +DF_BASE__INST5_SEG0 = 0 # macro +DF_BASE__INST5_SEG1 = 0 # macro +DF_BASE__INST5_SEG2 = 0 # macro +DF_BASE__INST5_SEG3 = 0 # macro +DF_BASE__INST5_SEG4 = 0 # macro +DF_BASE__INST6_SEG0 = 0 # macro +DF_BASE__INST6_SEG1 = 0 # macro +DF_BASE__INST6_SEG2 = 0 # macro +DF_BASE__INST6_SEG3 = 0 # macro +DF_BASE__INST6_SEG4 = 0 # macro +DIO_BASE__INST0_SEG0 = 0x02404000 # macro +DIO_BASE__INST0_SEG1 = 0 # macro +DIO_BASE__INST0_SEG2 = 0 # macro +DIO_BASE__INST0_SEG3 = 0 # macro +DIO_BASE__INST0_SEG4 = 0 # macro +DIO_BASE__INST1_SEG0 = 0 # macro +DIO_BASE__INST1_SEG1 = 0 # macro +DIO_BASE__INST1_SEG2 = 0 # macro +DIO_BASE__INST1_SEG3 = 0 # macro +DIO_BASE__INST1_SEG4 = 0 # macro +DIO_BASE__INST2_SEG0 = 0 # macro +DIO_BASE__INST2_SEG1 = 0 # macro +DIO_BASE__INST2_SEG2 = 0 # macro +DIO_BASE__INST2_SEG3 = 0 # macro +DIO_BASE__INST2_SEG4 = 0 # macro +DIO_BASE__INST3_SEG0 = 0 # macro +DIO_BASE__INST3_SEG1 = 0 # macro +DIO_BASE__INST3_SEG2 = 0 # macro +DIO_BASE__INST3_SEG3 = 0 # macro +DIO_BASE__INST3_SEG4 = 0 # macro +DIO_BASE__INST4_SEG0 = 0 # macro +DIO_BASE__INST4_SEG1 = 0 # macro +DIO_BASE__INST4_SEG2 = 0 # macro +DIO_BASE__INST4_SEG3 = 0 # macro +DIO_BASE__INST4_SEG4 = 0 # macro +DIO_BASE__INST5_SEG0 = 0 # macro +DIO_BASE__INST5_SEG1 = 0 # macro +DIO_BASE__INST5_SEG2 = 0 # macro +DIO_BASE__INST5_SEG3 = 0 # macro +DIO_BASE__INST5_SEG4 = 0 # macro +DIO_BASE__INST6_SEG0 = 0 # macro +DIO_BASE__INST6_SEG1 = 0 # macro +DIO_BASE__INST6_SEG2 = 0 # macro +DIO_BASE__INST6_SEG3 = 0 # macro +DIO_BASE__INST6_SEG4 = 0 # macro +DCN_BASE__INST0_SEG0 = 0x00000012 # macro +DCN_BASE__INST0_SEG1 = 0x000000C0 # macro +DCN_BASE__INST0_SEG2 = 0x000034C0 # macro +DCN_BASE__INST0_SEG3 = 0x00009000 # macro +DCN_BASE__INST0_SEG4 = 0x02403C00 # macro +DCN_BASE__INST1_SEG0 = 0 # macro +DCN_BASE__INST1_SEG1 = 0 # macro +DCN_BASE__INST1_SEG2 = 0 # macro +DCN_BASE__INST1_SEG3 = 0 # macro +DCN_BASE__INST1_SEG4 = 0 # macro +DCN_BASE__INST2_SEG0 = 0 # macro +DCN_BASE__INST2_SEG1 = 0 # macro +DCN_BASE__INST2_SEG2 = 0 # macro +DCN_BASE__INST2_SEG3 = 0 # macro +DCN_BASE__INST2_SEG4 = 0 # macro +DCN_BASE__INST3_SEG0 = 0 # macro +DCN_BASE__INST3_SEG1 = 0 # macro +DCN_BASE__INST3_SEG2 = 0 # macro +DCN_BASE__INST3_SEG3 = 0 # macro +DCN_BASE__INST3_SEG4 = 0 # macro +DCN_BASE__INST4_SEG0 = 0 # macro +DCN_BASE__INST4_SEG1 = 0 # macro +DCN_BASE__INST4_SEG2 = 0 # macro +DCN_BASE__INST4_SEG3 = 0 # macro +DCN_BASE__INST4_SEG4 = 0 # macro +DCN_BASE__INST5_SEG0 = 0 # macro +DCN_BASE__INST5_SEG1 = 0 # macro +DCN_BASE__INST5_SEG2 = 0 # macro +DCN_BASE__INST5_SEG3 = 0 # macro +DCN_BASE__INST5_SEG4 = 0 # macro +DCN_BASE__INST6_SEG0 = 0 # macro +DCN_BASE__INST6_SEG1 = 0 # macro +DCN_BASE__INST6_SEG2 = 0 # macro +DCN_BASE__INST6_SEG3 = 0 # macro +DCN_BASE__INST6_SEG4 = 0 # macro +DPCS_BASE__INST0_SEG0 = 0x00000012 # macro +DPCS_BASE__INST0_SEG1 = 0x000000C0 # macro +DPCS_BASE__INST0_SEG2 = 0x000034C0 # macro +DPCS_BASE__INST0_SEG3 = 0x00009000 # macro +DPCS_BASE__INST0_SEG4 = 0x02403C00 # macro +DPCS_BASE__INST1_SEG0 = 0 # macro +DPCS_BASE__INST1_SEG1 = 0 # macro +DPCS_BASE__INST1_SEG2 = 0 # macro +DPCS_BASE__INST1_SEG3 = 0 # macro +DPCS_BASE__INST1_SEG4 = 0 # macro +DPCS_BASE__INST2_SEG0 = 0 # macro +DPCS_BASE__INST2_SEG1 = 0 # macro +DPCS_BASE__INST2_SEG2 = 0 # macro +DPCS_BASE__INST2_SEG3 = 0 # macro +DPCS_BASE__INST2_SEG4 = 0 # macro +DPCS_BASE__INST3_SEG0 = 0 # macro +DPCS_BASE__INST3_SEG1 = 0 # macro +DPCS_BASE__INST3_SEG2 = 0 # macro +DPCS_BASE__INST3_SEG3 = 0 # macro +DPCS_BASE__INST3_SEG4 = 0 # macro +DPCS_BASE__INST4_SEG0 = 0 # macro +DPCS_BASE__INST4_SEG1 = 0 # macro +DPCS_BASE__INST4_SEG2 = 0 # macro +DPCS_BASE__INST4_SEG3 = 0 # macro +DPCS_BASE__INST4_SEG4 = 0 # macro +DPCS_BASE__INST5_SEG0 = 0 # macro +DPCS_BASE__INST5_SEG1 = 0 # macro +DPCS_BASE__INST5_SEG2 = 0 # macro +DPCS_BASE__INST5_SEG3 = 0 # macro +DPCS_BASE__INST5_SEG4 = 0 # macro +DPCS_BASE__INST6_SEG0 = 0 # macro +DPCS_BASE__INST6_SEG1 = 0 # macro +DPCS_BASE__INST6_SEG2 = 0 # macro +DPCS_BASE__INST6_SEG3 = 0 # macro +DPCS_BASE__INST6_SEG4 = 0 # macro +FUSE_BASE__INST0_SEG0 = 0x00017400 # macro +FUSE_BASE__INST0_SEG1 = 0x02401400 # macro +FUSE_BASE__INST0_SEG2 = 0 # macro +FUSE_BASE__INST0_SEG3 = 0 # macro +FUSE_BASE__INST0_SEG4 = 0 # macro +FUSE_BASE__INST1_SEG0 = 0 # macro +FUSE_BASE__INST1_SEG1 = 0 # macro +FUSE_BASE__INST1_SEG2 = 0 # macro +FUSE_BASE__INST1_SEG3 = 0 # macro +FUSE_BASE__INST1_SEG4 = 0 # macro +FUSE_BASE__INST2_SEG0 = 0 # macro +FUSE_BASE__INST2_SEG1 = 0 # macro +FUSE_BASE__INST2_SEG2 = 0 # macro +FUSE_BASE__INST2_SEG3 = 0 # macro +FUSE_BASE__INST2_SEG4 = 0 # macro +FUSE_BASE__INST3_SEG0 = 0 # macro +FUSE_BASE__INST3_SEG1 = 0 # macro +FUSE_BASE__INST3_SEG2 = 0 # macro +FUSE_BASE__INST3_SEG3 = 0 # macro +FUSE_BASE__INST3_SEG4 = 0 # macro +FUSE_BASE__INST4_SEG0 = 0 # macro +FUSE_BASE__INST4_SEG1 = 0 # macro +FUSE_BASE__INST4_SEG2 = 0 # macro +FUSE_BASE__INST4_SEG3 = 0 # macro +FUSE_BASE__INST4_SEG4 = 0 # macro +FUSE_BASE__INST5_SEG0 = 0 # macro +FUSE_BASE__INST5_SEG1 = 0 # macro +FUSE_BASE__INST5_SEG2 = 0 # macro +FUSE_BASE__INST5_SEG3 = 0 # macro +FUSE_BASE__INST5_SEG4 = 0 # macro +FUSE_BASE__INST6_SEG0 = 0 # macro +FUSE_BASE__INST6_SEG1 = 0 # macro +FUSE_BASE__INST6_SEG2 = 0 # macro +FUSE_BASE__INST6_SEG3 = 0 # macro +FUSE_BASE__INST6_SEG4 = 0 # macro +GC_BASE__INST0_SEG0 = 0x00001260 # macro +GC_BASE__INST0_SEG1 = 0x0000A000 # macro +GC_BASE__INST0_SEG2 = 0x0001C000 # macro +GC_BASE__INST0_SEG3 = 0x02402C00 # macro +GC_BASE__INST0_SEG4 = 0 # macro +GC_BASE__INST1_SEG0 = 0 # macro +GC_BASE__INST1_SEG1 = 0 # macro +GC_BASE__INST1_SEG2 = 0 # macro +GC_BASE__INST1_SEG3 = 0 # macro +GC_BASE__INST1_SEG4 = 0 # macro +GC_BASE__INST2_SEG0 = 0 # macro +GC_BASE__INST2_SEG1 = 0 # macro +GC_BASE__INST2_SEG2 = 0 # macro +GC_BASE__INST2_SEG3 = 0 # macro +GC_BASE__INST2_SEG4 = 0 # macro +GC_BASE__INST3_SEG0 = 0 # macro +GC_BASE__INST3_SEG1 = 0 # macro +GC_BASE__INST3_SEG2 = 0 # macro +GC_BASE__INST3_SEG3 = 0 # macro +GC_BASE__INST3_SEG4 = 0 # macro +GC_BASE__INST4_SEG0 = 0 # macro +GC_BASE__INST4_SEG1 = 0 # macro +GC_BASE__INST4_SEG2 = 0 # macro +GC_BASE__INST4_SEG3 = 0 # macro +GC_BASE__INST4_SEG4 = 0 # macro +GC_BASE__INST5_SEG0 = 0 # macro +GC_BASE__INST5_SEG1 = 0 # macro +GC_BASE__INST5_SEG2 = 0 # macro +GC_BASE__INST5_SEG3 = 0 # macro +GC_BASE__INST5_SEG4 = 0 # macro +GC_BASE__INST6_SEG0 = 0 # macro +GC_BASE__INST6_SEG1 = 0 # macro +GC_BASE__INST6_SEG2 = 0 # macro +GC_BASE__INST6_SEG3 = 0 # macro +GC_BASE__INST6_SEG4 = 0 # macro +HDA_BASE__INST0_SEG0 = 0x004C0000 # macro +HDA_BASE__INST0_SEG1 = 0x02404800 # macro +HDA_BASE__INST0_SEG2 = 0 # macro +HDA_BASE__INST0_SEG3 = 0 # macro +HDA_BASE__INST0_SEG4 = 0 # macro +HDA_BASE__INST1_SEG0 = 0 # macro +HDA_BASE__INST1_SEG1 = 0 # macro +HDA_BASE__INST1_SEG2 = 0 # macro +HDA_BASE__INST1_SEG3 = 0 # macro +HDA_BASE__INST1_SEG4 = 0 # macro +HDA_BASE__INST2_SEG0 = 0 # macro +HDA_BASE__INST2_SEG1 = 0 # macro +HDA_BASE__INST2_SEG2 = 0 # macro +HDA_BASE__INST2_SEG3 = 0 # macro +HDA_BASE__INST2_SEG4 = 0 # macro +HDA_BASE__INST3_SEG0 = 0 # macro +HDA_BASE__INST3_SEG1 = 0 # macro +HDA_BASE__INST3_SEG2 = 0 # macro +HDA_BASE__INST3_SEG3 = 0 # macro +HDA_BASE__INST3_SEG4 = 0 # macro +HDA_BASE__INST4_SEG0 = 0 # macro +HDA_BASE__INST4_SEG1 = 0 # macro +HDA_BASE__INST4_SEG2 = 0 # macro +HDA_BASE__INST4_SEG3 = 0 # macro +HDA_BASE__INST4_SEG4 = 0 # macro +HDA_BASE__INST5_SEG0 = 0 # macro +HDA_BASE__INST5_SEG1 = 0 # macro +HDA_BASE__INST5_SEG2 = 0 # macro +HDA_BASE__INST5_SEG3 = 0 # macro +HDA_BASE__INST5_SEG4 = 0 # macro +HDA_BASE__INST6_SEG0 = 0 # macro +HDA_BASE__INST6_SEG1 = 0 # macro +HDA_BASE__INST6_SEG2 = 0 # macro +HDA_BASE__INST6_SEG3 = 0 # macro +HDA_BASE__INST6_SEG4 = 0 # macro +HDP_BASE__INST0_SEG0 = 0x00000F20 # macro +HDP_BASE__INST0_SEG1 = 0x0240A400 # macro +HDP_BASE__INST0_SEG2 = 0 # macro +HDP_BASE__INST0_SEG3 = 0 # macro +HDP_BASE__INST0_SEG4 = 0 # macro +HDP_BASE__INST1_SEG0 = 0 # macro +HDP_BASE__INST1_SEG1 = 0 # macro +HDP_BASE__INST1_SEG2 = 0 # macro +HDP_BASE__INST1_SEG3 = 0 # macro +HDP_BASE__INST1_SEG4 = 0 # macro +HDP_BASE__INST2_SEG0 = 0 # macro +HDP_BASE__INST2_SEG1 = 0 # macro +HDP_BASE__INST2_SEG2 = 0 # macro +HDP_BASE__INST2_SEG3 = 0 # macro +HDP_BASE__INST2_SEG4 = 0 # macro +HDP_BASE__INST3_SEG0 = 0 # macro +HDP_BASE__INST3_SEG1 = 0 # macro +HDP_BASE__INST3_SEG2 = 0 # macro +HDP_BASE__INST3_SEG3 = 0 # macro +HDP_BASE__INST3_SEG4 = 0 # macro +HDP_BASE__INST4_SEG0 = 0 # macro +HDP_BASE__INST4_SEG1 = 0 # macro +HDP_BASE__INST4_SEG2 = 0 # macro +HDP_BASE__INST4_SEG3 = 0 # macro +HDP_BASE__INST4_SEG4 = 0 # macro +HDP_BASE__INST5_SEG0 = 0 # macro +HDP_BASE__INST5_SEG1 = 0 # macro +HDP_BASE__INST5_SEG2 = 0 # macro +HDP_BASE__INST5_SEG3 = 0 # macro +HDP_BASE__INST5_SEG4 = 0 # macro +HDP_BASE__INST6_SEG0 = 0 # macro +HDP_BASE__INST6_SEG1 = 0 # macro +HDP_BASE__INST6_SEG2 = 0 # macro +HDP_BASE__INST6_SEG3 = 0 # macro +HDP_BASE__INST6_SEG4 = 0 # macro +MMHUB_BASE__INST0_SEG0 = 0x0001A000 # macro +MMHUB_BASE__INST0_SEG1 = 0x02408800 # macro +MMHUB_BASE__INST0_SEG2 = 0 # macro +MMHUB_BASE__INST0_SEG3 = 0 # macro +MMHUB_BASE__INST0_SEG4 = 0 # macro +MMHUB_BASE__INST1_SEG0 = 0 # macro +MMHUB_BASE__INST1_SEG1 = 0 # macro +MMHUB_BASE__INST1_SEG2 = 0 # macro +MMHUB_BASE__INST1_SEG3 = 0 # macro +MMHUB_BASE__INST1_SEG4 = 0 # macro +MMHUB_BASE__INST2_SEG0 = 0 # macro +MMHUB_BASE__INST2_SEG1 = 0 # macro +MMHUB_BASE__INST2_SEG2 = 0 # macro +MMHUB_BASE__INST2_SEG3 = 0 # macro +MMHUB_BASE__INST2_SEG4 = 0 # macro +MMHUB_BASE__INST3_SEG0 = 0 # macro +MMHUB_BASE__INST3_SEG1 = 0 # macro +MMHUB_BASE__INST3_SEG2 = 0 # macro +MMHUB_BASE__INST3_SEG3 = 0 # macro +MMHUB_BASE__INST3_SEG4 = 0 # macro +MMHUB_BASE__INST4_SEG0 = 0 # macro +MMHUB_BASE__INST4_SEG1 = 0 # macro +MMHUB_BASE__INST4_SEG2 = 0 # macro +MMHUB_BASE__INST4_SEG3 = 0 # macro +MMHUB_BASE__INST4_SEG4 = 0 # macro +MMHUB_BASE__INST5_SEG0 = 0 # macro +MMHUB_BASE__INST5_SEG1 = 0 # macro +MMHUB_BASE__INST5_SEG2 = 0 # macro +MMHUB_BASE__INST5_SEG3 = 0 # macro +MMHUB_BASE__INST5_SEG4 = 0 # macro +MMHUB_BASE__INST6_SEG0 = 0 # macro +MMHUB_BASE__INST6_SEG1 = 0 # macro +MMHUB_BASE__INST6_SEG2 = 0 # macro +MMHUB_BASE__INST6_SEG3 = 0 # macro +MMHUB_BASE__INST6_SEG4 = 0 # macro +MP0_BASE__INST0_SEG0 = 0x00016000 # macro +MP0_BASE__INST0_SEG1 = 0x00DC0000 # macro +MP0_BASE__INST0_SEG2 = 0x00E00000 # macro +MP0_BASE__INST0_SEG3 = 0x00E40000 # macro +MP0_BASE__INST0_SEG4 = 0x0243FC00 # macro +MP0_BASE__INST1_SEG0 = 0 # macro +MP0_BASE__INST1_SEG1 = 0 # macro +MP0_BASE__INST1_SEG2 = 0 # macro +MP0_BASE__INST1_SEG3 = 0 # macro +MP0_BASE__INST1_SEG4 = 0 # macro +MP0_BASE__INST2_SEG0 = 0 # macro +MP0_BASE__INST2_SEG1 = 0 # macro +MP0_BASE__INST2_SEG2 = 0 # macro +MP0_BASE__INST2_SEG3 = 0 # macro +MP0_BASE__INST2_SEG4 = 0 # macro +MP0_BASE__INST3_SEG0 = 0 # macro +MP0_BASE__INST3_SEG1 = 0 # macro +MP0_BASE__INST3_SEG2 = 0 # macro +MP0_BASE__INST3_SEG3 = 0 # macro +MP0_BASE__INST3_SEG4 = 0 # macro +MP0_BASE__INST4_SEG0 = 0 # macro +MP0_BASE__INST4_SEG1 = 0 # macro +MP0_BASE__INST4_SEG2 = 0 # macro +MP0_BASE__INST4_SEG3 = 0 # macro +MP0_BASE__INST4_SEG4 = 0 # macro +MP0_BASE__INST5_SEG0 = 0 # macro +MP0_BASE__INST5_SEG1 = 0 # macro +MP0_BASE__INST5_SEG2 = 0 # macro +MP0_BASE__INST5_SEG3 = 0 # macro +MP0_BASE__INST5_SEG4 = 0 # macro +MP0_BASE__INST6_SEG0 = 0 # macro +MP0_BASE__INST6_SEG1 = 0 # macro +MP0_BASE__INST6_SEG2 = 0 # macro +MP0_BASE__INST6_SEG3 = 0 # macro +MP0_BASE__INST6_SEG4 = 0 # macro +MP1_BASE__INST0_SEG0 = 0x00016000 # macro +MP1_BASE__INST0_SEG1 = 0x00DC0000 # macro +MP1_BASE__INST0_SEG2 = 0x00E00000 # macro +MP1_BASE__INST0_SEG3 = 0x00E40000 # macro +MP1_BASE__INST0_SEG4 = 0x0243FC00 # macro +MP1_BASE__INST1_SEG0 = 0 # macro +MP1_BASE__INST1_SEG1 = 0 # macro +MP1_BASE__INST1_SEG2 = 0 # macro +MP1_BASE__INST1_SEG3 = 0 # macro +MP1_BASE__INST1_SEG4 = 0 # macro +MP1_BASE__INST2_SEG0 = 0 # macro +MP1_BASE__INST2_SEG1 = 0 # macro +MP1_BASE__INST2_SEG2 = 0 # macro +MP1_BASE__INST2_SEG3 = 0 # macro +MP1_BASE__INST2_SEG4 = 0 # macro +MP1_BASE__INST3_SEG0 = 0 # macro +MP1_BASE__INST3_SEG1 = 0 # macro +MP1_BASE__INST3_SEG2 = 0 # macro +MP1_BASE__INST3_SEG3 = 0 # macro +MP1_BASE__INST3_SEG4 = 0 # macro +MP1_BASE__INST4_SEG0 = 0 # macro +MP1_BASE__INST4_SEG1 = 0 # macro +MP1_BASE__INST4_SEG2 = 0 # macro +MP1_BASE__INST4_SEG3 = 0 # macro +MP1_BASE__INST4_SEG4 = 0 # macro +MP1_BASE__INST5_SEG0 = 0 # macro +MP1_BASE__INST5_SEG1 = 0 # macro +MP1_BASE__INST5_SEG2 = 0 # macro +MP1_BASE__INST5_SEG3 = 0 # macro +MP1_BASE__INST5_SEG4 = 0 # macro +MP1_BASE__INST6_SEG0 = 0 # macro +MP1_BASE__INST6_SEG1 = 0 # macro +MP1_BASE__INST6_SEG2 = 0 # macro +MP1_BASE__INST6_SEG3 = 0 # macro +MP1_BASE__INST6_SEG4 = 0 # macro +NBIO_BASE__INST0_SEG0 = 0x00000000 # macro +NBIO_BASE__INST0_SEG1 = 0x00000014 # macro +NBIO_BASE__INST0_SEG2 = 0x00000D20 # macro +NBIO_BASE__INST0_SEG3 = 0x00010400 # macro +NBIO_BASE__INST0_SEG4 = 0x0241B000 # macro +NBIO_BASE__INST1_SEG0 = 0 # macro +NBIO_BASE__INST1_SEG1 = 0 # macro +NBIO_BASE__INST1_SEG2 = 0 # macro +NBIO_BASE__INST1_SEG3 = 0 # macro +NBIO_BASE__INST1_SEG4 = 0 # macro +NBIO_BASE__INST2_SEG0 = 0 # macro +NBIO_BASE__INST2_SEG1 = 0 # macro +NBIO_BASE__INST2_SEG2 = 0 # macro +NBIO_BASE__INST2_SEG3 = 0 # macro +NBIO_BASE__INST2_SEG4 = 0 # macro +NBIO_BASE__INST3_SEG0 = 0 # macro +NBIO_BASE__INST3_SEG1 = 0 # macro +NBIO_BASE__INST3_SEG2 = 0 # macro +NBIO_BASE__INST3_SEG3 = 0 # macro +NBIO_BASE__INST3_SEG4 = 0 # macro +NBIO_BASE__INST4_SEG0 = 0 # macro +NBIO_BASE__INST4_SEG1 = 0 # macro +NBIO_BASE__INST4_SEG2 = 0 # macro +NBIO_BASE__INST4_SEG3 = 0 # macro +NBIO_BASE__INST4_SEG4 = 0 # macro +NBIO_BASE__INST5_SEG0 = 0 # macro +NBIO_BASE__INST5_SEG1 = 0 # macro +NBIO_BASE__INST5_SEG2 = 0 # macro +NBIO_BASE__INST5_SEG3 = 0 # macro +NBIO_BASE__INST5_SEG4 = 0 # macro +NBIO_BASE__INST6_SEG0 = 0 # macro +NBIO_BASE__INST6_SEG1 = 0 # macro +NBIO_BASE__INST6_SEG2 = 0 # macro +NBIO_BASE__INST6_SEG3 = 0 # macro +NBIO_BASE__INST6_SEG4 = 0 # macro +OSSSYS_BASE__INST0_SEG0 = 0x000010A0 # macro +OSSSYS_BASE__INST0_SEG1 = 0x0240A000 # macro +OSSSYS_BASE__INST0_SEG2 = 0 # macro +OSSSYS_BASE__INST0_SEG3 = 0 # macro +OSSSYS_BASE__INST0_SEG4 = 0 # macro +OSSSYS_BASE__INST1_SEG0 = 0 # macro +OSSSYS_BASE__INST1_SEG1 = 0 # macro +OSSSYS_BASE__INST1_SEG2 = 0 # macro +OSSSYS_BASE__INST1_SEG3 = 0 # macro +OSSSYS_BASE__INST1_SEG4 = 0 # macro +OSSSYS_BASE__INST2_SEG0 = 0 # macro +OSSSYS_BASE__INST2_SEG1 = 0 # macro +OSSSYS_BASE__INST2_SEG2 = 0 # macro +OSSSYS_BASE__INST2_SEG3 = 0 # macro +OSSSYS_BASE__INST2_SEG4 = 0 # macro +OSSSYS_BASE__INST3_SEG0 = 0 # macro +OSSSYS_BASE__INST3_SEG1 = 0 # macro +OSSSYS_BASE__INST3_SEG2 = 0 # macro +OSSSYS_BASE__INST3_SEG3 = 0 # macro +OSSSYS_BASE__INST3_SEG4 = 0 # macro +OSSSYS_BASE__INST4_SEG0 = 0 # macro +OSSSYS_BASE__INST4_SEG1 = 0 # macro +OSSSYS_BASE__INST4_SEG2 = 0 # macro +OSSSYS_BASE__INST4_SEG3 = 0 # macro +OSSSYS_BASE__INST4_SEG4 = 0 # macro +OSSSYS_BASE__INST5_SEG0 = 0 # macro +OSSSYS_BASE__INST5_SEG1 = 0 # macro +OSSSYS_BASE__INST5_SEG2 = 0 # macro +OSSSYS_BASE__INST5_SEG3 = 0 # macro +OSSSYS_BASE__INST5_SEG4 = 0 # macro +OSSSYS_BASE__INST6_SEG0 = 0 # macro +OSSSYS_BASE__INST6_SEG1 = 0 # macro +OSSSYS_BASE__INST6_SEG2 = 0 # macro +OSSSYS_BASE__INST6_SEG3 = 0 # macro +OSSSYS_BASE__INST6_SEG4 = 0 # macro +PCIE0_BASE__INST0_SEG0 = 0x00000000 # macro +PCIE0_BASE__INST0_SEG1 = 0x00000014 # macro +PCIE0_BASE__INST0_SEG2 = 0x00000D20 # macro +PCIE0_BASE__INST0_SEG3 = 0x00010400 # macro +PCIE0_BASE__INST0_SEG4 = 0x0241B000 # macro +PCIE0_BASE__INST1_SEG0 = 0 # macro +PCIE0_BASE__INST1_SEG1 = 0 # macro +PCIE0_BASE__INST1_SEG2 = 0 # macro +PCIE0_BASE__INST1_SEG3 = 0 # macro +PCIE0_BASE__INST1_SEG4 = 0 # macro +PCIE0_BASE__INST2_SEG0 = 0 # macro +PCIE0_BASE__INST2_SEG1 = 0 # macro +PCIE0_BASE__INST2_SEG2 = 0 # macro +PCIE0_BASE__INST2_SEG3 = 0 # macro +PCIE0_BASE__INST2_SEG4 = 0 # macro +PCIE0_BASE__INST3_SEG0 = 0 # macro +PCIE0_BASE__INST3_SEG1 = 0 # macro +PCIE0_BASE__INST3_SEG2 = 0 # macro +PCIE0_BASE__INST3_SEG3 = 0 # macro +PCIE0_BASE__INST3_SEG4 = 0 # macro +PCIE0_BASE__INST4_SEG0 = 0 # macro +PCIE0_BASE__INST4_SEG1 = 0 # macro +PCIE0_BASE__INST4_SEG2 = 0 # macro +PCIE0_BASE__INST4_SEG3 = 0 # macro +PCIE0_BASE__INST4_SEG4 = 0 # macro +PCIE0_BASE__INST5_SEG0 = 0 # macro +PCIE0_BASE__INST5_SEG1 = 0 # macro +PCIE0_BASE__INST5_SEG2 = 0 # macro +PCIE0_BASE__INST5_SEG3 = 0 # macro +PCIE0_BASE__INST5_SEG4 = 0 # macro +PCIE0_BASE__INST6_SEG0 = 0 # macro +PCIE0_BASE__INST6_SEG1 = 0 # macro +PCIE0_BASE__INST6_SEG2 = 0 # macro +PCIE0_BASE__INST6_SEG3 = 0 # macro +PCIE0_BASE__INST6_SEG4 = 0 # macro +SDMA0_BASE__INST0_SEG0 = 0x00001260 # macro +SDMA0_BASE__INST0_SEG1 = 0x0000A000 # macro +SDMA0_BASE__INST0_SEG2 = 0x0001C000 # macro +SDMA0_BASE__INST0_SEG3 = 0x02402C00 # macro +SDMA0_BASE__INST0_SEG4 = 0 # macro +SDMA0_BASE__INST1_SEG0 = 0 # macro +SDMA0_BASE__INST1_SEG1 = 0 # macro +SDMA0_BASE__INST1_SEG2 = 0 # macro +SDMA0_BASE__INST1_SEG3 = 0 # macro +SDMA0_BASE__INST1_SEG4 = 0 # macro +SDMA0_BASE__INST2_SEG0 = 0 # macro +SDMA0_BASE__INST2_SEG1 = 0 # macro +SDMA0_BASE__INST2_SEG2 = 0 # macro +SDMA0_BASE__INST2_SEG3 = 0 # macro +SDMA0_BASE__INST2_SEG4 = 0 # macro +SDMA0_BASE__INST3_SEG0 = 0 # macro +SDMA0_BASE__INST3_SEG1 = 0 # macro +SDMA0_BASE__INST3_SEG2 = 0 # macro +SDMA0_BASE__INST3_SEG3 = 0 # macro +SDMA0_BASE__INST3_SEG4 = 0 # macro +SDMA0_BASE__INST4_SEG0 = 0 # macro +SDMA0_BASE__INST4_SEG1 = 0 # macro +SDMA0_BASE__INST4_SEG2 = 0 # macro +SDMA0_BASE__INST4_SEG3 = 0 # macro +SDMA0_BASE__INST4_SEG4 = 0 # macro +SDMA0_BASE__INST5_SEG0 = 0 # macro +SDMA0_BASE__INST5_SEG1 = 0 # macro +SDMA0_BASE__INST5_SEG2 = 0 # macro +SDMA0_BASE__INST5_SEG3 = 0 # macro +SDMA0_BASE__INST5_SEG4 = 0 # macro +SDMA0_BASE__INST6_SEG0 = 0 # macro +SDMA0_BASE__INST6_SEG1 = 0 # macro +SDMA0_BASE__INST6_SEG2 = 0 # macro +SDMA0_BASE__INST6_SEG3 = 0 # macro +SDMA0_BASE__INST6_SEG4 = 0 # macro +SDMA1_BASE__INST0_SEG0 = 0x00001260 # macro +SDMA1_BASE__INST0_SEG1 = 0x0000A000 # macro +SDMA1_BASE__INST0_SEG2 = 0x0001C000 # macro +SDMA1_BASE__INST0_SEG3 = 0x02402C00 # macro +SDMA1_BASE__INST0_SEG4 = 0 # macro +SDMA1_BASE__INST1_SEG0 = 0 # macro +SDMA1_BASE__INST1_SEG1 = 0 # macro +SDMA1_BASE__INST1_SEG2 = 0 # macro +SDMA1_BASE__INST1_SEG3 = 0 # macro +SDMA1_BASE__INST1_SEG4 = 0 # macro +SDMA1_BASE__INST2_SEG0 = 0 # macro +SDMA1_BASE__INST2_SEG1 = 0 # macro +SDMA1_BASE__INST2_SEG2 = 0 # macro +SDMA1_BASE__INST2_SEG3 = 0 # macro +SDMA1_BASE__INST2_SEG4 = 0 # macro +SDMA1_BASE__INST3_SEG0 = 0 # macro +SDMA1_BASE__INST3_SEG1 = 0 # macro +SDMA1_BASE__INST3_SEG2 = 0 # macro +SDMA1_BASE__INST3_SEG3 = 0 # macro +SDMA1_BASE__INST3_SEG4 = 0 # macro +SDMA1_BASE__INST4_SEG0 = 0 # macro +SDMA1_BASE__INST4_SEG1 = 0 # macro +SDMA1_BASE__INST4_SEG2 = 0 # macro +SDMA1_BASE__INST4_SEG3 = 0 # macro +SDMA1_BASE__INST4_SEG4 = 0 # macro +SDMA1_BASE__INST5_SEG0 = 0 # macro +SDMA1_BASE__INST5_SEG1 = 0 # macro +SDMA1_BASE__INST5_SEG2 = 0 # macro +SDMA1_BASE__INST5_SEG3 = 0 # macro +SDMA1_BASE__INST5_SEG4 = 0 # macro +SDMA1_BASE__INST6_SEG0 = 0 # macro +SDMA1_BASE__INST6_SEG1 = 0 # macro +SDMA1_BASE__INST6_SEG2 = 0 # macro +SDMA1_BASE__INST6_SEG3 = 0 # macro +SDMA1_BASE__INST6_SEG4 = 0 # macro +SMUIO_BASE__INST0_SEG0 = 0x00016800 # macro +SMUIO_BASE__INST0_SEG1 = 0x00016A00 # macro +SMUIO_BASE__INST0_SEG2 = 0x00440000 # macro +SMUIO_BASE__INST0_SEG3 = 0x02401000 # macro +SMUIO_BASE__INST0_SEG4 = 0 # macro +SMUIO_BASE__INST1_SEG0 = 0 # macro +SMUIO_BASE__INST1_SEG1 = 0 # macro +SMUIO_BASE__INST1_SEG2 = 0 # macro +SMUIO_BASE__INST1_SEG3 = 0 # macro +SMUIO_BASE__INST1_SEG4 = 0 # macro +SMUIO_BASE__INST2_SEG0 = 0 # macro +SMUIO_BASE__INST2_SEG1 = 0 # macro +SMUIO_BASE__INST2_SEG2 = 0 # macro +SMUIO_BASE__INST2_SEG3 = 0 # macro +SMUIO_BASE__INST2_SEG4 = 0 # macro +SMUIO_BASE__INST3_SEG0 = 0 # macro +SMUIO_BASE__INST3_SEG1 = 0 # macro +SMUIO_BASE__INST3_SEG2 = 0 # macro +SMUIO_BASE__INST3_SEG3 = 0 # macro +SMUIO_BASE__INST3_SEG4 = 0 # macro +SMUIO_BASE__INST4_SEG0 = 0 # macro +SMUIO_BASE__INST4_SEG1 = 0 # macro +SMUIO_BASE__INST4_SEG2 = 0 # macro +SMUIO_BASE__INST4_SEG3 = 0 # macro +SMUIO_BASE__INST4_SEG4 = 0 # macro +SMUIO_BASE__INST5_SEG0 = 0 # macro +SMUIO_BASE__INST5_SEG1 = 0 # macro +SMUIO_BASE__INST5_SEG2 = 0 # macro +SMUIO_BASE__INST5_SEG3 = 0 # macro +SMUIO_BASE__INST5_SEG4 = 0 # macro +SMUIO_BASE__INST6_SEG0 = 0 # macro +SMUIO_BASE__INST6_SEG1 = 0 # macro +SMUIO_BASE__INST6_SEG2 = 0 # macro +SMUIO_BASE__INST6_SEG3 = 0 # macro +SMUIO_BASE__INST6_SEG4 = 0 # macro +THM_BASE__INST0_SEG0 = 0x00016600 # macro +THM_BASE__INST0_SEG1 = 0x02400C00 # macro +THM_BASE__INST0_SEG2 = 0 # macro +THM_BASE__INST0_SEG3 = 0 # macro +THM_BASE__INST0_SEG4 = 0 # macro +THM_BASE__INST1_SEG0 = 0 # macro +THM_BASE__INST1_SEG1 = 0 # macro +THM_BASE__INST1_SEG2 = 0 # macro +THM_BASE__INST1_SEG3 = 0 # macro +THM_BASE__INST1_SEG4 = 0 # macro +THM_BASE__INST2_SEG0 = 0 # macro +THM_BASE__INST2_SEG1 = 0 # macro +THM_BASE__INST2_SEG2 = 0 # macro +THM_BASE__INST2_SEG3 = 0 # macro +THM_BASE__INST2_SEG4 = 0 # macro +THM_BASE__INST3_SEG0 = 0 # macro +THM_BASE__INST3_SEG1 = 0 # macro +THM_BASE__INST3_SEG2 = 0 # macro +THM_BASE__INST3_SEG3 = 0 # macro +THM_BASE__INST3_SEG4 = 0 # macro +THM_BASE__INST4_SEG0 = 0 # macro +THM_BASE__INST4_SEG1 = 0 # macro +THM_BASE__INST4_SEG2 = 0 # macro +THM_BASE__INST4_SEG3 = 0 # macro +THM_BASE__INST4_SEG4 = 0 # macro +THM_BASE__INST5_SEG0 = 0 # macro +THM_BASE__INST5_SEG1 = 0 # macro +THM_BASE__INST5_SEG2 = 0 # macro +THM_BASE__INST5_SEG3 = 0 # macro +THM_BASE__INST5_SEG4 = 0 # macro +THM_BASE__INST6_SEG0 = 0 # macro +THM_BASE__INST6_SEG1 = 0 # macro +THM_BASE__INST6_SEG2 = 0 # macro +THM_BASE__INST6_SEG3 = 0 # macro +THM_BASE__INST6_SEG4 = 0 # macro +UMC_BASE__INST0_SEG0 = 0x00014000 # macro +UMC_BASE__INST0_SEG1 = 0x02425800 # macro +UMC_BASE__INST0_SEG2 = 0 # macro +UMC_BASE__INST0_SEG3 = 0 # macro +UMC_BASE__INST0_SEG4 = 0 # macro +UMC_BASE__INST1_SEG0 = 0x00054000 # macro +UMC_BASE__INST1_SEG1 = 0x02425C00 # macro +UMC_BASE__INST1_SEG2 = 0 # macro +UMC_BASE__INST1_SEG3 = 0 # macro +UMC_BASE__INST1_SEG4 = 0 # macro +UMC_BASE__INST2_SEG0 = 0x00094000 # macro +UMC_BASE__INST2_SEG1 = 0x02426000 # macro +UMC_BASE__INST2_SEG2 = 0 # macro +UMC_BASE__INST2_SEG3 = 0 # macro +UMC_BASE__INST2_SEG4 = 0 # macro +UMC_BASE__INST3_SEG0 = 0x000D4000 # macro +UMC_BASE__INST3_SEG1 = 0x02426400 # macro +UMC_BASE__INST3_SEG2 = 0 # macro +UMC_BASE__INST3_SEG3 = 0 # macro +UMC_BASE__INST3_SEG4 = 0 # macro +UMC_BASE__INST4_SEG0 = 0x00114000 # macro +UMC_BASE__INST4_SEG1 = 0x02426800 # macro +UMC_BASE__INST4_SEG2 = 0 # macro +UMC_BASE__INST4_SEG3 = 0 # macro +UMC_BASE__INST4_SEG4 = 0 # macro +UMC_BASE__INST5_SEG0 = 0x00154000 # macro +UMC_BASE__INST5_SEG1 = 0x02426C00 # macro +UMC_BASE__INST5_SEG2 = 0 # macro +UMC_BASE__INST5_SEG3 = 0 # macro +UMC_BASE__INST5_SEG4 = 0 # macro +UMC_BASE__INST6_SEG0 = 0x00194000 # macro +UMC_BASE__INST6_SEG1 = 0x02427000 # macro +UMC_BASE__INST6_SEG2 = 0 # macro +UMC_BASE__INST6_SEG3 = 0 # macro +UMC_BASE__INST6_SEG4 = 0 # macro +USB0_BASE__INST0_SEG0 = 0x0242A800 # macro +USB0_BASE__INST0_SEG1 = 0x05B00000 # macro +USB0_BASE__INST0_SEG2 = 0 # macro +USB0_BASE__INST0_SEG3 = 0 # macro +USB0_BASE__INST0_SEG4 = 0 # macro +USB0_BASE__INST1_SEG0 = 0 # macro +USB0_BASE__INST1_SEG1 = 0 # macro +USB0_BASE__INST1_SEG2 = 0 # macro +USB0_BASE__INST1_SEG3 = 0 # macro +USB0_BASE__INST1_SEG4 = 0 # macro +USB0_BASE__INST2_SEG0 = 0 # macro +USB0_BASE__INST2_SEG1 = 0 # macro +USB0_BASE__INST2_SEG2 = 0 # macro +USB0_BASE__INST2_SEG3 = 0 # macro +USB0_BASE__INST2_SEG4 = 0 # macro +USB0_BASE__INST3_SEG0 = 0 # macro +USB0_BASE__INST3_SEG1 = 0 # macro +USB0_BASE__INST3_SEG2 = 0 # macro +USB0_BASE__INST3_SEG3 = 0 # macro +USB0_BASE__INST3_SEG4 = 0 # macro +USB0_BASE__INST4_SEG0 = 0 # macro +USB0_BASE__INST4_SEG1 = 0 # macro +USB0_BASE__INST4_SEG2 = 0 # macro +USB0_BASE__INST4_SEG3 = 0 # macro +USB0_BASE__INST4_SEG4 = 0 # macro +USB0_BASE__INST5_SEG0 = 0 # macro +USB0_BASE__INST5_SEG1 = 0 # macro +USB0_BASE__INST5_SEG2 = 0 # macro +USB0_BASE__INST5_SEG3 = 0 # macro +USB0_BASE__INST5_SEG4 = 0 # macro +USB0_BASE__INST6_SEG0 = 0 # macro +USB0_BASE__INST6_SEG1 = 0 # macro +USB0_BASE__INST6_SEG2 = 0 # macro +USB0_BASE__INST6_SEG3 = 0 # macro +USB0_BASE__INST6_SEG4 = 0 # macro +VCN_BASE__INST0_SEG0 = 0x00007800 # macro +VCN_BASE__INST0_SEG1 = 0x00007E00 # macro +VCN_BASE__INST0_SEG2 = 0x02403000 # macro +VCN_BASE__INST0_SEG3 = 0 # macro +VCN_BASE__INST0_SEG4 = 0 # macro +VCN_BASE__INST1_SEG0 = 0x00007B00 # macro +VCN_BASE__INST1_SEG1 = 0x00012000 # macro +VCN_BASE__INST1_SEG2 = 0x02445000 # macro +VCN_BASE__INST1_SEG3 = 0 # macro +VCN_BASE__INST1_SEG4 = 0 # macro +VCN_BASE__INST2_SEG0 = 0 # macro +VCN_BASE__INST2_SEG1 = 0 # macro +VCN_BASE__INST2_SEG2 = 0 # macro +VCN_BASE__INST2_SEG3 = 0 # macro +VCN_BASE__INST2_SEG4 = 0 # macro +VCN_BASE__INST3_SEG0 = 0 # macro +VCN_BASE__INST3_SEG1 = 0 # macro +VCN_BASE__INST3_SEG2 = 0 # macro +VCN_BASE__INST3_SEG3 = 0 # macro +VCN_BASE__INST3_SEG4 = 0 # macro +VCN_BASE__INST4_SEG0 = 0 # macro +VCN_BASE__INST4_SEG1 = 0 # macro +VCN_BASE__INST4_SEG2 = 0 # macro +VCN_BASE__INST4_SEG3 = 0 # macro +VCN_BASE__INST4_SEG4 = 0 # macro +VCN_BASE__INST5_SEG0 = 0 # macro +VCN_BASE__INST5_SEG1 = 0 # macro +VCN_BASE__INST5_SEG2 = 0 # macro +VCN_BASE__INST5_SEG3 = 0 # macro +VCN_BASE__INST5_SEG4 = 0 # macro +VCN_BASE__INST6_SEG0 = 0 # macro +VCN_BASE__INST6_SEG1 = 0 # macro +VCN_BASE__INST6_SEG2 = 0 # macro +VCN_BASE__INST6_SEG3 = 0 # macro +VCN_BASE__INST6_SEG4 = 0 # macro +class struct_IP_BASE_INSTANCE(Structure): + pass + +struct_IP_BASE_INSTANCE._pack_ = 1 # source:False +struct_IP_BASE_INSTANCE._fields_ = [ + ('segment', ctypes.c_uint32 * 5), +] + +class struct_IP_BASE(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('instance', struct_IP_BASE_INSTANCE * 7), + ] + +__maybe_unused = struct_IP_BASE # Variable struct_IP_BASE +ATHUB_BASE = struct_IP_BASE # Variable struct_IP_BASE +CLK_BASE = struct_IP_BASE # Variable struct_IP_BASE +DF_BASE = struct_IP_BASE # Variable struct_IP_BASE +DIO_BASE = struct_IP_BASE # Variable struct_IP_BASE +DCN_BASE = struct_IP_BASE # Variable struct_IP_BASE +DPCS_BASE = struct_IP_BASE # Variable struct_IP_BASE +FUSE_BASE = struct_IP_BASE # Variable struct_IP_BASE +GC_BASE = struct_IP_BASE # Variable struct_IP_BASE +HDA_BASE = struct_IP_BASE # Variable struct_IP_BASE +HDP_BASE = struct_IP_BASE # Variable struct_IP_BASE +MMHUB_BASE = struct_IP_BASE # Variable struct_IP_BASE +MP0_BASE = struct_IP_BASE # Variable struct_IP_BASE +MP1_BASE = struct_IP_BASE # Variable struct_IP_BASE +NBIO_BASE = struct_IP_BASE # Variable struct_IP_BASE +OSSSYS_BASE = struct_IP_BASE # Variable struct_IP_BASE +PCIE0_BASE = struct_IP_BASE # Variable struct_IP_BASE +SDMA0_BASE = struct_IP_BASE # Variable struct_IP_BASE +SDMA1_BASE = struct_IP_BASE # Variable struct_IP_BASE +SMUIO_BASE = struct_IP_BASE # Variable struct_IP_BASE +THM_BASE = struct_IP_BASE # Variable struct_IP_BASE +UMC_BASE = struct_IP_BASE # Variable struct_IP_BASE +USB0_BASE = struct_IP_BASE # Variable struct_IP_BASE +VCN_BASE = struct_IP_BASE # Variable struct_IP_BASE __all__ = \ ['ACCEPT_UNSOLICITED_RESPONSE_ENABLE', 'ACCEPT_UNSOLICITED_RESPONSE_NOT_ENABLE', 'ACP_TYPE_DVD_AUDIO', @@ -61034,11 +61880,29 @@ __all__ = \ 'ARGB16161616_10LSB', 'ARGB16161616_10MSB', 'ARGB16161616_12LSB', 'ARGB16161616_12MSB', 'ARGB16161616_FLOAT', 'ARGB16161616_SNORM', 'ARGB16161616_UNORM', 'ARGB2101010', 'ARGB4444', 'ARGB8888', - 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', 'AUDIO_LAYOUT_SELECT', - 'AUTOCAL_MODE_AUTOCENTER', 'AUTOCAL_MODE_AUTOREPLICATE', - 'AUTOCAL_MODE_AUTOSCALE', 'AUTOCAL_MODE_OFF', - 'AYCrCb16161616_10LSB', 'AYCrCb16161616_10MSB', - 'AYCrCb16161616_12LSB', 'AYCrCb16161616_12MSB', 'AYCrCb8888', + 'ATHUB_BASE', 'ATHUB_BASE__INST0_SEG0', 'ATHUB_BASE__INST0_SEG1', + 'ATHUB_BASE__INST0_SEG2', 'ATHUB_BASE__INST0_SEG3', + 'ATHUB_BASE__INST0_SEG4', 'ATHUB_BASE__INST1_SEG0', + 'ATHUB_BASE__INST1_SEG1', 'ATHUB_BASE__INST1_SEG2', + 'ATHUB_BASE__INST1_SEG3', 'ATHUB_BASE__INST1_SEG4', + 'ATHUB_BASE__INST2_SEG0', 'ATHUB_BASE__INST2_SEG1', + 'ATHUB_BASE__INST2_SEG2', 'ATHUB_BASE__INST2_SEG3', + 'ATHUB_BASE__INST2_SEG4', 'ATHUB_BASE__INST3_SEG0', + 'ATHUB_BASE__INST3_SEG1', 'ATHUB_BASE__INST3_SEG2', + 'ATHUB_BASE__INST3_SEG3', 'ATHUB_BASE__INST3_SEG4', + 'ATHUB_BASE__INST4_SEG0', 'ATHUB_BASE__INST4_SEG1', + 'ATHUB_BASE__INST4_SEG2', 'ATHUB_BASE__INST4_SEG3', + 'ATHUB_BASE__INST4_SEG4', 'ATHUB_BASE__INST5_SEG0', + 'ATHUB_BASE__INST5_SEG1', 'ATHUB_BASE__INST5_SEG2', + 'ATHUB_BASE__INST5_SEG3', 'ATHUB_BASE__INST5_SEG4', + 'ATHUB_BASE__INST6_SEG0', 'ATHUB_BASE__INST6_SEG1', + 'ATHUB_BASE__INST6_SEG2', 'ATHUB_BASE__INST6_SEG3', + 'ATHUB_BASE__INST6_SEG4', 'AUDIO_LAYOUT_0', 'AUDIO_LAYOUT_1', + 'AUDIO_LAYOUT_SELECT', 'AUTOCAL_MODE_AUTOCENTER', + 'AUTOCAL_MODE_AUTOREPLICATE', 'AUTOCAL_MODE_AUTOSCALE', + 'AUTOCAL_MODE_OFF', 'AYCrCb16161616_10LSB', + 'AYCrCb16161616_10MSB', 'AYCrCb16161616_12LSB', + 'AYCrCb16161616_12MSB', 'AYCrCb8888', 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AMPLIFIER_PARAMETER_OVERRIDE', 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES', 'AZALIA_F0_CODEC_CONVERTER_PARAMETER_AUDIO_WIDGET_CAPABILITIES_AUDIO_CHANNEL_CAPABILITIES_MONOPHONIC', @@ -61911,10 +62775,28 @@ __all__ = \ 'CHUNK_SIZE_1KB', 'CHUNK_SIZE_2KB', 'CHUNK_SIZE_32KB', 'CHUNK_SIZE_4KB', 'CHUNK_SIZE_64KB', 'CHUNK_SIZE_8KB', 'CLEAR_SMU_INTR', 'CLKGATE_BASE_MODE', 'CLKGATE_SM_MODE', - 'CLOCK_BRANCH_SOFT_RESET', 'CLOCK_BRANCH_SOFT_RESET_FORCE', - 'CLOCK_BRANCH_SOFT_RESET_NOOP', 'CLOCK_GATING_DISABLE', - 'CLOCK_GATING_DISABLED', 'CLOCK_GATING_DISABLED_IN_DCO', - 'CLOCK_GATING_DISABLE_ENUM', 'CLOCK_GATING_DISABLE_ENUM_DISABLED', + 'CLK_BASE', 'CLK_BASE__INST0_SEG0', 'CLK_BASE__INST0_SEG1', + 'CLK_BASE__INST0_SEG2', 'CLK_BASE__INST0_SEG3', + 'CLK_BASE__INST0_SEG4', 'CLK_BASE__INST1_SEG0', + 'CLK_BASE__INST1_SEG1', 'CLK_BASE__INST1_SEG2', + 'CLK_BASE__INST1_SEG3', 'CLK_BASE__INST1_SEG4', + 'CLK_BASE__INST2_SEG0', 'CLK_BASE__INST2_SEG1', + 'CLK_BASE__INST2_SEG2', 'CLK_BASE__INST2_SEG3', + 'CLK_BASE__INST2_SEG4', 'CLK_BASE__INST3_SEG0', + 'CLK_BASE__INST3_SEG1', 'CLK_BASE__INST3_SEG2', + 'CLK_BASE__INST3_SEG3', 'CLK_BASE__INST3_SEG4', + 'CLK_BASE__INST4_SEG0', 'CLK_BASE__INST4_SEG1', + 'CLK_BASE__INST4_SEG2', 'CLK_BASE__INST4_SEG3', + 'CLK_BASE__INST4_SEG4', 'CLK_BASE__INST5_SEG0', + 'CLK_BASE__INST5_SEG1', 'CLK_BASE__INST5_SEG2', + 'CLK_BASE__INST5_SEG3', 'CLK_BASE__INST5_SEG4', + 'CLK_BASE__INST6_SEG0', 'CLK_BASE__INST6_SEG1', + 'CLK_BASE__INST6_SEG2', 'CLK_BASE__INST6_SEG3', + 'CLK_BASE__INST6_SEG4', 'CLOCK_BRANCH_SOFT_RESET', + 'CLOCK_BRANCH_SOFT_RESET_FORCE', 'CLOCK_BRANCH_SOFT_RESET_NOOP', + 'CLOCK_GATING_DISABLE', 'CLOCK_GATING_DISABLED', + 'CLOCK_GATING_DISABLED_IN_DCO', 'CLOCK_GATING_DISABLE_ENUM', + 'CLOCK_GATING_DISABLE_ENUM_DISABLED', 'CLOCK_GATING_DISABLE_ENUM_ENABLED', 'CLOCK_GATING_EN', 'CLOCK_GATING_ENABLE', 'CLOCK_GATING_ENABLED', 'CLOCK_GATING_ENABLED_IN_DCO', 'CMASK_CLR00_F0', 'CMASK_CLR00_F1', @@ -62709,7 +63591,25 @@ __all__ = \ 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW', 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_DEBOUNCED', 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_ALLOW_TOGGLE_FILTERED', - 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', 'DC_DMCUB_INT_TYPE', + 'DCIO_UNIPHY_LINK_ENABLE_HPD_MASK_DISALLOW', 'DCN_BASE', + 'DCN_BASE__INST0_SEG0', 'DCN_BASE__INST0_SEG1', + 'DCN_BASE__INST0_SEG2', 'DCN_BASE__INST0_SEG3', + 'DCN_BASE__INST0_SEG4', 'DCN_BASE__INST1_SEG0', + 'DCN_BASE__INST1_SEG1', 'DCN_BASE__INST1_SEG2', + 'DCN_BASE__INST1_SEG3', 'DCN_BASE__INST1_SEG4', + 'DCN_BASE__INST2_SEG0', 'DCN_BASE__INST2_SEG1', + 'DCN_BASE__INST2_SEG2', 'DCN_BASE__INST2_SEG3', + 'DCN_BASE__INST2_SEG4', 'DCN_BASE__INST3_SEG0', + 'DCN_BASE__INST3_SEG1', 'DCN_BASE__INST3_SEG2', + 'DCN_BASE__INST3_SEG3', 'DCN_BASE__INST3_SEG4', + 'DCN_BASE__INST4_SEG0', 'DCN_BASE__INST4_SEG1', + 'DCN_BASE__INST4_SEG2', 'DCN_BASE__INST4_SEG3', + 'DCN_BASE__INST4_SEG4', 'DCN_BASE__INST5_SEG0', + 'DCN_BASE__INST5_SEG1', 'DCN_BASE__INST5_SEG2', + 'DCN_BASE__INST5_SEG3', 'DCN_BASE__INST5_SEG4', + 'DCN_BASE__INST6_SEG0', 'DCN_BASE__INST6_SEG1', + 'DCN_BASE__INST6_SEG2', 'DCN_BASE__INST6_SEG3', + 'DCN_BASE__INST6_SEG4', 'DC_DMCUB_INT_TYPE', 'DC_DMCUB_TIMER_WINDOW', 'DC_MEM_GLOBAL_PWR_REQ_DIS', 'DC_MEM_GLOBAL_PWR_REQ_DISABLE', 'DC_MEM_GLOBAL_PWR_REQ_ENABLE', 'DC_SMU_INTERRUPT_ENABLE', 'DDID_VMID_CNTL', 'DDID_VMID_PIPE', @@ -62742,14 +63642,31 @@ __all__ = \ 'DFQ_NUM_ENTRIES_5', 'DFQ_NUM_ENTRIES_6', 'DFQ_NUM_ENTRIES_7', 'DFQ_NUM_ENTRIES_8', 'DFQ_SIZE', 'DFQ_SIZE_0', 'DFQ_SIZE_1', 'DFQ_SIZE_2', 'DFQ_SIZE_3', 'DFQ_SIZE_4', 'DFQ_SIZE_5', - 'DFQ_SIZE_6', 'DFQ_SIZE_7', 'DFSMFlushEvents', 'DIFFERENT_RGB', - 'DIG_10BIT_TEST_PATTERN', 'DIG_ALL_PIXEL', - 'DIG_ALTERNATING_TEST_PATTERN', 'DIG_BE_CNTL_HPD1', - 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', 'DIG_BE_CNTL_HPD4', - 'DIG_BE_CNTL_HPD5', 'DIG_BE_CNTL_HPD_SELECT', 'DIG_BE_CNTL_MODE', - 'DIG_BE_CNTL_NO_HPD', 'DIG_BE_DP_MST_MODE', 'DIG_BE_DP_SST_MODE', - 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', 'DIG_BE_RESERVED3', - 'DIG_BE_RESERVED4', 'DIG_BE_TMDS_DVI_MODE', + 'DFQ_SIZE_6', 'DFQ_SIZE_7', 'DFSMFlushEvents', 'DF_BASE', + 'DF_BASE__INST0_SEG0', 'DF_BASE__INST0_SEG1', + 'DF_BASE__INST0_SEG2', 'DF_BASE__INST0_SEG3', + 'DF_BASE__INST0_SEG4', 'DF_BASE__INST1_SEG0', + 'DF_BASE__INST1_SEG1', 'DF_BASE__INST1_SEG2', + 'DF_BASE__INST1_SEG3', 'DF_BASE__INST1_SEG4', + 'DF_BASE__INST2_SEG0', 'DF_BASE__INST2_SEG1', + 'DF_BASE__INST2_SEG2', 'DF_BASE__INST2_SEG3', + 'DF_BASE__INST2_SEG4', 'DF_BASE__INST3_SEG0', + 'DF_BASE__INST3_SEG1', 'DF_BASE__INST3_SEG2', + 'DF_BASE__INST3_SEG3', 'DF_BASE__INST3_SEG4', + 'DF_BASE__INST4_SEG0', 'DF_BASE__INST4_SEG1', + 'DF_BASE__INST4_SEG2', 'DF_BASE__INST4_SEG3', + 'DF_BASE__INST4_SEG4', 'DF_BASE__INST5_SEG0', + 'DF_BASE__INST5_SEG1', 'DF_BASE__INST5_SEG2', + 'DF_BASE__INST5_SEG3', 'DF_BASE__INST5_SEG4', + 'DF_BASE__INST6_SEG0', 'DF_BASE__INST6_SEG1', + 'DF_BASE__INST6_SEG2', 'DF_BASE__INST6_SEG3', + 'DF_BASE__INST6_SEG4', 'DIFFERENT_RGB', 'DIG_10BIT_TEST_PATTERN', + 'DIG_ALL_PIXEL', 'DIG_ALTERNATING_TEST_PATTERN', + 'DIG_BE_CNTL_HPD1', 'DIG_BE_CNTL_HPD2', 'DIG_BE_CNTL_HPD3', + 'DIG_BE_CNTL_HPD4', 'DIG_BE_CNTL_HPD5', 'DIG_BE_CNTL_HPD_SELECT', + 'DIG_BE_CNTL_MODE', 'DIG_BE_CNTL_NO_HPD', 'DIG_BE_DP_MST_MODE', + 'DIG_BE_DP_SST_MODE', 'DIG_BE_RESERVED1', 'DIG_BE_RESERVED2', + 'DIG_BE_RESERVED3', 'DIG_BE_RESERVED4', 'DIG_BE_TMDS_DVI_MODE', 'DIG_BE_TMDS_HDMI_MODE', 'DIG_DIGITAL_BYPASS_ENABLE', 'DIG_DIGITAL_BYPASS_OFF', 'DIG_DIGITAL_BYPASS_ON', 'DIG_DIGITAL_BYPASS_SEL', 'DIG_DIGITAL_BYPASS_SEL_10BPP_LSB', @@ -62810,24 +63727,41 @@ __all__ = \ 'DIOMEM_FORCE_SHUT_DOWN_REQUEST', 'DIOMEM_NO_FORCE_REQ', 'DIOMEM_NO_FORCE_REQUEST', 'DIOMEM_PWR_DIS_CTRL', 'DIOMEM_PWR_FORCE_CTRL', 'DIOMEM_PWR_FORCE_CTRL2', - 'DIOMEM_PWR_SEL_CTRL', 'DIOMEM_PWR_SEL_CTRL2', - 'DIO_DBG_BLOCK_SEL', 'DIO_DBG_BLOCK_SEL_AUX0', - 'DIO_DBG_BLOCK_SEL_AUX1', 'DIO_DBG_BLOCK_SEL_AUX2', - 'DIO_DBG_BLOCK_SEL_AUX3', 'DIO_DBG_BLOCK_SEL_AUX4', - 'DIO_DBG_BLOCK_SEL_DIGA', 'DIO_DBG_BLOCK_SEL_DIGB', - 'DIO_DBG_BLOCK_SEL_DIGC', 'DIO_DBG_BLOCK_SEL_DIGD', - 'DIO_DBG_BLOCK_SEL_DIGE', 'DIO_DBG_BLOCK_SEL_DIGFE_A', - 'DIO_DBG_BLOCK_SEL_DIGFE_B', 'DIO_DBG_BLOCK_SEL_DIGFE_C', - 'DIO_DBG_BLOCK_SEL_DIGFE_D', 'DIO_DBG_BLOCK_SEL_DIGFE_E', - 'DIO_DBG_BLOCK_SEL_DIO', 'DIO_DBG_BLOCK_SEL_DPA', - 'DIO_DBG_BLOCK_SEL_DPB', 'DIO_DBG_BLOCK_SEL_DPC', - 'DIO_DBG_BLOCK_SEL_DPD', 'DIO_DBG_BLOCK_SEL_DPE', - 'DIO_DBG_BLOCK_SEL_DPFE_A', 'DIO_DBG_BLOCK_SEL_DPFE_B', - 'DIO_DBG_BLOCK_SEL_DPFE_C', 'DIO_DBG_BLOCK_SEL_DPFE_D', - 'DIO_DBG_BLOCK_SEL_DPFE_E', 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', - 'DIO_DBG_BLOCK_SEL_RESERVED', 'DIO_FIFO_ERROR', - 'DIO_FIFO_ERROR_00', 'DIO_FIFO_ERROR_01', 'DIO_FIFO_ERROR_10', - 'DIO_FIFO_ERROR_11', + 'DIOMEM_PWR_SEL_CTRL', 'DIOMEM_PWR_SEL_CTRL2', 'DIO_BASE', + 'DIO_BASE__INST0_SEG0', 'DIO_BASE__INST0_SEG1', + 'DIO_BASE__INST0_SEG2', 'DIO_BASE__INST0_SEG3', + 'DIO_BASE__INST0_SEG4', 'DIO_BASE__INST1_SEG0', + 'DIO_BASE__INST1_SEG1', 'DIO_BASE__INST1_SEG2', + 'DIO_BASE__INST1_SEG3', 'DIO_BASE__INST1_SEG4', + 'DIO_BASE__INST2_SEG0', 'DIO_BASE__INST2_SEG1', + 'DIO_BASE__INST2_SEG2', 'DIO_BASE__INST2_SEG3', + 'DIO_BASE__INST2_SEG4', 'DIO_BASE__INST3_SEG0', + 'DIO_BASE__INST3_SEG1', 'DIO_BASE__INST3_SEG2', + 'DIO_BASE__INST3_SEG3', 'DIO_BASE__INST3_SEG4', + 'DIO_BASE__INST4_SEG0', 'DIO_BASE__INST4_SEG1', + 'DIO_BASE__INST4_SEG2', 'DIO_BASE__INST4_SEG3', + 'DIO_BASE__INST4_SEG4', 'DIO_BASE__INST5_SEG0', + 'DIO_BASE__INST5_SEG1', 'DIO_BASE__INST5_SEG2', + 'DIO_BASE__INST5_SEG3', 'DIO_BASE__INST5_SEG4', + 'DIO_BASE__INST6_SEG0', 'DIO_BASE__INST6_SEG1', + 'DIO_BASE__INST6_SEG2', 'DIO_BASE__INST6_SEG3', + 'DIO_BASE__INST6_SEG4', 'DIO_DBG_BLOCK_SEL', + 'DIO_DBG_BLOCK_SEL_AUX0', 'DIO_DBG_BLOCK_SEL_AUX1', + 'DIO_DBG_BLOCK_SEL_AUX2', 'DIO_DBG_BLOCK_SEL_AUX3', + 'DIO_DBG_BLOCK_SEL_AUX4', 'DIO_DBG_BLOCK_SEL_DIGA', + 'DIO_DBG_BLOCK_SEL_DIGB', 'DIO_DBG_BLOCK_SEL_DIGC', + 'DIO_DBG_BLOCK_SEL_DIGD', 'DIO_DBG_BLOCK_SEL_DIGE', + 'DIO_DBG_BLOCK_SEL_DIGFE_A', 'DIO_DBG_BLOCK_SEL_DIGFE_B', + 'DIO_DBG_BLOCK_SEL_DIGFE_C', 'DIO_DBG_BLOCK_SEL_DIGFE_D', + 'DIO_DBG_BLOCK_SEL_DIGFE_E', 'DIO_DBG_BLOCK_SEL_DIO', + 'DIO_DBG_BLOCK_SEL_DPA', 'DIO_DBG_BLOCK_SEL_DPB', + 'DIO_DBG_BLOCK_SEL_DPC', 'DIO_DBG_BLOCK_SEL_DPD', + 'DIO_DBG_BLOCK_SEL_DPE', 'DIO_DBG_BLOCK_SEL_DPFE_A', + 'DIO_DBG_BLOCK_SEL_DPFE_B', 'DIO_DBG_BLOCK_SEL_DPFE_C', + 'DIO_DBG_BLOCK_SEL_DPFE_D', 'DIO_DBG_BLOCK_SEL_DPFE_E', + 'DIO_DBG_BLOCK_SEL_PERFMON_DIO', 'DIO_DBG_BLOCK_SEL_RESERVED', + 'DIO_FIFO_ERROR', 'DIO_FIFO_ERROR_00', 'DIO_FIFO_ERROR_01', + 'DIO_FIFO_ERROR_10', 'DIO_FIFO_ERROR_11', 'DIO_HDMI_RXSTATUS_TIMER_CONTROL_DIO_HDMI_RXSTATUS_TIMER_TYPE', 'DIO_HDMI_RXSTATUS_TIMER_TYPE_LEVEL', 'DIO_HDMI_RXSTATUS_TIMER_TYPE_PULSE', @@ -63009,7 +63943,25 @@ __all__ = \ 'DOUT_I2C_READ_REQUEST_INTERRUPT_TYPE__PULSE', 'DOUT_I2C_TRANSACTION_STOP_ALL_TRANS', 'DOUT_I2C_TRANSACTION_STOP_CURRENT_TRANS', - 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DPHY_8B10B_CUR_DISP', + 'DOUT_I2C_TRANSACTION_STOP_ON_NACK', 'DPCS_BASE', + 'DPCS_BASE__INST0_SEG0', 'DPCS_BASE__INST0_SEG1', + 'DPCS_BASE__INST0_SEG2', 'DPCS_BASE__INST0_SEG3', + 'DPCS_BASE__INST0_SEG4', 'DPCS_BASE__INST1_SEG0', + 'DPCS_BASE__INST1_SEG1', 'DPCS_BASE__INST1_SEG2', + 'DPCS_BASE__INST1_SEG3', 'DPCS_BASE__INST1_SEG4', + 'DPCS_BASE__INST2_SEG0', 'DPCS_BASE__INST2_SEG1', + 'DPCS_BASE__INST2_SEG2', 'DPCS_BASE__INST2_SEG3', + 'DPCS_BASE__INST2_SEG4', 'DPCS_BASE__INST3_SEG0', + 'DPCS_BASE__INST3_SEG1', 'DPCS_BASE__INST3_SEG2', + 'DPCS_BASE__INST3_SEG3', 'DPCS_BASE__INST3_SEG4', + 'DPCS_BASE__INST4_SEG0', 'DPCS_BASE__INST4_SEG1', + 'DPCS_BASE__INST4_SEG2', 'DPCS_BASE__INST4_SEG3', + 'DPCS_BASE__INST4_SEG4', 'DPCS_BASE__INST5_SEG0', + 'DPCS_BASE__INST5_SEG1', 'DPCS_BASE__INST5_SEG2', + 'DPCS_BASE__INST5_SEG3', 'DPCS_BASE__INST5_SEG4', + 'DPCS_BASE__INST6_SEG0', 'DPCS_BASE__INST6_SEG1', + 'DPCS_BASE__INST6_SEG2', 'DPCS_BASE__INST6_SEG3', + 'DPCS_BASE__INST6_SEG4', 'DPHY_8B10B_CUR_DISP', 'DPHY_8B10B_CUR_DISP_ONE', 'DPHY_8B10B_CUR_DISP_ZERO', 'DPHY_8B10B_NOT_RESET', 'DPHY_8B10B_OUTPUT', 'DPHY_8B10B_RESET', 'DPHY_8B10B_RESETET', @@ -63729,8 +64681,26 @@ __all__ = \ 'FORMAT_CROSSBAR_B', 'FORMAT_CROSSBAR_G', 'FORMAT_CROSSBAR_R', 'FRAG_ALWAYS', 'FRAG_EQUAL', 'FRAG_GEQUAL', 'FRAG_GREATER', 'FRAG_LEQUAL', 'FRAG_LESS', 'FRAG_NEVER', 'FRAG_NOTEQUAL', - 'FRAME_TMZ', 'ForceControl', 'GAMUT_COEF', 'GAMUT_COEF_B', - 'GATCL1RequestType', 'GATCL1_TYPE_BYPASS', 'GATCL1_TYPE_NORMAL', + 'FRAME_TMZ', 'FUSE_BASE', 'FUSE_BASE__INST0_SEG0', + 'FUSE_BASE__INST0_SEG1', 'FUSE_BASE__INST0_SEG2', + 'FUSE_BASE__INST0_SEG3', 'FUSE_BASE__INST0_SEG4', + 'FUSE_BASE__INST1_SEG0', 'FUSE_BASE__INST1_SEG1', + 'FUSE_BASE__INST1_SEG2', 'FUSE_BASE__INST1_SEG3', + 'FUSE_BASE__INST1_SEG4', 'FUSE_BASE__INST2_SEG0', + 'FUSE_BASE__INST2_SEG1', 'FUSE_BASE__INST2_SEG2', + 'FUSE_BASE__INST2_SEG3', 'FUSE_BASE__INST2_SEG4', + 'FUSE_BASE__INST3_SEG0', 'FUSE_BASE__INST3_SEG1', + 'FUSE_BASE__INST3_SEG2', 'FUSE_BASE__INST3_SEG3', + 'FUSE_BASE__INST3_SEG4', 'FUSE_BASE__INST4_SEG0', + 'FUSE_BASE__INST4_SEG1', 'FUSE_BASE__INST4_SEG2', + 'FUSE_BASE__INST4_SEG3', 'FUSE_BASE__INST4_SEG4', + 'FUSE_BASE__INST5_SEG0', 'FUSE_BASE__INST5_SEG1', + 'FUSE_BASE__INST5_SEG2', 'FUSE_BASE__INST5_SEG3', + 'FUSE_BASE__INST5_SEG4', 'FUSE_BASE__INST6_SEG0', + 'FUSE_BASE__INST6_SEG1', 'FUSE_BASE__INST6_SEG2', + 'FUSE_BASE__INST6_SEG3', 'FUSE_BASE__INST6_SEG4', 'ForceControl', + 'GAMUT_COEF', 'GAMUT_COEF_B', 'GATCL1RequestType', + 'GATCL1_TYPE_BYPASS', 'GATCL1_TYPE_NORMAL', 'GATCL1_TYPE_SHOOTDOWN', 'GB_EDC_DED_MODE', 'GB_EDC_DED_MODE_HALT', 'GB_EDC_DED_MODE_INT_HALT', 'GB_EDC_DED_MODE_LOG', 'GB_TILING_CONFIG_MACROTABLE_SIZE', @@ -63846,12 +64816,29 @@ __all__ = \ 'GCR_PERF_SEL_UTCL2_INFLIGHT_REQ', 'GCR_PERF_SEL_UTCL2_OUT_OF_CREDIT_EVENT', 'GCR_PERF_SEL_UTCL2_REQ', 'GCR_PERF_SEL_UTCL2_RET', - 'GCR_PERF_SEL_VIRT_REQ', 'GDS_PERFCOUNT_SELECT', - 'GDS_PERF_SEL_GWS_BYPASS', 'GDS_PERF_SEL_GWS_RELEASED', - 'GDS_PERF_SEL_SE0_2COMP_REQ', 'GDS_PERF_SEL_SE0_GDS_ATOM_OP', - 'GDS_PERF_SEL_SE0_GDS_BYTE_OP', 'GDS_PERF_SEL_SE0_GDS_CMPXCH_OP', - 'GDS_PERF_SEL_SE0_GDS_RD_OP', 'GDS_PERF_SEL_SE0_GDS_REL_OP', - 'GDS_PERF_SEL_SE0_GDS_SHORT_OP', + 'GCR_PERF_SEL_VIRT_REQ', 'GC_BASE', 'GC_BASE__INST0_SEG0', + 'GC_BASE__INST0_SEG1', 'GC_BASE__INST0_SEG2', + 'GC_BASE__INST0_SEG3', 'GC_BASE__INST0_SEG4', + 'GC_BASE__INST1_SEG0', 'GC_BASE__INST1_SEG1', + 'GC_BASE__INST1_SEG2', 'GC_BASE__INST1_SEG3', + 'GC_BASE__INST1_SEG4', 'GC_BASE__INST2_SEG0', + 'GC_BASE__INST2_SEG1', 'GC_BASE__INST2_SEG2', + 'GC_BASE__INST2_SEG3', 'GC_BASE__INST2_SEG4', + 'GC_BASE__INST3_SEG0', 'GC_BASE__INST3_SEG1', + 'GC_BASE__INST3_SEG2', 'GC_BASE__INST3_SEG3', + 'GC_BASE__INST3_SEG4', 'GC_BASE__INST4_SEG0', + 'GC_BASE__INST4_SEG1', 'GC_BASE__INST4_SEG2', + 'GC_BASE__INST4_SEG3', 'GC_BASE__INST4_SEG4', + 'GC_BASE__INST5_SEG0', 'GC_BASE__INST5_SEG1', + 'GC_BASE__INST5_SEG2', 'GC_BASE__INST5_SEG3', + 'GC_BASE__INST5_SEG4', 'GC_BASE__INST6_SEG0', + 'GC_BASE__INST6_SEG1', 'GC_BASE__INST6_SEG2', + 'GC_BASE__INST6_SEG3', 'GC_BASE__INST6_SEG4', + 'GDS_PERFCOUNT_SELECT', 'GDS_PERF_SEL_GWS_BYPASS', + 'GDS_PERF_SEL_GWS_RELEASED', 'GDS_PERF_SEL_SE0_2COMP_REQ', + 'GDS_PERF_SEL_SE0_GDS_ATOM_OP', 'GDS_PERF_SEL_SE0_GDS_BYTE_OP', + 'GDS_PERF_SEL_SE0_GDS_CMPXCH_OP', 'GDS_PERF_SEL_SE0_GDS_RD_OP', + 'GDS_PERF_SEL_SE0_GDS_REL_OP', 'GDS_PERF_SEL_SE0_GDS_SHORT_OP', 'GDS_PERF_SEL_SE0_GDS_STALL_BY_ORD', 'GDS_PERF_SEL_SE0_GDS_WR_OP', 'GDS_PERF_SEL_SE0_NORET', 'GDS_PERF_SEL_SE0_ORD_CNT', 'GDS_PERF_SEL_SE0_ORD_WAVE_VALID', 'GDS_PERF_SEL_SE0_RET', @@ -64442,18 +65429,35 @@ __all__ = \ 'GRBM_SE7_PERF_SEL_USER_DEFINED', 'GRBM_SE7_PERF_SEL_UTCL1_BUSY', 'GREEN_LUT', 'GSTHREADID_SIZE', 'GS_OFF', 'GS_SCENARIO_A', 'GS_SCENARIO_B', 'GS_SCENARIO_C', 'GS_SCENARIO_G', 'GS_STAGE_OFF', - 'GS_STAGE_ON', 'HDMICHARCLK_SRC_SEL', - 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', 'HDMICHARCLK_SRC_SEL_UNIPHYA', - 'HDMICHARCLK_SRC_SEL_UNIPHYB', 'HDMICHARCLK_SRC_SEL_UNIPHYC', - 'HDMICHARCLK_SRC_SEL_UNIPHYD', 'HDMICHARCLK_SRC_SEL_UNIPHYE', - 'HDMISTREAMCLK_DTO_FORCE_DIS', 'HDMISTREAMCLK_SRC_SEL', - 'HDMI_ACP_NOT_SEND', 'HDMI_ACP_PKT_SEND', 'HDMI_ACP_SEND', - 'HDMI_ACR_0_MULTIPLE_RESERVED', 'HDMI_ACR_1_MULTIPLE', - 'HDMI_ACR_2_MULTIPLE', 'HDMI_ACR_3_MULTIPLE_RESERVED', - 'HDMI_ACR_4_MULTIPLE', 'HDMI_ACR_5_MULTIPLE_RESERVED', - 'HDMI_ACR_6_MULTIPLE_RESERVED', 'HDMI_ACR_7_MULTIPLE_RESERVED', - 'HDMI_ACR_AUDIO_PRIORITY', 'HDMI_ACR_CONT', - 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', + 'GS_STAGE_ON', 'HDA_BASE', 'HDA_BASE__INST0_SEG0', + 'HDA_BASE__INST0_SEG1', 'HDA_BASE__INST0_SEG2', + 'HDA_BASE__INST0_SEG3', 'HDA_BASE__INST0_SEG4', + 'HDA_BASE__INST1_SEG0', 'HDA_BASE__INST1_SEG1', + 'HDA_BASE__INST1_SEG2', 'HDA_BASE__INST1_SEG3', + 'HDA_BASE__INST1_SEG4', 'HDA_BASE__INST2_SEG0', + 'HDA_BASE__INST2_SEG1', 'HDA_BASE__INST2_SEG2', + 'HDA_BASE__INST2_SEG3', 'HDA_BASE__INST2_SEG4', + 'HDA_BASE__INST3_SEG0', 'HDA_BASE__INST3_SEG1', + 'HDA_BASE__INST3_SEG2', 'HDA_BASE__INST3_SEG3', + 'HDA_BASE__INST3_SEG4', 'HDA_BASE__INST4_SEG0', + 'HDA_BASE__INST4_SEG1', 'HDA_BASE__INST4_SEG2', + 'HDA_BASE__INST4_SEG3', 'HDA_BASE__INST4_SEG4', + 'HDA_BASE__INST5_SEG0', 'HDA_BASE__INST5_SEG1', + 'HDA_BASE__INST5_SEG2', 'HDA_BASE__INST5_SEG3', + 'HDA_BASE__INST5_SEG4', 'HDA_BASE__INST6_SEG0', + 'HDA_BASE__INST6_SEG1', 'HDA_BASE__INST6_SEG2', + 'HDA_BASE__INST6_SEG3', 'HDA_BASE__INST6_SEG4', + 'HDMICHARCLK_SRC_SEL', 'HDMICHARCLK_SRC_SEL_SRC_RESERVED', + 'HDMICHARCLK_SRC_SEL_UNIPHYA', 'HDMICHARCLK_SRC_SEL_UNIPHYB', + 'HDMICHARCLK_SRC_SEL_UNIPHYC', 'HDMICHARCLK_SRC_SEL_UNIPHYD', + 'HDMICHARCLK_SRC_SEL_UNIPHYE', 'HDMISTREAMCLK_DTO_FORCE_DIS', + 'HDMISTREAMCLK_SRC_SEL', 'HDMI_ACP_NOT_SEND', 'HDMI_ACP_PKT_SEND', + 'HDMI_ACP_SEND', 'HDMI_ACR_0_MULTIPLE_RESERVED', + 'HDMI_ACR_1_MULTIPLE', 'HDMI_ACR_2_MULTIPLE', + 'HDMI_ACR_3_MULTIPLE_RESERVED', 'HDMI_ACR_4_MULTIPLE', + 'HDMI_ACR_5_MULTIPLE_RESERVED', 'HDMI_ACR_6_MULTIPLE_RESERVED', + 'HDMI_ACR_7_MULTIPLE_RESERVED', 'HDMI_ACR_AUDIO_PRIORITY', + 'HDMI_ACR_CONT', 'HDMI_ACR_CONT_DISABLE', 'HDMI_ACR_CONT_ENABLE', 'HDMI_ACR_NOT_SEND', 'HDMI_ACR_N_MULTIPLE', 'HDMI_ACR_PKT_HIGH_PRIORITY_THAN_AUDIO_SAMPLE', 'HDMI_ACR_PKT_SEND', 'HDMI_ACR_SELECT', 'HDMI_ACR_SELECT_32K', @@ -64534,9 +65538,27 @@ __all__ = \ 'HDMI_TB_ENC_ISRC_SEND', 'HDMI_TB_ENC_METADATA_ENABLE', 'HDMI_TB_ENC_PACKET_LINE_REFERENCE', 'HDMI_TB_ENC_PIXEL_ENCODING', 'HDMI_TB_ENC_RESET', 'HDMI_TB_ENC_SYNC_PHASE', - 'HDMI_TMDS_OR_DP_8B10B', 'HDP_ENDIAN_8IN16', 'HDP_ENDIAN_8IN32', - 'HDP_ENDIAN_8IN64', 'HDP_ENDIAN_NONE', 'HEADER_AGENT_DISPATCH', - 'HEADER_BARRIER', 'HPD_INT_CONTROL_ACK', 'HPD_INT_CONTROL_ACK_0', + 'HDMI_TMDS_OR_DP_8B10B', 'HDP_BASE', 'HDP_BASE__INST0_SEG0', + 'HDP_BASE__INST0_SEG1', 'HDP_BASE__INST0_SEG2', + 'HDP_BASE__INST0_SEG3', 'HDP_BASE__INST0_SEG4', + 'HDP_BASE__INST1_SEG0', 'HDP_BASE__INST1_SEG1', + 'HDP_BASE__INST1_SEG2', 'HDP_BASE__INST1_SEG3', + 'HDP_BASE__INST1_SEG4', 'HDP_BASE__INST2_SEG0', + 'HDP_BASE__INST2_SEG1', 'HDP_BASE__INST2_SEG2', + 'HDP_BASE__INST2_SEG3', 'HDP_BASE__INST2_SEG4', + 'HDP_BASE__INST3_SEG0', 'HDP_BASE__INST3_SEG1', + 'HDP_BASE__INST3_SEG2', 'HDP_BASE__INST3_SEG3', + 'HDP_BASE__INST3_SEG4', 'HDP_BASE__INST4_SEG0', + 'HDP_BASE__INST4_SEG1', 'HDP_BASE__INST4_SEG2', + 'HDP_BASE__INST4_SEG3', 'HDP_BASE__INST4_SEG4', + 'HDP_BASE__INST5_SEG0', 'HDP_BASE__INST5_SEG1', + 'HDP_BASE__INST5_SEG2', 'HDP_BASE__INST5_SEG3', + 'HDP_BASE__INST5_SEG4', 'HDP_BASE__INST6_SEG0', + 'HDP_BASE__INST6_SEG1', 'HDP_BASE__INST6_SEG2', + 'HDP_BASE__INST6_SEG3', 'HDP_BASE__INST6_SEG4', + 'HDP_ENDIAN_8IN16', 'HDP_ENDIAN_8IN32', 'HDP_ENDIAN_8IN64', + 'HDP_ENDIAN_NONE', 'HEADER_AGENT_DISPATCH', 'HEADER_BARRIER', + 'HPD_INT_CONTROL_ACK', 'HPD_INT_CONTROL_ACK_0', 'HPD_INT_CONTROL_ACK_1', 'HPD_INT_CONTROL_GEN_INT_ON_CON', 'HPD_INT_CONTROL_GEN_INT_ON_DISCON', 'HPD_INT_CONTROL_POLARITY', 'HPD_INT_CONTROL_RX_INT_ACK', 'HPD_INT_CONTROL_RX_INT_ACK_0', @@ -64979,9 +66001,10 @@ __all__ = \ 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_BOTTOM', 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_RESERVED', 'MASTER_UPDATE_MODE_MASTER_UPDATE_INTERLACED_MODE_TOP', - 'MEM_ARB_MODE_AGE', 'MEM_ARB_MODE_BOTH', 'MEM_ARB_MODE_FIXED', - 'MEM_ARB_MODE_WEIGHT', 'MEM_POWER_DIS_MODE_DISABLE', - 'MEM_POWER_DIS_MODE_ENABLE', 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', + 'MAX_INSTANCE', 'MAX_SEGMENT', 'MEM_ARB_MODE_AGE', + 'MEM_ARB_MODE_BOTH', 'MEM_ARB_MODE_FIXED', 'MEM_ARB_MODE_WEIGHT', + 'MEM_POWER_DIS_MODE_DISABLE', 'MEM_POWER_DIS_MODE_ENABLE', + 'MEM_POWER_FORCE_MODE_DEEP_SLEEP', 'MEM_POWER_FORCE_MODE_LIGHT_SLEEP', 'MEM_POWER_FORCE_MODE_OFF', 'MEM_POWER_FORCE_MODE_SHUT_DOWN', 'MEM_POWER_STATUS_DEEP_SLEEP', 'MEM_POWER_STATUS_LIGHT_SLEEP', 'MEM_POWER_STATUS_ON', @@ -65005,12 +66028,64 @@ __all__ = \ 'MIN_CHUNK_SIZE_1024B', 'MIN_CHUNK_SIZE_256B', 'MIN_CHUNK_SIZE_512B', 'MIN_META_CHUNK_SIZE', 'MIN_META_CHUNK_SIZE_128B', 'MIN_META_CHUNK_SIZE_256B', - 'MIN_META_CHUNK_SIZE_64B', 'MONO_10LSB', 'MONO_10MSB', - 'MONO_12LSB', 'MONO_12MSB', 'MONO_16', 'MONO_2BIT', 'MONO_8', - 'MPCC_BG_COLOR_BPC', 'MPCC_BG_COLOR_BPC_10bit', - 'MPCC_BG_COLOR_BPC_11bit', 'MPCC_BG_COLOR_BPC_12bit', - 'MPCC_BG_COLOR_BPC_8bit', 'MPCC_BG_COLOR_BPC_9bit', - 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY', + 'MIN_META_CHUNK_SIZE_64B', 'MMHUB_BASE', 'MMHUB_BASE__INST0_SEG0', + 'MMHUB_BASE__INST0_SEG1', 'MMHUB_BASE__INST0_SEG2', + 'MMHUB_BASE__INST0_SEG3', 'MMHUB_BASE__INST0_SEG4', + 'MMHUB_BASE__INST1_SEG0', 'MMHUB_BASE__INST1_SEG1', + 'MMHUB_BASE__INST1_SEG2', 'MMHUB_BASE__INST1_SEG3', + 'MMHUB_BASE__INST1_SEG4', 'MMHUB_BASE__INST2_SEG0', + 'MMHUB_BASE__INST2_SEG1', 'MMHUB_BASE__INST2_SEG2', + 'MMHUB_BASE__INST2_SEG3', 'MMHUB_BASE__INST2_SEG4', + 'MMHUB_BASE__INST3_SEG0', 'MMHUB_BASE__INST3_SEG1', + 'MMHUB_BASE__INST3_SEG2', 'MMHUB_BASE__INST3_SEG3', + 'MMHUB_BASE__INST3_SEG4', 'MMHUB_BASE__INST4_SEG0', + 'MMHUB_BASE__INST4_SEG1', 'MMHUB_BASE__INST4_SEG2', + 'MMHUB_BASE__INST4_SEG3', 'MMHUB_BASE__INST4_SEG4', + 'MMHUB_BASE__INST5_SEG0', 'MMHUB_BASE__INST5_SEG1', + 'MMHUB_BASE__INST5_SEG2', 'MMHUB_BASE__INST5_SEG3', + 'MMHUB_BASE__INST5_SEG4', 'MMHUB_BASE__INST6_SEG0', + 'MMHUB_BASE__INST6_SEG1', 'MMHUB_BASE__INST6_SEG2', + 'MMHUB_BASE__INST6_SEG3', 'MMHUB_BASE__INST6_SEG4', 'MONO_10LSB', + 'MONO_10MSB', 'MONO_12LSB', 'MONO_12MSB', 'MONO_16', 'MONO_2BIT', + 'MONO_8', 'MP0_BASE', 'MP0_BASE__INST0_SEG0', + 'MP0_BASE__INST0_SEG1', 'MP0_BASE__INST0_SEG2', + 'MP0_BASE__INST0_SEG3', 'MP0_BASE__INST0_SEG4', + 'MP0_BASE__INST1_SEG0', 'MP0_BASE__INST1_SEG1', + 'MP0_BASE__INST1_SEG2', 'MP0_BASE__INST1_SEG3', + 'MP0_BASE__INST1_SEG4', 'MP0_BASE__INST2_SEG0', + 'MP0_BASE__INST2_SEG1', 'MP0_BASE__INST2_SEG2', + 'MP0_BASE__INST2_SEG3', 'MP0_BASE__INST2_SEG4', + 'MP0_BASE__INST3_SEG0', 'MP0_BASE__INST3_SEG1', + 'MP0_BASE__INST3_SEG2', 'MP0_BASE__INST3_SEG3', + 'MP0_BASE__INST3_SEG4', 'MP0_BASE__INST4_SEG0', + 'MP0_BASE__INST4_SEG1', 'MP0_BASE__INST4_SEG2', + 'MP0_BASE__INST4_SEG3', 'MP0_BASE__INST4_SEG4', + 'MP0_BASE__INST5_SEG0', 'MP0_BASE__INST5_SEG1', + 'MP0_BASE__INST5_SEG2', 'MP0_BASE__INST5_SEG3', + 'MP0_BASE__INST5_SEG4', 'MP0_BASE__INST6_SEG0', + 'MP0_BASE__INST6_SEG1', 'MP0_BASE__INST6_SEG2', + 'MP0_BASE__INST6_SEG3', 'MP0_BASE__INST6_SEG4', 'MP1_BASE', + 'MP1_BASE__INST0_SEG0', 'MP1_BASE__INST0_SEG1', + 'MP1_BASE__INST0_SEG2', 'MP1_BASE__INST0_SEG3', + 'MP1_BASE__INST0_SEG4', 'MP1_BASE__INST1_SEG0', + 'MP1_BASE__INST1_SEG1', 'MP1_BASE__INST1_SEG2', + 'MP1_BASE__INST1_SEG3', 'MP1_BASE__INST1_SEG4', + 'MP1_BASE__INST2_SEG0', 'MP1_BASE__INST2_SEG1', + 'MP1_BASE__INST2_SEG2', 'MP1_BASE__INST2_SEG3', + 'MP1_BASE__INST2_SEG4', 'MP1_BASE__INST3_SEG0', + 'MP1_BASE__INST3_SEG1', 'MP1_BASE__INST3_SEG2', + 'MP1_BASE__INST3_SEG3', 'MP1_BASE__INST3_SEG4', + 'MP1_BASE__INST4_SEG0', 'MP1_BASE__INST4_SEG1', + 'MP1_BASE__INST4_SEG2', 'MP1_BASE__INST4_SEG3', + 'MP1_BASE__INST4_SEG4', 'MP1_BASE__INST5_SEG0', + 'MP1_BASE__INST5_SEG1', 'MP1_BASE__INST5_SEG2', + 'MP1_BASE__INST5_SEG3', 'MP1_BASE__INST5_SEG4', + 'MP1_BASE__INST6_SEG0', 'MP1_BASE__INST6_SEG1', + 'MP1_BASE__INST6_SEG2', 'MP1_BASE__INST6_SEG3', + 'MP1_BASE__INST6_SEG4', 'MPCC_BG_COLOR_BPC', + 'MPCC_BG_COLOR_BPC_10bit', 'MPCC_BG_COLOR_BPC_11bit', + 'MPCC_BG_COLOR_BPC_12bit', 'MPCC_BG_COLOR_BPC_8bit', + 'MPCC_BG_COLOR_BPC_9bit', 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY', 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_FALSE', 'MPCC_CONTROL_MPCC_ACTIVE_OVERLAP_ONLY_TRUE', 'MPCC_CONTROL_MPCC_ALPHA_BLND_MODE', @@ -65189,9 +66264,27 @@ __all__ = \ 'MTYPE_RESERVED_5', 'MTYPE_RESERVED_7', 'MTYPE_UC', 'MTYPE_WC', 'MULTIPLE_BY1', 'MULTIPLE_BY2', 'MULTIPLE_BY3_RESERVED', 'MULTIPLE_BY4', 'MULTIPLE_RESERVED', 'MULT_16', 'MULT_8', - 'MemArbMode', 'NON_BYPASS', 'NOT_FORCE_THE_CLOCK_DISABLED', - 'NOT_SENT', 'NO_DIST', 'NO_DIV', 'NO_FORCE', 'NO_FORCE_REQ', - 'NO_FORCE_REQUEST', 'NO_MIN_CHUNK_SIZE', 'NO_MIN_META_CHUNK_SIZE', + 'MemArbMode', 'NBIO_BASE', 'NBIO_BASE__INST0_SEG0', + 'NBIO_BASE__INST0_SEG1', 'NBIO_BASE__INST0_SEG2', + 'NBIO_BASE__INST0_SEG3', 'NBIO_BASE__INST0_SEG4', + 'NBIO_BASE__INST1_SEG0', 'NBIO_BASE__INST1_SEG1', + 'NBIO_BASE__INST1_SEG2', 'NBIO_BASE__INST1_SEG3', + 'NBIO_BASE__INST1_SEG4', 'NBIO_BASE__INST2_SEG0', + 'NBIO_BASE__INST2_SEG1', 'NBIO_BASE__INST2_SEG2', + 'NBIO_BASE__INST2_SEG3', 'NBIO_BASE__INST2_SEG4', + 'NBIO_BASE__INST3_SEG0', 'NBIO_BASE__INST3_SEG1', + 'NBIO_BASE__INST3_SEG2', 'NBIO_BASE__INST3_SEG3', + 'NBIO_BASE__INST3_SEG4', 'NBIO_BASE__INST4_SEG0', + 'NBIO_BASE__INST4_SEG1', 'NBIO_BASE__INST4_SEG2', + 'NBIO_BASE__INST4_SEG3', 'NBIO_BASE__INST4_SEG4', + 'NBIO_BASE__INST5_SEG0', 'NBIO_BASE__INST5_SEG1', + 'NBIO_BASE__INST5_SEG2', 'NBIO_BASE__INST5_SEG3', + 'NBIO_BASE__INST5_SEG4', 'NBIO_BASE__INST6_SEG0', + 'NBIO_BASE__INST6_SEG1', 'NBIO_BASE__INST6_SEG2', + 'NBIO_BASE__INST6_SEG3', 'NBIO_BASE__INST6_SEG4', 'NON_BYPASS', + 'NOT_FORCE_THE_CLOCK_DISABLED', 'NOT_SENT', 'NO_DIST', 'NO_DIV', + 'NO_FORCE', 'NO_FORCE_REQ', 'NO_FORCE_REQUEST', + 'NO_MIN_CHUNK_SIZE', 'NO_MIN_META_CHUNK_SIZE', 'NO_OUTSTANDING_REQ', 'NUM_SIMD_PER_CU', 'NVD_H', 'OBUF_BYPASS_DIS', 'OBUF_BYPASS_EN', 'OBUF_BYPASS_SEL', 'OBUF_FULL', 'OBUF_FULL_RECOUT', 'OBUF_HALF_RECOUT', @@ -65258,7 +66351,25 @@ __all__ = \ 'OPTC_GSL_SOURCE_SELECT_GSL_TIMING_SYNC_SEL_RESERVED5', 'OPT_COMB_ADD', 'OPT_COMB_BLEND_DISABLED', 'OPT_COMB_MAX', 'OPT_COMB_MIN', 'OPT_COMB_NONE', 'OPT_COMB_REVSUBTRACT', - 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', + 'OPT_COMB_SAFE_ADD', 'OPT_COMB_SUBTRACT', 'OSSSYS_BASE', + 'OSSSYS_BASE__INST0_SEG0', 'OSSSYS_BASE__INST0_SEG1', + 'OSSSYS_BASE__INST0_SEG2', 'OSSSYS_BASE__INST0_SEG3', + 'OSSSYS_BASE__INST0_SEG4', 'OSSSYS_BASE__INST1_SEG0', + 'OSSSYS_BASE__INST1_SEG1', 'OSSSYS_BASE__INST1_SEG2', + 'OSSSYS_BASE__INST1_SEG3', 'OSSSYS_BASE__INST1_SEG4', + 'OSSSYS_BASE__INST2_SEG0', 'OSSSYS_BASE__INST2_SEG1', + 'OSSSYS_BASE__INST2_SEG2', 'OSSSYS_BASE__INST2_SEG3', + 'OSSSYS_BASE__INST2_SEG4', 'OSSSYS_BASE__INST3_SEG0', + 'OSSSYS_BASE__INST3_SEG1', 'OSSSYS_BASE__INST3_SEG2', + 'OSSSYS_BASE__INST3_SEG3', 'OSSSYS_BASE__INST3_SEG4', + 'OSSSYS_BASE__INST4_SEG0', 'OSSSYS_BASE__INST4_SEG1', + 'OSSSYS_BASE__INST4_SEG2', 'OSSSYS_BASE__INST4_SEG3', + 'OSSSYS_BASE__INST4_SEG4', 'OSSSYS_BASE__INST5_SEG0', + 'OSSSYS_BASE__INST5_SEG1', 'OSSSYS_BASE__INST5_SEG2', + 'OSSSYS_BASE__INST5_SEG3', 'OSSSYS_BASE__INST5_SEG4', + 'OSSSYS_BASE__INST6_SEG0', 'OSSSYS_BASE__INST6_SEG1', + 'OSSSYS_BASE__INST6_SEG2', 'OSSSYS_BASE__INST6_SEG3', + 'OSSSYS_BASE__INST6_SEG4', 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN', 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB', 'OTG_3D_STRUCTURE_CONTROL_OTG_3D_STRUCTURE_EN_DB_FALSE', @@ -65865,7 +66976,25 @@ __all__ = \ 'PACKET3_WAIT_REG_MEM64', 'PACKET3_WRITE_CONST_RAM', 'PACKET3_WRITE_DATA', 'PACKET_TYPE0', 'PACKET_TYPE1', 'PACKET_TYPE2', 'PACKET_TYPE3', 'PART_FRAC_EVEN', 'PART_FRAC_ODD', - 'PART_INTEGER', 'PART_POW2', 'PATCHES', 'PERFCOUNTER_ACTIVE', + 'PART_INTEGER', 'PART_POW2', 'PATCHES', 'PCIE0_BASE', + 'PCIE0_BASE__INST0_SEG0', 'PCIE0_BASE__INST0_SEG1', + 'PCIE0_BASE__INST0_SEG2', 'PCIE0_BASE__INST0_SEG3', + 'PCIE0_BASE__INST0_SEG4', 'PCIE0_BASE__INST1_SEG0', + 'PCIE0_BASE__INST1_SEG1', 'PCIE0_BASE__INST1_SEG2', + 'PCIE0_BASE__INST1_SEG3', 'PCIE0_BASE__INST1_SEG4', + 'PCIE0_BASE__INST2_SEG0', 'PCIE0_BASE__INST2_SEG1', + 'PCIE0_BASE__INST2_SEG2', 'PCIE0_BASE__INST2_SEG3', + 'PCIE0_BASE__INST2_SEG4', 'PCIE0_BASE__INST3_SEG0', + 'PCIE0_BASE__INST3_SEG1', 'PCIE0_BASE__INST3_SEG2', + 'PCIE0_BASE__INST3_SEG3', 'PCIE0_BASE__INST3_SEG4', + 'PCIE0_BASE__INST4_SEG0', 'PCIE0_BASE__INST4_SEG1', + 'PCIE0_BASE__INST4_SEG2', 'PCIE0_BASE__INST4_SEG3', + 'PCIE0_BASE__INST4_SEG4', 'PCIE0_BASE__INST5_SEG0', + 'PCIE0_BASE__INST5_SEG1', 'PCIE0_BASE__INST5_SEG2', + 'PCIE0_BASE__INST5_SEG3', 'PCIE0_BASE__INST5_SEG4', + 'PCIE0_BASE__INST6_SEG0', 'PCIE0_BASE__INST6_SEG1', + 'PCIE0_BASE__INST6_SEG2', 'PCIE0_BASE__INST6_SEG3', + 'PCIE0_BASE__INST6_SEG4', 'PERFCOUNTER_ACTIVE', 'PERFCOUNTER_CNT0_STATE', 'PERFCOUNTER_CNT0_STATE_FREEZE', 'PERFCOUNTER_CNT0_STATE_HW', 'PERFCOUNTER_CNT0_STATE_RESET', 'PERFCOUNTER_CNT0_STATE_START', 'PERFCOUNTER_CNT1_STATE', @@ -67634,6 +68763,41 @@ __all__ = \ 'SC_UR_2X', 'SC_UR_4X', 'SC_UR_8X', 'SC_VRS_COMB_MODE_MAX', 'SC_VRS_COMB_MODE_MIN', 'SC_VRS_COMB_MODE_OVERRIDE', 'SC_VRS_COMB_MODE_PASSTHRU', 'SC_VRS_COMB_MODE_SATURATE', + 'SDMA0_BASE', 'SDMA0_BASE__INST0_SEG0', 'SDMA0_BASE__INST0_SEG1', + 'SDMA0_BASE__INST0_SEG2', 'SDMA0_BASE__INST0_SEG3', + 'SDMA0_BASE__INST0_SEG4', 'SDMA0_BASE__INST1_SEG0', + 'SDMA0_BASE__INST1_SEG1', 'SDMA0_BASE__INST1_SEG2', + 'SDMA0_BASE__INST1_SEG3', 'SDMA0_BASE__INST1_SEG4', + 'SDMA0_BASE__INST2_SEG0', 'SDMA0_BASE__INST2_SEG1', + 'SDMA0_BASE__INST2_SEG2', 'SDMA0_BASE__INST2_SEG3', + 'SDMA0_BASE__INST2_SEG4', 'SDMA0_BASE__INST3_SEG0', + 'SDMA0_BASE__INST3_SEG1', 'SDMA0_BASE__INST3_SEG2', + 'SDMA0_BASE__INST3_SEG3', 'SDMA0_BASE__INST3_SEG4', + 'SDMA0_BASE__INST4_SEG0', 'SDMA0_BASE__INST4_SEG1', + 'SDMA0_BASE__INST4_SEG2', 'SDMA0_BASE__INST4_SEG3', + 'SDMA0_BASE__INST4_SEG4', 'SDMA0_BASE__INST5_SEG0', + 'SDMA0_BASE__INST5_SEG1', 'SDMA0_BASE__INST5_SEG2', + 'SDMA0_BASE__INST5_SEG3', 'SDMA0_BASE__INST5_SEG4', + 'SDMA0_BASE__INST6_SEG0', 'SDMA0_BASE__INST6_SEG1', + 'SDMA0_BASE__INST6_SEG2', 'SDMA0_BASE__INST6_SEG3', + 'SDMA0_BASE__INST6_SEG4', 'SDMA1_BASE', 'SDMA1_BASE__INST0_SEG0', + 'SDMA1_BASE__INST0_SEG1', 'SDMA1_BASE__INST0_SEG2', + 'SDMA1_BASE__INST0_SEG3', 'SDMA1_BASE__INST0_SEG4', + 'SDMA1_BASE__INST1_SEG0', 'SDMA1_BASE__INST1_SEG1', + 'SDMA1_BASE__INST1_SEG2', 'SDMA1_BASE__INST1_SEG3', + 'SDMA1_BASE__INST1_SEG4', 'SDMA1_BASE__INST2_SEG0', + 'SDMA1_BASE__INST2_SEG1', 'SDMA1_BASE__INST2_SEG2', + 'SDMA1_BASE__INST2_SEG3', 'SDMA1_BASE__INST2_SEG4', + 'SDMA1_BASE__INST3_SEG0', 'SDMA1_BASE__INST3_SEG1', + 'SDMA1_BASE__INST3_SEG2', 'SDMA1_BASE__INST3_SEG3', + 'SDMA1_BASE__INST3_SEG4', 'SDMA1_BASE__INST4_SEG0', + 'SDMA1_BASE__INST4_SEG1', 'SDMA1_BASE__INST4_SEG2', + 'SDMA1_BASE__INST4_SEG3', 'SDMA1_BASE__INST4_SEG4', + 'SDMA1_BASE__INST5_SEG0', 'SDMA1_BASE__INST5_SEG1', + 'SDMA1_BASE__INST5_SEG2', 'SDMA1_BASE__INST5_SEG3', + 'SDMA1_BASE__INST5_SEG4', 'SDMA1_BASE__INST6_SEG0', + 'SDMA1_BASE__INST6_SEG1', 'SDMA1_BASE__INST6_SEG2', + 'SDMA1_BASE__INST6_SEG3', 'SDMA1_BASE__INST6_SEG4', 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_mask', 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_offset', 'SDMA_AQL_PKT_BARRIER_OR_CACHE_POLICY_cache_policy0_shift', @@ -70456,13 +71620,30 @@ __all__ = \ 'SIMM16_WAITCNT_VM_CNT_SIZE', 'SIMM16_WAITCNT_VM_CNT_START', 'SIMM16_WAIT_EVENT_EXP_RDY_SIZE', 'SIMM16_WAIT_EVENT_EXP_RDY_START', 'SIZE_16K', 'SIZE_8K', - 'SLVERR', 'SMU_INTR', 'SMU_INTR_STATUS_CLEAR', - 'SMU_INTR_STATUS_NOOP', 'SMU_MSG_INTR_NOOP', 'SM_MODE_RESERVED', - 'SOFT_RESET', 'SOFT_RESET_0', 'SOFT_RESET_1', - 'SO_VGTSTREAMOUT_FLUSH', 'SPI_FOG_EXP', 'SPI_FOG_EXP2', - 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', 'SPI_FOG_NONE', - 'SPI_LB_WAVES_RSVD', 'SPI_LB_WAVES_SELECT', 'SPI_PERFCNT_SEL', - 'SPI_PERF_BUSY', 'SPI_PERF_CSGN_BUSY', + 'SLVERR', 'SMUIO_BASE', 'SMUIO_BASE__INST0_SEG0', + 'SMUIO_BASE__INST0_SEG1', 'SMUIO_BASE__INST0_SEG2', + 'SMUIO_BASE__INST0_SEG3', 'SMUIO_BASE__INST0_SEG4', + 'SMUIO_BASE__INST1_SEG0', 'SMUIO_BASE__INST1_SEG1', + 'SMUIO_BASE__INST1_SEG2', 'SMUIO_BASE__INST1_SEG3', + 'SMUIO_BASE__INST1_SEG4', 'SMUIO_BASE__INST2_SEG0', + 'SMUIO_BASE__INST2_SEG1', 'SMUIO_BASE__INST2_SEG2', + 'SMUIO_BASE__INST2_SEG3', 'SMUIO_BASE__INST2_SEG4', + 'SMUIO_BASE__INST3_SEG0', 'SMUIO_BASE__INST3_SEG1', + 'SMUIO_BASE__INST3_SEG2', 'SMUIO_BASE__INST3_SEG3', + 'SMUIO_BASE__INST3_SEG4', 'SMUIO_BASE__INST4_SEG0', + 'SMUIO_BASE__INST4_SEG1', 'SMUIO_BASE__INST4_SEG2', + 'SMUIO_BASE__INST4_SEG3', 'SMUIO_BASE__INST4_SEG4', + 'SMUIO_BASE__INST5_SEG0', 'SMUIO_BASE__INST5_SEG1', + 'SMUIO_BASE__INST5_SEG2', 'SMUIO_BASE__INST5_SEG3', + 'SMUIO_BASE__INST5_SEG4', 'SMUIO_BASE__INST6_SEG0', + 'SMUIO_BASE__INST6_SEG1', 'SMUIO_BASE__INST6_SEG2', + 'SMUIO_BASE__INST6_SEG3', 'SMUIO_BASE__INST6_SEG4', 'SMU_INTR', + 'SMU_INTR_STATUS_CLEAR', 'SMU_INTR_STATUS_NOOP', + 'SMU_MSG_INTR_NOOP', 'SM_MODE_RESERVED', 'SOFT_RESET', + 'SOFT_RESET_0', 'SOFT_RESET_1', 'SO_VGTSTREAMOUT_FLUSH', + 'SPI_FOG_EXP', 'SPI_FOG_EXP2', 'SPI_FOG_LINEAR', 'SPI_FOG_MODE', + 'SPI_FOG_NONE', 'SPI_LB_WAVES_RSVD', 'SPI_LB_WAVES_SELECT', + 'SPI_PERFCNT_SEL', 'SPI_PERF_BUSY', 'SPI_PERF_CSGN_BUSY', 'SPI_PERF_CSGN_CRAWLER_STALL', 'SPI_PERF_CSGN_EVENT_WAVE', 'SPI_PERF_CSGN_NUM_THREADGROUPS', 'SPI_PERF_CSGN_PWS_STALL', 'SPI_PERF_CSGN_WAVE', 'SPI_PERF_CSGN_WINDOW_VALID', @@ -71774,7 +72955,25 @@ __all__ = \ 'TEX_XYFilter_Linear', 'TEX_XYFilter_Point', 'TEX_XY_FILTER', 'TEX_ZFilter_Linear', 'TEX_ZFilter_None', 'TEX_ZFilter_Point', 'TEX_ZFilter_RESERVED_3', 'TEX_Z_FILTER', 'TGID_ROLLOVER', - 'THREAD_TRACE_DRAW', 'THREAD_TRACE_FINISH', 'THREAD_TRACE_MARKER', + 'THM_BASE', 'THM_BASE__INST0_SEG0', 'THM_BASE__INST0_SEG1', + 'THM_BASE__INST0_SEG2', 'THM_BASE__INST0_SEG3', + 'THM_BASE__INST0_SEG4', 'THM_BASE__INST1_SEG0', + 'THM_BASE__INST1_SEG1', 'THM_BASE__INST1_SEG2', + 'THM_BASE__INST1_SEG3', 'THM_BASE__INST1_SEG4', + 'THM_BASE__INST2_SEG0', 'THM_BASE__INST2_SEG1', + 'THM_BASE__INST2_SEG2', 'THM_BASE__INST2_SEG3', + 'THM_BASE__INST2_SEG4', 'THM_BASE__INST3_SEG0', + 'THM_BASE__INST3_SEG1', 'THM_BASE__INST3_SEG2', + 'THM_BASE__INST3_SEG3', 'THM_BASE__INST3_SEG4', + 'THM_BASE__INST4_SEG0', 'THM_BASE__INST4_SEG1', + 'THM_BASE__INST4_SEG2', 'THM_BASE__INST4_SEG3', + 'THM_BASE__INST4_SEG4', 'THM_BASE__INST5_SEG0', + 'THM_BASE__INST5_SEG1', 'THM_BASE__INST5_SEG2', + 'THM_BASE__INST5_SEG3', 'THM_BASE__INST5_SEG4', + 'THM_BASE__INST6_SEG0', 'THM_BASE__INST6_SEG1', + 'THM_BASE__INST6_SEG2', 'THM_BASE__INST6_SEG3', + 'THM_BASE__INST6_SEG4', 'THREAD_TRACE_DRAW', + 'THREAD_TRACE_FINISH', 'THREAD_TRACE_MARKER', 'THREAD_TRACE_START', 'THREAD_TRACE_STOP', 'TIGHT_PACK', 'TMDS_COLOR_FORMAT', 'TMDS_COLOR_FORMAT_DUAL30BPP', 'TMDS_COLOR_FORMAT_RESERVED', 'TMDS_COLOR_FORMAT_TWIN30BPP_LSB', @@ -71897,16 +73096,51 @@ __all__ = \ 'TRISTRIP', 'TVX_TYPE', 'TVX_Type_InvalidTextureResource', 'TVX_Type_InvalidVertexBuffer', 'TVX_Type_ValidTextureResource', 'TVX_Type_ValidVertexBuffer', 'UCONFIG_SPACE_END', - 'UCONFIG_SPACE_START', 'UNDEF', 'UNSIGNED', 'USE_MALL_FOR_CURSOR', - 'USE_MALL_FOR_CURSOR_0', 'USE_MALL_FOR_CURSOR_1', - 'USE_MALL_FOR_PSTATE_CHANGE', 'USE_MALL_FOR_PSTATE_CHANGE_0', - 'USE_MALL_FOR_PSTATE_CHANGE_1', 'USE_MALL_FOR_STATIC_SCREEN', - 'USE_MALL_FOR_STATIC_SCREEN_0', 'USE_MALL_FOR_STATIC_SCREEN_1', - 'UTCL0FaultType', 'UTCL0RequestType', 'UTCL0_TYPE_BYPASS', - 'UTCL0_TYPE_NORMAL', 'UTCL0_TYPE_SHOOTDOWN', - 'UTCL0_XNACK_NO_RETRY', 'UTCL0_XNACK_PRT', 'UTCL0_XNACK_RETRY', - 'UTCL0_XNACK_SUCCESS', 'UTCL1FaultType', 'UTCL1PerfSel', - 'UTCL1RequestType', 'UTCL1_PERF_SEL_BYPASS_REQS', + 'UCONFIG_SPACE_START', 'UMC_BASE', 'UMC_BASE__INST0_SEG0', + 'UMC_BASE__INST0_SEG1', 'UMC_BASE__INST0_SEG2', + 'UMC_BASE__INST0_SEG3', 'UMC_BASE__INST0_SEG4', + 'UMC_BASE__INST1_SEG0', 'UMC_BASE__INST1_SEG1', + 'UMC_BASE__INST1_SEG2', 'UMC_BASE__INST1_SEG3', + 'UMC_BASE__INST1_SEG4', 'UMC_BASE__INST2_SEG0', + 'UMC_BASE__INST2_SEG1', 'UMC_BASE__INST2_SEG2', + 'UMC_BASE__INST2_SEG3', 'UMC_BASE__INST2_SEG4', + 'UMC_BASE__INST3_SEG0', 'UMC_BASE__INST3_SEG1', + 'UMC_BASE__INST3_SEG2', 'UMC_BASE__INST3_SEG3', + 'UMC_BASE__INST3_SEG4', 'UMC_BASE__INST4_SEG0', + 'UMC_BASE__INST4_SEG1', 'UMC_BASE__INST4_SEG2', + 'UMC_BASE__INST4_SEG3', 'UMC_BASE__INST4_SEG4', + 'UMC_BASE__INST5_SEG0', 'UMC_BASE__INST5_SEG1', + 'UMC_BASE__INST5_SEG2', 'UMC_BASE__INST5_SEG3', + 'UMC_BASE__INST5_SEG4', 'UMC_BASE__INST6_SEG0', + 'UMC_BASE__INST6_SEG1', 'UMC_BASE__INST6_SEG2', + 'UMC_BASE__INST6_SEG3', 'UMC_BASE__INST6_SEG4', 'UNDEF', + 'UNSIGNED', 'USB0_BASE', 'USB0_BASE__INST0_SEG0', + 'USB0_BASE__INST0_SEG1', 'USB0_BASE__INST0_SEG2', + 'USB0_BASE__INST0_SEG3', 'USB0_BASE__INST0_SEG4', + 'USB0_BASE__INST1_SEG0', 'USB0_BASE__INST1_SEG1', + 'USB0_BASE__INST1_SEG2', 'USB0_BASE__INST1_SEG3', + 'USB0_BASE__INST1_SEG4', 'USB0_BASE__INST2_SEG0', + 'USB0_BASE__INST2_SEG1', 'USB0_BASE__INST2_SEG2', + 'USB0_BASE__INST2_SEG3', 'USB0_BASE__INST2_SEG4', + 'USB0_BASE__INST3_SEG0', 'USB0_BASE__INST3_SEG1', + 'USB0_BASE__INST3_SEG2', 'USB0_BASE__INST3_SEG3', + 'USB0_BASE__INST3_SEG4', 'USB0_BASE__INST4_SEG0', + 'USB0_BASE__INST4_SEG1', 'USB0_BASE__INST4_SEG2', + 'USB0_BASE__INST4_SEG3', 'USB0_BASE__INST4_SEG4', + 'USB0_BASE__INST5_SEG0', 'USB0_BASE__INST5_SEG1', + 'USB0_BASE__INST5_SEG2', 'USB0_BASE__INST5_SEG3', + 'USB0_BASE__INST5_SEG4', 'USB0_BASE__INST6_SEG0', + 'USB0_BASE__INST6_SEG1', 'USB0_BASE__INST6_SEG2', + 'USB0_BASE__INST6_SEG3', 'USB0_BASE__INST6_SEG4', + 'USE_MALL_FOR_CURSOR', 'USE_MALL_FOR_CURSOR_0', + 'USE_MALL_FOR_CURSOR_1', 'USE_MALL_FOR_PSTATE_CHANGE', + 'USE_MALL_FOR_PSTATE_CHANGE_0', 'USE_MALL_FOR_PSTATE_CHANGE_1', + 'USE_MALL_FOR_STATIC_SCREEN', 'USE_MALL_FOR_STATIC_SCREEN_0', + 'USE_MALL_FOR_STATIC_SCREEN_1', 'UTCL0FaultType', + 'UTCL0RequestType', 'UTCL0_TYPE_BYPASS', 'UTCL0_TYPE_NORMAL', + 'UTCL0_TYPE_SHOOTDOWN', 'UTCL0_XNACK_NO_RETRY', 'UTCL0_XNACK_PRT', + 'UTCL0_XNACK_RETRY', 'UTCL0_XNACK_SUCCESS', 'UTCL1FaultType', + 'UTCL1PerfSel', 'UTCL1RequestType', 'UTCL1_PERF_SEL_BYPASS_REQS', 'UTCL1_PERF_SEL_CP_INVREQS', 'UTCL1_PERF_SEL_HITS', 'UTCL1_PERF_SEL_HIT_INV_FILTER_REQS', 'UTCL1_PERF_SEL_INV_ALL_VMID_INVREQS', @@ -71925,14 +73159,31 @@ __all__ = \ 'UTCL1_PERF_SEL_XLAT_REQ_BUSY', 'UTCL1_TYPE_BYPASS', 'UTCL1_TYPE_NORMAL', 'UTCL1_TYPE_SHOOTDOWN', 'UTCL1_XNACK_NO_RETRY', 'UTCL1_XNACK_PRT', 'UTCL1_XNACK_RETRY', - 'UTCL1_XNACK_SUCCESS', 'VGT_DETECT_ONE', 'VGT_DETECT_ZERO', - 'VGT_DIST_MODE', 'VGT_DI_INDEX_SIZE', 'VGT_DI_MAJOR_MODE_SELECT', - 'VGT_DI_PRIM_TYPE', 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', - 'VGT_DMA_BUF_RING', 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', - 'VGT_DMA_PTR_UPDATE', 'VGT_DMA_SWAP_16_BIT', - 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', 'VGT_DMA_SWAP_NONE', - 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', 'VGT_FLUSH', - 'VGT_GROUP_CONV_SEL', 'VGT_GRP_AUTO_PRIM', + 'UTCL1_XNACK_SUCCESS', 'VCN_BASE', 'VCN_BASE__INST0_SEG0', + 'VCN_BASE__INST0_SEG1', 'VCN_BASE__INST0_SEG2', + 'VCN_BASE__INST0_SEG3', 'VCN_BASE__INST0_SEG4', + 'VCN_BASE__INST1_SEG0', 'VCN_BASE__INST1_SEG1', + 'VCN_BASE__INST1_SEG2', 'VCN_BASE__INST1_SEG3', + 'VCN_BASE__INST1_SEG4', 'VCN_BASE__INST2_SEG0', + 'VCN_BASE__INST2_SEG1', 'VCN_BASE__INST2_SEG2', + 'VCN_BASE__INST2_SEG3', 'VCN_BASE__INST2_SEG4', + 'VCN_BASE__INST3_SEG0', 'VCN_BASE__INST3_SEG1', + 'VCN_BASE__INST3_SEG2', 'VCN_BASE__INST3_SEG3', + 'VCN_BASE__INST3_SEG4', 'VCN_BASE__INST4_SEG0', + 'VCN_BASE__INST4_SEG1', 'VCN_BASE__INST4_SEG2', + 'VCN_BASE__INST4_SEG3', 'VCN_BASE__INST4_SEG4', + 'VCN_BASE__INST5_SEG0', 'VCN_BASE__INST5_SEG1', + 'VCN_BASE__INST5_SEG2', 'VCN_BASE__INST5_SEG3', + 'VCN_BASE__INST5_SEG4', 'VCN_BASE__INST6_SEG0', + 'VCN_BASE__INST6_SEG1', 'VCN_BASE__INST6_SEG2', + 'VCN_BASE__INST6_SEG3', 'VCN_BASE__INST6_SEG4', 'VGT_DETECT_ONE', + 'VGT_DETECT_ZERO', 'VGT_DIST_MODE', 'VGT_DI_INDEX_SIZE', + 'VGT_DI_MAJOR_MODE_SELECT', 'VGT_DI_PRIM_TYPE', + 'VGT_DI_SOURCE_SELECT', 'VGT_DMA_BUF_MEM', 'VGT_DMA_BUF_RING', + 'VGT_DMA_BUF_SETUP', 'VGT_DMA_BUF_TYPE', 'VGT_DMA_PTR_UPDATE', + 'VGT_DMA_SWAP_16_BIT', 'VGT_DMA_SWAP_32_BIT', 'VGT_DMA_SWAP_MODE', + 'VGT_DMA_SWAP_NONE', 'VGT_DMA_SWAP_WORD', 'VGT_EVENT_TYPE', + 'VGT_FLUSH', 'VGT_GROUP_CONV_SEL', 'VGT_GRP_AUTO_PRIM', 'VGT_GRP_FIX_1_23_TO_FLOAT', 'VGT_GRP_FLOAT_32', 'VGT_GRP_INDEX_16', 'VGT_GRP_INDEX_32', 'VGT_GRP_SINT_16', 'VGT_GRP_SINT_32', 'VGT_GRP_UINT_16', 'VGT_GRP_UINT_32', @@ -72018,9 +73269,9 @@ __all__ = \ 'Y_G_DATA_ONTO_Y_G_PORT', 'ZLimitSumm', 'ZModeForce', 'ZOrder', 'ZPASS_DISABLE', 'ZPASS_PIXELS', 'ZPASS_SAMPLES', 'ZSamplePosition', 'Z_SAMPLE_CENTER', 'Z_SAMPLE_CENTROID', - 'ZpassControl', '__SDMA_V6_0_0_PKT_OPEN_H_', + 'ZpassControl', '__SDMA_V6_0_0_PKT_OPEN_H_', '__maybe_unused', '_gc_10_3_0_OFFSET_HEADER', '_gc_11_0_0_OFFSET_HEADER', - '_soc21_ENUM_HEADER', + '_sienna_cichlid_ip_offset_HEADER', '_soc21_ENUM_HEADER', 'addr_incr___write_data__do_not_increment_address', 'addr_incr___write_data__increment_address', 'c__Ea_CACHE_FLUSH_AND_INV_TS_EVENT', 'c_uint32', 'c_uint32', @@ -87751,6 +89002,7 @@ __all__ = \ 'regWD_ENHANCE_BASE_IDX', 'regWD_QOS', 'regWD_QOS_BASE_IDX', 'regWD_UTCL1_CNTL', 'regWD_UTCL1_CNTL_BASE_IDX', 'regWD_UTCL1_STATUS', 'regWD_UTCL1_STATUS_BASE_IDX', + 'struct_IP_BASE', 'struct_IP_BASE_INSTANCE', 'struct_PM4_MES_TYPE_3_HEADER_0', 'struct_SDMA_PKT_ATOMIC_TAG', 'struct_SDMA_PKT_ATOMIC_TAG_0_0', 'struct_SDMA_PKT_ATOMIC_TAG_1_0', diff --git a/tinygrad_repo/tinygrad/runtime/autogen/comgr.py b/tinygrad_repo/tinygrad/runtime/autogen/comgr.py index e76ee220e5..d4e05ec397 100644 --- a/tinygrad_repo/tinygrad/runtime/autogen/comgr.py +++ b/tinygrad_repo/tinygrad/runtime/autogen/comgr.py @@ -10,6 +10,8 @@ import ctypes, ctypes.util, os PATHS_TO_TRY = [ '/opt/rocm/lib/libamd_comgr.so', os.getenv('ROCM_PATH', '')+'/lib/libamd_comgr.so', + '/usr/local/lib/libamd_comgr.dylib', + '/opt/homebrew/lib/libamd_comgr.dylib', ] def _try_dlopen_amd_comgr(): library = ctypes.util.find_library("amd_comgr") @@ -17,7 +19,7 @@ def _try_dlopen_amd_comgr(): for candidate in PATHS_TO_TRY: try: return ctypes.CDLL(candidate) except OSError: pass - raise RuntimeError("library amd_comgr not found") + return None def string_cast(char_pointer, encoding='utf-8', errors='strict'): diff --git a/tinygrad_repo/tinygrad/runtime/autogen/kfd.py b/tinygrad_repo/tinygrad/runtime/autogen/kfd.py index 4fc6368239..4b970abf9a 100644 --- a/tinygrad_repo/tinygrad/runtime/autogen/kfd.py +++ b/tinygrad_repo/tinygrad/runtime/autogen/kfd.py @@ -10,10 +10,11 @@ import ctypes, os -import fcntl, functools +import functools +from tinygrad.runtime.support.hcq import FileIOInterface -def _do_ioctl(__idir, __base, __nr, __user_struct, __fd, **kwargs): - ret = fcntl.ioctl(__fd, (__idir<<30) | (ctypes.sizeof(made := __user_struct(**kwargs))<<16) | (__base<<8) | __nr, made) +def _do_ioctl(__idir, __base, __nr, __user_struct, __fd:FileIOInterface, **kwargs): + ret = __fd.ioctl((__idir<<30) | (ctypes.sizeof(made := __user_struct(**kwargs))<<16) | (__base<<8) | __nr, made) if ret != 0: raise RuntimeError(f"ioctl returned {ret}") return made diff --git a/tinygrad_repo/tinygrad/runtime/autogen/kgsl.py b/tinygrad_repo/tinygrad/runtime/autogen/kgsl.py index 313f3ece37..439484d15b 100644 --- a/tinygrad_repo/tinygrad/runtime/autogen/kgsl.py +++ b/tinygrad_repo/tinygrad/runtime/autogen/kgsl.py @@ -129,7 +129,7 @@ else: import fcntl, functools def _do_ioctl(__idir, __base, __nr, __user_struct, __fd, __payload=None, **kwargs): - ret = fcntl.ioctl(__fd, (__idir<<30) | (ctypes.sizeof(made := (__payload or __user_struct(**kwargs)))<<16) | (__base<<8) | __nr, made) + ret = __fd.ioctl((__idir<<30) | (ctypes.sizeof(made := (__payload or __user_struct(**kwargs)))<<16) | (__base<<8) | __nr, made) if ret != 0: raise RuntimeError(f"ioctl returned {ret}") return made diff --git a/tinygrad_repo/tinygrad/runtime/autogen/libc.py b/tinygrad_repo/tinygrad/runtime/autogen/libc.py index 53e1841ed6..fe955160ba 100644 --- a/tinygrad_repo/tinygrad/runtime/autogen/libc.py +++ b/tinygrad_repo/tinygrad/runtime/autogen/libc.py @@ -245,6 +245,265 @@ try: except AttributeError: pass _SYSCALL_H = 1 # macro +_STRING_H = 1 # macro +__GLIBC_INTERNAL_STARTING_HEADER_IMPLEMENTATION = True # macro +__need_NULL = True # macro +try: + memcpy = _libraries['libc'].memcpy + memcpy.restype = ctypes.POINTER(None) + memcpy.argtypes = [ctypes.POINTER(None), ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + memmove = _libraries['libc'].memmove + memmove.restype = ctypes.POINTER(None) + memmove.argtypes = [ctypes.POINTER(None), ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + memccpy = _libraries['libc'].memccpy + memccpy.restype = ctypes.POINTER(None) + memccpy.argtypes = [ctypes.POINTER(None), ctypes.POINTER(None), ctypes.c_int32, size_t] +except AttributeError: + pass +try: + memset = _libraries['libc'].memset + memset.restype = ctypes.POINTER(None) + memset.argtypes = [ctypes.POINTER(None), ctypes.c_int32, size_t] +except AttributeError: + pass +try: + memcmp = _libraries['libc'].memcmp + memcmp.restype = ctypes.c_int32 + memcmp.argtypes = [ctypes.POINTER(None), ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + __memcmpeq = _libraries['libc'].__memcmpeq + __memcmpeq.restype = ctypes.c_int32 + __memcmpeq.argtypes = [ctypes.POINTER(None), ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + memchr = _libraries['libc'].memchr + memchr.restype = ctypes.POINTER(None) + memchr.argtypes = [ctypes.POINTER(None), ctypes.c_int32, size_t] +except AttributeError: + pass +try: + strcpy = _libraries['libc'].strcpy + strcpy.restype = ctypes.POINTER(ctypes.c_char) + strcpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strncpy = _libraries['libc'].strncpy + strncpy.restype = ctypes.POINTER(ctypes.c_char) + strncpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strcat = _libraries['libc'].strcat + strcat.restype = ctypes.POINTER(ctypes.c_char) + strcat.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strncat = _libraries['libc'].strncat + strncat.restype = ctypes.POINTER(ctypes.c_char) + strncat.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strcmp = _libraries['libc'].strcmp + strcmp.restype = ctypes.c_int32 + strcmp.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strncmp = _libraries['libc'].strncmp + strncmp.restype = ctypes.c_int32 + strncmp.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strcoll = _libraries['libc'].strcoll + strcoll.restype = ctypes.c_int32 + strcoll.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strxfrm = _libraries['libc'].strxfrm + strxfrm.restype = ctypes.c_uint64 + strxfrm.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +class struct___locale_struct(Structure): + pass + +class struct___locale_data(Structure): + pass + +struct___locale_struct._pack_ = 1 # source:False +struct___locale_struct._fields_ = [ + ('__locales', ctypes.POINTER(struct___locale_data) * 13), + ('__ctype_b', ctypes.POINTER(ctypes.c_uint16)), + ('__ctype_tolower', ctypes.POINTER(ctypes.c_int32)), + ('__ctype_toupper', ctypes.POINTER(ctypes.c_int32)), + ('__names', ctypes.POINTER(ctypes.c_char) * 13), +] + +locale_t = ctypes.POINTER(struct___locale_struct) +try: + strcoll_l = _libraries['libc'].strcoll_l + strcoll_l.restype = ctypes.c_int32 + strcoll_l.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), locale_t] +except AttributeError: + pass +try: + strxfrm_l = _libraries['libc'].strxfrm_l + strxfrm_l.restype = size_t + strxfrm_l.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t, locale_t] +except AttributeError: + pass +try: + strdup = _libraries['libc'].strdup + strdup.restype = ctypes.POINTER(ctypes.c_char) + strdup.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strndup = _libraries['libc'].strndup + strndup.restype = ctypes.POINTER(ctypes.c_char) + strndup.argtypes = [ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strchr = _libraries['libc'].strchr + strchr.restype = ctypes.POINTER(ctypes.c_char) + strchr.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.c_int32] +except AttributeError: + pass +try: + strrchr = _libraries['libc'].strrchr + strrchr.restype = ctypes.POINTER(ctypes.c_char) + strrchr.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.c_int32] +except AttributeError: + pass +try: + strcspn = _libraries['libc'].strcspn + strcspn.restype = ctypes.c_uint64 + strcspn.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strspn = _libraries['libc'].strspn + strspn.restype = ctypes.c_uint64 + strspn.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strpbrk = _libraries['libc'].strpbrk + strpbrk.restype = ctypes.POINTER(ctypes.c_char) + strpbrk.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strstr = _libraries['libc'].strstr + strstr.restype = ctypes.POINTER(ctypes.c_char) + strstr.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strtok = _libraries['libc'].strtok + strtok.restype = ctypes.POINTER(ctypes.c_char) + strtok.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + __strtok_r = _libraries['libc'].__strtok_r + __strtok_r.restype = ctypes.POINTER(ctypes.c_char) + __strtok_r.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + strtok_r = _libraries['libc'].strtok_r + strtok_r.restype = ctypes.POINTER(ctypes.c_char) + strtok_r.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + strlen = _libraries['libc'].strlen + strlen.restype = ctypes.c_uint64 + strlen.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strnlen = _libraries['libc'].strnlen + strnlen.restype = size_t + strnlen.argtypes = [ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strerror = _libraries['libc'].strerror + strerror.restype = ctypes.POINTER(ctypes.c_char) + strerror.argtypes = [ctypes.c_int32] +except AttributeError: + pass +try: + strerror_r = _libraries['libc'].strerror_r + strerror_r.restype = ctypes.c_int32 + strerror_r.argtypes = [ctypes.c_int32, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + strerror_l = _libraries['libc'].strerror_l + strerror_l.restype = ctypes.POINTER(ctypes.c_char) + strerror_l.argtypes = [ctypes.c_int32, locale_t] +except AttributeError: + pass +try: + explicit_bzero = _libraries['libc'].explicit_bzero + explicit_bzero.restype = None + explicit_bzero.argtypes = [ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + strsep = _libraries['libc'].strsep + strsep.restype = ctypes.POINTER(ctypes.c_char) + strsep.argtypes = [ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + strsignal = _libraries['libc'].strsignal + strsignal.restype = ctypes.POINTER(ctypes.c_char) + strsignal.argtypes = [ctypes.c_int32] +except AttributeError: + pass +try: + __stpcpy = _libraries['libc'].__stpcpy + __stpcpy.restype = ctypes.POINTER(ctypes.c_char) + __stpcpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + stpcpy = _libraries['libc'].stpcpy + stpcpy.restype = ctypes.POINTER(ctypes.c_char) + stpcpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + __stpncpy = _libraries['libc'].__stpncpy + __stpncpy.restype = ctypes.POINTER(ctypes.c_char) + __stpncpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + stpncpy = _libraries['libc'].stpncpy + stpncpy.restype = ctypes.POINTER(ctypes.c_char) + stpncpy.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass _ELF_H = 1 # macro EI_NIDENT = (16) # macro EI_MAG0 = 0 # macro @@ -3726,7 +3985,6 @@ STDIN_FILENO = 0 # macro STDOUT_FILENO = 1 # macro STDERR_FILENO = 2 # macro __ssize_t_defined = True # macro -__need_NULL = True # macro __gid_t_defined = True # macro __uid_t_defined = True # macro __useconds_t_defined = True # macro @@ -4401,6 +4659,55 @@ try: getentropy.argtypes = [ctypes.POINTER(None), size_t] except AttributeError: pass +__ASM_GENERIC_MMAN_COMMON_H = True # macro +PROT_READ = 0x1 # macro +PROT_WRITE = 0x2 # macro +PROT_EXEC = 0x4 # macro +PROT_SEM = 0x8 # macro +PROT_NONE = 0x0 # macro +PROT_GROWSDOWN = 0x01000000 # macro +PROT_GROWSUP = 0x02000000 # macro +MAP_TYPE = 0x0f # macro +MAP_FIXED = 0x10 # macro +MAP_ANONYMOUS = 0x20 # macro +MAP_POPULATE = 0x008000 # macro +MAP_NONBLOCK = 0x010000 # macro +MAP_STACK = 0x020000 # macro +MAP_HUGETLB = 0x040000 # macro +MAP_SYNC = 0x080000 # macro +MAP_FIXED_NOREPLACE = 0x100000 # macro +MAP_UNINITIALIZED = 0x4000000 # macro +MLOCK_ONFAULT = 0x01 # macro +MS_ASYNC = 1 # macro +MS_INVALIDATE = 2 # macro +MS_SYNC = 4 # macro +MADV_NORMAL = 0 # macro +MADV_RANDOM = 1 # macro +MADV_SEQUENTIAL = 2 # macro +MADV_WILLNEED = 3 # macro +MADV_DONTNEED = 4 # macro +MADV_FREE = 8 # macro +MADV_REMOVE = 9 # macro +MADV_DONTFORK = 10 # macro +MADV_DOFORK = 11 # macro +MADV_HWPOISON = 100 # macro +MADV_SOFT_OFFLINE = 101 # macro +MADV_MERGEABLE = 12 # macro +MADV_UNMERGEABLE = 13 # macro +MADV_HUGEPAGE = 14 # macro +MADV_NOHUGEPAGE = 15 # macro +MADV_DONTDUMP = 16 # macro +MADV_DODUMP = 17 # macro +MADV_WIPEONFORK = 18 # macro +MADV_KEEPONFORK = 19 # macro +MADV_COLD = 20 # macro +MADV_PAGEOUT = 21 # macro +MADV_POPULATE_READ = 22 # macro +MADV_POPULATE_WRITE = 23 # macro +MAP_FILE = 0 # macro +PKEY_DISABLE_ACCESS = 0x1 # macro +PKEY_DISABLE_WRITE = 0x2 # macro +PKEY_ACCESS_MASK = (0x1|0x2) # macro __all__ = \ ['AT_BASE', 'AT_BASE_PLATFORM', 'AT_CLKTCK', 'AT_DCACHEBSIZE', 'AT_EGID', 'AT_ENTRY', 'AT_EUID', 'AT_EXECFD', 'AT_EXECFN', @@ -4596,20 +4903,31 @@ __all__ = \ 'LITUSE_ALPHA_TLS_GD', 'LITUSE_ALPHA_TLS_LDM', 'LL_DELAY_LOAD', 'LL_DELTA', 'LL_EXACT_MATCH', 'LL_EXPORTS', 'LL_IGNORE_INT_VER', 'LL_NONE', 'LL_REQUIRE_MINOR', 'L_INCR', 'L_SET', 'L_XTND', - 'MIPS_AFL_ASE_DSP', 'MIPS_AFL_ASE_DSPR2', 'MIPS_AFL_ASE_EVA', - 'MIPS_AFL_ASE_MASK', 'MIPS_AFL_ASE_MCU', 'MIPS_AFL_ASE_MDMX', - 'MIPS_AFL_ASE_MICROMIPS', 'MIPS_AFL_ASE_MIPS16', - 'MIPS_AFL_ASE_MIPS3D', 'MIPS_AFL_ASE_MSA', 'MIPS_AFL_ASE_MT', - 'MIPS_AFL_ASE_SMARTMIPS', 'MIPS_AFL_ASE_VIRT', 'MIPS_AFL_ASE_XPA', - 'MIPS_AFL_EXT_10000', 'MIPS_AFL_EXT_3900', 'MIPS_AFL_EXT_4010', - 'MIPS_AFL_EXT_4100', 'MIPS_AFL_EXT_4111', 'MIPS_AFL_EXT_4120', - 'MIPS_AFL_EXT_4650', 'MIPS_AFL_EXT_5400', 'MIPS_AFL_EXT_5500', - 'MIPS_AFL_EXT_5900', 'MIPS_AFL_EXT_LOONGSON_2E', - 'MIPS_AFL_EXT_LOONGSON_2F', 'MIPS_AFL_EXT_LOONGSON_3A', - 'MIPS_AFL_EXT_OCTEON', 'MIPS_AFL_EXT_OCTEON2', - 'MIPS_AFL_EXT_OCTEONP', 'MIPS_AFL_EXT_SB1', 'MIPS_AFL_EXT_XLR', + 'MADV_COLD', 'MADV_DODUMP', 'MADV_DOFORK', 'MADV_DONTDUMP', + 'MADV_DONTFORK', 'MADV_DONTNEED', 'MADV_FREE', 'MADV_HUGEPAGE', + 'MADV_HWPOISON', 'MADV_KEEPONFORK', 'MADV_MERGEABLE', + 'MADV_NOHUGEPAGE', 'MADV_NORMAL', 'MADV_PAGEOUT', + 'MADV_POPULATE_READ', 'MADV_POPULATE_WRITE', 'MADV_RANDOM', + 'MADV_REMOVE', 'MADV_SEQUENTIAL', 'MADV_SOFT_OFFLINE', + 'MADV_UNMERGEABLE', 'MADV_WILLNEED', 'MADV_WIPEONFORK', + 'MAP_ANONYMOUS', 'MAP_FILE', 'MAP_FIXED', 'MAP_FIXED_NOREPLACE', + 'MAP_HUGETLB', 'MAP_NONBLOCK', 'MAP_POPULATE', 'MAP_STACK', + 'MAP_SYNC', 'MAP_TYPE', 'MAP_UNINITIALIZED', 'MIPS_AFL_ASE_DSP', + 'MIPS_AFL_ASE_DSPR2', 'MIPS_AFL_ASE_EVA', 'MIPS_AFL_ASE_MASK', + 'MIPS_AFL_ASE_MCU', 'MIPS_AFL_ASE_MDMX', 'MIPS_AFL_ASE_MICROMIPS', + 'MIPS_AFL_ASE_MIPS16', 'MIPS_AFL_ASE_MIPS3D', 'MIPS_AFL_ASE_MSA', + 'MIPS_AFL_ASE_MT', 'MIPS_AFL_ASE_SMARTMIPS', 'MIPS_AFL_ASE_VIRT', + 'MIPS_AFL_ASE_XPA', 'MIPS_AFL_EXT_10000', 'MIPS_AFL_EXT_3900', + 'MIPS_AFL_EXT_4010', 'MIPS_AFL_EXT_4100', 'MIPS_AFL_EXT_4111', + 'MIPS_AFL_EXT_4120', 'MIPS_AFL_EXT_4650', 'MIPS_AFL_EXT_5400', + 'MIPS_AFL_EXT_5500', 'MIPS_AFL_EXT_5900', + 'MIPS_AFL_EXT_LOONGSON_2E', 'MIPS_AFL_EXT_LOONGSON_2F', + 'MIPS_AFL_EXT_LOONGSON_3A', 'MIPS_AFL_EXT_OCTEON', + 'MIPS_AFL_EXT_OCTEON2', 'MIPS_AFL_EXT_OCTEONP', + 'MIPS_AFL_EXT_SB1', 'MIPS_AFL_EXT_XLR', 'MIPS_AFL_FLAGS1_ODDSPREG', 'MIPS_AFL_REG_128', 'MIPS_AFL_REG_32', - 'MIPS_AFL_REG_64', 'MIPS_AFL_REG_NONE', + 'MIPS_AFL_REG_64', 'MIPS_AFL_REG_NONE', 'MLOCK_ONFAULT', + 'MS_ASYNC', 'MS_INVALIDATE', 'MS_SYNC', 'NOTE_GNU_PROPERTY_SECTION_NAME', 'NT_386_IOPERM', 'NT_386_TLS', 'NT_ARM_HW_BREAK', 'NT_ARM_HW_WATCH', 'NT_ARM_PACA_KEYS', 'NT_ARM_PACG_KEYS', 'NT_ARM_PAC_ENABLED_KEYS', 'NT_ARM_PAC_MASK', @@ -4644,9 +4962,12 @@ __all__ = \ 'PF_HP_FAR_SHARED', 'PF_HP_LAZYSWAP', 'PF_HP_MODIFY', 'PF_HP_NEAR_SHARED', 'PF_HP_PAGE_SIZE', 'PF_HP_SBP', 'PF_IA_64_NORECOV', 'PF_MASKOS', 'PF_MASKPROC', 'PF_MIPS_LOCAL', - 'PF_PARISC_SBP', 'PF_R', 'PF_W', 'PF_X', 'PN_XNUM', + 'PF_PARISC_SBP', 'PF_R', 'PF_W', 'PF_X', 'PKEY_ACCESS_MASK', + 'PKEY_DISABLE_ACCESS', 'PKEY_DISABLE_WRITE', 'PN_XNUM', 'PPC64_OPT_LOCALENTRY', 'PPC64_OPT_MULTI_TOC', 'PPC64_OPT_TLS', - 'PPC_OPT_TLS', 'PT_ARM_EXIDX', 'PT_DYNAMIC', 'PT_GNU_EH_FRAME', + 'PPC_OPT_TLS', 'PROT_EXEC', 'PROT_GROWSDOWN', 'PROT_GROWSUP', + 'PROT_NONE', 'PROT_READ', 'PROT_SEM', 'PROT_WRITE', + 'PT_ARM_EXIDX', 'PT_DYNAMIC', 'PT_GNU_EH_FRAME', 'PT_GNU_PROPERTY', 'PT_GNU_RELRO', 'PT_GNU_STACK', 'PT_HIOS', 'PT_HIPROC', 'PT_HISUNW', 'PT_HP_CORE_COMM', 'PT_HP_CORE_KERNEL', 'PT_HP_CORE_LOADABLE', 'PT_HP_CORE_MMF', 'PT_HP_CORE_NONE', @@ -5404,59 +5725,71 @@ __all__ = \ 'Val_GNU_MIPS_ABI_FP_SOFT', 'Val_GNU_MIPS_ABI_FP_XX', 'W_OK', 'X_OK', '_ELF_H', '_POSIX2_C_BIND', '_POSIX2_C_DEV', '_POSIX2_C_VERSION', '_POSIX2_LOCALEDEF', '_POSIX2_SW_DEV', - '_POSIX2_VERSION', '_POSIX_VERSION', '_SYSCALL_H', '_SYS_MMAN_H', - '_UNISTD_H', '_XOPEN_ENH_I18N', '_XOPEN_LEGACY', '_XOPEN_UNIX', - '_XOPEN_VERSION', '_XOPEN_XCU_VERSION', '_XOPEN_XPG2', - '_XOPEN_XPG3', '_XOPEN_XPG4', '__POSIX2_THIS_VERSION', - '__environ', '__getpgid', '__gid_t', '__gid_t_defined', - '__intptr_t_defined', '__mode_t_defined', '__need_NULL', - '__need_size_t', '__off_t', '__off_t_defined', '__pid_t', - '__pid_t_defined', '__socklen_t_defined', '__ssize_t_defined', - '__uid_t', '__uid_t_defined', '__useconds_t', - '__useconds_t_defined', '_exit', 'access', 'acct', 'alarm', 'brk', - 'c__Ea_Val_GNU_MIPS_ABI_FP_ANY', 'chdir', 'chown', 'chroot', - 'close', 'closefrom', 'confstr', 'crypt', 'daemon', 'dup', 'dup2', - 'endusershell', 'execl', 'execle', 'execlp', 'execv', 'execve', - 'execvp', 'faccessat', 'fchdir', 'fchown', 'fchownat', - 'fdatasync', 'fexecve', 'fork', 'fpathconf', 'fsync', 'ftruncate', - 'getcwd', 'getdomainname', 'getdtablesize', 'getegid', - 'getentropy', 'geteuid', 'getgid', 'getgroups', 'gethostid', - 'gethostname', 'getlogin', 'getlogin_r', 'getpagesize', 'getpass', - 'getpgid', 'getpgrp', 'getpid', 'getppid', 'getsid', 'getuid', - 'getusershell', 'getwd', 'gid_t', 'intptr_t', 'isatty', 'lchown', - 'link', 'linkat', 'lockf', 'lseek', 'madvise', 'mincore', 'mlock', - 'mlockall', 'mmap', 'mode_t', 'mprotect', 'msync', 'munlock', - 'munlockall', 'munmap', 'nice', 'off_t', 'pathconf', 'pause', - 'pid_t', 'pipe', 'posix_madvise', 'pread', 'profil', 'pwrite', - 'read', 'readlink', 'readlinkat', 'revoke', 'rmdir', 'sbrk', - 'setdomainname', 'setegid', 'seteuid', 'setgid', 'sethostid', - 'sethostname', 'setlogin', 'setpgid', 'setpgrp', 'setregid', - 'setreuid', 'setsid', 'setuid', 'setusershell', 'shm_open', - 'shm_unlink', 'size_t', 'sleep', 'socklen_t', 'ssize_t', - 'struct_c__SA_Elf32_Chdr', 'struct_c__SA_Elf32_Dyn', - 'struct_c__SA_Elf32_Ehdr', 'struct_c__SA_Elf32_Lib', - 'struct_c__SA_Elf32_Move', 'struct_c__SA_Elf32_Nhdr', - 'struct_c__SA_Elf32_Phdr', 'struct_c__SA_Elf32_RegInfo', - 'struct_c__SA_Elf32_Rel', 'struct_c__SA_Elf32_Rela', - 'struct_c__SA_Elf32_Shdr', 'struct_c__SA_Elf32_Sym', - 'struct_c__SA_Elf32_Syminfo', 'struct_c__SA_Elf32_Verdaux', - 'struct_c__SA_Elf32_Verdef', 'struct_c__SA_Elf32_Vernaux', - 'struct_c__SA_Elf32_Verneed', 'struct_c__SA_Elf32_auxv_t', - 'struct_c__SA_Elf64_Chdr', 'struct_c__SA_Elf64_Dyn', - 'struct_c__SA_Elf64_Ehdr', 'struct_c__SA_Elf64_Lib', - 'struct_c__SA_Elf64_Move', 'struct_c__SA_Elf64_Nhdr', - 'struct_c__SA_Elf64_Phdr', 'struct_c__SA_Elf64_Rel', - 'struct_c__SA_Elf64_Rela', 'struct_c__SA_Elf64_Shdr', - 'struct_c__SA_Elf64_Sym', 'struct_c__SA_Elf64_Syminfo', - 'struct_c__SA_Elf64_Verdaux', 'struct_c__SA_Elf64_Verdef', - 'struct_c__SA_Elf64_Vernaux', 'struct_c__SA_Elf64_Verneed', - 'struct_c__SA_Elf64_auxv_t', 'struct_c__SA_Elf_MIPS_ABIFlags_v0', - 'struct_c__SA_Elf_Options', 'struct_c__SA_Elf_Options_Hw', + '_POSIX2_VERSION', '_POSIX_VERSION', '_STRING_H', '_SYSCALL_H', + '_SYS_MMAN_H', '_UNISTD_H', '_XOPEN_ENH_I18N', '_XOPEN_LEGACY', + '_XOPEN_UNIX', '_XOPEN_VERSION', '_XOPEN_XCU_VERSION', + '_XOPEN_XPG2', '_XOPEN_XPG3', '_XOPEN_XPG4', + '__ASM_GENERIC_MMAN_COMMON_H', + '__GLIBC_INTERNAL_STARTING_HEADER_IMPLEMENTATION', + '__POSIX2_THIS_VERSION', '__environ', '__getpgid', '__gid_t', + '__gid_t_defined', '__intptr_t_defined', '__memcmpeq', + '__mode_t_defined', '__need_NULL', '__need_size_t', '__off_t', + '__off_t_defined', '__pid_t', '__pid_t_defined', + '__socklen_t_defined', '__ssize_t_defined', '__stpcpy', + '__stpncpy', '__strtok_r', '__uid_t', '__uid_t_defined', + '__useconds_t', '__useconds_t_defined', '_exit', 'access', 'acct', + 'alarm', 'brk', 'c__Ea_Val_GNU_MIPS_ABI_FP_ANY', 'chdir', 'chown', + 'chroot', 'close', 'closefrom', 'confstr', 'crypt', 'daemon', + 'dup', 'dup2', 'endusershell', 'execl', 'execle', 'execlp', + 'execv', 'execve', 'execvp', 'explicit_bzero', 'faccessat', + 'fchdir', 'fchown', 'fchownat', 'fdatasync', 'fexecve', 'fork', + 'fpathconf', 'fsync', 'ftruncate', 'getcwd', 'getdomainname', + 'getdtablesize', 'getegid', 'getentropy', 'geteuid', 'getgid', + 'getgroups', 'gethostid', 'gethostname', 'getlogin', 'getlogin_r', + 'getpagesize', 'getpass', 'getpgid', 'getpgrp', 'getpid', + 'getppid', 'getsid', 'getuid', 'getusershell', 'getwd', 'gid_t', + 'intptr_t', 'isatty', 'lchown', 'link', 'linkat', 'locale_t', + 'lockf', 'lseek', 'madvise', 'memccpy', 'memchr', 'memcmp', + 'memcpy', 'memmove', 'memset', 'mincore', 'mlock', 'mlockall', + 'mmap', 'mode_t', 'mprotect', 'msync', 'munlock', 'munlockall', + 'munmap', 'nice', 'off_t', 'pathconf', 'pause', 'pid_t', 'pipe', + 'posix_madvise', 'pread', 'profil', 'pwrite', 'read', 'readlink', + 'readlinkat', 'revoke', 'rmdir', 'sbrk', 'setdomainname', + 'setegid', 'seteuid', 'setgid', 'sethostid', 'sethostname', + 'setlogin', 'setpgid', 'setpgrp', 'setregid', 'setreuid', + 'setsid', 'setuid', 'setusershell', 'shm_open', 'shm_unlink', + 'size_t', 'sleep', 'socklen_t', 'ssize_t', 'stpcpy', 'stpncpy', + 'strcat', 'strchr', 'strcmp', 'strcoll', 'strcoll_l', 'strcpy', + 'strcspn', 'strdup', 'strerror', 'strerror_l', 'strerror_r', + 'strlen', 'strncat', 'strncmp', 'strncpy', 'strndup', 'strnlen', + 'strpbrk', 'strrchr', 'strsep', 'strsignal', 'strspn', 'strstr', + 'strtok', 'strtok_r', 'struct___locale_data', + 'struct___locale_struct', 'struct_c__SA_Elf32_Chdr', + 'struct_c__SA_Elf32_Dyn', 'struct_c__SA_Elf32_Ehdr', + 'struct_c__SA_Elf32_Lib', 'struct_c__SA_Elf32_Move', + 'struct_c__SA_Elf32_Nhdr', 'struct_c__SA_Elf32_Phdr', + 'struct_c__SA_Elf32_RegInfo', 'struct_c__SA_Elf32_Rel', + 'struct_c__SA_Elf32_Rela', 'struct_c__SA_Elf32_Shdr', + 'struct_c__SA_Elf32_Sym', 'struct_c__SA_Elf32_Syminfo', + 'struct_c__SA_Elf32_Verdaux', 'struct_c__SA_Elf32_Verdef', + 'struct_c__SA_Elf32_Vernaux', 'struct_c__SA_Elf32_Verneed', + 'struct_c__SA_Elf32_auxv_t', 'struct_c__SA_Elf64_Chdr', + 'struct_c__SA_Elf64_Dyn', 'struct_c__SA_Elf64_Ehdr', + 'struct_c__SA_Elf64_Lib', 'struct_c__SA_Elf64_Move', + 'struct_c__SA_Elf64_Nhdr', 'struct_c__SA_Elf64_Phdr', + 'struct_c__SA_Elf64_Rel', 'struct_c__SA_Elf64_Rela', + 'struct_c__SA_Elf64_Shdr', 'struct_c__SA_Elf64_Sym', + 'struct_c__SA_Elf64_Syminfo', 'struct_c__SA_Elf64_Verdaux', + 'struct_c__SA_Elf64_Verdef', 'struct_c__SA_Elf64_Vernaux', + 'struct_c__SA_Elf64_Verneed', 'struct_c__SA_Elf64_auxv_t', + 'struct_c__SA_Elf_MIPS_ABIFlags_v0', 'struct_c__SA_Elf_Options', + 'struct_c__SA_Elf_Options_Hw', 'struct_c__UA_Elf32_gptab_gt_entry', - 'struct_c__UA_Elf32_gptab_gt_header', 'symlink', 'symlinkat', - 'sync', 'syscall', 'sysconf', 'tcgetpgrp', 'tcsetpgrp', - 'truncate', 'ttyname', 'ttyname_r', 'ttyslot', 'ualarm', 'uid_t', - 'union_c__SA_Elf32_Dyn_d_un', 'union_c__SA_Elf32_auxv_t_a_un', - 'union_c__SA_Elf64_Dyn_d_un', 'union_c__SA_Elf64_auxv_t_a_un', - 'union_c__UA_Elf32_gptab', 'unlink', 'unlinkat', 'useconds_t', - 'usleep', 'vfork', 'vhangup', 'write'] + 'struct_c__UA_Elf32_gptab_gt_header', 'strxfrm', 'strxfrm_l', + 'symlink', 'symlinkat', 'sync', 'syscall', 'sysconf', 'tcgetpgrp', + 'tcsetpgrp', 'truncate', 'ttyname', 'ttyname_r', 'ttyslot', + 'ualarm', 'uid_t', 'union_c__SA_Elf32_Dyn_d_un', + 'union_c__SA_Elf32_auxv_t_a_un', 'union_c__SA_Elf64_Dyn_d_un', + 'union_c__SA_Elf64_auxv_t_a_un', 'union_c__UA_Elf32_gptab', + 'unlink', 'unlinkat', 'useconds_t', 'usleep', 'vfork', 'vhangup', + 'write'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/libusb.py b/tinygrad_repo/tinygrad/runtime/autogen/libusb.py new file mode 100644 index 0000000000..c516ef6de1 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/libusb.py @@ -0,0 +1,1643 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes, os + + +class FunctionFactoryStub: + def __getattr__(self, _): + return ctypes.CFUNCTYPE(lambda y:y) + +# libraries['libusb'] explanation +# As you did not list (-l libraryname.so) a library that exports this function +# This is a non-working stub instead. +# You can either re-run clan2py with -l /path/to/library.so +# Or manually fix this by comment the ctypes.CDLL loading +_libraries = {} +_libraries['libusb'] = None if (lib_path:=os.getenv('LIBUSB_PATH', ctypes.util.find_library('usb-1.0'))) is None else ctypes.CDLL(lib_path) # ctypes.CDLL('libusb') +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +def string_cast(char_pointer, encoding='utf-8', errors='strict'): + value = ctypes.cast(char_pointer, ctypes.c_char_p).value + if value is not None and encoding is not None: + value = value.decode(encoding, errors=errors) + return value + + +def char_pointer_cast(string, encoding='utf-8'): + if encoding is not None: + try: + string = string.encode(encoding) + except AttributeError: + # In Python3, bytes has no encode attribute + pass + string = ctypes.c_char_p(string) + return ctypes.cast(string, ctypes.POINTER(ctypes.c_char)) + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +LIBUSB_H = True # macro +ZERO_SIZED_ARRAY = True # macro +# def LIBUSB_DEPRECATED_FOR(f): # macro +# return ((deprecated)) +# LIBUSB_PACKED = ((packed)) # macro +LIBUSB_CALL = True # macro +LIBUSB_API_VERSION = 0x01000109 # macro +LIBUSBX_API_VERSION = 0x01000109 # macro +LIBUSB_DT_DEVICE_SIZE = 18 # macro +LIBUSB_DT_CONFIG_SIZE = 9 # macro +LIBUSB_DT_INTERFACE_SIZE = 9 # macro +LIBUSB_DT_ENDPOINT_SIZE = 7 # macro +LIBUSB_DT_ENDPOINT_AUDIO_SIZE = 9 # macro +LIBUSB_DT_HUB_NONVAR_SIZE = 7 # macro +LIBUSB_DT_SS_ENDPOINT_COMPANION_SIZE = 6 # macro +LIBUSB_DT_BOS_SIZE = 5 # macro +LIBUSB_DT_DEVICE_CAPABILITY_SIZE = 3 # macro +LIBUSB_BT_USB_2_0_EXTENSION_SIZE = 7 # macro +LIBUSB_BT_SS_USB_DEVICE_CAPABILITY_SIZE = 10 # macro +LIBUSB_BT_CONTAINER_ID_SIZE = 20 # macro +LIBUSB_DT_BOS_MAX_SIZE = (5+7+10+20) # macro +LIBUSB_ENDPOINT_ADDRESS_MASK = 0x0f # macro +LIBUSB_ENDPOINT_DIR_MASK = 0x80 # macro +LIBUSB_TRANSFER_TYPE_MASK = 0x03 # macro +LIBUSB_ISO_SYNC_TYPE_MASK = 0x0c # macro +LIBUSB_ISO_USAGE_TYPE_MASK = 0x30 # macro +LIBUSB_ERROR_COUNT = 14 # macro +LIBUSB_HOTPLUG_NO_FLAGS = 0 # macro +LIBUSB_HOTPLUG_MATCH_ANY = -1 # macro +uint16_t = ctypes.c_uint16 +try: + libusb_cpu_to_le16 = _libraries['libusb'].libusb_cpu_to_le16 + libusb_cpu_to_le16.restype = uint16_t + libusb_cpu_to_le16.argtypes = [uint16_t] +except AttributeError: + pass + # macro + +# values for enumeration 'libusb_class_code' +libusb_class_code__enumvalues = { + 0: 'LIBUSB_CLASS_PER_INTERFACE', + 1: 'LIBUSB_CLASS_AUDIO', + 2: 'LIBUSB_CLASS_COMM', + 3: 'LIBUSB_CLASS_HID', + 5: 'LIBUSB_CLASS_PHYSICAL', + 6: 'LIBUSB_CLASS_IMAGE', + 6: 'LIBUSB_CLASS_PTP', + 7: 'LIBUSB_CLASS_PRINTER', + 8: 'LIBUSB_CLASS_MASS_STORAGE', + 9: 'LIBUSB_CLASS_HUB', + 10: 'LIBUSB_CLASS_DATA', + 11: 'LIBUSB_CLASS_SMART_CARD', + 13: 'LIBUSB_CLASS_CONTENT_SECURITY', + 14: 'LIBUSB_CLASS_VIDEO', + 15: 'LIBUSB_CLASS_PERSONAL_HEALTHCARE', + 220: 'LIBUSB_CLASS_DIAGNOSTIC_DEVICE', + 224: 'LIBUSB_CLASS_WIRELESS', + 239: 'LIBUSB_CLASS_MISCELLANEOUS', + 254: 'LIBUSB_CLASS_APPLICATION', + 255: 'LIBUSB_CLASS_VENDOR_SPEC', +} +LIBUSB_CLASS_PER_INTERFACE = 0 +LIBUSB_CLASS_AUDIO = 1 +LIBUSB_CLASS_COMM = 2 +LIBUSB_CLASS_HID = 3 +LIBUSB_CLASS_PHYSICAL = 5 +LIBUSB_CLASS_IMAGE = 6 +LIBUSB_CLASS_PTP = 6 +LIBUSB_CLASS_PRINTER = 7 +LIBUSB_CLASS_MASS_STORAGE = 8 +LIBUSB_CLASS_HUB = 9 +LIBUSB_CLASS_DATA = 10 +LIBUSB_CLASS_SMART_CARD = 11 +LIBUSB_CLASS_CONTENT_SECURITY = 13 +LIBUSB_CLASS_VIDEO = 14 +LIBUSB_CLASS_PERSONAL_HEALTHCARE = 15 +LIBUSB_CLASS_DIAGNOSTIC_DEVICE = 220 +LIBUSB_CLASS_WIRELESS = 224 +LIBUSB_CLASS_MISCELLANEOUS = 239 +LIBUSB_CLASS_APPLICATION = 254 +LIBUSB_CLASS_VENDOR_SPEC = 255 +libusb_class_code = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_descriptor_type' +libusb_descriptor_type__enumvalues = { + 1: 'LIBUSB_DT_DEVICE', + 2: 'LIBUSB_DT_CONFIG', + 3: 'LIBUSB_DT_STRING', + 4: 'LIBUSB_DT_INTERFACE', + 5: 'LIBUSB_DT_ENDPOINT', + 15: 'LIBUSB_DT_BOS', + 16: 'LIBUSB_DT_DEVICE_CAPABILITY', + 33: 'LIBUSB_DT_HID', + 34: 'LIBUSB_DT_REPORT', + 35: 'LIBUSB_DT_PHYSICAL', + 41: 'LIBUSB_DT_HUB', + 42: 'LIBUSB_DT_SUPERSPEED_HUB', + 48: 'LIBUSB_DT_SS_ENDPOINT_COMPANION', +} +LIBUSB_DT_DEVICE = 1 +LIBUSB_DT_CONFIG = 2 +LIBUSB_DT_STRING = 3 +LIBUSB_DT_INTERFACE = 4 +LIBUSB_DT_ENDPOINT = 5 +LIBUSB_DT_BOS = 15 +LIBUSB_DT_DEVICE_CAPABILITY = 16 +LIBUSB_DT_HID = 33 +LIBUSB_DT_REPORT = 34 +LIBUSB_DT_PHYSICAL = 35 +LIBUSB_DT_HUB = 41 +LIBUSB_DT_SUPERSPEED_HUB = 42 +LIBUSB_DT_SS_ENDPOINT_COMPANION = 48 +libusb_descriptor_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_endpoint_direction' +libusb_endpoint_direction__enumvalues = { + 0: 'LIBUSB_ENDPOINT_OUT', + 128: 'LIBUSB_ENDPOINT_IN', +} +LIBUSB_ENDPOINT_OUT = 0 +LIBUSB_ENDPOINT_IN = 128 +libusb_endpoint_direction = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_endpoint_transfer_type' +libusb_endpoint_transfer_type__enumvalues = { + 0: 'LIBUSB_ENDPOINT_TRANSFER_TYPE_CONTROL', + 1: 'LIBUSB_ENDPOINT_TRANSFER_TYPE_ISOCHRONOUS', + 2: 'LIBUSB_ENDPOINT_TRANSFER_TYPE_BULK', + 3: 'LIBUSB_ENDPOINT_TRANSFER_TYPE_INTERRUPT', +} +LIBUSB_ENDPOINT_TRANSFER_TYPE_CONTROL = 0 +LIBUSB_ENDPOINT_TRANSFER_TYPE_ISOCHRONOUS = 1 +LIBUSB_ENDPOINT_TRANSFER_TYPE_BULK = 2 +LIBUSB_ENDPOINT_TRANSFER_TYPE_INTERRUPT = 3 +libusb_endpoint_transfer_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_standard_request' +libusb_standard_request__enumvalues = { + 0: 'LIBUSB_REQUEST_GET_STATUS', + 1: 'LIBUSB_REQUEST_CLEAR_FEATURE', + 3: 'LIBUSB_REQUEST_SET_FEATURE', + 5: 'LIBUSB_REQUEST_SET_ADDRESS', + 6: 'LIBUSB_REQUEST_GET_DESCRIPTOR', + 7: 'LIBUSB_REQUEST_SET_DESCRIPTOR', + 8: 'LIBUSB_REQUEST_GET_CONFIGURATION', + 9: 'LIBUSB_REQUEST_SET_CONFIGURATION', + 10: 'LIBUSB_REQUEST_GET_INTERFACE', + 11: 'LIBUSB_REQUEST_SET_INTERFACE', + 12: 'LIBUSB_REQUEST_SYNCH_FRAME', + 48: 'LIBUSB_REQUEST_SET_SEL', + 49: 'LIBUSB_SET_ISOCH_DELAY', +} +LIBUSB_REQUEST_GET_STATUS = 0 +LIBUSB_REQUEST_CLEAR_FEATURE = 1 +LIBUSB_REQUEST_SET_FEATURE = 3 +LIBUSB_REQUEST_SET_ADDRESS = 5 +LIBUSB_REQUEST_GET_DESCRIPTOR = 6 +LIBUSB_REQUEST_SET_DESCRIPTOR = 7 +LIBUSB_REQUEST_GET_CONFIGURATION = 8 +LIBUSB_REQUEST_SET_CONFIGURATION = 9 +LIBUSB_REQUEST_GET_INTERFACE = 10 +LIBUSB_REQUEST_SET_INTERFACE = 11 +LIBUSB_REQUEST_SYNCH_FRAME = 12 +LIBUSB_REQUEST_SET_SEL = 48 +LIBUSB_SET_ISOCH_DELAY = 49 +libusb_standard_request = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_request_type' +libusb_request_type__enumvalues = { + 0: 'LIBUSB_REQUEST_TYPE_STANDARD', + 32: 'LIBUSB_REQUEST_TYPE_CLASS', + 64: 'LIBUSB_REQUEST_TYPE_VENDOR', + 96: 'LIBUSB_REQUEST_TYPE_RESERVED', +} +LIBUSB_REQUEST_TYPE_STANDARD = 0 +LIBUSB_REQUEST_TYPE_CLASS = 32 +LIBUSB_REQUEST_TYPE_VENDOR = 64 +LIBUSB_REQUEST_TYPE_RESERVED = 96 +libusb_request_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_request_recipient' +libusb_request_recipient__enumvalues = { + 0: 'LIBUSB_RECIPIENT_DEVICE', + 1: 'LIBUSB_RECIPIENT_INTERFACE', + 2: 'LIBUSB_RECIPIENT_ENDPOINT', + 3: 'LIBUSB_RECIPIENT_OTHER', +} +LIBUSB_RECIPIENT_DEVICE = 0 +LIBUSB_RECIPIENT_INTERFACE = 1 +LIBUSB_RECIPIENT_ENDPOINT = 2 +LIBUSB_RECIPIENT_OTHER = 3 +libusb_request_recipient = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_iso_sync_type' +libusb_iso_sync_type__enumvalues = { + 0: 'LIBUSB_ISO_SYNC_TYPE_NONE', + 1: 'LIBUSB_ISO_SYNC_TYPE_ASYNC', + 2: 'LIBUSB_ISO_SYNC_TYPE_ADAPTIVE', + 3: 'LIBUSB_ISO_SYNC_TYPE_SYNC', +} +LIBUSB_ISO_SYNC_TYPE_NONE = 0 +LIBUSB_ISO_SYNC_TYPE_ASYNC = 1 +LIBUSB_ISO_SYNC_TYPE_ADAPTIVE = 2 +LIBUSB_ISO_SYNC_TYPE_SYNC = 3 +libusb_iso_sync_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_iso_usage_type' +libusb_iso_usage_type__enumvalues = { + 0: 'LIBUSB_ISO_USAGE_TYPE_DATA', + 1: 'LIBUSB_ISO_USAGE_TYPE_FEEDBACK', + 2: 'LIBUSB_ISO_USAGE_TYPE_IMPLICIT', +} +LIBUSB_ISO_USAGE_TYPE_DATA = 0 +LIBUSB_ISO_USAGE_TYPE_FEEDBACK = 1 +LIBUSB_ISO_USAGE_TYPE_IMPLICIT = 2 +libusb_iso_usage_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_supported_speed' +libusb_supported_speed__enumvalues = { + 1: 'LIBUSB_LOW_SPEED_OPERATION', + 2: 'LIBUSB_FULL_SPEED_OPERATION', + 4: 'LIBUSB_HIGH_SPEED_OPERATION', + 8: 'LIBUSB_SUPER_SPEED_OPERATION', +} +LIBUSB_LOW_SPEED_OPERATION = 1 +LIBUSB_FULL_SPEED_OPERATION = 2 +LIBUSB_HIGH_SPEED_OPERATION = 4 +LIBUSB_SUPER_SPEED_OPERATION = 8 +libusb_supported_speed = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_usb_2_0_extension_attributes' +libusb_usb_2_0_extension_attributes__enumvalues = { + 2: 'LIBUSB_BM_LPM_SUPPORT', +} +LIBUSB_BM_LPM_SUPPORT = 2 +libusb_usb_2_0_extension_attributes = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_ss_usb_device_capability_attributes' +libusb_ss_usb_device_capability_attributes__enumvalues = { + 2: 'LIBUSB_BM_LTM_SUPPORT', +} +LIBUSB_BM_LTM_SUPPORT = 2 +libusb_ss_usb_device_capability_attributes = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_bos_type' +libusb_bos_type__enumvalues = { + 1: 'LIBUSB_BT_WIRELESS_USB_DEVICE_CAPABILITY', + 2: 'LIBUSB_BT_USB_2_0_EXTENSION', + 3: 'LIBUSB_BT_SS_USB_DEVICE_CAPABILITY', + 4: 'LIBUSB_BT_CONTAINER_ID', +} +LIBUSB_BT_WIRELESS_USB_DEVICE_CAPABILITY = 1 +LIBUSB_BT_USB_2_0_EXTENSION = 2 +LIBUSB_BT_SS_USB_DEVICE_CAPABILITY = 3 +LIBUSB_BT_CONTAINER_ID = 4 +libusb_bos_type = ctypes.c_uint32 # enum +class struct_libusb_device_descriptor(Structure): + pass + +struct_libusb_device_descriptor._pack_ = 1 # source:False +struct_libusb_device_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bcdUSB', ctypes.c_uint16), + ('bDeviceClass', ctypes.c_ubyte), + ('bDeviceSubClass', ctypes.c_ubyte), + ('bDeviceProtocol', ctypes.c_ubyte), + ('bMaxPacketSize0', ctypes.c_ubyte), + ('idVendor', ctypes.c_uint16), + ('idProduct', ctypes.c_uint16), + ('bcdDevice', ctypes.c_uint16), + ('iManufacturer', ctypes.c_ubyte), + ('iProduct', ctypes.c_ubyte), + ('iSerialNumber', ctypes.c_ubyte), + ('bNumConfigurations', ctypes.c_ubyte), +] + +class struct_libusb_endpoint_descriptor(Structure): + pass + +struct_libusb_endpoint_descriptor._pack_ = 1 # source:False +struct_libusb_endpoint_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bEndpointAddress', ctypes.c_ubyte), + ('bmAttributes', ctypes.c_ubyte), + ('wMaxPacketSize', ctypes.c_uint16), + ('bInterval', ctypes.c_ubyte), + ('bRefresh', ctypes.c_ubyte), + ('bSynchAddress', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 7), + ('extra', ctypes.POINTER(ctypes.c_ubyte)), + ('extra_length', ctypes.c_int32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +class struct_libusb_interface_descriptor(Structure): + pass + +struct_libusb_interface_descriptor._pack_ = 1 # source:False +struct_libusb_interface_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bInterfaceNumber', ctypes.c_ubyte), + ('bAlternateSetting', ctypes.c_ubyte), + ('bNumEndpoints', ctypes.c_ubyte), + ('bInterfaceClass', ctypes.c_ubyte), + ('bInterfaceSubClass', ctypes.c_ubyte), + ('bInterfaceProtocol', ctypes.c_ubyte), + ('iInterface', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 7), + ('endpoint', ctypes.POINTER(struct_libusb_endpoint_descriptor)), + ('extra', ctypes.POINTER(ctypes.c_ubyte)), + ('extra_length', ctypes.c_int32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +class struct_libusb_interface(Structure): + pass + +struct_libusb_interface._pack_ = 1 # source:False +struct_libusb_interface._fields_ = [ + ('altsetting', ctypes.POINTER(struct_libusb_interface_descriptor)), + ('num_altsetting', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +class struct_libusb_config_descriptor(Structure): + pass + +struct_libusb_config_descriptor._pack_ = 1 # source:False +struct_libusb_config_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('wTotalLength', ctypes.c_uint16), + ('bNumInterfaces', ctypes.c_ubyte), + ('bConfigurationValue', ctypes.c_ubyte), + ('iConfiguration', ctypes.c_ubyte), + ('bmAttributes', ctypes.c_ubyte), + ('MaxPower', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 7), + ('interface', ctypes.POINTER(struct_libusb_interface)), + ('extra', ctypes.POINTER(ctypes.c_ubyte)), + ('extra_length', ctypes.c_int32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +class struct_libusb_ss_endpoint_companion_descriptor(Structure): + pass + +struct_libusb_ss_endpoint_companion_descriptor._pack_ = 1 # source:False +struct_libusb_ss_endpoint_companion_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bMaxBurst', ctypes.c_ubyte), + ('bmAttributes', ctypes.c_ubyte), + ('wBytesPerInterval', ctypes.c_uint16), +] + +class struct_libusb_bos_dev_capability_descriptor(Structure): + pass + +struct_libusb_bos_dev_capability_descriptor._pack_ = 1 # source:False +struct_libusb_bos_dev_capability_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bDevCapabilityType', ctypes.c_ubyte), + ('dev_capability_data', ctypes.c_ubyte * 0), +] + +class struct_libusb_bos_descriptor(Structure): + pass + +struct_libusb_bos_descriptor._pack_ = 1 # source:False +struct_libusb_bos_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('wTotalLength', ctypes.c_uint16), + ('bNumDeviceCaps', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte * 3), + ('dev_capability', ctypes.POINTER(struct_libusb_bos_dev_capability_descriptor) * 0), +] + +class struct_libusb_usb_2_0_extension_descriptor(Structure): + pass + +struct_libusb_usb_2_0_extension_descriptor._pack_ = 1 # source:False +struct_libusb_usb_2_0_extension_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bDevCapabilityType', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte), + ('bmAttributes', ctypes.c_uint32), +] + +class struct_libusb_ss_usb_device_capability_descriptor(Structure): + pass + +struct_libusb_ss_usb_device_capability_descriptor._pack_ = 1 # source:False +struct_libusb_ss_usb_device_capability_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bDevCapabilityType', ctypes.c_ubyte), + ('bmAttributes', ctypes.c_ubyte), + ('wSpeedSupported', ctypes.c_uint16), + ('bFunctionalitySupport', ctypes.c_ubyte), + ('bU1DevExitLat', ctypes.c_ubyte), + ('bU2DevExitLat', ctypes.c_uint16), +] + +class struct_libusb_container_id_descriptor(Structure): + pass + +struct_libusb_container_id_descriptor._pack_ = 1 # source:False +struct_libusb_container_id_descriptor._fields_ = [ + ('bLength', ctypes.c_ubyte), + ('bDescriptorType', ctypes.c_ubyte), + ('bDevCapabilityType', ctypes.c_ubyte), + ('bReserved', ctypes.c_ubyte), + ('ContainerID', ctypes.c_ubyte * 16), +] + +class struct_libusb_control_setup(Structure): + pass + +struct_libusb_control_setup._pack_ = 1 # source:True +struct_libusb_control_setup._fields_ = [ + ('bmRequestType', ctypes.c_ubyte), + ('bRequest', ctypes.c_ubyte), + ('wValue', ctypes.c_uint16), + ('wIndex', ctypes.c_uint16), + ('wLength', ctypes.c_uint16), +] + +# LIBUSB_CONTROL_SETUP_SIZE = (ctypes.sizeof(struct_libusb_control_setup)) # macro +class struct_libusb_context(Structure): + pass + +class struct_libusb_device(Structure): + pass + +class struct_libusb_device_handle(Structure): + pass + +class struct_libusb_version(Structure): + pass + +struct_libusb_version._pack_ = 1 # source:False +struct_libusb_version._fields_ = [ + ('major', ctypes.c_uint16), + ('minor', ctypes.c_uint16), + ('micro', ctypes.c_uint16), + ('nano', ctypes.c_uint16), + ('rc', ctypes.POINTER(ctypes.c_char)), + ('describe', ctypes.POINTER(ctypes.c_char)), +] + +libusb_context = struct_libusb_context +libusb_device = struct_libusb_device +libusb_device_handle = struct_libusb_device_handle + +# values for enumeration 'libusb_speed' +libusb_speed__enumvalues = { + 0: 'LIBUSB_SPEED_UNKNOWN', + 1: 'LIBUSB_SPEED_LOW', + 2: 'LIBUSB_SPEED_FULL', + 3: 'LIBUSB_SPEED_HIGH', + 4: 'LIBUSB_SPEED_SUPER', + 5: 'LIBUSB_SPEED_SUPER_PLUS', +} +LIBUSB_SPEED_UNKNOWN = 0 +LIBUSB_SPEED_LOW = 1 +LIBUSB_SPEED_FULL = 2 +LIBUSB_SPEED_HIGH = 3 +LIBUSB_SPEED_SUPER = 4 +LIBUSB_SPEED_SUPER_PLUS = 5 +libusb_speed = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_error' +libusb_error__enumvalues = { + 0: 'LIBUSB_SUCCESS', + -1: 'LIBUSB_ERROR_IO', + -2: 'LIBUSB_ERROR_INVALID_PARAM', + -3: 'LIBUSB_ERROR_ACCESS', + -4: 'LIBUSB_ERROR_NO_DEVICE', + -5: 'LIBUSB_ERROR_NOT_FOUND', + -6: 'LIBUSB_ERROR_BUSY', + -7: 'LIBUSB_ERROR_TIMEOUT', + -8: 'LIBUSB_ERROR_OVERFLOW', + -9: 'LIBUSB_ERROR_PIPE', + -10: 'LIBUSB_ERROR_INTERRUPTED', + -11: 'LIBUSB_ERROR_NO_MEM', + -12: 'LIBUSB_ERROR_NOT_SUPPORTED', + -99: 'LIBUSB_ERROR_OTHER', +} +LIBUSB_SUCCESS = 0 +LIBUSB_ERROR_IO = -1 +LIBUSB_ERROR_INVALID_PARAM = -2 +LIBUSB_ERROR_ACCESS = -3 +LIBUSB_ERROR_NO_DEVICE = -4 +LIBUSB_ERROR_NOT_FOUND = -5 +LIBUSB_ERROR_BUSY = -6 +LIBUSB_ERROR_TIMEOUT = -7 +LIBUSB_ERROR_OVERFLOW = -8 +LIBUSB_ERROR_PIPE = -9 +LIBUSB_ERROR_INTERRUPTED = -10 +LIBUSB_ERROR_NO_MEM = -11 +LIBUSB_ERROR_NOT_SUPPORTED = -12 +LIBUSB_ERROR_OTHER = -99 +libusb_error = ctypes.c_int32 # enum + +# values for enumeration 'libusb_transfer_type' +libusb_transfer_type__enumvalues = { + 0: 'LIBUSB_TRANSFER_TYPE_CONTROL', + 1: 'LIBUSB_TRANSFER_TYPE_ISOCHRONOUS', + 2: 'LIBUSB_TRANSFER_TYPE_BULK', + 3: 'LIBUSB_TRANSFER_TYPE_INTERRUPT', + 4: 'LIBUSB_TRANSFER_TYPE_BULK_STREAM', +} +LIBUSB_TRANSFER_TYPE_CONTROL = 0 +LIBUSB_TRANSFER_TYPE_ISOCHRONOUS = 1 +LIBUSB_TRANSFER_TYPE_BULK = 2 +LIBUSB_TRANSFER_TYPE_INTERRUPT = 3 +LIBUSB_TRANSFER_TYPE_BULK_STREAM = 4 +libusb_transfer_type = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_transfer_status' +libusb_transfer_status__enumvalues = { + 0: 'LIBUSB_TRANSFER_COMPLETED', + 1: 'LIBUSB_TRANSFER_ERROR', + 2: 'LIBUSB_TRANSFER_TIMED_OUT', + 3: 'LIBUSB_TRANSFER_CANCELLED', + 4: 'LIBUSB_TRANSFER_STALL', + 5: 'LIBUSB_TRANSFER_NO_DEVICE', + 6: 'LIBUSB_TRANSFER_OVERFLOW', +} +LIBUSB_TRANSFER_COMPLETED = 0 +LIBUSB_TRANSFER_ERROR = 1 +LIBUSB_TRANSFER_TIMED_OUT = 2 +LIBUSB_TRANSFER_CANCELLED = 3 +LIBUSB_TRANSFER_STALL = 4 +LIBUSB_TRANSFER_NO_DEVICE = 5 +LIBUSB_TRANSFER_OVERFLOW = 6 +libusb_transfer_status = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_transfer_flags' +libusb_transfer_flags__enumvalues = { + 1: 'LIBUSB_TRANSFER_SHORT_NOT_OK', + 2: 'LIBUSB_TRANSFER_FREE_BUFFER', + 4: 'LIBUSB_TRANSFER_FREE_TRANSFER', + 8: 'LIBUSB_TRANSFER_ADD_ZERO_PACKET', +} +LIBUSB_TRANSFER_SHORT_NOT_OK = 1 +LIBUSB_TRANSFER_FREE_BUFFER = 2 +LIBUSB_TRANSFER_FREE_TRANSFER = 4 +LIBUSB_TRANSFER_ADD_ZERO_PACKET = 8 +libusb_transfer_flags = ctypes.c_uint32 # enum +class struct_libusb_iso_packet_descriptor(Structure): + pass + +struct_libusb_iso_packet_descriptor._pack_ = 1 # source:False +struct_libusb_iso_packet_descriptor._fields_ = [ + ('length', ctypes.c_uint32), + ('actual_length', ctypes.c_uint32), + ('status', libusb_transfer_status), +] + +class struct_libusb_transfer(Structure): + pass + +libusb_transfer_cb_fn = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_libusb_transfer)) + +# values for enumeration 'libusb_capability' +libusb_capability__enumvalues = { + 0: 'LIBUSB_CAP_HAS_CAPABILITY', + 1: 'LIBUSB_CAP_HAS_HOTPLUG', + 256: 'LIBUSB_CAP_HAS_HID_ACCESS', + 257: 'LIBUSB_CAP_SUPPORTS_DETACH_KERNEL_DRIVER', +} +LIBUSB_CAP_HAS_CAPABILITY = 0 +LIBUSB_CAP_HAS_HOTPLUG = 1 +LIBUSB_CAP_HAS_HID_ACCESS = 256 +LIBUSB_CAP_SUPPORTS_DETACH_KERNEL_DRIVER = 257 +libusb_capability = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_log_level' +libusb_log_level__enumvalues = { + 0: 'LIBUSB_LOG_LEVEL_NONE', + 1: 'LIBUSB_LOG_LEVEL_ERROR', + 2: 'LIBUSB_LOG_LEVEL_WARNING', + 3: 'LIBUSB_LOG_LEVEL_INFO', + 4: 'LIBUSB_LOG_LEVEL_DEBUG', +} +LIBUSB_LOG_LEVEL_NONE = 0 +LIBUSB_LOG_LEVEL_ERROR = 1 +LIBUSB_LOG_LEVEL_WARNING = 2 +LIBUSB_LOG_LEVEL_INFO = 3 +LIBUSB_LOG_LEVEL_DEBUG = 4 +libusb_log_level = ctypes.c_uint32 # enum + +# values for enumeration 'libusb_log_cb_mode' +libusb_log_cb_mode__enumvalues = { + 1: 'LIBUSB_LOG_CB_GLOBAL', + 2: 'LIBUSB_LOG_CB_CONTEXT', +} +LIBUSB_LOG_CB_GLOBAL = 1 +LIBUSB_LOG_CB_CONTEXT = 2 +libusb_log_cb_mode = ctypes.c_uint32 # enum +libusb_log_cb = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_libusb_context), libusb_log_level, ctypes.POINTER(ctypes.c_char)) +try: + libusb_init = _libraries['libusb'].libusb_init + libusb_init.restype = ctypes.c_int32 + libusb_init.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_libusb_context))] +except AttributeError: + pass +try: + libusb_exit = _libraries['libusb'].libusb_exit + libusb_exit.restype = None + libusb_exit.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_set_debug = _libraries['libusb'].libusb_set_debug + libusb_set_debug.restype = None + libusb_set_debug.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_set_log_cb = _libraries['libusb'].libusb_set_log_cb + libusb_set_log_cb.restype = None + libusb_set_log_cb.argtypes = [ctypes.POINTER(struct_libusb_context), libusb_log_cb, ctypes.c_int32] +except AttributeError: + pass +try: + libusb_get_version = _libraries['libusb'].libusb_get_version + libusb_get_version.restype = ctypes.POINTER(struct_libusb_version) + libusb_get_version.argtypes = [] +except AttributeError: + pass +uint32_t = ctypes.c_uint32 +try: + libusb_has_capability = _libraries['libusb'].libusb_has_capability + libusb_has_capability.restype = ctypes.c_int32 + libusb_has_capability.argtypes = [uint32_t] +except AttributeError: + pass +try: + libusb_error_name = _libraries['libusb'].libusb_error_name + libusb_error_name.restype = ctypes.POINTER(ctypes.c_char) + libusb_error_name.argtypes = [ctypes.c_int32] +except AttributeError: + pass +try: + libusb_setlocale = _libraries['libusb'].libusb_setlocale + libusb_setlocale.restype = ctypes.c_int32 + libusb_setlocale.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + libusb_strerror = _libraries['libusb'].libusb_strerror + libusb_strerror.restype = ctypes.POINTER(ctypes.c_char) + libusb_strerror.argtypes = [ctypes.c_int32] +except AttributeError: + pass +ssize_t = ctypes.c_int64 +try: + libusb_get_device_list = _libraries['libusb'].libusb_get_device_list + libusb_get_device_list.restype = ssize_t + libusb_get_device_list.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(ctypes.POINTER(ctypes.POINTER(struct_libusb_device)))] +except AttributeError: + pass +try: + libusb_free_device_list = _libraries['libusb'].libusb_free_device_list + libusb_free_device_list.restype = None + libusb_free_device_list.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_libusb_device)), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_ref_device = _libraries['libusb'].libusb_ref_device + libusb_ref_device.restype = ctypes.POINTER(struct_libusb_device) + libusb_ref_device.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_unref_device = _libraries['libusb'].libusb_unref_device + libusb_unref_device.restype = None + libusb_unref_device.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_configuration = _libraries['libusb'].libusb_get_configuration + libusb_get_configuration.restype = ctypes.c_int32 + libusb_get_configuration.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.POINTER(ctypes.c_int32)] +except AttributeError: + pass +try: + libusb_get_device_descriptor = _libraries['libusb'].libusb_get_device_descriptor + libusb_get_device_descriptor.restype = ctypes.c_int32 + libusb_get_device_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.POINTER(struct_libusb_device_descriptor)] +except AttributeError: + pass +try: + libusb_get_active_config_descriptor = _libraries['libusb'].libusb_get_active_config_descriptor + libusb_get_active_config_descriptor.restype = ctypes.c_int32 + libusb_get_active_config_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.POINTER(ctypes.POINTER(struct_libusb_config_descriptor))] +except AttributeError: + pass +uint8_t = ctypes.c_uint8 +try: + libusb_get_config_descriptor = _libraries['libusb'].libusb_get_config_descriptor + libusb_get_config_descriptor.restype = ctypes.c_int32 + libusb_get_config_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device), uint8_t, ctypes.POINTER(ctypes.POINTER(struct_libusb_config_descriptor))] +except AttributeError: + pass +try: + libusb_get_config_descriptor_by_value = _libraries['libusb'].libusb_get_config_descriptor_by_value + libusb_get_config_descriptor_by_value.restype = ctypes.c_int32 + libusb_get_config_descriptor_by_value.argtypes = [ctypes.POINTER(struct_libusb_device), uint8_t, ctypes.POINTER(ctypes.POINTER(struct_libusb_config_descriptor))] +except AttributeError: + pass +try: + libusb_free_config_descriptor = _libraries['libusb'].libusb_free_config_descriptor + libusb_free_config_descriptor.restype = None + libusb_free_config_descriptor.argtypes = [ctypes.POINTER(struct_libusb_config_descriptor)] +except AttributeError: + pass +try: + libusb_get_ss_endpoint_companion_descriptor = _libraries['libusb'].libusb_get_ss_endpoint_companion_descriptor + libusb_get_ss_endpoint_companion_descriptor.restype = ctypes.c_int32 + libusb_get_ss_endpoint_companion_descriptor.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_endpoint_descriptor), ctypes.POINTER(ctypes.POINTER(struct_libusb_ss_endpoint_companion_descriptor))] +except AttributeError: + pass +try: + libusb_free_ss_endpoint_companion_descriptor = _libraries['libusb'].libusb_free_ss_endpoint_companion_descriptor + libusb_free_ss_endpoint_companion_descriptor.restype = None + libusb_free_ss_endpoint_companion_descriptor.argtypes = [ctypes.POINTER(struct_libusb_ss_endpoint_companion_descriptor)] +except AttributeError: + pass +try: + libusb_get_bos_descriptor = _libraries['libusb'].libusb_get_bos_descriptor + libusb_get_bos_descriptor.restype = ctypes.c_int32 + libusb_get_bos_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.POINTER(ctypes.POINTER(struct_libusb_bos_descriptor))] +except AttributeError: + pass +try: + libusb_free_bos_descriptor = _libraries['libusb'].libusb_free_bos_descriptor + libusb_free_bos_descriptor.restype = None + libusb_free_bos_descriptor.argtypes = [ctypes.POINTER(struct_libusb_bos_descriptor)] +except AttributeError: + pass +try: + libusb_get_usb_2_0_extension_descriptor = _libraries['libusb'].libusb_get_usb_2_0_extension_descriptor + libusb_get_usb_2_0_extension_descriptor.restype = ctypes.c_int32 + libusb_get_usb_2_0_extension_descriptor.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_bos_dev_capability_descriptor), ctypes.POINTER(ctypes.POINTER(struct_libusb_usb_2_0_extension_descriptor))] +except AttributeError: + pass +try: + libusb_free_usb_2_0_extension_descriptor = _libraries['libusb'].libusb_free_usb_2_0_extension_descriptor + libusb_free_usb_2_0_extension_descriptor.restype = None + libusb_free_usb_2_0_extension_descriptor.argtypes = [ctypes.POINTER(struct_libusb_usb_2_0_extension_descriptor)] +except AttributeError: + pass +try: + libusb_get_ss_usb_device_capability_descriptor = _libraries['libusb'].libusb_get_ss_usb_device_capability_descriptor + libusb_get_ss_usb_device_capability_descriptor.restype = ctypes.c_int32 + libusb_get_ss_usb_device_capability_descriptor.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_bos_dev_capability_descriptor), ctypes.POINTER(ctypes.POINTER(struct_libusb_ss_usb_device_capability_descriptor))] +except AttributeError: + pass +try: + libusb_free_ss_usb_device_capability_descriptor = _libraries['libusb'].libusb_free_ss_usb_device_capability_descriptor + libusb_free_ss_usb_device_capability_descriptor.restype = None + libusb_free_ss_usb_device_capability_descriptor.argtypes = [ctypes.POINTER(struct_libusb_ss_usb_device_capability_descriptor)] +except AttributeError: + pass +try: + libusb_get_container_id_descriptor = _libraries['libusb'].libusb_get_container_id_descriptor + libusb_get_container_id_descriptor.restype = ctypes.c_int32 + libusb_get_container_id_descriptor.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_bos_dev_capability_descriptor), ctypes.POINTER(ctypes.POINTER(struct_libusb_container_id_descriptor))] +except AttributeError: + pass +try: + libusb_free_container_id_descriptor = _libraries['libusb'].libusb_free_container_id_descriptor + libusb_free_container_id_descriptor.restype = None + libusb_free_container_id_descriptor.argtypes = [ctypes.POINTER(struct_libusb_container_id_descriptor)] +except AttributeError: + pass +try: + libusb_get_bus_number = _libraries['libusb'].libusb_get_bus_number + libusb_get_bus_number.restype = uint8_t + libusb_get_bus_number.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_port_number = _libraries['libusb'].libusb_get_port_number + libusb_get_port_number.restype = uint8_t + libusb_get_port_number.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_port_numbers = _libraries['libusb'].libusb_get_port_numbers + libusb_get_port_numbers.restype = ctypes.c_int32 + libusb_get_port_numbers.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_get_port_path = _libraries['libusb'].libusb_get_port_path + libusb_get_port_path.restype = ctypes.c_int32 + libusb_get_port_path.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_device), ctypes.POINTER(ctypes.c_ubyte), uint8_t] +except AttributeError: + pass +try: + libusb_get_parent = _libraries['libusb'].libusb_get_parent + libusb_get_parent.restype = ctypes.POINTER(struct_libusb_device) + libusb_get_parent.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_device_address = _libraries['libusb'].libusb_get_device_address + libusb_get_device_address.restype = uint8_t + libusb_get_device_address.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_device_speed = _libraries['libusb'].libusb_get_device_speed + libusb_get_device_speed.restype = ctypes.c_int32 + libusb_get_device_speed.argtypes = [ctypes.POINTER(struct_libusb_device)] +except AttributeError: + pass +try: + libusb_get_max_packet_size = _libraries['libusb'].libusb_get_max_packet_size + libusb_get_max_packet_size.restype = ctypes.c_int32 + libusb_get_max_packet_size.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.c_ubyte] +except AttributeError: + pass +try: + libusb_get_max_iso_packet_size = _libraries['libusb'].libusb_get_max_iso_packet_size + libusb_get_max_iso_packet_size.restype = ctypes.c_int32 + libusb_get_max_iso_packet_size.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.c_ubyte] +except AttributeError: + pass +intptr_t = ctypes.c_int64 +try: + libusb_wrap_sys_device = _libraries['libusb'].libusb_wrap_sys_device + libusb_wrap_sys_device.restype = ctypes.c_int32 + libusb_wrap_sys_device.argtypes = [ctypes.POINTER(struct_libusb_context), intptr_t, ctypes.POINTER(ctypes.POINTER(struct_libusb_device_handle))] +except AttributeError: + pass +try: + libusb_open = _libraries['libusb'].libusb_open + libusb_open.restype = ctypes.c_int32 + libusb_open.argtypes = [ctypes.POINTER(struct_libusb_device), ctypes.POINTER(ctypes.POINTER(struct_libusb_device_handle))] +except AttributeError: + pass +try: + libusb_close = _libraries['libusb'].libusb_close + libusb_close.restype = None + libusb_close.argtypes = [ctypes.POINTER(struct_libusb_device_handle)] +except AttributeError: + pass +try: + libusb_get_device = _libraries['libusb'].libusb_get_device + libusb_get_device.restype = ctypes.POINTER(struct_libusb_device) + libusb_get_device.argtypes = [ctypes.POINTER(struct_libusb_device_handle)] +except AttributeError: + pass +try: + libusb_set_configuration = _libraries['libusb'].libusb_set_configuration + libusb_set_configuration.restype = ctypes.c_int32 + libusb_set_configuration.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_claim_interface = _libraries['libusb'].libusb_claim_interface + libusb_claim_interface.restype = ctypes.c_int32 + libusb_claim_interface.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_release_interface = _libraries['libusb'].libusb_release_interface + libusb_release_interface.restype = ctypes.c_int32 + libusb_release_interface.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_open_device_with_vid_pid = _libraries['libusb'].libusb_open_device_with_vid_pid + libusb_open_device_with_vid_pid.restype = ctypes.POINTER(struct_libusb_device_handle) + libusb_open_device_with_vid_pid.argtypes = [ctypes.POINTER(struct_libusb_context), uint16_t, uint16_t] +except AttributeError: + pass +try: + libusb_set_interface_alt_setting = _libraries['libusb'].libusb_set_interface_alt_setting + libusb_set_interface_alt_setting.restype = ctypes.c_int32 + libusb_set_interface_alt_setting.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32, ctypes.c_int32] +except AttributeError: + pass +try: + libusb_clear_halt = _libraries['libusb'].libusb_clear_halt + libusb_clear_halt.restype = ctypes.c_int32 + libusb_clear_halt.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte] +except AttributeError: + pass +try: + libusb_reset_device = _libraries['libusb'].libusb_reset_device + libusb_reset_device.restype = ctypes.c_int32 + libusb_reset_device.argtypes = [ctypes.POINTER(struct_libusb_device_handle)] +except AttributeError: + pass +try: + libusb_alloc_streams = _libraries['libusb'].libusb_alloc_streams + libusb_alloc_streams.restype = ctypes.c_int32 + libusb_alloc_streams.argtypes = [ctypes.POINTER(struct_libusb_device_handle), uint32_t, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_free_streams = _libraries['libusb'].libusb_free_streams + libusb_free_streams.restype = ctypes.c_int32 + libusb_free_streams.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +size_t = ctypes.c_uint64 +try: + libusb_dev_mem_alloc = _libraries['libusb'].libusb_dev_mem_alloc + libusb_dev_mem_alloc.restype = ctypes.POINTER(ctypes.c_ubyte) + libusb_dev_mem_alloc.argtypes = [ctypes.POINTER(struct_libusb_device_handle), size_t] +except AttributeError: + pass +try: + libusb_dev_mem_free = _libraries['libusb'].libusb_dev_mem_free + libusb_dev_mem_free.restype = ctypes.c_int32 + libusb_dev_mem_free.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.POINTER(ctypes.c_ubyte), size_t] +except AttributeError: + pass +try: + libusb_kernel_driver_active = _libraries['libusb'].libusb_kernel_driver_active + libusb_kernel_driver_active.restype = ctypes.c_int32 + libusb_kernel_driver_active.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_detach_kernel_driver = _libraries['libusb'].libusb_detach_kernel_driver + libusb_detach_kernel_driver.restype = ctypes.c_int32 + libusb_detach_kernel_driver.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_attach_kernel_driver = _libraries['libusb'].libusb_attach_kernel_driver + libusb_attach_kernel_driver.restype = ctypes.c_int32 + libusb_attach_kernel_driver.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_set_auto_detach_kernel_driver = _libraries['libusb'].libusb_set_auto_detach_kernel_driver + libusb_set_auto_detach_kernel_driver.restype = ctypes.c_int32 + libusb_set_auto_detach_kernel_driver.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_control_transfer_get_data = _libraries['libusb'].libusb_control_transfer_get_data + libusb_control_transfer_get_data.restype = ctypes.POINTER(ctypes.c_ubyte) + libusb_control_transfer_get_data.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_control_transfer_get_setup = _libraries['libusb'].libusb_control_transfer_get_setup + libusb_control_transfer_get_setup.restype = ctypes.POINTER(struct_libusb_control_setup) + libusb_control_transfer_get_setup.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_fill_control_setup = _libraries['libusb'].libusb_fill_control_setup + libusb_fill_control_setup.restype = None + libusb_fill_control_setup.argtypes = [ctypes.POINTER(ctypes.c_ubyte), uint8_t, uint8_t, uint16_t, uint16_t, uint16_t] +except AttributeError: + pass +try: + libusb_alloc_transfer = _libraries['libusb'].libusb_alloc_transfer + libusb_alloc_transfer.restype = ctypes.POINTER(struct_libusb_transfer) + libusb_alloc_transfer.argtypes = [ctypes.c_int32] +except AttributeError: + pass +try: + libusb_submit_transfer = _libraries['libusb'].libusb_submit_transfer + libusb_submit_transfer.restype = ctypes.c_int32 + libusb_submit_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_cancel_transfer = _libraries['libusb'].libusb_cancel_transfer + libusb_cancel_transfer.restype = ctypes.c_int32 + libusb_cancel_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_free_transfer = _libraries['libusb'].libusb_free_transfer + libusb_free_transfer.restype = None + libusb_free_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_transfer_set_stream_id = _libraries['libusb'].libusb_transfer_set_stream_id + libusb_transfer_set_stream_id.restype = None + libusb_transfer_set_stream_id.argtypes = [ctypes.POINTER(struct_libusb_transfer), uint32_t] +except AttributeError: + pass +try: + libusb_transfer_get_stream_id = _libraries['libusb'].libusb_transfer_get_stream_id + libusb_transfer_get_stream_id.restype = uint32_t + libusb_transfer_get_stream_id.argtypes = [ctypes.POINTER(struct_libusb_transfer)] +except AttributeError: + pass +try: + libusb_fill_control_transfer = _libraries['libusb'].libusb_fill_control_transfer + libusb_fill_control_transfer.restype = None + libusb_fill_control_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.POINTER(struct_libusb_device_handle), ctypes.POINTER(ctypes.c_ubyte), libusb_transfer_cb_fn, ctypes.POINTER(None), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_fill_bulk_transfer = _libraries['libusb'].libusb_fill_bulk_transfer + libusb_fill_bulk_transfer.restype = None + libusb_fill_bulk_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, libusb_transfer_cb_fn, ctypes.POINTER(None), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_fill_bulk_stream_transfer = _libraries['libusb'].libusb_fill_bulk_stream_transfer + libusb_fill_bulk_stream_transfer.restype = None + libusb_fill_bulk_stream_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, uint32_t, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, libusb_transfer_cb_fn, ctypes.POINTER(None), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_fill_interrupt_transfer = _libraries['libusb'].libusb_fill_interrupt_transfer + libusb_fill_interrupt_transfer.restype = None + libusb_fill_interrupt_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, libusb_transfer_cb_fn, ctypes.POINTER(None), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_fill_iso_transfer = _libraries['libusb'].libusb_fill_iso_transfer + libusb_fill_iso_transfer.restype = None + libusb_fill_iso_transfer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, ctypes.c_int32, libusb_transfer_cb_fn, ctypes.POINTER(None), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_set_iso_packet_lengths = _libraries['libusb'].libusb_set_iso_packet_lengths + libusb_set_iso_packet_lengths.restype = None + libusb_set_iso_packet_lengths.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_get_iso_packet_buffer = _libraries['libusb'].libusb_get_iso_packet_buffer + libusb_get_iso_packet_buffer.restype = ctypes.POINTER(ctypes.c_ubyte) + libusb_get_iso_packet_buffer.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_get_iso_packet_buffer_simple = _libraries['libusb'].libusb_get_iso_packet_buffer_simple + libusb_get_iso_packet_buffer_simple.restype = ctypes.POINTER(ctypes.c_ubyte) + libusb_get_iso_packet_buffer_simple.argtypes = [ctypes.POINTER(struct_libusb_transfer), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_control_transfer = _libraries['libusb'].libusb_control_transfer + libusb_control_transfer.restype = ctypes.c_int32 + libusb_control_transfer.argtypes = [ctypes.POINTER(struct_libusb_device_handle), uint8_t, uint8_t, uint16_t, uint16_t, ctypes.POINTER(ctypes.c_ubyte), uint16_t, ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_bulk_transfer = _libraries['libusb'].libusb_bulk_transfer + libusb_bulk_transfer.restype = ctypes.c_int32 + libusb_bulk_transfer.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, ctypes.POINTER(ctypes.c_int32), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_interrupt_transfer = _libraries['libusb'].libusb_interrupt_transfer + libusb_interrupt_transfer.restype = ctypes.c_int32 + libusb_interrupt_transfer.argtypes = [ctypes.POINTER(struct_libusb_device_handle), ctypes.c_ubyte, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32, ctypes.POINTER(ctypes.c_int32), ctypes.c_uint32] +except AttributeError: + pass +try: + libusb_get_descriptor = _libraries['libusb'].libusb_get_descriptor + libusb_get_descriptor.restype = ctypes.c_int32 + libusb_get_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device_handle), uint8_t, uint8_t, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_get_string_descriptor = _libraries['libusb'].libusb_get_string_descriptor + libusb_get_string_descriptor.restype = ctypes.c_int32 + libusb_get_string_descriptor.argtypes = [ctypes.POINTER(struct_libusb_device_handle), uint8_t, uint16_t, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_get_string_descriptor_ascii = _libraries['libusb'].libusb_get_string_descriptor_ascii + libusb_get_string_descriptor_ascii.restype = ctypes.c_int32 + libusb_get_string_descriptor_ascii.argtypes = [ctypes.POINTER(struct_libusb_device_handle), uint8_t, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_int32] +except AttributeError: + pass +try: + libusb_try_lock_events = _libraries['libusb'].libusb_try_lock_events + libusb_try_lock_events.restype = ctypes.c_int32 + libusb_try_lock_events.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_lock_events = _libraries['libusb'].libusb_lock_events + libusb_lock_events.restype = None + libusb_lock_events.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_unlock_events = _libraries['libusb'].libusb_unlock_events + libusb_unlock_events.restype = None + libusb_unlock_events.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_event_handling_ok = _libraries['libusb'].libusb_event_handling_ok + libusb_event_handling_ok.restype = ctypes.c_int32 + libusb_event_handling_ok.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_event_handler_active = _libraries['libusb'].libusb_event_handler_active + libusb_event_handler_active.restype = ctypes.c_int32 + libusb_event_handler_active.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_interrupt_event_handler = _libraries['libusb'].libusb_interrupt_event_handler + libusb_interrupt_event_handler.restype = None + libusb_interrupt_event_handler.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_lock_event_waiters = _libraries['libusb'].libusb_lock_event_waiters + libusb_lock_event_waiters.restype = None + libusb_lock_event_waiters.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_unlock_event_waiters = _libraries['libusb'].libusb_unlock_event_waiters + libusb_unlock_event_waiters.restype = None + libusb_unlock_event_waiters.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +class struct_timeval(Structure): + pass + +struct_timeval._pack_ = 1 # source:False +struct_timeval._fields_ = [ + ('tv_sec', ctypes.c_int64), + ('tv_usec', ctypes.c_int64), +] + +try: + libusb_wait_for_event = _libraries['libusb'].libusb_wait_for_event + libusb_wait_for_event.restype = ctypes.c_int32 + libusb_wait_for_event.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_timeval)] +except AttributeError: + pass +try: + libusb_handle_events_timeout = _libraries['libusb'].libusb_handle_events_timeout + libusb_handle_events_timeout.restype = ctypes.c_int32 + libusb_handle_events_timeout.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_timeval)] +except AttributeError: + pass +try: + libusb_handle_events_timeout_completed = _libraries['libusb'].libusb_handle_events_timeout_completed + libusb_handle_events_timeout_completed.restype = ctypes.c_int32 + libusb_handle_events_timeout_completed.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_timeval), ctypes.POINTER(ctypes.c_int32)] +except AttributeError: + pass +try: + libusb_handle_events = _libraries['libusb'].libusb_handle_events + libusb_handle_events.restype = ctypes.c_int32 + libusb_handle_events.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_handle_events_completed = _libraries['libusb'].libusb_handle_events_completed + libusb_handle_events_completed.restype = ctypes.c_int32 + libusb_handle_events_completed.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(ctypes.c_int32)] +except AttributeError: + pass +try: + libusb_handle_events_locked = _libraries['libusb'].libusb_handle_events_locked + libusb_handle_events_locked.restype = ctypes.c_int32 + libusb_handle_events_locked.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_timeval)] +except AttributeError: + pass +try: + libusb_pollfds_handle_timeouts = _libraries['libusb'].libusb_pollfds_handle_timeouts + libusb_pollfds_handle_timeouts.restype = ctypes.c_int32 + libusb_pollfds_handle_timeouts.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_get_next_timeout = _libraries['libusb'].libusb_get_next_timeout + libusb_get_next_timeout.restype = ctypes.c_int32 + libusb_get_next_timeout.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_timeval)] +except AttributeError: + pass +class struct_libusb_pollfd(Structure): + pass + +struct_libusb_pollfd._pack_ = 1 # source:False +struct_libusb_pollfd._fields_ = [ + ('fd', ctypes.c_int32), + ('events', ctypes.c_int16), + ('PADDING_0', ctypes.c_ubyte * 2), +] + +libusb_pollfd_added_cb = ctypes.CFUNCTYPE(None, ctypes.c_int32, ctypes.c_int16, ctypes.POINTER(None)) +libusb_pollfd_removed_cb = ctypes.CFUNCTYPE(None, ctypes.c_int32, ctypes.POINTER(None)) +try: + libusb_get_pollfds = _libraries['libusb'].libusb_get_pollfds + libusb_get_pollfds.restype = ctypes.POINTER(ctypes.POINTER(struct_libusb_pollfd)) + libusb_get_pollfds.argtypes = [ctypes.POINTER(struct_libusb_context)] +except AttributeError: + pass +try: + libusb_free_pollfds = _libraries['libusb'].libusb_free_pollfds + libusb_free_pollfds.restype = None + libusb_free_pollfds.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_libusb_pollfd))] +except AttributeError: + pass +try: + libusb_set_pollfd_notifiers = _libraries['libusb'].libusb_set_pollfd_notifiers + libusb_set_pollfd_notifiers.restype = None + libusb_set_pollfd_notifiers.argtypes = [ctypes.POINTER(struct_libusb_context), libusb_pollfd_added_cb, libusb_pollfd_removed_cb, ctypes.POINTER(None)] +except AttributeError: + pass +libusb_hotplug_callback_handle = ctypes.c_int32 + +# values for enumeration 'c__EA_libusb_hotplug_event' +c__EA_libusb_hotplug_event__enumvalues = { + 1: 'LIBUSB_HOTPLUG_EVENT_DEVICE_ARRIVED', + 2: 'LIBUSB_HOTPLUG_EVENT_DEVICE_LEFT', +} +LIBUSB_HOTPLUG_EVENT_DEVICE_ARRIVED = 1 +LIBUSB_HOTPLUG_EVENT_DEVICE_LEFT = 2 +c__EA_libusb_hotplug_event = ctypes.c_uint32 # enum +libusb_hotplug_event = c__EA_libusb_hotplug_event +libusb_hotplug_event__enumvalues = c__EA_libusb_hotplug_event__enumvalues + +# values for enumeration 'c__EA_libusb_hotplug_flag' +c__EA_libusb_hotplug_flag__enumvalues = { + 1: 'LIBUSB_HOTPLUG_ENUMERATE', +} +LIBUSB_HOTPLUG_ENUMERATE = 1 +c__EA_libusb_hotplug_flag = ctypes.c_uint32 # enum +libusb_hotplug_flag = c__EA_libusb_hotplug_flag +libusb_hotplug_flag__enumvalues = c__EA_libusb_hotplug_flag__enumvalues +libusb_hotplug_callback_fn = ctypes.CFUNCTYPE(ctypes.c_int32, ctypes.POINTER(struct_libusb_context), ctypes.POINTER(struct_libusb_device), c__EA_libusb_hotplug_event, ctypes.POINTER(None)) +try: + libusb_hotplug_register_callback = _libraries['libusb'].libusb_hotplug_register_callback + libusb_hotplug_register_callback.restype = ctypes.c_int32 + libusb_hotplug_register_callback.argtypes = [ctypes.POINTER(struct_libusb_context), ctypes.c_int32, ctypes.c_int32, ctypes.c_int32, ctypes.c_int32, ctypes.c_int32, libusb_hotplug_callback_fn, ctypes.POINTER(None), ctypes.POINTER(ctypes.c_int32)] +except AttributeError: + pass +try: + libusb_hotplug_deregister_callback = _libraries['libusb'].libusb_hotplug_deregister_callback + libusb_hotplug_deregister_callback.restype = None + libusb_hotplug_deregister_callback.argtypes = [ctypes.POINTER(struct_libusb_context), libusb_hotplug_callback_handle] +except AttributeError: + pass +try: + libusb_hotplug_get_user_data = _libraries['libusb'].libusb_hotplug_get_user_data + libusb_hotplug_get_user_data.restype = ctypes.POINTER(None) + libusb_hotplug_get_user_data.argtypes = [ctypes.POINTER(struct_libusb_context), libusb_hotplug_callback_handle] +except AttributeError: + pass + +# values for enumeration 'libusb_option' +libusb_option__enumvalues = { + 0: 'LIBUSB_OPTION_LOG_LEVEL', + 1: 'LIBUSB_OPTION_USE_USBDK', + 2: 'LIBUSB_OPTION_NO_DEVICE_DISCOVERY', + 3: 'LIBUSB_OPTION_MAX', +} +LIBUSB_OPTION_LOG_LEVEL = 0 +LIBUSB_OPTION_USE_USBDK = 1 +LIBUSB_OPTION_NO_DEVICE_DISCOVERY = 2 +LIBUSB_OPTION_MAX = 3 +libusb_option = ctypes.c_uint32 # enum +LIBUSB_OPTION_WEAK_AUTHORITY = LIBUSB_OPTION_NO_DEVICE_DISCOVERY # macro +try: + libusb_set_option = _libraries['libusb'].libusb_set_option + libusb_set_option.restype = ctypes.c_int32 + libusb_set_option.argtypes = [ctypes.POINTER(struct_libusb_context), libusb_option] +except AttributeError: + pass +struct_libusb_transfer._pack_ = 1 # source:False +struct_libusb_transfer._fields_ = [ + ('dev_handle', ctypes.POINTER(struct_libusb_device_handle)), + ('flags', ctypes.c_ubyte), + ('endpoint', ctypes.c_ubyte), + ('type', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte), + ('timeout', ctypes.c_uint32), + ('status', libusb_transfer_status), + ('length', ctypes.c_int32), + ('actual_length', ctypes.c_int32), + ('PADDING_1', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_libusb_transfer))), + ('user_data', ctypes.POINTER(None)), + ('buffer', ctypes.POINTER(ctypes.c_ubyte)), + ('num_iso_packets', ctypes.c_int32), + ('iso_packet_desc', struct_libusb_iso_packet_descriptor * 0), + ('PADDING_2', ctypes.c_ubyte * 4), +] + +__all__ = \ + ['LIBUSBX_API_VERSION', 'LIBUSB_API_VERSION', + 'LIBUSB_BM_LPM_SUPPORT', 'LIBUSB_BM_LTM_SUPPORT', + 'LIBUSB_BT_CONTAINER_ID', 'LIBUSB_BT_CONTAINER_ID_SIZE', + 'LIBUSB_BT_SS_USB_DEVICE_CAPABILITY', + 'LIBUSB_BT_SS_USB_DEVICE_CAPABILITY_SIZE', + 'LIBUSB_BT_USB_2_0_EXTENSION', 'LIBUSB_BT_USB_2_0_EXTENSION_SIZE', + 'LIBUSB_BT_WIRELESS_USB_DEVICE_CAPABILITY', 'LIBUSB_CALL', + 'LIBUSB_CAP_HAS_CAPABILITY', 'LIBUSB_CAP_HAS_HID_ACCESS', + 'LIBUSB_CAP_HAS_HOTPLUG', + 'LIBUSB_CAP_SUPPORTS_DETACH_KERNEL_DRIVER', + 'LIBUSB_CLASS_APPLICATION', 'LIBUSB_CLASS_AUDIO', + 'LIBUSB_CLASS_COMM', 'LIBUSB_CLASS_CONTENT_SECURITY', + 'LIBUSB_CLASS_DATA', 'LIBUSB_CLASS_DIAGNOSTIC_DEVICE', + 'LIBUSB_CLASS_HID', 'LIBUSB_CLASS_HUB', 'LIBUSB_CLASS_IMAGE', + 'LIBUSB_CLASS_MASS_STORAGE', 'LIBUSB_CLASS_MISCELLANEOUS', + 'LIBUSB_CLASS_PERSONAL_HEALTHCARE', 'LIBUSB_CLASS_PER_INTERFACE', + 'LIBUSB_CLASS_PHYSICAL', 'LIBUSB_CLASS_PRINTER', + 'LIBUSB_CLASS_PTP', 'LIBUSB_CLASS_SMART_CARD', + 'LIBUSB_CLASS_VENDOR_SPEC', 'LIBUSB_CLASS_VIDEO', + 'LIBUSB_CLASS_WIRELESS', 'LIBUSB_DT_BOS', + 'LIBUSB_DT_BOS_MAX_SIZE', 'LIBUSB_DT_BOS_SIZE', + 'LIBUSB_DT_CONFIG', 'LIBUSB_DT_CONFIG_SIZE', 'LIBUSB_DT_DEVICE', + 'LIBUSB_DT_DEVICE_CAPABILITY', 'LIBUSB_DT_DEVICE_CAPABILITY_SIZE', + 'LIBUSB_DT_DEVICE_SIZE', 'LIBUSB_DT_ENDPOINT', + 'LIBUSB_DT_ENDPOINT_AUDIO_SIZE', 'LIBUSB_DT_ENDPOINT_SIZE', + 'LIBUSB_DT_HID', 'LIBUSB_DT_HUB', 'LIBUSB_DT_HUB_NONVAR_SIZE', + 'LIBUSB_DT_INTERFACE', 'LIBUSB_DT_INTERFACE_SIZE', + 'LIBUSB_DT_PHYSICAL', 'LIBUSB_DT_REPORT', + 'LIBUSB_DT_SS_ENDPOINT_COMPANION', + 'LIBUSB_DT_SS_ENDPOINT_COMPANION_SIZE', 'LIBUSB_DT_STRING', + 'LIBUSB_DT_SUPERSPEED_HUB', 'LIBUSB_ENDPOINT_ADDRESS_MASK', + 'LIBUSB_ENDPOINT_DIR_MASK', 'LIBUSB_ENDPOINT_IN', + 'LIBUSB_ENDPOINT_OUT', 'LIBUSB_ENDPOINT_TRANSFER_TYPE_BULK', + 'LIBUSB_ENDPOINT_TRANSFER_TYPE_CONTROL', + 'LIBUSB_ENDPOINT_TRANSFER_TYPE_INTERRUPT', + 'LIBUSB_ENDPOINT_TRANSFER_TYPE_ISOCHRONOUS', + 'LIBUSB_ERROR_ACCESS', 'LIBUSB_ERROR_BUSY', 'LIBUSB_ERROR_COUNT', + 'LIBUSB_ERROR_INTERRUPTED', 'LIBUSB_ERROR_INVALID_PARAM', + 'LIBUSB_ERROR_IO', 'LIBUSB_ERROR_NOT_FOUND', + 'LIBUSB_ERROR_NOT_SUPPORTED', 'LIBUSB_ERROR_NO_DEVICE', + 'LIBUSB_ERROR_NO_MEM', 'LIBUSB_ERROR_OTHER', + 'LIBUSB_ERROR_OVERFLOW', 'LIBUSB_ERROR_PIPE', + 'LIBUSB_ERROR_TIMEOUT', 'LIBUSB_FULL_SPEED_OPERATION', 'LIBUSB_H', + 'LIBUSB_HIGH_SPEED_OPERATION', 'LIBUSB_HOTPLUG_ENUMERATE', + 'LIBUSB_HOTPLUG_EVENT_DEVICE_ARRIVED', + 'LIBUSB_HOTPLUG_EVENT_DEVICE_LEFT', 'LIBUSB_HOTPLUG_MATCH_ANY', + 'LIBUSB_HOTPLUG_NO_FLAGS', 'LIBUSB_ISO_SYNC_TYPE_ADAPTIVE', + 'LIBUSB_ISO_SYNC_TYPE_ASYNC', 'LIBUSB_ISO_SYNC_TYPE_MASK', + 'LIBUSB_ISO_SYNC_TYPE_NONE', 'LIBUSB_ISO_SYNC_TYPE_SYNC', + 'LIBUSB_ISO_USAGE_TYPE_DATA', 'LIBUSB_ISO_USAGE_TYPE_FEEDBACK', + 'LIBUSB_ISO_USAGE_TYPE_IMPLICIT', 'LIBUSB_ISO_USAGE_TYPE_MASK', + 'LIBUSB_LOG_CB_CONTEXT', 'LIBUSB_LOG_CB_GLOBAL', + 'LIBUSB_LOG_LEVEL_DEBUG', 'LIBUSB_LOG_LEVEL_ERROR', + 'LIBUSB_LOG_LEVEL_INFO', 'LIBUSB_LOG_LEVEL_NONE', + 'LIBUSB_LOG_LEVEL_WARNING', 'LIBUSB_LOW_SPEED_OPERATION', + 'LIBUSB_OPTION_LOG_LEVEL', 'LIBUSB_OPTION_MAX', + 'LIBUSB_OPTION_NO_DEVICE_DISCOVERY', 'LIBUSB_OPTION_USE_USBDK', + 'LIBUSB_OPTION_WEAK_AUTHORITY', 'LIBUSB_RECIPIENT_DEVICE', + 'LIBUSB_RECIPIENT_ENDPOINT', 'LIBUSB_RECIPIENT_INTERFACE', + 'LIBUSB_RECIPIENT_OTHER', 'LIBUSB_REQUEST_CLEAR_FEATURE', + 'LIBUSB_REQUEST_GET_CONFIGURATION', + 'LIBUSB_REQUEST_GET_DESCRIPTOR', 'LIBUSB_REQUEST_GET_INTERFACE', + 'LIBUSB_REQUEST_GET_STATUS', 'LIBUSB_REQUEST_SET_ADDRESS', + 'LIBUSB_REQUEST_SET_CONFIGURATION', + 'LIBUSB_REQUEST_SET_DESCRIPTOR', 'LIBUSB_REQUEST_SET_FEATURE', + 'LIBUSB_REQUEST_SET_INTERFACE', 'LIBUSB_REQUEST_SET_SEL', + 'LIBUSB_REQUEST_SYNCH_FRAME', 'LIBUSB_REQUEST_TYPE_CLASS', + 'LIBUSB_REQUEST_TYPE_RESERVED', 'LIBUSB_REQUEST_TYPE_STANDARD', + 'LIBUSB_REQUEST_TYPE_VENDOR', 'LIBUSB_SET_ISOCH_DELAY', + 'LIBUSB_SPEED_FULL', 'LIBUSB_SPEED_HIGH', 'LIBUSB_SPEED_LOW', + 'LIBUSB_SPEED_SUPER', 'LIBUSB_SPEED_SUPER_PLUS', + 'LIBUSB_SPEED_UNKNOWN', 'LIBUSB_SUCCESS', + 'LIBUSB_SUPER_SPEED_OPERATION', 'LIBUSB_TRANSFER_ADD_ZERO_PACKET', + 'LIBUSB_TRANSFER_CANCELLED', 'LIBUSB_TRANSFER_COMPLETED', + 'LIBUSB_TRANSFER_ERROR', 'LIBUSB_TRANSFER_FREE_BUFFER', + 'LIBUSB_TRANSFER_FREE_TRANSFER', 'LIBUSB_TRANSFER_NO_DEVICE', + 'LIBUSB_TRANSFER_OVERFLOW', 'LIBUSB_TRANSFER_SHORT_NOT_OK', + 'LIBUSB_TRANSFER_STALL', 'LIBUSB_TRANSFER_TIMED_OUT', + 'LIBUSB_TRANSFER_TYPE_BULK', 'LIBUSB_TRANSFER_TYPE_BULK_STREAM', + 'LIBUSB_TRANSFER_TYPE_CONTROL', 'LIBUSB_TRANSFER_TYPE_INTERRUPT', + 'LIBUSB_TRANSFER_TYPE_ISOCHRONOUS', 'LIBUSB_TRANSFER_TYPE_MASK', + 'ZERO_SIZED_ARRAY', 'c__EA_libusb_hotplug_event', + 'c__EA_libusb_hotplug_flag', 'intptr_t', 'libusb_alloc_streams', + 'libusb_alloc_transfer', 'libusb_attach_kernel_driver', + 'libusb_bos_type', 'libusb_bulk_transfer', + 'libusb_cancel_transfer', 'libusb_capability', + 'libusb_claim_interface', 'libusb_class_code', + 'libusb_clear_halt', 'libusb_close', 'libusb_context', + 'libusb_control_transfer', 'libusb_control_transfer_get_data', + 'libusb_control_transfer_get_setup', 'libusb_cpu_to_le16', + 'libusb_descriptor_type', 'libusb_detach_kernel_driver', + 'libusb_dev_mem_alloc', 'libusb_dev_mem_free', 'libusb_device', + 'libusb_device_handle', 'libusb_endpoint_direction', + 'libusb_endpoint_transfer_type', 'libusb_error', + 'libusb_error_name', 'libusb_event_handler_active', + 'libusb_event_handling_ok', 'libusb_exit', + 'libusb_fill_bulk_stream_transfer', 'libusb_fill_bulk_transfer', + 'libusb_fill_control_setup', 'libusb_fill_control_transfer', + 'libusb_fill_interrupt_transfer', 'libusb_fill_iso_transfer', + 'libusb_free_bos_descriptor', 'libusb_free_config_descriptor', + 'libusb_free_container_id_descriptor', 'libusb_free_device_list', + 'libusb_free_pollfds', + 'libusb_free_ss_endpoint_companion_descriptor', + 'libusb_free_ss_usb_device_capability_descriptor', + 'libusb_free_streams', 'libusb_free_transfer', + 'libusb_free_usb_2_0_extension_descriptor', + 'libusb_get_active_config_descriptor', + 'libusb_get_bos_descriptor', 'libusb_get_bus_number', + 'libusb_get_config_descriptor', + 'libusb_get_config_descriptor_by_value', + 'libusb_get_configuration', 'libusb_get_container_id_descriptor', + 'libusb_get_descriptor', 'libusb_get_device', + 'libusb_get_device_address', 'libusb_get_device_descriptor', + 'libusb_get_device_list', 'libusb_get_device_speed', + 'libusb_get_iso_packet_buffer', + 'libusb_get_iso_packet_buffer_simple', + 'libusb_get_max_iso_packet_size', 'libusb_get_max_packet_size', + 'libusb_get_next_timeout', 'libusb_get_parent', + 'libusb_get_pollfds', 'libusb_get_port_number', + 'libusb_get_port_numbers', 'libusb_get_port_path', + 'libusb_get_ss_endpoint_companion_descriptor', + 'libusb_get_ss_usb_device_capability_descriptor', + 'libusb_get_string_descriptor', + 'libusb_get_string_descriptor_ascii', + 'libusb_get_usb_2_0_extension_descriptor', 'libusb_get_version', + 'libusb_handle_events', 'libusb_handle_events_completed', + 'libusb_handle_events_locked', 'libusb_handle_events_timeout', + 'libusb_handle_events_timeout_completed', 'libusb_has_capability', + 'libusb_hotplug_callback_fn', 'libusb_hotplug_callback_handle', + 'libusb_hotplug_deregister_callback', 'libusb_hotplug_event', + 'libusb_hotplug_event__enumvalues', 'libusb_hotplug_flag', + 'libusb_hotplug_flag__enumvalues', 'libusb_hotplug_get_user_data', + 'libusb_hotplug_register_callback', 'libusb_init', + 'libusb_interrupt_event_handler', 'libusb_interrupt_transfer', + 'libusb_iso_sync_type', 'libusb_iso_usage_type', + 'libusb_kernel_driver_active', 'libusb_le16_to_cpu', + 'libusb_lock_event_waiters', 'libusb_lock_events', + 'libusb_log_cb', 'libusb_log_cb_mode', 'libusb_log_level', + 'libusb_open', 'libusb_open_device_with_vid_pid', 'libusb_option', + 'libusb_pollfd_added_cb', 'libusb_pollfd_removed_cb', + 'libusb_pollfds_handle_timeouts', 'libusb_ref_device', + 'libusb_release_interface', 'libusb_request_recipient', + 'libusb_request_type', 'libusb_reset_device', + 'libusb_set_auto_detach_kernel_driver', + 'libusb_set_configuration', 'libusb_set_debug', + 'libusb_set_interface_alt_setting', + 'libusb_set_iso_packet_lengths', 'libusb_set_log_cb', + 'libusb_set_option', 'libusb_set_pollfd_notifiers', + 'libusb_setlocale', 'libusb_speed', + 'libusb_ss_usb_device_capability_attributes', + 'libusb_standard_request', 'libusb_strerror', + 'libusb_submit_transfer', 'libusb_supported_speed', + 'libusb_transfer_cb_fn', 'libusb_transfer_flags', + 'libusb_transfer_get_stream_id', 'libusb_transfer_set_stream_id', + 'libusb_transfer_status', 'libusb_transfer_type', + 'libusb_try_lock_events', 'libusb_unlock_event_waiters', + 'libusb_unlock_events', 'libusb_unref_device', + 'libusb_usb_2_0_extension_attributes', 'libusb_wait_for_event', + 'libusb_wrap_sys_device', 'size_t', 'ssize_t', + 'struct_libusb_bos_descriptor', + 'struct_libusb_bos_dev_capability_descriptor', + 'struct_libusb_config_descriptor', + 'struct_libusb_container_id_descriptor', 'struct_libusb_context', + 'struct_libusb_control_setup', 'struct_libusb_device', + 'struct_libusb_device_descriptor', 'struct_libusb_device_handle', + 'struct_libusb_endpoint_descriptor', 'struct_libusb_interface', + 'struct_libusb_interface_descriptor', + 'struct_libusb_iso_packet_descriptor', 'struct_libusb_pollfd', + 'struct_libusb_ss_endpoint_companion_descriptor', + 'struct_libusb_ss_usb_device_capability_descriptor', + 'struct_libusb_transfer', + 'struct_libusb_usb_2_0_extension_descriptor', + 'struct_libusb_version', 'struct_timeval', 'uint16_t', 'uint32_t', + 'uint8_t'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/llvm.py b/tinygrad_repo/tinygrad/runtime/autogen/llvm.py new file mode 100644 index 0000000000..1b50e41e49 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/llvm.py @@ -0,0 +1,11379 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/usr/lib/llvm-14/include', '-D_GNU_SOURCE', '-D__STDC_CONSTANT_MACROS', '-D__STDC_FORMAT_MACROS', '-D__STDC_LIMIT_MACROS'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes, tinygrad.runtime.support.llvm as llvm_support + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +def string_cast(char_pointer, encoding='utf-8', errors='strict'): + value = ctypes.cast(char_pointer, ctypes.c_char_p).value + if value is not None and encoding is not None: + value = value.decode(encoding, errors=errors) + return value + + +def char_pointer_cast(string, encoding='utf-8'): + if encoding is not None: + try: + string = string.encode(encoding) + except AttributeError: + # In Python3, bytes has no encode attribute + pass + string = ctypes.c_char_p(string) + return ctypes.cast(string, ctypes.POINTER(ctypes.c_char)) + + + +class FunctionFactoryStub: + def __getattr__(self, _): + return ctypes.CFUNCTYPE(lambda y:y) + +# libraries['llvm'] explanation +# As you did not list (-l libraryname.so) a library that exports this function +# This is a non-working stub instead. +# You can either re-run clan2py with -l /path/to/library.so +# Or manually fix this by comment the ctypes.CDLL loading +_libraries = {} +_libraries['llvm'] = ctypes.CDLL(llvm_support.LLVM_PATH) # ctypes.CDLL('llvm') +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +LLVM_C_ANALYSIS_H = True # macro +LLVM_C_EXTERNC_H = True # macro +# LLVM_C_STRICT_PROTOTYPES_BEGIN = _Pragma ( "clang diagnostic push" ) _Pragma ( "clang diagnostic error \"-Wstrict-prototypes\"" ) # macro +# LLVM_C_STRICT_PROTOTYPES_END = _Pragma ( "clang diagnostic pop" ) # macro +# LLVM_C_EXTERN_C_BEGIN = _Pragma ( "clang diagnostic push" ) _Pragma ( "clang diagnostic error \"-Wstrict-prototypes\"" ) # macro +# LLVM_C_EXTERN_C_END = _Pragma ( "clang diagnostic pop" ) # macro +LLVM_C_TYPES_H = True # macro +LLVM_C_DATATYPES_H = True # macro +LLVMBool = ctypes.c_int32 +class struct_LLVMOpaqueMemoryBuffer(Structure): + pass + +LLVMMemoryBufferRef = ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer) +class struct_LLVMOpaqueContext(Structure): + pass + +LLVMContextRef = ctypes.POINTER(struct_LLVMOpaqueContext) +class struct_LLVMOpaqueModule(Structure): + pass + +LLVMModuleRef = ctypes.POINTER(struct_LLVMOpaqueModule) +class struct_LLVMOpaqueType(Structure): + pass + +LLVMTypeRef = ctypes.POINTER(struct_LLVMOpaqueType) +class struct_LLVMOpaqueValue(Structure): + pass + +LLVMValueRef = ctypes.POINTER(struct_LLVMOpaqueValue) +class struct_LLVMOpaqueBasicBlock(Structure): + pass + +LLVMBasicBlockRef = ctypes.POINTER(struct_LLVMOpaqueBasicBlock) +class struct_LLVMOpaqueMetadata(Structure): + pass + +LLVMMetadataRef = ctypes.POINTER(struct_LLVMOpaqueMetadata) +class struct_LLVMOpaqueNamedMDNode(Structure): + pass + +LLVMNamedMDNodeRef = ctypes.POINTER(struct_LLVMOpaqueNamedMDNode) +class struct_LLVMOpaqueValueMetadataEntry(Structure): + pass + +LLVMValueMetadataEntry = struct_LLVMOpaqueValueMetadataEntry +class struct_LLVMOpaqueBuilder(Structure): + pass + +LLVMBuilderRef = ctypes.POINTER(struct_LLVMOpaqueBuilder) +class struct_LLVMOpaqueDIBuilder(Structure): + pass + +LLVMDIBuilderRef = ctypes.POINTER(struct_LLVMOpaqueDIBuilder) +class struct_LLVMOpaqueModuleProvider(Structure): + pass + +LLVMModuleProviderRef = ctypes.POINTER(struct_LLVMOpaqueModuleProvider) +class struct_LLVMOpaquePassManager(Structure): + pass + +LLVMPassManagerRef = ctypes.POINTER(struct_LLVMOpaquePassManager) +class struct_LLVMOpaquePassRegistry(Structure): + pass + +LLVMPassRegistryRef = ctypes.POINTER(struct_LLVMOpaquePassRegistry) +class struct_LLVMOpaqueUse(Structure): + pass + +LLVMUseRef = ctypes.POINTER(struct_LLVMOpaqueUse) +class struct_LLVMOpaqueAttributeRef(Structure): + pass + +LLVMAttributeRef = ctypes.POINTER(struct_LLVMOpaqueAttributeRef) +class struct_LLVMOpaqueDiagnosticInfo(Structure): + pass + +LLVMDiagnosticInfoRef = ctypes.POINTER(struct_LLVMOpaqueDiagnosticInfo) +class struct_LLVMComdat(Structure): + pass + +LLVMComdatRef = ctypes.POINTER(struct_LLVMComdat) +class struct_LLVMOpaqueModuleFlagEntry(Structure): + pass + +LLVMModuleFlagEntry = struct_LLVMOpaqueModuleFlagEntry +class struct_LLVMOpaqueJITEventListener(Structure): + pass + +LLVMJITEventListenerRef = ctypes.POINTER(struct_LLVMOpaqueJITEventListener) +class struct_LLVMOpaqueBinary(Structure): + pass + +LLVMBinaryRef = ctypes.POINTER(struct_LLVMOpaqueBinary) + +# values for enumeration 'c__EA_LLVMVerifierFailureAction' +c__EA_LLVMVerifierFailureAction__enumvalues = { + 0: 'LLVMAbortProcessAction', + 1: 'LLVMPrintMessageAction', + 2: 'LLVMReturnStatusAction', +} +LLVMAbortProcessAction = 0 +LLVMPrintMessageAction = 1 +LLVMReturnStatusAction = 2 +c__EA_LLVMVerifierFailureAction = ctypes.c_uint32 # enum +LLVMVerifierFailureAction = c__EA_LLVMVerifierFailureAction +LLVMVerifierFailureAction__enumvalues = c__EA_LLVMVerifierFailureAction__enumvalues +try: + LLVMVerifyModule = _libraries['llvm'].LLVMVerifyModule + LLVMVerifyModule.restype = LLVMBool + LLVMVerifyModule.argtypes = [LLVMModuleRef, LLVMVerifierFailureAction, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMVerifyFunction = _libraries['llvm'].LLVMVerifyFunction + LLVMVerifyFunction.restype = LLVMBool + LLVMVerifyFunction.argtypes = [LLVMValueRef, LLVMVerifierFailureAction] +except AttributeError: + pass +try: + LLVMViewFunctionCFG = _libraries['llvm'].LLVMViewFunctionCFG + LLVMViewFunctionCFG.restype = None + LLVMViewFunctionCFG.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMViewFunctionCFGOnly = _libraries['llvm'].LLVMViewFunctionCFGOnly + LLVMViewFunctionCFGOnly.restype = None + LLVMViewFunctionCFGOnly.argtypes = [LLVMValueRef] +except AttributeError: + pass +LLVM_C_BITREADER_H = True # macro +try: + LLVMParseBitcode = _libraries['llvm'].LLVMParseBitcode + LLVMParseBitcode.restype = LLVMBool + LLVMParseBitcode.argtypes = [LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMParseBitcode2 = _libraries['llvm'].LLVMParseBitcode2 + LLVMParseBitcode2.restype = LLVMBool + LLVMParseBitcode2.argtypes = [LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule))] +except AttributeError: + pass +try: + LLVMParseBitcodeInContext = _libraries['llvm'].LLVMParseBitcodeInContext + LLVMParseBitcodeInContext.restype = LLVMBool + LLVMParseBitcodeInContext.argtypes = [LLVMContextRef, LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMParseBitcodeInContext2 = _libraries['llvm'].LLVMParseBitcodeInContext2 + LLVMParseBitcodeInContext2.restype = LLVMBool + LLVMParseBitcodeInContext2.argtypes = [LLVMContextRef, LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule))] +except AttributeError: + pass +try: + LLVMGetBitcodeModuleInContext = _libraries['llvm'].LLVMGetBitcodeModuleInContext + LLVMGetBitcodeModuleInContext.restype = LLVMBool + LLVMGetBitcodeModuleInContext.argtypes = [LLVMContextRef, LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMGetBitcodeModuleInContext2 = _libraries['llvm'].LLVMGetBitcodeModuleInContext2 + LLVMGetBitcodeModuleInContext2.restype = LLVMBool + LLVMGetBitcodeModuleInContext2.argtypes = [LLVMContextRef, LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule))] +except AttributeError: + pass +try: + LLVMGetBitcodeModule = _libraries['llvm'].LLVMGetBitcodeModule + LLVMGetBitcodeModule.restype = LLVMBool + LLVMGetBitcodeModule.argtypes = [LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMGetBitcodeModule2 = _libraries['llvm'].LLVMGetBitcodeModule2 + LLVMGetBitcodeModule2.restype = LLVMBool + LLVMGetBitcodeModule2.argtypes = [LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule))] +except AttributeError: + pass +LLVM_C_BITWRITER_H = True # macro +try: + LLVMWriteBitcodeToFile = _libraries['llvm'].LLVMWriteBitcodeToFile + LLVMWriteBitcodeToFile.restype = ctypes.c_int32 + LLVMWriteBitcodeToFile.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMWriteBitcodeToFD = _libraries['llvm'].LLVMWriteBitcodeToFD + LLVMWriteBitcodeToFD.restype = ctypes.c_int32 + LLVMWriteBitcodeToFD.argtypes = [LLVMModuleRef, ctypes.c_int32, ctypes.c_int32, ctypes.c_int32] +except AttributeError: + pass +try: + LLVMWriteBitcodeToFileHandle = _libraries['llvm'].LLVMWriteBitcodeToFileHandle + LLVMWriteBitcodeToFileHandle.restype = ctypes.c_int32 + LLVMWriteBitcodeToFileHandle.argtypes = [LLVMModuleRef, ctypes.c_int32] +except AttributeError: + pass +try: + LLVMWriteBitcodeToMemoryBuffer = _libraries['llvm'].LLVMWriteBitcodeToMemoryBuffer + LLVMWriteBitcodeToMemoryBuffer.restype = LLVMMemoryBufferRef + LLVMWriteBitcodeToMemoryBuffer.argtypes = [LLVMModuleRef] +except AttributeError: + pass +LLVM_C_COMDAT_H = True # macro + +# values for enumeration 'c__EA_LLVMComdatSelectionKind' +c__EA_LLVMComdatSelectionKind__enumvalues = { + 0: 'LLVMAnyComdatSelectionKind', + 1: 'LLVMExactMatchComdatSelectionKind', + 2: 'LLVMLargestComdatSelectionKind', + 3: 'LLVMNoDeduplicateComdatSelectionKind', + 4: 'LLVMSameSizeComdatSelectionKind', +} +LLVMAnyComdatSelectionKind = 0 +LLVMExactMatchComdatSelectionKind = 1 +LLVMLargestComdatSelectionKind = 2 +LLVMNoDeduplicateComdatSelectionKind = 3 +LLVMSameSizeComdatSelectionKind = 4 +c__EA_LLVMComdatSelectionKind = ctypes.c_uint32 # enum +LLVMComdatSelectionKind = c__EA_LLVMComdatSelectionKind +LLVMComdatSelectionKind__enumvalues = c__EA_LLVMComdatSelectionKind__enumvalues +try: + LLVMGetOrInsertComdat = _libraries['llvm'].LLVMGetOrInsertComdat + LLVMGetOrInsertComdat.restype = LLVMComdatRef + LLVMGetOrInsertComdat.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetComdat = _libraries['llvm'].LLVMGetComdat + LLVMGetComdat.restype = LLVMComdatRef + LLVMGetComdat.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetComdat = _libraries['llvm'].LLVMSetComdat + LLVMSetComdat.restype = None + LLVMSetComdat.argtypes = [LLVMValueRef, LLVMComdatRef] +except AttributeError: + pass +try: + LLVMGetComdatSelectionKind = _libraries['llvm'].LLVMGetComdatSelectionKind + LLVMGetComdatSelectionKind.restype = LLVMComdatSelectionKind + LLVMGetComdatSelectionKind.argtypes = [LLVMComdatRef] +except AttributeError: + pass +try: + LLVMSetComdatSelectionKind = _libraries['llvm'].LLVMSetComdatSelectionKind + LLVMSetComdatSelectionKind.restype = None + LLVMSetComdatSelectionKind.argtypes = [LLVMComdatRef, LLVMComdatSelectionKind] +except AttributeError: + pass +LLVM_C_CORE_H = True # macro +LLVM_C_DEPRECATED_H = True # macro +# def LLVM_ATTRIBUTE_C_DEPRECATED(decl, message): # macro +# return decl((deprecated(message))) +LLVM_C_ERRORHANDLING_H = True # macro +# def LLVM_FOR_EACH_VALUE_SUBCLASS(macro): # macro +# return macro(Argument)macro(BasicBlock)macro(InlineAsm)macro(User)macro(Constant)macro(BlockAddress)macro(ConstantAggregateZero)macro(ConstantArray)macro(ConstantDataSequential)macro(ConstantDataArray)macro(ConstantDataVector)macro(ConstantExpr)macro(ConstantFP)macro(ConstantInt)macro(ConstantPointerNull)macro(ConstantStruct)macro(ConstantTokenNone)macro(ConstantVector)macro(GlobalValue)macro(GlobalAlias)macro(GlobalObject)macro(Function)macro(GlobalVariable)macro(GlobalIFunc)macro(UndefValue)macro(PoisonValue)macro(Instruction)macro(UnaryOperator)macro(BinaryOperator)macro(CallInst)macro(IntrinsicInst)macro(DbgInfoIntrinsic)macro(DbgVariableIntrinsic)macro(DbgDeclareInst)macro(DbgLabelInst)macro(MemIntrinsic)macro(MemCpyInst)macro(MemMoveInst)macro(MemSetInst)macro(CmpInst)macro(FCmpInst)macro(ICmpInst)macro(ExtractElementInst)macro(GetElementPtrInst)macro(InsertElementInst)macro(InsertValueInst)macro(LandingPadInst)macro(PHINode)macro(SelectInst)macro(ShuffleVectorInst)macro(StoreInst)macro(BranchInst)macro(IndirectBrInst)macro(InvokeInst)macro(ReturnInst)macro(SwitchInst)macro(UnreachableInst)macro(ResumeInst)macro(CleanupReturnInst)macro(CatchReturnInst)macro(CatchSwitchInst)macro(CallBrInst)macro(FuncletPadInst)macro(CatchPadInst)macro(CleanupPadInst)macro(UnaryInstruction)macro(AllocaInst)macro(CastInst)macro(AddrSpaceCastInst)macro(BitCastInst)macro(FPExtInst)macro(FPToSIInst)macro(FPToUIInst)macro(FPTruncInst)macro(IntToPtrInst)macro(PtrToIntInst)macro(SExtInst)macro(SIToFPInst)macro(TruncInst)macro(UIToFPInst)macro(ZExtInst)macro(ExtractValueInst)macro(LoadInst)macro(VAArgInst)macro(FreezeInst)macro(AtomicCmpXchgInst)macro(AtomicRMWInst)macro(FenceInst) +# def LLVM_DECLARE_VALUE_CAST(name): # macro +# return LLVMIsA##name(Val); +LLVMFatalErrorHandler = ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.c_char)) +try: + LLVMInstallFatalErrorHandler = _libraries['llvm'].LLVMInstallFatalErrorHandler + LLVMInstallFatalErrorHandler.restype = None + LLVMInstallFatalErrorHandler.argtypes = [LLVMFatalErrorHandler] +except AttributeError: + pass +try: + LLVMResetFatalErrorHandler = _libraries['llvm'].LLVMResetFatalErrorHandler + LLVMResetFatalErrorHandler.restype = None + LLVMResetFatalErrorHandler.argtypes = [] +except AttributeError: + pass +try: + LLVMEnablePrettyStackTrace = _libraries['llvm'].LLVMEnablePrettyStackTrace + LLVMEnablePrettyStackTrace.restype = None + LLVMEnablePrettyStackTrace.argtypes = [] +except AttributeError: + pass + +# values for enumeration 'c__EA_LLVMOpcode' +c__EA_LLVMOpcode__enumvalues = { + 1: 'LLVMRet', + 2: 'LLVMBr', + 3: 'LLVMSwitch', + 4: 'LLVMIndirectBr', + 5: 'LLVMInvoke', + 7: 'LLVMUnreachable', + 67: 'LLVMCallBr', + 66: 'LLVMFNeg', + 8: 'LLVMAdd', + 9: 'LLVMFAdd', + 10: 'LLVMSub', + 11: 'LLVMFSub', + 12: 'LLVMMul', + 13: 'LLVMFMul', + 14: 'LLVMUDiv', + 15: 'LLVMSDiv', + 16: 'LLVMFDiv', + 17: 'LLVMURem', + 18: 'LLVMSRem', + 19: 'LLVMFRem', + 20: 'LLVMShl', + 21: 'LLVMLShr', + 22: 'LLVMAShr', + 23: 'LLVMAnd', + 24: 'LLVMOr', + 25: 'LLVMXor', + 26: 'LLVMAlloca', + 27: 'LLVMLoad', + 28: 'LLVMStore', + 29: 'LLVMGetElementPtr', + 30: 'LLVMTrunc', + 31: 'LLVMZExt', + 32: 'LLVMSExt', + 33: 'LLVMFPToUI', + 34: 'LLVMFPToSI', + 35: 'LLVMUIToFP', + 36: 'LLVMSIToFP', + 37: 'LLVMFPTrunc', + 38: 'LLVMFPExt', + 39: 'LLVMPtrToInt', + 40: 'LLVMIntToPtr', + 41: 'LLVMBitCast', + 60: 'LLVMAddrSpaceCast', + 42: 'LLVMICmp', + 43: 'LLVMFCmp', + 44: 'LLVMPHI', + 45: 'LLVMCall', + 46: 'LLVMSelect', + 47: 'LLVMUserOp1', + 48: 'LLVMUserOp2', + 49: 'LLVMVAArg', + 50: 'LLVMExtractElement', + 51: 'LLVMInsertElement', + 52: 'LLVMShuffleVector', + 53: 'LLVMExtractValue', + 54: 'LLVMInsertValue', + 68: 'LLVMFreeze', + 55: 'LLVMFence', + 56: 'LLVMAtomicCmpXchg', + 57: 'LLVMAtomicRMW', + 58: 'LLVMResume', + 59: 'LLVMLandingPad', + 61: 'LLVMCleanupRet', + 62: 'LLVMCatchRet', + 63: 'LLVMCatchPad', + 64: 'LLVMCleanupPad', + 65: 'LLVMCatchSwitch', +} +LLVMRet = 1 +LLVMBr = 2 +LLVMSwitch = 3 +LLVMIndirectBr = 4 +LLVMInvoke = 5 +LLVMUnreachable = 7 +LLVMCallBr = 67 +LLVMFNeg = 66 +LLVMAdd = 8 +LLVMFAdd = 9 +LLVMSub = 10 +LLVMFSub = 11 +LLVMMul = 12 +LLVMFMul = 13 +LLVMUDiv = 14 +LLVMSDiv = 15 +LLVMFDiv = 16 +LLVMURem = 17 +LLVMSRem = 18 +LLVMFRem = 19 +LLVMShl = 20 +LLVMLShr = 21 +LLVMAShr = 22 +LLVMAnd = 23 +LLVMOr = 24 +LLVMXor = 25 +LLVMAlloca = 26 +LLVMLoad = 27 +LLVMStore = 28 +LLVMGetElementPtr = 29 +LLVMTrunc = 30 +LLVMZExt = 31 +LLVMSExt = 32 +LLVMFPToUI = 33 +LLVMFPToSI = 34 +LLVMUIToFP = 35 +LLVMSIToFP = 36 +LLVMFPTrunc = 37 +LLVMFPExt = 38 +LLVMPtrToInt = 39 +LLVMIntToPtr = 40 +LLVMBitCast = 41 +LLVMAddrSpaceCast = 60 +LLVMICmp = 42 +LLVMFCmp = 43 +LLVMPHI = 44 +LLVMCall = 45 +LLVMSelect = 46 +LLVMUserOp1 = 47 +LLVMUserOp2 = 48 +LLVMVAArg = 49 +LLVMExtractElement = 50 +LLVMInsertElement = 51 +LLVMShuffleVector = 52 +LLVMExtractValue = 53 +LLVMInsertValue = 54 +LLVMFreeze = 68 +LLVMFence = 55 +LLVMAtomicCmpXchg = 56 +LLVMAtomicRMW = 57 +LLVMResume = 58 +LLVMLandingPad = 59 +LLVMCleanupRet = 61 +LLVMCatchRet = 62 +LLVMCatchPad = 63 +LLVMCleanupPad = 64 +LLVMCatchSwitch = 65 +c__EA_LLVMOpcode = ctypes.c_uint32 # enum +LLVMOpcode = c__EA_LLVMOpcode +LLVMOpcode__enumvalues = c__EA_LLVMOpcode__enumvalues + +# values for enumeration 'c__EA_LLVMTypeKind' +c__EA_LLVMTypeKind__enumvalues = { + 0: 'LLVMVoidTypeKind', + 1: 'LLVMHalfTypeKind', + 2: 'LLVMFloatTypeKind', + 3: 'LLVMDoubleTypeKind', + 4: 'LLVMX86_FP80TypeKind', + 5: 'LLVMFP128TypeKind', + 6: 'LLVMPPC_FP128TypeKind', + 7: 'LLVMLabelTypeKind', + 8: 'LLVMIntegerTypeKind', + 9: 'LLVMFunctionTypeKind', + 10: 'LLVMStructTypeKind', + 11: 'LLVMArrayTypeKind', + 12: 'LLVMPointerTypeKind', + 13: 'LLVMVectorTypeKind', + 14: 'LLVMMetadataTypeKind', + 15: 'LLVMX86_MMXTypeKind', + 16: 'LLVMTokenTypeKind', + 17: 'LLVMScalableVectorTypeKind', + 18: 'LLVMBFloatTypeKind', + 19: 'LLVMX86_AMXTypeKind', +} +LLVMVoidTypeKind = 0 +LLVMHalfTypeKind = 1 +LLVMFloatTypeKind = 2 +LLVMDoubleTypeKind = 3 +LLVMX86_FP80TypeKind = 4 +LLVMFP128TypeKind = 5 +LLVMPPC_FP128TypeKind = 6 +LLVMLabelTypeKind = 7 +LLVMIntegerTypeKind = 8 +LLVMFunctionTypeKind = 9 +LLVMStructTypeKind = 10 +LLVMArrayTypeKind = 11 +LLVMPointerTypeKind = 12 +LLVMVectorTypeKind = 13 +LLVMMetadataTypeKind = 14 +LLVMX86_MMXTypeKind = 15 +LLVMTokenTypeKind = 16 +LLVMScalableVectorTypeKind = 17 +LLVMBFloatTypeKind = 18 +LLVMX86_AMXTypeKind = 19 +c__EA_LLVMTypeKind = ctypes.c_uint32 # enum +LLVMTypeKind = c__EA_LLVMTypeKind +LLVMTypeKind__enumvalues = c__EA_LLVMTypeKind__enumvalues + +# values for enumeration 'c__EA_LLVMLinkage' +c__EA_LLVMLinkage__enumvalues = { + 0: 'LLVMExternalLinkage', + 1: 'LLVMAvailableExternallyLinkage', + 2: 'LLVMLinkOnceAnyLinkage', + 3: 'LLVMLinkOnceODRLinkage', + 4: 'LLVMLinkOnceODRAutoHideLinkage', + 5: 'LLVMWeakAnyLinkage', + 6: 'LLVMWeakODRLinkage', + 7: 'LLVMAppendingLinkage', + 8: 'LLVMInternalLinkage', + 9: 'LLVMPrivateLinkage', + 10: 'LLVMDLLImportLinkage', + 11: 'LLVMDLLExportLinkage', + 12: 'LLVMExternalWeakLinkage', + 13: 'LLVMGhostLinkage', + 14: 'LLVMCommonLinkage', + 15: 'LLVMLinkerPrivateLinkage', + 16: 'LLVMLinkerPrivateWeakLinkage', +} +LLVMExternalLinkage = 0 +LLVMAvailableExternallyLinkage = 1 +LLVMLinkOnceAnyLinkage = 2 +LLVMLinkOnceODRLinkage = 3 +LLVMLinkOnceODRAutoHideLinkage = 4 +LLVMWeakAnyLinkage = 5 +LLVMWeakODRLinkage = 6 +LLVMAppendingLinkage = 7 +LLVMInternalLinkage = 8 +LLVMPrivateLinkage = 9 +LLVMDLLImportLinkage = 10 +LLVMDLLExportLinkage = 11 +LLVMExternalWeakLinkage = 12 +LLVMGhostLinkage = 13 +LLVMCommonLinkage = 14 +LLVMLinkerPrivateLinkage = 15 +LLVMLinkerPrivateWeakLinkage = 16 +c__EA_LLVMLinkage = ctypes.c_uint32 # enum +LLVMLinkage = c__EA_LLVMLinkage +LLVMLinkage__enumvalues = c__EA_LLVMLinkage__enumvalues + +# values for enumeration 'c__EA_LLVMVisibility' +c__EA_LLVMVisibility__enumvalues = { + 0: 'LLVMDefaultVisibility', + 1: 'LLVMHiddenVisibility', + 2: 'LLVMProtectedVisibility', +} +LLVMDefaultVisibility = 0 +LLVMHiddenVisibility = 1 +LLVMProtectedVisibility = 2 +c__EA_LLVMVisibility = ctypes.c_uint32 # enum +LLVMVisibility = c__EA_LLVMVisibility +LLVMVisibility__enumvalues = c__EA_LLVMVisibility__enumvalues + +# values for enumeration 'c__EA_LLVMUnnamedAddr' +c__EA_LLVMUnnamedAddr__enumvalues = { + 0: 'LLVMNoUnnamedAddr', + 1: 'LLVMLocalUnnamedAddr', + 2: 'LLVMGlobalUnnamedAddr', +} +LLVMNoUnnamedAddr = 0 +LLVMLocalUnnamedAddr = 1 +LLVMGlobalUnnamedAddr = 2 +c__EA_LLVMUnnamedAddr = ctypes.c_uint32 # enum +LLVMUnnamedAddr = c__EA_LLVMUnnamedAddr +LLVMUnnamedAddr__enumvalues = c__EA_LLVMUnnamedAddr__enumvalues + +# values for enumeration 'c__EA_LLVMDLLStorageClass' +c__EA_LLVMDLLStorageClass__enumvalues = { + 0: 'LLVMDefaultStorageClass', + 1: 'LLVMDLLImportStorageClass', + 2: 'LLVMDLLExportStorageClass', +} +LLVMDefaultStorageClass = 0 +LLVMDLLImportStorageClass = 1 +LLVMDLLExportStorageClass = 2 +c__EA_LLVMDLLStorageClass = ctypes.c_uint32 # enum +LLVMDLLStorageClass = c__EA_LLVMDLLStorageClass +LLVMDLLStorageClass__enumvalues = c__EA_LLVMDLLStorageClass__enumvalues + +# values for enumeration 'c__EA_LLVMCallConv' +c__EA_LLVMCallConv__enumvalues = { + 0: 'LLVMCCallConv', + 8: 'LLVMFastCallConv', + 9: 'LLVMColdCallConv', + 10: 'LLVMGHCCallConv', + 11: 'LLVMHiPECallConv', + 12: 'LLVMWebKitJSCallConv', + 13: 'LLVMAnyRegCallConv', + 14: 'LLVMPreserveMostCallConv', + 15: 'LLVMPreserveAllCallConv', + 16: 'LLVMSwiftCallConv', + 17: 'LLVMCXXFASTTLSCallConv', + 64: 'LLVMX86StdcallCallConv', + 65: 'LLVMX86FastcallCallConv', + 66: 'LLVMARMAPCSCallConv', + 67: 'LLVMARMAAPCSCallConv', + 68: 'LLVMARMAAPCSVFPCallConv', + 69: 'LLVMMSP430INTRCallConv', + 70: 'LLVMX86ThisCallCallConv', + 71: 'LLVMPTXKernelCallConv', + 72: 'LLVMPTXDeviceCallConv', + 75: 'LLVMSPIRFUNCCallConv', + 76: 'LLVMSPIRKERNELCallConv', + 77: 'LLVMIntelOCLBICallConv', + 78: 'LLVMX8664SysVCallConv', + 79: 'LLVMWin64CallConv', + 80: 'LLVMX86VectorCallCallConv', + 81: 'LLVMHHVMCallConv', + 82: 'LLVMHHVMCCallConv', + 83: 'LLVMX86INTRCallConv', + 84: 'LLVMAVRINTRCallConv', + 85: 'LLVMAVRSIGNALCallConv', + 86: 'LLVMAVRBUILTINCallConv', + 87: 'LLVMAMDGPUVSCallConv', + 88: 'LLVMAMDGPUGSCallConv', + 89: 'LLVMAMDGPUPSCallConv', + 90: 'LLVMAMDGPUCSCallConv', + 91: 'LLVMAMDGPUKERNELCallConv', + 92: 'LLVMX86RegCallCallConv', + 93: 'LLVMAMDGPUHSCallConv', + 94: 'LLVMMSP430BUILTINCallConv', + 95: 'LLVMAMDGPULSCallConv', + 96: 'LLVMAMDGPUESCallConv', +} +LLVMCCallConv = 0 +LLVMFastCallConv = 8 +LLVMColdCallConv = 9 +LLVMGHCCallConv = 10 +LLVMHiPECallConv = 11 +LLVMWebKitJSCallConv = 12 +LLVMAnyRegCallConv = 13 +LLVMPreserveMostCallConv = 14 +LLVMPreserveAllCallConv = 15 +LLVMSwiftCallConv = 16 +LLVMCXXFASTTLSCallConv = 17 +LLVMX86StdcallCallConv = 64 +LLVMX86FastcallCallConv = 65 +LLVMARMAPCSCallConv = 66 +LLVMARMAAPCSCallConv = 67 +LLVMARMAAPCSVFPCallConv = 68 +LLVMMSP430INTRCallConv = 69 +LLVMX86ThisCallCallConv = 70 +LLVMPTXKernelCallConv = 71 +LLVMPTXDeviceCallConv = 72 +LLVMSPIRFUNCCallConv = 75 +LLVMSPIRKERNELCallConv = 76 +LLVMIntelOCLBICallConv = 77 +LLVMX8664SysVCallConv = 78 +LLVMWin64CallConv = 79 +LLVMX86VectorCallCallConv = 80 +LLVMHHVMCallConv = 81 +LLVMHHVMCCallConv = 82 +LLVMX86INTRCallConv = 83 +LLVMAVRINTRCallConv = 84 +LLVMAVRSIGNALCallConv = 85 +LLVMAVRBUILTINCallConv = 86 +LLVMAMDGPUVSCallConv = 87 +LLVMAMDGPUGSCallConv = 88 +LLVMAMDGPUPSCallConv = 89 +LLVMAMDGPUCSCallConv = 90 +LLVMAMDGPUKERNELCallConv = 91 +LLVMX86RegCallCallConv = 92 +LLVMAMDGPUHSCallConv = 93 +LLVMMSP430BUILTINCallConv = 94 +LLVMAMDGPULSCallConv = 95 +LLVMAMDGPUESCallConv = 96 +c__EA_LLVMCallConv = ctypes.c_uint32 # enum +LLVMCallConv = c__EA_LLVMCallConv +LLVMCallConv__enumvalues = c__EA_LLVMCallConv__enumvalues + +# values for enumeration 'c__EA_LLVMValueKind' +c__EA_LLVMValueKind__enumvalues = { + 0: 'LLVMArgumentValueKind', + 1: 'LLVMBasicBlockValueKind', + 2: 'LLVMMemoryUseValueKind', + 3: 'LLVMMemoryDefValueKind', + 4: 'LLVMMemoryPhiValueKind', + 5: 'LLVMFunctionValueKind', + 6: 'LLVMGlobalAliasValueKind', + 7: 'LLVMGlobalIFuncValueKind', + 8: 'LLVMGlobalVariableValueKind', + 9: 'LLVMBlockAddressValueKind', + 10: 'LLVMConstantExprValueKind', + 11: 'LLVMConstantArrayValueKind', + 12: 'LLVMConstantStructValueKind', + 13: 'LLVMConstantVectorValueKind', + 14: 'LLVMUndefValueValueKind', + 15: 'LLVMConstantAggregateZeroValueKind', + 16: 'LLVMConstantDataArrayValueKind', + 17: 'LLVMConstantDataVectorValueKind', + 18: 'LLVMConstantIntValueKind', + 19: 'LLVMConstantFPValueKind', + 20: 'LLVMConstantPointerNullValueKind', + 21: 'LLVMConstantTokenNoneValueKind', + 22: 'LLVMMetadataAsValueValueKind', + 23: 'LLVMInlineAsmValueKind', + 24: 'LLVMInstructionValueKind', + 25: 'LLVMPoisonValueValueKind', +} +LLVMArgumentValueKind = 0 +LLVMBasicBlockValueKind = 1 +LLVMMemoryUseValueKind = 2 +LLVMMemoryDefValueKind = 3 +LLVMMemoryPhiValueKind = 4 +LLVMFunctionValueKind = 5 +LLVMGlobalAliasValueKind = 6 +LLVMGlobalIFuncValueKind = 7 +LLVMGlobalVariableValueKind = 8 +LLVMBlockAddressValueKind = 9 +LLVMConstantExprValueKind = 10 +LLVMConstantArrayValueKind = 11 +LLVMConstantStructValueKind = 12 +LLVMConstantVectorValueKind = 13 +LLVMUndefValueValueKind = 14 +LLVMConstantAggregateZeroValueKind = 15 +LLVMConstantDataArrayValueKind = 16 +LLVMConstantDataVectorValueKind = 17 +LLVMConstantIntValueKind = 18 +LLVMConstantFPValueKind = 19 +LLVMConstantPointerNullValueKind = 20 +LLVMConstantTokenNoneValueKind = 21 +LLVMMetadataAsValueValueKind = 22 +LLVMInlineAsmValueKind = 23 +LLVMInstructionValueKind = 24 +LLVMPoisonValueValueKind = 25 +c__EA_LLVMValueKind = ctypes.c_uint32 # enum +LLVMValueKind = c__EA_LLVMValueKind +LLVMValueKind__enumvalues = c__EA_LLVMValueKind__enumvalues + +# values for enumeration 'c__EA_LLVMIntPredicate' +c__EA_LLVMIntPredicate__enumvalues = { + 32: 'LLVMIntEQ', + 33: 'LLVMIntNE', + 34: 'LLVMIntUGT', + 35: 'LLVMIntUGE', + 36: 'LLVMIntULT', + 37: 'LLVMIntULE', + 38: 'LLVMIntSGT', + 39: 'LLVMIntSGE', + 40: 'LLVMIntSLT', + 41: 'LLVMIntSLE', +} +LLVMIntEQ = 32 +LLVMIntNE = 33 +LLVMIntUGT = 34 +LLVMIntUGE = 35 +LLVMIntULT = 36 +LLVMIntULE = 37 +LLVMIntSGT = 38 +LLVMIntSGE = 39 +LLVMIntSLT = 40 +LLVMIntSLE = 41 +c__EA_LLVMIntPredicate = ctypes.c_uint32 # enum +LLVMIntPredicate = c__EA_LLVMIntPredicate +LLVMIntPredicate__enumvalues = c__EA_LLVMIntPredicate__enumvalues + +# values for enumeration 'c__EA_LLVMRealPredicate' +c__EA_LLVMRealPredicate__enumvalues = { + 0: 'LLVMRealPredicateFalse', + 1: 'LLVMRealOEQ', + 2: 'LLVMRealOGT', + 3: 'LLVMRealOGE', + 4: 'LLVMRealOLT', + 5: 'LLVMRealOLE', + 6: 'LLVMRealONE', + 7: 'LLVMRealORD', + 8: 'LLVMRealUNO', + 9: 'LLVMRealUEQ', + 10: 'LLVMRealUGT', + 11: 'LLVMRealUGE', + 12: 'LLVMRealULT', + 13: 'LLVMRealULE', + 14: 'LLVMRealUNE', + 15: 'LLVMRealPredicateTrue', +} +LLVMRealPredicateFalse = 0 +LLVMRealOEQ = 1 +LLVMRealOGT = 2 +LLVMRealOGE = 3 +LLVMRealOLT = 4 +LLVMRealOLE = 5 +LLVMRealONE = 6 +LLVMRealORD = 7 +LLVMRealUNO = 8 +LLVMRealUEQ = 9 +LLVMRealUGT = 10 +LLVMRealUGE = 11 +LLVMRealULT = 12 +LLVMRealULE = 13 +LLVMRealUNE = 14 +LLVMRealPredicateTrue = 15 +c__EA_LLVMRealPredicate = ctypes.c_uint32 # enum +LLVMRealPredicate = c__EA_LLVMRealPredicate +LLVMRealPredicate__enumvalues = c__EA_LLVMRealPredicate__enumvalues + +# values for enumeration 'c__EA_LLVMLandingPadClauseTy' +c__EA_LLVMLandingPadClauseTy__enumvalues = { + 0: 'LLVMLandingPadCatch', + 1: 'LLVMLandingPadFilter', +} +LLVMLandingPadCatch = 0 +LLVMLandingPadFilter = 1 +c__EA_LLVMLandingPadClauseTy = ctypes.c_uint32 # enum +LLVMLandingPadClauseTy = c__EA_LLVMLandingPadClauseTy +LLVMLandingPadClauseTy__enumvalues = c__EA_LLVMLandingPadClauseTy__enumvalues + +# values for enumeration 'c__EA_LLVMThreadLocalMode' +c__EA_LLVMThreadLocalMode__enumvalues = { + 0: 'LLVMNotThreadLocal', + 1: 'LLVMGeneralDynamicTLSModel', + 2: 'LLVMLocalDynamicTLSModel', + 3: 'LLVMInitialExecTLSModel', + 4: 'LLVMLocalExecTLSModel', +} +LLVMNotThreadLocal = 0 +LLVMGeneralDynamicTLSModel = 1 +LLVMLocalDynamicTLSModel = 2 +LLVMInitialExecTLSModel = 3 +LLVMLocalExecTLSModel = 4 +c__EA_LLVMThreadLocalMode = ctypes.c_uint32 # enum +LLVMThreadLocalMode = c__EA_LLVMThreadLocalMode +LLVMThreadLocalMode__enumvalues = c__EA_LLVMThreadLocalMode__enumvalues + +# values for enumeration 'c__EA_LLVMAtomicOrdering' +c__EA_LLVMAtomicOrdering__enumvalues = { + 0: 'LLVMAtomicOrderingNotAtomic', + 1: 'LLVMAtomicOrderingUnordered', + 2: 'LLVMAtomicOrderingMonotonic', + 4: 'LLVMAtomicOrderingAcquire', + 5: 'LLVMAtomicOrderingRelease', + 6: 'LLVMAtomicOrderingAcquireRelease', + 7: 'LLVMAtomicOrderingSequentiallyConsistent', +} +LLVMAtomicOrderingNotAtomic = 0 +LLVMAtomicOrderingUnordered = 1 +LLVMAtomicOrderingMonotonic = 2 +LLVMAtomicOrderingAcquire = 4 +LLVMAtomicOrderingRelease = 5 +LLVMAtomicOrderingAcquireRelease = 6 +LLVMAtomicOrderingSequentiallyConsistent = 7 +c__EA_LLVMAtomicOrdering = ctypes.c_uint32 # enum +LLVMAtomicOrdering = c__EA_LLVMAtomicOrdering +LLVMAtomicOrdering__enumvalues = c__EA_LLVMAtomicOrdering__enumvalues + +# values for enumeration 'c__EA_LLVMAtomicRMWBinOp' +c__EA_LLVMAtomicRMWBinOp__enumvalues = { + 0: 'LLVMAtomicRMWBinOpXchg', + 1: 'LLVMAtomicRMWBinOpAdd', + 2: 'LLVMAtomicRMWBinOpSub', + 3: 'LLVMAtomicRMWBinOpAnd', + 4: 'LLVMAtomicRMWBinOpNand', + 5: 'LLVMAtomicRMWBinOpOr', + 6: 'LLVMAtomicRMWBinOpXor', + 7: 'LLVMAtomicRMWBinOpMax', + 8: 'LLVMAtomicRMWBinOpMin', + 9: 'LLVMAtomicRMWBinOpUMax', + 10: 'LLVMAtomicRMWBinOpUMin', + 11: 'LLVMAtomicRMWBinOpFAdd', + 12: 'LLVMAtomicRMWBinOpFSub', +} +LLVMAtomicRMWBinOpXchg = 0 +LLVMAtomicRMWBinOpAdd = 1 +LLVMAtomicRMWBinOpSub = 2 +LLVMAtomicRMWBinOpAnd = 3 +LLVMAtomicRMWBinOpNand = 4 +LLVMAtomicRMWBinOpOr = 5 +LLVMAtomicRMWBinOpXor = 6 +LLVMAtomicRMWBinOpMax = 7 +LLVMAtomicRMWBinOpMin = 8 +LLVMAtomicRMWBinOpUMax = 9 +LLVMAtomicRMWBinOpUMin = 10 +LLVMAtomicRMWBinOpFAdd = 11 +LLVMAtomicRMWBinOpFSub = 12 +c__EA_LLVMAtomicRMWBinOp = ctypes.c_uint32 # enum +LLVMAtomicRMWBinOp = c__EA_LLVMAtomicRMWBinOp +LLVMAtomicRMWBinOp__enumvalues = c__EA_LLVMAtomicRMWBinOp__enumvalues + +# values for enumeration 'c__EA_LLVMDiagnosticSeverity' +c__EA_LLVMDiagnosticSeverity__enumvalues = { + 0: 'LLVMDSError', + 1: 'LLVMDSWarning', + 2: 'LLVMDSRemark', + 3: 'LLVMDSNote', +} +LLVMDSError = 0 +LLVMDSWarning = 1 +LLVMDSRemark = 2 +LLVMDSNote = 3 +c__EA_LLVMDiagnosticSeverity = ctypes.c_uint32 # enum +LLVMDiagnosticSeverity = c__EA_LLVMDiagnosticSeverity +LLVMDiagnosticSeverity__enumvalues = c__EA_LLVMDiagnosticSeverity__enumvalues + +# values for enumeration 'c__EA_LLVMInlineAsmDialect' +c__EA_LLVMInlineAsmDialect__enumvalues = { + 0: 'LLVMInlineAsmDialectATT', + 1: 'LLVMInlineAsmDialectIntel', +} +LLVMInlineAsmDialectATT = 0 +LLVMInlineAsmDialectIntel = 1 +c__EA_LLVMInlineAsmDialect = ctypes.c_uint32 # enum +LLVMInlineAsmDialect = c__EA_LLVMInlineAsmDialect +LLVMInlineAsmDialect__enumvalues = c__EA_LLVMInlineAsmDialect__enumvalues + +# values for enumeration 'c__EA_LLVMModuleFlagBehavior' +c__EA_LLVMModuleFlagBehavior__enumvalues = { + 0: 'LLVMModuleFlagBehaviorError', + 1: 'LLVMModuleFlagBehaviorWarning', + 2: 'LLVMModuleFlagBehaviorRequire', + 3: 'LLVMModuleFlagBehaviorOverride', + 4: 'LLVMModuleFlagBehaviorAppend', + 5: 'LLVMModuleFlagBehaviorAppendUnique', +} +LLVMModuleFlagBehaviorError = 0 +LLVMModuleFlagBehaviorWarning = 1 +LLVMModuleFlagBehaviorRequire = 2 +LLVMModuleFlagBehaviorOverride = 3 +LLVMModuleFlagBehaviorAppend = 4 +LLVMModuleFlagBehaviorAppendUnique = 5 +c__EA_LLVMModuleFlagBehavior = ctypes.c_uint32 # enum +LLVMModuleFlagBehavior = c__EA_LLVMModuleFlagBehavior +LLVMModuleFlagBehavior__enumvalues = c__EA_LLVMModuleFlagBehavior__enumvalues + +# values for enumeration 'c__Ea_LLVMAttributeReturnIndex' +c__Ea_LLVMAttributeReturnIndex__enumvalues = { + 0: 'LLVMAttributeReturnIndex', + -1: 'LLVMAttributeFunctionIndex', +} +LLVMAttributeReturnIndex = 0 +LLVMAttributeFunctionIndex = -1 +c__Ea_LLVMAttributeReturnIndex = ctypes.c_int32 # enum +LLVMAttributeIndex = ctypes.c_uint32 +try: + LLVMInitializeCore = _libraries['llvm'].LLVMInitializeCore + LLVMInitializeCore.restype = None + LLVMInitializeCore.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMShutdown = _libraries['llvm'].LLVMShutdown + LLVMShutdown.restype = None + LLVMShutdown.argtypes = [] +except AttributeError: + pass +try: + LLVMCreateMessage = _libraries['llvm'].LLVMCreateMessage + LLVMCreateMessage.restype = ctypes.POINTER(ctypes.c_char) + LLVMCreateMessage.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMDisposeMessage = _libraries['llvm'].LLVMDisposeMessage + LLVMDisposeMessage.restype = None + LLVMDisposeMessage.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +LLVMDiagnosticHandler = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_LLVMOpaqueDiagnosticInfo), ctypes.POINTER(None)) +LLVMYieldCallback = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_LLVMOpaqueContext), ctypes.POINTER(None)) +try: + LLVMContextCreate = _libraries['llvm'].LLVMContextCreate + LLVMContextCreate.restype = LLVMContextRef + LLVMContextCreate.argtypes = [] +except AttributeError: + pass +try: + LLVMGetGlobalContext = _libraries['llvm'].LLVMGetGlobalContext + LLVMGetGlobalContext.restype = LLVMContextRef + LLVMGetGlobalContext.argtypes = [] +except AttributeError: + pass +try: + LLVMContextSetDiagnosticHandler = _libraries['llvm'].LLVMContextSetDiagnosticHandler + LLVMContextSetDiagnosticHandler.restype = None + LLVMContextSetDiagnosticHandler.argtypes = [LLVMContextRef, LLVMDiagnosticHandler, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMContextGetDiagnosticHandler = _libraries['llvm'].LLVMContextGetDiagnosticHandler + LLVMContextGetDiagnosticHandler.restype = LLVMDiagnosticHandler + LLVMContextGetDiagnosticHandler.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMContextGetDiagnosticContext = _libraries['llvm'].LLVMContextGetDiagnosticContext + LLVMContextGetDiagnosticContext.restype = ctypes.POINTER(None) + LLVMContextGetDiagnosticContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMContextSetYieldCallback = _libraries['llvm'].LLVMContextSetYieldCallback + LLVMContextSetYieldCallback.restype = None + LLVMContextSetYieldCallback.argtypes = [LLVMContextRef, LLVMYieldCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMContextShouldDiscardValueNames = _libraries['llvm'].LLVMContextShouldDiscardValueNames + LLVMContextShouldDiscardValueNames.restype = LLVMBool + LLVMContextShouldDiscardValueNames.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMContextSetDiscardValueNames = _libraries['llvm'].LLVMContextSetDiscardValueNames + LLVMContextSetDiscardValueNames.restype = None + LLVMContextSetDiscardValueNames.argtypes = [LLVMContextRef, LLVMBool] +except AttributeError: + pass +try: + LLVMContextDispose = _libraries['llvm'].LLVMContextDispose + LLVMContextDispose.restype = None + LLVMContextDispose.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMGetDiagInfoDescription = _libraries['llvm'].LLVMGetDiagInfoDescription + LLVMGetDiagInfoDescription.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDiagInfoDescription.argtypes = [LLVMDiagnosticInfoRef] +except AttributeError: + pass +try: + LLVMGetDiagInfoSeverity = _libraries['llvm'].LLVMGetDiagInfoSeverity + LLVMGetDiagInfoSeverity.restype = LLVMDiagnosticSeverity + LLVMGetDiagInfoSeverity.argtypes = [LLVMDiagnosticInfoRef] +except AttributeError: + pass +try: + LLVMGetMDKindIDInContext = _libraries['llvm'].LLVMGetMDKindIDInContext + LLVMGetMDKindIDInContext.restype = ctypes.c_uint32 + LLVMGetMDKindIDInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetMDKindID = _libraries['llvm'].LLVMGetMDKindID + LLVMGetMDKindID.restype = ctypes.c_uint32 + LLVMGetMDKindID.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +size_t = ctypes.c_uint64 +try: + LLVMGetEnumAttributeKindForName = _libraries['llvm'].LLVMGetEnumAttributeKindForName + LLVMGetEnumAttributeKindForName.restype = ctypes.c_uint32 + LLVMGetEnumAttributeKindForName.argtypes = [ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetLastEnumAttributeKind = _libraries['llvm'].LLVMGetLastEnumAttributeKind + LLVMGetLastEnumAttributeKind.restype = ctypes.c_uint32 + LLVMGetLastEnumAttributeKind.argtypes = [] +except AttributeError: + pass +uint64_t = ctypes.c_uint64 +try: + LLVMCreateEnumAttribute = _libraries['llvm'].LLVMCreateEnumAttribute + LLVMCreateEnumAttribute.restype = LLVMAttributeRef + LLVMCreateEnumAttribute.argtypes = [LLVMContextRef, ctypes.c_uint32, uint64_t] +except AttributeError: + pass +try: + LLVMGetEnumAttributeKind = _libraries['llvm'].LLVMGetEnumAttributeKind + LLVMGetEnumAttributeKind.restype = ctypes.c_uint32 + LLVMGetEnumAttributeKind.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMGetEnumAttributeValue = _libraries['llvm'].LLVMGetEnumAttributeValue + LLVMGetEnumAttributeValue.restype = uint64_t + LLVMGetEnumAttributeValue.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMCreateTypeAttribute = _libraries['llvm'].LLVMCreateTypeAttribute + LLVMCreateTypeAttribute.restype = LLVMAttributeRef + LLVMCreateTypeAttribute.argtypes = [LLVMContextRef, ctypes.c_uint32, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetTypeAttributeValue = _libraries['llvm'].LLVMGetTypeAttributeValue + LLVMGetTypeAttributeValue.restype = LLVMTypeRef + LLVMGetTypeAttributeValue.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMCreateStringAttribute = _libraries['llvm'].LLVMCreateStringAttribute + LLVMCreateStringAttribute.restype = LLVMAttributeRef + LLVMCreateStringAttribute.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetStringAttributeKind = _libraries['llvm'].LLVMGetStringAttributeKind + LLVMGetStringAttributeKind.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetStringAttributeKind.argtypes = [LLVMAttributeRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMGetStringAttributeValue = _libraries['llvm'].LLVMGetStringAttributeValue + LLVMGetStringAttributeValue.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetStringAttributeValue.argtypes = [LLVMAttributeRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMIsEnumAttribute = _libraries['llvm'].LLVMIsEnumAttribute + LLVMIsEnumAttribute.restype = LLVMBool + LLVMIsEnumAttribute.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMIsStringAttribute = _libraries['llvm'].LLVMIsStringAttribute + LLVMIsStringAttribute.restype = LLVMBool + LLVMIsStringAttribute.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMIsTypeAttribute = _libraries['llvm'].LLVMIsTypeAttribute + LLVMIsTypeAttribute.restype = LLVMBool + LLVMIsTypeAttribute.argtypes = [LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMGetTypeByName2 = _libraries['llvm'].LLVMGetTypeByName2 + LLVMGetTypeByName2.restype = LLVMTypeRef + LLVMGetTypeByName2.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMModuleCreateWithName = _libraries['llvm'].LLVMModuleCreateWithName + LLVMModuleCreateWithName.restype = LLVMModuleRef + LLVMModuleCreateWithName.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMModuleCreateWithNameInContext = _libraries['llvm'].LLVMModuleCreateWithNameInContext + LLVMModuleCreateWithNameInContext.restype = LLVMModuleRef + LLVMModuleCreateWithNameInContext.argtypes = [ctypes.POINTER(ctypes.c_char), LLVMContextRef] +except AttributeError: + pass +try: + LLVMCloneModule = _libraries['llvm'].LLVMCloneModule + LLVMCloneModule.restype = LLVMModuleRef + LLVMCloneModule.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMDisposeModule = _libraries['llvm'].LLVMDisposeModule + LLVMDisposeModule.restype = None + LLVMDisposeModule.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetModuleIdentifier = _libraries['llvm'].LLVMGetModuleIdentifier + LLVMGetModuleIdentifier.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetModuleIdentifier.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMSetModuleIdentifier = _libraries['llvm'].LLVMSetModuleIdentifier + LLVMSetModuleIdentifier.restype = None + LLVMSetModuleIdentifier.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetSourceFileName = _libraries['llvm'].LLVMGetSourceFileName + LLVMGetSourceFileName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetSourceFileName.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMSetSourceFileName = _libraries['llvm'].LLVMSetSourceFileName + LLVMSetSourceFileName.restype = None + LLVMSetSourceFileName.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetDataLayoutStr = _libraries['llvm'].LLVMGetDataLayoutStr + LLVMGetDataLayoutStr.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDataLayoutStr.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetDataLayout = _libraries['llvm'].LLVMGetDataLayout + LLVMGetDataLayout.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDataLayout.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMSetDataLayout = _libraries['llvm'].LLVMSetDataLayout + LLVMSetDataLayout.restype = None + LLVMSetDataLayout.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetTarget = _libraries['llvm'].LLVMGetTarget + LLVMGetTarget.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTarget.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMSetTarget = _libraries['llvm'].LLVMSetTarget + LLVMSetTarget.restype = None + LLVMSetTarget.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMCopyModuleFlagsMetadata = _libraries['llvm'].LLVMCopyModuleFlagsMetadata + LLVMCopyModuleFlagsMetadata.restype = ctypes.POINTER(struct_LLVMOpaqueModuleFlagEntry) + LLVMCopyModuleFlagsMetadata.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMDisposeModuleFlagsMetadata = _libraries['llvm'].LLVMDisposeModuleFlagsMetadata + LLVMDisposeModuleFlagsMetadata.restype = None + LLVMDisposeModuleFlagsMetadata.argtypes = [ctypes.POINTER(struct_LLVMOpaqueModuleFlagEntry)] +except AttributeError: + pass +try: + LLVMModuleFlagEntriesGetFlagBehavior = _libraries['llvm'].LLVMModuleFlagEntriesGetFlagBehavior + LLVMModuleFlagEntriesGetFlagBehavior.restype = LLVMModuleFlagBehavior + LLVMModuleFlagEntriesGetFlagBehavior.argtypes = [ctypes.POINTER(struct_LLVMOpaqueModuleFlagEntry), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMModuleFlagEntriesGetKey = _libraries['llvm'].LLVMModuleFlagEntriesGetKey + LLVMModuleFlagEntriesGetKey.restype = ctypes.POINTER(ctypes.c_char) + LLVMModuleFlagEntriesGetKey.argtypes = [ctypes.POINTER(struct_LLVMOpaqueModuleFlagEntry), ctypes.c_uint32, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMModuleFlagEntriesGetMetadata = _libraries['llvm'].LLVMModuleFlagEntriesGetMetadata + LLVMModuleFlagEntriesGetMetadata.restype = LLVMMetadataRef + LLVMModuleFlagEntriesGetMetadata.argtypes = [ctypes.POINTER(struct_LLVMOpaqueModuleFlagEntry), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetModuleFlag = _libraries['llvm'].LLVMGetModuleFlag + LLVMGetModuleFlag.restype = LLVMMetadataRef + LLVMGetModuleFlag.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMAddModuleFlag = _libraries['llvm'].LLVMAddModuleFlag + LLVMAddModuleFlag.restype = None + LLVMAddModuleFlag.argtypes = [LLVMModuleRef, LLVMModuleFlagBehavior, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDumpModule = _libraries['llvm'].LLVMDumpModule + LLVMDumpModule.restype = None + LLVMDumpModule.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMPrintModuleToFile = _libraries['llvm'].LLVMPrintModuleToFile + LLVMPrintModuleToFile.restype = LLVMBool + LLVMPrintModuleToFile.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMPrintModuleToString = _libraries['llvm'].LLVMPrintModuleToString + LLVMPrintModuleToString.restype = ctypes.POINTER(ctypes.c_char) + LLVMPrintModuleToString.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetModuleInlineAsm = _libraries['llvm'].LLVMGetModuleInlineAsm + LLVMGetModuleInlineAsm.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetModuleInlineAsm.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMSetModuleInlineAsm2 = _libraries['llvm'].LLVMSetModuleInlineAsm2 + LLVMSetModuleInlineAsm2.restype = None + LLVMSetModuleInlineAsm2.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMAppendModuleInlineAsm = _libraries['llvm'].LLVMAppendModuleInlineAsm + LLVMAppendModuleInlineAsm.restype = None + LLVMAppendModuleInlineAsm.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetInlineAsm = _libraries['llvm'].LLVMGetInlineAsm + LLVMGetInlineAsm.restype = LLVMValueRef + LLVMGetInlineAsm.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, LLVMBool, LLVMBool, LLVMInlineAsmDialect, LLVMBool] +except AttributeError: + pass +try: + LLVMGetModuleContext = _libraries['llvm'].LLVMGetModuleContext + LLVMGetModuleContext.restype = LLVMContextRef + LLVMGetModuleContext.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetTypeByName = _libraries['llvm'].LLVMGetTypeByName + LLVMGetTypeByName.restype = LLVMTypeRef + LLVMGetTypeByName.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetFirstNamedMetadata = _libraries['llvm'].LLVMGetFirstNamedMetadata + LLVMGetFirstNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetFirstNamedMetadata.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetLastNamedMetadata = _libraries['llvm'].LLVMGetLastNamedMetadata + LLVMGetLastNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetLastNamedMetadata.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetNextNamedMetadata = _libraries['llvm'].LLVMGetNextNamedMetadata + LLVMGetNextNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetNextNamedMetadata.argtypes = [LLVMNamedMDNodeRef] +except AttributeError: + pass +try: + LLVMGetPreviousNamedMetadata = _libraries['llvm'].LLVMGetPreviousNamedMetadata + LLVMGetPreviousNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetPreviousNamedMetadata.argtypes = [LLVMNamedMDNodeRef] +except AttributeError: + pass +try: + LLVMGetNamedMetadata = _libraries['llvm'].LLVMGetNamedMetadata + LLVMGetNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetNamedMetadata.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetOrInsertNamedMetadata = _libraries['llvm'].LLVMGetOrInsertNamedMetadata + LLVMGetOrInsertNamedMetadata.restype = LLVMNamedMDNodeRef + LLVMGetOrInsertNamedMetadata.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetNamedMetadataName = _libraries['llvm'].LLVMGetNamedMetadataName + LLVMGetNamedMetadataName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetNamedMetadataName.argtypes = [LLVMNamedMDNodeRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMGetNamedMetadataNumOperands = _libraries['llvm'].LLVMGetNamedMetadataNumOperands + LLVMGetNamedMetadataNumOperands.restype = ctypes.c_uint32 + LLVMGetNamedMetadataNumOperands.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetNamedMetadataOperands = _libraries['llvm'].LLVMGetNamedMetadataOperands + LLVMGetNamedMetadataOperands.restype = None + LLVMGetNamedMetadataOperands.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue))] +except AttributeError: + pass +try: + LLVMAddNamedMetadataOperand = _libraries['llvm'].LLVMAddNamedMetadataOperand + LLVMAddNamedMetadataOperand.restype = None + LLVMAddNamedMetadataOperand.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetDebugLocDirectory = _libraries['llvm'].LLVMGetDebugLocDirectory + LLVMGetDebugLocDirectory.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDebugLocDirectory.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMGetDebugLocFilename = _libraries['llvm'].LLVMGetDebugLocFilename + LLVMGetDebugLocFilename.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDebugLocFilename.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMGetDebugLocLine = _libraries['llvm'].LLVMGetDebugLocLine + LLVMGetDebugLocLine.restype = ctypes.c_uint32 + LLVMGetDebugLocLine.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetDebugLocColumn = _libraries['llvm'].LLVMGetDebugLocColumn + LLVMGetDebugLocColumn.restype = ctypes.c_uint32 + LLVMGetDebugLocColumn.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMAddFunction = _libraries['llvm'].LLVMAddFunction + LLVMAddFunction.restype = LLVMValueRef + LLVMAddFunction.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetNamedFunction = _libraries['llvm'].LLVMGetNamedFunction + LLVMGetNamedFunction.restype = LLVMValueRef + LLVMGetNamedFunction.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetFirstFunction = _libraries['llvm'].LLVMGetFirstFunction + LLVMGetFirstFunction.restype = LLVMValueRef + LLVMGetFirstFunction.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetLastFunction = _libraries['llvm'].LLVMGetLastFunction + LLVMGetLastFunction.restype = LLVMValueRef + LLVMGetLastFunction.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetNextFunction = _libraries['llvm'].LLVMGetNextFunction + LLVMGetNextFunction.restype = LLVMValueRef + LLVMGetNextFunction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousFunction = _libraries['llvm'].LLVMGetPreviousFunction + LLVMGetPreviousFunction.restype = LLVMValueRef + LLVMGetPreviousFunction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetModuleInlineAsm = _libraries['llvm'].LLVMSetModuleInlineAsm + LLVMSetModuleInlineAsm.restype = None + LLVMSetModuleInlineAsm.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetTypeKind = _libraries['llvm'].LLVMGetTypeKind + LLVMGetTypeKind.restype = LLVMTypeKind + LLVMGetTypeKind.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMTypeIsSized = _libraries['llvm'].LLVMTypeIsSized + LLVMTypeIsSized.restype = LLVMBool + LLVMTypeIsSized.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetTypeContext = _libraries['llvm'].LLVMGetTypeContext + LLVMGetTypeContext.restype = LLVMContextRef + LLVMGetTypeContext.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMDumpType = _libraries['llvm'].LLVMDumpType + LLVMDumpType.restype = None + LLVMDumpType.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMPrintTypeToString = _libraries['llvm'].LLVMPrintTypeToString + LLVMPrintTypeToString.restype = ctypes.POINTER(ctypes.c_char) + LLVMPrintTypeToString.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMInt1TypeInContext = _libraries['llvm'].LLVMInt1TypeInContext + LLVMInt1TypeInContext.restype = LLVMTypeRef + LLVMInt1TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMInt8TypeInContext = _libraries['llvm'].LLVMInt8TypeInContext + LLVMInt8TypeInContext.restype = LLVMTypeRef + LLVMInt8TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMInt16TypeInContext = _libraries['llvm'].LLVMInt16TypeInContext + LLVMInt16TypeInContext.restype = LLVMTypeRef + LLVMInt16TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMInt32TypeInContext = _libraries['llvm'].LLVMInt32TypeInContext + LLVMInt32TypeInContext.restype = LLVMTypeRef + LLVMInt32TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMInt64TypeInContext = _libraries['llvm'].LLVMInt64TypeInContext + LLVMInt64TypeInContext.restype = LLVMTypeRef + LLVMInt64TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMInt128TypeInContext = _libraries['llvm'].LLVMInt128TypeInContext + LLVMInt128TypeInContext.restype = LLVMTypeRef + LLVMInt128TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMIntTypeInContext = _libraries['llvm'].LLVMIntTypeInContext + LLVMIntTypeInContext.restype = LLVMTypeRef + LLVMIntTypeInContext.argtypes = [LLVMContextRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMInt1Type = _libraries['llvm'].LLVMInt1Type + LLVMInt1Type.restype = LLVMTypeRef + LLVMInt1Type.argtypes = [] +except AttributeError: + pass +try: + LLVMInt8Type = _libraries['llvm'].LLVMInt8Type + LLVMInt8Type.restype = LLVMTypeRef + LLVMInt8Type.argtypes = [] +except AttributeError: + pass +try: + LLVMInt16Type = _libraries['llvm'].LLVMInt16Type + LLVMInt16Type.restype = LLVMTypeRef + LLVMInt16Type.argtypes = [] +except AttributeError: + pass +try: + LLVMInt32Type = _libraries['llvm'].LLVMInt32Type + LLVMInt32Type.restype = LLVMTypeRef + LLVMInt32Type.argtypes = [] +except AttributeError: + pass +try: + LLVMInt64Type = _libraries['llvm'].LLVMInt64Type + LLVMInt64Type.restype = LLVMTypeRef + LLVMInt64Type.argtypes = [] +except AttributeError: + pass +try: + LLVMInt128Type = _libraries['llvm'].LLVMInt128Type + LLVMInt128Type.restype = LLVMTypeRef + LLVMInt128Type.argtypes = [] +except AttributeError: + pass +try: + LLVMIntType = _libraries['llvm'].LLVMIntType + LLVMIntType.restype = LLVMTypeRef + LLVMIntType.argtypes = [ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetIntTypeWidth = _libraries['llvm'].LLVMGetIntTypeWidth + LLVMGetIntTypeWidth.restype = ctypes.c_uint32 + LLVMGetIntTypeWidth.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMHalfTypeInContext = _libraries['llvm'].LLVMHalfTypeInContext + LLVMHalfTypeInContext.restype = LLVMTypeRef + LLVMHalfTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMBFloatTypeInContext = _libraries['llvm'].LLVMBFloatTypeInContext + LLVMBFloatTypeInContext.restype = LLVMTypeRef + LLVMBFloatTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMFloatTypeInContext = _libraries['llvm'].LLVMFloatTypeInContext + LLVMFloatTypeInContext.restype = LLVMTypeRef + LLVMFloatTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMDoubleTypeInContext = _libraries['llvm'].LLVMDoubleTypeInContext + LLVMDoubleTypeInContext.restype = LLVMTypeRef + LLVMDoubleTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMX86FP80TypeInContext = _libraries['llvm'].LLVMX86FP80TypeInContext + LLVMX86FP80TypeInContext.restype = LLVMTypeRef + LLVMX86FP80TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMFP128TypeInContext = _libraries['llvm'].LLVMFP128TypeInContext + LLVMFP128TypeInContext.restype = LLVMTypeRef + LLVMFP128TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMPPCFP128TypeInContext = _libraries['llvm'].LLVMPPCFP128TypeInContext + LLVMPPCFP128TypeInContext.restype = LLVMTypeRef + LLVMPPCFP128TypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMHalfType = _libraries['llvm'].LLVMHalfType + LLVMHalfType.restype = LLVMTypeRef + LLVMHalfType.argtypes = [] +except AttributeError: + pass +try: + LLVMBFloatType = _libraries['llvm'].LLVMBFloatType + LLVMBFloatType.restype = LLVMTypeRef + LLVMBFloatType.argtypes = [] +except AttributeError: + pass +try: + LLVMFloatType = _libraries['llvm'].LLVMFloatType + LLVMFloatType.restype = LLVMTypeRef + LLVMFloatType.argtypes = [] +except AttributeError: + pass +try: + LLVMDoubleType = _libraries['llvm'].LLVMDoubleType + LLVMDoubleType.restype = LLVMTypeRef + LLVMDoubleType.argtypes = [] +except AttributeError: + pass +try: + LLVMX86FP80Type = _libraries['llvm'].LLVMX86FP80Type + LLVMX86FP80Type.restype = LLVMTypeRef + LLVMX86FP80Type.argtypes = [] +except AttributeError: + pass +try: + LLVMFP128Type = _libraries['llvm'].LLVMFP128Type + LLVMFP128Type.restype = LLVMTypeRef + LLVMFP128Type.argtypes = [] +except AttributeError: + pass +try: + LLVMPPCFP128Type = _libraries['llvm'].LLVMPPCFP128Type + LLVMPPCFP128Type.restype = LLVMTypeRef + LLVMPPCFP128Type.argtypes = [] +except AttributeError: + pass +try: + LLVMFunctionType = _libraries['llvm'].LLVMFunctionType + LLVMFunctionType.restype = LLVMTypeRef + LLVMFunctionType.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMIsFunctionVarArg = _libraries['llvm'].LLVMIsFunctionVarArg + LLVMIsFunctionVarArg.restype = LLVMBool + LLVMIsFunctionVarArg.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetReturnType = _libraries['llvm'].LLVMGetReturnType + LLVMGetReturnType.restype = LLVMTypeRef + LLVMGetReturnType.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMCountParamTypes = _libraries['llvm'].LLVMCountParamTypes + LLVMCountParamTypes.restype = ctypes.c_uint32 + LLVMCountParamTypes.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetParamTypes = _libraries['llvm'].LLVMGetParamTypes + LLVMGetParamTypes.restype = None + LLVMGetParamTypes.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType))] +except AttributeError: + pass +try: + LLVMStructTypeInContext = _libraries['llvm'].LLVMStructTypeInContext + LLVMStructTypeInContext.restype = LLVMTypeRef + LLVMStructTypeInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMStructType = _libraries['llvm'].LLVMStructType + LLVMStructType.restype = LLVMTypeRef + LLVMStructType.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMStructCreateNamed = _libraries['llvm'].LLVMStructCreateNamed + LLVMStructCreateNamed.restype = LLVMTypeRef + LLVMStructCreateNamed.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetStructName = _libraries['llvm'].LLVMGetStructName + LLVMGetStructName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetStructName.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMStructSetBody = _libraries['llvm'].LLVMStructSetBody + LLVMStructSetBody.restype = None + LLVMStructSetBody.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMCountStructElementTypes = _libraries['llvm'].LLVMCountStructElementTypes + LLVMCountStructElementTypes.restype = ctypes.c_uint32 + LLVMCountStructElementTypes.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetStructElementTypes = _libraries['llvm'].LLVMGetStructElementTypes + LLVMGetStructElementTypes.restype = None + LLVMGetStructElementTypes.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType))] +except AttributeError: + pass +try: + LLVMStructGetTypeAtIndex = _libraries['llvm'].LLVMStructGetTypeAtIndex + LLVMStructGetTypeAtIndex.restype = LLVMTypeRef + LLVMStructGetTypeAtIndex.argtypes = [LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMIsPackedStruct = _libraries['llvm'].LLVMIsPackedStruct + LLVMIsPackedStruct.restype = LLVMBool + LLVMIsPackedStruct.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMIsOpaqueStruct = _libraries['llvm'].LLVMIsOpaqueStruct + LLVMIsOpaqueStruct.restype = LLVMBool + LLVMIsOpaqueStruct.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMIsLiteralStruct = _libraries['llvm'].LLVMIsLiteralStruct + LLVMIsLiteralStruct.restype = LLVMBool + LLVMIsLiteralStruct.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetElementType = _libraries['llvm'].LLVMGetElementType + LLVMGetElementType.restype = LLVMTypeRef + LLVMGetElementType.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetSubtypes = _libraries['llvm'].LLVMGetSubtypes + LLVMGetSubtypes.restype = None + LLVMGetSubtypes.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType))] +except AttributeError: + pass +try: + LLVMGetNumContainedTypes = _libraries['llvm'].LLVMGetNumContainedTypes + LLVMGetNumContainedTypes.restype = ctypes.c_uint32 + LLVMGetNumContainedTypes.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMArrayType = _libraries['llvm'].LLVMArrayType + LLVMArrayType.restype = LLVMTypeRef + LLVMArrayType.argtypes = [LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetArrayLength = _libraries['llvm'].LLVMGetArrayLength + LLVMGetArrayLength.restype = ctypes.c_uint32 + LLVMGetArrayLength.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMPointerType = _libraries['llvm'].LLVMPointerType + LLVMPointerType.restype = LLVMTypeRef + LLVMPointerType.argtypes = [LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetPointerAddressSpace = _libraries['llvm'].LLVMGetPointerAddressSpace + LLVMGetPointerAddressSpace.restype = ctypes.c_uint32 + LLVMGetPointerAddressSpace.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMVectorType = _libraries['llvm'].LLVMVectorType + LLVMVectorType.restype = LLVMTypeRef + LLVMVectorType.argtypes = [LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMScalableVectorType = _libraries['llvm'].LLVMScalableVectorType + LLVMScalableVectorType.restype = LLVMTypeRef + LLVMScalableVectorType.argtypes = [LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetVectorSize = _libraries['llvm'].LLVMGetVectorSize + LLVMGetVectorSize.restype = ctypes.c_uint32 + LLVMGetVectorSize.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMVoidTypeInContext = _libraries['llvm'].LLVMVoidTypeInContext + LLVMVoidTypeInContext.restype = LLVMTypeRef + LLVMVoidTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMLabelTypeInContext = _libraries['llvm'].LLVMLabelTypeInContext + LLVMLabelTypeInContext.restype = LLVMTypeRef + LLVMLabelTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMX86MMXTypeInContext = _libraries['llvm'].LLVMX86MMXTypeInContext + LLVMX86MMXTypeInContext.restype = LLVMTypeRef + LLVMX86MMXTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMX86AMXTypeInContext = _libraries['llvm'].LLVMX86AMXTypeInContext + LLVMX86AMXTypeInContext.restype = LLVMTypeRef + LLVMX86AMXTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMTokenTypeInContext = _libraries['llvm'].LLVMTokenTypeInContext + LLVMTokenTypeInContext.restype = LLVMTypeRef + LLVMTokenTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMMetadataTypeInContext = _libraries['llvm'].LLVMMetadataTypeInContext + LLVMMetadataTypeInContext.restype = LLVMTypeRef + LLVMMetadataTypeInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMVoidType = _libraries['llvm'].LLVMVoidType + LLVMVoidType.restype = LLVMTypeRef + LLVMVoidType.argtypes = [] +except AttributeError: + pass +try: + LLVMLabelType = _libraries['llvm'].LLVMLabelType + LLVMLabelType.restype = LLVMTypeRef + LLVMLabelType.argtypes = [] +except AttributeError: + pass +try: + LLVMX86MMXType = _libraries['llvm'].LLVMX86MMXType + LLVMX86MMXType.restype = LLVMTypeRef + LLVMX86MMXType.argtypes = [] +except AttributeError: + pass +try: + LLVMX86AMXType = _libraries['llvm'].LLVMX86AMXType + LLVMX86AMXType.restype = LLVMTypeRef + LLVMX86AMXType.argtypes = [] +except AttributeError: + pass +try: + LLVMTypeOf = _libraries['llvm'].LLVMTypeOf + LLVMTypeOf.restype = LLVMTypeRef + LLVMTypeOf.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetValueKind = _libraries['llvm'].LLVMGetValueKind + LLVMGetValueKind.restype = LLVMValueKind + LLVMGetValueKind.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetValueName2 = _libraries['llvm'].LLVMGetValueName2 + LLVMGetValueName2.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetValueName2.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMSetValueName2 = _libraries['llvm'].LLVMSetValueName2 + LLVMSetValueName2.restype = None + LLVMSetValueName2.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDumpValue = _libraries['llvm'].LLVMDumpValue + LLVMDumpValue.restype = None + LLVMDumpValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMPrintValueToString = _libraries['llvm'].LLVMPrintValueToString + LLVMPrintValueToString.restype = ctypes.POINTER(ctypes.c_char) + LLVMPrintValueToString.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMReplaceAllUsesWith = _libraries['llvm'].LLVMReplaceAllUsesWith + LLVMReplaceAllUsesWith.restype = None + LLVMReplaceAllUsesWith.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsConstant = _libraries['llvm'].LLVMIsConstant + LLVMIsConstant.restype = LLVMBool + LLVMIsConstant.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsUndef = _libraries['llvm'].LLVMIsUndef + LLVMIsUndef.restype = LLVMBool + LLVMIsUndef.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsPoison = _libraries['llvm'].LLVMIsPoison + LLVMIsPoison.restype = LLVMBool + LLVMIsPoison.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAArgument = _libraries['llvm'].LLVMIsAArgument + LLVMIsAArgument.restype = LLVMValueRef + LLVMIsAArgument.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsABasicBlock = _libraries['llvm'].LLVMIsABasicBlock + LLVMIsABasicBlock.restype = LLVMValueRef + LLVMIsABasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAInlineAsm = _libraries['llvm'].LLVMIsAInlineAsm + LLVMIsAInlineAsm.restype = LLVMValueRef + LLVMIsAInlineAsm.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUser = _libraries['llvm'].LLVMIsAUser + LLVMIsAUser.restype = LLVMValueRef + LLVMIsAUser.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstant = _libraries['llvm'].LLVMIsAConstant + LLVMIsAConstant.restype = LLVMValueRef + LLVMIsAConstant.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsABlockAddress = _libraries['llvm'].LLVMIsABlockAddress + LLVMIsABlockAddress.restype = LLVMValueRef + LLVMIsABlockAddress.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantAggregateZero = _libraries['llvm'].LLVMIsAConstantAggregateZero + LLVMIsAConstantAggregateZero.restype = LLVMValueRef + LLVMIsAConstantAggregateZero.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantArray = _libraries['llvm'].LLVMIsAConstantArray + LLVMIsAConstantArray.restype = LLVMValueRef + LLVMIsAConstantArray.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantDataSequential = _libraries['llvm'].LLVMIsAConstantDataSequential + LLVMIsAConstantDataSequential.restype = LLVMValueRef + LLVMIsAConstantDataSequential.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantDataArray = _libraries['llvm'].LLVMIsAConstantDataArray + LLVMIsAConstantDataArray.restype = LLVMValueRef + LLVMIsAConstantDataArray.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantDataVector = _libraries['llvm'].LLVMIsAConstantDataVector + LLVMIsAConstantDataVector.restype = LLVMValueRef + LLVMIsAConstantDataVector.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantExpr = _libraries['llvm'].LLVMIsAConstantExpr + LLVMIsAConstantExpr.restype = LLVMValueRef + LLVMIsAConstantExpr.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantFP = _libraries['llvm'].LLVMIsAConstantFP + LLVMIsAConstantFP.restype = LLVMValueRef + LLVMIsAConstantFP.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantInt = _libraries['llvm'].LLVMIsAConstantInt + LLVMIsAConstantInt.restype = LLVMValueRef + LLVMIsAConstantInt.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantPointerNull = _libraries['llvm'].LLVMIsAConstantPointerNull + LLVMIsAConstantPointerNull.restype = LLVMValueRef + LLVMIsAConstantPointerNull.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantStruct = _libraries['llvm'].LLVMIsAConstantStruct + LLVMIsAConstantStruct.restype = LLVMValueRef + LLVMIsAConstantStruct.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantTokenNone = _libraries['llvm'].LLVMIsAConstantTokenNone + LLVMIsAConstantTokenNone.restype = LLVMValueRef + LLVMIsAConstantTokenNone.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAConstantVector = _libraries['llvm'].LLVMIsAConstantVector + LLVMIsAConstantVector.restype = LLVMValueRef + LLVMIsAConstantVector.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGlobalValue = _libraries['llvm'].LLVMIsAGlobalValue + LLVMIsAGlobalValue.restype = LLVMValueRef + LLVMIsAGlobalValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGlobalAlias = _libraries['llvm'].LLVMIsAGlobalAlias + LLVMIsAGlobalAlias.restype = LLVMValueRef + LLVMIsAGlobalAlias.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGlobalObject = _libraries['llvm'].LLVMIsAGlobalObject + LLVMIsAGlobalObject.restype = LLVMValueRef + LLVMIsAGlobalObject.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFunction = _libraries['llvm'].LLVMIsAFunction + LLVMIsAFunction.restype = LLVMValueRef + LLVMIsAFunction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGlobalVariable = _libraries['llvm'].LLVMIsAGlobalVariable + LLVMIsAGlobalVariable.restype = LLVMValueRef + LLVMIsAGlobalVariable.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGlobalIFunc = _libraries['llvm'].LLVMIsAGlobalIFunc + LLVMIsAGlobalIFunc.restype = LLVMValueRef + LLVMIsAGlobalIFunc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUndefValue = _libraries['llvm'].LLVMIsAUndefValue + LLVMIsAUndefValue.restype = LLVMValueRef + LLVMIsAUndefValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAPoisonValue = _libraries['llvm'].LLVMIsAPoisonValue + LLVMIsAPoisonValue.restype = LLVMValueRef + LLVMIsAPoisonValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAInstruction = _libraries['llvm'].LLVMIsAInstruction + LLVMIsAInstruction.restype = LLVMValueRef + LLVMIsAInstruction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUnaryOperator = _libraries['llvm'].LLVMIsAUnaryOperator + LLVMIsAUnaryOperator.restype = LLVMValueRef + LLVMIsAUnaryOperator.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsABinaryOperator = _libraries['llvm'].LLVMIsABinaryOperator + LLVMIsABinaryOperator.restype = LLVMValueRef + LLVMIsABinaryOperator.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACallInst = _libraries['llvm'].LLVMIsACallInst + LLVMIsACallInst.restype = LLVMValueRef + LLVMIsACallInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAIntrinsicInst = _libraries['llvm'].LLVMIsAIntrinsicInst + LLVMIsAIntrinsicInst.restype = LLVMValueRef + LLVMIsAIntrinsicInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsADbgInfoIntrinsic = _libraries['llvm'].LLVMIsADbgInfoIntrinsic + LLVMIsADbgInfoIntrinsic.restype = LLVMValueRef + LLVMIsADbgInfoIntrinsic.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsADbgVariableIntrinsic = _libraries['llvm'].LLVMIsADbgVariableIntrinsic + LLVMIsADbgVariableIntrinsic.restype = LLVMValueRef + LLVMIsADbgVariableIntrinsic.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsADbgDeclareInst = _libraries['llvm'].LLVMIsADbgDeclareInst + LLVMIsADbgDeclareInst.restype = LLVMValueRef + LLVMIsADbgDeclareInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsADbgLabelInst = _libraries['llvm'].LLVMIsADbgLabelInst + LLVMIsADbgLabelInst.restype = LLVMValueRef + LLVMIsADbgLabelInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMemIntrinsic = _libraries['llvm'].LLVMIsAMemIntrinsic + LLVMIsAMemIntrinsic.restype = LLVMValueRef + LLVMIsAMemIntrinsic.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMemCpyInst = _libraries['llvm'].LLVMIsAMemCpyInst + LLVMIsAMemCpyInst.restype = LLVMValueRef + LLVMIsAMemCpyInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMemMoveInst = _libraries['llvm'].LLVMIsAMemMoveInst + LLVMIsAMemMoveInst.restype = LLVMValueRef + LLVMIsAMemMoveInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMemSetInst = _libraries['llvm'].LLVMIsAMemSetInst + LLVMIsAMemSetInst.restype = LLVMValueRef + LLVMIsAMemSetInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACmpInst = _libraries['llvm'].LLVMIsACmpInst + LLVMIsACmpInst.restype = LLVMValueRef + LLVMIsACmpInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFCmpInst = _libraries['llvm'].LLVMIsAFCmpInst + LLVMIsAFCmpInst.restype = LLVMValueRef + LLVMIsAFCmpInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAICmpInst = _libraries['llvm'].LLVMIsAICmpInst + LLVMIsAICmpInst.restype = LLVMValueRef + LLVMIsAICmpInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAExtractElementInst = _libraries['llvm'].LLVMIsAExtractElementInst + LLVMIsAExtractElementInst.restype = LLVMValueRef + LLVMIsAExtractElementInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAGetElementPtrInst = _libraries['llvm'].LLVMIsAGetElementPtrInst + LLVMIsAGetElementPtrInst.restype = LLVMValueRef + LLVMIsAGetElementPtrInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAInsertElementInst = _libraries['llvm'].LLVMIsAInsertElementInst + LLVMIsAInsertElementInst.restype = LLVMValueRef + LLVMIsAInsertElementInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAInsertValueInst = _libraries['llvm'].LLVMIsAInsertValueInst + LLVMIsAInsertValueInst.restype = LLVMValueRef + LLVMIsAInsertValueInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsALandingPadInst = _libraries['llvm'].LLVMIsALandingPadInst + LLVMIsALandingPadInst.restype = LLVMValueRef + LLVMIsALandingPadInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAPHINode = _libraries['llvm'].LLVMIsAPHINode + LLVMIsAPHINode.restype = LLVMValueRef + LLVMIsAPHINode.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsASelectInst = _libraries['llvm'].LLVMIsASelectInst + LLVMIsASelectInst.restype = LLVMValueRef + LLVMIsASelectInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAShuffleVectorInst = _libraries['llvm'].LLVMIsAShuffleVectorInst + LLVMIsAShuffleVectorInst.restype = LLVMValueRef + LLVMIsAShuffleVectorInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAStoreInst = _libraries['llvm'].LLVMIsAStoreInst + LLVMIsAStoreInst.restype = LLVMValueRef + LLVMIsAStoreInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsABranchInst = _libraries['llvm'].LLVMIsABranchInst + LLVMIsABranchInst.restype = LLVMValueRef + LLVMIsABranchInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAIndirectBrInst = _libraries['llvm'].LLVMIsAIndirectBrInst + LLVMIsAIndirectBrInst.restype = LLVMValueRef + LLVMIsAIndirectBrInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAInvokeInst = _libraries['llvm'].LLVMIsAInvokeInst + LLVMIsAInvokeInst.restype = LLVMValueRef + LLVMIsAInvokeInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAReturnInst = _libraries['llvm'].LLVMIsAReturnInst + LLVMIsAReturnInst.restype = LLVMValueRef + LLVMIsAReturnInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsASwitchInst = _libraries['llvm'].LLVMIsASwitchInst + LLVMIsASwitchInst.restype = LLVMValueRef + LLVMIsASwitchInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUnreachableInst = _libraries['llvm'].LLVMIsAUnreachableInst + LLVMIsAUnreachableInst.restype = LLVMValueRef + LLVMIsAUnreachableInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAResumeInst = _libraries['llvm'].LLVMIsAResumeInst + LLVMIsAResumeInst.restype = LLVMValueRef + LLVMIsAResumeInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACleanupReturnInst = _libraries['llvm'].LLVMIsACleanupReturnInst + LLVMIsACleanupReturnInst.restype = LLVMValueRef + LLVMIsACleanupReturnInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACatchReturnInst = _libraries['llvm'].LLVMIsACatchReturnInst + LLVMIsACatchReturnInst.restype = LLVMValueRef + LLVMIsACatchReturnInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACatchSwitchInst = _libraries['llvm'].LLVMIsACatchSwitchInst + LLVMIsACatchSwitchInst.restype = LLVMValueRef + LLVMIsACatchSwitchInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACallBrInst = _libraries['llvm'].LLVMIsACallBrInst + LLVMIsACallBrInst.restype = LLVMValueRef + LLVMIsACallBrInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFuncletPadInst = _libraries['llvm'].LLVMIsAFuncletPadInst + LLVMIsAFuncletPadInst.restype = LLVMValueRef + LLVMIsAFuncletPadInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACatchPadInst = _libraries['llvm'].LLVMIsACatchPadInst + LLVMIsACatchPadInst.restype = LLVMValueRef + LLVMIsACatchPadInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACleanupPadInst = _libraries['llvm'].LLVMIsACleanupPadInst + LLVMIsACleanupPadInst.restype = LLVMValueRef + LLVMIsACleanupPadInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUnaryInstruction = _libraries['llvm'].LLVMIsAUnaryInstruction + LLVMIsAUnaryInstruction.restype = LLVMValueRef + LLVMIsAUnaryInstruction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAAllocaInst = _libraries['llvm'].LLVMIsAAllocaInst + LLVMIsAAllocaInst.restype = LLVMValueRef + LLVMIsAAllocaInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsACastInst = _libraries['llvm'].LLVMIsACastInst + LLVMIsACastInst.restype = LLVMValueRef + LLVMIsACastInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAAddrSpaceCastInst = _libraries['llvm'].LLVMIsAAddrSpaceCastInst + LLVMIsAAddrSpaceCastInst.restype = LLVMValueRef + LLVMIsAAddrSpaceCastInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsABitCastInst = _libraries['llvm'].LLVMIsABitCastInst + LLVMIsABitCastInst.restype = LLVMValueRef + LLVMIsABitCastInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFPExtInst = _libraries['llvm'].LLVMIsAFPExtInst + LLVMIsAFPExtInst.restype = LLVMValueRef + LLVMIsAFPExtInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFPToSIInst = _libraries['llvm'].LLVMIsAFPToSIInst + LLVMIsAFPToSIInst.restype = LLVMValueRef + LLVMIsAFPToSIInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFPToUIInst = _libraries['llvm'].LLVMIsAFPToUIInst + LLVMIsAFPToUIInst.restype = LLVMValueRef + LLVMIsAFPToUIInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFPTruncInst = _libraries['llvm'].LLVMIsAFPTruncInst + LLVMIsAFPTruncInst.restype = LLVMValueRef + LLVMIsAFPTruncInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAIntToPtrInst = _libraries['llvm'].LLVMIsAIntToPtrInst + LLVMIsAIntToPtrInst.restype = LLVMValueRef + LLVMIsAIntToPtrInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAPtrToIntInst = _libraries['llvm'].LLVMIsAPtrToIntInst + LLVMIsAPtrToIntInst.restype = LLVMValueRef + LLVMIsAPtrToIntInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsASExtInst = _libraries['llvm'].LLVMIsASExtInst + LLVMIsASExtInst.restype = LLVMValueRef + LLVMIsASExtInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsASIToFPInst = _libraries['llvm'].LLVMIsASIToFPInst + LLVMIsASIToFPInst.restype = LLVMValueRef + LLVMIsASIToFPInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsATruncInst = _libraries['llvm'].LLVMIsATruncInst + LLVMIsATruncInst.restype = LLVMValueRef + LLVMIsATruncInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAUIToFPInst = _libraries['llvm'].LLVMIsAUIToFPInst + LLVMIsAUIToFPInst.restype = LLVMValueRef + LLVMIsAUIToFPInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAZExtInst = _libraries['llvm'].LLVMIsAZExtInst + LLVMIsAZExtInst.restype = LLVMValueRef + LLVMIsAZExtInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAExtractValueInst = _libraries['llvm'].LLVMIsAExtractValueInst + LLVMIsAExtractValueInst.restype = LLVMValueRef + LLVMIsAExtractValueInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsALoadInst = _libraries['llvm'].LLVMIsALoadInst + LLVMIsALoadInst.restype = LLVMValueRef + LLVMIsALoadInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAVAArgInst = _libraries['llvm'].LLVMIsAVAArgInst + LLVMIsAVAArgInst.restype = LLVMValueRef + LLVMIsAVAArgInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFreezeInst = _libraries['llvm'].LLVMIsAFreezeInst + LLVMIsAFreezeInst.restype = LLVMValueRef + LLVMIsAFreezeInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAAtomicCmpXchgInst = _libraries['llvm'].LLVMIsAAtomicCmpXchgInst + LLVMIsAAtomicCmpXchgInst.restype = LLVMValueRef + LLVMIsAAtomicCmpXchgInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAAtomicRMWInst = _libraries['llvm'].LLVMIsAAtomicRMWInst + LLVMIsAAtomicRMWInst.restype = LLVMValueRef + LLVMIsAAtomicRMWInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAFenceInst = _libraries['llvm'].LLVMIsAFenceInst + LLVMIsAFenceInst.restype = LLVMValueRef + LLVMIsAFenceInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMDNode = _libraries['llvm'].LLVMIsAMDNode + LLVMIsAMDNode.restype = LLVMValueRef + LLVMIsAMDNode.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsAMDString = _libraries['llvm'].LLVMIsAMDString + LLVMIsAMDString.restype = LLVMValueRef + LLVMIsAMDString.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetValueName = _libraries['llvm'].LLVMGetValueName + LLVMGetValueName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetValueName.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetValueName = _libraries['llvm'].LLVMSetValueName + LLVMSetValueName.restype = None + LLVMSetValueName.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetFirstUse = _libraries['llvm'].LLVMGetFirstUse + LLVMGetFirstUse.restype = LLVMUseRef + LLVMGetFirstUse.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNextUse = _libraries['llvm'].LLVMGetNextUse + LLVMGetNextUse.restype = LLVMUseRef + LLVMGetNextUse.argtypes = [LLVMUseRef] +except AttributeError: + pass +try: + LLVMGetUser = _libraries['llvm'].LLVMGetUser + LLVMGetUser.restype = LLVMValueRef + LLVMGetUser.argtypes = [LLVMUseRef] +except AttributeError: + pass +try: + LLVMGetUsedValue = _libraries['llvm'].LLVMGetUsedValue + LLVMGetUsedValue.restype = LLVMValueRef + LLVMGetUsedValue.argtypes = [LLVMUseRef] +except AttributeError: + pass +try: + LLVMGetOperand = _libraries['llvm'].LLVMGetOperand + LLVMGetOperand.restype = LLVMValueRef + LLVMGetOperand.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetOperandUse = _libraries['llvm'].LLVMGetOperandUse + LLVMGetOperandUse.restype = LLVMUseRef + LLVMGetOperandUse.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMSetOperand = _libraries['llvm'].LLVMSetOperand + LLVMSetOperand.restype = None + LLVMSetOperand.argtypes = [LLVMValueRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNumOperands = _libraries['llvm'].LLVMGetNumOperands + LLVMGetNumOperands.restype = ctypes.c_int32 + LLVMGetNumOperands.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNull = _libraries['llvm'].LLVMConstNull + LLVMConstNull.restype = LLVMValueRef + LLVMConstNull.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstAllOnes = _libraries['llvm'].LLVMConstAllOnes + LLVMConstAllOnes.restype = LLVMValueRef + LLVMConstAllOnes.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetUndef = _libraries['llvm'].LLVMGetUndef + LLVMGetUndef.restype = LLVMValueRef + LLVMGetUndef.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMGetPoison = _libraries['llvm'].LLVMGetPoison + LLVMGetPoison.restype = LLVMValueRef + LLVMGetPoison.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMIsNull = _libraries['llvm'].LLVMIsNull + LLVMIsNull.restype = LLVMBool + LLVMIsNull.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstPointerNull = _libraries['llvm'].LLVMConstPointerNull + LLVMConstPointerNull.restype = LLVMValueRef + LLVMConstPointerNull.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstInt = _libraries['llvm'].LLVMConstInt + LLVMConstInt.restype = LLVMValueRef + LLVMConstInt.argtypes = [LLVMTypeRef, ctypes.c_uint64, LLVMBool] +except AttributeError: + pass +try: + LLVMConstIntOfArbitraryPrecision = _libraries['llvm'].LLVMConstIntOfArbitraryPrecision + LLVMConstIntOfArbitraryPrecision.restype = LLVMValueRef + LLVMConstIntOfArbitraryPrecision.argtypes = [LLVMTypeRef, ctypes.c_uint32, ctypes.c_uint64 * 0] +except AttributeError: + pass +uint8_t = ctypes.c_uint8 +try: + LLVMConstIntOfString = _libraries['llvm'].LLVMConstIntOfString + LLVMConstIntOfString.restype = LLVMValueRef + LLVMConstIntOfString.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char), uint8_t] +except AttributeError: + pass +try: + LLVMConstIntOfStringAndSize = _libraries['llvm'].LLVMConstIntOfStringAndSize + LLVMConstIntOfStringAndSize.restype = LLVMValueRef + LLVMConstIntOfStringAndSize.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32, uint8_t] +except AttributeError: + pass +try: + LLVMConstReal = _libraries['llvm'].LLVMConstReal + LLVMConstReal.restype = LLVMValueRef + LLVMConstReal.argtypes = [LLVMTypeRef, ctypes.c_double] +except AttributeError: + pass +try: + LLVMConstRealOfString = _libraries['llvm'].LLVMConstRealOfString + LLVMConstRealOfString.restype = LLVMValueRef + LLVMConstRealOfString.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMConstRealOfStringAndSize = _libraries['llvm'].LLVMConstRealOfStringAndSize + LLVMConstRealOfStringAndSize.restype = LLVMValueRef + LLVMConstRealOfStringAndSize.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstIntGetZExtValue = _libraries['llvm'].LLVMConstIntGetZExtValue + LLVMConstIntGetZExtValue.restype = ctypes.c_uint64 + LLVMConstIntGetZExtValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstIntGetSExtValue = _libraries['llvm'].LLVMConstIntGetSExtValue + LLVMConstIntGetSExtValue.restype = ctypes.c_int64 + LLVMConstIntGetSExtValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstRealGetDouble = _libraries['llvm'].LLVMConstRealGetDouble + LLVMConstRealGetDouble.restype = ctypes.c_double + LLVMConstRealGetDouble.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_int32)] +except AttributeError: + pass +try: + LLVMConstStringInContext = _libraries['llvm'].LLVMConstStringInContext + LLVMConstStringInContext.restype = LLVMValueRef + LLVMConstStringInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMConstString = _libraries['llvm'].LLVMConstString + LLVMConstString.restype = LLVMValueRef + LLVMConstString.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMIsConstantString = _libraries['llvm'].LLVMIsConstantString + LLVMIsConstantString.restype = LLVMBool + LLVMIsConstantString.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetAsString = _libraries['llvm'].LLVMGetAsString + LLVMGetAsString.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetAsString.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMConstStructInContext = _libraries['llvm'].LLVMConstStructInContext + LLVMConstStructInContext.restype = LLVMValueRef + LLVMConstStructInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMConstStruct = _libraries['llvm'].LLVMConstStruct + LLVMConstStruct.restype = LLVMValueRef + LLVMConstStruct.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, LLVMBool] +except AttributeError: + pass +try: + LLVMConstArray = _libraries['llvm'].LLVMConstArray + LLVMConstArray.restype = LLVMValueRef + LLVMConstArray.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstNamedStruct = _libraries['llvm'].LLVMConstNamedStruct + LLVMConstNamedStruct.restype = LLVMValueRef + LLVMConstNamedStruct.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetElementAsConstant = _libraries['llvm'].LLVMGetElementAsConstant + LLVMGetElementAsConstant.restype = LLVMValueRef + LLVMGetElementAsConstant.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstVector = _libraries['llvm'].LLVMConstVector + LLVMConstVector.restype = LLVMValueRef + LLVMConstVector.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetConstOpcode = _libraries['llvm'].LLVMGetConstOpcode + LLVMGetConstOpcode.restype = LLVMOpcode + LLVMGetConstOpcode.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMAlignOf = _libraries['llvm'].LLVMAlignOf + LLVMAlignOf.restype = LLVMValueRef + LLVMAlignOf.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMSizeOf = _libraries['llvm'].LLVMSizeOf + LLVMSizeOf.restype = LLVMValueRef + LLVMSizeOf.argtypes = [LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstNeg = _libraries['llvm'].LLVMConstNeg + LLVMConstNeg.restype = LLVMValueRef + LLVMConstNeg.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNSWNeg = _libraries['llvm'].LLVMConstNSWNeg + LLVMConstNSWNeg.restype = LLVMValueRef + LLVMConstNSWNeg.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNUWNeg = _libraries['llvm'].LLVMConstNUWNeg + LLVMConstNUWNeg.restype = LLVMValueRef + LLVMConstNUWNeg.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFNeg = _libraries['llvm'].LLVMConstFNeg + LLVMConstFNeg.restype = LLVMValueRef + LLVMConstFNeg.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNot = _libraries['llvm'].LLVMConstNot + LLVMConstNot.restype = LLVMValueRef + LLVMConstNot.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstAdd = _libraries['llvm'].LLVMConstAdd + LLVMConstAdd.restype = LLVMValueRef + LLVMConstAdd.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNSWAdd = _libraries['llvm'].LLVMConstNSWAdd + LLVMConstNSWAdd.restype = LLVMValueRef + LLVMConstNSWAdd.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNUWAdd = _libraries['llvm'].LLVMConstNUWAdd + LLVMConstNUWAdd.restype = LLVMValueRef + LLVMConstNUWAdd.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFAdd = _libraries['llvm'].LLVMConstFAdd + LLVMConstFAdd.restype = LLVMValueRef + LLVMConstFAdd.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstSub = _libraries['llvm'].LLVMConstSub + LLVMConstSub.restype = LLVMValueRef + LLVMConstSub.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNSWSub = _libraries['llvm'].LLVMConstNSWSub + LLVMConstNSWSub.restype = LLVMValueRef + LLVMConstNSWSub.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNUWSub = _libraries['llvm'].LLVMConstNUWSub + LLVMConstNUWSub.restype = LLVMValueRef + LLVMConstNUWSub.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFSub = _libraries['llvm'].LLVMConstFSub + LLVMConstFSub.restype = LLVMValueRef + LLVMConstFSub.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstMul = _libraries['llvm'].LLVMConstMul + LLVMConstMul.restype = LLVMValueRef + LLVMConstMul.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNSWMul = _libraries['llvm'].LLVMConstNSWMul + LLVMConstNSWMul.restype = LLVMValueRef + LLVMConstNSWMul.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstNUWMul = _libraries['llvm'].LLVMConstNUWMul + LLVMConstNUWMul.restype = LLVMValueRef + LLVMConstNUWMul.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFMul = _libraries['llvm'].LLVMConstFMul + LLVMConstFMul.restype = LLVMValueRef + LLVMConstFMul.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstUDiv = _libraries['llvm'].LLVMConstUDiv + LLVMConstUDiv.restype = LLVMValueRef + LLVMConstUDiv.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstExactUDiv = _libraries['llvm'].LLVMConstExactUDiv + LLVMConstExactUDiv.restype = LLVMValueRef + LLVMConstExactUDiv.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstSDiv = _libraries['llvm'].LLVMConstSDiv + LLVMConstSDiv.restype = LLVMValueRef + LLVMConstSDiv.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstExactSDiv = _libraries['llvm'].LLVMConstExactSDiv + LLVMConstExactSDiv.restype = LLVMValueRef + LLVMConstExactSDiv.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFDiv = _libraries['llvm'].LLVMConstFDiv + LLVMConstFDiv.restype = LLVMValueRef + LLVMConstFDiv.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstURem = _libraries['llvm'].LLVMConstURem + LLVMConstURem.restype = LLVMValueRef + LLVMConstURem.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstSRem = _libraries['llvm'].LLVMConstSRem + LLVMConstSRem.restype = LLVMValueRef + LLVMConstSRem.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFRem = _libraries['llvm'].LLVMConstFRem + LLVMConstFRem.restype = LLVMValueRef + LLVMConstFRem.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstAnd = _libraries['llvm'].LLVMConstAnd + LLVMConstAnd.restype = LLVMValueRef + LLVMConstAnd.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstOr = _libraries['llvm'].LLVMConstOr + LLVMConstOr.restype = LLVMValueRef + LLVMConstOr.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstXor = _libraries['llvm'].LLVMConstXor + LLVMConstXor.restype = LLVMValueRef + LLVMConstXor.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstICmp = _libraries['llvm'].LLVMConstICmp + LLVMConstICmp.restype = LLVMValueRef + LLVMConstICmp.argtypes = [LLVMIntPredicate, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstFCmp = _libraries['llvm'].LLVMConstFCmp + LLVMConstFCmp.restype = LLVMValueRef + LLVMConstFCmp.argtypes = [LLVMRealPredicate, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstShl = _libraries['llvm'].LLVMConstShl + LLVMConstShl.restype = LLVMValueRef + LLVMConstShl.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstLShr = _libraries['llvm'].LLVMConstLShr + LLVMConstLShr.restype = LLVMValueRef + LLVMConstLShr.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstAShr = _libraries['llvm'].LLVMConstAShr + LLVMConstAShr.restype = LLVMValueRef + LLVMConstAShr.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstGEP = _libraries['llvm'].LLVMConstGEP + LLVMConstGEP.restype = LLVMValueRef + LLVMConstGEP.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstGEP2 = _libraries['llvm'].LLVMConstGEP2 + LLVMConstGEP2.restype = LLVMValueRef + LLVMConstGEP2.argtypes = [LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstInBoundsGEP = _libraries['llvm'].LLVMConstInBoundsGEP + LLVMConstInBoundsGEP.restype = LLVMValueRef + LLVMConstInBoundsGEP.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstInBoundsGEP2 = _libraries['llvm'].LLVMConstInBoundsGEP2 + LLVMConstInBoundsGEP2.restype = LLVMValueRef + LLVMConstInBoundsGEP2.argtypes = [LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstTrunc = _libraries['llvm'].LLVMConstTrunc + LLVMConstTrunc.restype = LLVMValueRef + LLVMConstTrunc.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstSExt = _libraries['llvm'].LLVMConstSExt + LLVMConstSExt.restype = LLVMValueRef + LLVMConstSExt.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstZExt = _libraries['llvm'].LLVMConstZExt + LLVMConstZExt.restype = LLVMValueRef + LLVMConstZExt.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstFPTrunc = _libraries['llvm'].LLVMConstFPTrunc + LLVMConstFPTrunc.restype = LLVMValueRef + LLVMConstFPTrunc.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstFPExt = _libraries['llvm'].LLVMConstFPExt + LLVMConstFPExt.restype = LLVMValueRef + LLVMConstFPExt.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstUIToFP = _libraries['llvm'].LLVMConstUIToFP + LLVMConstUIToFP.restype = LLVMValueRef + LLVMConstUIToFP.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstSIToFP = _libraries['llvm'].LLVMConstSIToFP + LLVMConstSIToFP.restype = LLVMValueRef + LLVMConstSIToFP.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstFPToUI = _libraries['llvm'].LLVMConstFPToUI + LLVMConstFPToUI.restype = LLVMValueRef + LLVMConstFPToUI.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstFPToSI = _libraries['llvm'].LLVMConstFPToSI + LLVMConstFPToSI.restype = LLVMValueRef + LLVMConstFPToSI.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstPtrToInt = _libraries['llvm'].LLVMConstPtrToInt + LLVMConstPtrToInt.restype = LLVMValueRef + LLVMConstPtrToInt.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstIntToPtr = _libraries['llvm'].LLVMConstIntToPtr + LLVMConstIntToPtr.restype = LLVMValueRef + LLVMConstIntToPtr.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstBitCast = _libraries['llvm'].LLVMConstBitCast + LLVMConstBitCast.restype = LLVMValueRef + LLVMConstBitCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstAddrSpaceCast = _libraries['llvm'].LLVMConstAddrSpaceCast + LLVMConstAddrSpaceCast.restype = LLVMValueRef + LLVMConstAddrSpaceCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstZExtOrBitCast = _libraries['llvm'].LLVMConstZExtOrBitCast + LLVMConstZExtOrBitCast.restype = LLVMValueRef + LLVMConstZExtOrBitCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstSExtOrBitCast = _libraries['llvm'].LLVMConstSExtOrBitCast + LLVMConstSExtOrBitCast.restype = LLVMValueRef + LLVMConstSExtOrBitCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstTruncOrBitCast = _libraries['llvm'].LLVMConstTruncOrBitCast + LLVMConstTruncOrBitCast.restype = LLVMValueRef + LLVMConstTruncOrBitCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstPointerCast = _libraries['llvm'].LLVMConstPointerCast + LLVMConstPointerCast.restype = LLVMValueRef + LLVMConstPointerCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstIntCast = _libraries['llvm'].LLVMConstIntCast + LLVMConstIntCast.restype = LLVMValueRef + LLVMConstIntCast.argtypes = [LLVMValueRef, LLVMTypeRef, LLVMBool] +except AttributeError: + pass +try: + LLVMConstFPCast = _libraries['llvm'].LLVMConstFPCast + LLVMConstFPCast.restype = LLVMValueRef + LLVMConstFPCast.argtypes = [LLVMValueRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMConstSelect = _libraries['llvm'].LLVMConstSelect + LLVMConstSelect.restype = LLVMValueRef + LLVMConstSelect.argtypes = [LLVMValueRef, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstExtractElement = _libraries['llvm'].LLVMConstExtractElement + LLVMConstExtractElement.restype = LLVMValueRef + LLVMConstExtractElement.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstInsertElement = _libraries['llvm'].LLVMConstInsertElement + LLVMConstInsertElement.restype = LLVMValueRef + LLVMConstInsertElement.argtypes = [LLVMValueRef, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstShuffleVector = _libraries['llvm'].LLVMConstShuffleVector + LLVMConstShuffleVector.restype = LLVMValueRef + LLVMConstShuffleVector.argtypes = [LLVMValueRef, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMConstExtractValue = _libraries['llvm'].LLVMConstExtractValue + LLVMConstExtractValue.restype = LLVMValueRef + LLVMConstExtractValue.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint32), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMConstInsertValue = _libraries['llvm'].LLVMConstInsertValue + LLVMConstInsertValue.restype = LLVMValueRef + LLVMConstInsertValue.argtypes = [LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_uint32), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBlockAddress = _libraries['llvm'].LLVMBlockAddress + LLVMBlockAddress.restype = LLVMValueRef + LLVMBlockAddress.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMConstInlineAsm = _libraries['llvm'].LLVMConstInlineAsm + LLVMConstInlineAsm.restype = LLVMValueRef + LLVMConstInlineAsm.argtypes = [LLVMTypeRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), LLVMBool, LLVMBool] +except AttributeError: + pass +try: + LLVMGetGlobalParent = _libraries['llvm'].LLVMGetGlobalParent + LLVMGetGlobalParent.restype = LLVMModuleRef + LLVMGetGlobalParent.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsDeclaration = _libraries['llvm'].LLVMIsDeclaration + LLVMIsDeclaration.restype = LLVMBool + LLVMIsDeclaration.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetLinkage = _libraries['llvm'].LLVMGetLinkage + LLVMGetLinkage.restype = LLVMLinkage + LLVMGetLinkage.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetLinkage = _libraries['llvm'].LLVMSetLinkage + LLVMSetLinkage.restype = None + LLVMSetLinkage.argtypes = [LLVMValueRef, LLVMLinkage] +except AttributeError: + pass +try: + LLVMGetSection = _libraries['llvm'].LLVMGetSection + LLVMGetSection.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetSection.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetSection = _libraries['llvm'].LLVMSetSection + LLVMSetSection.restype = None + LLVMSetSection.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetVisibility = _libraries['llvm'].LLVMGetVisibility + LLVMGetVisibility.restype = LLVMVisibility + LLVMGetVisibility.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetVisibility = _libraries['llvm'].LLVMSetVisibility + LLVMSetVisibility.restype = None + LLVMSetVisibility.argtypes = [LLVMValueRef, LLVMVisibility] +except AttributeError: + pass +try: + LLVMGetDLLStorageClass = _libraries['llvm'].LLVMGetDLLStorageClass + LLVMGetDLLStorageClass.restype = LLVMDLLStorageClass + LLVMGetDLLStorageClass.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetDLLStorageClass = _libraries['llvm'].LLVMSetDLLStorageClass + LLVMSetDLLStorageClass.restype = None + LLVMSetDLLStorageClass.argtypes = [LLVMValueRef, LLVMDLLStorageClass] +except AttributeError: + pass +try: + LLVMGetUnnamedAddress = _libraries['llvm'].LLVMGetUnnamedAddress + LLVMGetUnnamedAddress.restype = LLVMUnnamedAddr + LLVMGetUnnamedAddress.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetUnnamedAddress = _libraries['llvm'].LLVMSetUnnamedAddress + LLVMSetUnnamedAddress.restype = None + LLVMSetUnnamedAddress.argtypes = [LLVMValueRef, LLVMUnnamedAddr] +except AttributeError: + pass +try: + LLVMGlobalGetValueType = _libraries['llvm'].LLVMGlobalGetValueType + LLVMGlobalGetValueType.restype = LLVMTypeRef + LLVMGlobalGetValueType.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMHasUnnamedAddr = _libraries['llvm'].LLVMHasUnnamedAddr + LLVMHasUnnamedAddr.restype = LLVMBool + LLVMHasUnnamedAddr.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetUnnamedAddr = _libraries['llvm'].LLVMSetUnnamedAddr + LLVMSetUnnamedAddr.restype = None + LLVMSetUnnamedAddr.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetAlignment = _libraries['llvm'].LLVMGetAlignment + LLVMGetAlignment.restype = ctypes.c_uint32 + LLVMGetAlignment.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetAlignment = _libraries['llvm'].LLVMSetAlignment + LLVMSetAlignment.restype = None + LLVMSetAlignment.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGlobalSetMetadata = _libraries['llvm'].LLVMGlobalSetMetadata + LLVMGlobalSetMetadata.restype = None + LLVMGlobalSetMetadata.argtypes = [LLVMValueRef, ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMGlobalEraseMetadata = _libraries['llvm'].LLVMGlobalEraseMetadata + LLVMGlobalEraseMetadata.restype = None + LLVMGlobalEraseMetadata.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGlobalClearMetadata = _libraries['llvm'].LLVMGlobalClearMetadata + LLVMGlobalClearMetadata.restype = None + LLVMGlobalClearMetadata.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGlobalCopyAllMetadata = _libraries['llvm'].LLVMGlobalCopyAllMetadata + LLVMGlobalCopyAllMetadata.restype = ctypes.POINTER(struct_LLVMOpaqueValueMetadataEntry) + LLVMGlobalCopyAllMetadata.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMDisposeValueMetadataEntries = _libraries['llvm'].LLVMDisposeValueMetadataEntries + LLVMDisposeValueMetadataEntries.restype = None + LLVMDisposeValueMetadataEntries.argtypes = [ctypes.POINTER(struct_LLVMOpaqueValueMetadataEntry)] +except AttributeError: + pass +try: + LLVMValueMetadataEntriesGetKind = _libraries['llvm'].LLVMValueMetadataEntriesGetKind + LLVMValueMetadataEntriesGetKind.restype = ctypes.c_uint32 + LLVMValueMetadataEntriesGetKind.argtypes = [ctypes.POINTER(struct_LLVMOpaqueValueMetadataEntry), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMValueMetadataEntriesGetMetadata = _libraries['llvm'].LLVMValueMetadataEntriesGetMetadata + LLVMValueMetadataEntriesGetMetadata.restype = LLVMMetadataRef + LLVMValueMetadataEntriesGetMetadata.argtypes = [ctypes.POINTER(struct_LLVMOpaqueValueMetadataEntry), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddGlobal = _libraries['llvm'].LLVMAddGlobal + LLVMAddGlobal.restype = LLVMValueRef + LLVMAddGlobal.argtypes = [LLVMModuleRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAddGlobalInAddressSpace = _libraries['llvm'].LLVMAddGlobalInAddressSpace + LLVMAddGlobalInAddressSpace.restype = LLVMValueRef + LLVMAddGlobalInAddressSpace.argtypes = [LLVMModuleRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetNamedGlobal = _libraries['llvm'].LLVMGetNamedGlobal + LLVMGetNamedGlobal.restype = LLVMValueRef + LLVMGetNamedGlobal.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetFirstGlobal = _libraries['llvm'].LLVMGetFirstGlobal + LLVMGetFirstGlobal.restype = LLVMValueRef + LLVMGetFirstGlobal.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetLastGlobal = _libraries['llvm'].LLVMGetLastGlobal + LLVMGetLastGlobal.restype = LLVMValueRef + LLVMGetLastGlobal.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetNextGlobal = _libraries['llvm'].LLVMGetNextGlobal + LLVMGetNextGlobal.restype = LLVMValueRef + LLVMGetNextGlobal.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousGlobal = _libraries['llvm'].LLVMGetPreviousGlobal + LLVMGetPreviousGlobal.restype = LLVMValueRef + LLVMGetPreviousGlobal.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMDeleteGlobal = _libraries['llvm'].LLVMDeleteGlobal + LLVMDeleteGlobal.restype = None + LLVMDeleteGlobal.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetInitializer = _libraries['llvm'].LLVMGetInitializer + LLVMGetInitializer.restype = LLVMValueRef + LLVMGetInitializer.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetInitializer = _libraries['llvm'].LLVMSetInitializer + LLVMSetInitializer.restype = None + LLVMSetInitializer.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsThreadLocal = _libraries['llvm'].LLVMIsThreadLocal + LLVMIsThreadLocal.restype = LLVMBool + LLVMIsThreadLocal.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetThreadLocal = _libraries['llvm'].LLVMSetThreadLocal + LLVMSetThreadLocal.restype = None + LLVMSetThreadLocal.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMIsGlobalConstant = _libraries['llvm'].LLVMIsGlobalConstant + LLVMIsGlobalConstant.restype = LLVMBool + LLVMIsGlobalConstant.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetGlobalConstant = _libraries['llvm'].LLVMSetGlobalConstant + LLVMSetGlobalConstant.restype = None + LLVMSetGlobalConstant.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetThreadLocalMode = _libraries['llvm'].LLVMGetThreadLocalMode + LLVMGetThreadLocalMode.restype = LLVMThreadLocalMode + LLVMGetThreadLocalMode.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetThreadLocalMode = _libraries['llvm'].LLVMSetThreadLocalMode + LLVMSetThreadLocalMode.restype = None + LLVMSetThreadLocalMode.argtypes = [LLVMValueRef, LLVMThreadLocalMode] +except AttributeError: + pass +try: + LLVMIsExternallyInitialized = _libraries['llvm'].LLVMIsExternallyInitialized + LLVMIsExternallyInitialized.restype = LLVMBool + LLVMIsExternallyInitialized.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetExternallyInitialized = _libraries['llvm'].LLVMSetExternallyInitialized + LLVMSetExternallyInitialized.restype = None + LLVMSetExternallyInitialized.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMAddAlias = _libraries['llvm'].LLVMAddAlias + LLVMAddAlias.restype = LLVMValueRef + LLVMAddAlias.argtypes = [LLVMModuleRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAddAlias2 = _libraries['llvm'].LLVMAddAlias2 + LLVMAddAlias2.restype = LLVMValueRef + LLVMAddAlias2.argtypes = [LLVMModuleRef, LLVMTypeRef, ctypes.c_uint32, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetNamedGlobalAlias = _libraries['llvm'].LLVMGetNamedGlobalAlias + LLVMGetNamedGlobalAlias.restype = LLVMValueRef + LLVMGetNamedGlobalAlias.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetFirstGlobalAlias = _libraries['llvm'].LLVMGetFirstGlobalAlias + LLVMGetFirstGlobalAlias.restype = LLVMValueRef + LLVMGetFirstGlobalAlias.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetLastGlobalAlias = _libraries['llvm'].LLVMGetLastGlobalAlias + LLVMGetLastGlobalAlias.restype = LLVMValueRef + LLVMGetLastGlobalAlias.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetNextGlobalAlias = _libraries['llvm'].LLVMGetNextGlobalAlias + LLVMGetNextGlobalAlias.restype = LLVMValueRef + LLVMGetNextGlobalAlias.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousGlobalAlias = _libraries['llvm'].LLVMGetPreviousGlobalAlias + LLVMGetPreviousGlobalAlias.restype = LLVMValueRef + LLVMGetPreviousGlobalAlias.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMAliasGetAliasee = _libraries['llvm'].LLVMAliasGetAliasee + LLVMAliasGetAliasee.restype = LLVMValueRef + LLVMAliasGetAliasee.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMAliasSetAliasee = _libraries['llvm'].LLVMAliasSetAliasee + LLVMAliasSetAliasee.restype = None + LLVMAliasSetAliasee.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMDeleteFunction = _libraries['llvm'].LLVMDeleteFunction + LLVMDeleteFunction.restype = None + LLVMDeleteFunction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMHasPersonalityFn = _libraries['llvm'].LLVMHasPersonalityFn + LLVMHasPersonalityFn.restype = LLVMBool + LLVMHasPersonalityFn.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPersonalityFn = _libraries['llvm'].LLVMGetPersonalityFn + LLVMGetPersonalityFn.restype = LLVMValueRef + LLVMGetPersonalityFn.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetPersonalityFn = _libraries['llvm'].LLVMSetPersonalityFn + LLVMSetPersonalityFn.restype = None + LLVMSetPersonalityFn.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMLookupIntrinsicID = _libraries['llvm'].LLVMLookupIntrinsicID + LLVMLookupIntrinsicID.restype = ctypes.c_uint32 + LLVMLookupIntrinsicID.argtypes = [ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetIntrinsicID = _libraries['llvm'].LLVMGetIntrinsicID + LLVMGetIntrinsicID.restype = ctypes.c_uint32 + LLVMGetIntrinsicID.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetIntrinsicDeclaration = _libraries['llvm'].LLVMGetIntrinsicDeclaration + LLVMGetIntrinsicDeclaration.restype = LLVMValueRef + LLVMGetIntrinsicDeclaration.argtypes = [LLVMModuleRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), size_t] +except AttributeError: + pass +try: + LLVMIntrinsicGetType = _libraries['llvm'].LLVMIntrinsicGetType + LLVMIntrinsicGetType.restype = LLVMTypeRef + LLVMIntrinsicGetType.argtypes = [LLVMContextRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), size_t] +except AttributeError: + pass +try: + LLVMIntrinsicGetName = _libraries['llvm'].LLVMIntrinsicGetName + LLVMIntrinsicGetName.restype = ctypes.POINTER(ctypes.c_char) + LLVMIntrinsicGetName.argtypes = [ctypes.c_uint32, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMIntrinsicCopyOverloadedName = _libraries['llvm'].LLVMIntrinsicCopyOverloadedName + LLVMIntrinsicCopyOverloadedName.restype = ctypes.POINTER(ctypes.c_char) + LLVMIntrinsicCopyOverloadedName.argtypes = [ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), size_t, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMIntrinsicCopyOverloadedName2 = _libraries['llvm'].LLVMIntrinsicCopyOverloadedName2 + LLVMIntrinsicCopyOverloadedName2.restype = ctypes.POINTER(ctypes.c_char) + LLVMIntrinsicCopyOverloadedName2.argtypes = [LLVMModuleRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueType)), size_t, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMIntrinsicIsOverloaded = _libraries['llvm'].LLVMIntrinsicIsOverloaded + LLVMIntrinsicIsOverloaded.restype = LLVMBool + LLVMIntrinsicIsOverloaded.argtypes = [ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetFunctionCallConv = _libraries['llvm'].LLVMGetFunctionCallConv + LLVMGetFunctionCallConv.restype = ctypes.c_uint32 + LLVMGetFunctionCallConv.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetFunctionCallConv = _libraries['llvm'].LLVMSetFunctionCallConv + LLVMSetFunctionCallConv.restype = None + LLVMSetFunctionCallConv.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetGC = _libraries['llvm'].LLVMGetGC + LLVMGetGC.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetGC.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetGC = _libraries['llvm'].LLVMSetGC + LLVMSetGC.restype = None + LLVMSetGC.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAddAttributeAtIndex = _libraries['llvm'].LLVMAddAttributeAtIndex + LLVMAddAttributeAtIndex.restype = None + LLVMAddAttributeAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMGetAttributeCountAtIndex = _libraries['llvm'].LLVMGetAttributeCountAtIndex + LLVMGetAttributeCountAtIndex.restype = ctypes.c_uint32 + LLVMGetAttributeCountAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex] +except AttributeError: + pass +try: + LLVMGetAttributesAtIndex = _libraries['llvm'].LLVMGetAttributesAtIndex + LLVMGetAttributesAtIndex.restype = None + LLVMGetAttributesAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueAttributeRef))] +except AttributeError: + pass +try: + LLVMGetEnumAttributeAtIndex = _libraries['llvm'].LLVMGetEnumAttributeAtIndex + LLVMGetEnumAttributeAtIndex.restype = LLVMAttributeRef + LLVMGetEnumAttributeAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetStringAttributeAtIndex = _libraries['llvm'].LLVMGetStringAttributeAtIndex + LLVMGetStringAttributeAtIndex.restype = LLVMAttributeRef + LLVMGetStringAttributeAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMRemoveEnumAttributeAtIndex = _libraries['llvm'].LLVMRemoveEnumAttributeAtIndex + LLVMRemoveEnumAttributeAtIndex.restype = None + LLVMRemoveEnumAttributeAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMRemoveStringAttributeAtIndex = _libraries['llvm'].LLVMRemoveStringAttributeAtIndex + LLVMRemoveStringAttributeAtIndex.restype = None + LLVMRemoveStringAttributeAtIndex.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddTargetDependentFunctionAttr = _libraries['llvm'].LLVMAddTargetDependentFunctionAttr + LLVMAddTargetDependentFunctionAttr.restype = None + LLVMAddTargetDependentFunctionAttr.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMCountParams = _libraries['llvm'].LLVMCountParams + LLVMCountParams.restype = ctypes.c_uint32 + LLVMCountParams.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetParams = _libraries['llvm'].LLVMGetParams + LLVMGetParams.restype = None + LLVMGetParams.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue))] +except AttributeError: + pass +try: + LLVMGetParam = _libraries['llvm'].LLVMGetParam + LLVMGetParam.restype = LLVMValueRef + LLVMGetParam.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetParamParent = _libraries['llvm'].LLVMGetParamParent + LLVMGetParamParent.restype = LLVMValueRef + LLVMGetParamParent.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetFirstParam = _libraries['llvm'].LLVMGetFirstParam + LLVMGetFirstParam.restype = LLVMValueRef + LLVMGetFirstParam.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetLastParam = _libraries['llvm'].LLVMGetLastParam + LLVMGetLastParam.restype = LLVMValueRef + LLVMGetLastParam.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNextParam = _libraries['llvm'].LLVMGetNextParam + LLVMGetNextParam.restype = LLVMValueRef + LLVMGetNextParam.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousParam = _libraries['llvm'].LLVMGetPreviousParam + LLVMGetPreviousParam.restype = LLVMValueRef + LLVMGetPreviousParam.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetParamAlignment = _libraries['llvm'].LLVMSetParamAlignment + LLVMSetParamAlignment.restype = None + LLVMSetParamAlignment.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddGlobalIFunc = _libraries['llvm'].LLVMAddGlobalIFunc + LLVMAddGlobalIFunc.restype = LLVMValueRef + LLVMAddGlobalIFunc.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMTypeRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNamedGlobalIFunc = _libraries['llvm'].LLVMGetNamedGlobalIFunc + LLVMGetNamedGlobalIFunc.restype = LLVMValueRef + LLVMGetNamedGlobalIFunc.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMGetFirstGlobalIFunc = _libraries['llvm'].LLVMGetFirstGlobalIFunc + LLVMGetFirstGlobalIFunc.restype = LLVMValueRef + LLVMGetFirstGlobalIFunc.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetLastGlobalIFunc = _libraries['llvm'].LLVMGetLastGlobalIFunc + LLVMGetLastGlobalIFunc.restype = LLVMValueRef + LLVMGetLastGlobalIFunc.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMGetNextGlobalIFunc = _libraries['llvm'].LLVMGetNextGlobalIFunc + LLVMGetNextGlobalIFunc.restype = LLVMValueRef + LLVMGetNextGlobalIFunc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousGlobalIFunc = _libraries['llvm'].LLVMGetPreviousGlobalIFunc + LLVMGetPreviousGlobalIFunc.restype = LLVMValueRef + LLVMGetPreviousGlobalIFunc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetGlobalIFuncResolver = _libraries['llvm'].LLVMGetGlobalIFuncResolver + LLVMGetGlobalIFuncResolver.restype = LLVMValueRef + LLVMGetGlobalIFuncResolver.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetGlobalIFuncResolver = _libraries['llvm'].LLVMSetGlobalIFuncResolver + LLVMSetGlobalIFuncResolver.restype = None + LLVMSetGlobalIFuncResolver.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMEraseGlobalIFunc = _libraries['llvm'].LLVMEraseGlobalIFunc + LLVMEraseGlobalIFunc.restype = None + LLVMEraseGlobalIFunc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMRemoveGlobalIFunc = _libraries['llvm'].LLVMRemoveGlobalIFunc + LLVMRemoveGlobalIFunc.restype = None + LLVMRemoveGlobalIFunc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMMDStringInContext2 = _libraries['llvm'].LLVMMDStringInContext2 + LLVMMDStringInContext2.restype = LLVMMetadataRef + LLVMMDStringInContext2.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMMDNodeInContext2 = _libraries['llvm'].LLVMMDNodeInContext2 + LLVMMDNodeInContext2.restype = LLVMMetadataRef + LLVMMDNodeInContext2.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), size_t] +except AttributeError: + pass +try: + LLVMMetadataAsValue = _libraries['llvm'].LLVMMetadataAsValue + LLVMMetadataAsValue.restype = LLVMValueRef + LLVMMetadataAsValue.argtypes = [LLVMContextRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMValueAsMetadata = _libraries['llvm'].LLVMValueAsMetadata + LLVMValueAsMetadata.restype = LLVMMetadataRef + LLVMValueAsMetadata.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetMDString = _libraries['llvm'].LLVMGetMDString + LLVMGetMDString.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetMDString.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMGetMDNodeNumOperands = _libraries['llvm'].LLVMGetMDNodeNumOperands + LLVMGetMDNodeNumOperands.restype = ctypes.c_uint32 + LLVMGetMDNodeNumOperands.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetMDNodeOperands = _libraries['llvm'].LLVMGetMDNodeOperands + LLVMGetMDNodeOperands.restype = None + LLVMGetMDNodeOperands.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue))] +except AttributeError: + pass +try: + LLVMMDStringInContext = _libraries['llvm'].LLVMMDStringInContext + LLVMMDStringInContext.restype = LLVMValueRef + LLVMMDStringInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMMDString = _libraries['llvm'].LLVMMDString + LLVMMDString.restype = LLVMValueRef + LLVMMDString.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMMDNodeInContext = _libraries['llvm'].LLVMMDNodeInContext + LLVMMDNodeInContext.restype = LLVMValueRef + LLVMMDNodeInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMMDNode = _libraries['llvm'].LLVMMDNode + LLVMMDNode.restype = LLVMValueRef + LLVMMDNode.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBasicBlockAsValue = _libraries['llvm'].LLVMBasicBlockAsValue + LLVMBasicBlockAsValue.restype = LLVMValueRef + LLVMBasicBlockAsValue.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMValueIsBasicBlock = _libraries['llvm'].LLVMValueIsBasicBlock + LLVMValueIsBasicBlock.restype = LLVMBool + LLVMValueIsBasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMValueAsBasicBlock = _libraries['llvm'].LLVMValueAsBasicBlock + LLVMValueAsBasicBlock.restype = LLVMBasicBlockRef + LLVMValueAsBasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetBasicBlockName = _libraries['llvm'].LLVMGetBasicBlockName + LLVMGetBasicBlockName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetBasicBlockName.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetBasicBlockParent = _libraries['llvm'].LLVMGetBasicBlockParent + LLVMGetBasicBlockParent.restype = LLVMValueRef + LLVMGetBasicBlockParent.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetBasicBlockTerminator = _libraries['llvm'].LLVMGetBasicBlockTerminator + LLVMGetBasicBlockTerminator.restype = LLVMValueRef + LLVMGetBasicBlockTerminator.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMCountBasicBlocks = _libraries['llvm'].LLVMCountBasicBlocks + LLVMCountBasicBlocks.restype = ctypes.c_uint32 + LLVMCountBasicBlocks.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetBasicBlocks = _libraries['llvm'].LLVMGetBasicBlocks + LLVMGetBasicBlocks.restype = None + LLVMGetBasicBlocks.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueBasicBlock))] +except AttributeError: + pass +try: + LLVMGetFirstBasicBlock = _libraries['llvm'].LLVMGetFirstBasicBlock + LLVMGetFirstBasicBlock.restype = LLVMBasicBlockRef + LLVMGetFirstBasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetLastBasicBlock = _libraries['llvm'].LLVMGetLastBasicBlock + LLVMGetLastBasicBlock.restype = LLVMBasicBlockRef + LLVMGetLastBasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNextBasicBlock = _libraries['llvm'].LLVMGetNextBasicBlock + LLVMGetNextBasicBlock.restype = LLVMBasicBlockRef + LLVMGetNextBasicBlock.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetPreviousBasicBlock = _libraries['llvm'].LLVMGetPreviousBasicBlock + LLVMGetPreviousBasicBlock.restype = LLVMBasicBlockRef + LLVMGetPreviousBasicBlock.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetEntryBasicBlock = _libraries['llvm'].LLVMGetEntryBasicBlock + LLVMGetEntryBasicBlock.restype = LLVMBasicBlockRef + LLVMGetEntryBasicBlock.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMInsertExistingBasicBlockAfterInsertBlock = _libraries['llvm'].LLVMInsertExistingBasicBlockAfterInsertBlock + LLVMInsertExistingBasicBlockAfterInsertBlock.restype = None + LLVMInsertExistingBasicBlockAfterInsertBlock.argtypes = [LLVMBuilderRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMAppendExistingBasicBlock = _libraries['llvm'].LLVMAppendExistingBasicBlock + LLVMAppendExistingBasicBlock.restype = None + LLVMAppendExistingBasicBlock.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMCreateBasicBlockInContext = _libraries['llvm'].LLVMCreateBasicBlockInContext + LLVMCreateBasicBlockInContext.restype = LLVMBasicBlockRef + LLVMCreateBasicBlockInContext.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAppendBasicBlockInContext = _libraries['llvm'].LLVMAppendBasicBlockInContext + LLVMAppendBasicBlockInContext.restype = LLVMBasicBlockRef + LLVMAppendBasicBlockInContext.argtypes = [LLVMContextRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAppendBasicBlock = _libraries['llvm'].LLVMAppendBasicBlock + LLVMAppendBasicBlock.restype = LLVMBasicBlockRef + LLVMAppendBasicBlock.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMInsertBasicBlockInContext = _libraries['llvm'].LLVMInsertBasicBlockInContext + LLVMInsertBasicBlockInContext.restype = LLVMBasicBlockRef + LLVMInsertBasicBlockInContext.argtypes = [LLVMContextRef, LLVMBasicBlockRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMInsertBasicBlock = _libraries['llvm'].LLVMInsertBasicBlock + LLVMInsertBasicBlock.restype = LLVMBasicBlockRef + LLVMInsertBasicBlock.argtypes = [LLVMBasicBlockRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMDeleteBasicBlock = _libraries['llvm'].LLVMDeleteBasicBlock + LLVMDeleteBasicBlock.restype = None + LLVMDeleteBasicBlock.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMRemoveBasicBlockFromParent = _libraries['llvm'].LLVMRemoveBasicBlockFromParent + LLVMRemoveBasicBlockFromParent.restype = None + LLVMRemoveBasicBlockFromParent.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMMoveBasicBlockBefore = _libraries['llvm'].LLVMMoveBasicBlockBefore + LLVMMoveBasicBlockBefore.restype = None + LLVMMoveBasicBlockBefore.argtypes = [LLVMBasicBlockRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMMoveBasicBlockAfter = _libraries['llvm'].LLVMMoveBasicBlockAfter + LLVMMoveBasicBlockAfter.restype = None + LLVMMoveBasicBlockAfter.argtypes = [LLVMBasicBlockRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetFirstInstruction = _libraries['llvm'].LLVMGetFirstInstruction + LLVMGetFirstInstruction.restype = LLVMValueRef + LLVMGetFirstInstruction.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetLastInstruction = _libraries['llvm'].LLVMGetLastInstruction + LLVMGetLastInstruction.restype = LLVMValueRef + LLVMGetLastInstruction.argtypes = [LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMHasMetadata = _libraries['llvm'].LLVMHasMetadata + LLVMHasMetadata.restype = ctypes.c_int32 + LLVMHasMetadata.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetMetadata = _libraries['llvm'].LLVMGetMetadata + LLVMGetMetadata.restype = LLVMValueRef + LLVMGetMetadata.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMSetMetadata = _libraries['llvm'].LLVMSetMetadata + LLVMSetMetadata.restype = None + LLVMSetMetadata.argtypes = [LLVMValueRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMInstructionGetAllMetadataOtherThanDebugLoc = _libraries['llvm'].LLVMInstructionGetAllMetadataOtherThanDebugLoc + LLVMInstructionGetAllMetadataOtherThanDebugLoc.restype = ctypes.POINTER(struct_LLVMOpaqueValueMetadataEntry) + LLVMInstructionGetAllMetadataOtherThanDebugLoc.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMGetInstructionParent = _libraries['llvm'].LLVMGetInstructionParent + LLVMGetInstructionParent.restype = LLVMBasicBlockRef + LLVMGetInstructionParent.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNextInstruction = _libraries['llvm'].LLVMGetNextInstruction + LLVMGetNextInstruction.restype = LLVMValueRef + LLVMGetNextInstruction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetPreviousInstruction = _libraries['llvm'].LLVMGetPreviousInstruction + LLVMGetPreviousInstruction.restype = LLVMValueRef + LLVMGetPreviousInstruction.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMInstructionRemoveFromParent = _libraries['llvm'].LLVMInstructionRemoveFromParent + LLVMInstructionRemoveFromParent.restype = None + LLVMInstructionRemoveFromParent.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMInstructionEraseFromParent = _libraries['llvm'].LLVMInstructionEraseFromParent + LLVMInstructionEraseFromParent.restype = None + LLVMInstructionEraseFromParent.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetInstructionOpcode = _libraries['llvm'].LLVMGetInstructionOpcode + LLVMGetInstructionOpcode.restype = LLVMOpcode + LLVMGetInstructionOpcode.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetICmpPredicate = _libraries['llvm'].LLVMGetICmpPredicate + LLVMGetICmpPredicate.restype = LLVMIntPredicate + LLVMGetICmpPredicate.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetFCmpPredicate = _libraries['llvm'].LLVMGetFCmpPredicate + LLVMGetFCmpPredicate.restype = LLVMRealPredicate + LLVMGetFCmpPredicate.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMInstructionClone = _libraries['llvm'].LLVMInstructionClone + LLVMInstructionClone.restype = LLVMValueRef + LLVMInstructionClone.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsATerminatorInst = _libraries['llvm'].LLVMIsATerminatorInst + LLVMIsATerminatorInst.restype = LLVMValueRef + LLVMIsATerminatorInst.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetNumArgOperands = _libraries['llvm'].LLVMGetNumArgOperands + LLVMGetNumArgOperands.restype = ctypes.c_uint32 + LLVMGetNumArgOperands.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetInstructionCallConv = _libraries['llvm'].LLVMSetInstructionCallConv + LLVMSetInstructionCallConv.restype = None + LLVMSetInstructionCallConv.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetInstructionCallConv = _libraries['llvm'].LLVMGetInstructionCallConv + LLVMGetInstructionCallConv.restype = ctypes.c_uint32 + LLVMGetInstructionCallConv.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetInstrParamAlignment = _libraries['llvm'].LLVMSetInstrParamAlignment + LLVMSetInstrParamAlignment.restype = None + LLVMSetInstrParamAlignment.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddCallSiteAttribute = _libraries['llvm'].LLVMAddCallSiteAttribute + LLVMAddCallSiteAttribute.restype = None + LLVMAddCallSiteAttribute.argtypes = [LLVMValueRef, LLVMAttributeIndex, LLVMAttributeRef] +except AttributeError: + pass +try: + LLVMGetCallSiteAttributeCount = _libraries['llvm'].LLVMGetCallSiteAttributeCount + LLVMGetCallSiteAttributeCount.restype = ctypes.c_uint32 + LLVMGetCallSiteAttributeCount.argtypes = [LLVMValueRef, LLVMAttributeIndex] +except AttributeError: + pass +try: + LLVMGetCallSiteAttributes = _libraries['llvm'].LLVMGetCallSiteAttributes + LLVMGetCallSiteAttributes.restype = None + LLVMGetCallSiteAttributes.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueAttributeRef))] +except AttributeError: + pass +try: + LLVMGetCallSiteEnumAttribute = _libraries['llvm'].LLVMGetCallSiteEnumAttribute + LLVMGetCallSiteEnumAttribute.restype = LLVMAttributeRef + LLVMGetCallSiteEnumAttribute.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetCallSiteStringAttribute = _libraries['llvm'].LLVMGetCallSiteStringAttribute + LLVMGetCallSiteStringAttribute.restype = LLVMAttributeRef + LLVMGetCallSiteStringAttribute.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMRemoveCallSiteEnumAttribute = _libraries['llvm'].LLVMRemoveCallSiteEnumAttribute + LLVMRemoveCallSiteEnumAttribute.restype = None + LLVMRemoveCallSiteEnumAttribute.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMRemoveCallSiteStringAttribute = _libraries['llvm'].LLVMRemoveCallSiteStringAttribute + LLVMRemoveCallSiteStringAttribute.restype = None + LLVMRemoveCallSiteStringAttribute.argtypes = [LLVMValueRef, LLVMAttributeIndex, ctypes.POINTER(ctypes.c_char), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetCalledFunctionType = _libraries['llvm'].LLVMGetCalledFunctionType + LLVMGetCalledFunctionType.restype = LLVMTypeRef + LLVMGetCalledFunctionType.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetCalledValue = _libraries['llvm'].LLVMGetCalledValue + LLVMGetCalledValue.restype = LLVMValueRef + LLVMGetCalledValue.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsTailCall = _libraries['llvm'].LLVMIsTailCall + LLVMIsTailCall.restype = LLVMBool + LLVMIsTailCall.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetTailCall = _libraries['llvm'].LLVMSetTailCall + LLVMSetTailCall.restype = None + LLVMSetTailCall.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetNormalDest = _libraries['llvm'].LLVMGetNormalDest + LLVMGetNormalDest.restype = LLVMBasicBlockRef + LLVMGetNormalDest.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetUnwindDest = _libraries['llvm'].LLVMGetUnwindDest + LLVMGetUnwindDest.restype = LLVMBasicBlockRef + LLVMGetUnwindDest.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetNormalDest = _libraries['llvm'].LLVMSetNormalDest + LLVMSetNormalDest.restype = None + LLVMSetNormalDest.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMSetUnwindDest = _libraries['llvm'].LLVMSetUnwindDest + LLVMSetUnwindDest.restype = None + LLVMSetUnwindDest.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetNumSuccessors = _libraries['llvm'].LLVMGetNumSuccessors + LLVMGetNumSuccessors.restype = ctypes.c_uint32 + LLVMGetNumSuccessors.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetSuccessor = _libraries['llvm'].LLVMGetSuccessor + LLVMGetSuccessor.restype = LLVMBasicBlockRef + LLVMGetSuccessor.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMSetSuccessor = _libraries['llvm'].LLVMSetSuccessor + LLVMSetSuccessor.restype = None + LLVMSetSuccessor.argtypes = [LLVMValueRef, ctypes.c_uint32, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMIsConditional = _libraries['llvm'].LLVMIsConditional + LLVMIsConditional.restype = LLVMBool + LLVMIsConditional.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetCondition = _libraries['llvm'].LLVMGetCondition + LLVMGetCondition.restype = LLVMValueRef + LLVMGetCondition.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetCondition = _libraries['llvm'].LLVMSetCondition + LLVMSetCondition.restype = None + LLVMSetCondition.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetSwitchDefaultDest = _libraries['llvm'].LLVMGetSwitchDefaultDest + LLVMGetSwitchDefaultDest.restype = LLVMBasicBlockRef + LLVMGetSwitchDefaultDest.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetAllocatedType = _libraries['llvm'].LLVMGetAllocatedType + LLVMGetAllocatedType.restype = LLVMTypeRef + LLVMGetAllocatedType.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsInBounds = _libraries['llvm'].LLVMIsInBounds + LLVMIsInBounds.restype = LLVMBool + LLVMIsInBounds.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetIsInBounds = _libraries['llvm'].LLVMSetIsInBounds + LLVMSetIsInBounds.restype = None + LLVMSetIsInBounds.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetGEPSourceElementType = _libraries['llvm'].LLVMGetGEPSourceElementType + LLVMGetGEPSourceElementType.restype = LLVMTypeRef + LLVMGetGEPSourceElementType.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMAddIncoming = _libraries['llvm'].LLVMAddIncoming + LLVMAddIncoming.restype = None + LLVMAddIncoming.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueBasicBlock)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMCountIncoming = _libraries['llvm'].LLVMCountIncoming + LLVMCountIncoming.restype = ctypes.c_uint32 + LLVMCountIncoming.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetIncomingValue = _libraries['llvm'].LLVMGetIncomingValue + LLVMGetIncomingValue.restype = LLVMValueRef + LLVMGetIncomingValue.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetIncomingBlock = _libraries['llvm'].LLVMGetIncomingBlock + LLVMGetIncomingBlock.restype = LLVMBasicBlockRef + LLVMGetIncomingBlock.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMGetNumIndices = _libraries['llvm'].LLVMGetNumIndices + LLVMGetNumIndices.restype = ctypes.c_uint32 + LLVMGetNumIndices.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetIndices = _libraries['llvm'].LLVMGetIndices + LLVMGetIndices.restype = ctypes.POINTER(ctypes.c_uint32) + LLVMGetIndices.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMCreateBuilderInContext = _libraries['llvm'].LLVMCreateBuilderInContext + LLVMCreateBuilderInContext.restype = LLVMBuilderRef + LLVMCreateBuilderInContext.argtypes = [LLVMContextRef] +except AttributeError: + pass +try: + LLVMCreateBuilder = _libraries['llvm'].LLVMCreateBuilder + LLVMCreateBuilder.restype = LLVMBuilderRef + LLVMCreateBuilder.argtypes = [] +except AttributeError: + pass +try: + LLVMPositionBuilder = _libraries['llvm'].LLVMPositionBuilder + LLVMPositionBuilder.restype = None + LLVMPositionBuilder.argtypes = [LLVMBuilderRef, LLVMBasicBlockRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMPositionBuilderBefore = _libraries['llvm'].LLVMPositionBuilderBefore + LLVMPositionBuilderBefore.restype = None + LLVMPositionBuilderBefore.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMPositionBuilderAtEnd = _libraries['llvm'].LLVMPositionBuilderAtEnd + LLVMPositionBuilderAtEnd.restype = None + LLVMPositionBuilderAtEnd.argtypes = [LLVMBuilderRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetInsertBlock = _libraries['llvm'].LLVMGetInsertBlock + LLVMGetInsertBlock.restype = LLVMBasicBlockRef + LLVMGetInsertBlock.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMClearInsertionPosition = _libraries['llvm'].LLVMClearInsertionPosition + LLVMClearInsertionPosition.restype = None + LLVMClearInsertionPosition.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMInsertIntoBuilder = _libraries['llvm'].LLVMInsertIntoBuilder + LLVMInsertIntoBuilder.restype = None + LLVMInsertIntoBuilder.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMInsertIntoBuilderWithName = _libraries['llvm'].LLVMInsertIntoBuilderWithName + LLVMInsertIntoBuilderWithName.restype = None + LLVMInsertIntoBuilderWithName.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMDisposeBuilder = _libraries['llvm'].LLVMDisposeBuilder + LLVMDisposeBuilder.restype = None + LLVMDisposeBuilder.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMGetCurrentDebugLocation2 = _libraries['llvm'].LLVMGetCurrentDebugLocation2 + LLVMGetCurrentDebugLocation2.restype = LLVMMetadataRef + LLVMGetCurrentDebugLocation2.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMSetCurrentDebugLocation2 = _libraries['llvm'].LLVMSetCurrentDebugLocation2 + LLVMSetCurrentDebugLocation2.restype = None + LLVMSetCurrentDebugLocation2.argtypes = [LLVMBuilderRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMSetInstDebugLocation = _libraries['llvm'].LLVMSetInstDebugLocation + LLVMSetInstDebugLocation.restype = None + LLVMSetInstDebugLocation.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMAddMetadataToInst = _libraries['llvm'].LLVMAddMetadataToInst + LLVMAddMetadataToInst.restype = None + LLVMAddMetadataToInst.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuilderGetDefaultFPMathTag = _libraries['llvm'].LLVMBuilderGetDefaultFPMathTag + LLVMBuilderGetDefaultFPMathTag.restype = LLVMMetadataRef + LLVMBuilderGetDefaultFPMathTag.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMBuilderSetDefaultFPMathTag = _libraries['llvm'].LLVMBuilderSetDefaultFPMathTag + LLVMBuilderSetDefaultFPMathTag.restype = None + LLVMBuilderSetDefaultFPMathTag.argtypes = [LLVMBuilderRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMSetCurrentDebugLocation = _libraries['llvm'].LLVMSetCurrentDebugLocation + LLVMSetCurrentDebugLocation.restype = None + LLVMSetCurrentDebugLocation.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetCurrentDebugLocation = _libraries['llvm'].LLVMGetCurrentDebugLocation + LLVMGetCurrentDebugLocation.restype = LLVMValueRef + LLVMGetCurrentDebugLocation.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMBuildRetVoid = _libraries['llvm'].LLVMBuildRetVoid + LLVMBuildRetVoid.restype = LLVMValueRef + LLVMBuildRetVoid.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMBuildRet = _libraries['llvm'].LLVMBuildRet + LLVMBuildRet.restype = LLVMValueRef + LLVMBuildRet.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildAggregateRet = _libraries['llvm'].LLVMBuildAggregateRet + LLVMBuildAggregateRet.restype = LLVMValueRef + LLVMBuildAggregateRet.argtypes = [LLVMBuilderRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBuildBr = _libraries['llvm'].LLVMBuildBr + LLVMBuildBr.restype = LLVMValueRef + LLVMBuildBr.argtypes = [LLVMBuilderRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMBuildCondBr = _libraries['llvm'].LLVMBuildCondBr + LLVMBuildCondBr.restype = LLVMValueRef + LLVMBuildCondBr.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMBasicBlockRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMBuildSwitch = _libraries['llvm'].LLVMBuildSwitch + LLVMBuildSwitch.restype = LLVMValueRef + LLVMBuildSwitch.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMBasicBlockRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBuildIndirectBr = _libraries['llvm'].LLVMBuildIndirectBr + LLVMBuildIndirectBr.restype = LLVMValueRef + LLVMBuildIndirectBr.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBuildInvoke = _libraries['llvm'].LLVMBuildInvoke + LLVMBuildInvoke.restype = LLVMValueRef + LLVMBuildInvoke.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, LLVMBasicBlockRef, LLVMBasicBlockRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildInvoke2 = _libraries['llvm'].LLVMBuildInvoke2 + LLVMBuildInvoke2.restype = LLVMValueRef + LLVMBuildInvoke2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, LLVMBasicBlockRef, LLVMBasicBlockRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildUnreachable = _libraries['llvm'].LLVMBuildUnreachable + LLVMBuildUnreachable.restype = LLVMValueRef + LLVMBuildUnreachable.argtypes = [LLVMBuilderRef] +except AttributeError: + pass +try: + LLVMBuildResume = _libraries['llvm'].LLVMBuildResume + LLVMBuildResume.restype = LLVMValueRef + LLVMBuildResume.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildLandingPad = _libraries['llvm'].LLVMBuildLandingPad + LLVMBuildLandingPad.restype = LLVMValueRef + LLVMBuildLandingPad.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCleanupRet = _libraries['llvm'].LLVMBuildCleanupRet + LLVMBuildCleanupRet.restype = LLVMValueRef + LLVMBuildCleanupRet.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMBuildCatchRet = _libraries['llvm'].LLVMBuildCatchRet + LLVMBuildCatchRet.restype = LLVMValueRef + LLVMBuildCatchRet.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMBuildCatchPad = _libraries['llvm'].LLVMBuildCatchPad + LLVMBuildCatchPad.restype = LLVMValueRef + LLVMBuildCatchPad.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCleanupPad = _libraries['llvm'].LLVMBuildCleanupPad + LLVMBuildCleanupPad.restype = LLVMValueRef + LLVMBuildCleanupPad.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCatchSwitch = _libraries['llvm'].LLVMBuildCatchSwitch + LLVMBuildCatchSwitch.restype = LLVMValueRef + LLVMBuildCatchSwitch.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMBasicBlockRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAddCase = _libraries['llvm'].LLVMAddCase + LLVMAddCase.restype = None + LLVMAddCase.argtypes = [LLVMValueRef, LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMAddDestination = _libraries['llvm'].LLVMAddDestination + LLVMAddDestination.restype = None + LLVMAddDestination.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetNumClauses = _libraries['llvm'].LLVMGetNumClauses + LLVMGetNumClauses.restype = ctypes.c_uint32 + LLVMGetNumClauses.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetClause = _libraries['llvm'].LLVMGetClause + LLVMGetClause.restype = LLVMValueRef + LLVMGetClause.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddClause = _libraries['llvm'].LLVMAddClause + LLVMAddClause.restype = None + LLVMAddClause.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMIsCleanup = _libraries['llvm'].LLVMIsCleanup + LLVMIsCleanup.restype = LLVMBool + LLVMIsCleanup.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetCleanup = _libraries['llvm'].LLVMSetCleanup + LLVMSetCleanup.restype = None + LLVMSetCleanup.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMAddHandler = _libraries['llvm'].LLVMAddHandler + LLVMAddHandler.restype = None + LLVMAddHandler.argtypes = [LLVMValueRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMGetNumHandlers = _libraries['llvm'].LLVMGetNumHandlers + LLVMGetNumHandlers.restype = ctypes.c_uint32 + LLVMGetNumHandlers.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetHandlers = _libraries['llvm'].LLVMGetHandlers + LLVMGetHandlers.restype = None + LLVMGetHandlers.argtypes = [LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueBasicBlock))] +except AttributeError: + pass +try: + LLVMGetArgOperand = _libraries['llvm'].LLVMGetArgOperand + LLVMGetArgOperand.restype = LLVMValueRef + LLVMGetArgOperand.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMSetArgOperand = _libraries['llvm'].LLVMSetArgOperand + LLVMSetArgOperand.restype = None + LLVMSetArgOperand.argtypes = [LLVMValueRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetParentCatchSwitch = _libraries['llvm'].LLVMGetParentCatchSwitch + LLVMGetParentCatchSwitch.restype = LLVMValueRef + LLVMGetParentCatchSwitch.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetParentCatchSwitch = _libraries['llvm'].LLVMSetParentCatchSwitch + LLVMSetParentCatchSwitch.restype = None + LLVMSetParentCatchSwitch.argtypes = [LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildAdd = _libraries['llvm'].LLVMBuildAdd + LLVMBuildAdd.restype = LLVMValueRef + LLVMBuildAdd.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNSWAdd = _libraries['llvm'].LLVMBuildNSWAdd + LLVMBuildNSWAdd.restype = LLVMValueRef + LLVMBuildNSWAdd.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNUWAdd = _libraries['llvm'].LLVMBuildNUWAdd + LLVMBuildNUWAdd.restype = LLVMValueRef + LLVMBuildNUWAdd.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFAdd = _libraries['llvm'].LLVMBuildFAdd + LLVMBuildFAdd.restype = LLVMValueRef + LLVMBuildFAdd.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSub = _libraries['llvm'].LLVMBuildSub + LLVMBuildSub.restype = LLVMValueRef + LLVMBuildSub.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNSWSub = _libraries['llvm'].LLVMBuildNSWSub + LLVMBuildNSWSub.restype = LLVMValueRef + LLVMBuildNSWSub.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNUWSub = _libraries['llvm'].LLVMBuildNUWSub + LLVMBuildNUWSub.restype = LLVMValueRef + LLVMBuildNUWSub.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFSub = _libraries['llvm'].LLVMBuildFSub + LLVMBuildFSub.restype = LLVMValueRef + LLVMBuildFSub.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildMul = _libraries['llvm'].LLVMBuildMul + LLVMBuildMul.restype = LLVMValueRef + LLVMBuildMul.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNSWMul = _libraries['llvm'].LLVMBuildNSWMul + LLVMBuildNSWMul.restype = LLVMValueRef + LLVMBuildNSWMul.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNUWMul = _libraries['llvm'].LLVMBuildNUWMul + LLVMBuildNUWMul.restype = LLVMValueRef + LLVMBuildNUWMul.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFMul = _libraries['llvm'].LLVMBuildFMul + LLVMBuildFMul.restype = LLVMValueRef + LLVMBuildFMul.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildUDiv = _libraries['llvm'].LLVMBuildUDiv + LLVMBuildUDiv.restype = LLVMValueRef + LLVMBuildUDiv.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildExactUDiv = _libraries['llvm'].LLVMBuildExactUDiv + LLVMBuildExactUDiv.restype = LLVMValueRef + LLVMBuildExactUDiv.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSDiv = _libraries['llvm'].LLVMBuildSDiv + LLVMBuildSDiv.restype = LLVMValueRef + LLVMBuildSDiv.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildExactSDiv = _libraries['llvm'].LLVMBuildExactSDiv + LLVMBuildExactSDiv.restype = LLVMValueRef + LLVMBuildExactSDiv.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFDiv = _libraries['llvm'].LLVMBuildFDiv + LLVMBuildFDiv.restype = LLVMValueRef + LLVMBuildFDiv.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildURem = _libraries['llvm'].LLVMBuildURem + LLVMBuildURem.restype = LLVMValueRef + LLVMBuildURem.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSRem = _libraries['llvm'].LLVMBuildSRem + LLVMBuildSRem.restype = LLVMValueRef + LLVMBuildSRem.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFRem = _libraries['llvm'].LLVMBuildFRem + LLVMBuildFRem.restype = LLVMValueRef + LLVMBuildFRem.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildShl = _libraries['llvm'].LLVMBuildShl + LLVMBuildShl.restype = LLVMValueRef + LLVMBuildShl.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildLShr = _libraries['llvm'].LLVMBuildLShr + LLVMBuildLShr.restype = LLVMValueRef + LLVMBuildLShr.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildAShr = _libraries['llvm'].LLVMBuildAShr + LLVMBuildAShr.restype = LLVMValueRef + LLVMBuildAShr.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildAnd = _libraries['llvm'].LLVMBuildAnd + LLVMBuildAnd.restype = LLVMValueRef + LLVMBuildAnd.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildOr = _libraries['llvm'].LLVMBuildOr + LLVMBuildOr.restype = LLVMValueRef + LLVMBuildOr.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildXor = _libraries['llvm'].LLVMBuildXor + LLVMBuildXor.restype = LLVMValueRef + LLVMBuildXor.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildBinOp = _libraries['llvm'].LLVMBuildBinOp + LLVMBuildBinOp.restype = LLVMValueRef + LLVMBuildBinOp.argtypes = [LLVMBuilderRef, LLVMOpcode, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNeg = _libraries['llvm'].LLVMBuildNeg + LLVMBuildNeg.restype = LLVMValueRef + LLVMBuildNeg.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNSWNeg = _libraries['llvm'].LLVMBuildNSWNeg + LLVMBuildNSWNeg.restype = LLVMValueRef + LLVMBuildNSWNeg.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNUWNeg = _libraries['llvm'].LLVMBuildNUWNeg + LLVMBuildNUWNeg.restype = LLVMValueRef + LLVMBuildNUWNeg.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFNeg = _libraries['llvm'].LLVMBuildFNeg + LLVMBuildFNeg.restype = LLVMValueRef + LLVMBuildFNeg.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildNot = _libraries['llvm'].LLVMBuildNot + LLVMBuildNot.restype = LLVMValueRef + LLVMBuildNot.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildMalloc = _libraries['llvm'].LLVMBuildMalloc + LLVMBuildMalloc.restype = LLVMValueRef + LLVMBuildMalloc.argtypes = [LLVMBuilderRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildArrayMalloc = _libraries['llvm'].LLVMBuildArrayMalloc + LLVMBuildArrayMalloc.restype = LLVMValueRef + LLVMBuildArrayMalloc.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildMemSet = _libraries['llvm'].LLVMBuildMemSet + LLVMBuildMemSet.restype = LLVMValueRef + LLVMBuildMemSet.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMBuildMemCpy = _libraries['llvm'].LLVMBuildMemCpy + LLVMBuildMemCpy.restype = LLVMValueRef + LLVMBuildMemCpy.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.c_uint32, LLVMValueRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildMemMove = _libraries['llvm'].LLVMBuildMemMove + LLVMBuildMemMove.restype = LLVMValueRef + LLVMBuildMemMove.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.c_uint32, LLVMValueRef, ctypes.c_uint32, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildAlloca = _libraries['llvm'].LLVMBuildAlloca + LLVMBuildAlloca.restype = LLVMValueRef + LLVMBuildAlloca.argtypes = [LLVMBuilderRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildArrayAlloca = _libraries['llvm'].LLVMBuildArrayAlloca + LLVMBuildArrayAlloca.restype = LLVMValueRef + LLVMBuildArrayAlloca.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFree = _libraries['llvm'].LLVMBuildFree + LLVMBuildFree.restype = LLVMValueRef + LLVMBuildFree.argtypes = [LLVMBuilderRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildLoad = _libraries['llvm'].LLVMBuildLoad + LLVMBuildLoad.restype = LLVMValueRef + LLVMBuildLoad.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildLoad2 = _libraries['llvm'].LLVMBuildLoad2 + LLVMBuildLoad2.restype = LLVMValueRef + LLVMBuildLoad2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildStore = _libraries['llvm'].LLVMBuildStore + LLVMBuildStore.restype = LLVMValueRef + LLVMBuildStore.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMBuildGEP = _libraries['llvm'].LLVMBuildGEP + LLVMBuildGEP.restype = LLVMValueRef + LLVMBuildGEP.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildInBoundsGEP = _libraries['llvm'].LLVMBuildInBoundsGEP + LLVMBuildInBoundsGEP.restype = LLVMValueRef + LLVMBuildInBoundsGEP.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildStructGEP = _libraries['llvm'].LLVMBuildStructGEP + LLVMBuildStructGEP.restype = LLVMValueRef + LLVMBuildStructGEP.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildGEP2 = _libraries['llvm'].LLVMBuildGEP2 + LLVMBuildGEP2.restype = LLVMValueRef + LLVMBuildGEP2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildInBoundsGEP2 = _libraries['llvm'].LLVMBuildInBoundsGEP2 + LLVMBuildInBoundsGEP2.restype = LLVMValueRef + LLVMBuildInBoundsGEP2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildStructGEP2 = _libraries['llvm'].LLVMBuildStructGEP2 + LLVMBuildStructGEP2.restype = LLVMValueRef + LLVMBuildStructGEP2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildGlobalString = _libraries['llvm'].LLVMBuildGlobalString + LLVMBuildGlobalString.restype = LLVMValueRef + LLVMBuildGlobalString.argtypes = [LLVMBuilderRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildGlobalStringPtr = _libraries['llvm'].LLVMBuildGlobalStringPtr + LLVMBuildGlobalStringPtr.restype = LLVMValueRef + LLVMBuildGlobalStringPtr.argtypes = [LLVMBuilderRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetVolatile = _libraries['llvm'].LLVMGetVolatile + LLVMGetVolatile.restype = LLVMBool + LLVMGetVolatile.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetVolatile = _libraries['llvm'].LLVMSetVolatile + LLVMSetVolatile.restype = None + LLVMSetVolatile.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetWeak = _libraries['llvm'].LLVMGetWeak + LLVMGetWeak.restype = LLVMBool + LLVMGetWeak.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetWeak = _libraries['llvm'].LLVMSetWeak + LLVMSetWeak.restype = None + LLVMSetWeak.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetOrdering = _libraries['llvm'].LLVMGetOrdering + LLVMGetOrdering.restype = LLVMAtomicOrdering + LLVMGetOrdering.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetOrdering = _libraries['llvm'].LLVMSetOrdering + LLVMSetOrdering.restype = None + LLVMSetOrdering.argtypes = [LLVMValueRef, LLVMAtomicOrdering] +except AttributeError: + pass +try: + LLVMGetAtomicRMWBinOp = _libraries['llvm'].LLVMGetAtomicRMWBinOp + LLVMGetAtomicRMWBinOp.restype = LLVMAtomicRMWBinOp + LLVMGetAtomicRMWBinOp.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetAtomicRMWBinOp = _libraries['llvm'].LLVMSetAtomicRMWBinOp + LLVMSetAtomicRMWBinOp.restype = None + LLVMSetAtomicRMWBinOp.argtypes = [LLVMValueRef, LLVMAtomicRMWBinOp] +except AttributeError: + pass +try: + LLVMBuildTrunc = _libraries['llvm'].LLVMBuildTrunc + LLVMBuildTrunc.restype = LLVMValueRef + LLVMBuildTrunc.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildZExt = _libraries['llvm'].LLVMBuildZExt + LLVMBuildZExt.restype = LLVMValueRef + LLVMBuildZExt.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSExt = _libraries['llvm'].LLVMBuildSExt + LLVMBuildSExt.restype = LLVMValueRef + LLVMBuildSExt.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFPToUI = _libraries['llvm'].LLVMBuildFPToUI + LLVMBuildFPToUI.restype = LLVMValueRef + LLVMBuildFPToUI.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFPToSI = _libraries['llvm'].LLVMBuildFPToSI + LLVMBuildFPToSI.restype = LLVMValueRef + LLVMBuildFPToSI.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildUIToFP = _libraries['llvm'].LLVMBuildUIToFP + LLVMBuildUIToFP.restype = LLVMValueRef + LLVMBuildUIToFP.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSIToFP = _libraries['llvm'].LLVMBuildSIToFP + LLVMBuildSIToFP.restype = LLVMValueRef + LLVMBuildSIToFP.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFPTrunc = _libraries['llvm'].LLVMBuildFPTrunc + LLVMBuildFPTrunc.restype = LLVMValueRef + LLVMBuildFPTrunc.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFPExt = _libraries['llvm'].LLVMBuildFPExt + LLVMBuildFPExt.restype = LLVMValueRef + LLVMBuildFPExt.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildPtrToInt = _libraries['llvm'].LLVMBuildPtrToInt + LLVMBuildPtrToInt.restype = LLVMValueRef + LLVMBuildPtrToInt.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildIntToPtr = _libraries['llvm'].LLVMBuildIntToPtr + LLVMBuildIntToPtr.restype = LLVMValueRef + LLVMBuildIntToPtr.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildBitCast = _libraries['llvm'].LLVMBuildBitCast + LLVMBuildBitCast.restype = LLVMValueRef + LLVMBuildBitCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildAddrSpaceCast = _libraries['llvm'].LLVMBuildAddrSpaceCast + LLVMBuildAddrSpaceCast.restype = LLVMValueRef + LLVMBuildAddrSpaceCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildZExtOrBitCast = _libraries['llvm'].LLVMBuildZExtOrBitCast + LLVMBuildZExtOrBitCast.restype = LLVMValueRef + LLVMBuildZExtOrBitCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSExtOrBitCast = _libraries['llvm'].LLVMBuildSExtOrBitCast + LLVMBuildSExtOrBitCast.restype = LLVMValueRef + LLVMBuildSExtOrBitCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildTruncOrBitCast = _libraries['llvm'].LLVMBuildTruncOrBitCast + LLVMBuildTruncOrBitCast.restype = LLVMValueRef + LLVMBuildTruncOrBitCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCast = _libraries['llvm'].LLVMBuildCast + LLVMBuildCast.restype = LLVMValueRef + LLVMBuildCast.argtypes = [LLVMBuilderRef, LLVMOpcode, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildPointerCast = _libraries['llvm'].LLVMBuildPointerCast + LLVMBuildPointerCast.restype = LLVMValueRef + LLVMBuildPointerCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildIntCast2 = _libraries['llvm'].LLVMBuildIntCast2 + LLVMBuildIntCast2.restype = LLVMValueRef + LLVMBuildIntCast2.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, LLVMBool, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFPCast = _libraries['llvm'].LLVMBuildFPCast + LLVMBuildFPCast.restype = LLVMValueRef + LLVMBuildFPCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildIntCast = _libraries['llvm'].LLVMBuildIntCast + LLVMBuildIntCast.restype = LLVMValueRef + LLVMBuildIntCast.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildICmp = _libraries['llvm'].LLVMBuildICmp + LLVMBuildICmp.restype = LLVMValueRef + LLVMBuildICmp.argtypes = [LLVMBuilderRef, LLVMIntPredicate, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFCmp = _libraries['llvm'].LLVMBuildFCmp + LLVMBuildFCmp.restype = LLVMValueRef + LLVMBuildFCmp.argtypes = [LLVMBuilderRef, LLVMRealPredicate, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildPhi = _libraries['llvm'].LLVMBuildPhi + LLVMBuildPhi.restype = LLVMValueRef + LLVMBuildPhi.argtypes = [LLVMBuilderRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCall = _libraries['llvm'].LLVMBuildCall + LLVMBuildCall.restype = LLVMValueRef + LLVMBuildCall.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildCall2 = _libraries['llvm'].LLVMBuildCall2 + LLVMBuildCall2.restype = LLVMValueRef + LLVMBuildCall2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue)), ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildSelect = _libraries['llvm'].LLVMBuildSelect + LLVMBuildSelect.restype = LLVMValueRef + LLVMBuildSelect.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildVAArg = _libraries['llvm'].LLVMBuildVAArg + LLVMBuildVAArg.restype = LLVMValueRef + LLVMBuildVAArg.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMTypeRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildExtractElement = _libraries['llvm'].LLVMBuildExtractElement + LLVMBuildExtractElement.restype = LLVMValueRef + LLVMBuildExtractElement.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildInsertElement = _libraries['llvm'].LLVMBuildInsertElement + LLVMBuildInsertElement.restype = LLVMValueRef + LLVMBuildInsertElement.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildShuffleVector = _libraries['llvm'].LLVMBuildShuffleVector + LLVMBuildShuffleVector.restype = LLVMValueRef + LLVMBuildShuffleVector.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildExtractValue = _libraries['llvm'].LLVMBuildExtractValue + LLVMBuildExtractValue.restype = LLVMValueRef + LLVMBuildExtractValue.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildInsertValue = _libraries['llvm'].LLVMBuildInsertValue + LLVMBuildInsertValue.restype = LLVMValueRef + LLVMBuildInsertValue.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFreeze = _libraries['llvm'].LLVMBuildFreeze + LLVMBuildFreeze.restype = LLVMValueRef + LLVMBuildFreeze.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildIsNull = _libraries['llvm'].LLVMBuildIsNull + LLVMBuildIsNull.restype = LLVMValueRef + LLVMBuildIsNull.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildIsNotNull = _libraries['llvm'].LLVMBuildIsNotNull + LLVMBuildIsNotNull.restype = LLVMValueRef + LLVMBuildIsNotNull.argtypes = [LLVMBuilderRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildPtrDiff = _libraries['llvm'].LLVMBuildPtrDiff + LLVMBuildPtrDiff.restype = LLVMValueRef + LLVMBuildPtrDiff.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildPtrDiff2 = _libraries['llvm'].LLVMBuildPtrDiff2 + LLVMBuildPtrDiff2.restype = LLVMValueRef + LLVMBuildPtrDiff2.argtypes = [LLVMBuilderRef, LLVMTypeRef, LLVMValueRef, LLVMValueRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildFence = _libraries['llvm'].LLVMBuildFence + LLVMBuildFence.restype = LLVMValueRef + LLVMBuildFence.argtypes = [LLVMBuilderRef, LLVMAtomicOrdering, LLVMBool, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMBuildAtomicRMW = _libraries['llvm'].LLVMBuildAtomicRMW + LLVMBuildAtomicRMW.restype = LLVMValueRef + LLVMBuildAtomicRMW.argtypes = [LLVMBuilderRef, LLVMAtomicRMWBinOp, LLVMValueRef, LLVMValueRef, LLVMAtomicOrdering, LLVMBool] +except AttributeError: + pass +try: + LLVMBuildAtomicCmpXchg = _libraries['llvm'].LLVMBuildAtomicCmpXchg + LLVMBuildAtomicCmpXchg.restype = LLVMValueRef + LLVMBuildAtomicCmpXchg.argtypes = [LLVMBuilderRef, LLVMValueRef, LLVMValueRef, LLVMValueRef, LLVMAtomicOrdering, LLVMAtomicOrdering, LLVMBool] +except AttributeError: + pass +try: + LLVMGetNumMaskElements = _libraries['llvm'].LLVMGetNumMaskElements + LLVMGetNumMaskElements.restype = ctypes.c_uint32 + LLVMGetNumMaskElements.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetUndefMaskElem = _libraries['llvm'].LLVMGetUndefMaskElem + LLVMGetUndefMaskElem.restype = ctypes.c_int32 + LLVMGetUndefMaskElem.argtypes = [] +except AttributeError: + pass +try: + LLVMGetMaskValue = _libraries['llvm'].LLVMGetMaskValue + LLVMGetMaskValue.restype = ctypes.c_int32 + LLVMGetMaskValue.argtypes = [LLVMValueRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMIsAtomicSingleThread = _libraries['llvm'].LLVMIsAtomicSingleThread + LLVMIsAtomicSingleThread.restype = LLVMBool + LLVMIsAtomicSingleThread.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetAtomicSingleThread = _libraries['llvm'].LLVMSetAtomicSingleThread + LLVMSetAtomicSingleThread.restype = None + LLVMSetAtomicSingleThread.argtypes = [LLVMValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGetCmpXchgSuccessOrdering = _libraries['llvm'].LLVMGetCmpXchgSuccessOrdering + LLVMGetCmpXchgSuccessOrdering.restype = LLVMAtomicOrdering + LLVMGetCmpXchgSuccessOrdering.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetCmpXchgSuccessOrdering = _libraries['llvm'].LLVMSetCmpXchgSuccessOrdering + LLVMSetCmpXchgSuccessOrdering.restype = None + LLVMSetCmpXchgSuccessOrdering.argtypes = [LLVMValueRef, LLVMAtomicOrdering] +except AttributeError: + pass +try: + LLVMGetCmpXchgFailureOrdering = _libraries['llvm'].LLVMGetCmpXchgFailureOrdering + LLVMGetCmpXchgFailureOrdering.restype = LLVMAtomicOrdering + LLVMGetCmpXchgFailureOrdering.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetCmpXchgFailureOrdering = _libraries['llvm'].LLVMSetCmpXchgFailureOrdering + LLVMSetCmpXchgFailureOrdering.restype = None + LLVMSetCmpXchgFailureOrdering.argtypes = [LLVMValueRef, LLVMAtomicOrdering] +except AttributeError: + pass +try: + LLVMCreateModuleProviderForExistingModule = _libraries['llvm'].LLVMCreateModuleProviderForExistingModule + LLVMCreateModuleProviderForExistingModule.restype = LLVMModuleProviderRef + LLVMCreateModuleProviderForExistingModule.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMDisposeModuleProvider = _libraries['llvm'].LLVMDisposeModuleProvider + LLVMDisposeModuleProvider.restype = None + LLVMDisposeModuleProvider.argtypes = [LLVMModuleProviderRef] +except AttributeError: + pass +try: + LLVMCreateMemoryBufferWithContentsOfFile = _libraries['llvm'].LLVMCreateMemoryBufferWithContentsOfFile + LLVMCreateMemoryBufferWithContentsOfFile.restype = LLVMBool + LLVMCreateMemoryBufferWithContentsOfFile.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMCreateMemoryBufferWithSTDIN = _libraries['llvm'].LLVMCreateMemoryBufferWithSTDIN + LLVMCreateMemoryBufferWithSTDIN.restype = LLVMBool + LLVMCreateMemoryBufferWithSTDIN.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMCreateMemoryBufferWithMemoryRange = _libraries['llvm'].LLVMCreateMemoryBufferWithMemoryRange + LLVMCreateMemoryBufferWithMemoryRange.restype = LLVMMemoryBufferRef + LLVMCreateMemoryBufferWithMemoryRange.argtypes = [ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), LLVMBool] +except AttributeError: + pass +try: + LLVMCreateMemoryBufferWithMemoryRangeCopy = _libraries['llvm'].LLVMCreateMemoryBufferWithMemoryRangeCopy + LLVMCreateMemoryBufferWithMemoryRangeCopy.restype = LLVMMemoryBufferRef + LLVMCreateMemoryBufferWithMemoryRangeCopy.argtypes = [ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetBufferStart = _libraries['llvm'].LLVMGetBufferStart + LLVMGetBufferStart.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetBufferStart.argtypes = [LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMGetBufferSize = _libraries['llvm'].LLVMGetBufferSize + LLVMGetBufferSize.restype = size_t + LLVMGetBufferSize.argtypes = [LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMDisposeMemoryBuffer = _libraries['llvm'].LLVMDisposeMemoryBuffer + LLVMDisposeMemoryBuffer.restype = None + LLVMDisposeMemoryBuffer.argtypes = [LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMGetGlobalPassRegistry = _libraries['llvm'].LLVMGetGlobalPassRegistry + LLVMGetGlobalPassRegistry.restype = LLVMPassRegistryRef + LLVMGetGlobalPassRegistry.argtypes = [] +except AttributeError: + pass +try: + LLVMCreatePassManager = _libraries['llvm'].LLVMCreatePassManager + LLVMCreatePassManager.restype = LLVMPassManagerRef + LLVMCreatePassManager.argtypes = [] +except AttributeError: + pass +try: + LLVMCreateFunctionPassManagerForModule = _libraries['llvm'].LLVMCreateFunctionPassManagerForModule + LLVMCreateFunctionPassManagerForModule.restype = LLVMPassManagerRef + LLVMCreateFunctionPassManagerForModule.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMCreateFunctionPassManager = _libraries['llvm'].LLVMCreateFunctionPassManager + LLVMCreateFunctionPassManager.restype = LLVMPassManagerRef + LLVMCreateFunctionPassManager.argtypes = [LLVMModuleProviderRef] +except AttributeError: + pass +try: + LLVMRunPassManager = _libraries['llvm'].LLVMRunPassManager + LLVMRunPassManager.restype = LLVMBool + LLVMRunPassManager.argtypes = [LLVMPassManagerRef, LLVMModuleRef] +except AttributeError: + pass +try: + LLVMInitializeFunctionPassManager = _libraries['llvm'].LLVMInitializeFunctionPassManager + LLVMInitializeFunctionPassManager.restype = LLVMBool + LLVMInitializeFunctionPassManager.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMRunFunctionPassManager = _libraries['llvm'].LLVMRunFunctionPassManager + LLVMRunFunctionPassManager.restype = LLVMBool + LLVMRunFunctionPassManager.argtypes = [LLVMPassManagerRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMFinalizeFunctionPassManager = _libraries['llvm'].LLVMFinalizeFunctionPassManager + LLVMFinalizeFunctionPassManager.restype = LLVMBool + LLVMFinalizeFunctionPassManager.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMDisposePassManager = _libraries['llvm'].LLVMDisposePassManager + LLVMDisposePassManager.restype = None + LLVMDisposePassManager.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMStartMultithreaded = _libraries['llvm'].LLVMStartMultithreaded + LLVMStartMultithreaded.restype = LLVMBool + LLVMStartMultithreaded.argtypes = [] +except AttributeError: + pass +try: + LLVMStopMultithreaded = _libraries['llvm'].LLVMStopMultithreaded + LLVMStopMultithreaded.restype = None + LLVMStopMultithreaded.argtypes = [] +except AttributeError: + pass +try: + LLVMIsMultithreaded = _libraries['llvm'].LLVMIsMultithreaded + LLVMIsMultithreaded.restype = LLVMBool + LLVMIsMultithreaded.argtypes = [] +except AttributeError: + pass +LLVM_C_DEBUGINFO_H = True # macro + +# values for enumeration 'c__EA_LLVMDIFlags' +c__EA_LLVMDIFlags__enumvalues = { + 0: 'LLVMDIFlagZero', + 1: 'LLVMDIFlagPrivate', + 2: 'LLVMDIFlagProtected', + 3: 'LLVMDIFlagPublic', + 4: 'LLVMDIFlagFwdDecl', + 8: 'LLVMDIFlagAppleBlock', + 16: 'LLVMDIFlagReservedBit4', + 32: 'LLVMDIFlagVirtual', + 64: 'LLVMDIFlagArtificial', + 128: 'LLVMDIFlagExplicit', + 256: 'LLVMDIFlagPrototyped', + 512: 'LLVMDIFlagObjcClassComplete', + 1024: 'LLVMDIFlagObjectPointer', + 2048: 'LLVMDIFlagVector', + 4096: 'LLVMDIFlagStaticMember', + 8192: 'LLVMDIFlagLValueReference', + 16384: 'LLVMDIFlagRValueReference', + 32768: 'LLVMDIFlagReserved', + 65536: 'LLVMDIFlagSingleInheritance', + 131072: 'LLVMDIFlagMultipleInheritance', + 196608: 'LLVMDIFlagVirtualInheritance', + 262144: 'LLVMDIFlagIntroducedVirtual', + 524288: 'LLVMDIFlagBitField', + 1048576: 'LLVMDIFlagNoReturn', + 4194304: 'LLVMDIFlagTypePassByValue', + 8388608: 'LLVMDIFlagTypePassByReference', + 16777216: 'LLVMDIFlagEnumClass', + 16777216: 'LLVMDIFlagFixedEnum', + 33554432: 'LLVMDIFlagThunk', + 67108864: 'LLVMDIFlagNonTrivial', + 134217728: 'LLVMDIFlagBigEndian', + 268435456: 'LLVMDIFlagLittleEndian', + 36: 'LLVMDIFlagIndirectVirtualBase', + 3: 'LLVMDIFlagAccessibility', + 196608: 'LLVMDIFlagPtrToMemberRep', +} +LLVMDIFlagZero = 0 +LLVMDIFlagPrivate = 1 +LLVMDIFlagProtected = 2 +LLVMDIFlagPublic = 3 +LLVMDIFlagFwdDecl = 4 +LLVMDIFlagAppleBlock = 8 +LLVMDIFlagReservedBit4 = 16 +LLVMDIFlagVirtual = 32 +LLVMDIFlagArtificial = 64 +LLVMDIFlagExplicit = 128 +LLVMDIFlagPrototyped = 256 +LLVMDIFlagObjcClassComplete = 512 +LLVMDIFlagObjectPointer = 1024 +LLVMDIFlagVector = 2048 +LLVMDIFlagStaticMember = 4096 +LLVMDIFlagLValueReference = 8192 +LLVMDIFlagRValueReference = 16384 +LLVMDIFlagReserved = 32768 +LLVMDIFlagSingleInheritance = 65536 +LLVMDIFlagMultipleInheritance = 131072 +LLVMDIFlagVirtualInheritance = 196608 +LLVMDIFlagIntroducedVirtual = 262144 +LLVMDIFlagBitField = 524288 +LLVMDIFlagNoReturn = 1048576 +LLVMDIFlagTypePassByValue = 4194304 +LLVMDIFlagTypePassByReference = 8388608 +LLVMDIFlagEnumClass = 16777216 +LLVMDIFlagFixedEnum = 16777216 +LLVMDIFlagThunk = 33554432 +LLVMDIFlagNonTrivial = 67108864 +LLVMDIFlagBigEndian = 134217728 +LLVMDIFlagLittleEndian = 268435456 +LLVMDIFlagIndirectVirtualBase = 36 +LLVMDIFlagAccessibility = 3 +LLVMDIFlagPtrToMemberRep = 196608 +c__EA_LLVMDIFlags = ctypes.c_uint32 # enum +LLVMDIFlags = c__EA_LLVMDIFlags +LLVMDIFlags__enumvalues = c__EA_LLVMDIFlags__enumvalues + +# values for enumeration 'c__EA_LLVMDWARFSourceLanguage' +c__EA_LLVMDWARFSourceLanguage__enumvalues = { + 0: 'LLVMDWARFSourceLanguageC89', + 1: 'LLVMDWARFSourceLanguageC', + 2: 'LLVMDWARFSourceLanguageAda83', + 3: 'LLVMDWARFSourceLanguageC_plus_plus', + 4: 'LLVMDWARFSourceLanguageCobol74', + 5: 'LLVMDWARFSourceLanguageCobol85', + 6: 'LLVMDWARFSourceLanguageFortran77', + 7: 'LLVMDWARFSourceLanguageFortran90', + 8: 'LLVMDWARFSourceLanguagePascal83', + 9: 'LLVMDWARFSourceLanguageModula2', + 10: 'LLVMDWARFSourceLanguageJava', + 11: 'LLVMDWARFSourceLanguageC99', + 12: 'LLVMDWARFSourceLanguageAda95', + 13: 'LLVMDWARFSourceLanguageFortran95', + 14: 'LLVMDWARFSourceLanguagePLI', + 15: 'LLVMDWARFSourceLanguageObjC', + 16: 'LLVMDWARFSourceLanguageObjC_plus_plus', + 17: 'LLVMDWARFSourceLanguageUPC', + 18: 'LLVMDWARFSourceLanguageD', + 19: 'LLVMDWARFSourceLanguagePython', + 20: 'LLVMDWARFSourceLanguageOpenCL', + 21: 'LLVMDWARFSourceLanguageGo', + 22: 'LLVMDWARFSourceLanguageModula3', + 23: 'LLVMDWARFSourceLanguageHaskell', + 24: 'LLVMDWARFSourceLanguageC_plus_plus_03', + 25: 'LLVMDWARFSourceLanguageC_plus_plus_11', + 26: 'LLVMDWARFSourceLanguageOCaml', + 27: 'LLVMDWARFSourceLanguageRust', + 28: 'LLVMDWARFSourceLanguageC11', + 29: 'LLVMDWARFSourceLanguageSwift', + 30: 'LLVMDWARFSourceLanguageJulia', + 31: 'LLVMDWARFSourceLanguageDylan', + 32: 'LLVMDWARFSourceLanguageC_plus_plus_14', + 33: 'LLVMDWARFSourceLanguageFortran03', + 34: 'LLVMDWARFSourceLanguageFortran08', + 35: 'LLVMDWARFSourceLanguageRenderScript', + 36: 'LLVMDWARFSourceLanguageBLISS', + 37: 'LLVMDWARFSourceLanguageMips_Assembler', + 38: 'LLVMDWARFSourceLanguageGOOGLE_RenderScript', + 39: 'LLVMDWARFSourceLanguageBORLAND_Delphi', +} +LLVMDWARFSourceLanguageC89 = 0 +LLVMDWARFSourceLanguageC = 1 +LLVMDWARFSourceLanguageAda83 = 2 +LLVMDWARFSourceLanguageC_plus_plus = 3 +LLVMDWARFSourceLanguageCobol74 = 4 +LLVMDWARFSourceLanguageCobol85 = 5 +LLVMDWARFSourceLanguageFortran77 = 6 +LLVMDWARFSourceLanguageFortran90 = 7 +LLVMDWARFSourceLanguagePascal83 = 8 +LLVMDWARFSourceLanguageModula2 = 9 +LLVMDWARFSourceLanguageJava = 10 +LLVMDWARFSourceLanguageC99 = 11 +LLVMDWARFSourceLanguageAda95 = 12 +LLVMDWARFSourceLanguageFortran95 = 13 +LLVMDWARFSourceLanguagePLI = 14 +LLVMDWARFSourceLanguageObjC = 15 +LLVMDWARFSourceLanguageObjC_plus_plus = 16 +LLVMDWARFSourceLanguageUPC = 17 +LLVMDWARFSourceLanguageD = 18 +LLVMDWARFSourceLanguagePython = 19 +LLVMDWARFSourceLanguageOpenCL = 20 +LLVMDWARFSourceLanguageGo = 21 +LLVMDWARFSourceLanguageModula3 = 22 +LLVMDWARFSourceLanguageHaskell = 23 +LLVMDWARFSourceLanguageC_plus_plus_03 = 24 +LLVMDWARFSourceLanguageC_plus_plus_11 = 25 +LLVMDWARFSourceLanguageOCaml = 26 +LLVMDWARFSourceLanguageRust = 27 +LLVMDWARFSourceLanguageC11 = 28 +LLVMDWARFSourceLanguageSwift = 29 +LLVMDWARFSourceLanguageJulia = 30 +LLVMDWARFSourceLanguageDylan = 31 +LLVMDWARFSourceLanguageC_plus_plus_14 = 32 +LLVMDWARFSourceLanguageFortran03 = 33 +LLVMDWARFSourceLanguageFortran08 = 34 +LLVMDWARFSourceLanguageRenderScript = 35 +LLVMDWARFSourceLanguageBLISS = 36 +LLVMDWARFSourceLanguageMips_Assembler = 37 +LLVMDWARFSourceLanguageGOOGLE_RenderScript = 38 +LLVMDWARFSourceLanguageBORLAND_Delphi = 39 +c__EA_LLVMDWARFSourceLanguage = ctypes.c_uint32 # enum +LLVMDWARFSourceLanguage = c__EA_LLVMDWARFSourceLanguage +LLVMDWARFSourceLanguage__enumvalues = c__EA_LLVMDWARFSourceLanguage__enumvalues + +# values for enumeration 'c__EA_LLVMDWARFEmissionKind' +c__EA_LLVMDWARFEmissionKind__enumvalues = { + 0: 'LLVMDWARFEmissionNone', + 1: 'LLVMDWARFEmissionFull', + 2: 'LLVMDWARFEmissionLineTablesOnly', +} +LLVMDWARFEmissionNone = 0 +LLVMDWARFEmissionFull = 1 +LLVMDWARFEmissionLineTablesOnly = 2 +c__EA_LLVMDWARFEmissionKind = ctypes.c_uint32 # enum +LLVMDWARFEmissionKind = c__EA_LLVMDWARFEmissionKind +LLVMDWARFEmissionKind__enumvalues = c__EA_LLVMDWARFEmissionKind__enumvalues + +# values for enumeration 'c__Ea_LLVMMDStringMetadataKind' +c__Ea_LLVMMDStringMetadataKind__enumvalues = { + 0: 'LLVMMDStringMetadataKind', + 1: 'LLVMConstantAsMetadataMetadataKind', + 2: 'LLVMLocalAsMetadataMetadataKind', + 3: 'LLVMDistinctMDOperandPlaceholderMetadataKind', + 4: 'LLVMMDTupleMetadataKind', + 5: 'LLVMDILocationMetadataKind', + 6: 'LLVMDIExpressionMetadataKind', + 7: 'LLVMDIGlobalVariableExpressionMetadataKind', + 8: 'LLVMGenericDINodeMetadataKind', + 9: 'LLVMDISubrangeMetadataKind', + 10: 'LLVMDIEnumeratorMetadataKind', + 11: 'LLVMDIBasicTypeMetadataKind', + 12: 'LLVMDIDerivedTypeMetadataKind', + 13: 'LLVMDICompositeTypeMetadataKind', + 14: 'LLVMDISubroutineTypeMetadataKind', + 15: 'LLVMDIFileMetadataKind', + 16: 'LLVMDICompileUnitMetadataKind', + 17: 'LLVMDISubprogramMetadataKind', + 18: 'LLVMDILexicalBlockMetadataKind', + 19: 'LLVMDILexicalBlockFileMetadataKind', + 20: 'LLVMDINamespaceMetadataKind', + 21: 'LLVMDIModuleMetadataKind', + 22: 'LLVMDITemplateTypeParameterMetadataKind', + 23: 'LLVMDITemplateValueParameterMetadataKind', + 24: 'LLVMDIGlobalVariableMetadataKind', + 25: 'LLVMDILocalVariableMetadataKind', + 26: 'LLVMDILabelMetadataKind', + 27: 'LLVMDIObjCPropertyMetadataKind', + 28: 'LLVMDIImportedEntityMetadataKind', + 29: 'LLVMDIMacroMetadataKind', + 30: 'LLVMDIMacroFileMetadataKind', + 31: 'LLVMDICommonBlockMetadataKind', + 32: 'LLVMDIStringTypeMetadataKind', + 33: 'LLVMDIGenericSubrangeMetadataKind', + 34: 'LLVMDIArgListMetadataKind', +} +LLVMMDStringMetadataKind = 0 +LLVMConstantAsMetadataMetadataKind = 1 +LLVMLocalAsMetadataMetadataKind = 2 +LLVMDistinctMDOperandPlaceholderMetadataKind = 3 +LLVMMDTupleMetadataKind = 4 +LLVMDILocationMetadataKind = 5 +LLVMDIExpressionMetadataKind = 6 +LLVMDIGlobalVariableExpressionMetadataKind = 7 +LLVMGenericDINodeMetadataKind = 8 +LLVMDISubrangeMetadataKind = 9 +LLVMDIEnumeratorMetadataKind = 10 +LLVMDIBasicTypeMetadataKind = 11 +LLVMDIDerivedTypeMetadataKind = 12 +LLVMDICompositeTypeMetadataKind = 13 +LLVMDISubroutineTypeMetadataKind = 14 +LLVMDIFileMetadataKind = 15 +LLVMDICompileUnitMetadataKind = 16 +LLVMDISubprogramMetadataKind = 17 +LLVMDILexicalBlockMetadataKind = 18 +LLVMDILexicalBlockFileMetadataKind = 19 +LLVMDINamespaceMetadataKind = 20 +LLVMDIModuleMetadataKind = 21 +LLVMDITemplateTypeParameterMetadataKind = 22 +LLVMDITemplateValueParameterMetadataKind = 23 +LLVMDIGlobalVariableMetadataKind = 24 +LLVMDILocalVariableMetadataKind = 25 +LLVMDILabelMetadataKind = 26 +LLVMDIObjCPropertyMetadataKind = 27 +LLVMDIImportedEntityMetadataKind = 28 +LLVMDIMacroMetadataKind = 29 +LLVMDIMacroFileMetadataKind = 30 +LLVMDICommonBlockMetadataKind = 31 +LLVMDIStringTypeMetadataKind = 32 +LLVMDIGenericSubrangeMetadataKind = 33 +LLVMDIArgListMetadataKind = 34 +c__Ea_LLVMMDStringMetadataKind = ctypes.c_uint32 # enum +LLVMMetadataKind = ctypes.c_uint32 +LLVMDWARFTypeEncoding = ctypes.c_uint32 + +# values for enumeration 'c__EA_LLVMDWARFMacinfoRecordType' +c__EA_LLVMDWARFMacinfoRecordType__enumvalues = { + 1: 'LLVMDWARFMacinfoRecordTypeDefine', + 2: 'LLVMDWARFMacinfoRecordTypeMacro', + 3: 'LLVMDWARFMacinfoRecordTypeStartFile', + 4: 'LLVMDWARFMacinfoRecordTypeEndFile', + 255: 'LLVMDWARFMacinfoRecordTypeVendorExt', +} +LLVMDWARFMacinfoRecordTypeDefine = 1 +LLVMDWARFMacinfoRecordTypeMacro = 2 +LLVMDWARFMacinfoRecordTypeStartFile = 3 +LLVMDWARFMacinfoRecordTypeEndFile = 4 +LLVMDWARFMacinfoRecordTypeVendorExt = 255 +c__EA_LLVMDWARFMacinfoRecordType = ctypes.c_uint32 # enum +LLVMDWARFMacinfoRecordType = c__EA_LLVMDWARFMacinfoRecordType +LLVMDWARFMacinfoRecordType__enumvalues = c__EA_LLVMDWARFMacinfoRecordType__enumvalues +try: + LLVMDebugMetadataVersion = _libraries['llvm'].LLVMDebugMetadataVersion + LLVMDebugMetadataVersion.restype = ctypes.c_uint32 + LLVMDebugMetadataVersion.argtypes = [] +except AttributeError: + pass +try: + LLVMGetModuleDebugMetadataVersion = _libraries['llvm'].LLVMGetModuleDebugMetadataVersion + LLVMGetModuleDebugMetadataVersion.restype = ctypes.c_uint32 + LLVMGetModuleDebugMetadataVersion.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMStripModuleDebugInfo = _libraries['llvm'].LLVMStripModuleDebugInfo + LLVMStripModuleDebugInfo.restype = LLVMBool + LLVMStripModuleDebugInfo.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMCreateDIBuilderDisallowUnresolved = _libraries['llvm'].LLVMCreateDIBuilderDisallowUnresolved + LLVMCreateDIBuilderDisallowUnresolved.restype = LLVMDIBuilderRef + LLVMCreateDIBuilderDisallowUnresolved.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMCreateDIBuilder = _libraries['llvm'].LLVMCreateDIBuilder + LLVMCreateDIBuilder.restype = LLVMDIBuilderRef + LLVMCreateDIBuilder.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMDisposeDIBuilder = _libraries['llvm'].LLVMDisposeDIBuilder + LLVMDisposeDIBuilder.restype = None + LLVMDisposeDIBuilder.argtypes = [LLVMDIBuilderRef] +except AttributeError: + pass +try: + LLVMDIBuilderFinalize = _libraries['llvm'].LLVMDIBuilderFinalize + LLVMDIBuilderFinalize.restype = None + LLVMDIBuilderFinalize.argtypes = [LLVMDIBuilderRef] +except AttributeError: + pass +try: + LLVMDIBuilderFinalizeSubprogram = _libraries['llvm'].LLVMDIBuilderFinalizeSubprogram + LLVMDIBuilderFinalizeSubprogram.restype = None + LLVMDIBuilderFinalizeSubprogram.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateCompileUnit = _libraries['llvm'].LLVMDIBuilderCreateCompileUnit + LLVMDIBuilderCreateCompileUnit.restype = LLVMMetadataRef + LLVMDIBuilderCreateCompileUnit.argtypes = [LLVMDIBuilderRef, LLVMDWARFSourceLanguage, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMBool, ctypes.POINTER(ctypes.c_char), size_t, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t, LLVMDWARFEmissionKind, ctypes.c_uint32, LLVMBool, LLVMBool, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateFile = _libraries['llvm'].LLVMDIBuilderCreateFile + LLVMDIBuilderCreateFile.restype = LLVMMetadataRef + LLVMDIBuilderCreateFile.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateModule = _libraries['llvm'].LLVMDIBuilderCreateModule + LLVMDIBuilderCreateModule.restype = LLVMMetadataRef + LLVMDIBuilderCreateModule.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateNameSpace = _libraries['llvm'].LLVMDIBuilderCreateNameSpace + LLVMDIBuilderCreateNameSpace.restype = LLVMMetadataRef + LLVMDIBuilderCreateNameSpace.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMBool] +except AttributeError: + pass +try: + LLVMDIBuilderCreateFunction = _libraries['llvm'].LLVMDIBuilderCreateFunction + LLVMDIBuilderCreateFunction.restype = LLVMMetadataRef + LLVMDIBuilderCreateFunction.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMBool, LLVMBool, ctypes.c_uint32, LLVMDIFlags, LLVMBool] +except AttributeError: + pass +try: + LLVMDIBuilderCreateLexicalBlock = _libraries['llvm'].LLVMDIBuilderCreateLexicalBlock + LLVMDIBuilderCreateLexicalBlock.restype = LLVMMetadataRef + LLVMDIBuilderCreateLexicalBlock.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateLexicalBlockFile = _libraries['llvm'].LLVMDIBuilderCreateLexicalBlockFile + LLVMDIBuilderCreateLexicalBlockFile.restype = LLVMMetadataRef + LLVMDIBuilderCreateLexicalBlockFile.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateImportedModuleFromNamespace = _libraries['llvm'].LLVMDIBuilderCreateImportedModuleFromNamespace + LLVMDIBuilderCreateImportedModuleFromNamespace.restype = LLVMMetadataRef + LLVMDIBuilderCreateImportedModuleFromNamespace.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateImportedModuleFromAlias = _libraries['llvm'].LLVMDIBuilderCreateImportedModuleFromAlias + LLVMDIBuilderCreateImportedModuleFromAlias.restype = LLVMMetadataRef + LLVMDIBuilderCreateImportedModuleFromAlias.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateImportedModuleFromModule = _libraries['llvm'].LLVMDIBuilderCreateImportedModuleFromModule + LLVMDIBuilderCreateImportedModuleFromModule.restype = LLVMMetadataRef + LLVMDIBuilderCreateImportedModuleFromModule.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateImportedDeclaration = _libraries['llvm'].LLVMDIBuilderCreateImportedDeclaration + LLVMDIBuilderCreateImportedDeclaration.restype = LLVMMetadataRef + LLVMDIBuilderCreateImportedDeclaration.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateDebugLocation = _libraries['llvm'].LLVMDIBuilderCreateDebugLocation + LLVMDIBuilderCreateDebugLocation.restype = LLVMMetadataRef + LLVMDIBuilderCreateDebugLocation.argtypes = [LLVMContextRef, ctypes.c_uint32, ctypes.c_uint32, LLVMMetadataRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDILocationGetLine = _libraries['llvm'].LLVMDILocationGetLine + LLVMDILocationGetLine.restype = ctypes.c_uint32 + LLVMDILocationGetLine.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDILocationGetColumn = _libraries['llvm'].LLVMDILocationGetColumn + LLVMDILocationGetColumn.restype = ctypes.c_uint32 + LLVMDILocationGetColumn.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDILocationGetScope = _libraries['llvm'].LLVMDILocationGetScope + LLVMDILocationGetScope.restype = LLVMMetadataRef + LLVMDILocationGetScope.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDILocationGetInlinedAt = _libraries['llvm'].LLVMDILocationGetInlinedAt + LLVMDILocationGetInlinedAt.restype = LLVMMetadataRef + LLVMDILocationGetInlinedAt.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIScopeGetFile = _libraries['llvm'].LLVMDIScopeGetFile + LLVMDIScopeGetFile.restype = LLVMMetadataRef + LLVMDIScopeGetFile.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIFileGetDirectory = _libraries['llvm'].LLVMDIFileGetDirectory + LLVMDIFileGetDirectory.restype = ctypes.POINTER(ctypes.c_char) + LLVMDIFileGetDirectory.argtypes = [LLVMMetadataRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMDIFileGetFilename = _libraries['llvm'].LLVMDIFileGetFilename + LLVMDIFileGetFilename.restype = ctypes.POINTER(ctypes.c_char) + LLVMDIFileGetFilename.argtypes = [LLVMMetadataRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMDIFileGetSource = _libraries['llvm'].LLVMDIFileGetSource + LLVMDIFileGetSource.restype = ctypes.POINTER(ctypes.c_char) + LLVMDIFileGetSource.argtypes = [LLVMMetadataRef, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + LLVMDIBuilderGetOrCreateTypeArray = _libraries['llvm'].LLVMDIBuilderGetOrCreateTypeArray + LLVMDIBuilderGetOrCreateTypeArray.restype = LLVMMetadataRef + LLVMDIBuilderGetOrCreateTypeArray.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateSubroutineType = _libraries['llvm'].LLVMDIBuilderCreateSubroutineType + LLVMDIBuilderCreateSubroutineType.restype = LLVMMetadataRef + LLVMDIBuilderCreateSubroutineType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32, LLVMDIFlags] +except AttributeError: + pass +try: + LLVMDIBuilderCreateMacro = _libraries['llvm'].LLVMDIBuilderCreateMacro + LLVMDIBuilderCreateMacro.restype = LLVMMetadataRef + LLVMDIBuilderCreateMacro.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.c_uint32, LLVMDWARFMacinfoRecordType, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateTempMacroFile = _libraries['llvm'].LLVMDIBuilderCreateTempMacroFile + LLVMDIBuilderCreateTempMacroFile.restype = LLVMMetadataRef + LLVMDIBuilderCreateTempMacroFile.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +int64_t = ctypes.c_int64 +try: + LLVMDIBuilderCreateEnumerator = _libraries['llvm'].LLVMDIBuilderCreateEnumerator + LLVMDIBuilderCreateEnumerator.restype = LLVMMetadataRef + LLVMDIBuilderCreateEnumerator.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t, int64_t, LLVMBool] +except AttributeError: + pass +uint32_t = ctypes.c_uint32 +try: + LLVMDIBuilderCreateEnumerationType = _libraries['llvm'].LLVMDIBuilderCreateEnumerationType + LLVMDIBuilderCreateEnumerationType.restype = LLVMMetadataRef + LLVMDIBuilderCreateEnumerationType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateUnionType = _libraries['llvm'].LLVMDIBuilderCreateUnionType + LLVMDIBuilderCreateUnionType.restype = LLVMMetadataRef + LLVMDIBuilderCreateUnionType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, LLVMDIFlags, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateArrayType = _libraries['llvm'].LLVMDIBuilderCreateArrayType + LLVMDIBuilderCreateArrayType.restype = LLVMMetadataRef + LLVMDIBuilderCreateArrayType.argtypes = [LLVMDIBuilderRef, uint64_t, uint32_t, LLVMMetadataRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateVectorType = _libraries['llvm'].LLVMDIBuilderCreateVectorType + LLVMDIBuilderCreateVectorType.restype = LLVMMetadataRef + LLVMDIBuilderCreateVectorType.argtypes = [LLVMDIBuilderRef, uint64_t, uint32_t, LLVMMetadataRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMDIBuilderCreateUnspecifiedType = _libraries['llvm'].LLVMDIBuilderCreateUnspecifiedType + LLVMDIBuilderCreateUnspecifiedType.restype = LLVMMetadataRef + LLVMDIBuilderCreateUnspecifiedType.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateBasicType = _libraries['llvm'].LLVMDIBuilderCreateBasicType + LLVMDIBuilderCreateBasicType.restype = LLVMMetadataRef + LLVMDIBuilderCreateBasicType.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t, uint64_t, LLVMDWARFTypeEncoding, LLVMDIFlags] +except AttributeError: + pass +try: + LLVMDIBuilderCreatePointerType = _libraries['llvm'].LLVMDIBuilderCreatePointerType + LLVMDIBuilderCreatePointerType.restype = LLVMMetadataRef + LLVMDIBuilderCreatePointerType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, uint64_t, uint32_t, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateStructType = _libraries['llvm'].LLVMDIBuilderCreateStructType + LLVMDIBuilderCreateStructType.restype = LLVMMetadataRef + LLVMDIBuilderCreateStructType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, LLVMDIFlags, LLVMMetadataRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32, ctypes.c_uint32, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateMemberType = _libraries['llvm'].LLVMDIBuilderCreateMemberType + LLVMDIBuilderCreateMemberType.restype = LLVMMetadataRef + LLVMDIBuilderCreateMemberType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, uint64_t, LLVMDIFlags, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateStaticMemberType = _libraries['llvm'].LLVMDIBuilderCreateStaticMemberType + LLVMDIBuilderCreateStaticMemberType.restype = LLVMMetadataRef + LLVMDIBuilderCreateStaticMemberType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMDIFlags, LLVMValueRef, uint32_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateMemberPointerType = _libraries['llvm'].LLVMDIBuilderCreateMemberPointerType + LLVMDIBuilderCreateMemberPointerType.restype = LLVMMetadataRef + LLVMDIBuilderCreateMemberPointerType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, uint64_t, uint32_t, LLVMDIFlags] +except AttributeError: + pass +try: + LLVMDIBuilderCreateObjCIVar = _libraries['llvm'].LLVMDIBuilderCreateObjCIVar + LLVMDIBuilderCreateObjCIVar.restype = LLVMMetadataRef + LLVMDIBuilderCreateObjCIVar.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, uint64_t, LLVMDIFlags, LLVMMetadataRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateObjCProperty = _libraries['llvm'].LLVMDIBuilderCreateObjCProperty + LLVMDIBuilderCreateObjCProperty.restype = LLVMMetadataRef + LLVMDIBuilderCreateObjCProperty.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateObjectPointerType = _libraries['llvm'].LLVMDIBuilderCreateObjectPointerType + LLVMDIBuilderCreateObjectPointerType.restype = LLVMMetadataRef + LLVMDIBuilderCreateObjectPointerType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateQualifiedType = _libraries['llvm'].LLVMDIBuilderCreateQualifiedType + LLVMDIBuilderCreateQualifiedType.restype = LLVMMetadataRef + LLVMDIBuilderCreateQualifiedType.argtypes = [LLVMDIBuilderRef, ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateReferenceType = _libraries['llvm'].LLVMDIBuilderCreateReferenceType + LLVMDIBuilderCreateReferenceType.restype = LLVMMetadataRef + LLVMDIBuilderCreateReferenceType.argtypes = [LLVMDIBuilderRef, ctypes.c_uint32, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateNullPtrType = _libraries['llvm'].LLVMDIBuilderCreateNullPtrType + LLVMDIBuilderCreateNullPtrType.restype = LLVMMetadataRef + LLVMDIBuilderCreateNullPtrType.argtypes = [LLVMDIBuilderRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateTypedef = _libraries['llvm'].LLVMDIBuilderCreateTypedef + LLVMDIBuilderCreateTypedef.restype = LLVMMetadataRef + LLVMDIBuilderCreateTypedef.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, uint32_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateInheritance = _libraries['llvm'].LLVMDIBuilderCreateInheritance + LLVMDIBuilderCreateInheritance.restype = LLVMMetadataRef + LLVMDIBuilderCreateInheritance.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, LLVMMetadataRef, uint64_t, uint32_t, LLVMDIFlags] +except AttributeError: + pass +try: + LLVMDIBuilderCreateForwardDecl = _libraries['llvm'].LLVMDIBuilderCreateForwardDecl + LLVMDIBuilderCreateForwardDecl.restype = LLVMMetadataRef + LLVMDIBuilderCreateForwardDecl.argtypes = [LLVMDIBuilderRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.c_uint32, uint64_t, uint32_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateReplaceableCompositeType = _libraries['llvm'].LLVMDIBuilderCreateReplaceableCompositeType + LLVMDIBuilderCreateReplaceableCompositeType.restype = LLVMMetadataRef + LLVMDIBuilderCreateReplaceableCompositeType.argtypes = [LLVMDIBuilderRef, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, LLVMMetadataRef, ctypes.c_uint32, ctypes.c_uint32, uint64_t, uint32_t, LLVMDIFlags, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateBitFieldMemberType = _libraries['llvm'].LLVMDIBuilderCreateBitFieldMemberType + LLVMDIBuilderCreateBitFieldMemberType.restype = LLVMMetadataRef + LLVMDIBuilderCreateBitFieldMemberType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint64_t, uint64_t, LLVMDIFlags, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateClassType = _libraries['llvm'].LLVMDIBuilderCreateClassType + LLVMDIBuilderCreateClassType.restype = LLVMMetadataRef + LLVMDIBuilderCreateClassType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, uint64_t, uint32_t, uint64_t, LLVMDIFlags, LLVMMetadataRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), ctypes.c_uint32, LLVMMetadataRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateArtificialType = _libraries['llvm'].LLVMDIBuilderCreateArtificialType + LLVMDIBuilderCreateArtificialType.restype = LLVMMetadataRef + LLVMDIBuilderCreateArtificialType.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDITypeGetName = _libraries['llvm'].LLVMDITypeGetName + LLVMDITypeGetName.restype = ctypes.POINTER(ctypes.c_char) + LLVMDITypeGetName.argtypes = [LLVMMetadataRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMDITypeGetSizeInBits = _libraries['llvm'].LLVMDITypeGetSizeInBits + LLVMDITypeGetSizeInBits.restype = uint64_t + LLVMDITypeGetSizeInBits.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDITypeGetOffsetInBits = _libraries['llvm'].LLVMDITypeGetOffsetInBits + LLVMDITypeGetOffsetInBits.restype = uint64_t + LLVMDITypeGetOffsetInBits.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDITypeGetAlignInBits = _libraries['llvm'].LLVMDITypeGetAlignInBits + LLVMDITypeGetAlignInBits.restype = uint32_t + LLVMDITypeGetAlignInBits.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDITypeGetLine = _libraries['llvm'].LLVMDITypeGetLine + LLVMDITypeGetLine.restype = ctypes.c_uint32 + LLVMDITypeGetLine.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDITypeGetFlags = _libraries['llvm'].LLVMDITypeGetFlags + LLVMDITypeGetFlags.restype = LLVMDIFlags + LLVMDITypeGetFlags.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderGetOrCreateSubrange = _libraries['llvm'].LLVMDIBuilderGetOrCreateSubrange + LLVMDIBuilderGetOrCreateSubrange.restype = LLVMMetadataRef + LLVMDIBuilderGetOrCreateSubrange.argtypes = [LLVMDIBuilderRef, int64_t, int64_t] +except AttributeError: + pass +try: + LLVMDIBuilderGetOrCreateArray = _libraries['llvm'].LLVMDIBuilderGetOrCreateArray + LLVMDIBuilderGetOrCreateArray.restype = LLVMMetadataRef + LLVMDIBuilderGetOrCreateArray.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateExpression = _libraries['llvm'].LLVMDIBuilderCreateExpression + LLVMDIBuilderCreateExpression.restype = LLVMMetadataRef + LLVMDIBuilderCreateExpression.argtypes = [LLVMDIBuilderRef, ctypes.POINTER(ctypes.c_uint64), size_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateConstantValueExpression = _libraries['llvm'].LLVMDIBuilderCreateConstantValueExpression + LLVMDIBuilderCreateConstantValueExpression.restype = LLVMMetadataRef + LLVMDIBuilderCreateConstantValueExpression.argtypes = [LLVMDIBuilderRef, uint64_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateGlobalVariableExpression = _libraries['llvm'].LLVMDIBuilderCreateGlobalVariableExpression + LLVMDIBuilderCreateGlobalVariableExpression.restype = LLVMMetadataRef + LLVMDIBuilderCreateGlobalVariableExpression.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMBool, LLVMMetadataRef, LLVMMetadataRef, uint32_t] +except AttributeError: + pass +try: + LLVMDIGlobalVariableExpressionGetVariable = _libraries['llvm'].LLVMDIGlobalVariableExpressionGetVariable + LLVMDIGlobalVariableExpressionGetVariable.restype = LLVMMetadataRef + LLVMDIGlobalVariableExpressionGetVariable.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIGlobalVariableExpressionGetExpression = _libraries['llvm'].LLVMDIGlobalVariableExpressionGetExpression + LLVMDIGlobalVariableExpressionGetExpression.restype = LLVMMetadataRef + LLVMDIGlobalVariableExpressionGetExpression.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIVariableGetFile = _libraries['llvm'].LLVMDIVariableGetFile + LLVMDIVariableGetFile.restype = LLVMMetadataRef + LLVMDIVariableGetFile.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIVariableGetScope = _libraries['llvm'].LLVMDIVariableGetScope + LLVMDIVariableGetScope.restype = LLVMMetadataRef + LLVMDIVariableGetScope.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIVariableGetLine = _libraries['llvm'].LLVMDIVariableGetLine + LLVMDIVariableGetLine.restype = ctypes.c_uint32 + LLVMDIVariableGetLine.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMTemporaryMDNode = _libraries['llvm'].LLVMTemporaryMDNode + LLVMTemporaryMDNode.restype = LLVMMetadataRef + LLVMTemporaryMDNode.argtypes = [LLVMContextRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMetadata)), size_t] +except AttributeError: + pass +try: + LLVMDisposeTemporaryMDNode = _libraries['llvm'].LLVMDisposeTemporaryMDNode + LLVMDisposeTemporaryMDNode.restype = None + LLVMDisposeTemporaryMDNode.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMMetadataReplaceAllUsesWith = _libraries['llvm'].LLVMMetadataReplaceAllUsesWith + LLVMMetadataReplaceAllUsesWith.restype = None + LLVMMetadataReplaceAllUsesWith.argtypes = [LLVMMetadataRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateTempGlobalVariableFwdDecl = _libraries['llvm'].LLVMDIBuilderCreateTempGlobalVariableFwdDecl + LLVMDIBuilderCreateTempGlobalVariableFwdDecl.restype = LLVMMetadataRef + LLVMDIBuilderCreateTempGlobalVariableFwdDecl.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMBool, LLVMMetadataRef, uint32_t] +except AttributeError: + pass +try: + LLVMDIBuilderInsertDeclareBefore = _libraries['llvm'].LLVMDIBuilderInsertDeclareBefore + LLVMDIBuilderInsertDeclareBefore.restype = LLVMValueRef + LLVMDIBuilderInsertDeclareBefore.argtypes = [LLVMDIBuilderRef, LLVMValueRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMDIBuilderInsertDeclareAtEnd = _libraries['llvm'].LLVMDIBuilderInsertDeclareAtEnd + LLVMDIBuilderInsertDeclareAtEnd.restype = LLVMValueRef + LLVMDIBuilderInsertDeclareAtEnd.argtypes = [LLVMDIBuilderRef, LLVMValueRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMDIBuilderInsertDbgValueBefore = _libraries['llvm'].LLVMDIBuilderInsertDbgValueBefore + LLVMDIBuilderInsertDbgValueBefore.restype = LLVMValueRef + LLVMDIBuilderInsertDbgValueBefore.argtypes = [LLVMDIBuilderRef, LLVMValueRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMDIBuilderInsertDbgValueAtEnd = _libraries['llvm'].LLVMDIBuilderInsertDbgValueAtEnd + LLVMDIBuilderInsertDbgValueAtEnd.restype = LLVMValueRef + LLVMDIBuilderInsertDbgValueAtEnd.argtypes = [LLVMDIBuilderRef, LLVMValueRef, LLVMMetadataRef, LLVMMetadataRef, LLVMMetadataRef, LLVMBasicBlockRef] +except AttributeError: + pass +try: + LLVMDIBuilderCreateAutoVariable = _libraries['llvm'].LLVMDIBuilderCreateAutoVariable + LLVMDIBuilderCreateAutoVariable.restype = LLVMMetadataRef + LLVMDIBuilderCreateAutoVariable.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMBool, LLVMDIFlags, uint32_t] +except AttributeError: + pass +try: + LLVMDIBuilderCreateParameterVariable = _libraries['llvm'].LLVMDIBuilderCreateParameterVariable + LLVMDIBuilderCreateParameterVariable.restype = LLVMMetadataRef + LLVMDIBuilderCreateParameterVariable.argtypes = [LLVMDIBuilderRef, LLVMMetadataRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.c_uint32, LLVMMetadataRef, ctypes.c_uint32, LLVMMetadataRef, LLVMBool, LLVMDIFlags] +except AttributeError: + pass +try: + LLVMGetSubprogram = _libraries['llvm'].LLVMGetSubprogram + LLVMGetSubprogram.restype = LLVMMetadataRef + LLVMGetSubprogram.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMSetSubprogram = _libraries['llvm'].LLVMSetSubprogram + LLVMSetSubprogram.restype = None + LLVMSetSubprogram.argtypes = [LLVMValueRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMDISubprogramGetLine = _libraries['llvm'].LLVMDISubprogramGetLine + LLVMDISubprogramGetLine.restype = ctypes.c_uint32 + LLVMDISubprogramGetLine.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMInstructionGetDebugLoc = _libraries['llvm'].LLVMInstructionGetDebugLoc + LLVMInstructionGetDebugLoc.restype = LLVMMetadataRef + LLVMInstructionGetDebugLoc.argtypes = [LLVMValueRef] +except AttributeError: + pass +try: + LLVMInstructionSetDebugLoc = _libraries['llvm'].LLVMInstructionSetDebugLoc + LLVMInstructionSetDebugLoc.restype = None + LLVMInstructionSetDebugLoc.argtypes = [LLVMValueRef, LLVMMetadataRef] +except AttributeError: + pass +try: + LLVMGetMetadataKind = _libraries['llvm'].LLVMGetMetadataKind + LLVMGetMetadataKind.restype = LLVMMetadataKind + LLVMGetMetadataKind.argtypes = [LLVMMetadataRef] +except AttributeError: + pass +LLVM_C_DISASSEMBLER_H = True # macro +LLVM_C_DISASSEMBLERTYPES_H = True # macro +LLVMDisassembler_VariantKind_None = 0 # macro +LLVMDisassembler_VariantKind_ARM_HI16 = 1 # macro +LLVMDisassembler_VariantKind_ARM_LO16 = 2 # macro +LLVMDisassembler_VariantKind_ARM64_PAGE = 1 # macro +LLVMDisassembler_VariantKind_ARM64_PAGEOFF = 2 # macro +LLVMDisassembler_VariantKind_ARM64_GOTPAGE = 3 # macro +LLVMDisassembler_VariantKind_ARM64_GOTPAGEOFF = 4 # macro +LLVMDisassembler_VariantKind_ARM64_TLVP = 5 # macro +LLVMDisassembler_VariantKind_ARM64_TLVOFF = 6 # macro +LLVMDisassembler_ReferenceType_InOut_None = 0 # macro +LLVMDisassembler_ReferenceType_In_Branch = 1 # macro +LLVMDisassembler_ReferenceType_In_PCrel_Load = 2 # macro +LLVMDisassembler_ReferenceType_In_ARM64_ADRP = 0x100000001 # macro +LLVMDisassembler_ReferenceType_In_ARM64_ADDXri = 0x100000002 # macro +LLVMDisassembler_ReferenceType_In_ARM64_LDRXui = 0x100000003 # macro +LLVMDisassembler_ReferenceType_In_ARM64_LDRXl = 0x100000004 # macro +LLVMDisassembler_ReferenceType_In_ARM64_ADR = 0x100000005 # macro +LLVMDisassembler_ReferenceType_Out_SymbolStub = 1 # macro +LLVMDisassembler_ReferenceType_Out_LitPool_SymAddr = 2 # macro +LLVMDisassembler_ReferenceType_Out_LitPool_CstrAddr = 3 # macro +LLVMDisassembler_ReferenceType_Out_Objc_CFString_Ref = 4 # macro +LLVMDisassembler_ReferenceType_Out_Objc_Message = 5 # macro +LLVMDisassembler_ReferenceType_Out_Objc_Message_Ref = 6 # macro +LLVMDisassembler_ReferenceType_Out_Objc_Selector_Ref = 7 # macro +LLVMDisassembler_ReferenceType_Out_Objc_Class_Ref = 8 # macro +LLVMDisassembler_ReferenceType_DeMangled_Name = 9 # macro +LLVMDisassembler_Option_UseMarkup = 1 # macro +LLVMDisassembler_Option_PrintImmHex = 2 # macro +LLVMDisassembler_Option_AsmPrinterVariant = 4 # macro +LLVMDisassembler_Option_SetInstrComments = 8 # macro +LLVMDisassembler_Option_PrintLatency = 16 # macro +LLVMDisasmContextRef = ctypes.POINTER(None) +LLVMOpInfoCallback = ctypes.CFUNCTYPE(ctypes.c_int32, ctypes.POINTER(None), ctypes.c_uint64, ctypes.c_uint64, ctypes.c_uint64, ctypes.c_int32, ctypes.POINTER(None)) +class struct_LLVMOpInfoSymbol1(Structure): + pass + +struct_LLVMOpInfoSymbol1._pack_ = 1 # source:False +struct_LLVMOpInfoSymbol1._fields_ = [ + ('Present', ctypes.c_uint64), + ('Name', ctypes.POINTER(ctypes.c_char)), + ('Value', ctypes.c_uint64), +] + +class struct_LLVMOpInfo1(Structure): + pass + +struct_LLVMOpInfo1._pack_ = 1 # source:False +struct_LLVMOpInfo1._fields_ = [ + ('AddSymbol', struct_LLVMOpInfoSymbol1), + ('SubtractSymbol', struct_LLVMOpInfoSymbol1), + ('Value', ctypes.c_uint64), + ('VariantKind', ctypes.c_uint64), +] + +LLVMSymbolLookupCallback = ctypes.CFUNCTYPE(ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(ctypes.c_uint64), ctypes.c_uint64, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))) +try: + LLVMCreateDisasm = _libraries['llvm'].LLVMCreateDisasm + LLVMCreateDisasm.restype = LLVMDisasmContextRef + LLVMCreateDisasm.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None), ctypes.c_int32, LLVMOpInfoCallback, LLVMSymbolLookupCallback] +except AttributeError: + pass +try: + LLVMCreateDisasmCPU = _libraries['llvm'].LLVMCreateDisasmCPU + LLVMCreateDisasmCPU.restype = LLVMDisasmContextRef + LLVMCreateDisasmCPU.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None), ctypes.c_int32, LLVMOpInfoCallback, LLVMSymbolLookupCallback] +except AttributeError: + pass +try: + LLVMCreateDisasmCPUFeatures = _libraries['llvm'].LLVMCreateDisasmCPUFeatures + LLVMCreateDisasmCPUFeatures.restype = LLVMDisasmContextRef + LLVMCreateDisasmCPUFeatures.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None), ctypes.c_int32, LLVMOpInfoCallback, LLVMSymbolLookupCallback] +except AttributeError: + pass +try: + LLVMSetDisasmOptions = _libraries['llvm'].LLVMSetDisasmOptions + LLVMSetDisasmOptions.restype = ctypes.c_int32 + LLVMSetDisasmOptions.argtypes = [LLVMDisasmContextRef, uint64_t] +except AttributeError: + pass +try: + LLVMDisasmDispose = _libraries['llvm'].LLVMDisasmDispose + LLVMDisasmDispose.restype = None + LLVMDisasmDispose.argtypes = [LLVMDisasmContextRef] +except AttributeError: + pass +try: + LLVMDisasmInstruction = _libraries['llvm'].LLVMDisasmInstruction + LLVMDisasmInstruction.restype = size_t + LLVMDisasmInstruction.argtypes = [LLVMDisasmContextRef, ctypes.POINTER(ctypes.c_ubyte), uint64_t, uint64_t, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +LLVM_C_ERROR_H = True # macro +LLVMErrorSuccess = 0 # macro +class struct_LLVMOpaqueError(Structure): + pass + +LLVMErrorRef = ctypes.POINTER(struct_LLVMOpaqueError) +LLVMErrorTypeId = ctypes.POINTER(None) +try: + LLVMGetErrorTypeId = _libraries['llvm'].LLVMGetErrorTypeId + LLVMGetErrorTypeId.restype = LLVMErrorTypeId + LLVMGetErrorTypeId.argtypes = [LLVMErrorRef] +except AttributeError: + pass +try: + LLVMConsumeError = _libraries['llvm'].LLVMConsumeError + LLVMConsumeError.restype = None + LLVMConsumeError.argtypes = [LLVMErrorRef] +except AttributeError: + pass +try: + LLVMGetErrorMessage = _libraries['llvm'].LLVMGetErrorMessage + LLVMGetErrorMessage.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetErrorMessage.argtypes = [LLVMErrorRef] +except AttributeError: + pass +try: + LLVMDisposeErrorMessage = _libraries['llvm'].LLVMDisposeErrorMessage + LLVMDisposeErrorMessage.restype = None + LLVMDisposeErrorMessage.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetStringErrorTypeId = _libraries['llvm'].LLVMGetStringErrorTypeId + LLVMGetStringErrorTypeId.restype = LLVMErrorTypeId + LLVMGetStringErrorTypeId.argtypes = [] +except AttributeError: + pass +try: + LLVMCreateStringError = _libraries['llvm'].LLVMCreateStringError + LLVMCreateStringError.restype = LLVMErrorRef + LLVMCreateStringError.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +LLVM_C_EXECUTIONENGINE_H = True # macro +LLVM_C_TARGET_H = True # macro +# def LLVM_TARGET(TargetName): # macro +# return LLVMInitialize##TargetName##TargetMC; +# def LLVM_ASM_PRINTER(TargetName): # macro +# return LLVMInitialize##TargetName##AsmPrinter; +# def LLVM_ASM_PARSER(TargetName): # macro +# return LLVMInitialize##TargetName##AsmParser; +# def LLVM_DISASSEMBLER(TargetName): # macro +# return LLVMInitialize##TargetName##Disassembler; +LLVM_C_TARGETMACHINE_H = True # macro + +# values for enumeration 'LLVMByteOrdering' +LLVMByteOrdering__enumvalues = { + 0: 'LLVMBigEndian', + 1: 'LLVMLittleEndian', +} +LLVMBigEndian = 0 +LLVMLittleEndian = 1 +LLVMByteOrdering = ctypes.c_uint32 # enum +class struct_LLVMOpaqueTargetData(Structure): + pass + +LLVMTargetDataRef = ctypes.POINTER(struct_LLVMOpaqueTargetData) +class struct_LLVMOpaqueTargetLibraryInfotData(Structure): + pass + +LLVMTargetLibraryInfoRef = ctypes.POINTER(struct_LLVMOpaqueTargetLibraryInfotData) +try: + LLVMInitializeAArch64TargetInfo = _libraries['llvm'].LLVMInitializeAArch64TargetInfo + LLVMInitializeAArch64TargetInfo.restype = None + LLVMInitializeAArch64TargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUTargetInfo = _libraries['llvm'].LLVMInitializeAMDGPUTargetInfo + LLVMInitializeAMDGPUTargetInfo.restype = None + LLVMInitializeAMDGPUTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMTargetInfo = _libraries['llvm'].LLVMInitializeARMTargetInfo + LLVMInitializeARMTargetInfo.restype = None + LLVMInitializeARMTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRTargetInfo = _libraries['llvm'].LLVMInitializeAVRTargetInfo + LLVMInitializeAVRTargetInfo.restype = None + LLVMInitializeAVRTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFTargetInfo = _libraries['llvm'].LLVMInitializeBPFTargetInfo + LLVMInitializeBPFTargetInfo.restype = None + LLVMInitializeBPFTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonTargetInfo = _libraries['llvm'].LLVMInitializeHexagonTargetInfo + LLVMInitializeHexagonTargetInfo.restype = None + LLVMInitializeHexagonTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiTargetInfo = _libraries['llvm'].LLVMInitializeLanaiTargetInfo + LLVMInitializeLanaiTargetInfo.restype = None + LLVMInitializeLanaiTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsTargetInfo = _libraries['llvm'].LLVMInitializeMipsTargetInfo + LLVMInitializeMipsTargetInfo.restype = None + LLVMInitializeMipsTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430TargetInfo = _libraries['llvm'].LLVMInitializeMSP430TargetInfo + LLVMInitializeMSP430TargetInfo.restype = None + LLVMInitializeMSP430TargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNVPTXTargetInfo = _libraries['llvm'].LLVMInitializeNVPTXTargetInfo + LLVMInitializeNVPTXTargetInfo.restype = None + LLVMInitializeNVPTXTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCTargetInfo = _libraries['llvm'].LLVMInitializePowerPCTargetInfo + LLVMInitializePowerPCTargetInfo.restype = None + LLVMInitializePowerPCTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVTargetInfo = _libraries['llvm'].LLVMInitializeRISCVTargetInfo + LLVMInitializeRISCVTargetInfo.restype = None + LLVMInitializeRISCVTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcTargetInfo = _libraries['llvm'].LLVMInitializeSparcTargetInfo + LLVMInitializeSparcTargetInfo.restype = None + LLVMInitializeSparcTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZTargetInfo = _libraries['llvm'].LLVMInitializeSystemZTargetInfo + LLVMInitializeSystemZTargetInfo.restype = None + LLVMInitializeSystemZTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVETargetInfo = _libraries['llvm'].LLVMInitializeVETargetInfo + LLVMInitializeVETargetInfo.restype = None + LLVMInitializeVETargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyTargetInfo = _libraries['llvm'].LLVMInitializeWebAssemblyTargetInfo + LLVMInitializeWebAssemblyTargetInfo.restype = None + LLVMInitializeWebAssemblyTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86TargetInfo = _libraries['llvm'].LLVMInitializeX86TargetInfo + LLVMInitializeX86TargetInfo.restype = None + LLVMInitializeX86TargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeXCoreTargetInfo = _libraries['llvm'].LLVMInitializeXCoreTargetInfo + LLVMInitializeXCoreTargetInfo.restype = None + LLVMInitializeXCoreTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kTargetInfo = _libraries['llvm'].LLVMInitializeM68kTargetInfo + LLVMInitializeM68kTargetInfo.restype = None + LLVMInitializeM68kTargetInfo.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAArch64Target = _libraries['llvm'].LLVMInitializeAArch64Target + LLVMInitializeAArch64Target.restype = None + LLVMInitializeAArch64Target.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUTarget = _libraries['llvm'].LLVMInitializeAMDGPUTarget + LLVMInitializeAMDGPUTarget.restype = None + LLVMInitializeAMDGPUTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMTarget = _libraries['llvm'].LLVMInitializeARMTarget + LLVMInitializeARMTarget.restype = None + LLVMInitializeARMTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRTarget = _libraries['llvm'].LLVMInitializeAVRTarget + LLVMInitializeAVRTarget.restype = None + LLVMInitializeAVRTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFTarget = _libraries['llvm'].LLVMInitializeBPFTarget + LLVMInitializeBPFTarget.restype = None + LLVMInitializeBPFTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonTarget = _libraries['llvm'].LLVMInitializeHexagonTarget + LLVMInitializeHexagonTarget.restype = None + LLVMInitializeHexagonTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiTarget = _libraries['llvm'].LLVMInitializeLanaiTarget + LLVMInitializeLanaiTarget.restype = None + LLVMInitializeLanaiTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsTarget = _libraries['llvm'].LLVMInitializeMipsTarget + LLVMInitializeMipsTarget.restype = None + LLVMInitializeMipsTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430Target = _libraries['llvm'].LLVMInitializeMSP430Target + LLVMInitializeMSP430Target.restype = None + LLVMInitializeMSP430Target.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNVPTXTarget = _libraries['llvm'].LLVMInitializeNVPTXTarget + LLVMInitializeNVPTXTarget.restype = None + LLVMInitializeNVPTXTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCTarget = _libraries['llvm'].LLVMInitializePowerPCTarget + LLVMInitializePowerPCTarget.restype = None + LLVMInitializePowerPCTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVTarget = _libraries['llvm'].LLVMInitializeRISCVTarget + LLVMInitializeRISCVTarget.restype = None + LLVMInitializeRISCVTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcTarget = _libraries['llvm'].LLVMInitializeSparcTarget + LLVMInitializeSparcTarget.restype = None + LLVMInitializeSparcTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZTarget = _libraries['llvm'].LLVMInitializeSystemZTarget + LLVMInitializeSystemZTarget.restype = None + LLVMInitializeSystemZTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVETarget = _libraries['llvm'].LLVMInitializeVETarget + LLVMInitializeVETarget.restype = None + LLVMInitializeVETarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyTarget = _libraries['llvm'].LLVMInitializeWebAssemblyTarget + LLVMInitializeWebAssemblyTarget.restype = None + LLVMInitializeWebAssemblyTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86Target = _libraries['llvm'].LLVMInitializeX86Target + LLVMInitializeX86Target.restype = None + LLVMInitializeX86Target.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeXCoreTarget = _libraries['llvm'].LLVMInitializeXCoreTarget + LLVMInitializeXCoreTarget.restype = None + LLVMInitializeXCoreTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kTarget = _libraries['llvm'].LLVMInitializeM68kTarget + LLVMInitializeM68kTarget.restype = None + LLVMInitializeM68kTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAArch64TargetMC = _libraries['llvm'].LLVMInitializeAArch64TargetMC + LLVMInitializeAArch64TargetMC.restype = None + LLVMInitializeAArch64TargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUTargetMC = _libraries['llvm'].LLVMInitializeAMDGPUTargetMC + LLVMInitializeAMDGPUTargetMC.restype = None + LLVMInitializeAMDGPUTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMTargetMC = _libraries['llvm'].LLVMInitializeARMTargetMC + LLVMInitializeARMTargetMC.restype = None + LLVMInitializeARMTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRTargetMC = _libraries['llvm'].LLVMInitializeAVRTargetMC + LLVMInitializeAVRTargetMC.restype = None + LLVMInitializeAVRTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFTargetMC = _libraries['llvm'].LLVMInitializeBPFTargetMC + LLVMInitializeBPFTargetMC.restype = None + LLVMInitializeBPFTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonTargetMC = _libraries['llvm'].LLVMInitializeHexagonTargetMC + LLVMInitializeHexagonTargetMC.restype = None + LLVMInitializeHexagonTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiTargetMC = _libraries['llvm'].LLVMInitializeLanaiTargetMC + LLVMInitializeLanaiTargetMC.restype = None + LLVMInitializeLanaiTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsTargetMC = _libraries['llvm'].LLVMInitializeMipsTargetMC + LLVMInitializeMipsTargetMC.restype = None + LLVMInitializeMipsTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430TargetMC = _libraries['llvm'].LLVMInitializeMSP430TargetMC + LLVMInitializeMSP430TargetMC.restype = None + LLVMInitializeMSP430TargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNVPTXTargetMC = _libraries['llvm'].LLVMInitializeNVPTXTargetMC + LLVMInitializeNVPTXTargetMC.restype = None + LLVMInitializeNVPTXTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCTargetMC = _libraries['llvm'].LLVMInitializePowerPCTargetMC + LLVMInitializePowerPCTargetMC.restype = None + LLVMInitializePowerPCTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVTargetMC = _libraries['llvm'].LLVMInitializeRISCVTargetMC + LLVMInitializeRISCVTargetMC.restype = None + LLVMInitializeRISCVTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcTargetMC = _libraries['llvm'].LLVMInitializeSparcTargetMC + LLVMInitializeSparcTargetMC.restype = None + LLVMInitializeSparcTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZTargetMC = _libraries['llvm'].LLVMInitializeSystemZTargetMC + LLVMInitializeSystemZTargetMC.restype = None + LLVMInitializeSystemZTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVETargetMC = _libraries['llvm'].LLVMInitializeVETargetMC + LLVMInitializeVETargetMC.restype = None + LLVMInitializeVETargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyTargetMC = _libraries['llvm'].LLVMInitializeWebAssemblyTargetMC + LLVMInitializeWebAssemblyTargetMC.restype = None + LLVMInitializeWebAssemblyTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86TargetMC = _libraries['llvm'].LLVMInitializeX86TargetMC + LLVMInitializeX86TargetMC.restype = None + LLVMInitializeX86TargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeXCoreTargetMC = _libraries['llvm'].LLVMInitializeXCoreTargetMC + LLVMInitializeXCoreTargetMC.restype = None + LLVMInitializeXCoreTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kTargetMC = _libraries['llvm'].LLVMInitializeM68kTargetMC + LLVMInitializeM68kTargetMC.restype = None + LLVMInitializeM68kTargetMC.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAArch64AsmPrinter = _libraries['llvm'].LLVMInitializeAArch64AsmPrinter + LLVMInitializeAArch64AsmPrinter.restype = None + LLVMInitializeAArch64AsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUAsmPrinter = _libraries['llvm'].LLVMInitializeAMDGPUAsmPrinter + LLVMInitializeAMDGPUAsmPrinter.restype = None + LLVMInitializeAMDGPUAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMAsmPrinter = _libraries['llvm'].LLVMInitializeARMAsmPrinter + LLVMInitializeARMAsmPrinter.restype = None + LLVMInitializeARMAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRAsmPrinter = _libraries['llvm'].LLVMInitializeAVRAsmPrinter + LLVMInitializeAVRAsmPrinter.restype = None + LLVMInitializeAVRAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFAsmPrinter = _libraries['llvm'].LLVMInitializeBPFAsmPrinter + LLVMInitializeBPFAsmPrinter.restype = None + LLVMInitializeBPFAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonAsmPrinter = _libraries['llvm'].LLVMInitializeHexagonAsmPrinter + LLVMInitializeHexagonAsmPrinter.restype = None + LLVMInitializeHexagonAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiAsmPrinter = _libraries['llvm'].LLVMInitializeLanaiAsmPrinter + LLVMInitializeLanaiAsmPrinter.restype = None + LLVMInitializeLanaiAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsAsmPrinter = _libraries['llvm'].LLVMInitializeMipsAsmPrinter + LLVMInitializeMipsAsmPrinter.restype = None + LLVMInitializeMipsAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430AsmPrinter = _libraries['llvm'].LLVMInitializeMSP430AsmPrinter + LLVMInitializeMSP430AsmPrinter.restype = None + LLVMInitializeMSP430AsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNVPTXAsmPrinter = _libraries['llvm'].LLVMInitializeNVPTXAsmPrinter + LLVMInitializeNVPTXAsmPrinter.restype = None + LLVMInitializeNVPTXAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCAsmPrinter = _libraries['llvm'].LLVMInitializePowerPCAsmPrinter + LLVMInitializePowerPCAsmPrinter.restype = None + LLVMInitializePowerPCAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVAsmPrinter = _libraries['llvm'].LLVMInitializeRISCVAsmPrinter + LLVMInitializeRISCVAsmPrinter.restype = None + LLVMInitializeRISCVAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcAsmPrinter = _libraries['llvm'].LLVMInitializeSparcAsmPrinter + LLVMInitializeSparcAsmPrinter.restype = None + LLVMInitializeSparcAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZAsmPrinter = _libraries['llvm'].LLVMInitializeSystemZAsmPrinter + LLVMInitializeSystemZAsmPrinter.restype = None + LLVMInitializeSystemZAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVEAsmPrinter = _libraries['llvm'].LLVMInitializeVEAsmPrinter + LLVMInitializeVEAsmPrinter.restype = None + LLVMInitializeVEAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyAsmPrinter = _libraries['llvm'].LLVMInitializeWebAssemblyAsmPrinter + LLVMInitializeWebAssemblyAsmPrinter.restype = None + LLVMInitializeWebAssemblyAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86AsmPrinter = _libraries['llvm'].LLVMInitializeX86AsmPrinter + LLVMInitializeX86AsmPrinter.restype = None + LLVMInitializeX86AsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeXCoreAsmPrinter = _libraries['llvm'].LLVMInitializeXCoreAsmPrinter + LLVMInitializeXCoreAsmPrinter.restype = None + LLVMInitializeXCoreAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kAsmPrinter = _libraries['llvm'].LLVMInitializeM68kAsmPrinter + LLVMInitializeM68kAsmPrinter.restype = None + LLVMInitializeM68kAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAArch64AsmParser = _libraries['llvm'].LLVMInitializeAArch64AsmParser + LLVMInitializeAArch64AsmParser.restype = None + LLVMInitializeAArch64AsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUAsmParser = _libraries['llvm'].LLVMInitializeAMDGPUAsmParser + LLVMInitializeAMDGPUAsmParser.restype = None + LLVMInitializeAMDGPUAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMAsmParser = _libraries['llvm'].LLVMInitializeARMAsmParser + LLVMInitializeARMAsmParser.restype = None + LLVMInitializeARMAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRAsmParser = _libraries['llvm'].LLVMInitializeAVRAsmParser + LLVMInitializeAVRAsmParser.restype = None + LLVMInitializeAVRAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFAsmParser = _libraries['llvm'].LLVMInitializeBPFAsmParser + LLVMInitializeBPFAsmParser.restype = None + LLVMInitializeBPFAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonAsmParser = _libraries['llvm'].LLVMInitializeHexagonAsmParser + LLVMInitializeHexagonAsmParser.restype = None + LLVMInitializeHexagonAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiAsmParser = _libraries['llvm'].LLVMInitializeLanaiAsmParser + LLVMInitializeLanaiAsmParser.restype = None + LLVMInitializeLanaiAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsAsmParser = _libraries['llvm'].LLVMInitializeMipsAsmParser + LLVMInitializeMipsAsmParser.restype = None + LLVMInitializeMipsAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430AsmParser = _libraries['llvm'].LLVMInitializeMSP430AsmParser + LLVMInitializeMSP430AsmParser.restype = None + LLVMInitializeMSP430AsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCAsmParser = _libraries['llvm'].LLVMInitializePowerPCAsmParser + LLVMInitializePowerPCAsmParser.restype = None + LLVMInitializePowerPCAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVAsmParser = _libraries['llvm'].LLVMInitializeRISCVAsmParser + LLVMInitializeRISCVAsmParser.restype = None + LLVMInitializeRISCVAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcAsmParser = _libraries['llvm'].LLVMInitializeSparcAsmParser + LLVMInitializeSparcAsmParser.restype = None + LLVMInitializeSparcAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZAsmParser = _libraries['llvm'].LLVMInitializeSystemZAsmParser + LLVMInitializeSystemZAsmParser.restype = None + LLVMInitializeSystemZAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVEAsmParser = _libraries['llvm'].LLVMInitializeVEAsmParser + LLVMInitializeVEAsmParser.restype = None + LLVMInitializeVEAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyAsmParser = _libraries['llvm'].LLVMInitializeWebAssemblyAsmParser + LLVMInitializeWebAssemblyAsmParser.restype = None + LLVMInitializeWebAssemblyAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86AsmParser = _libraries['llvm'].LLVMInitializeX86AsmParser + LLVMInitializeX86AsmParser.restype = None + LLVMInitializeX86AsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kAsmParser = _libraries['llvm'].LLVMInitializeM68kAsmParser + LLVMInitializeM68kAsmParser.restype = None + LLVMInitializeM68kAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAArch64Disassembler = _libraries['llvm'].LLVMInitializeAArch64Disassembler + LLVMInitializeAArch64Disassembler.restype = None + LLVMInitializeAArch64Disassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAMDGPUDisassembler = _libraries['llvm'].LLVMInitializeAMDGPUDisassembler + LLVMInitializeAMDGPUDisassembler.restype = None + LLVMInitializeAMDGPUDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeARMDisassembler = _libraries['llvm'].LLVMInitializeARMDisassembler + LLVMInitializeARMDisassembler.restype = None + LLVMInitializeARMDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAVRDisassembler = _libraries['llvm'].LLVMInitializeAVRDisassembler + LLVMInitializeAVRDisassembler.restype = None + LLVMInitializeAVRDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeBPFDisassembler = _libraries['llvm'].LLVMInitializeBPFDisassembler + LLVMInitializeBPFDisassembler.restype = None + LLVMInitializeBPFDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeHexagonDisassembler = _libraries['llvm'].LLVMInitializeHexagonDisassembler + LLVMInitializeHexagonDisassembler.restype = None + LLVMInitializeHexagonDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeLanaiDisassembler = _libraries['llvm'].LLVMInitializeLanaiDisassembler + LLVMInitializeLanaiDisassembler.restype = None + LLVMInitializeLanaiDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMipsDisassembler = _libraries['llvm'].LLVMInitializeMipsDisassembler + LLVMInitializeMipsDisassembler.restype = None + LLVMInitializeMipsDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeMSP430Disassembler = _libraries['llvm'].LLVMInitializeMSP430Disassembler + LLVMInitializeMSP430Disassembler.restype = None + LLVMInitializeMSP430Disassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializePowerPCDisassembler = _libraries['llvm'].LLVMInitializePowerPCDisassembler + LLVMInitializePowerPCDisassembler.restype = None + LLVMInitializePowerPCDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeRISCVDisassembler = _libraries['llvm'].LLVMInitializeRISCVDisassembler + LLVMInitializeRISCVDisassembler.restype = None + LLVMInitializeRISCVDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSparcDisassembler = _libraries['llvm'].LLVMInitializeSparcDisassembler + LLVMInitializeSparcDisassembler.restype = None + LLVMInitializeSparcDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeSystemZDisassembler = _libraries['llvm'].LLVMInitializeSystemZDisassembler + LLVMInitializeSystemZDisassembler.restype = None + LLVMInitializeSystemZDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeVEDisassembler = _libraries['llvm'].LLVMInitializeVEDisassembler + LLVMInitializeVEDisassembler.restype = None + LLVMInitializeVEDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeWebAssemblyDisassembler = _libraries['llvm'].LLVMInitializeWebAssemblyDisassembler + LLVMInitializeWebAssemblyDisassembler.restype = None + LLVMInitializeWebAssemblyDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeX86Disassembler = _libraries['llvm'].LLVMInitializeX86Disassembler + LLVMInitializeX86Disassembler.restype = None + LLVMInitializeX86Disassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeXCoreDisassembler = _libraries['llvm'].LLVMInitializeXCoreDisassembler + LLVMInitializeXCoreDisassembler.restype = None + LLVMInitializeXCoreDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeM68kDisassembler = _libraries['llvm'].LLVMInitializeM68kDisassembler + LLVMInitializeM68kDisassembler.restype = None + LLVMInitializeM68kDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllTargetInfos = _libraries['llvm'].LLVMInitializeAllTargetInfos + LLVMInitializeAllTargetInfos.restype = None + LLVMInitializeAllTargetInfos.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllTargets = _libraries['llvm'].LLVMInitializeAllTargets + LLVMInitializeAllTargets.restype = None + LLVMInitializeAllTargets.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllTargetMCs = _libraries['llvm'].LLVMInitializeAllTargetMCs + LLVMInitializeAllTargetMCs.restype = None + LLVMInitializeAllTargetMCs.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllAsmPrinters = _libraries['llvm'].LLVMInitializeAllAsmPrinters + LLVMInitializeAllAsmPrinters.restype = None + LLVMInitializeAllAsmPrinters.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllAsmParsers = _libraries['llvm'].LLVMInitializeAllAsmParsers + LLVMInitializeAllAsmParsers.restype = None + LLVMInitializeAllAsmParsers.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeAllDisassemblers = _libraries['llvm'].LLVMInitializeAllDisassemblers + LLVMInitializeAllDisassemblers.restype = None + LLVMInitializeAllDisassemblers.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNativeTarget = _libraries['llvm'].LLVMInitializeNativeTarget + LLVMInitializeNativeTarget.restype = LLVMBool + LLVMInitializeNativeTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNativeAsmParser = _libraries['llvm'].LLVMInitializeNativeAsmParser + LLVMInitializeNativeAsmParser.restype = LLVMBool + LLVMInitializeNativeAsmParser.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNativeAsmPrinter = _libraries['llvm'].LLVMInitializeNativeAsmPrinter + LLVMInitializeNativeAsmPrinter.restype = LLVMBool + LLVMInitializeNativeAsmPrinter.argtypes = [] +except AttributeError: + pass +try: + LLVMInitializeNativeDisassembler = _libraries['llvm'].LLVMInitializeNativeDisassembler + LLVMInitializeNativeDisassembler.restype = LLVMBool + LLVMInitializeNativeDisassembler.argtypes = [] +except AttributeError: + pass +try: + LLVMGetModuleDataLayout = _libraries['llvm'].LLVMGetModuleDataLayout + LLVMGetModuleDataLayout.restype = LLVMTargetDataRef + LLVMGetModuleDataLayout.argtypes = [LLVMModuleRef] +except AttributeError: + pass +try: + LLVMSetModuleDataLayout = _libraries['llvm'].LLVMSetModuleDataLayout + LLVMSetModuleDataLayout.restype = None + LLVMSetModuleDataLayout.argtypes = [LLVMModuleRef, LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMCreateTargetData = _libraries['llvm'].LLVMCreateTargetData + LLVMCreateTargetData.restype = LLVMTargetDataRef + LLVMCreateTargetData.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMDisposeTargetData = _libraries['llvm'].LLVMDisposeTargetData + LLVMDisposeTargetData.restype = None + LLVMDisposeTargetData.argtypes = [LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMAddTargetLibraryInfo = _libraries['llvm'].LLVMAddTargetLibraryInfo + LLVMAddTargetLibraryInfo.restype = None + LLVMAddTargetLibraryInfo.argtypes = [LLVMTargetLibraryInfoRef, LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMCopyStringRepOfTargetData = _libraries['llvm'].LLVMCopyStringRepOfTargetData + LLVMCopyStringRepOfTargetData.restype = ctypes.POINTER(ctypes.c_char) + LLVMCopyStringRepOfTargetData.argtypes = [LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMByteOrder = _libraries['llvm'].LLVMByteOrder + LLVMByteOrder.restype = LLVMByteOrdering + LLVMByteOrder.argtypes = [LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMPointerSize = _libraries['llvm'].LLVMPointerSize + LLVMPointerSize.restype = ctypes.c_uint32 + LLVMPointerSize.argtypes = [LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMPointerSizeForAS = _libraries['llvm'].LLVMPointerSizeForAS + LLVMPointerSizeForAS.restype = ctypes.c_uint32 + LLVMPointerSizeForAS.argtypes = [LLVMTargetDataRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMIntPtrType = _libraries['llvm'].LLVMIntPtrType + LLVMIntPtrType.restype = LLVMTypeRef + LLVMIntPtrType.argtypes = [LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMIntPtrTypeForAS = _libraries['llvm'].LLVMIntPtrTypeForAS + LLVMIntPtrTypeForAS.restype = LLVMTypeRef + LLVMIntPtrTypeForAS.argtypes = [LLVMTargetDataRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMIntPtrTypeInContext = _libraries['llvm'].LLVMIntPtrTypeInContext + LLVMIntPtrTypeInContext.restype = LLVMTypeRef + LLVMIntPtrTypeInContext.argtypes = [LLVMContextRef, LLVMTargetDataRef] +except AttributeError: + pass +try: + LLVMIntPtrTypeForASInContext = _libraries['llvm'].LLVMIntPtrTypeForASInContext + LLVMIntPtrTypeForASInContext.restype = LLVMTypeRef + LLVMIntPtrTypeForASInContext.argtypes = [LLVMContextRef, LLVMTargetDataRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMSizeOfTypeInBits = _libraries['llvm'].LLVMSizeOfTypeInBits + LLVMSizeOfTypeInBits.restype = ctypes.c_uint64 + LLVMSizeOfTypeInBits.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMStoreSizeOfType = _libraries['llvm'].LLVMStoreSizeOfType + LLVMStoreSizeOfType.restype = ctypes.c_uint64 + LLVMStoreSizeOfType.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMABISizeOfType = _libraries['llvm'].LLVMABISizeOfType + LLVMABISizeOfType.restype = ctypes.c_uint64 + LLVMABISizeOfType.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMABIAlignmentOfType = _libraries['llvm'].LLVMABIAlignmentOfType + LLVMABIAlignmentOfType.restype = ctypes.c_uint32 + LLVMABIAlignmentOfType.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMCallFrameAlignmentOfType = _libraries['llvm'].LLVMCallFrameAlignmentOfType + LLVMCallFrameAlignmentOfType.restype = ctypes.c_uint32 + LLVMCallFrameAlignmentOfType.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMPreferredAlignmentOfType = _libraries['llvm'].LLVMPreferredAlignmentOfType + LLVMPreferredAlignmentOfType.restype = ctypes.c_uint32 + LLVMPreferredAlignmentOfType.argtypes = [LLVMTargetDataRef, LLVMTypeRef] +except AttributeError: + pass +try: + LLVMPreferredAlignmentOfGlobal = _libraries['llvm'].LLVMPreferredAlignmentOfGlobal + LLVMPreferredAlignmentOfGlobal.restype = ctypes.c_uint32 + LLVMPreferredAlignmentOfGlobal.argtypes = [LLVMTargetDataRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMElementAtOffset = _libraries['llvm'].LLVMElementAtOffset + LLVMElementAtOffset.restype = ctypes.c_uint32 + LLVMElementAtOffset.argtypes = [LLVMTargetDataRef, LLVMTypeRef, ctypes.c_uint64] +except AttributeError: + pass +try: + LLVMOffsetOfElement = _libraries['llvm'].LLVMOffsetOfElement + LLVMOffsetOfElement.restype = ctypes.c_uint64 + LLVMOffsetOfElement.argtypes = [LLVMTargetDataRef, LLVMTypeRef, ctypes.c_uint32] +except AttributeError: + pass +class struct_LLVMOpaqueTargetMachine(Structure): + pass + +LLVMTargetMachineRef = ctypes.POINTER(struct_LLVMOpaqueTargetMachine) +class struct_LLVMTarget(Structure): + pass + +LLVMTargetRef = ctypes.POINTER(struct_LLVMTarget) + +# values for enumeration 'c__EA_LLVMCodeGenOptLevel' +c__EA_LLVMCodeGenOptLevel__enumvalues = { + 0: 'LLVMCodeGenLevelNone', + 1: 'LLVMCodeGenLevelLess', + 2: 'LLVMCodeGenLevelDefault', + 3: 'LLVMCodeGenLevelAggressive', +} +LLVMCodeGenLevelNone = 0 +LLVMCodeGenLevelLess = 1 +LLVMCodeGenLevelDefault = 2 +LLVMCodeGenLevelAggressive = 3 +c__EA_LLVMCodeGenOptLevel = ctypes.c_uint32 # enum +LLVMCodeGenOptLevel = c__EA_LLVMCodeGenOptLevel +LLVMCodeGenOptLevel__enumvalues = c__EA_LLVMCodeGenOptLevel__enumvalues + +# values for enumeration 'c__EA_LLVMRelocMode' +c__EA_LLVMRelocMode__enumvalues = { + 0: 'LLVMRelocDefault', + 1: 'LLVMRelocStatic', + 2: 'LLVMRelocPIC', + 3: 'LLVMRelocDynamicNoPic', + 4: 'LLVMRelocROPI', + 5: 'LLVMRelocRWPI', + 6: 'LLVMRelocROPI_RWPI', +} +LLVMRelocDefault = 0 +LLVMRelocStatic = 1 +LLVMRelocPIC = 2 +LLVMRelocDynamicNoPic = 3 +LLVMRelocROPI = 4 +LLVMRelocRWPI = 5 +LLVMRelocROPI_RWPI = 6 +c__EA_LLVMRelocMode = ctypes.c_uint32 # enum +LLVMRelocMode = c__EA_LLVMRelocMode +LLVMRelocMode__enumvalues = c__EA_LLVMRelocMode__enumvalues + +# values for enumeration 'c__EA_LLVMCodeModel' +c__EA_LLVMCodeModel__enumvalues = { + 0: 'LLVMCodeModelDefault', + 1: 'LLVMCodeModelJITDefault', + 2: 'LLVMCodeModelTiny', + 3: 'LLVMCodeModelSmall', + 4: 'LLVMCodeModelKernel', + 5: 'LLVMCodeModelMedium', + 6: 'LLVMCodeModelLarge', +} +LLVMCodeModelDefault = 0 +LLVMCodeModelJITDefault = 1 +LLVMCodeModelTiny = 2 +LLVMCodeModelSmall = 3 +LLVMCodeModelKernel = 4 +LLVMCodeModelMedium = 5 +LLVMCodeModelLarge = 6 +c__EA_LLVMCodeModel = ctypes.c_uint32 # enum +LLVMCodeModel = c__EA_LLVMCodeModel +LLVMCodeModel__enumvalues = c__EA_LLVMCodeModel__enumvalues + +# values for enumeration 'c__EA_LLVMCodeGenFileType' +c__EA_LLVMCodeGenFileType__enumvalues = { + 0: 'LLVMAssemblyFile', + 1: 'LLVMObjectFile', +} +LLVMAssemblyFile = 0 +LLVMObjectFile = 1 +c__EA_LLVMCodeGenFileType = ctypes.c_uint32 # enum +LLVMCodeGenFileType = c__EA_LLVMCodeGenFileType +LLVMCodeGenFileType__enumvalues = c__EA_LLVMCodeGenFileType__enumvalues +try: + LLVMGetFirstTarget = _libraries['llvm'].LLVMGetFirstTarget + LLVMGetFirstTarget.restype = LLVMTargetRef + LLVMGetFirstTarget.argtypes = [] +except AttributeError: + pass +try: + LLVMGetNextTarget = _libraries['llvm'].LLVMGetNextTarget + LLVMGetNextTarget.restype = LLVMTargetRef + LLVMGetNextTarget.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMGetTargetFromName = _libraries['llvm'].LLVMGetTargetFromName + LLVMGetTargetFromName.restype = LLVMTargetRef + LLVMGetTargetFromName.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetTargetFromTriple = _libraries['llvm'].LLVMGetTargetFromTriple + LLVMGetTargetFromTriple.restype = LLVMBool + LLVMGetTargetFromTriple.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(struct_LLVMTarget)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMGetTargetName = _libraries['llvm'].LLVMGetTargetName + LLVMGetTargetName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTargetName.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMGetTargetDescription = _libraries['llvm'].LLVMGetTargetDescription + LLVMGetTargetDescription.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTargetDescription.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMTargetHasJIT = _libraries['llvm'].LLVMTargetHasJIT + LLVMTargetHasJIT.restype = LLVMBool + LLVMTargetHasJIT.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMTargetHasTargetMachine = _libraries['llvm'].LLVMTargetHasTargetMachine + LLVMTargetHasTargetMachine.restype = LLVMBool + LLVMTargetHasTargetMachine.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMTargetHasAsmBackend = _libraries['llvm'].LLVMTargetHasAsmBackend + LLVMTargetHasAsmBackend.restype = LLVMBool + LLVMTargetHasAsmBackend.argtypes = [LLVMTargetRef] +except AttributeError: + pass +try: + LLVMCreateTargetMachine = _libraries['llvm'].LLVMCreateTargetMachine + LLVMCreateTargetMachine.restype = LLVMTargetMachineRef + LLVMCreateTargetMachine.argtypes = [LLVMTargetRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), LLVMCodeGenOptLevel, LLVMRelocMode, LLVMCodeModel] +except AttributeError: + pass +try: + LLVMDisposeTargetMachine = _libraries['llvm'].LLVMDisposeTargetMachine + LLVMDisposeTargetMachine.restype = None + LLVMDisposeTargetMachine.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMGetTargetMachineTarget = _libraries['llvm'].LLVMGetTargetMachineTarget + LLVMGetTargetMachineTarget.restype = LLVMTargetRef + LLVMGetTargetMachineTarget.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMGetTargetMachineTriple = _libraries['llvm'].LLVMGetTargetMachineTriple + LLVMGetTargetMachineTriple.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTargetMachineTriple.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMGetTargetMachineCPU = _libraries['llvm'].LLVMGetTargetMachineCPU + LLVMGetTargetMachineCPU.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTargetMachineCPU.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMGetTargetMachineFeatureString = _libraries['llvm'].LLVMGetTargetMachineFeatureString + LLVMGetTargetMachineFeatureString.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetTargetMachineFeatureString.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMCreateTargetDataLayout = _libraries['llvm'].LLVMCreateTargetDataLayout + LLVMCreateTargetDataLayout.restype = LLVMTargetDataRef + LLVMCreateTargetDataLayout.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMSetTargetMachineAsmVerbosity = _libraries['llvm'].LLVMSetTargetMachineAsmVerbosity + LLVMSetTargetMachineAsmVerbosity.restype = None + LLVMSetTargetMachineAsmVerbosity.argtypes = [LLVMTargetMachineRef, LLVMBool] +except AttributeError: + pass +try: + LLVMTargetMachineEmitToFile = _libraries['llvm'].LLVMTargetMachineEmitToFile + LLVMTargetMachineEmitToFile.restype = LLVMBool + LLVMTargetMachineEmitToFile.argtypes = [LLVMTargetMachineRef, LLVMModuleRef, ctypes.POINTER(ctypes.c_char), LLVMCodeGenFileType, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMTargetMachineEmitToMemoryBuffer = _libraries['llvm'].LLVMTargetMachineEmitToMemoryBuffer + LLVMTargetMachineEmitToMemoryBuffer.restype = LLVMBool + LLVMTargetMachineEmitToMemoryBuffer.argtypes = [LLVMTargetMachineRef, LLVMModuleRef, LLVMCodeGenFileType, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer))] +except AttributeError: + pass +try: + LLVMGetDefaultTargetTriple = _libraries['llvm'].LLVMGetDefaultTargetTriple + LLVMGetDefaultTargetTriple.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetDefaultTargetTriple.argtypes = [] +except AttributeError: + pass +try: + LLVMNormalizeTargetTriple = _libraries['llvm'].LLVMNormalizeTargetTriple + LLVMNormalizeTargetTriple.restype = ctypes.POINTER(ctypes.c_char) + LLVMNormalizeTargetTriple.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetHostCPUName = _libraries['llvm'].LLVMGetHostCPUName + LLVMGetHostCPUName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetHostCPUName.argtypes = [] +except AttributeError: + pass +try: + LLVMGetHostCPUFeatures = _libraries['llvm'].LLVMGetHostCPUFeatures + LLVMGetHostCPUFeatures.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetHostCPUFeatures.argtypes = [] +except AttributeError: + pass +try: + LLVMAddAnalysisPasses = _libraries['llvm'].LLVMAddAnalysisPasses + LLVMAddAnalysisPasses.restype = None + LLVMAddAnalysisPasses.argtypes = [LLVMTargetMachineRef, LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMLinkInMCJIT = _libraries['llvm'].LLVMLinkInMCJIT + LLVMLinkInMCJIT.restype = None + LLVMLinkInMCJIT.argtypes = [] +except AttributeError: + pass +try: + LLVMLinkInInterpreter = _libraries['llvm'].LLVMLinkInInterpreter + LLVMLinkInInterpreter.restype = None + LLVMLinkInInterpreter.argtypes = [] +except AttributeError: + pass +class struct_LLVMOpaqueGenericValue(Structure): + pass + +LLVMGenericValueRef = ctypes.POINTER(struct_LLVMOpaqueGenericValue) +class struct_LLVMOpaqueExecutionEngine(Structure): + pass + +LLVMExecutionEngineRef = ctypes.POINTER(struct_LLVMOpaqueExecutionEngine) +class struct_LLVMOpaqueMCJITMemoryManager(Structure): + pass + +LLVMMCJITMemoryManagerRef = ctypes.POINTER(struct_LLVMOpaqueMCJITMemoryManager) +class struct_LLVMMCJITCompilerOptions(Structure): + pass + +struct_LLVMMCJITCompilerOptions._pack_ = 1 # source:False +struct_LLVMMCJITCompilerOptions._fields_ = [ + ('OptLevel', ctypes.c_uint32), + ('CodeModel', LLVMCodeModel), + ('NoFramePointerElim', ctypes.c_int32), + ('EnableFastISel', ctypes.c_int32), + ('MCJMM', ctypes.POINTER(struct_LLVMOpaqueMCJITMemoryManager)), +] + +try: + LLVMCreateGenericValueOfInt = _libraries['llvm'].LLVMCreateGenericValueOfInt + LLVMCreateGenericValueOfInt.restype = LLVMGenericValueRef + LLVMCreateGenericValueOfInt.argtypes = [LLVMTypeRef, ctypes.c_uint64, LLVMBool] +except AttributeError: + pass +try: + LLVMCreateGenericValueOfPointer = _libraries['llvm'].LLVMCreateGenericValueOfPointer + LLVMCreateGenericValueOfPointer.restype = LLVMGenericValueRef + LLVMCreateGenericValueOfPointer.argtypes = [ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMCreateGenericValueOfFloat = _libraries['llvm'].LLVMCreateGenericValueOfFloat + LLVMCreateGenericValueOfFloat.restype = LLVMGenericValueRef + LLVMCreateGenericValueOfFloat.argtypes = [LLVMTypeRef, ctypes.c_double] +except AttributeError: + pass +try: + LLVMGenericValueIntWidth = _libraries['llvm'].LLVMGenericValueIntWidth + LLVMGenericValueIntWidth.restype = ctypes.c_uint32 + LLVMGenericValueIntWidth.argtypes = [LLVMGenericValueRef] +except AttributeError: + pass +try: + LLVMGenericValueToInt = _libraries['llvm'].LLVMGenericValueToInt + LLVMGenericValueToInt.restype = ctypes.c_uint64 + LLVMGenericValueToInt.argtypes = [LLVMGenericValueRef, LLVMBool] +except AttributeError: + pass +try: + LLVMGenericValueToPointer = _libraries['llvm'].LLVMGenericValueToPointer + LLVMGenericValueToPointer.restype = ctypes.POINTER(None) + LLVMGenericValueToPointer.argtypes = [LLVMGenericValueRef] +except AttributeError: + pass +try: + LLVMGenericValueToFloat = _libraries['llvm'].LLVMGenericValueToFloat + LLVMGenericValueToFloat.restype = ctypes.c_double + LLVMGenericValueToFloat.argtypes = [LLVMTypeRef, LLVMGenericValueRef] +except AttributeError: + pass +try: + LLVMDisposeGenericValue = _libraries['llvm'].LLVMDisposeGenericValue + LLVMDisposeGenericValue.restype = None + LLVMDisposeGenericValue.argtypes = [LLVMGenericValueRef] +except AttributeError: + pass +try: + LLVMCreateExecutionEngineForModule = _libraries['llvm'].LLVMCreateExecutionEngineForModule + LLVMCreateExecutionEngineForModule.restype = LLVMBool + LLVMCreateExecutionEngineForModule.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueExecutionEngine)), LLVMModuleRef, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMCreateInterpreterForModule = _libraries['llvm'].LLVMCreateInterpreterForModule + LLVMCreateInterpreterForModule.restype = LLVMBool + LLVMCreateInterpreterForModule.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueExecutionEngine)), LLVMModuleRef, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMCreateJITCompilerForModule = _libraries['llvm'].LLVMCreateJITCompilerForModule + LLVMCreateJITCompilerForModule.restype = LLVMBool + LLVMCreateJITCompilerForModule.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueExecutionEngine)), LLVMModuleRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMInitializeMCJITCompilerOptions = _libraries['llvm'].LLVMInitializeMCJITCompilerOptions + LLVMInitializeMCJITCompilerOptions.restype = None + LLVMInitializeMCJITCompilerOptions.argtypes = [ctypes.POINTER(struct_LLVMMCJITCompilerOptions), size_t] +except AttributeError: + pass +try: + LLVMCreateMCJITCompilerForModule = _libraries['llvm'].LLVMCreateMCJITCompilerForModule + LLVMCreateMCJITCompilerForModule.restype = LLVMBool + LLVMCreateMCJITCompilerForModule.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueExecutionEngine)), LLVMModuleRef, ctypes.POINTER(struct_LLVMMCJITCompilerOptions), size_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMDisposeExecutionEngine = _libraries['llvm'].LLVMDisposeExecutionEngine + LLVMDisposeExecutionEngine.restype = None + LLVMDisposeExecutionEngine.argtypes = [LLVMExecutionEngineRef] +except AttributeError: + pass +try: + LLVMRunStaticConstructors = _libraries['llvm'].LLVMRunStaticConstructors + LLVMRunStaticConstructors.restype = None + LLVMRunStaticConstructors.argtypes = [LLVMExecutionEngineRef] +except AttributeError: + pass +try: + LLVMRunStaticDestructors = _libraries['llvm'].LLVMRunStaticDestructors + LLVMRunStaticDestructors.restype = None + LLVMRunStaticDestructors.argtypes = [LLVMExecutionEngineRef] +except AttributeError: + pass +try: + LLVMRunFunctionAsMain = _libraries['llvm'].LLVMRunFunctionAsMain + LLVMRunFunctionAsMain.restype = ctypes.c_int32 + LLVMRunFunctionAsMain.argtypes = [LLVMExecutionEngineRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMRunFunction = _libraries['llvm'].LLVMRunFunction + LLVMRunFunction.restype = LLVMGenericValueRef + LLVMRunFunction.argtypes = [LLVMExecutionEngineRef, LLVMValueRef, ctypes.c_uint32, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueGenericValue))] +except AttributeError: + pass +try: + LLVMFreeMachineCodeForFunction = _libraries['llvm'].LLVMFreeMachineCodeForFunction + LLVMFreeMachineCodeForFunction.restype = None + LLVMFreeMachineCodeForFunction.argtypes = [LLVMExecutionEngineRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMAddModule = _libraries['llvm'].LLVMAddModule + LLVMAddModule.restype = None + LLVMAddModule.argtypes = [LLVMExecutionEngineRef, LLVMModuleRef] +except AttributeError: + pass +try: + LLVMRemoveModule = _libraries['llvm'].LLVMRemoveModule + LLVMRemoveModule.restype = LLVMBool + LLVMRemoveModule.argtypes = [LLVMExecutionEngineRef, LLVMModuleRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMFindFunction = _libraries['llvm'].LLVMFindFunction + LLVMFindFunction.restype = LLVMBool + LLVMFindFunction.argtypes = [LLVMExecutionEngineRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueValue))] +except AttributeError: + pass +try: + LLVMRecompileAndRelinkFunction = _libraries['llvm'].LLVMRecompileAndRelinkFunction + LLVMRecompileAndRelinkFunction.restype = ctypes.POINTER(None) + LLVMRecompileAndRelinkFunction.argtypes = [LLVMExecutionEngineRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetExecutionEngineTargetData = _libraries['llvm'].LLVMGetExecutionEngineTargetData + LLVMGetExecutionEngineTargetData.restype = LLVMTargetDataRef + LLVMGetExecutionEngineTargetData.argtypes = [LLVMExecutionEngineRef] +except AttributeError: + pass +try: + LLVMGetExecutionEngineTargetMachine = _libraries['llvm'].LLVMGetExecutionEngineTargetMachine + LLVMGetExecutionEngineTargetMachine.restype = LLVMTargetMachineRef + LLVMGetExecutionEngineTargetMachine.argtypes = [LLVMExecutionEngineRef] +except AttributeError: + pass +try: + LLVMAddGlobalMapping = _libraries['llvm'].LLVMAddGlobalMapping + LLVMAddGlobalMapping.restype = None + LLVMAddGlobalMapping.argtypes = [LLVMExecutionEngineRef, LLVMValueRef, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMGetPointerToGlobal = _libraries['llvm'].LLVMGetPointerToGlobal + LLVMGetPointerToGlobal.restype = ctypes.POINTER(None) + LLVMGetPointerToGlobal.argtypes = [LLVMExecutionEngineRef, LLVMValueRef] +except AttributeError: + pass +try: + LLVMGetGlobalValueAddress = _libraries['llvm'].LLVMGetGlobalValueAddress + LLVMGetGlobalValueAddress.restype = uint64_t + LLVMGetGlobalValueAddress.argtypes = [LLVMExecutionEngineRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMGetFunctionAddress = _libraries['llvm'].LLVMGetFunctionAddress + LLVMGetFunctionAddress.restype = uint64_t + LLVMGetFunctionAddress.argtypes = [LLVMExecutionEngineRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMExecutionEngineGetErrMsg = _libraries['llvm'].LLVMExecutionEngineGetErrMsg + LLVMExecutionEngineGetErrMsg.restype = LLVMBool + LLVMExecutionEngineGetErrMsg.argtypes = [LLVMExecutionEngineRef, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +LLVMMemoryManagerAllocateCodeSectionCallback = ctypes.CFUNCTYPE(ctypes.POINTER(ctypes.c_ubyte), ctypes.POINTER(None), ctypes.c_uint64, ctypes.c_uint32, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char)) +LLVMMemoryManagerAllocateDataSectionCallback = ctypes.CFUNCTYPE(ctypes.POINTER(ctypes.c_ubyte), ctypes.POINTER(None), ctypes.c_uint64, ctypes.c_uint32, ctypes.c_uint32, ctypes.POINTER(ctypes.c_char), ctypes.c_int32) +LLVMMemoryManagerFinalizeMemoryCallback = ctypes.CFUNCTYPE(ctypes.c_int32, ctypes.POINTER(None), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))) +LLVMMemoryManagerDestroyCallback = ctypes.CFUNCTYPE(None, ctypes.POINTER(None)) +try: + LLVMCreateSimpleMCJITMemoryManager = _libraries['llvm'].LLVMCreateSimpleMCJITMemoryManager + LLVMCreateSimpleMCJITMemoryManager.restype = LLVMMCJITMemoryManagerRef + LLVMCreateSimpleMCJITMemoryManager.argtypes = [ctypes.POINTER(None), LLVMMemoryManagerAllocateCodeSectionCallback, LLVMMemoryManagerAllocateDataSectionCallback, LLVMMemoryManagerFinalizeMemoryCallback, LLVMMemoryManagerDestroyCallback] +except AttributeError: + pass +try: + LLVMDisposeMCJITMemoryManager = _libraries['llvm'].LLVMDisposeMCJITMemoryManager + LLVMDisposeMCJITMemoryManager.restype = None + LLVMDisposeMCJITMemoryManager.argtypes = [LLVMMCJITMemoryManagerRef] +except AttributeError: + pass +try: + LLVMCreateGDBRegistrationListener = _libraries['llvm'].LLVMCreateGDBRegistrationListener + LLVMCreateGDBRegistrationListener.restype = LLVMJITEventListenerRef + LLVMCreateGDBRegistrationListener.argtypes = [] +except AttributeError: + pass +try: + LLVMCreateIntelJITEventListener = _libraries['llvm'].LLVMCreateIntelJITEventListener + LLVMCreateIntelJITEventListener.restype = LLVMJITEventListenerRef + LLVMCreateIntelJITEventListener.argtypes = [] +except AttributeError: + pass +try: + LLVMCreateOProfileJITEventListener = _libraries['llvm'].LLVMCreateOProfileJITEventListener + LLVMCreateOProfileJITEventListener.restype = LLVMJITEventListenerRef + LLVMCreateOProfileJITEventListener.argtypes = [] +except AttributeError: + pass +try: + LLVMCreatePerfJITEventListener = _libraries['llvm'].LLVMCreatePerfJITEventListener + LLVMCreatePerfJITEventListener.restype = LLVMJITEventListenerRef + LLVMCreatePerfJITEventListener.argtypes = [] +except AttributeError: + pass +LLVM_C_IRREADER_H = True # macro +try: + LLVMParseIRInContext = _libraries['llvm'].LLVMParseIRInContext + LLVMParseIRInContext.restype = LLVMBool + LLVMParseIRInContext.argtypes = [LLVMContextRef, LLVMMemoryBufferRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueModule)), ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +LLVM_C_INITIALIZATION_H = True # macro +try: + LLVMInitializeTransformUtils = _libraries['llvm'].LLVMInitializeTransformUtils + LLVMInitializeTransformUtils.restype = None + LLVMInitializeTransformUtils.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeScalarOpts = _libraries['llvm'].LLVMInitializeScalarOpts + LLVMInitializeScalarOpts.restype = None + LLVMInitializeScalarOpts.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeObjCARCOpts = _libraries['llvm'].LLVMInitializeObjCARCOpts + LLVMInitializeObjCARCOpts.restype = None + LLVMInitializeObjCARCOpts.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeVectorization = _libraries['llvm'].LLVMInitializeVectorization + LLVMInitializeVectorization.restype = None + LLVMInitializeVectorization.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeInstCombine = _libraries['llvm'].LLVMInitializeInstCombine + LLVMInitializeInstCombine.restype = None + LLVMInitializeInstCombine.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeAggressiveInstCombiner = _libraries['llvm'].LLVMInitializeAggressiveInstCombiner + LLVMInitializeAggressiveInstCombiner.restype = None + LLVMInitializeAggressiveInstCombiner.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeIPO = _libraries['llvm'].LLVMInitializeIPO + LLVMInitializeIPO.restype = None + LLVMInitializeIPO.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeInstrumentation = _libraries['llvm'].LLVMInitializeInstrumentation + LLVMInitializeInstrumentation.restype = None + LLVMInitializeInstrumentation.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeAnalysis = _libraries['llvm'].LLVMInitializeAnalysis + LLVMInitializeAnalysis.restype = None + LLVMInitializeAnalysis.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeIPA = _libraries['llvm'].LLVMInitializeIPA + LLVMInitializeIPA.restype = None + LLVMInitializeIPA.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeCodeGen = _libraries['llvm'].LLVMInitializeCodeGen + LLVMInitializeCodeGen.restype = None + LLVMInitializeCodeGen.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +try: + LLVMInitializeTarget = _libraries['llvm'].LLVMInitializeTarget + LLVMInitializeTarget.restype = None + LLVMInitializeTarget.argtypes = [LLVMPassRegistryRef] +except AttributeError: + pass +LLVM_C_LLJIT_H = True # macro +LLVM_C_ORC_H = True # macro +LLVMOrcJITTargetAddress = ctypes.c_uint64 +LLVMOrcExecutorAddress = ctypes.c_uint64 + +# values for enumeration 'c__EA_LLVMJITSymbolGenericFlags' +c__EA_LLVMJITSymbolGenericFlags__enumvalues = { + 1: 'LLVMJITSymbolGenericFlagsExported', + 2: 'LLVMJITSymbolGenericFlagsWeak', + 4: 'LLVMJITSymbolGenericFlagsCallable', + 8: 'LLVMJITSymbolGenericFlagsMaterializationSideEffectsOnly', +} +LLVMJITSymbolGenericFlagsExported = 1 +LLVMJITSymbolGenericFlagsWeak = 2 +LLVMJITSymbolGenericFlagsCallable = 4 +LLVMJITSymbolGenericFlagsMaterializationSideEffectsOnly = 8 +c__EA_LLVMJITSymbolGenericFlags = ctypes.c_uint32 # enum +LLVMJITSymbolGenericFlags = c__EA_LLVMJITSymbolGenericFlags +LLVMJITSymbolGenericFlags__enumvalues = c__EA_LLVMJITSymbolGenericFlags__enumvalues +LLVMJITSymbolTargetFlags = ctypes.c_ubyte +class struct_c__SA_LLVMJITSymbolFlags(Structure): + pass + +struct_c__SA_LLVMJITSymbolFlags._pack_ = 1 # source:False +struct_c__SA_LLVMJITSymbolFlags._fields_ = [ + ('GenericFlags', ctypes.c_ubyte), + ('TargetFlags', ctypes.c_ubyte), +] + +LLVMJITSymbolFlags = struct_c__SA_LLVMJITSymbolFlags +class struct_c__SA_LLVMJITEvaluatedSymbol(Structure): + pass + +struct_c__SA_LLVMJITEvaluatedSymbol._pack_ = 1 # source:False +struct_c__SA_LLVMJITEvaluatedSymbol._fields_ = [ + ('Address', ctypes.c_uint64), + ('Flags', LLVMJITSymbolFlags), + ('PADDING_0', ctypes.c_ubyte * 6), +] + +LLVMJITEvaluatedSymbol = struct_c__SA_LLVMJITEvaluatedSymbol +class struct_LLVMOrcOpaqueExecutionSession(Structure): + pass + +LLVMOrcExecutionSessionRef = ctypes.POINTER(struct_LLVMOrcOpaqueExecutionSession) +LLVMOrcErrorReporterFunction = ctypes.CFUNCTYPE(None, ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOpaqueError)) +class struct_LLVMOrcOpaqueSymbolStringPool(Structure): + pass + +LLVMOrcSymbolStringPoolRef = ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPool) +class struct_LLVMOrcOpaqueSymbolStringPoolEntry(Structure): + pass + +LLVMOrcSymbolStringPoolEntryRef = ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry) +class struct_c__SA_LLVMOrcCSymbolFlagsMapPair(Structure): + pass + +struct_c__SA_LLVMOrcCSymbolFlagsMapPair._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCSymbolFlagsMapPair._fields_ = [ + ('Name', ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), + ('Flags', LLVMJITSymbolFlags), + ('PADDING_0', ctypes.c_ubyte * 6), +] + +LLVMOrcCSymbolFlagsMapPair = struct_c__SA_LLVMOrcCSymbolFlagsMapPair +LLVMOrcCSymbolFlagsMapPairs = ctypes.POINTER(struct_c__SA_LLVMOrcCSymbolFlagsMapPair) +class struct_c__SA_LLVMJITCSymbolMapPair(Structure): + pass + +struct_c__SA_LLVMJITCSymbolMapPair._pack_ = 1 # source:False +struct_c__SA_LLVMJITCSymbolMapPair._fields_ = [ + ('Name', ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), + ('Sym', LLVMJITEvaluatedSymbol), +] + +LLVMJITCSymbolMapPair = struct_c__SA_LLVMJITCSymbolMapPair +LLVMOrcCSymbolMapPairs = ctypes.POINTER(struct_c__SA_LLVMJITCSymbolMapPair) +class struct_c__SA_LLVMOrcCSymbolAliasMapEntry(Structure): + pass + +struct_c__SA_LLVMOrcCSymbolAliasMapEntry._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCSymbolAliasMapEntry._fields_ = [ + ('Name', ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), + ('Flags', LLVMJITSymbolFlags), + ('PADDING_0', ctypes.c_ubyte * 6), +] + +LLVMOrcCSymbolAliasMapEntry = struct_c__SA_LLVMOrcCSymbolAliasMapEntry +class struct_c__SA_LLVMOrcCSymbolAliasMapPair(Structure): + pass + +struct_c__SA_LLVMOrcCSymbolAliasMapPair._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCSymbolAliasMapPair._fields_ = [ + ('Name', ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), + ('Entry', LLVMOrcCSymbolAliasMapEntry), +] + +LLVMOrcCSymbolAliasMapPair = struct_c__SA_LLVMOrcCSymbolAliasMapPair +LLVMOrcCSymbolAliasMapPairs = ctypes.POINTER(struct_c__SA_LLVMOrcCSymbolAliasMapPair) +class struct_LLVMOrcOpaqueJITDylib(Structure): + pass + +LLVMOrcJITDylibRef = ctypes.POINTER(struct_LLVMOrcOpaqueJITDylib) +class struct_c__SA_LLVMOrcCSymbolsList(Structure): + pass + +struct_c__SA_LLVMOrcCSymbolsList._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCSymbolsList._fields_ = [ + ('Symbols', ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry))), + ('Length', ctypes.c_uint64), +] + +LLVMOrcCSymbolsList = struct_c__SA_LLVMOrcCSymbolsList +class struct_c__SA_LLVMOrcCDependenceMapPair(Structure): + pass + +struct_c__SA_LLVMOrcCDependenceMapPair._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCDependenceMapPair._fields_ = [ + ('JD', ctypes.POINTER(struct_LLVMOrcOpaqueJITDylib)), + ('Names', LLVMOrcCSymbolsList), +] + +LLVMOrcCDependenceMapPair = struct_c__SA_LLVMOrcCDependenceMapPair +LLVMOrcCDependenceMapPairs = ctypes.POINTER(struct_c__SA_LLVMOrcCDependenceMapPair) + +# values for enumeration 'c__EA_LLVMOrcLookupKind' +c__EA_LLVMOrcLookupKind__enumvalues = { + 0: 'LLVMOrcLookupKindStatic', + 1: 'LLVMOrcLookupKindDLSym', +} +LLVMOrcLookupKindStatic = 0 +LLVMOrcLookupKindDLSym = 1 +c__EA_LLVMOrcLookupKind = ctypes.c_uint32 # enum +LLVMOrcLookupKind = c__EA_LLVMOrcLookupKind +LLVMOrcLookupKind__enumvalues = c__EA_LLVMOrcLookupKind__enumvalues + +# values for enumeration 'c__EA_LLVMOrcJITDylibLookupFlags' +c__EA_LLVMOrcJITDylibLookupFlags__enumvalues = { + 0: 'LLVMOrcJITDylibLookupFlagsMatchExportedSymbolsOnly', + 1: 'LLVMOrcJITDylibLookupFlagsMatchAllSymbols', +} +LLVMOrcJITDylibLookupFlagsMatchExportedSymbolsOnly = 0 +LLVMOrcJITDylibLookupFlagsMatchAllSymbols = 1 +c__EA_LLVMOrcJITDylibLookupFlags = ctypes.c_uint32 # enum +LLVMOrcJITDylibLookupFlags = c__EA_LLVMOrcJITDylibLookupFlags +LLVMOrcJITDylibLookupFlags__enumvalues = c__EA_LLVMOrcJITDylibLookupFlags__enumvalues + +# values for enumeration 'c__EA_LLVMOrcSymbolLookupFlags' +c__EA_LLVMOrcSymbolLookupFlags__enumvalues = { + 0: 'LLVMOrcSymbolLookupFlagsRequiredSymbol', + 1: 'LLVMOrcSymbolLookupFlagsWeaklyReferencedSymbol', +} +LLVMOrcSymbolLookupFlagsRequiredSymbol = 0 +LLVMOrcSymbolLookupFlagsWeaklyReferencedSymbol = 1 +c__EA_LLVMOrcSymbolLookupFlags = ctypes.c_uint32 # enum +LLVMOrcSymbolLookupFlags = c__EA_LLVMOrcSymbolLookupFlags +LLVMOrcSymbolLookupFlags__enumvalues = c__EA_LLVMOrcSymbolLookupFlags__enumvalues +class struct_c__SA_LLVMOrcCLookupSetElement(Structure): + pass + +struct_c__SA_LLVMOrcCLookupSetElement._pack_ = 1 # source:False +struct_c__SA_LLVMOrcCLookupSetElement._fields_ = [ + ('Name', ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), + ('LookupFlags', LLVMOrcSymbolLookupFlags), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +LLVMOrcCLookupSetElement = struct_c__SA_LLVMOrcCLookupSetElement +LLVMOrcCLookupSet = ctypes.POINTER(struct_c__SA_LLVMOrcCLookupSetElement) +class struct_LLVMOrcOpaqueMaterializationUnit(Structure): + pass + +LLVMOrcMaterializationUnitRef = ctypes.POINTER(struct_LLVMOrcOpaqueMaterializationUnit) +class struct_LLVMOrcOpaqueMaterializationResponsibility(Structure): + pass + +LLVMOrcMaterializationResponsibilityRef = ctypes.POINTER(struct_LLVMOrcOpaqueMaterializationResponsibility) +LLVMOrcMaterializationUnitMaterializeFunction = ctypes.CFUNCTYPE(None, ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOrcOpaqueMaterializationResponsibility)) +LLVMOrcMaterializationUnitDiscardFunction = ctypes.CFUNCTYPE(None, ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOrcOpaqueJITDylib), ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)) +LLVMOrcMaterializationUnitDestroyFunction = ctypes.CFUNCTYPE(None, ctypes.POINTER(None)) +class struct_LLVMOrcOpaqueResourceTracker(Structure): + pass + +LLVMOrcResourceTrackerRef = ctypes.POINTER(struct_LLVMOrcOpaqueResourceTracker) +class struct_LLVMOrcOpaqueDefinitionGenerator(Structure): + pass + +LLVMOrcDefinitionGeneratorRef = ctypes.POINTER(struct_LLVMOrcOpaqueDefinitionGenerator) +class struct_LLVMOrcOpaqueLookupState(Structure): + pass + +LLVMOrcLookupStateRef = ctypes.POINTER(struct_LLVMOrcOpaqueLookupState) +LLVMOrcCAPIDefinitionGeneratorTryToGenerateFunction = ctypes.CFUNCTYPE(ctypes.POINTER(struct_LLVMOpaqueError), ctypes.POINTER(struct_LLVMOrcOpaqueDefinitionGenerator), ctypes.POINTER(None), ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueLookupState)), c__EA_LLVMOrcLookupKind, ctypes.POINTER(struct_LLVMOrcOpaqueJITDylib), c__EA_LLVMOrcJITDylibLookupFlags, ctypes.POINTER(struct_c__SA_LLVMOrcCLookupSetElement), ctypes.c_uint64) +LLVMOrcSymbolPredicate = ctypes.CFUNCTYPE(ctypes.c_int32, ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)) +class struct_LLVMOrcOpaqueThreadSafeContext(Structure): + pass + +LLVMOrcThreadSafeContextRef = ctypes.POINTER(struct_LLVMOrcOpaqueThreadSafeContext) +class struct_LLVMOrcOpaqueThreadSafeModule(Structure): + pass + +LLVMOrcThreadSafeModuleRef = ctypes.POINTER(struct_LLVMOrcOpaqueThreadSafeModule) +LLVMOrcGenericIRModuleOperationFunction = ctypes.CFUNCTYPE(ctypes.POINTER(struct_LLVMOpaqueError), ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOpaqueModule)) +class struct_LLVMOrcOpaqueJITTargetMachineBuilder(Structure): + pass + +LLVMOrcJITTargetMachineBuilderRef = ctypes.POINTER(struct_LLVMOrcOpaqueJITTargetMachineBuilder) +class struct_LLVMOrcOpaqueObjectLayer(Structure): + pass + +LLVMOrcObjectLayerRef = ctypes.POINTER(struct_LLVMOrcOpaqueObjectLayer) +class struct_LLVMOrcOpaqueObjectLinkingLayer(Structure): + pass + +LLVMOrcObjectLinkingLayerRef = ctypes.POINTER(struct_LLVMOrcOpaqueObjectLinkingLayer) +class struct_LLVMOrcOpaqueIRTransformLayer(Structure): + pass + +LLVMOrcIRTransformLayerRef = ctypes.POINTER(struct_LLVMOrcOpaqueIRTransformLayer) +LLVMOrcIRTransformLayerTransformFunction = ctypes.CFUNCTYPE(ctypes.POINTER(struct_LLVMOpaqueError), ctypes.POINTER(None), ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueThreadSafeModule)), ctypes.POINTER(struct_LLVMOrcOpaqueMaterializationResponsibility)) +class struct_LLVMOrcOpaqueObjectTransformLayer(Structure): + pass + +LLVMOrcObjectTransformLayerRef = ctypes.POINTER(struct_LLVMOrcOpaqueObjectTransformLayer) +LLVMOrcObjectTransformLayerTransformFunction = ctypes.CFUNCTYPE(ctypes.POINTER(struct_LLVMOpaqueError), ctypes.POINTER(None), ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer))) +class struct_LLVMOrcOpaqueIndirectStubsManager(Structure): + pass + +LLVMOrcIndirectStubsManagerRef = ctypes.POINTER(struct_LLVMOrcOpaqueIndirectStubsManager) +class struct_LLVMOrcOpaqueLazyCallThroughManager(Structure): + pass + +LLVMOrcLazyCallThroughManagerRef = ctypes.POINTER(struct_LLVMOrcOpaqueLazyCallThroughManager) +class struct_LLVMOrcOpaqueDumpObjects(Structure): + pass + +LLVMOrcDumpObjectsRef = ctypes.POINTER(struct_LLVMOrcOpaqueDumpObjects) +try: + LLVMOrcExecutionSessionSetErrorReporter = _libraries['llvm'].LLVMOrcExecutionSessionSetErrorReporter + LLVMOrcExecutionSessionSetErrorReporter.restype = None + LLVMOrcExecutionSessionSetErrorReporter.argtypes = [LLVMOrcExecutionSessionRef, LLVMOrcErrorReporterFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcExecutionSessionGetSymbolStringPool = _libraries['llvm'].LLVMOrcExecutionSessionGetSymbolStringPool + LLVMOrcExecutionSessionGetSymbolStringPool.restype = LLVMOrcSymbolStringPoolRef + LLVMOrcExecutionSessionGetSymbolStringPool.argtypes = [LLVMOrcExecutionSessionRef] +except AttributeError: + pass +try: + LLVMOrcSymbolStringPoolClearDeadEntries = _libraries['llvm'].LLVMOrcSymbolStringPoolClearDeadEntries + LLVMOrcSymbolStringPoolClearDeadEntries.restype = None + LLVMOrcSymbolStringPoolClearDeadEntries.argtypes = [LLVMOrcSymbolStringPoolRef] +except AttributeError: + pass +try: + LLVMOrcExecutionSessionIntern = _libraries['llvm'].LLVMOrcExecutionSessionIntern + LLVMOrcExecutionSessionIntern.restype = LLVMOrcSymbolStringPoolEntryRef + LLVMOrcExecutionSessionIntern.argtypes = [LLVMOrcExecutionSessionRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcRetainSymbolStringPoolEntry = _libraries['llvm'].LLVMOrcRetainSymbolStringPoolEntry + LLVMOrcRetainSymbolStringPoolEntry.restype = None + LLVMOrcRetainSymbolStringPoolEntry.argtypes = [LLVMOrcSymbolStringPoolEntryRef] +except AttributeError: + pass +try: + LLVMOrcReleaseSymbolStringPoolEntry = _libraries['llvm'].LLVMOrcReleaseSymbolStringPoolEntry + LLVMOrcReleaseSymbolStringPoolEntry.restype = None + LLVMOrcReleaseSymbolStringPoolEntry.argtypes = [LLVMOrcSymbolStringPoolEntryRef] +except AttributeError: + pass +try: + LLVMOrcSymbolStringPoolEntryStr = _libraries['llvm'].LLVMOrcSymbolStringPoolEntryStr + LLVMOrcSymbolStringPoolEntryStr.restype = ctypes.POINTER(ctypes.c_char) + LLVMOrcSymbolStringPoolEntryStr.argtypes = [LLVMOrcSymbolStringPoolEntryRef] +except AttributeError: + pass +try: + LLVMOrcReleaseResourceTracker = _libraries['llvm'].LLVMOrcReleaseResourceTracker + LLVMOrcReleaseResourceTracker.restype = None + LLVMOrcReleaseResourceTracker.argtypes = [LLVMOrcResourceTrackerRef] +except AttributeError: + pass +try: + LLVMOrcResourceTrackerTransferTo = _libraries['llvm'].LLVMOrcResourceTrackerTransferTo + LLVMOrcResourceTrackerTransferTo.restype = None + LLVMOrcResourceTrackerTransferTo.argtypes = [LLVMOrcResourceTrackerRef, LLVMOrcResourceTrackerRef] +except AttributeError: + pass +try: + LLVMOrcResourceTrackerRemove = _libraries['llvm'].LLVMOrcResourceTrackerRemove + LLVMOrcResourceTrackerRemove.restype = LLVMErrorRef + LLVMOrcResourceTrackerRemove.argtypes = [LLVMOrcResourceTrackerRef] +except AttributeError: + pass +try: + LLVMOrcDisposeDefinitionGenerator = _libraries['llvm'].LLVMOrcDisposeDefinitionGenerator + LLVMOrcDisposeDefinitionGenerator.restype = None + LLVMOrcDisposeDefinitionGenerator.argtypes = [LLVMOrcDefinitionGeneratorRef] +except AttributeError: + pass +try: + LLVMOrcDisposeMaterializationUnit = _libraries['llvm'].LLVMOrcDisposeMaterializationUnit + LLVMOrcDisposeMaterializationUnit.restype = None + LLVMOrcDisposeMaterializationUnit.argtypes = [LLVMOrcMaterializationUnitRef] +except AttributeError: + pass +try: + LLVMOrcCreateCustomMaterializationUnit = _libraries['llvm'].LLVMOrcCreateCustomMaterializationUnit + LLVMOrcCreateCustomMaterializationUnit.restype = LLVMOrcMaterializationUnitRef + LLVMOrcCreateCustomMaterializationUnit.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None), LLVMOrcCSymbolFlagsMapPairs, size_t, LLVMOrcSymbolStringPoolEntryRef, LLVMOrcMaterializationUnitMaterializeFunction, LLVMOrcMaterializationUnitDiscardFunction, LLVMOrcMaterializationUnitDestroyFunction] +except AttributeError: + pass +try: + LLVMOrcAbsoluteSymbols = _libraries['llvm'].LLVMOrcAbsoluteSymbols + LLVMOrcAbsoluteSymbols.restype = LLVMOrcMaterializationUnitRef + LLVMOrcAbsoluteSymbols.argtypes = [LLVMOrcCSymbolMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcLazyReexports = _libraries['llvm'].LLVMOrcLazyReexports + LLVMOrcLazyReexports.restype = LLVMOrcMaterializationUnitRef + LLVMOrcLazyReexports.argtypes = [LLVMOrcLazyCallThroughManagerRef, LLVMOrcIndirectStubsManagerRef, LLVMOrcJITDylibRef, LLVMOrcCSymbolAliasMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcDisposeMaterializationResponsibility = _libraries['llvm'].LLVMOrcDisposeMaterializationResponsibility + LLVMOrcDisposeMaterializationResponsibility.restype = None + LLVMOrcDisposeMaterializationResponsibility.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityGetTargetDylib = _libraries['llvm'].LLVMOrcMaterializationResponsibilityGetTargetDylib + LLVMOrcMaterializationResponsibilityGetTargetDylib.restype = LLVMOrcJITDylibRef + LLVMOrcMaterializationResponsibilityGetTargetDylib.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityGetExecutionSession = _libraries['llvm'].LLVMOrcMaterializationResponsibilityGetExecutionSession + LLVMOrcMaterializationResponsibilityGetExecutionSession.restype = LLVMOrcExecutionSessionRef + LLVMOrcMaterializationResponsibilityGetExecutionSession.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityGetSymbols = _libraries['llvm'].LLVMOrcMaterializationResponsibilityGetSymbols + LLVMOrcMaterializationResponsibilityGetSymbols.restype = LLVMOrcCSymbolFlagsMapPairs + LLVMOrcMaterializationResponsibilityGetSymbols.argtypes = [LLVMOrcMaterializationResponsibilityRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMOrcDisposeCSymbolFlagsMap = _libraries['llvm'].LLVMOrcDisposeCSymbolFlagsMap + LLVMOrcDisposeCSymbolFlagsMap.restype = None + LLVMOrcDisposeCSymbolFlagsMap.argtypes = [LLVMOrcCSymbolFlagsMapPairs] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityGetInitializerSymbol = _libraries['llvm'].LLVMOrcMaterializationResponsibilityGetInitializerSymbol + LLVMOrcMaterializationResponsibilityGetInitializerSymbol.restype = LLVMOrcSymbolStringPoolEntryRef + LLVMOrcMaterializationResponsibilityGetInitializerSymbol.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityGetRequestedSymbols = _libraries['llvm'].LLVMOrcMaterializationResponsibilityGetRequestedSymbols + LLVMOrcMaterializationResponsibilityGetRequestedSymbols.restype = ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)) + LLVMOrcMaterializationResponsibilityGetRequestedSymbols.argtypes = [LLVMOrcMaterializationResponsibilityRef, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + LLVMOrcDisposeSymbols = _libraries['llvm'].LLVMOrcDisposeSymbols + LLVMOrcDisposeSymbols.restype = None + LLVMOrcDisposeSymbols.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry))] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityNotifyResolved = _libraries['llvm'].LLVMOrcMaterializationResponsibilityNotifyResolved + LLVMOrcMaterializationResponsibilityNotifyResolved.restype = LLVMErrorRef + LLVMOrcMaterializationResponsibilityNotifyResolved.argtypes = [LLVMOrcMaterializationResponsibilityRef, LLVMOrcCSymbolMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityNotifyEmitted = _libraries['llvm'].LLVMOrcMaterializationResponsibilityNotifyEmitted + LLVMOrcMaterializationResponsibilityNotifyEmitted.restype = LLVMErrorRef + LLVMOrcMaterializationResponsibilityNotifyEmitted.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityDefineMaterializing = _libraries['llvm'].LLVMOrcMaterializationResponsibilityDefineMaterializing + LLVMOrcMaterializationResponsibilityDefineMaterializing.restype = LLVMErrorRef + LLVMOrcMaterializationResponsibilityDefineMaterializing.argtypes = [LLVMOrcMaterializationResponsibilityRef, LLVMOrcCSymbolFlagsMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityFailMaterialization = _libraries['llvm'].LLVMOrcMaterializationResponsibilityFailMaterialization + LLVMOrcMaterializationResponsibilityFailMaterialization.restype = None + LLVMOrcMaterializationResponsibilityFailMaterialization.argtypes = [LLVMOrcMaterializationResponsibilityRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityReplace = _libraries['llvm'].LLVMOrcMaterializationResponsibilityReplace + LLVMOrcMaterializationResponsibilityReplace.restype = LLVMErrorRef + LLVMOrcMaterializationResponsibilityReplace.argtypes = [LLVMOrcMaterializationResponsibilityRef, LLVMOrcMaterializationUnitRef] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityDelegate = _libraries['llvm'].LLVMOrcMaterializationResponsibilityDelegate + LLVMOrcMaterializationResponsibilityDelegate.restype = LLVMErrorRef + LLVMOrcMaterializationResponsibilityDelegate.argtypes = [LLVMOrcMaterializationResponsibilityRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueSymbolStringPoolEntry)), size_t, ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueMaterializationResponsibility))] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityAddDependencies = _libraries['llvm'].LLVMOrcMaterializationResponsibilityAddDependencies + LLVMOrcMaterializationResponsibilityAddDependencies.restype = None + LLVMOrcMaterializationResponsibilityAddDependencies.argtypes = [LLVMOrcMaterializationResponsibilityRef, LLVMOrcSymbolStringPoolEntryRef, LLVMOrcCDependenceMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcMaterializationResponsibilityAddDependenciesForAll = _libraries['llvm'].LLVMOrcMaterializationResponsibilityAddDependenciesForAll + LLVMOrcMaterializationResponsibilityAddDependenciesForAll.restype = None + LLVMOrcMaterializationResponsibilityAddDependenciesForAll.argtypes = [LLVMOrcMaterializationResponsibilityRef, LLVMOrcCDependenceMapPairs, size_t] +except AttributeError: + pass +try: + LLVMOrcExecutionSessionCreateBareJITDylib = _libraries['llvm'].LLVMOrcExecutionSessionCreateBareJITDylib + LLVMOrcExecutionSessionCreateBareJITDylib.restype = LLVMOrcJITDylibRef + LLVMOrcExecutionSessionCreateBareJITDylib.argtypes = [LLVMOrcExecutionSessionRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcExecutionSessionCreateJITDylib = _libraries['llvm'].LLVMOrcExecutionSessionCreateJITDylib + LLVMOrcExecutionSessionCreateJITDylib.restype = LLVMErrorRef + LLVMOrcExecutionSessionCreateJITDylib.argtypes = [LLVMOrcExecutionSessionRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueJITDylib)), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcExecutionSessionGetJITDylibByName = _libraries['llvm'].LLVMOrcExecutionSessionGetJITDylibByName + LLVMOrcExecutionSessionGetJITDylibByName.restype = LLVMOrcJITDylibRef + LLVMOrcExecutionSessionGetJITDylibByName.argtypes = [LLVMOrcExecutionSessionRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcJITDylibCreateResourceTracker = _libraries['llvm'].LLVMOrcJITDylibCreateResourceTracker + LLVMOrcJITDylibCreateResourceTracker.restype = LLVMOrcResourceTrackerRef + LLVMOrcJITDylibCreateResourceTracker.argtypes = [LLVMOrcJITDylibRef] +except AttributeError: + pass +try: + LLVMOrcJITDylibGetDefaultResourceTracker = _libraries['llvm'].LLVMOrcJITDylibGetDefaultResourceTracker + LLVMOrcJITDylibGetDefaultResourceTracker.restype = LLVMOrcResourceTrackerRef + LLVMOrcJITDylibGetDefaultResourceTracker.argtypes = [LLVMOrcJITDylibRef] +except AttributeError: + pass +try: + LLVMOrcJITDylibDefine = _libraries['llvm'].LLVMOrcJITDylibDefine + LLVMOrcJITDylibDefine.restype = LLVMErrorRef + LLVMOrcJITDylibDefine.argtypes = [LLVMOrcJITDylibRef, LLVMOrcMaterializationUnitRef] +except AttributeError: + pass +try: + LLVMOrcJITDylibClear = _libraries['llvm'].LLVMOrcJITDylibClear + LLVMOrcJITDylibClear.restype = LLVMErrorRef + LLVMOrcJITDylibClear.argtypes = [LLVMOrcJITDylibRef] +except AttributeError: + pass +try: + LLVMOrcJITDylibAddGenerator = _libraries['llvm'].LLVMOrcJITDylibAddGenerator + LLVMOrcJITDylibAddGenerator.restype = None + LLVMOrcJITDylibAddGenerator.argtypes = [LLVMOrcJITDylibRef, LLVMOrcDefinitionGeneratorRef] +except AttributeError: + pass +try: + LLVMOrcCreateCustomCAPIDefinitionGenerator = _libraries['llvm'].LLVMOrcCreateCustomCAPIDefinitionGenerator + LLVMOrcCreateCustomCAPIDefinitionGenerator.restype = LLVMOrcDefinitionGeneratorRef + LLVMOrcCreateCustomCAPIDefinitionGenerator.argtypes = [LLVMOrcCAPIDefinitionGeneratorTryToGenerateFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcCreateDynamicLibrarySearchGeneratorForProcess = _libraries['llvm'].LLVMOrcCreateDynamicLibrarySearchGeneratorForProcess + LLVMOrcCreateDynamicLibrarySearchGeneratorForProcess.restype = LLVMErrorRef + LLVMOrcCreateDynamicLibrarySearchGeneratorForProcess.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueDefinitionGenerator)), ctypes.c_char, LLVMOrcSymbolPredicate, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcCreateDynamicLibrarySearchGeneratorForPath = _libraries['llvm'].LLVMOrcCreateDynamicLibrarySearchGeneratorForPath + LLVMOrcCreateDynamicLibrarySearchGeneratorForPath.restype = LLVMErrorRef + LLVMOrcCreateDynamicLibrarySearchGeneratorForPath.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueDefinitionGenerator)), ctypes.POINTER(ctypes.c_char), ctypes.c_char, LLVMOrcSymbolPredicate, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcCreateStaticLibrarySearchGeneratorForPath = _libraries['llvm'].LLVMOrcCreateStaticLibrarySearchGeneratorForPath + LLVMOrcCreateStaticLibrarySearchGeneratorForPath.restype = LLVMErrorRef + LLVMOrcCreateStaticLibrarySearchGeneratorForPath.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueDefinitionGenerator)), LLVMOrcObjectLayerRef, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcCreateNewThreadSafeContext = _libraries['llvm'].LLVMOrcCreateNewThreadSafeContext + LLVMOrcCreateNewThreadSafeContext.restype = LLVMOrcThreadSafeContextRef + LLVMOrcCreateNewThreadSafeContext.argtypes = [] +except AttributeError: + pass +try: + LLVMOrcThreadSafeContextGetContext = _libraries['llvm'].LLVMOrcThreadSafeContextGetContext + LLVMOrcThreadSafeContextGetContext.restype = LLVMContextRef + LLVMOrcThreadSafeContextGetContext.argtypes = [LLVMOrcThreadSafeContextRef] +except AttributeError: + pass +try: + LLVMOrcDisposeThreadSafeContext = _libraries['llvm'].LLVMOrcDisposeThreadSafeContext + LLVMOrcDisposeThreadSafeContext.restype = None + LLVMOrcDisposeThreadSafeContext.argtypes = [LLVMOrcThreadSafeContextRef] +except AttributeError: + pass +try: + LLVMOrcCreateNewThreadSafeModule = _libraries['llvm'].LLVMOrcCreateNewThreadSafeModule + LLVMOrcCreateNewThreadSafeModule.restype = LLVMOrcThreadSafeModuleRef + LLVMOrcCreateNewThreadSafeModule.argtypes = [LLVMModuleRef, LLVMOrcThreadSafeContextRef] +except AttributeError: + pass +try: + LLVMOrcDisposeThreadSafeModule = _libraries['llvm'].LLVMOrcDisposeThreadSafeModule + LLVMOrcDisposeThreadSafeModule.restype = None + LLVMOrcDisposeThreadSafeModule.argtypes = [LLVMOrcThreadSafeModuleRef] +except AttributeError: + pass +try: + LLVMOrcThreadSafeModuleWithModuleDo = _libraries['llvm'].LLVMOrcThreadSafeModuleWithModuleDo + LLVMOrcThreadSafeModuleWithModuleDo.restype = LLVMErrorRef + LLVMOrcThreadSafeModuleWithModuleDo.argtypes = [LLVMOrcThreadSafeModuleRef, LLVMOrcGenericIRModuleOperationFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcJITTargetMachineBuilderDetectHost = _libraries['llvm'].LLVMOrcJITTargetMachineBuilderDetectHost + LLVMOrcJITTargetMachineBuilderDetectHost.restype = LLVMErrorRef + LLVMOrcJITTargetMachineBuilderDetectHost.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueJITTargetMachineBuilder))] +except AttributeError: + pass +try: + LLVMOrcJITTargetMachineBuilderCreateFromTargetMachine = _libraries['llvm'].LLVMOrcJITTargetMachineBuilderCreateFromTargetMachine + LLVMOrcJITTargetMachineBuilderCreateFromTargetMachine.restype = LLVMOrcJITTargetMachineBuilderRef + LLVMOrcJITTargetMachineBuilderCreateFromTargetMachine.argtypes = [LLVMTargetMachineRef] +except AttributeError: + pass +try: + LLVMOrcDisposeJITTargetMachineBuilder = _libraries['llvm'].LLVMOrcDisposeJITTargetMachineBuilder + LLVMOrcDisposeJITTargetMachineBuilder.restype = None + LLVMOrcDisposeJITTargetMachineBuilder.argtypes = [LLVMOrcJITTargetMachineBuilderRef] +except AttributeError: + pass +try: + LLVMOrcJITTargetMachineBuilderGetTargetTriple = _libraries['llvm'].LLVMOrcJITTargetMachineBuilderGetTargetTriple + LLVMOrcJITTargetMachineBuilderGetTargetTriple.restype = ctypes.POINTER(ctypes.c_char) + LLVMOrcJITTargetMachineBuilderGetTargetTriple.argtypes = [LLVMOrcJITTargetMachineBuilderRef] +except AttributeError: + pass +try: + LLVMOrcJITTargetMachineBuilderSetTargetTriple = _libraries['llvm'].LLVMOrcJITTargetMachineBuilderSetTargetTriple + LLVMOrcJITTargetMachineBuilderSetTargetTriple.restype = None + LLVMOrcJITTargetMachineBuilderSetTargetTriple.argtypes = [LLVMOrcJITTargetMachineBuilderRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcObjectLayerAddObjectFile = _libraries['llvm'].LLVMOrcObjectLayerAddObjectFile + LLVMOrcObjectLayerAddObjectFile.restype = LLVMErrorRef + LLVMOrcObjectLayerAddObjectFile.argtypes = [LLVMOrcObjectLayerRef, LLVMOrcJITDylibRef, LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMOrcObjectLayerAddObjectFileWithRT = _libraries['llvm'].LLVMOrcObjectLayerAddObjectFileWithRT + LLVMOrcObjectLayerAddObjectFileWithRT.restype = LLVMErrorRef + LLVMOrcObjectLayerAddObjectFileWithRT.argtypes = [LLVMOrcObjectLayerRef, LLVMOrcResourceTrackerRef, LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMOrcObjectLayerEmit = _libraries['llvm'].LLVMOrcObjectLayerEmit + LLVMOrcObjectLayerEmit.restype = None + LLVMOrcObjectLayerEmit.argtypes = [LLVMOrcObjectLayerRef, LLVMOrcMaterializationResponsibilityRef, LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMOrcDisposeObjectLayer = _libraries['llvm'].LLVMOrcDisposeObjectLayer + LLVMOrcDisposeObjectLayer.restype = None + LLVMOrcDisposeObjectLayer.argtypes = [LLVMOrcObjectLayerRef] +except AttributeError: + pass +try: + LLVMOrcIRTransformLayerEmit = _libraries['llvm'].LLVMOrcIRTransformLayerEmit + LLVMOrcIRTransformLayerEmit.restype = None + LLVMOrcIRTransformLayerEmit.argtypes = [LLVMOrcIRTransformLayerRef, LLVMOrcMaterializationResponsibilityRef, LLVMOrcThreadSafeModuleRef] +except AttributeError: + pass +try: + LLVMOrcIRTransformLayerSetTransform = _libraries['llvm'].LLVMOrcIRTransformLayerSetTransform + LLVMOrcIRTransformLayerSetTransform.restype = None + LLVMOrcIRTransformLayerSetTransform.argtypes = [LLVMOrcIRTransformLayerRef, LLVMOrcIRTransformLayerTransformFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcObjectTransformLayerSetTransform = _libraries['llvm'].LLVMOrcObjectTransformLayerSetTransform + LLVMOrcObjectTransformLayerSetTransform.restype = None + LLVMOrcObjectTransformLayerSetTransform.argtypes = [LLVMOrcObjectTransformLayerRef, LLVMOrcObjectTransformLayerTransformFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcCreateLocalIndirectStubsManager = _libraries['llvm'].LLVMOrcCreateLocalIndirectStubsManager + LLVMOrcCreateLocalIndirectStubsManager.restype = LLVMOrcIndirectStubsManagerRef + LLVMOrcCreateLocalIndirectStubsManager.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcDisposeIndirectStubsManager = _libraries['llvm'].LLVMOrcDisposeIndirectStubsManager + LLVMOrcDisposeIndirectStubsManager.restype = None + LLVMOrcDisposeIndirectStubsManager.argtypes = [LLVMOrcIndirectStubsManagerRef] +except AttributeError: + pass +try: + LLVMOrcCreateLocalLazyCallThroughManager = _libraries['llvm'].LLVMOrcCreateLocalLazyCallThroughManager + LLVMOrcCreateLocalLazyCallThroughManager.restype = LLVMErrorRef + LLVMOrcCreateLocalLazyCallThroughManager.argtypes = [ctypes.POINTER(ctypes.c_char), LLVMOrcExecutionSessionRef, LLVMOrcJITTargetAddress, ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueLazyCallThroughManager))] +except AttributeError: + pass +try: + LLVMOrcDisposeLazyCallThroughManager = _libraries['llvm'].LLVMOrcDisposeLazyCallThroughManager + LLVMOrcDisposeLazyCallThroughManager.restype = None + LLVMOrcDisposeLazyCallThroughManager.argtypes = [LLVMOrcLazyCallThroughManagerRef] +except AttributeError: + pass +try: + LLVMOrcCreateDumpObjects = _libraries['llvm'].LLVMOrcCreateDumpObjects + LLVMOrcCreateDumpObjects.restype = LLVMOrcDumpObjectsRef + LLVMOrcCreateDumpObjects.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcDisposeDumpObjects = _libraries['llvm'].LLVMOrcDisposeDumpObjects + LLVMOrcDisposeDumpObjects.restype = None + LLVMOrcDisposeDumpObjects.argtypes = [LLVMOrcDumpObjectsRef] +except AttributeError: + pass +try: + LLVMOrcDumpObjects_CallOperator = _libraries['llvm'].LLVMOrcDumpObjects_CallOperator + LLVMOrcDumpObjects_CallOperator.restype = LLVMErrorRef + LLVMOrcDumpObjects_CallOperator.argtypes = [LLVMOrcDumpObjectsRef, ctypes.POINTER(ctypes.POINTER(struct_LLVMOpaqueMemoryBuffer))] +except AttributeError: + pass +LLVMOrcLLJITBuilderObjectLinkingLayerCreatorFunction = ctypes.CFUNCTYPE(ctypes.POINTER(struct_LLVMOrcOpaqueObjectLayer), ctypes.POINTER(None), ctypes.POINTER(struct_LLVMOrcOpaqueExecutionSession), ctypes.POINTER(ctypes.c_char)) +class struct_LLVMOrcOpaqueLLJITBuilder(Structure): + pass + +LLVMOrcLLJITBuilderRef = ctypes.POINTER(struct_LLVMOrcOpaqueLLJITBuilder) +class struct_LLVMOrcOpaqueLLJIT(Structure): + pass + +LLVMOrcLLJITRef = ctypes.POINTER(struct_LLVMOrcOpaqueLLJIT) +try: + LLVMOrcCreateLLJITBuilder = _libraries['llvm'].LLVMOrcCreateLLJITBuilder + LLVMOrcCreateLLJITBuilder.restype = LLVMOrcLLJITBuilderRef + LLVMOrcCreateLLJITBuilder.argtypes = [] +except AttributeError: + pass +try: + LLVMOrcDisposeLLJITBuilder = _libraries['llvm'].LLVMOrcDisposeLLJITBuilder + LLVMOrcDisposeLLJITBuilder.restype = None + LLVMOrcDisposeLLJITBuilder.argtypes = [LLVMOrcLLJITBuilderRef] +except AttributeError: + pass +try: + LLVMOrcLLJITBuilderSetJITTargetMachineBuilder = _libraries['llvm'].LLVMOrcLLJITBuilderSetJITTargetMachineBuilder + LLVMOrcLLJITBuilderSetJITTargetMachineBuilder.restype = None + LLVMOrcLLJITBuilderSetJITTargetMachineBuilder.argtypes = [LLVMOrcLLJITBuilderRef, LLVMOrcJITTargetMachineBuilderRef] +except AttributeError: + pass +try: + LLVMOrcLLJITBuilderSetObjectLinkingLayerCreator = _libraries['llvm'].LLVMOrcLLJITBuilderSetObjectLinkingLayerCreator + LLVMOrcLLJITBuilderSetObjectLinkingLayerCreator.restype = None + LLVMOrcLLJITBuilderSetObjectLinkingLayerCreator.argtypes = [LLVMOrcLLJITBuilderRef, LLVMOrcLLJITBuilderObjectLinkingLayerCreatorFunction, ctypes.POINTER(None)] +except AttributeError: + pass +try: + LLVMOrcCreateLLJIT = _libraries['llvm'].LLVMOrcCreateLLJIT + LLVMOrcCreateLLJIT.restype = LLVMErrorRef + LLVMOrcCreateLLJIT.argtypes = [ctypes.POINTER(ctypes.POINTER(struct_LLVMOrcOpaqueLLJIT)), LLVMOrcLLJITBuilderRef] +except AttributeError: + pass +try: + LLVMOrcDisposeLLJIT = _libraries['llvm'].LLVMOrcDisposeLLJIT + LLVMOrcDisposeLLJIT.restype = LLVMErrorRef + LLVMOrcDisposeLLJIT.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetExecutionSession = _libraries['llvm'].LLVMOrcLLJITGetExecutionSession + LLVMOrcLLJITGetExecutionSession.restype = LLVMOrcExecutionSessionRef + LLVMOrcLLJITGetExecutionSession.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetMainJITDylib = _libraries['llvm'].LLVMOrcLLJITGetMainJITDylib + LLVMOrcLLJITGetMainJITDylib.restype = LLVMOrcJITDylibRef + LLVMOrcLLJITGetMainJITDylib.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetTripleString = _libraries['llvm'].LLVMOrcLLJITGetTripleString + LLVMOrcLLJITGetTripleString.restype = ctypes.POINTER(ctypes.c_char) + LLVMOrcLLJITGetTripleString.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetGlobalPrefix = _libraries['llvm'].LLVMOrcLLJITGetGlobalPrefix + LLVMOrcLLJITGetGlobalPrefix.restype = ctypes.c_char + LLVMOrcLLJITGetGlobalPrefix.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITMangleAndIntern = _libraries['llvm'].LLVMOrcLLJITMangleAndIntern + LLVMOrcLLJITMangleAndIntern.restype = LLVMOrcSymbolStringPoolEntryRef + LLVMOrcLLJITMangleAndIntern.argtypes = [LLVMOrcLLJITRef, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcLLJITAddObjectFile = _libraries['llvm'].LLVMOrcLLJITAddObjectFile + LLVMOrcLLJITAddObjectFile.restype = LLVMErrorRef + LLVMOrcLLJITAddObjectFile.argtypes = [LLVMOrcLLJITRef, LLVMOrcJITDylibRef, LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMOrcLLJITAddObjectFileWithRT = _libraries['llvm'].LLVMOrcLLJITAddObjectFileWithRT + LLVMOrcLLJITAddObjectFileWithRT.restype = LLVMErrorRef + LLVMOrcLLJITAddObjectFileWithRT.argtypes = [LLVMOrcLLJITRef, LLVMOrcResourceTrackerRef, LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMOrcLLJITAddLLVMIRModule = _libraries['llvm'].LLVMOrcLLJITAddLLVMIRModule + LLVMOrcLLJITAddLLVMIRModule.restype = LLVMErrorRef + LLVMOrcLLJITAddLLVMIRModule.argtypes = [LLVMOrcLLJITRef, LLVMOrcJITDylibRef, LLVMOrcThreadSafeModuleRef] +except AttributeError: + pass +try: + LLVMOrcLLJITAddLLVMIRModuleWithRT = _libraries['llvm'].LLVMOrcLLJITAddLLVMIRModuleWithRT + LLVMOrcLLJITAddLLVMIRModuleWithRT.restype = LLVMErrorRef + LLVMOrcLLJITAddLLVMIRModuleWithRT.argtypes = [LLVMOrcLLJITRef, LLVMOrcResourceTrackerRef, LLVMOrcThreadSafeModuleRef] +except AttributeError: + pass +try: + LLVMOrcLLJITLookup = _libraries['llvm'].LLVMOrcLLJITLookup + LLVMOrcLLJITLookup.restype = LLVMErrorRef + LLVMOrcLLJITLookup.argtypes = [LLVMOrcLLJITRef, ctypes.POINTER(ctypes.c_uint64), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMOrcLLJITGetObjLinkingLayer = _libraries['llvm'].LLVMOrcLLJITGetObjLinkingLayer + LLVMOrcLLJITGetObjLinkingLayer.restype = LLVMOrcObjectLayerRef + LLVMOrcLLJITGetObjLinkingLayer.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetObjTransformLayer = _libraries['llvm'].LLVMOrcLLJITGetObjTransformLayer + LLVMOrcLLJITGetObjTransformLayer.restype = LLVMOrcObjectTransformLayerRef + LLVMOrcLLJITGetObjTransformLayer.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetIRTransformLayer = _libraries['llvm'].LLVMOrcLLJITGetIRTransformLayer + LLVMOrcLLJITGetIRTransformLayer.restype = LLVMOrcIRTransformLayerRef + LLVMOrcLLJITGetIRTransformLayer.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +try: + LLVMOrcLLJITGetDataLayoutStr = _libraries['llvm'].LLVMOrcLLJITGetDataLayoutStr + LLVMOrcLLJITGetDataLayoutStr.restype = ctypes.POINTER(ctypes.c_char) + LLVMOrcLLJITGetDataLayoutStr.argtypes = [LLVMOrcLLJITRef] +except AttributeError: + pass +LLVM_C_LINKER_H = True # macro + +# values for enumeration 'c__EA_LLVMLinkerMode' +c__EA_LLVMLinkerMode__enumvalues = { + 0: 'LLVMLinkerDestroySource', + 1: 'LLVMLinkerPreserveSource_Removed', +} +LLVMLinkerDestroySource = 0 +LLVMLinkerPreserveSource_Removed = 1 +c__EA_LLVMLinkerMode = ctypes.c_uint32 # enum +LLVMLinkerMode = c__EA_LLVMLinkerMode +LLVMLinkerMode__enumvalues = c__EA_LLVMLinkerMode__enumvalues +try: + LLVMLinkModules2 = _libraries['llvm'].LLVMLinkModules2 + LLVMLinkModules2.restype = LLVMBool + LLVMLinkModules2.argtypes = [LLVMModuleRef, LLVMModuleRef] +except AttributeError: + pass +LLVM_C_OBJECT_H = True # macro +class struct_LLVMOpaqueSectionIterator(Structure): + pass + +LLVMSectionIteratorRef = ctypes.POINTER(struct_LLVMOpaqueSectionIterator) +class struct_LLVMOpaqueSymbolIterator(Structure): + pass + +LLVMSymbolIteratorRef = ctypes.POINTER(struct_LLVMOpaqueSymbolIterator) +class struct_LLVMOpaqueRelocationIterator(Structure): + pass + +LLVMRelocationIteratorRef = ctypes.POINTER(struct_LLVMOpaqueRelocationIterator) + +# values for enumeration 'c__EA_LLVMBinaryType' +c__EA_LLVMBinaryType__enumvalues = { + 0: 'LLVMBinaryTypeArchive', + 1: 'LLVMBinaryTypeMachOUniversalBinary', + 2: 'LLVMBinaryTypeCOFFImportFile', + 3: 'LLVMBinaryTypeIR', + 4: 'LLVMBinaryTypeWinRes', + 5: 'LLVMBinaryTypeCOFF', + 6: 'LLVMBinaryTypeELF32L', + 7: 'LLVMBinaryTypeELF32B', + 8: 'LLVMBinaryTypeELF64L', + 9: 'LLVMBinaryTypeELF64B', + 10: 'LLVMBinaryTypeMachO32L', + 11: 'LLVMBinaryTypeMachO32B', + 12: 'LLVMBinaryTypeMachO64L', + 13: 'LLVMBinaryTypeMachO64B', + 14: 'LLVMBinaryTypeWasm', +} +LLVMBinaryTypeArchive = 0 +LLVMBinaryTypeMachOUniversalBinary = 1 +LLVMBinaryTypeCOFFImportFile = 2 +LLVMBinaryTypeIR = 3 +LLVMBinaryTypeWinRes = 4 +LLVMBinaryTypeCOFF = 5 +LLVMBinaryTypeELF32L = 6 +LLVMBinaryTypeELF32B = 7 +LLVMBinaryTypeELF64L = 8 +LLVMBinaryTypeELF64B = 9 +LLVMBinaryTypeMachO32L = 10 +LLVMBinaryTypeMachO32B = 11 +LLVMBinaryTypeMachO64L = 12 +LLVMBinaryTypeMachO64B = 13 +LLVMBinaryTypeWasm = 14 +c__EA_LLVMBinaryType = ctypes.c_uint32 # enum +LLVMBinaryType = c__EA_LLVMBinaryType +LLVMBinaryType__enumvalues = c__EA_LLVMBinaryType__enumvalues +try: + LLVMCreateBinary = _libraries['llvm'].LLVMCreateBinary + LLVMCreateBinary.restype = LLVMBinaryRef + LLVMCreateBinary.argtypes = [LLVMMemoryBufferRef, LLVMContextRef, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMDisposeBinary = _libraries['llvm'].LLVMDisposeBinary + LLVMDisposeBinary.restype = None + LLVMDisposeBinary.argtypes = [LLVMBinaryRef] +except AttributeError: + pass +try: + LLVMBinaryCopyMemoryBuffer = _libraries['llvm'].LLVMBinaryCopyMemoryBuffer + LLVMBinaryCopyMemoryBuffer.restype = LLVMMemoryBufferRef + LLVMBinaryCopyMemoryBuffer.argtypes = [LLVMBinaryRef] +except AttributeError: + pass +try: + LLVMBinaryGetType = _libraries['llvm'].LLVMBinaryGetType + LLVMBinaryGetType.restype = LLVMBinaryType + LLVMBinaryGetType.argtypes = [LLVMBinaryRef] +except AttributeError: + pass +try: + LLVMMachOUniversalBinaryCopyObjectForArch = _libraries['llvm'].LLVMMachOUniversalBinaryCopyObjectForArch + LLVMMachOUniversalBinaryCopyObjectForArch.restype = LLVMBinaryRef + LLVMMachOUniversalBinaryCopyObjectForArch.argtypes = [LLVMBinaryRef, ctypes.POINTER(ctypes.c_char), size_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + LLVMObjectFileCopySectionIterator = _libraries['llvm'].LLVMObjectFileCopySectionIterator + LLVMObjectFileCopySectionIterator.restype = LLVMSectionIteratorRef + LLVMObjectFileCopySectionIterator.argtypes = [LLVMBinaryRef] +except AttributeError: + pass +try: + LLVMObjectFileIsSectionIteratorAtEnd = _libraries['llvm'].LLVMObjectFileIsSectionIteratorAtEnd + LLVMObjectFileIsSectionIteratorAtEnd.restype = LLVMBool + LLVMObjectFileIsSectionIteratorAtEnd.argtypes = [LLVMBinaryRef, LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMObjectFileCopySymbolIterator = _libraries['llvm'].LLVMObjectFileCopySymbolIterator + LLVMObjectFileCopySymbolIterator.restype = LLVMSymbolIteratorRef + LLVMObjectFileCopySymbolIterator.argtypes = [LLVMBinaryRef] +except AttributeError: + pass +try: + LLVMObjectFileIsSymbolIteratorAtEnd = _libraries['llvm'].LLVMObjectFileIsSymbolIteratorAtEnd + LLVMObjectFileIsSymbolIteratorAtEnd.restype = LLVMBool + LLVMObjectFileIsSymbolIteratorAtEnd.argtypes = [LLVMBinaryRef, LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMDisposeSectionIterator = _libraries['llvm'].LLVMDisposeSectionIterator + LLVMDisposeSectionIterator.restype = None + LLVMDisposeSectionIterator.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMMoveToNextSection = _libraries['llvm'].LLVMMoveToNextSection + LLVMMoveToNextSection.restype = None + LLVMMoveToNextSection.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMMoveToContainingSection = _libraries['llvm'].LLVMMoveToContainingSection + LLVMMoveToContainingSection.restype = None + LLVMMoveToContainingSection.argtypes = [LLVMSectionIteratorRef, LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMDisposeSymbolIterator = _libraries['llvm'].LLVMDisposeSymbolIterator + LLVMDisposeSymbolIterator.restype = None + LLVMDisposeSymbolIterator.argtypes = [LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMMoveToNextSymbol = _libraries['llvm'].LLVMMoveToNextSymbol + LLVMMoveToNextSymbol.restype = None + LLVMMoveToNextSymbol.argtypes = [LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMGetSectionName = _libraries['llvm'].LLVMGetSectionName + LLVMGetSectionName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetSectionName.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMGetSectionSize = _libraries['llvm'].LLVMGetSectionSize + LLVMGetSectionSize.restype = uint64_t + LLVMGetSectionSize.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMGetSectionContents = _libraries['llvm'].LLVMGetSectionContents + LLVMGetSectionContents.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetSectionContents.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMGetSectionAddress = _libraries['llvm'].LLVMGetSectionAddress + LLVMGetSectionAddress.restype = uint64_t + LLVMGetSectionAddress.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMGetSectionContainsSymbol = _libraries['llvm'].LLVMGetSectionContainsSymbol + LLVMGetSectionContainsSymbol.restype = LLVMBool + LLVMGetSectionContainsSymbol.argtypes = [LLVMSectionIteratorRef, LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocations = _libraries['llvm'].LLVMGetRelocations + LLVMGetRelocations.restype = LLVMRelocationIteratorRef + LLVMGetRelocations.argtypes = [LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMDisposeRelocationIterator = _libraries['llvm'].LLVMDisposeRelocationIterator + LLVMDisposeRelocationIterator.restype = None + LLVMDisposeRelocationIterator.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMIsRelocationIteratorAtEnd = _libraries['llvm'].LLVMIsRelocationIteratorAtEnd + LLVMIsRelocationIteratorAtEnd.restype = LLVMBool + LLVMIsRelocationIteratorAtEnd.argtypes = [LLVMSectionIteratorRef, LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMMoveToNextRelocation = _libraries['llvm'].LLVMMoveToNextRelocation + LLVMMoveToNextRelocation.restype = None + LLVMMoveToNextRelocation.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMGetSymbolName = _libraries['llvm'].LLVMGetSymbolName + LLVMGetSymbolName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetSymbolName.argtypes = [LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMGetSymbolAddress = _libraries['llvm'].LLVMGetSymbolAddress + LLVMGetSymbolAddress.restype = uint64_t + LLVMGetSymbolAddress.argtypes = [LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMGetSymbolSize = _libraries['llvm'].LLVMGetSymbolSize + LLVMGetSymbolSize.restype = uint64_t + LLVMGetSymbolSize.argtypes = [LLVMSymbolIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocationOffset = _libraries['llvm'].LLVMGetRelocationOffset + LLVMGetRelocationOffset.restype = uint64_t + LLVMGetRelocationOffset.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocationSymbol = _libraries['llvm'].LLVMGetRelocationSymbol + LLVMGetRelocationSymbol.restype = LLVMSymbolIteratorRef + LLVMGetRelocationSymbol.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocationType = _libraries['llvm'].LLVMGetRelocationType + LLVMGetRelocationType.restype = uint64_t + LLVMGetRelocationType.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocationTypeName = _libraries['llvm'].LLVMGetRelocationTypeName + LLVMGetRelocationTypeName.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetRelocationTypeName.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +try: + LLVMGetRelocationValueString = _libraries['llvm'].LLVMGetRelocationValueString + LLVMGetRelocationValueString.restype = ctypes.POINTER(ctypes.c_char) + LLVMGetRelocationValueString.argtypes = [LLVMRelocationIteratorRef] +except AttributeError: + pass +class struct_LLVMOpaqueObjectFile(Structure): + pass + +LLVMObjectFileRef = ctypes.POINTER(struct_LLVMOpaqueObjectFile) +try: + LLVMCreateObjectFile = _libraries['llvm'].LLVMCreateObjectFile + LLVMCreateObjectFile.restype = LLVMObjectFileRef + LLVMCreateObjectFile.argtypes = [LLVMMemoryBufferRef] +except AttributeError: + pass +try: + LLVMDisposeObjectFile = _libraries['llvm'].LLVMDisposeObjectFile + LLVMDisposeObjectFile.restype = None + LLVMDisposeObjectFile.argtypes = [LLVMObjectFileRef] +except AttributeError: + pass +try: + LLVMGetSections = _libraries['llvm'].LLVMGetSections + LLVMGetSections.restype = LLVMSectionIteratorRef + LLVMGetSections.argtypes = [LLVMObjectFileRef] +except AttributeError: + pass +try: + LLVMIsSectionIteratorAtEnd = _libraries['llvm'].LLVMIsSectionIteratorAtEnd + LLVMIsSectionIteratorAtEnd.restype = LLVMBool + LLVMIsSectionIteratorAtEnd.argtypes = [LLVMObjectFileRef, LLVMSectionIteratorRef] +except AttributeError: + pass +try: + LLVMGetSymbols = _libraries['llvm'].LLVMGetSymbols + LLVMGetSymbols.restype = LLVMSymbolIteratorRef + LLVMGetSymbols.argtypes = [LLVMObjectFileRef] +except AttributeError: + pass +try: + LLVMIsSymbolIteratorAtEnd = _libraries['llvm'].LLVMIsSymbolIteratorAtEnd + LLVMIsSymbolIteratorAtEnd.restype = LLVMBool + LLVMIsSymbolIteratorAtEnd.argtypes = [LLVMObjectFileRef, LLVMSymbolIteratorRef] +except AttributeError: + pass +LLVM_C_ORCEE_H = True # macro +try: + LLVMOrcCreateRTDyldObjectLinkingLayerWithSectionMemoryManager = _libraries['llvm'].LLVMOrcCreateRTDyldObjectLinkingLayerWithSectionMemoryManager + LLVMOrcCreateRTDyldObjectLinkingLayerWithSectionMemoryManager.restype = LLVMOrcObjectLayerRef + LLVMOrcCreateRTDyldObjectLinkingLayerWithSectionMemoryManager.argtypes = [LLVMOrcExecutionSessionRef] +except AttributeError: + pass +try: + LLVMOrcRTDyldObjectLinkingLayerRegisterJITEventListener = _libraries['llvm'].LLVMOrcRTDyldObjectLinkingLayerRegisterJITEventListener + LLVMOrcRTDyldObjectLinkingLayerRegisterJITEventListener.restype = None + LLVMOrcRTDyldObjectLinkingLayerRegisterJITEventListener.argtypes = [LLVMOrcObjectLayerRef, LLVMJITEventListenerRef] +except AttributeError: + pass +LLVM_C_REMARKS_H = True # macro +REMARKS_API_VERSION = 1 # macro + +# values for enumeration 'LLVMRemarkType' +LLVMRemarkType__enumvalues = { + 0: 'LLVMRemarkTypeUnknown', + 1: 'LLVMRemarkTypePassed', + 2: 'LLVMRemarkTypeMissed', + 3: 'LLVMRemarkTypeAnalysis', + 4: 'LLVMRemarkTypeAnalysisFPCommute', + 5: 'LLVMRemarkTypeAnalysisAliasing', + 6: 'LLVMRemarkTypeFailure', +} +LLVMRemarkTypeUnknown = 0 +LLVMRemarkTypePassed = 1 +LLVMRemarkTypeMissed = 2 +LLVMRemarkTypeAnalysis = 3 +LLVMRemarkTypeAnalysisFPCommute = 4 +LLVMRemarkTypeAnalysisAliasing = 5 +LLVMRemarkTypeFailure = 6 +LLVMRemarkType = ctypes.c_uint32 # enum +class struct_LLVMRemarkOpaqueString(Structure): + pass + +LLVMRemarkStringRef = ctypes.POINTER(struct_LLVMRemarkOpaqueString) +try: + LLVMRemarkStringGetData = _libraries['llvm'].LLVMRemarkStringGetData + LLVMRemarkStringGetData.restype = ctypes.POINTER(ctypes.c_char) + LLVMRemarkStringGetData.argtypes = [LLVMRemarkStringRef] +except AttributeError: + pass +try: + LLVMRemarkStringGetLen = _libraries['llvm'].LLVMRemarkStringGetLen + LLVMRemarkStringGetLen.restype = uint32_t + LLVMRemarkStringGetLen.argtypes = [LLVMRemarkStringRef] +except AttributeError: + pass +class struct_LLVMRemarkOpaqueDebugLoc(Structure): + pass + +LLVMRemarkDebugLocRef = ctypes.POINTER(struct_LLVMRemarkOpaqueDebugLoc) +try: + LLVMRemarkDebugLocGetSourceFilePath = _libraries['llvm'].LLVMRemarkDebugLocGetSourceFilePath + LLVMRemarkDebugLocGetSourceFilePath.restype = LLVMRemarkStringRef + LLVMRemarkDebugLocGetSourceFilePath.argtypes = [LLVMRemarkDebugLocRef] +except AttributeError: + pass +try: + LLVMRemarkDebugLocGetSourceLine = _libraries['llvm'].LLVMRemarkDebugLocGetSourceLine + LLVMRemarkDebugLocGetSourceLine.restype = uint32_t + LLVMRemarkDebugLocGetSourceLine.argtypes = [LLVMRemarkDebugLocRef] +except AttributeError: + pass +try: + LLVMRemarkDebugLocGetSourceColumn = _libraries['llvm'].LLVMRemarkDebugLocGetSourceColumn + LLVMRemarkDebugLocGetSourceColumn.restype = uint32_t + LLVMRemarkDebugLocGetSourceColumn.argtypes = [LLVMRemarkDebugLocRef] +except AttributeError: + pass +class struct_LLVMRemarkOpaqueArg(Structure): + pass + +LLVMRemarkArgRef = ctypes.POINTER(struct_LLVMRemarkOpaqueArg) +try: + LLVMRemarkArgGetKey = _libraries['llvm'].LLVMRemarkArgGetKey + LLVMRemarkArgGetKey.restype = LLVMRemarkStringRef + LLVMRemarkArgGetKey.argtypes = [LLVMRemarkArgRef] +except AttributeError: + pass +try: + LLVMRemarkArgGetValue = _libraries['llvm'].LLVMRemarkArgGetValue + LLVMRemarkArgGetValue.restype = LLVMRemarkStringRef + LLVMRemarkArgGetValue.argtypes = [LLVMRemarkArgRef] +except AttributeError: + pass +try: + LLVMRemarkArgGetDebugLoc = _libraries['llvm'].LLVMRemarkArgGetDebugLoc + LLVMRemarkArgGetDebugLoc.restype = LLVMRemarkDebugLocRef + LLVMRemarkArgGetDebugLoc.argtypes = [LLVMRemarkArgRef] +except AttributeError: + pass +class struct_LLVMRemarkOpaqueEntry(Structure): + pass + +LLVMRemarkEntryRef = ctypes.POINTER(struct_LLVMRemarkOpaqueEntry) +try: + LLVMRemarkEntryDispose = _libraries['llvm'].LLVMRemarkEntryDispose + LLVMRemarkEntryDispose.restype = None + LLVMRemarkEntryDispose.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetType = _libraries['llvm'].LLVMRemarkEntryGetType + LLVMRemarkEntryGetType.restype = LLVMRemarkType + LLVMRemarkEntryGetType.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetPassName = _libraries['llvm'].LLVMRemarkEntryGetPassName + LLVMRemarkEntryGetPassName.restype = LLVMRemarkStringRef + LLVMRemarkEntryGetPassName.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetRemarkName = _libraries['llvm'].LLVMRemarkEntryGetRemarkName + LLVMRemarkEntryGetRemarkName.restype = LLVMRemarkStringRef + LLVMRemarkEntryGetRemarkName.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetFunctionName = _libraries['llvm'].LLVMRemarkEntryGetFunctionName + LLVMRemarkEntryGetFunctionName.restype = LLVMRemarkStringRef + LLVMRemarkEntryGetFunctionName.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetDebugLoc = _libraries['llvm'].LLVMRemarkEntryGetDebugLoc + LLVMRemarkEntryGetDebugLoc.restype = LLVMRemarkDebugLocRef + LLVMRemarkEntryGetDebugLoc.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetHotness = _libraries['llvm'].LLVMRemarkEntryGetHotness + LLVMRemarkEntryGetHotness.restype = uint64_t + LLVMRemarkEntryGetHotness.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetNumArgs = _libraries['llvm'].LLVMRemarkEntryGetNumArgs + LLVMRemarkEntryGetNumArgs.restype = uint32_t + LLVMRemarkEntryGetNumArgs.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetFirstArg = _libraries['llvm'].LLVMRemarkEntryGetFirstArg + LLVMRemarkEntryGetFirstArg.restype = LLVMRemarkArgRef + LLVMRemarkEntryGetFirstArg.argtypes = [LLVMRemarkEntryRef] +except AttributeError: + pass +try: + LLVMRemarkEntryGetNextArg = _libraries['llvm'].LLVMRemarkEntryGetNextArg + LLVMRemarkEntryGetNextArg.restype = LLVMRemarkArgRef + LLVMRemarkEntryGetNextArg.argtypes = [LLVMRemarkArgRef, LLVMRemarkEntryRef] +except AttributeError: + pass +class struct_LLVMRemarkOpaqueParser(Structure): + pass + +LLVMRemarkParserRef = ctypes.POINTER(struct_LLVMRemarkOpaqueParser) +try: + LLVMRemarkParserCreateYAML = _libraries['llvm'].LLVMRemarkParserCreateYAML + LLVMRemarkParserCreateYAML.restype = LLVMRemarkParserRef + LLVMRemarkParserCreateYAML.argtypes = [ctypes.POINTER(None), uint64_t] +except AttributeError: + pass +try: + LLVMRemarkParserCreateBitstream = _libraries['llvm'].LLVMRemarkParserCreateBitstream + LLVMRemarkParserCreateBitstream.restype = LLVMRemarkParserRef + LLVMRemarkParserCreateBitstream.argtypes = [ctypes.POINTER(None), uint64_t] +except AttributeError: + pass +try: + LLVMRemarkParserGetNext = _libraries['llvm'].LLVMRemarkParserGetNext + LLVMRemarkParserGetNext.restype = LLVMRemarkEntryRef + LLVMRemarkParserGetNext.argtypes = [LLVMRemarkParserRef] +except AttributeError: + pass +try: + LLVMRemarkParserHasError = _libraries['llvm'].LLVMRemarkParserHasError + LLVMRemarkParserHasError.restype = LLVMBool + LLVMRemarkParserHasError.argtypes = [LLVMRemarkParserRef] +except AttributeError: + pass +try: + LLVMRemarkParserGetErrorMessage = _libraries['llvm'].LLVMRemarkParserGetErrorMessage + LLVMRemarkParserGetErrorMessage.restype = ctypes.POINTER(ctypes.c_char) + LLVMRemarkParserGetErrorMessage.argtypes = [LLVMRemarkParserRef] +except AttributeError: + pass +try: + LLVMRemarkParserDispose = _libraries['llvm'].LLVMRemarkParserDispose + LLVMRemarkParserDispose.restype = None + LLVMRemarkParserDispose.argtypes = [LLVMRemarkParserRef] +except AttributeError: + pass +try: + LLVMRemarkVersion = _libraries['llvm'].LLVMRemarkVersion + LLVMRemarkVersion.restype = uint32_t + LLVMRemarkVersion.argtypes = [] +except AttributeError: + pass +LLVM_C_SUPPORT_H = True # macro +try: + LLVMLoadLibraryPermanently = _libraries['llvm'].LLVMLoadLibraryPermanently + LLVMLoadLibraryPermanently.restype = LLVMBool + LLVMLoadLibraryPermanently.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMParseCommandLineOptions = _libraries['llvm'].LLVMParseCommandLineOptions + LLVMParseCommandLineOptions.restype = None + LLVMParseCommandLineOptions.argtypes = [ctypes.c_int32, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMSearchForAddressOfSymbol = _libraries['llvm'].LLVMSearchForAddressOfSymbol + LLVMSearchForAddressOfSymbol.restype = ctypes.POINTER(None) + LLVMSearchForAddressOfSymbol.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + LLVMAddSymbol = _libraries['llvm'].LLVMAddSymbol + LLVMAddSymbol.restype = None + LLVMAddSymbol.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None)] +except AttributeError: + pass +LLVM_C_TRANSFORMS_AGGRESSIVEINSTCOMBINE_H = True # macro +try: + LLVMAddAggressiveInstCombinerPass = _libraries['llvm'].LLVMAddAggressiveInstCombinerPass + LLVMAddAggressiveInstCombinerPass.restype = None + LLVMAddAggressiveInstCombinerPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_COROUTINES_H = True # macro +LLVM_C_TRANSFORMS_PASSMANAGERBUILDER_H = True # macro +class struct_LLVMOpaquePassManagerBuilder(Structure): + pass + +LLVMPassManagerBuilderRef = ctypes.POINTER(struct_LLVMOpaquePassManagerBuilder) +try: + LLVMPassManagerBuilderCreate = _libraries['llvm'].LLVMPassManagerBuilderCreate + LLVMPassManagerBuilderCreate.restype = LLVMPassManagerBuilderRef + LLVMPassManagerBuilderCreate.argtypes = [] +except AttributeError: + pass +try: + LLVMPassManagerBuilderDispose = _libraries['llvm'].LLVMPassManagerBuilderDispose + LLVMPassManagerBuilderDispose.restype = None + LLVMPassManagerBuilderDispose.argtypes = [LLVMPassManagerBuilderRef] +except AttributeError: + pass +try: + LLVMPassManagerBuilderSetOptLevel = _libraries['llvm'].LLVMPassManagerBuilderSetOptLevel + LLVMPassManagerBuilderSetOptLevel.restype = None + LLVMPassManagerBuilderSetOptLevel.argtypes = [LLVMPassManagerBuilderRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMPassManagerBuilderSetSizeLevel = _libraries['llvm'].LLVMPassManagerBuilderSetSizeLevel + LLVMPassManagerBuilderSetSizeLevel.restype = None + LLVMPassManagerBuilderSetSizeLevel.argtypes = [LLVMPassManagerBuilderRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMPassManagerBuilderSetDisableUnitAtATime = _libraries['llvm'].LLVMPassManagerBuilderSetDisableUnitAtATime + LLVMPassManagerBuilderSetDisableUnitAtATime.restype = None + LLVMPassManagerBuilderSetDisableUnitAtATime.argtypes = [LLVMPassManagerBuilderRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassManagerBuilderSetDisableUnrollLoops = _libraries['llvm'].LLVMPassManagerBuilderSetDisableUnrollLoops + LLVMPassManagerBuilderSetDisableUnrollLoops.restype = None + LLVMPassManagerBuilderSetDisableUnrollLoops.argtypes = [LLVMPassManagerBuilderRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassManagerBuilderSetDisableSimplifyLibCalls = _libraries['llvm'].LLVMPassManagerBuilderSetDisableSimplifyLibCalls + LLVMPassManagerBuilderSetDisableSimplifyLibCalls.restype = None + LLVMPassManagerBuilderSetDisableSimplifyLibCalls.argtypes = [LLVMPassManagerBuilderRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassManagerBuilderUseInlinerWithThreshold = _libraries['llvm'].LLVMPassManagerBuilderUseInlinerWithThreshold + LLVMPassManagerBuilderUseInlinerWithThreshold.restype = None + LLVMPassManagerBuilderUseInlinerWithThreshold.argtypes = [LLVMPassManagerBuilderRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMPassManagerBuilderPopulateFunctionPassManager = _libraries['llvm'].LLVMPassManagerBuilderPopulateFunctionPassManager + LLVMPassManagerBuilderPopulateFunctionPassManager.restype = None + LLVMPassManagerBuilderPopulateFunctionPassManager.argtypes = [LLVMPassManagerBuilderRef, LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMPassManagerBuilderPopulateModulePassManager = _libraries['llvm'].LLVMPassManagerBuilderPopulateModulePassManager + LLVMPassManagerBuilderPopulateModulePassManager.restype = None + LLVMPassManagerBuilderPopulateModulePassManager.argtypes = [LLVMPassManagerBuilderRef, LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMPassManagerBuilderPopulateLTOPassManager = _libraries['llvm'].LLVMPassManagerBuilderPopulateLTOPassManager + LLVMPassManagerBuilderPopulateLTOPassManager.restype = None + LLVMPassManagerBuilderPopulateLTOPassManager.argtypes = [LLVMPassManagerBuilderRef, LLVMPassManagerRef, LLVMBool, LLVMBool] +except AttributeError: + pass +try: + LLVMAddCoroEarlyPass = _libraries['llvm'].LLVMAddCoroEarlyPass + LLVMAddCoroEarlyPass.restype = None + LLVMAddCoroEarlyPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCoroSplitPass = _libraries['llvm'].LLVMAddCoroSplitPass + LLVMAddCoroSplitPass.restype = None + LLVMAddCoroSplitPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCoroElidePass = _libraries['llvm'].LLVMAddCoroElidePass + LLVMAddCoroElidePass.restype = None + LLVMAddCoroElidePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCoroCleanupPass = _libraries['llvm'].LLVMAddCoroCleanupPass + LLVMAddCoroCleanupPass.restype = None + LLVMAddCoroCleanupPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMPassManagerBuilderAddCoroutinePassesToExtensionPoints = _libraries['llvm'].LLVMPassManagerBuilderAddCoroutinePassesToExtensionPoints + LLVMPassManagerBuilderAddCoroutinePassesToExtensionPoints.restype = None + LLVMPassManagerBuilderAddCoroutinePassesToExtensionPoints.argtypes = [LLVMPassManagerBuilderRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_IPO_H = True # macro +try: + LLVMAddArgumentPromotionPass = _libraries['llvm'].LLVMAddArgumentPromotionPass + LLVMAddArgumentPromotionPass.restype = None + LLVMAddArgumentPromotionPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddConstantMergePass = _libraries['llvm'].LLVMAddConstantMergePass + LLVMAddConstantMergePass.restype = None + LLVMAddConstantMergePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddMergeFunctionsPass = _libraries['llvm'].LLVMAddMergeFunctionsPass + LLVMAddMergeFunctionsPass.restype = None + LLVMAddMergeFunctionsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCalledValuePropagationPass = _libraries['llvm'].LLVMAddCalledValuePropagationPass + LLVMAddCalledValuePropagationPass.restype = None + LLVMAddCalledValuePropagationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddDeadArgEliminationPass = _libraries['llvm'].LLVMAddDeadArgEliminationPass + LLVMAddDeadArgEliminationPass.restype = None + LLVMAddDeadArgEliminationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddFunctionAttrsPass = _libraries['llvm'].LLVMAddFunctionAttrsPass + LLVMAddFunctionAttrsPass.restype = None + LLVMAddFunctionAttrsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddFunctionInliningPass = _libraries['llvm'].LLVMAddFunctionInliningPass + LLVMAddFunctionInliningPass.restype = None + LLVMAddFunctionInliningPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddAlwaysInlinerPass = _libraries['llvm'].LLVMAddAlwaysInlinerPass + LLVMAddAlwaysInlinerPass.restype = None + LLVMAddAlwaysInlinerPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddGlobalDCEPass = _libraries['llvm'].LLVMAddGlobalDCEPass + LLVMAddGlobalDCEPass.restype = None + LLVMAddGlobalDCEPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddGlobalOptimizerPass = _libraries['llvm'].LLVMAddGlobalOptimizerPass + LLVMAddGlobalOptimizerPass.restype = None + LLVMAddGlobalOptimizerPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddPruneEHPass = _libraries['llvm'].LLVMAddPruneEHPass + LLVMAddPruneEHPass.restype = None + LLVMAddPruneEHPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddIPSCCPPass = _libraries['llvm'].LLVMAddIPSCCPPass + LLVMAddIPSCCPPass.restype = None + LLVMAddIPSCCPPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddInternalizePass = _libraries['llvm'].LLVMAddInternalizePass + LLVMAddInternalizePass.restype = None + LLVMAddInternalizePass.argtypes = [LLVMPassManagerRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMAddInternalizePassWithMustPreservePredicate = _libraries['llvm'].LLVMAddInternalizePassWithMustPreservePredicate + LLVMAddInternalizePassWithMustPreservePredicate.restype = None + LLVMAddInternalizePassWithMustPreservePredicate.argtypes = [LLVMPassManagerRef, ctypes.POINTER(None), ctypes.CFUNCTYPE(ctypes.c_int32, ctypes.POINTER(struct_LLVMOpaqueValue), ctypes.POINTER(None))] +except AttributeError: + pass +try: + LLVMAddStripDeadPrototypesPass = _libraries['llvm'].LLVMAddStripDeadPrototypesPass + LLVMAddStripDeadPrototypesPass.restype = None + LLVMAddStripDeadPrototypesPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddStripSymbolsPass = _libraries['llvm'].LLVMAddStripSymbolsPass + LLVMAddStripSymbolsPass.restype = None + LLVMAddStripSymbolsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_INSTCOMBINE_H = True # macro +try: + LLVMAddInstructionCombiningPass = _libraries['llvm'].LLVMAddInstructionCombiningPass + LLVMAddInstructionCombiningPass.restype = None + LLVMAddInstructionCombiningPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_PASSBUILDER_H = True # macro +class struct_LLVMOpaquePassBuilderOptions(Structure): + pass + +LLVMPassBuilderOptionsRef = ctypes.POINTER(struct_LLVMOpaquePassBuilderOptions) +try: + LLVMRunPasses = _libraries['llvm'].LLVMRunPasses + LLVMRunPasses.restype = LLVMErrorRef + LLVMRunPasses.argtypes = [LLVMModuleRef, ctypes.POINTER(ctypes.c_char), LLVMTargetMachineRef, LLVMPassBuilderOptionsRef] +except AttributeError: + pass +try: + LLVMCreatePassBuilderOptions = _libraries['llvm'].LLVMCreatePassBuilderOptions + LLVMCreatePassBuilderOptions.restype = LLVMPassBuilderOptionsRef + LLVMCreatePassBuilderOptions.argtypes = [] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetVerifyEach = _libraries['llvm'].LLVMPassBuilderOptionsSetVerifyEach + LLVMPassBuilderOptionsSetVerifyEach.restype = None + LLVMPassBuilderOptionsSetVerifyEach.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetDebugLogging = _libraries['llvm'].LLVMPassBuilderOptionsSetDebugLogging + LLVMPassBuilderOptionsSetDebugLogging.restype = None + LLVMPassBuilderOptionsSetDebugLogging.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetLoopInterleaving = _libraries['llvm'].LLVMPassBuilderOptionsSetLoopInterleaving + LLVMPassBuilderOptionsSetLoopInterleaving.restype = None + LLVMPassBuilderOptionsSetLoopInterleaving.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetLoopVectorization = _libraries['llvm'].LLVMPassBuilderOptionsSetLoopVectorization + LLVMPassBuilderOptionsSetLoopVectorization.restype = None + LLVMPassBuilderOptionsSetLoopVectorization.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetSLPVectorization = _libraries['llvm'].LLVMPassBuilderOptionsSetSLPVectorization + LLVMPassBuilderOptionsSetSLPVectorization.restype = None + LLVMPassBuilderOptionsSetSLPVectorization.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetLoopUnrolling = _libraries['llvm'].LLVMPassBuilderOptionsSetLoopUnrolling + LLVMPassBuilderOptionsSetLoopUnrolling.restype = None + LLVMPassBuilderOptionsSetLoopUnrolling.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetForgetAllSCEVInLoopUnroll = _libraries['llvm'].LLVMPassBuilderOptionsSetForgetAllSCEVInLoopUnroll + LLVMPassBuilderOptionsSetForgetAllSCEVInLoopUnroll.restype = None + LLVMPassBuilderOptionsSetForgetAllSCEVInLoopUnroll.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetLicmMssaOptCap = _libraries['llvm'].LLVMPassBuilderOptionsSetLicmMssaOptCap + LLVMPassBuilderOptionsSetLicmMssaOptCap.restype = None + LLVMPassBuilderOptionsSetLicmMssaOptCap.argtypes = [LLVMPassBuilderOptionsRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetLicmMssaNoAccForPromotionCap = _libraries['llvm'].LLVMPassBuilderOptionsSetLicmMssaNoAccForPromotionCap + LLVMPassBuilderOptionsSetLicmMssaNoAccForPromotionCap.restype = None + LLVMPassBuilderOptionsSetLicmMssaNoAccForPromotionCap.argtypes = [LLVMPassBuilderOptionsRef, ctypes.c_uint32] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetCallGraphProfile = _libraries['llvm'].LLVMPassBuilderOptionsSetCallGraphProfile + LLVMPassBuilderOptionsSetCallGraphProfile.restype = None + LLVMPassBuilderOptionsSetCallGraphProfile.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMPassBuilderOptionsSetMergeFunctions = _libraries['llvm'].LLVMPassBuilderOptionsSetMergeFunctions + LLVMPassBuilderOptionsSetMergeFunctions.restype = None + LLVMPassBuilderOptionsSetMergeFunctions.argtypes = [LLVMPassBuilderOptionsRef, LLVMBool] +except AttributeError: + pass +try: + LLVMDisposePassBuilderOptions = _libraries['llvm'].LLVMDisposePassBuilderOptions + LLVMDisposePassBuilderOptions.restype = None + LLVMDisposePassBuilderOptions.argtypes = [LLVMPassBuilderOptionsRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_SCALAR_H = True # macro +try: + LLVMAddAggressiveDCEPass = _libraries['llvm'].LLVMAddAggressiveDCEPass + LLVMAddAggressiveDCEPass.restype = None + LLVMAddAggressiveDCEPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddDCEPass = _libraries['llvm'].LLVMAddDCEPass + LLVMAddDCEPass.restype = None + LLVMAddDCEPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddBitTrackingDCEPass = _libraries['llvm'].LLVMAddBitTrackingDCEPass + LLVMAddBitTrackingDCEPass.restype = None + LLVMAddBitTrackingDCEPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddAlignmentFromAssumptionsPass = _libraries['llvm'].LLVMAddAlignmentFromAssumptionsPass + LLVMAddAlignmentFromAssumptionsPass.restype = None + LLVMAddAlignmentFromAssumptionsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCFGSimplificationPass = _libraries['llvm'].LLVMAddCFGSimplificationPass + LLVMAddCFGSimplificationPass.restype = None + LLVMAddCFGSimplificationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddDeadStoreEliminationPass = _libraries['llvm'].LLVMAddDeadStoreEliminationPass + LLVMAddDeadStoreEliminationPass.restype = None + LLVMAddDeadStoreEliminationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddScalarizerPass = _libraries['llvm'].LLVMAddScalarizerPass + LLVMAddScalarizerPass.restype = None + LLVMAddScalarizerPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddMergedLoadStoreMotionPass = _libraries['llvm'].LLVMAddMergedLoadStoreMotionPass + LLVMAddMergedLoadStoreMotionPass.restype = None + LLVMAddMergedLoadStoreMotionPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddGVNPass = _libraries['llvm'].LLVMAddGVNPass + LLVMAddGVNPass.restype = None + LLVMAddGVNPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddNewGVNPass = _libraries['llvm'].LLVMAddNewGVNPass + LLVMAddNewGVNPass.restype = None + LLVMAddNewGVNPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddIndVarSimplifyPass = _libraries['llvm'].LLVMAddIndVarSimplifyPass + LLVMAddIndVarSimplifyPass.restype = None + LLVMAddIndVarSimplifyPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddInstructionSimplifyPass = _libraries['llvm'].LLVMAddInstructionSimplifyPass + LLVMAddInstructionSimplifyPass.restype = None + LLVMAddInstructionSimplifyPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddJumpThreadingPass = _libraries['llvm'].LLVMAddJumpThreadingPass + LLVMAddJumpThreadingPass.restype = None + LLVMAddJumpThreadingPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLICMPass = _libraries['llvm'].LLVMAddLICMPass + LLVMAddLICMPass.restype = None + LLVMAddLICMPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopDeletionPass = _libraries['llvm'].LLVMAddLoopDeletionPass + LLVMAddLoopDeletionPass.restype = None + LLVMAddLoopDeletionPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopIdiomPass = _libraries['llvm'].LLVMAddLoopIdiomPass + LLVMAddLoopIdiomPass.restype = None + LLVMAddLoopIdiomPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopRotatePass = _libraries['llvm'].LLVMAddLoopRotatePass + LLVMAddLoopRotatePass.restype = None + LLVMAddLoopRotatePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopRerollPass = _libraries['llvm'].LLVMAddLoopRerollPass + LLVMAddLoopRerollPass.restype = None + LLVMAddLoopRerollPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopUnrollPass = _libraries['llvm'].LLVMAddLoopUnrollPass + LLVMAddLoopUnrollPass.restype = None + LLVMAddLoopUnrollPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopUnrollAndJamPass = _libraries['llvm'].LLVMAddLoopUnrollAndJamPass + LLVMAddLoopUnrollAndJamPass.restype = None + LLVMAddLoopUnrollAndJamPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLoopUnswitchPass = _libraries['llvm'].LLVMAddLoopUnswitchPass + LLVMAddLoopUnswitchPass.restype = None + LLVMAddLoopUnswitchPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLowerAtomicPass = _libraries['llvm'].LLVMAddLowerAtomicPass + LLVMAddLowerAtomicPass.restype = None + LLVMAddLowerAtomicPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddMemCpyOptPass = _libraries['llvm'].LLVMAddMemCpyOptPass + LLVMAddMemCpyOptPass.restype = None + LLVMAddMemCpyOptPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddPartiallyInlineLibCallsPass = _libraries['llvm'].LLVMAddPartiallyInlineLibCallsPass + LLVMAddPartiallyInlineLibCallsPass.restype = None + LLVMAddPartiallyInlineLibCallsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddReassociatePass = _libraries['llvm'].LLVMAddReassociatePass + LLVMAddReassociatePass.restype = None + LLVMAddReassociatePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddSCCPPass = _libraries['llvm'].LLVMAddSCCPPass + LLVMAddSCCPPass.restype = None + LLVMAddSCCPPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddScalarReplAggregatesPass = _libraries['llvm'].LLVMAddScalarReplAggregatesPass + LLVMAddScalarReplAggregatesPass.restype = None + LLVMAddScalarReplAggregatesPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddScalarReplAggregatesPassSSA = _libraries['llvm'].LLVMAddScalarReplAggregatesPassSSA + LLVMAddScalarReplAggregatesPassSSA.restype = None + LLVMAddScalarReplAggregatesPassSSA.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddScalarReplAggregatesPassWithThreshold = _libraries['llvm'].LLVMAddScalarReplAggregatesPassWithThreshold + LLVMAddScalarReplAggregatesPassWithThreshold.restype = None + LLVMAddScalarReplAggregatesPassWithThreshold.argtypes = [LLVMPassManagerRef, ctypes.c_int32] +except AttributeError: + pass +try: + LLVMAddSimplifyLibCallsPass = _libraries['llvm'].LLVMAddSimplifyLibCallsPass + LLVMAddSimplifyLibCallsPass.restype = None + LLVMAddSimplifyLibCallsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddTailCallEliminationPass = _libraries['llvm'].LLVMAddTailCallEliminationPass + LLVMAddTailCallEliminationPass.restype = None + LLVMAddTailCallEliminationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddDemoteMemoryToRegisterPass = _libraries['llvm'].LLVMAddDemoteMemoryToRegisterPass + LLVMAddDemoteMemoryToRegisterPass.restype = None + LLVMAddDemoteMemoryToRegisterPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddVerifierPass = _libraries['llvm'].LLVMAddVerifierPass + LLVMAddVerifierPass.restype = None + LLVMAddVerifierPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddCorrelatedValuePropagationPass = _libraries['llvm'].LLVMAddCorrelatedValuePropagationPass + LLVMAddCorrelatedValuePropagationPass.restype = None + LLVMAddCorrelatedValuePropagationPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddEarlyCSEPass = _libraries['llvm'].LLVMAddEarlyCSEPass + LLVMAddEarlyCSEPass.restype = None + LLVMAddEarlyCSEPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddEarlyCSEMemSSAPass = _libraries['llvm'].LLVMAddEarlyCSEMemSSAPass + LLVMAddEarlyCSEMemSSAPass.restype = None + LLVMAddEarlyCSEMemSSAPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLowerExpectIntrinsicPass = _libraries['llvm'].LLVMAddLowerExpectIntrinsicPass + LLVMAddLowerExpectIntrinsicPass.restype = None + LLVMAddLowerExpectIntrinsicPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddLowerConstantIntrinsicsPass = _libraries['llvm'].LLVMAddLowerConstantIntrinsicsPass + LLVMAddLowerConstantIntrinsicsPass.restype = None + LLVMAddLowerConstantIntrinsicsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddTypeBasedAliasAnalysisPass = _libraries['llvm'].LLVMAddTypeBasedAliasAnalysisPass + LLVMAddTypeBasedAliasAnalysisPass.restype = None + LLVMAddTypeBasedAliasAnalysisPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddScopedNoAliasAAPass = _libraries['llvm'].LLVMAddScopedNoAliasAAPass + LLVMAddScopedNoAliasAAPass.restype = None + LLVMAddScopedNoAliasAAPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddBasicAliasAnalysisPass = _libraries['llvm'].LLVMAddBasicAliasAnalysisPass + LLVMAddBasicAliasAnalysisPass.restype = None + LLVMAddBasicAliasAnalysisPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddUnifyFunctionExitNodesPass = _libraries['llvm'].LLVMAddUnifyFunctionExitNodesPass + LLVMAddUnifyFunctionExitNodesPass.restype = None + LLVMAddUnifyFunctionExitNodesPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_UTILS_H = True # macro +try: + LLVMAddLowerSwitchPass = _libraries['llvm'].LLVMAddLowerSwitchPass + LLVMAddLowerSwitchPass.restype = None + LLVMAddLowerSwitchPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddPromoteMemoryToRegisterPass = _libraries['llvm'].LLVMAddPromoteMemoryToRegisterPass + LLVMAddPromoteMemoryToRegisterPass.restype = None + LLVMAddPromoteMemoryToRegisterPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddAddDiscriminatorsPass = _libraries['llvm'].LLVMAddAddDiscriminatorsPass + LLVMAddAddDiscriminatorsPass.restype = None + LLVMAddAddDiscriminatorsPass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_TRANSFORMS_VECTORIZE_H = True # macro +try: + LLVMAddLoopVectorizePass = _libraries['llvm'].LLVMAddLoopVectorizePass + LLVMAddLoopVectorizePass.restype = None + LLVMAddLoopVectorizePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +try: + LLVMAddSLPVectorizePass = _libraries['llvm'].LLVMAddSLPVectorizePass + LLVMAddSLPVectorizePass.restype = None + LLVMAddSLPVectorizePass.argtypes = [LLVMPassManagerRef] +except AttributeError: + pass +LLVM_C_LTO_H = True # macro +LTO_API_VERSION = 29 # macro +lto_bool_t = ctypes.c_bool + +# values for enumeration 'c__EA_lto_symbol_attributes' +c__EA_lto_symbol_attributes__enumvalues = { + 31: 'LTO_SYMBOL_ALIGNMENT_MASK', + 224: 'LTO_SYMBOL_PERMISSIONS_MASK', + 160: 'LTO_SYMBOL_PERMISSIONS_CODE', + 192: 'LTO_SYMBOL_PERMISSIONS_DATA', + 128: 'LTO_SYMBOL_PERMISSIONS_RODATA', + 1792: 'LTO_SYMBOL_DEFINITION_MASK', + 256: 'LTO_SYMBOL_DEFINITION_REGULAR', + 512: 'LTO_SYMBOL_DEFINITION_TENTATIVE', + 768: 'LTO_SYMBOL_DEFINITION_WEAK', + 1024: 'LTO_SYMBOL_DEFINITION_UNDEFINED', + 1280: 'LTO_SYMBOL_DEFINITION_WEAKUNDEF', + 14336: 'LTO_SYMBOL_SCOPE_MASK', + 2048: 'LTO_SYMBOL_SCOPE_INTERNAL', + 4096: 'LTO_SYMBOL_SCOPE_HIDDEN', + 8192: 'LTO_SYMBOL_SCOPE_PROTECTED', + 6144: 'LTO_SYMBOL_SCOPE_DEFAULT', + 10240: 'LTO_SYMBOL_SCOPE_DEFAULT_CAN_BE_HIDDEN', + 16384: 'LTO_SYMBOL_COMDAT', + 32768: 'LTO_SYMBOL_ALIAS', +} +LTO_SYMBOL_ALIGNMENT_MASK = 31 +LTO_SYMBOL_PERMISSIONS_MASK = 224 +LTO_SYMBOL_PERMISSIONS_CODE = 160 +LTO_SYMBOL_PERMISSIONS_DATA = 192 +LTO_SYMBOL_PERMISSIONS_RODATA = 128 +LTO_SYMBOL_DEFINITION_MASK = 1792 +LTO_SYMBOL_DEFINITION_REGULAR = 256 +LTO_SYMBOL_DEFINITION_TENTATIVE = 512 +LTO_SYMBOL_DEFINITION_WEAK = 768 +LTO_SYMBOL_DEFINITION_UNDEFINED = 1024 +LTO_SYMBOL_DEFINITION_WEAKUNDEF = 1280 +LTO_SYMBOL_SCOPE_MASK = 14336 +LTO_SYMBOL_SCOPE_INTERNAL = 2048 +LTO_SYMBOL_SCOPE_HIDDEN = 4096 +LTO_SYMBOL_SCOPE_PROTECTED = 8192 +LTO_SYMBOL_SCOPE_DEFAULT = 6144 +LTO_SYMBOL_SCOPE_DEFAULT_CAN_BE_HIDDEN = 10240 +LTO_SYMBOL_COMDAT = 16384 +LTO_SYMBOL_ALIAS = 32768 +c__EA_lto_symbol_attributes = ctypes.c_uint32 # enum +lto_symbol_attributes = c__EA_lto_symbol_attributes +lto_symbol_attributes__enumvalues = c__EA_lto_symbol_attributes__enumvalues + +# values for enumeration 'c__EA_lto_debug_model' +c__EA_lto_debug_model__enumvalues = { + 0: 'LTO_DEBUG_MODEL_NONE', + 1: 'LTO_DEBUG_MODEL_DWARF', +} +LTO_DEBUG_MODEL_NONE = 0 +LTO_DEBUG_MODEL_DWARF = 1 +c__EA_lto_debug_model = ctypes.c_uint32 # enum +lto_debug_model = c__EA_lto_debug_model +lto_debug_model__enumvalues = c__EA_lto_debug_model__enumvalues + +# values for enumeration 'c__EA_lto_codegen_model' +c__EA_lto_codegen_model__enumvalues = { + 0: 'LTO_CODEGEN_PIC_MODEL_STATIC', + 1: 'LTO_CODEGEN_PIC_MODEL_DYNAMIC', + 2: 'LTO_CODEGEN_PIC_MODEL_DYNAMIC_NO_PIC', + 3: 'LTO_CODEGEN_PIC_MODEL_DEFAULT', +} +LTO_CODEGEN_PIC_MODEL_STATIC = 0 +LTO_CODEGEN_PIC_MODEL_DYNAMIC = 1 +LTO_CODEGEN_PIC_MODEL_DYNAMIC_NO_PIC = 2 +LTO_CODEGEN_PIC_MODEL_DEFAULT = 3 +c__EA_lto_codegen_model = ctypes.c_uint32 # enum +lto_codegen_model = c__EA_lto_codegen_model +lto_codegen_model__enumvalues = c__EA_lto_codegen_model__enumvalues +class struct_LLVMOpaqueLTOModule(Structure): + pass + +lto_module_t = ctypes.POINTER(struct_LLVMOpaqueLTOModule) +class struct_LLVMOpaqueLTOCodeGenerator(Structure): + pass + +lto_code_gen_t = ctypes.POINTER(struct_LLVMOpaqueLTOCodeGenerator) +class struct_LLVMOpaqueThinLTOCodeGenerator(Structure): + pass + +thinlto_code_gen_t = ctypes.POINTER(struct_LLVMOpaqueThinLTOCodeGenerator) +try: + lto_get_version = _libraries['llvm'].lto_get_version + lto_get_version.restype = ctypes.POINTER(ctypes.c_char) + lto_get_version.argtypes = [] +except AttributeError: + pass +try: + lto_get_error_message = _libraries['llvm'].lto_get_error_message + lto_get_error_message.restype = ctypes.POINTER(ctypes.c_char) + lto_get_error_message.argtypes = [] +except AttributeError: + pass +try: + lto_module_is_object_file = _libraries['llvm'].lto_module_is_object_file + lto_module_is_object_file.restype = lto_bool_t + lto_module_is_object_file.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_is_object_file_for_target = _libraries['llvm'].lto_module_is_object_file_for_target + lto_module_is_object_file_for_target.restype = lto_bool_t + lto_module_is_object_file_for_target.argtypes = [ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_has_objc_category = _libraries['llvm'].lto_module_has_objc_category + lto_module_has_objc_category.restype = lto_bool_t + lto_module_has_objc_category.argtypes = [ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + lto_module_is_object_file_in_memory = _libraries['llvm'].lto_module_is_object_file_in_memory + lto_module_is_object_file_in_memory.restype = lto_bool_t + lto_module_is_object_file_in_memory.argtypes = [ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + lto_module_is_object_file_in_memory_for_target = _libraries['llvm'].lto_module_is_object_file_in_memory_for_target + lto_module_is_object_file_in_memory_for_target.restype = lto_bool_t + lto_module_is_object_file_in_memory_for_target.argtypes = [ctypes.POINTER(None), size_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_create = _libraries['llvm'].lto_module_create + lto_module_create.restype = lto_module_t + lto_module_create.argtypes = [ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_create_from_memory = _libraries['llvm'].lto_module_create_from_memory + lto_module_create_from_memory.restype = lto_module_t + lto_module_create_from_memory.argtypes = [ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + lto_module_create_from_memory_with_path = _libraries['llvm'].lto_module_create_from_memory_with_path + lto_module_create_from_memory_with_path.restype = lto_module_t + lto_module_create_from_memory_with_path.argtypes = [ctypes.POINTER(None), size_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_create_in_local_context = _libraries['llvm'].lto_module_create_in_local_context + lto_module_create_in_local_context.restype = lto_module_t + lto_module_create_in_local_context.argtypes = [ctypes.POINTER(None), size_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_create_in_codegen_context = _libraries['llvm'].lto_module_create_in_codegen_context + lto_module_create_in_codegen_context.restype = lto_module_t + lto_module_create_in_codegen_context.argtypes = [ctypes.POINTER(None), size_t, ctypes.POINTER(ctypes.c_char), lto_code_gen_t] +except AttributeError: + pass +try: + lto_module_create_from_fd = _libraries['llvm'].lto_module_create_from_fd + lto_module_create_from_fd.restype = lto_module_t + lto_module_create_from_fd.argtypes = [ctypes.c_int32, ctypes.POINTER(ctypes.c_char), size_t] +except AttributeError: + pass +off_t = ctypes.c_int64 +try: + lto_module_create_from_fd_at_offset = _libraries['llvm'].lto_module_create_from_fd_at_offset + lto_module_create_from_fd_at_offset.restype = lto_module_t + lto_module_create_from_fd_at_offset.argtypes = [ctypes.c_int32, ctypes.POINTER(ctypes.c_char), size_t, size_t, off_t] +except AttributeError: + pass +try: + lto_module_dispose = _libraries['llvm'].lto_module_dispose + lto_module_dispose.restype = None + lto_module_dispose.argtypes = [lto_module_t] +except AttributeError: + pass +try: + lto_module_get_target_triple = _libraries['llvm'].lto_module_get_target_triple + lto_module_get_target_triple.restype = ctypes.POINTER(ctypes.c_char) + lto_module_get_target_triple.argtypes = [lto_module_t] +except AttributeError: + pass +try: + lto_module_set_target_triple = _libraries['llvm'].lto_module_set_target_triple + lto_module_set_target_triple.restype = None + lto_module_set_target_triple.argtypes = [lto_module_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_module_get_num_symbols = _libraries['llvm'].lto_module_get_num_symbols + lto_module_get_num_symbols.restype = ctypes.c_uint32 + lto_module_get_num_symbols.argtypes = [lto_module_t] +except AttributeError: + pass +try: + lto_module_get_symbol_name = _libraries['llvm'].lto_module_get_symbol_name + lto_module_get_symbol_name.restype = ctypes.POINTER(ctypes.c_char) + lto_module_get_symbol_name.argtypes = [lto_module_t, ctypes.c_uint32] +except AttributeError: + pass +try: + lto_module_get_symbol_attribute = _libraries['llvm'].lto_module_get_symbol_attribute + lto_module_get_symbol_attribute.restype = lto_symbol_attributes + lto_module_get_symbol_attribute.argtypes = [lto_module_t, ctypes.c_uint32] +except AttributeError: + pass +try: + lto_module_get_linkeropts = _libraries['llvm'].lto_module_get_linkeropts + lto_module_get_linkeropts.restype = ctypes.POINTER(ctypes.c_char) + lto_module_get_linkeropts.argtypes = [lto_module_t] +except AttributeError: + pass +try: + lto_module_get_macho_cputype = _libraries['llvm'].lto_module_get_macho_cputype + lto_module_get_macho_cputype.restype = lto_bool_t + lto_module_get_macho_cputype.argtypes = [lto_module_t, ctypes.POINTER(ctypes.c_uint32), ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + lto_module_has_ctor_dtor = _libraries['llvm'].lto_module_has_ctor_dtor + lto_module_has_ctor_dtor.restype = lto_bool_t + lto_module_has_ctor_dtor.argtypes = [lto_module_t] +except AttributeError: + pass + +# values for enumeration 'c__EA_lto_codegen_diagnostic_severity_t' +c__EA_lto_codegen_diagnostic_severity_t__enumvalues = { + 0: 'LTO_DS_ERROR', + 1: 'LTO_DS_WARNING', + 3: 'LTO_DS_REMARK', + 2: 'LTO_DS_NOTE', +} +LTO_DS_ERROR = 0 +LTO_DS_WARNING = 1 +LTO_DS_REMARK = 3 +LTO_DS_NOTE = 2 +c__EA_lto_codegen_diagnostic_severity_t = ctypes.c_uint32 # enum +lto_codegen_diagnostic_severity_t = c__EA_lto_codegen_diagnostic_severity_t +lto_codegen_diagnostic_severity_t__enumvalues = c__EA_lto_codegen_diagnostic_severity_t__enumvalues +lto_diagnostic_handler_t = ctypes.CFUNCTYPE(None, c__EA_lto_codegen_diagnostic_severity_t, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(None)) +try: + lto_codegen_set_diagnostic_handler = _libraries['llvm'].lto_codegen_set_diagnostic_handler + lto_codegen_set_diagnostic_handler.restype = None + lto_codegen_set_diagnostic_handler.argtypes = [lto_code_gen_t, lto_diagnostic_handler_t, ctypes.POINTER(None)] +except AttributeError: + pass +try: + lto_codegen_create = _libraries['llvm'].lto_codegen_create + lto_codegen_create.restype = lto_code_gen_t + lto_codegen_create.argtypes = [] +except AttributeError: + pass +try: + lto_codegen_create_in_local_context = _libraries['llvm'].lto_codegen_create_in_local_context + lto_codegen_create_in_local_context.restype = lto_code_gen_t + lto_codegen_create_in_local_context.argtypes = [] +except AttributeError: + pass +try: + lto_codegen_dispose = _libraries['llvm'].lto_codegen_dispose + lto_codegen_dispose.restype = None + lto_codegen_dispose.argtypes = [lto_code_gen_t] +except AttributeError: + pass +try: + lto_codegen_add_module = _libraries['llvm'].lto_codegen_add_module + lto_codegen_add_module.restype = lto_bool_t + lto_codegen_add_module.argtypes = [lto_code_gen_t, lto_module_t] +except AttributeError: + pass +try: + lto_codegen_set_module = _libraries['llvm'].lto_codegen_set_module + lto_codegen_set_module.restype = None + lto_codegen_set_module.argtypes = [lto_code_gen_t, lto_module_t] +except AttributeError: + pass +try: + lto_codegen_set_debug_model = _libraries['llvm'].lto_codegen_set_debug_model + lto_codegen_set_debug_model.restype = lto_bool_t + lto_codegen_set_debug_model.argtypes = [lto_code_gen_t, lto_debug_model] +except AttributeError: + pass +try: + lto_codegen_set_pic_model = _libraries['llvm'].lto_codegen_set_pic_model + lto_codegen_set_pic_model.restype = lto_bool_t + lto_codegen_set_pic_model.argtypes = [lto_code_gen_t, lto_codegen_model] +except AttributeError: + pass +try: + lto_codegen_set_cpu = _libraries['llvm'].lto_codegen_set_cpu + lto_codegen_set_cpu.restype = None + lto_codegen_set_cpu.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_codegen_set_assembler_path = _libraries['llvm'].lto_codegen_set_assembler_path + lto_codegen_set_assembler_path.restype = None + lto_codegen_set_assembler_path.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_codegen_set_assembler_args = _libraries['llvm'].lto_codegen_set_assembler_args + lto_codegen_set_assembler_args.restype = None + lto_codegen_set_assembler_args.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.c_int32] +except AttributeError: + pass +try: + lto_codegen_add_must_preserve_symbol = _libraries['llvm'].lto_codegen_add_must_preserve_symbol + lto_codegen_add_must_preserve_symbol.restype = None + lto_codegen_add_must_preserve_symbol.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_codegen_write_merged_modules = _libraries['llvm'].lto_codegen_write_merged_modules + lto_codegen_write_merged_modules.restype = lto_bool_t + lto_codegen_write_merged_modules.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_codegen_compile = _libraries['llvm'].lto_codegen_compile + lto_codegen_compile.restype = ctypes.POINTER(None) + lto_codegen_compile.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + lto_codegen_compile_to_file = _libraries['llvm'].lto_codegen_compile_to_file + lto_codegen_compile_to_file.restype = lto_bool_t + lto_codegen_compile_to_file.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char))] +except AttributeError: + pass +try: + lto_codegen_optimize = _libraries['llvm'].lto_codegen_optimize + lto_codegen_optimize.restype = lto_bool_t + lto_codegen_optimize.argtypes = [lto_code_gen_t] +except AttributeError: + pass +try: + lto_codegen_compile_optimized = _libraries['llvm'].lto_codegen_compile_optimized + lto_codegen_compile_optimized.restype = ctypes.POINTER(None) + lto_codegen_compile_optimized.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + lto_api_version = _libraries['llvm'].lto_api_version + lto_api_version.restype = ctypes.c_uint32 + lto_api_version.argtypes = [] +except AttributeError: + pass +try: + lto_set_debug_options = _libraries['llvm'].lto_set_debug_options + lto_set_debug_options.restype = None + lto_set_debug_options.argtypes = [ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.c_int32] +except AttributeError: + pass +try: + lto_codegen_debug_options = _libraries['llvm'].lto_codegen_debug_options + lto_codegen_debug_options.restype = None + lto_codegen_debug_options.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_codegen_debug_options_array = _libraries['llvm'].lto_codegen_debug_options_array + lto_codegen_debug_options_array.restype = None + lto_codegen_debug_options_array.argtypes = [lto_code_gen_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.c_int32] +except AttributeError: + pass +try: + lto_initialize_disassembler = _libraries['llvm'].lto_initialize_disassembler + lto_initialize_disassembler.restype = None + lto_initialize_disassembler.argtypes = [] +except AttributeError: + pass +try: + lto_codegen_set_should_internalize = _libraries['llvm'].lto_codegen_set_should_internalize + lto_codegen_set_should_internalize.restype = None + lto_codegen_set_should_internalize.argtypes = [lto_code_gen_t, lto_bool_t] +except AttributeError: + pass +try: + lto_codegen_set_should_embed_uselists = _libraries['llvm'].lto_codegen_set_should_embed_uselists + lto_codegen_set_should_embed_uselists.restype = None + lto_codegen_set_should_embed_uselists.argtypes = [lto_code_gen_t, lto_bool_t] +except AttributeError: + pass +class struct_LLVMOpaqueLTOInput(Structure): + pass + +lto_input_t = ctypes.POINTER(struct_LLVMOpaqueLTOInput) +try: + lto_input_create = _libraries['llvm'].lto_input_create + lto_input_create.restype = lto_input_t + lto_input_create.argtypes = [ctypes.POINTER(None), size_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + lto_input_dispose = _libraries['llvm'].lto_input_dispose + lto_input_dispose.restype = None + lto_input_dispose.argtypes = [lto_input_t] +except AttributeError: + pass +try: + lto_input_get_num_dependent_libraries = _libraries['llvm'].lto_input_get_num_dependent_libraries + lto_input_get_num_dependent_libraries.restype = ctypes.c_uint32 + lto_input_get_num_dependent_libraries.argtypes = [lto_input_t] +except AttributeError: + pass +try: + lto_input_get_dependent_library = _libraries['llvm'].lto_input_get_dependent_library + lto_input_get_dependent_library.restype = ctypes.POINTER(ctypes.c_char) + lto_input_get_dependent_library.argtypes = [lto_input_t, size_t, ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +try: + lto_runtime_lib_symbols_list = _libraries['llvm'].lto_runtime_lib_symbols_list + lto_runtime_lib_symbols_list.restype = ctypes.POINTER(ctypes.POINTER(ctypes.c_char)) + lto_runtime_lib_symbols_list.argtypes = [ctypes.POINTER(ctypes.c_uint64)] +except AttributeError: + pass +class struct_c__SA_LTOObjectBuffer(Structure): + pass + +struct_c__SA_LTOObjectBuffer._pack_ = 1 # source:False +struct_c__SA_LTOObjectBuffer._fields_ = [ + ('Buffer', ctypes.POINTER(ctypes.c_char)), + ('Size', ctypes.c_uint64), +] + +LTOObjectBuffer = struct_c__SA_LTOObjectBuffer +try: + thinlto_create_codegen = _libraries['llvm'].thinlto_create_codegen + thinlto_create_codegen.restype = thinlto_code_gen_t + thinlto_create_codegen.argtypes = [] +except AttributeError: + pass +try: + thinlto_codegen_dispose = _libraries['llvm'].thinlto_codegen_dispose + thinlto_codegen_dispose.restype = None + thinlto_codegen_dispose.argtypes = [thinlto_code_gen_t] +except AttributeError: + pass +try: + thinlto_codegen_add_module = _libraries['llvm'].thinlto_codegen_add_module + thinlto_codegen_add_module.restype = None + thinlto_codegen_add_module.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char), ctypes.POINTER(ctypes.c_char), ctypes.c_int32] +except AttributeError: + pass +try: + thinlto_codegen_process = _libraries['llvm'].thinlto_codegen_process + thinlto_codegen_process.restype = None + thinlto_codegen_process.argtypes = [thinlto_code_gen_t] +except AttributeError: + pass +try: + thinlto_module_get_num_objects = _libraries['llvm'].thinlto_module_get_num_objects + thinlto_module_get_num_objects.restype = ctypes.c_uint32 + thinlto_module_get_num_objects.argtypes = [thinlto_code_gen_t] +except AttributeError: + pass +try: + thinlto_module_get_object = _libraries['llvm'].thinlto_module_get_object + thinlto_module_get_object.restype = LTOObjectBuffer + thinlto_module_get_object.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_module_get_num_object_files = _libraries['llvm'].thinlto_module_get_num_object_files + thinlto_module_get_num_object_files.restype = ctypes.c_uint32 + thinlto_module_get_num_object_files.argtypes = [thinlto_code_gen_t] +except AttributeError: + pass +try: + thinlto_module_get_object_file = _libraries['llvm'].thinlto_module_get_object_file + thinlto_module_get_object_file.restype = ctypes.POINTER(ctypes.c_char) + thinlto_module_get_object_file.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_codegen_set_pic_model = _libraries['llvm'].thinlto_codegen_set_pic_model + thinlto_codegen_set_pic_model.restype = lto_bool_t + thinlto_codegen_set_pic_model.argtypes = [thinlto_code_gen_t, lto_codegen_model] +except AttributeError: + pass +try: + thinlto_codegen_set_savetemps_dir = _libraries['llvm'].thinlto_codegen_set_savetemps_dir + thinlto_codegen_set_savetemps_dir.restype = None + thinlto_codegen_set_savetemps_dir.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + thinlto_set_generated_objects_dir = _libraries['llvm'].thinlto_set_generated_objects_dir + thinlto_set_generated_objects_dir.restype = None + thinlto_set_generated_objects_dir.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + thinlto_codegen_set_cpu = _libraries['llvm'].thinlto_codegen_set_cpu + thinlto_codegen_set_cpu.restype = None + thinlto_codegen_set_cpu.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + thinlto_codegen_disable_codegen = _libraries['llvm'].thinlto_codegen_disable_codegen + thinlto_codegen_disable_codegen.restype = None + thinlto_codegen_disable_codegen.argtypes = [thinlto_code_gen_t, lto_bool_t] +except AttributeError: + pass +try: + thinlto_codegen_set_codegen_only = _libraries['llvm'].thinlto_codegen_set_codegen_only + thinlto_codegen_set_codegen_only.restype = None + thinlto_codegen_set_codegen_only.argtypes = [thinlto_code_gen_t, lto_bool_t] +except AttributeError: + pass +try: + thinlto_debug_options = _libraries['llvm'].thinlto_debug_options + thinlto_debug_options.restype = None + thinlto_debug_options.argtypes = [ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), ctypes.c_int32] +except AttributeError: + pass +try: + lto_module_is_thinlto = _libraries['llvm'].lto_module_is_thinlto + lto_module_is_thinlto.restype = lto_bool_t + lto_module_is_thinlto.argtypes = [lto_module_t] +except AttributeError: + pass +try: + thinlto_codegen_add_must_preserve_symbol = _libraries['llvm'].thinlto_codegen_add_must_preserve_symbol + thinlto_codegen_add_must_preserve_symbol.restype = None + thinlto_codegen_add_must_preserve_symbol.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char), ctypes.c_int32] +except AttributeError: + pass +try: + thinlto_codegen_add_cross_referenced_symbol = _libraries['llvm'].thinlto_codegen_add_cross_referenced_symbol + thinlto_codegen_add_cross_referenced_symbol.restype = None + thinlto_codegen_add_cross_referenced_symbol.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char), ctypes.c_int32] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_dir = _libraries['llvm'].thinlto_codegen_set_cache_dir + thinlto_codegen_set_cache_dir.restype = None + thinlto_codegen_set_cache_dir.argtypes = [thinlto_code_gen_t, ctypes.POINTER(ctypes.c_char)] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_pruning_interval = _libraries['llvm'].thinlto_codegen_set_cache_pruning_interval + thinlto_codegen_set_cache_pruning_interval.restype = None + thinlto_codegen_set_cache_pruning_interval.argtypes = [thinlto_code_gen_t, ctypes.c_int32] +except AttributeError: + pass +try: + thinlto_codegen_set_final_cache_size_relative_to_available_space = _libraries['llvm'].thinlto_codegen_set_final_cache_size_relative_to_available_space + thinlto_codegen_set_final_cache_size_relative_to_available_space.restype = None + thinlto_codegen_set_final_cache_size_relative_to_available_space.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_entry_expiration = _libraries['llvm'].thinlto_codegen_set_cache_entry_expiration + thinlto_codegen_set_cache_entry_expiration.restype = None + thinlto_codegen_set_cache_entry_expiration.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_size_bytes = _libraries['llvm'].thinlto_codegen_set_cache_size_bytes + thinlto_codegen_set_cache_size_bytes.restype = None + thinlto_codegen_set_cache_size_bytes.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_size_megabytes = _libraries['llvm'].thinlto_codegen_set_cache_size_megabytes + thinlto_codegen_set_cache_size_megabytes.restype = None + thinlto_codegen_set_cache_size_megabytes.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +try: + thinlto_codegen_set_cache_size_files = _libraries['llvm'].thinlto_codegen_set_cache_size_files + thinlto_codegen_set_cache_size_files.restype = None + thinlto_codegen_set_cache_size_files.argtypes = [thinlto_code_gen_t, ctypes.c_uint32] +except AttributeError: + pass +__all__ = \ + ['LLVMABIAlignmentOfType', 'LLVMABISizeOfType', + 'LLVMAMDGPUCSCallConv', 'LLVMAMDGPUESCallConv', + 'LLVMAMDGPUGSCallConv', 'LLVMAMDGPUHSCallConv', + 'LLVMAMDGPUKERNELCallConv', 'LLVMAMDGPULSCallConv', + 'LLVMAMDGPUPSCallConv', 'LLVMAMDGPUVSCallConv', + 'LLVMARMAAPCSCallConv', 'LLVMARMAAPCSVFPCallConv', + 'LLVMARMAPCSCallConv', 'LLVMAShr', 'LLVMAVRBUILTINCallConv', + 'LLVMAVRINTRCallConv', 'LLVMAVRSIGNALCallConv', + 'LLVMAbortProcessAction', 'LLVMAdd', + 'LLVMAddAddDiscriminatorsPass', 'LLVMAddAggressiveDCEPass', + 'LLVMAddAggressiveInstCombinerPass', 'LLVMAddAlias', + 'LLVMAddAlias2', 'LLVMAddAlignmentFromAssumptionsPass', + 'LLVMAddAlwaysInlinerPass', 'LLVMAddAnalysisPasses', + 'LLVMAddArgumentPromotionPass', 'LLVMAddAttributeAtIndex', + 'LLVMAddBasicAliasAnalysisPass', 'LLVMAddBitTrackingDCEPass', + 'LLVMAddCFGSimplificationPass', 'LLVMAddCallSiteAttribute', + 'LLVMAddCalledValuePropagationPass', 'LLVMAddCase', + 'LLVMAddClause', 'LLVMAddConstantMergePass', + 'LLVMAddCoroCleanupPass', 'LLVMAddCoroEarlyPass', + 'LLVMAddCoroElidePass', 'LLVMAddCoroSplitPass', + 'LLVMAddCorrelatedValuePropagationPass', 'LLVMAddDCEPass', + 'LLVMAddDeadArgEliminationPass', + 'LLVMAddDeadStoreEliminationPass', + 'LLVMAddDemoteMemoryToRegisterPass', 'LLVMAddDestination', + 'LLVMAddEarlyCSEMemSSAPass', 'LLVMAddEarlyCSEPass', + 'LLVMAddFunction', 'LLVMAddFunctionAttrsPass', + 'LLVMAddFunctionInliningPass', 'LLVMAddGVNPass', 'LLVMAddGlobal', + 'LLVMAddGlobalDCEPass', 'LLVMAddGlobalIFunc', + 'LLVMAddGlobalInAddressSpace', 'LLVMAddGlobalMapping', + 'LLVMAddGlobalOptimizerPass', 'LLVMAddHandler', + 'LLVMAddIPSCCPPass', 'LLVMAddIncoming', + 'LLVMAddIndVarSimplifyPass', 'LLVMAddInstructionCombiningPass', + 'LLVMAddInstructionSimplifyPass', 'LLVMAddInternalizePass', + 'LLVMAddInternalizePassWithMustPreservePredicate', + 'LLVMAddJumpThreadingPass', 'LLVMAddLICMPass', + 'LLVMAddLoopDeletionPass', 'LLVMAddLoopIdiomPass', + 'LLVMAddLoopRerollPass', 'LLVMAddLoopRotatePass', + 'LLVMAddLoopUnrollAndJamPass', 'LLVMAddLoopUnrollPass', + 'LLVMAddLoopUnswitchPass', 'LLVMAddLoopVectorizePass', + 'LLVMAddLowerAtomicPass', 'LLVMAddLowerConstantIntrinsicsPass', + 'LLVMAddLowerExpectIntrinsicPass', 'LLVMAddLowerSwitchPass', + 'LLVMAddMemCpyOptPass', 'LLVMAddMergeFunctionsPass', + 'LLVMAddMergedLoadStoreMotionPass', 'LLVMAddMetadataToInst', + 'LLVMAddModule', 'LLVMAddModuleFlag', + 'LLVMAddNamedMetadataOperand', 'LLVMAddNewGVNPass', + 'LLVMAddPartiallyInlineLibCallsPass', + 'LLVMAddPromoteMemoryToRegisterPass', 'LLVMAddPruneEHPass', + 'LLVMAddReassociatePass', 'LLVMAddSCCPPass', + 'LLVMAddSLPVectorizePass', 'LLVMAddScalarReplAggregatesPass', + 'LLVMAddScalarReplAggregatesPassSSA', + 'LLVMAddScalarReplAggregatesPassWithThreshold', + 'LLVMAddScalarizerPass', 'LLVMAddScopedNoAliasAAPass', + 'LLVMAddSimplifyLibCallsPass', 'LLVMAddStripDeadPrototypesPass', + 'LLVMAddStripSymbolsPass', 'LLVMAddSymbol', + 'LLVMAddTailCallEliminationPass', + 'LLVMAddTargetDependentFunctionAttr', 'LLVMAddTargetLibraryInfo', + 'LLVMAddTypeBasedAliasAnalysisPass', + 'LLVMAddUnifyFunctionExitNodesPass', 'LLVMAddVerifierPass', + 'LLVMAddrSpaceCast', 'LLVMAliasGetAliasee', 'LLVMAliasSetAliasee', + 'LLVMAlignOf', 'LLVMAlloca', 'LLVMAnd', + 'LLVMAnyComdatSelectionKind', 'LLVMAnyRegCallConv', + 'LLVMAppendBasicBlock', 'LLVMAppendBasicBlockInContext', + 'LLVMAppendExistingBasicBlock', 'LLVMAppendModuleInlineAsm', + 'LLVMAppendingLinkage', 'LLVMArgumentValueKind', 'LLVMArrayType', + 'LLVMArrayTypeKind', 'LLVMAssemblyFile', 'LLVMAtomicCmpXchg', + 'LLVMAtomicOrdering', 'LLVMAtomicOrderingAcquire', + 'LLVMAtomicOrderingAcquireRelease', 'LLVMAtomicOrderingMonotonic', + 'LLVMAtomicOrderingNotAtomic', 'LLVMAtomicOrderingRelease', + 'LLVMAtomicOrderingSequentiallyConsistent', + 'LLVMAtomicOrderingUnordered', 'LLVMAtomicOrdering__enumvalues', + 'LLVMAtomicRMW', 'LLVMAtomicRMWBinOp', 'LLVMAtomicRMWBinOpAdd', + 'LLVMAtomicRMWBinOpAnd', 'LLVMAtomicRMWBinOpFAdd', + 'LLVMAtomicRMWBinOpFSub', 'LLVMAtomicRMWBinOpMax', + 'LLVMAtomicRMWBinOpMin', 'LLVMAtomicRMWBinOpNand', + 'LLVMAtomicRMWBinOpOr', 'LLVMAtomicRMWBinOpSub', + 'LLVMAtomicRMWBinOpUMax', 'LLVMAtomicRMWBinOpUMin', + 'LLVMAtomicRMWBinOpXchg', 'LLVMAtomicRMWBinOpXor', + 'LLVMAtomicRMWBinOp__enumvalues', 'LLVMAttributeFunctionIndex', + 'LLVMAttributeIndex', 'LLVMAttributeRef', + 'LLVMAttributeReturnIndex', 'LLVMAvailableExternallyLinkage', + 'LLVMBFloatType', 'LLVMBFloatTypeInContext', 'LLVMBFloatTypeKind', + 'LLVMBasicBlockAsValue', 'LLVMBasicBlockRef', + 'LLVMBasicBlockValueKind', 'LLVMBigEndian', + 'LLVMBinaryCopyMemoryBuffer', 'LLVMBinaryGetType', + 'LLVMBinaryRef', 'LLVMBinaryType', 'LLVMBinaryTypeArchive', + 'LLVMBinaryTypeCOFF', 'LLVMBinaryTypeCOFFImportFile', + 'LLVMBinaryTypeELF32B', 'LLVMBinaryTypeELF32L', + 'LLVMBinaryTypeELF64B', 'LLVMBinaryTypeELF64L', + 'LLVMBinaryTypeIR', 'LLVMBinaryTypeMachO32B', + 'LLVMBinaryTypeMachO32L', 'LLVMBinaryTypeMachO64B', + 'LLVMBinaryTypeMachO64L', 'LLVMBinaryTypeMachOUniversalBinary', + 'LLVMBinaryTypeWasm', 'LLVMBinaryTypeWinRes', + 'LLVMBinaryType__enumvalues', 'LLVMBitCast', 'LLVMBlockAddress', + 'LLVMBlockAddressValueKind', 'LLVMBool', 'LLVMBr', + 'LLVMBuildAShr', 'LLVMBuildAdd', 'LLVMBuildAddrSpaceCast', + 'LLVMBuildAggregateRet', 'LLVMBuildAlloca', 'LLVMBuildAnd', + 'LLVMBuildArrayAlloca', 'LLVMBuildArrayMalloc', + 'LLVMBuildAtomicCmpXchg', 'LLVMBuildAtomicRMW', 'LLVMBuildBinOp', + 'LLVMBuildBitCast', 'LLVMBuildBr', 'LLVMBuildCall', + 'LLVMBuildCall2', 'LLVMBuildCast', 'LLVMBuildCatchPad', + 'LLVMBuildCatchRet', 'LLVMBuildCatchSwitch', + 'LLVMBuildCleanupPad', 'LLVMBuildCleanupRet', 'LLVMBuildCondBr', + 'LLVMBuildExactSDiv', 'LLVMBuildExactUDiv', + 'LLVMBuildExtractElement', 'LLVMBuildExtractValue', + 'LLVMBuildFAdd', 'LLVMBuildFCmp', 'LLVMBuildFDiv', + 'LLVMBuildFMul', 'LLVMBuildFNeg', 'LLVMBuildFPCast', + 'LLVMBuildFPExt', 'LLVMBuildFPToSI', 'LLVMBuildFPToUI', + 'LLVMBuildFPTrunc', 'LLVMBuildFRem', 'LLVMBuildFSub', + 'LLVMBuildFence', 'LLVMBuildFree', 'LLVMBuildFreeze', + 'LLVMBuildGEP', 'LLVMBuildGEP2', 'LLVMBuildGlobalString', + 'LLVMBuildGlobalStringPtr', 'LLVMBuildICmp', + 'LLVMBuildInBoundsGEP', 'LLVMBuildInBoundsGEP2', + 'LLVMBuildIndirectBr', 'LLVMBuildInsertElement', + 'LLVMBuildInsertValue', 'LLVMBuildIntCast', 'LLVMBuildIntCast2', + 'LLVMBuildIntToPtr', 'LLVMBuildInvoke', 'LLVMBuildInvoke2', + 'LLVMBuildIsNotNull', 'LLVMBuildIsNull', 'LLVMBuildLShr', + 'LLVMBuildLandingPad', 'LLVMBuildLoad', 'LLVMBuildLoad2', + 'LLVMBuildMalloc', 'LLVMBuildMemCpy', 'LLVMBuildMemMove', + 'LLVMBuildMemSet', 'LLVMBuildMul', 'LLVMBuildNSWAdd', + 'LLVMBuildNSWMul', 'LLVMBuildNSWNeg', 'LLVMBuildNSWSub', + 'LLVMBuildNUWAdd', 'LLVMBuildNUWMul', 'LLVMBuildNUWNeg', + 'LLVMBuildNUWSub', 'LLVMBuildNeg', 'LLVMBuildNot', 'LLVMBuildOr', + 'LLVMBuildPhi', 'LLVMBuildPointerCast', 'LLVMBuildPtrDiff', + 'LLVMBuildPtrDiff2', 'LLVMBuildPtrToInt', 'LLVMBuildResume', + 'LLVMBuildRet', 'LLVMBuildRetVoid', 'LLVMBuildSDiv', + 'LLVMBuildSExt', 'LLVMBuildSExtOrBitCast', 'LLVMBuildSIToFP', + 'LLVMBuildSRem', 'LLVMBuildSelect', 'LLVMBuildShl', + 'LLVMBuildShuffleVector', 'LLVMBuildStore', 'LLVMBuildStructGEP', + 'LLVMBuildStructGEP2', 'LLVMBuildSub', 'LLVMBuildSwitch', + 'LLVMBuildTrunc', 'LLVMBuildTruncOrBitCast', 'LLVMBuildUDiv', + 'LLVMBuildUIToFP', 'LLVMBuildURem', 'LLVMBuildUnreachable', + 'LLVMBuildVAArg', 'LLVMBuildXor', 'LLVMBuildZExt', + 'LLVMBuildZExtOrBitCast', 'LLVMBuilderGetDefaultFPMathTag', + 'LLVMBuilderRef', 'LLVMBuilderSetDefaultFPMathTag', + 'LLVMByteOrder', 'LLVMByteOrdering', 'LLVMCCallConv', + 'LLVMCXXFASTTLSCallConv', 'LLVMCall', 'LLVMCallBr', + 'LLVMCallConv', 'LLVMCallConv__enumvalues', + 'LLVMCallFrameAlignmentOfType', 'LLVMCatchPad', 'LLVMCatchRet', + 'LLVMCatchSwitch', 'LLVMCleanupPad', 'LLVMCleanupRet', + 'LLVMClearInsertionPosition', 'LLVMCloneModule', + 'LLVMCodeGenFileType', 'LLVMCodeGenFileType__enumvalues', + 'LLVMCodeGenLevelAggressive', 'LLVMCodeGenLevelDefault', + 'LLVMCodeGenLevelLess', 'LLVMCodeGenLevelNone', + 'LLVMCodeGenOptLevel', 'LLVMCodeGenOptLevel__enumvalues', + 'LLVMCodeModel', 'LLVMCodeModelDefault', + 'LLVMCodeModelJITDefault', 'LLVMCodeModelKernel', + 'LLVMCodeModelLarge', 'LLVMCodeModelMedium', 'LLVMCodeModelSmall', + 'LLVMCodeModelTiny', 'LLVMCodeModel__enumvalues', + 'LLVMColdCallConv', 'LLVMComdatRef', 'LLVMComdatSelectionKind', + 'LLVMComdatSelectionKind__enumvalues', 'LLVMCommonLinkage', + 'LLVMConstAShr', 'LLVMConstAdd', 'LLVMConstAddrSpaceCast', + 'LLVMConstAllOnes', 'LLVMConstAnd', 'LLVMConstArray', + 'LLVMConstBitCast', 'LLVMConstExactSDiv', 'LLVMConstExactUDiv', + 'LLVMConstExtractElement', 'LLVMConstExtractValue', + 'LLVMConstFAdd', 'LLVMConstFCmp', 'LLVMConstFDiv', + 'LLVMConstFMul', 'LLVMConstFNeg', 'LLVMConstFPCast', + 'LLVMConstFPExt', 'LLVMConstFPToSI', 'LLVMConstFPToUI', + 'LLVMConstFPTrunc', 'LLVMConstFRem', 'LLVMConstFSub', + 'LLVMConstGEP', 'LLVMConstGEP2', 'LLVMConstICmp', + 'LLVMConstInBoundsGEP', 'LLVMConstInBoundsGEP2', + 'LLVMConstInlineAsm', 'LLVMConstInsertElement', + 'LLVMConstInsertValue', 'LLVMConstInt', 'LLVMConstIntCast', + 'LLVMConstIntGetSExtValue', 'LLVMConstIntGetZExtValue', + 'LLVMConstIntOfArbitraryPrecision', 'LLVMConstIntOfString', + 'LLVMConstIntOfStringAndSize', 'LLVMConstIntToPtr', + 'LLVMConstLShr', 'LLVMConstMul', 'LLVMConstNSWAdd', + 'LLVMConstNSWMul', 'LLVMConstNSWNeg', 'LLVMConstNSWSub', + 'LLVMConstNUWAdd', 'LLVMConstNUWMul', 'LLVMConstNUWNeg', + 'LLVMConstNUWSub', 'LLVMConstNamedStruct', 'LLVMConstNeg', + 'LLVMConstNot', 'LLVMConstNull', 'LLVMConstOr', + 'LLVMConstPointerCast', 'LLVMConstPointerNull', + 'LLVMConstPtrToInt', 'LLVMConstReal', 'LLVMConstRealGetDouble', + 'LLVMConstRealOfString', 'LLVMConstRealOfStringAndSize', + 'LLVMConstSDiv', 'LLVMConstSExt', 'LLVMConstSExtOrBitCast', + 'LLVMConstSIToFP', 'LLVMConstSRem', 'LLVMConstSelect', + 'LLVMConstShl', 'LLVMConstShuffleVector', 'LLVMConstString', + 'LLVMConstStringInContext', 'LLVMConstStruct', + 'LLVMConstStructInContext', 'LLVMConstSub', 'LLVMConstTrunc', + 'LLVMConstTruncOrBitCast', 'LLVMConstUDiv', 'LLVMConstUIToFP', + 'LLVMConstURem', 'LLVMConstVector', 'LLVMConstXor', + 'LLVMConstZExt', 'LLVMConstZExtOrBitCast', + 'LLVMConstantAggregateZeroValueKind', + 'LLVMConstantArrayValueKind', + 'LLVMConstantAsMetadataMetadataKind', + 'LLVMConstantDataArrayValueKind', + 'LLVMConstantDataVectorValueKind', 'LLVMConstantExprValueKind', + 'LLVMConstantFPValueKind', 'LLVMConstantIntValueKind', + 'LLVMConstantPointerNullValueKind', 'LLVMConstantStructValueKind', + 'LLVMConstantTokenNoneValueKind', 'LLVMConstantVectorValueKind', + 'LLVMConsumeError', 'LLVMContextCreate', 'LLVMContextDispose', + 'LLVMContextGetDiagnosticContext', + 'LLVMContextGetDiagnosticHandler', 'LLVMContextRef', + 'LLVMContextSetDiagnosticHandler', + 'LLVMContextSetDiscardValueNames', 'LLVMContextSetYieldCallback', + 'LLVMContextShouldDiscardValueNames', + 'LLVMCopyModuleFlagsMetadata', 'LLVMCopyStringRepOfTargetData', + 'LLVMCountBasicBlocks', 'LLVMCountIncoming', + 'LLVMCountParamTypes', 'LLVMCountParams', + 'LLVMCountStructElementTypes', 'LLVMCreateBasicBlockInContext', + 'LLVMCreateBinary', 'LLVMCreateBuilder', + 'LLVMCreateBuilderInContext', 'LLVMCreateDIBuilder', + 'LLVMCreateDIBuilderDisallowUnresolved', 'LLVMCreateDisasm', + 'LLVMCreateDisasmCPU', 'LLVMCreateDisasmCPUFeatures', + 'LLVMCreateEnumAttribute', 'LLVMCreateExecutionEngineForModule', + 'LLVMCreateFunctionPassManager', + 'LLVMCreateFunctionPassManagerForModule', + 'LLVMCreateGDBRegistrationListener', + 'LLVMCreateGenericValueOfFloat', 'LLVMCreateGenericValueOfInt', + 'LLVMCreateGenericValueOfPointer', + 'LLVMCreateIntelJITEventListener', + 'LLVMCreateInterpreterForModule', + 'LLVMCreateJITCompilerForModule', + 'LLVMCreateMCJITCompilerForModule', + 'LLVMCreateMemoryBufferWithContentsOfFile', + 'LLVMCreateMemoryBufferWithMemoryRange', + 'LLVMCreateMemoryBufferWithMemoryRangeCopy', + 'LLVMCreateMemoryBufferWithSTDIN', 'LLVMCreateMessage', + 'LLVMCreateModuleProviderForExistingModule', + 'LLVMCreateOProfileJITEventListener', 'LLVMCreateObjectFile', + 'LLVMCreatePassBuilderOptions', 'LLVMCreatePassManager', + 'LLVMCreatePerfJITEventListener', + 'LLVMCreateSimpleMCJITMemoryManager', 'LLVMCreateStringAttribute', + 'LLVMCreateStringError', 'LLVMCreateTargetData', + 'LLVMCreateTargetDataLayout', 'LLVMCreateTargetMachine', + 'LLVMCreateTypeAttribute', 'LLVMDIArgListMetadataKind', + 'LLVMDIBasicTypeMetadataKind', 'LLVMDIBuilderCreateArrayType', + 'LLVMDIBuilderCreateArtificialType', + 'LLVMDIBuilderCreateAutoVariable', 'LLVMDIBuilderCreateBasicType', + 'LLVMDIBuilderCreateBitFieldMemberType', + 'LLVMDIBuilderCreateClassType', 'LLVMDIBuilderCreateCompileUnit', + 'LLVMDIBuilderCreateConstantValueExpression', + 'LLVMDIBuilderCreateDebugLocation', + 'LLVMDIBuilderCreateEnumerationType', + 'LLVMDIBuilderCreateEnumerator', 'LLVMDIBuilderCreateExpression', + 'LLVMDIBuilderCreateFile', 'LLVMDIBuilderCreateForwardDecl', + 'LLVMDIBuilderCreateFunction', + 'LLVMDIBuilderCreateGlobalVariableExpression', + 'LLVMDIBuilderCreateImportedDeclaration', + 'LLVMDIBuilderCreateImportedModuleFromAlias', + 'LLVMDIBuilderCreateImportedModuleFromModule', + 'LLVMDIBuilderCreateImportedModuleFromNamespace', + 'LLVMDIBuilderCreateInheritance', + 'LLVMDIBuilderCreateLexicalBlock', + 'LLVMDIBuilderCreateLexicalBlockFile', 'LLVMDIBuilderCreateMacro', + 'LLVMDIBuilderCreateMemberPointerType', + 'LLVMDIBuilderCreateMemberType', 'LLVMDIBuilderCreateModule', + 'LLVMDIBuilderCreateNameSpace', 'LLVMDIBuilderCreateNullPtrType', + 'LLVMDIBuilderCreateObjCIVar', 'LLVMDIBuilderCreateObjCProperty', + 'LLVMDIBuilderCreateObjectPointerType', + 'LLVMDIBuilderCreateParameterVariable', + 'LLVMDIBuilderCreatePointerType', + 'LLVMDIBuilderCreateQualifiedType', + 'LLVMDIBuilderCreateReferenceType', + 'LLVMDIBuilderCreateReplaceableCompositeType', + 'LLVMDIBuilderCreateStaticMemberType', + 'LLVMDIBuilderCreateStructType', + 'LLVMDIBuilderCreateSubroutineType', + 'LLVMDIBuilderCreateTempGlobalVariableFwdDecl', + 'LLVMDIBuilderCreateTempMacroFile', 'LLVMDIBuilderCreateTypedef', + 'LLVMDIBuilderCreateUnionType', + 'LLVMDIBuilderCreateUnspecifiedType', + 'LLVMDIBuilderCreateVectorType', 'LLVMDIBuilderFinalize', + 'LLVMDIBuilderFinalizeSubprogram', + 'LLVMDIBuilderGetOrCreateArray', + 'LLVMDIBuilderGetOrCreateSubrange', + 'LLVMDIBuilderGetOrCreateTypeArray', + 'LLVMDIBuilderInsertDbgValueAtEnd', + 'LLVMDIBuilderInsertDbgValueBefore', + 'LLVMDIBuilderInsertDeclareAtEnd', + 'LLVMDIBuilderInsertDeclareBefore', 'LLVMDIBuilderRef', + 'LLVMDICommonBlockMetadataKind', 'LLVMDICompileUnitMetadataKind', + 'LLVMDICompositeTypeMetadataKind', + 'LLVMDIDerivedTypeMetadataKind', 'LLVMDIEnumeratorMetadataKind', + 'LLVMDIExpressionMetadataKind', 'LLVMDIFileGetDirectory', + 'LLVMDIFileGetFilename', 'LLVMDIFileGetSource', + 'LLVMDIFileMetadataKind', 'LLVMDIFlagAccessibility', + 'LLVMDIFlagAppleBlock', 'LLVMDIFlagArtificial', + 'LLVMDIFlagBigEndian', 'LLVMDIFlagBitField', + 'LLVMDIFlagEnumClass', 'LLVMDIFlagExplicit', + 'LLVMDIFlagFixedEnum', 'LLVMDIFlagFwdDecl', + 'LLVMDIFlagIndirectVirtualBase', 'LLVMDIFlagIntroducedVirtual', + 'LLVMDIFlagLValueReference', 'LLVMDIFlagLittleEndian', + 'LLVMDIFlagMultipleInheritance', 'LLVMDIFlagNoReturn', + 'LLVMDIFlagNonTrivial', 'LLVMDIFlagObjcClassComplete', + 'LLVMDIFlagObjectPointer', 'LLVMDIFlagPrivate', + 'LLVMDIFlagProtected', 'LLVMDIFlagPrototyped', + 'LLVMDIFlagPtrToMemberRep', 'LLVMDIFlagPublic', + 'LLVMDIFlagRValueReference', 'LLVMDIFlagReserved', + 'LLVMDIFlagReservedBit4', 'LLVMDIFlagSingleInheritance', + 'LLVMDIFlagStaticMember', 'LLVMDIFlagThunk', + 'LLVMDIFlagTypePassByReference', 'LLVMDIFlagTypePassByValue', + 'LLVMDIFlagVector', 'LLVMDIFlagVirtual', + 'LLVMDIFlagVirtualInheritance', 'LLVMDIFlagZero', 'LLVMDIFlags', + 'LLVMDIFlags__enumvalues', 'LLVMDIGenericSubrangeMetadataKind', + 'LLVMDIGlobalVariableExpressionGetExpression', + 'LLVMDIGlobalVariableExpressionGetVariable', + 'LLVMDIGlobalVariableExpressionMetadataKind', + 'LLVMDIGlobalVariableMetadataKind', + 'LLVMDIImportedEntityMetadataKind', 'LLVMDILabelMetadataKind', + 'LLVMDILexicalBlockFileMetadataKind', + 'LLVMDILexicalBlockMetadataKind', + 'LLVMDILocalVariableMetadataKind', 'LLVMDILocationGetColumn', + 'LLVMDILocationGetInlinedAt', 'LLVMDILocationGetLine', + 'LLVMDILocationGetScope', 'LLVMDILocationMetadataKind', + 'LLVMDIMacroFileMetadataKind', 'LLVMDIMacroMetadataKind', + 'LLVMDIModuleMetadataKind', 'LLVMDINamespaceMetadataKind', + 'LLVMDIObjCPropertyMetadataKind', 'LLVMDIScopeGetFile', + 'LLVMDIStringTypeMetadataKind', 'LLVMDISubprogramGetLine', + 'LLVMDISubprogramMetadataKind', 'LLVMDISubrangeMetadataKind', + 'LLVMDISubroutineTypeMetadataKind', + 'LLVMDITemplateTypeParameterMetadataKind', + 'LLVMDITemplateValueParameterMetadataKind', + 'LLVMDITypeGetAlignInBits', 'LLVMDITypeGetFlags', + 'LLVMDITypeGetLine', 'LLVMDITypeGetName', + 'LLVMDITypeGetOffsetInBits', 'LLVMDITypeGetSizeInBits', + 'LLVMDIVariableGetFile', 'LLVMDIVariableGetLine', + 'LLVMDIVariableGetScope', 'LLVMDLLExportLinkage', + 'LLVMDLLExportStorageClass', 'LLVMDLLImportLinkage', + 'LLVMDLLImportStorageClass', 'LLVMDLLStorageClass', + 'LLVMDLLStorageClass__enumvalues', 'LLVMDSError', 'LLVMDSNote', + 'LLVMDSRemark', 'LLVMDSWarning', 'LLVMDWARFEmissionFull', + 'LLVMDWARFEmissionKind', 'LLVMDWARFEmissionKind__enumvalues', + 'LLVMDWARFEmissionLineTablesOnly', 'LLVMDWARFEmissionNone', + 'LLVMDWARFMacinfoRecordType', 'LLVMDWARFMacinfoRecordTypeDefine', + 'LLVMDWARFMacinfoRecordTypeEndFile', + 'LLVMDWARFMacinfoRecordTypeMacro', + 'LLVMDWARFMacinfoRecordTypeStartFile', + 'LLVMDWARFMacinfoRecordTypeVendorExt', + 'LLVMDWARFMacinfoRecordType__enumvalues', + 'LLVMDWARFSourceLanguage', 'LLVMDWARFSourceLanguageAda83', + 'LLVMDWARFSourceLanguageAda95', 'LLVMDWARFSourceLanguageBLISS', + 'LLVMDWARFSourceLanguageBORLAND_Delphi', + 'LLVMDWARFSourceLanguageC', 'LLVMDWARFSourceLanguageC11', + 'LLVMDWARFSourceLanguageC89', 'LLVMDWARFSourceLanguageC99', + 'LLVMDWARFSourceLanguageC_plus_plus', + 'LLVMDWARFSourceLanguageC_plus_plus_03', + 'LLVMDWARFSourceLanguageC_plus_plus_11', + 'LLVMDWARFSourceLanguageC_plus_plus_14', + 'LLVMDWARFSourceLanguageCobol74', + 'LLVMDWARFSourceLanguageCobol85', 'LLVMDWARFSourceLanguageD', + 'LLVMDWARFSourceLanguageDylan', + 'LLVMDWARFSourceLanguageFortran03', + 'LLVMDWARFSourceLanguageFortran08', + 'LLVMDWARFSourceLanguageFortran77', + 'LLVMDWARFSourceLanguageFortran90', + 'LLVMDWARFSourceLanguageFortran95', + 'LLVMDWARFSourceLanguageGOOGLE_RenderScript', + 'LLVMDWARFSourceLanguageGo', 'LLVMDWARFSourceLanguageHaskell', + 'LLVMDWARFSourceLanguageJava', 'LLVMDWARFSourceLanguageJulia', + 'LLVMDWARFSourceLanguageMips_Assembler', + 'LLVMDWARFSourceLanguageModula2', + 'LLVMDWARFSourceLanguageModula3', 'LLVMDWARFSourceLanguageOCaml', + 'LLVMDWARFSourceLanguageObjC', + 'LLVMDWARFSourceLanguageObjC_plus_plus', + 'LLVMDWARFSourceLanguageOpenCL', 'LLVMDWARFSourceLanguagePLI', + 'LLVMDWARFSourceLanguagePascal83', + 'LLVMDWARFSourceLanguagePython', + 'LLVMDWARFSourceLanguageRenderScript', + 'LLVMDWARFSourceLanguageRust', 'LLVMDWARFSourceLanguageSwift', + 'LLVMDWARFSourceLanguageUPC', + 'LLVMDWARFSourceLanguage__enumvalues', 'LLVMDWARFTypeEncoding', + 'LLVMDebugMetadataVersion', 'LLVMDefaultStorageClass', + 'LLVMDefaultVisibility', 'LLVMDeleteBasicBlock', + 'LLVMDeleteFunction', 'LLVMDeleteGlobal', 'LLVMDiagnosticHandler', + 'LLVMDiagnosticInfoRef', 'LLVMDiagnosticSeverity', + 'LLVMDiagnosticSeverity__enumvalues', 'LLVMDisasmContextRef', + 'LLVMDisasmDispose', 'LLVMDisasmInstruction', + 'LLVMDisassembler_Option_AsmPrinterVariant', + 'LLVMDisassembler_Option_PrintImmHex', + 'LLVMDisassembler_Option_PrintLatency', + 'LLVMDisassembler_Option_SetInstrComments', + 'LLVMDisassembler_Option_UseMarkup', + 'LLVMDisassembler_ReferenceType_DeMangled_Name', + 'LLVMDisassembler_ReferenceType_InOut_None', + 'LLVMDisassembler_ReferenceType_In_ARM64_ADDXri', + 'LLVMDisassembler_ReferenceType_In_ARM64_ADR', + 'LLVMDisassembler_ReferenceType_In_ARM64_ADRP', + 'LLVMDisassembler_ReferenceType_In_ARM64_LDRXl', + 'LLVMDisassembler_ReferenceType_In_ARM64_LDRXui', + 'LLVMDisassembler_ReferenceType_In_Branch', + 'LLVMDisassembler_ReferenceType_In_PCrel_Load', + 'LLVMDisassembler_ReferenceType_Out_LitPool_CstrAddr', + 'LLVMDisassembler_ReferenceType_Out_LitPool_SymAddr', + 'LLVMDisassembler_ReferenceType_Out_Objc_CFString_Ref', + 'LLVMDisassembler_ReferenceType_Out_Objc_Class_Ref', + 'LLVMDisassembler_ReferenceType_Out_Objc_Message', + 'LLVMDisassembler_ReferenceType_Out_Objc_Message_Ref', + 'LLVMDisassembler_ReferenceType_Out_Objc_Selector_Ref', + 'LLVMDisassembler_ReferenceType_Out_SymbolStub', + 'LLVMDisassembler_VariantKind_ARM64_GOTPAGE', + 'LLVMDisassembler_VariantKind_ARM64_GOTPAGEOFF', + 'LLVMDisassembler_VariantKind_ARM64_PAGE', + 'LLVMDisassembler_VariantKind_ARM64_PAGEOFF', + 'LLVMDisassembler_VariantKind_ARM64_TLVOFF', + 'LLVMDisassembler_VariantKind_ARM64_TLVP', + 'LLVMDisassembler_VariantKind_ARM_HI16', + 'LLVMDisassembler_VariantKind_ARM_LO16', + 'LLVMDisassembler_VariantKind_None', 'LLVMDisposeBinary', + 'LLVMDisposeBuilder', 'LLVMDisposeDIBuilder', + 'LLVMDisposeErrorMessage', 'LLVMDisposeExecutionEngine', + 'LLVMDisposeGenericValue', 'LLVMDisposeMCJITMemoryManager', + 'LLVMDisposeMemoryBuffer', 'LLVMDisposeMessage', + 'LLVMDisposeModule', 'LLVMDisposeModuleFlagsMetadata', + 'LLVMDisposeModuleProvider', 'LLVMDisposeObjectFile', + 'LLVMDisposePassBuilderOptions', 'LLVMDisposePassManager', + 'LLVMDisposeRelocationIterator', 'LLVMDisposeSectionIterator', + 'LLVMDisposeSymbolIterator', 'LLVMDisposeTargetData', + 'LLVMDisposeTargetMachine', 'LLVMDisposeTemporaryMDNode', + 'LLVMDisposeValueMetadataEntries', + 'LLVMDistinctMDOperandPlaceholderMetadataKind', 'LLVMDoubleType', + 'LLVMDoubleTypeInContext', 'LLVMDoubleTypeKind', 'LLVMDumpModule', + 'LLVMDumpType', 'LLVMDumpValue', 'LLVMElementAtOffset', + 'LLVMEnablePrettyStackTrace', 'LLVMEraseGlobalIFunc', + 'LLVMErrorRef', 'LLVMErrorSuccess', 'LLVMErrorTypeId', + 'LLVMExactMatchComdatSelectionKind', + 'LLVMExecutionEngineGetErrMsg', 'LLVMExecutionEngineRef', + 'LLVMExternalLinkage', 'LLVMExternalWeakLinkage', + 'LLVMExtractElement', 'LLVMExtractValue', 'LLVMFAdd', 'LLVMFCmp', + 'LLVMFDiv', 'LLVMFMul', 'LLVMFNeg', 'LLVMFP128Type', + 'LLVMFP128TypeInContext', 'LLVMFP128TypeKind', 'LLVMFPExt', + 'LLVMFPToSI', 'LLVMFPToUI', 'LLVMFPTrunc', 'LLVMFRem', 'LLVMFSub', + 'LLVMFastCallConv', 'LLVMFatalErrorHandler', 'LLVMFence', + 'LLVMFinalizeFunctionPassManager', 'LLVMFindFunction', + 'LLVMFloatType', 'LLVMFloatTypeInContext', 'LLVMFloatTypeKind', + 'LLVMFreeMachineCodeForFunction', 'LLVMFreeze', + 'LLVMFunctionType', 'LLVMFunctionTypeKind', + 'LLVMFunctionValueKind', 'LLVMGHCCallConv', + 'LLVMGeneralDynamicTLSModel', 'LLVMGenericDINodeMetadataKind', + 'LLVMGenericValueIntWidth', 'LLVMGenericValueRef', + 'LLVMGenericValueToFloat', 'LLVMGenericValueToInt', + 'LLVMGenericValueToPointer', 'LLVMGetAlignment', + 'LLVMGetAllocatedType', 'LLVMGetArgOperand', 'LLVMGetArrayLength', + 'LLVMGetAsString', 'LLVMGetAtomicRMWBinOp', + 'LLVMGetAttributeCountAtIndex', 'LLVMGetAttributesAtIndex', + 'LLVMGetBasicBlockName', 'LLVMGetBasicBlockParent', + 'LLVMGetBasicBlockTerminator', 'LLVMGetBasicBlocks', + 'LLVMGetBitcodeModule', 'LLVMGetBitcodeModule2', + 'LLVMGetBitcodeModuleInContext', 'LLVMGetBitcodeModuleInContext2', + 'LLVMGetBufferSize', 'LLVMGetBufferStart', + 'LLVMGetCallSiteAttributeCount', 'LLVMGetCallSiteAttributes', + 'LLVMGetCallSiteEnumAttribute', 'LLVMGetCallSiteStringAttribute', + 'LLVMGetCalledFunctionType', 'LLVMGetCalledValue', + 'LLVMGetClause', 'LLVMGetCmpXchgFailureOrdering', + 'LLVMGetCmpXchgSuccessOrdering', 'LLVMGetComdat', + 'LLVMGetComdatSelectionKind', 'LLVMGetCondition', + 'LLVMGetConstOpcode', 'LLVMGetCurrentDebugLocation', + 'LLVMGetCurrentDebugLocation2', 'LLVMGetDLLStorageClass', + 'LLVMGetDataLayout', 'LLVMGetDataLayoutStr', + 'LLVMGetDebugLocColumn', 'LLVMGetDebugLocDirectory', + 'LLVMGetDebugLocFilename', 'LLVMGetDebugLocLine', + 'LLVMGetDefaultTargetTriple', 'LLVMGetDiagInfoDescription', + 'LLVMGetDiagInfoSeverity', 'LLVMGetElementAsConstant', + 'LLVMGetElementPtr', 'LLVMGetElementType', + 'LLVMGetEntryBasicBlock', 'LLVMGetEnumAttributeAtIndex', + 'LLVMGetEnumAttributeKind', 'LLVMGetEnumAttributeKindForName', + 'LLVMGetEnumAttributeValue', 'LLVMGetErrorMessage', + 'LLVMGetErrorTypeId', 'LLVMGetExecutionEngineTargetData', + 'LLVMGetExecutionEngineTargetMachine', 'LLVMGetFCmpPredicate', + 'LLVMGetFirstBasicBlock', 'LLVMGetFirstFunction', + 'LLVMGetFirstGlobal', 'LLVMGetFirstGlobalAlias', + 'LLVMGetFirstGlobalIFunc', 'LLVMGetFirstInstruction', + 'LLVMGetFirstNamedMetadata', 'LLVMGetFirstParam', + 'LLVMGetFirstTarget', 'LLVMGetFirstUse', 'LLVMGetFunctionAddress', + 'LLVMGetFunctionCallConv', 'LLVMGetGC', + 'LLVMGetGEPSourceElementType', 'LLVMGetGlobalContext', + 'LLVMGetGlobalIFuncResolver', 'LLVMGetGlobalParent', + 'LLVMGetGlobalPassRegistry', 'LLVMGetGlobalValueAddress', + 'LLVMGetHandlers', 'LLVMGetHostCPUFeatures', 'LLVMGetHostCPUName', + 'LLVMGetICmpPredicate', 'LLVMGetIncomingBlock', + 'LLVMGetIncomingValue', 'LLVMGetIndices', 'LLVMGetInitializer', + 'LLVMGetInlineAsm', 'LLVMGetInsertBlock', + 'LLVMGetInstructionCallConv', 'LLVMGetInstructionOpcode', + 'LLVMGetInstructionParent', 'LLVMGetIntTypeWidth', + 'LLVMGetIntrinsicDeclaration', 'LLVMGetIntrinsicID', + 'LLVMGetLastBasicBlock', 'LLVMGetLastEnumAttributeKind', + 'LLVMGetLastFunction', 'LLVMGetLastGlobal', + 'LLVMGetLastGlobalAlias', 'LLVMGetLastGlobalIFunc', + 'LLVMGetLastInstruction', 'LLVMGetLastNamedMetadata', + 'LLVMGetLastParam', 'LLVMGetLinkage', 'LLVMGetMDKindID', + 'LLVMGetMDKindIDInContext', 'LLVMGetMDNodeNumOperands', + 'LLVMGetMDNodeOperands', 'LLVMGetMDString', 'LLVMGetMaskValue', + 'LLVMGetMetadata', 'LLVMGetMetadataKind', 'LLVMGetModuleContext', + 'LLVMGetModuleDataLayout', 'LLVMGetModuleDebugMetadataVersion', + 'LLVMGetModuleFlag', 'LLVMGetModuleIdentifier', + 'LLVMGetModuleInlineAsm', 'LLVMGetNamedFunction', + 'LLVMGetNamedGlobal', 'LLVMGetNamedGlobalAlias', + 'LLVMGetNamedGlobalIFunc', 'LLVMGetNamedMetadata', + 'LLVMGetNamedMetadataName', 'LLVMGetNamedMetadataNumOperands', + 'LLVMGetNamedMetadataOperands', 'LLVMGetNextBasicBlock', + 'LLVMGetNextFunction', 'LLVMGetNextGlobal', + 'LLVMGetNextGlobalAlias', 'LLVMGetNextGlobalIFunc', + 'LLVMGetNextInstruction', 'LLVMGetNextNamedMetadata', + 'LLVMGetNextParam', 'LLVMGetNextTarget', 'LLVMGetNextUse', + 'LLVMGetNormalDest', 'LLVMGetNumArgOperands', 'LLVMGetNumClauses', + 'LLVMGetNumContainedTypes', 'LLVMGetNumHandlers', + 'LLVMGetNumIndices', 'LLVMGetNumMaskElements', + 'LLVMGetNumOperands', 'LLVMGetNumSuccessors', 'LLVMGetOperand', + 'LLVMGetOperandUse', 'LLVMGetOrInsertComdat', + 'LLVMGetOrInsertNamedMetadata', 'LLVMGetOrdering', 'LLVMGetParam', + 'LLVMGetParamParent', 'LLVMGetParamTypes', 'LLVMGetParams', + 'LLVMGetParentCatchSwitch', 'LLVMGetPersonalityFn', + 'LLVMGetPointerAddressSpace', 'LLVMGetPointerToGlobal', + 'LLVMGetPoison', 'LLVMGetPreviousBasicBlock', + 'LLVMGetPreviousFunction', 'LLVMGetPreviousGlobal', + 'LLVMGetPreviousGlobalAlias', 'LLVMGetPreviousGlobalIFunc', + 'LLVMGetPreviousInstruction', 'LLVMGetPreviousNamedMetadata', + 'LLVMGetPreviousParam', 'LLVMGetRelocationOffset', + 'LLVMGetRelocationSymbol', 'LLVMGetRelocationType', + 'LLVMGetRelocationTypeName', 'LLVMGetRelocationValueString', + 'LLVMGetRelocations', 'LLVMGetReturnType', 'LLVMGetSection', + 'LLVMGetSectionAddress', 'LLVMGetSectionContainsSymbol', + 'LLVMGetSectionContents', 'LLVMGetSectionName', + 'LLVMGetSectionSize', 'LLVMGetSections', 'LLVMGetSourceFileName', + 'LLVMGetStringAttributeAtIndex', 'LLVMGetStringAttributeKind', + 'LLVMGetStringAttributeValue', 'LLVMGetStringErrorTypeId', + 'LLVMGetStructElementTypes', 'LLVMGetStructName', + 'LLVMGetSubprogram', 'LLVMGetSubtypes', 'LLVMGetSuccessor', + 'LLVMGetSwitchDefaultDest', 'LLVMGetSymbolAddress', + 'LLVMGetSymbolName', 'LLVMGetSymbolSize', 'LLVMGetSymbols', + 'LLVMGetTarget', 'LLVMGetTargetDescription', + 'LLVMGetTargetFromName', 'LLVMGetTargetFromTriple', + 'LLVMGetTargetMachineCPU', 'LLVMGetTargetMachineFeatureString', + 'LLVMGetTargetMachineTarget', 'LLVMGetTargetMachineTriple', + 'LLVMGetTargetName', 'LLVMGetThreadLocalMode', + 'LLVMGetTypeAttributeValue', 'LLVMGetTypeByName', + 'LLVMGetTypeByName2', 'LLVMGetTypeContext', 'LLVMGetTypeKind', + 'LLVMGetUndef', 'LLVMGetUndefMaskElem', 'LLVMGetUnnamedAddress', + 'LLVMGetUnwindDest', 'LLVMGetUsedValue', 'LLVMGetUser', + 'LLVMGetValueKind', 'LLVMGetValueName', 'LLVMGetValueName2', + 'LLVMGetVectorSize', 'LLVMGetVisibility', 'LLVMGetVolatile', + 'LLVMGetWeak', 'LLVMGhostLinkage', 'LLVMGlobalAliasValueKind', + 'LLVMGlobalClearMetadata', 'LLVMGlobalCopyAllMetadata', + 'LLVMGlobalEraseMetadata', 'LLVMGlobalGetValueType', + 'LLVMGlobalIFuncValueKind', 'LLVMGlobalSetMetadata', + 'LLVMGlobalUnnamedAddr', 'LLVMGlobalVariableValueKind', + 'LLVMHHVMCCallConv', 'LLVMHHVMCallConv', 'LLVMHalfType', + 'LLVMHalfTypeInContext', 'LLVMHalfTypeKind', 'LLVMHasMetadata', + 'LLVMHasPersonalityFn', 'LLVMHasUnnamedAddr', 'LLVMHiPECallConv', + 'LLVMHiddenVisibility', 'LLVMICmp', 'LLVMIndirectBr', + 'LLVMInitialExecTLSModel', 'LLVMInitializeAArch64AsmParser', + 'LLVMInitializeAArch64AsmPrinter', + 'LLVMInitializeAArch64Disassembler', + 'LLVMInitializeAArch64Target', 'LLVMInitializeAArch64TargetInfo', + 'LLVMInitializeAArch64TargetMC', 'LLVMInitializeAMDGPUAsmParser', + 'LLVMInitializeAMDGPUAsmPrinter', + 'LLVMInitializeAMDGPUDisassembler', 'LLVMInitializeAMDGPUTarget', + 'LLVMInitializeAMDGPUTargetInfo', 'LLVMInitializeAMDGPUTargetMC', + 'LLVMInitializeARMAsmParser', 'LLVMInitializeARMAsmPrinter', + 'LLVMInitializeARMDisassembler', 'LLVMInitializeARMTarget', + 'LLVMInitializeARMTargetInfo', 'LLVMInitializeARMTargetMC', + 'LLVMInitializeAVRAsmParser', 'LLVMInitializeAVRAsmPrinter', + 'LLVMInitializeAVRDisassembler', 'LLVMInitializeAVRTarget', + 'LLVMInitializeAVRTargetInfo', 'LLVMInitializeAVRTargetMC', + 'LLVMInitializeAggressiveInstCombiner', + 'LLVMInitializeAllAsmParsers', 'LLVMInitializeAllAsmPrinters', + 'LLVMInitializeAllDisassemblers', 'LLVMInitializeAllTargetInfos', + 'LLVMInitializeAllTargetMCs', 'LLVMInitializeAllTargets', + 'LLVMInitializeAnalysis', 'LLVMInitializeBPFAsmParser', + 'LLVMInitializeBPFAsmPrinter', 'LLVMInitializeBPFDisassembler', + 'LLVMInitializeBPFTarget', 'LLVMInitializeBPFTargetInfo', + 'LLVMInitializeBPFTargetMC', 'LLVMInitializeCodeGen', + 'LLVMInitializeCore', 'LLVMInitializeFunctionPassManager', + 'LLVMInitializeHexagonAsmParser', + 'LLVMInitializeHexagonAsmPrinter', + 'LLVMInitializeHexagonDisassembler', + 'LLVMInitializeHexagonTarget', 'LLVMInitializeHexagonTargetInfo', + 'LLVMInitializeHexagonTargetMC', 'LLVMInitializeIPA', + 'LLVMInitializeIPO', 'LLVMInitializeInstCombine', + 'LLVMInitializeInstrumentation', 'LLVMInitializeLanaiAsmParser', + 'LLVMInitializeLanaiAsmPrinter', + 'LLVMInitializeLanaiDisassembler', 'LLVMInitializeLanaiTarget', + 'LLVMInitializeLanaiTargetInfo', 'LLVMInitializeLanaiTargetMC', + 'LLVMInitializeM68kAsmParser', 'LLVMInitializeM68kAsmPrinter', + 'LLVMInitializeM68kDisassembler', 'LLVMInitializeM68kTarget', + 'LLVMInitializeM68kTargetInfo', 'LLVMInitializeM68kTargetMC', + 'LLVMInitializeMCJITCompilerOptions', + 'LLVMInitializeMSP430AsmParser', 'LLVMInitializeMSP430AsmPrinter', + 'LLVMInitializeMSP430Disassembler', 'LLVMInitializeMSP430Target', + 'LLVMInitializeMSP430TargetInfo', 'LLVMInitializeMSP430TargetMC', + 'LLVMInitializeMipsAsmParser', 'LLVMInitializeMipsAsmPrinter', + 'LLVMInitializeMipsDisassembler', 'LLVMInitializeMipsTarget', + 'LLVMInitializeMipsTargetInfo', 'LLVMInitializeMipsTargetMC', + 'LLVMInitializeNVPTXAsmPrinter', 'LLVMInitializeNVPTXTarget', + 'LLVMInitializeNVPTXTargetInfo', 'LLVMInitializeNVPTXTargetMC', + 'LLVMInitializeNativeAsmParser', 'LLVMInitializeNativeAsmPrinter', + 'LLVMInitializeNativeDisassembler', 'LLVMInitializeNativeTarget', + 'LLVMInitializeObjCARCOpts', 'LLVMInitializePowerPCAsmParser', + 'LLVMInitializePowerPCAsmPrinter', + 'LLVMInitializePowerPCDisassembler', + 'LLVMInitializePowerPCTarget', 'LLVMInitializePowerPCTargetInfo', + 'LLVMInitializePowerPCTargetMC', 'LLVMInitializeRISCVAsmParser', + 'LLVMInitializeRISCVAsmPrinter', + 'LLVMInitializeRISCVDisassembler', 'LLVMInitializeRISCVTarget', + 'LLVMInitializeRISCVTargetInfo', 'LLVMInitializeRISCVTargetMC', + 'LLVMInitializeScalarOpts', 'LLVMInitializeSparcAsmParser', + 'LLVMInitializeSparcAsmPrinter', + 'LLVMInitializeSparcDisassembler', 'LLVMInitializeSparcTarget', + 'LLVMInitializeSparcTargetInfo', 'LLVMInitializeSparcTargetMC', + 'LLVMInitializeSystemZAsmParser', + 'LLVMInitializeSystemZAsmPrinter', + 'LLVMInitializeSystemZDisassembler', + 'LLVMInitializeSystemZTarget', 'LLVMInitializeSystemZTargetInfo', + 'LLVMInitializeSystemZTargetMC', 'LLVMInitializeTarget', + 'LLVMInitializeTransformUtils', 'LLVMInitializeVEAsmParser', + 'LLVMInitializeVEAsmPrinter', 'LLVMInitializeVEDisassembler', + 'LLVMInitializeVETarget', 'LLVMInitializeVETargetInfo', + 'LLVMInitializeVETargetMC', 'LLVMInitializeVectorization', + 'LLVMInitializeWebAssemblyAsmParser', + 'LLVMInitializeWebAssemblyAsmPrinter', + 'LLVMInitializeWebAssemblyDisassembler', + 'LLVMInitializeWebAssemblyTarget', + 'LLVMInitializeWebAssemblyTargetInfo', + 'LLVMInitializeWebAssemblyTargetMC', 'LLVMInitializeX86AsmParser', + 'LLVMInitializeX86AsmPrinter', 'LLVMInitializeX86Disassembler', + 'LLVMInitializeX86Target', 'LLVMInitializeX86TargetInfo', + 'LLVMInitializeX86TargetMC', 'LLVMInitializeXCoreAsmPrinter', + 'LLVMInitializeXCoreDisassembler', 'LLVMInitializeXCoreTarget', + 'LLVMInitializeXCoreTargetInfo', 'LLVMInitializeXCoreTargetMC', + 'LLVMInlineAsmDialect', 'LLVMInlineAsmDialectATT', + 'LLVMInlineAsmDialectIntel', 'LLVMInlineAsmDialect__enumvalues', + 'LLVMInlineAsmValueKind', 'LLVMInsertBasicBlock', + 'LLVMInsertBasicBlockInContext', 'LLVMInsertElement', + 'LLVMInsertExistingBasicBlockAfterInsertBlock', + 'LLVMInsertIntoBuilder', 'LLVMInsertIntoBuilderWithName', + 'LLVMInsertValue', 'LLVMInstallFatalErrorHandler', + 'LLVMInstructionClone', 'LLVMInstructionEraseFromParent', + 'LLVMInstructionGetAllMetadataOtherThanDebugLoc', + 'LLVMInstructionGetDebugLoc', 'LLVMInstructionRemoveFromParent', + 'LLVMInstructionSetDebugLoc', 'LLVMInstructionValueKind', + 'LLVMInt128Type', 'LLVMInt128TypeInContext', 'LLVMInt16Type', + 'LLVMInt16TypeInContext', 'LLVMInt1Type', 'LLVMInt1TypeInContext', + 'LLVMInt32Type', 'LLVMInt32TypeInContext', 'LLVMInt64Type', + 'LLVMInt64TypeInContext', 'LLVMInt8Type', 'LLVMInt8TypeInContext', + 'LLVMIntEQ', 'LLVMIntNE', 'LLVMIntPredicate', + 'LLVMIntPredicate__enumvalues', 'LLVMIntPtrType', + 'LLVMIntPtrTypeForAS', 'LLVMIntPtrTypeForASInContext', + 'LLVMIntPtrTypeInContext', 'LLVMIntSGE', 'LLVMIntSGT', + 'LLVMIntSLE', 'LLVMIntSLT', 'LLVMIntToPtr', 'LLVMIntType', + 'LLVMIntTypeInContext', 'LLVMIntUGE', 'LLVMIntUGT', 'LLVMIntULE', + 'LLVMIntULT', 'LLVMIntegerTypeKind', 'LLVMIntelOCLBICallConv', + 'LLVMInternalLinkage', 'LLVMIntrinsicCopyOverloadedName', + 'LLVMIntrinsicCopyOverloadedName2', 'LLVMIntrinsicGetName', + 'LLVMIntrinsicGetType', 'LLVMIntrinsicIsOverloaded', 'LLVMInvoke', + 'LLVMIsAAddrSpaceCastInst', 'LLVMIsAAllocaInst', + 'LLVMIsAArgument', 'LLVMIsAAtomicCmpXchgInst', + 'LLVMIsAAtomicRMWInst', 'LLVMIsABasicBlock', + 'LLVMIsABinaryOperator', 'LLVMIsABitCastInst', + 'LLVMIsABlockAddress', 'LLVMIsABranchInst', 'LLVMIsACallBrInst', + 'LLVMIsACallInst', 'LLVMIsACastInst', 'LLVMIsACatchPadInst', + 'LLVMIsACatchReturnInst', 'LLVMIsACatchSwitchInst', + 'LLVMIsACleanupPadInst', 'LLVMIsACleanupReturnInst', + 'LLVMIsACmpInst', 'LLVMIsAConstant', + 'LLVMIsAConstantAggregateZero', 'LLVMIsAConstantArray', + 'LLVMIsAConstantDataArray', 'LLVMIsAConstantDataSequential', + 'LLVMIsAConstantDataVector', 'LLVMIsAConstantExpr', + 'LLVMIsAConstantFP', 'LLVMIsAConstantInt', + 'LLVMIsAConstantPointerNull', 'LLVMIsAConstantStruct', + 'LLVMIsAConstantTokenNone', 'LLVMIsAConstantVector', + 'LLVMIsADbgDeclareInst', 'LLVMIsADbgInfoIntrinsic', + 'LLVMIsADbgLabelInst', 'LLVMIsADbgVariableIntrinsic', + 'LLVMIsAExtractElementInst', 'LLVMIsAExtractValueInst', + 'LLVMIsAFCmpInst', 'LLVMIsAFPExtInst', 'LLVMIsAFPToSIInst', + 'LLVMIsAFPToUIInst', 'LLVMIsAFPTruncInst', 'LLVMIsAFenceInst', + 'LLVMIsAFreezeInst', 'LLVMIsAFuncletPadInst', 'LLVMIsAFunction', + 'LLVMIsAGetElementPtrInst', 'LLVMIsAGlobalAlias', + 'LLVMIsAGlobalIFunc', 'LLVMIsAGlobalObject', 'LLVMIsAGlobalValue', + 'LLVMIsAGlobalVariable', 'LLVMIsAICmpInst', + 'LLVMIsAIndirectBrInst', 'LLVMIsAInlineAsm', + 'LLVMIsAInsertElementInst', 'LLVMIsAInsertValueInst', + 'LLVMIsAInstruction', 'LLVMIsAIntToPtrInst', + 'LLVMIsAIntrinsicInst', 'LLVMIsAInvokeInst', + 'LLVMIsALandingPadInst', 'LLVMIsALoadInst', 'LLVMIsAMDNode', + 'LLVMIsAMDString', 'LLVMIsAMemCpyInst', 'LLVMIsAMemIntrinsic', + 'LLVMIsAMemMoveInst', 'LLVMIsAMemSetInst', 'LLVMIsAPHINode', + 'LLVMIsAPoisonValue', 'LLVMIsAPtrToIntInst', 'LLVMIsAResumeInst', + 'LLVMIsAReturnInst', 'LLVMIsASExtInst', 'LLVMIsASIToFPInst', + 'LLVMIsASelectInst', 'LLVMIsAShuffleVectorInst', + 'LLVMIsAStoreInst', 'LLVMIsASwitchInst', 'LLVMIsATerminatorInst', + 'LLVMIsATruncInst', 'LLVMIsAUIToFPInst', + 'LLVMIsAUnaryInstruction', 'LLVMIsAUnaryOperator', + 'LLVMIsAUndefValue', 'LLVMIsAUnreachableInst', 'LLVMIsAUser', + 'LLVMIsAVAArgInst', 'LLVMIsAZExtInst', 'LLVMIsAtomicSingleThread', + 'LLVMIsCleanup', 'LLVMIsConditional', 'LLVMIsConstant', + 'LLVMIsConstantString', 'LLVMIsDeclaration', + 'LLVMIsEnumAttribute', 'LLVMIsExternallyInitialized', + 'LLVMIsFunctionVarArg', 'LLVMIsGlobalConstant', 'LLVMIsInBounds', + 'LLVMIsLiteralStruct', 'LLVMIsMultithreaded', 'LLVMIsNull', + 'LLVMIsOpaqueStruct', 'LLVMIsPackedStruct', 'LLVMIsPoison', + 'LLVMIsRelocationIteratorAtEnd', 'LLVMIsSectionIteratorAtEnd', + 'LLVMIsStringAttribute', 'LLVMIsSymbolIteratorAtEnd', + 'LLVMIsTailCall', 'LLVMIsThreadLocal', 'LLVMIsTypeAttribute', + 'LLVMIsUndef', 'LLVMJITCSymbolMapPair', 'LLVMJITEvaluatedSymbol', + 'LLVMJITEventListenerRef', 'LLVMJITSymbolFlags', + 'LLVMJITSymbolGenericFlags', 'LLVMJITSymbolGenericFlagsCallable', + 'LLVMJITSymbolGenericFlagsExported', + 'LLVMJITSymbolGenericFlagsMaterializationSideEffectsOnly', + 'LLVMJITSymbolGenericFlagsWeak', + 'LLVMJITSymbolGenericFlags__enumvalues', + 'LLVMJITSymbolTargetFlags', 'LLVMLShr', 'LLVMLabelType', + 'LLVMLabelTypeInContext', 'LLVMLabelTypeKind', 'LLVMLandingPad', + 'LLVMLandingPadCatch', 'LLVMLandingPadClauseTy', + 'LLVMLandingPadClauseTy__enumvalues', 'LLVMLandingPadFilter', + 'LLVMLargestComdatSelectionKind', 'LLVMLinkInInterpreter', + 'LLVMLinkInMCJIT', 'LLVMLinkModules2', 'LLVMLinkOnceAnyLinkage', + 'LLVMLinkOnceODRAutoHideLinkage', 'LLVMLinkOnceODRLinkage', + 'LLVMLinkage', 'LLVMLinkage__enumvalues', + 'LLVMLinkerDestroySource', 'LLVMLinkerMode', + 'LLVMLinkerMode__enumvalues', 'LLVMLinkerPreserveSource_Removed', + 'LLVMLinkerPrivateLinkage', 'LLVMLinkerPrivateWeakLinkage', + 'LLVMLittleEndian', 'LLVMLoad', 'LLVMLoadLibraryPermanently', + 'LLVMLocalAsMetadataMetadataKind', 'LLVMLocalDynamicTLSModel', + 'LLVMLocalExecTLSModel', 'LLVMLocalUnnamedAddr', + 'LLVMLookupIntrinsicID', 'LLVMMCJITMemoryManagerRef', + 'LLVMMDNode', 'LLVMMDNodeInContext', 'LLVMMDNodeInContext2', + 'LLVMMDString', 'LLVMMDStringInContext', 'LLVMMDStringInContext2', + 'LLVMMDStringMetadataKind', 'LLVMMDTupleMetadataKind', + 'LLVMMSP430BUILTINCallConv', 'LLVMMSP430INTRCallConv', + 'LLVMMachOUniversalBinaryCopyObjectForArch', + 'LLVMMemoryBufferRef', 'LLVMMemoryDefValueKind', + 'LLVMMemoryManagerAllocateCodeSectionCallback', + 'LLVMMemoryManagerAllocateDataSectionCallback', + 'LLVMMemoryManagerDestroyCallback', + 'LLVMMemoryManagerFinalizeMemoryCallback', + 'LLVMMemoryPhiValueKind', 'LLVMMemoryUseValueKind', + 'LLVMMetadataAsValue', 'LLVMMetadataAsValueValueKind', + 'LLVMMetadataKind', 'LLVMMetadataRef', + 'LLVMMetadataReplaceAllUsesWith', 'LLVMMetadataTypeInContext', + 'LLVMMetadataTypeKind', 'LLVMModuleCreateWithName', + 'LLVMModuleCreateWithNameInContext', 'LLVMModuleFlagBehavior', + 'LLVMModuleFlagBehaviorAppend', + 'LLVMModuleFlagBehaviorAppendUnique', + 'LLVMModuleFlagBehaviorError', 'LLVMModuleFlagBehaviorOverride', + 'LLVMModuleFlagBehaviorRequire', 'LLVMModuleFlagBehaviorWarning', + 'LLVMModuleFlagBehavior__enumvalues', + 'LLVMModuleFlagEntriesGetFlagBehavior', + 'LLVMModuleFlagEntriesGetKey', 'LLVMModuleFlagEntriesGetMetadata', + 'LLVMModuleFlagEntry', 'LLVMModuleProviderRef', 'LLVMModuleRef', + 'LLVMMoveBasicBlockAfter', 'LLVMMoveBasicBlockBefore', + 'LLVMMoveToContainingSection', 'LLVMMoveToNextRelocation', + 'LLVMMoveToNextSection', 'LLVMMoveToNextSymbol', 'LLVMMul', + 'LLVMNamedMDNodeRef', 'LLVMNoDeduplicateComdatSelectionKind', + 'LLVMNoUnnamedAddr', 'LLVMNormalizeTargetTriple', + 'LLVMNotThreadLocal', 'LLVMObjectFile', + 'LLVMObjectFileCopySectionIterator', + 'LLVMObjectFileCopySymbolIterator', + 'LLVMObjectFileIsSectionIteratorAtEnd', + 'LLVMObjectFileIsSymbolIteratorAtEnd', 'LLVMObjectFileRef', + 'LLVMOffsetOfElement', 'LLVMOpInfoCallback', 'LLVMOpcode', + 'LLVMOpcode__enumvalues', 'LLVMOr', 'LLVMOrcAbsoluteSymbols', + 'LLVMOrcCAPIDefinitionGeneratorTryToGenerateFunction', + 'LLVMOrcCDependenceMapPair', 'LLVMOrcCDependenceMapPairs', + 'LLVMOrcCLookupSet', 'LLVMOrcCLookupSetElement', + 'LLVMOrcCSymbolAliasMapEntry', 'LLVMOrcCSymbolAliasMapPair', + 'LLVMOrcCSymbolAliasMapPairs', 'LLVMOrcCSymbolFlagsMapPair', + 'LLVMOrcCSymbolFlagsMapPairs', 'LLVMOrcCSymbolMapPairs', + 'LLVMOrcCSymbolsList', + 'LLVMOrcCreateCustomCAPIDefinitionGenerator', + 'LLVMOrcCreateCustomMaterializationUnit', + 'LLVMOrcCreateDumpObjects', + 'LLVMOrcCreateDynamicLibrarySearchGeneratorForPath', + 'LLVMOrcCreateDynamicLibrarySearchGeneratorForProcess', + 'LLVMOrcCreateLLJIT', 'LLVMOrcCreateLLJITBuilder', + 'LLVMOrcCreateLocalIndirectStubsManager', + 'LLVMOrcCreateLocalLazyCallThroughManager', + 'LLVMOrcCreateNewThreadSafeContext', + 'LLVMOrcCreateNewThreadSafeModule', + 'LLVMOrcCreateRTDyldObjectLinkingLayerWithSectionMemoryManager', + 'LLVMOrcCreateStaticLibrarySearchGeneratorForPath', + 'LLVMOrcDefinitionGeneratorRef', 'LLVMOrcDisposeCSymbolFlagsMap', + 'LLVMOrcDisposeDefinitionGenerator', 'LLVMOrcDisposeDumpObjects', + 'LLVMOrcDisposeIndirectStubsManager', + 'LLVMOrcDisposeJITTargetMachineBuilder', 'LLVMOrcDisposeLLJIT', + 'LLVMOrcDisposeLLJITBuilder', + 'LLVMOrcDisposeLazyCallThroughManager', + 'LLVMOrcDisposeMaterializationResponsibility', + 'LLVMOrcDisposeMaterializationUnit', 'LLVMOrcDisposeObjectLayer', + 'LLVMOrcDisposeSymbols', 'LLVMOrcDisposeThreadSafeContext', + 'LLVMOrcDisposeThreadSafeModule', 'LLVMOrcDumpObjectsRef', + 'LLVMOrcDumpObjects_CallOperator', 'LLVMOrcErrorReporterFunction', + 'LLVMOrcExecutionSessionCreateBareJITDylib', + 'LLVMOrcExecutionSessionCreateJITDylib', + 'LLVMOrcExecutionSessionGetJITDylibByName', + 'LLVMOrcExecutionSessionGetSymbolStringPool', + 'LLVMOrcExecutionSessionIntern', 'LLVMOrcExecutionSessionRef', + 'LLVMOrcExecutionSessionSetErrorReporter', + 'LLVMOrcExecutorAddress', + 'LLVMOrcGenericIRModuleOperationFunction', + 'LLVMOrcIRTransformLayerEmit', 'LLVMOrcIRTransformLayerRef', + 'LLVMOrcIRTransformLayerSetTransform', + 'LLVMOrcIRTransformLayerTransformFunction', + 'LLVMOrcIndirectStubsManagerRef', 'LLVMOrcJITDylibAddGenerator', + 'LLVMOrcJITDylibClear', 'LLVMOrcJITDylibCreateResourceTracker', + 'LLVMOrcJITDylibDefine', + 'LLVMOrcJITDylibGetDefaultResourceTracker', + 'LLVMOrcJITDylibLookupFlags', + 'LLVMOrcJITDylibLookupFlagsMatchAllSymbols', + 'LLVMOrcJITDylibLookupFlagsMatchExportedSymbolsOnly', + 'LLVMOrcJITDylibLookupFlags__enumvalues', 'LLVMOrcJITDylibRef', + 'LLVMOrcJITTargetAddress', + 'LLVMOrcJITTargetMachineBuilderCreateFromTargetMachine', + 'LLVMOrcJITTargetMachineBuilderDetectHost', + 'LLVMOrcJITTargetMachineBuilderGetTargetTriple', + 'LLVMOrcJITTargetMachineBuilderRef', + 'LLVMOrcJITTargetMachineBuilderSetTargetTriple', + 'LLVMOrcLLJITAddLLVMIRModule', + 'LLVMOrcLLJITAddLLVMIRModuleWithRT', 'LLVMOrcLLJITAddObjectFile', + 'LLVMOrcLLJITAddObjectFileWithRT', + 'LLVMOrcLLJITBuilderObjectLinkingLayerCreatorFunction', + 'LLVMOrcLLJITBuilderRef', + 'LLVMOrcLLJITBuilderSetJITTargetMachineBuilder', + 'LLVMOrcLLJITBuilderSetObjectLinkingLayerCreator', + 'LLVMOrcLLJITGetDataLayoutStr', 'LLVMOrcLLJITGetExecutionSession', + 'LLVMOrcLLJITGetGlobalPrefix', 'LLVMOrcLLJITGetIRTransformLayer', + 'LLVMOrcLLJITGetMainJITDylib', 'LLVMOrcLLJITGetObjLinkingLayer', + 'LLVMOrcLLJITGetObjTransformLayer', 'LLVMOrcLLJITGetTripleString', + 'LLVMOrcLLJITLookup', 'LLVMOrcLLJITMangleAndIntern', + 'LLVMOrcLLJITRef', 'LLVMOrcLazyCallThroughManagerRef', + 'LLVMOrcLazyReexports', 'LLVMOrcLookupKind', + 'LLVMOrcLookupKindDLSym', 'LLVMOrcLookupKindStatic', + 'LLVMOrcLookupKind__enumvalues', 'LLVMOrcLookupStateRef', + 'LLVMOrcMaterializationResponsibilityAddDependencies', + 'LLVMOrcMaterializationResponsibilityAddDependenciesForAll', + 'LLVMOrcMaterializationResponsibilityDefineMaterializing', + 'LLVMOrcMaterializationResponsibilityDelegate', + 'LLVMOrcMaterializationResponsibilityFailMaterialization', + 'LLVMOrcMaterializationResponsibilityGetExecutionSession', + 'LLVMOrcMaterializationResponsibilityGetInitializerSymbol', + 'LLVMOrcMaterializationResponsibilityGetRequestedSymbols', + 'LLVMOrcMaterializationResponsibilityGetSymbols', + 'LLVMOrcMaterializationResponsibilityGetTargetDylib', + 'LLVMOrcMaterializationResponsibilityNotifyEmitted', + 'LLVMOrcMaterializationResponsibilityNotifyResolved', + 'LLVMOrcMaterializationResponsibilityRef', + 'LLVMOrcMaterializationResponsibilityReplace', + 'LLVMOrcMaterializationUnitDestroyFunction', + 'LLVMOrcMaterializationUnitDiscardFunction', + 'LLVMOrcMaterializationUnitMaterializeFunction', + 'LLVMOrcMaterializationUnitRef', + 'LLVMOrcObjectLayerAddObjectFile', + 'LLVMOrcObjectLayerAddObjectFileWithRT', 'LLVMOrcObjectLayerEmit', + 'LLVMOrcObjectLayerRef', 'LLVMOrcObjectLinkingLayerRef', + 'LLVMOrcObjectTransformLayerRef', + 'LLVMOrcObjectTransformLayerSetTransform', + 'LLVMOrcObjectTransformLayerTransformFunction', + 'LLVMOrcRTDyldObjectLinkingLayerRegisterJITEventListener', + 'LLVMOrcReleaseResourceTracker', + 'LLVMOrcReleaseSymbolStringPoolEntry', + 'LLVMOrcResourceTrackerRef', 'LLVMOrcResourceTrackerRemove', + 'LLVMOrcResourceTrackerTransferTo', + 'LLVMOrcRetainSymbolStringPoolEntry', 'LLVMOrcSymbolLookupFlags', + 'LLVMOrcSymbolLookupFlagsRequiredSymbol', + 'LLVMOrcSymbolLookupFlagsWeaklyReferencedSymbol', + 'LLVMOrcSymbolLookupFlags__enumvalues', 'LLVMOrcSymbolPredicate', + 'LLVMOrcSymbolStringPoolClearDeadEntries', + 'LLVMOrcSymbolStringPoolEntryRef', + 'LLVMOrcSymbolStringPoolEntryStr', 'LLVMOrcSymbolStringPoolRef', + 'LLVMOrcThreadSafeContextGetContext', + 'LLVMOrcThreadSafeContextRef', 'LLVMOrcThreadSafeModuleRef', + 'LLVMOrcThreadSafeModuleWithModuleDo', 'LLVMPHI', + 'LLVMPPCFP128Type', 'LLVMPPCFP128TypeInContext', + 'LLVMPPC_FP128TypeKind', 'LLVMPTXDeviceCallConv', + 'LLVMPTXKernelCallConv', 'LLVMParseBitcode', 'LLVMParseBitcode2', + 'LLVMParseBitcodeInContext', 'LLVMParseBitcodeInContext2', + 'LLVMParseCommandLineOptions', 'LLVMParseIRInContext', + 'LLVMPassBuilderOptionsRef', + 'LLVMPassBuilderOptionsSetCallGraphProfile', + 'LLVMPassBuilderOptionsSetDebugLogging', + 'LLVMPassBuilderOptionsSetForgetAllSCEVInLoopUnroll', + 'LLVMPassBuilderOptionsSetLicmMssaNoAccForPromotionCap', + 'LLVMPassBuilderOptionsSetLicmMssaOptCap', + 'LLVMPassBuilderOptionsSetLoopInterleaving', + 'LLVMPassBuilderOptionsSetLoopUnrolling', + 'LLVMPassBuilderOptionsSetLoopVectorization', + 'LLVMPassBuilderOptionsSetMergeFunctions', + 'LLVMPassBuilderOptionsSetSLPVectorization', + 'LLVMPassBuilderOptionsSetVerifyEach', + 'LLVMPassManagerBuilderAddCoroutinePassesToExtensionPoints', + 'LLVMPassManagerBuilderCreate', 'LLVMPassManagerBuilderDispose', + 'LLVMPassManagerBuilderPopulateFunctionPassManager', + 'LLVMPassManagerBuilderPopulateLTOPassManager', + 'LLVMPassManagerBuilderPopulateModulePassManager', + 'LLVMPassManagerBuilderRef', + 'LLVMPassManagerBuilderSetDisableSimplifyLibCalls', + 'LLVMPassManagerBuilderSetDisableUnitAtATime', + 'LLVMPassManagerBuilderSetDisableUnrollLoops', + 'LLVMPassManagerBuilderSetOptLevel', + 'LLVMPassManagerBuilderSetSizeLevel', + 'LLVMPassManagerBuilderUseInlinerWithThreshold', + 'LLVMPassManagerRef', 'LLVMPassRegistryRef', 'LLVMPointerSize', + 'LLVMPointerSizeForAS', 'LLVMPointerType', 'LLVMPointerTypeKind', + 'LLVMPoisonValueValueKind', 'LLVMPositionBuilder', + 'LLVMPositionBuilderAtEnd', 'LLVMPositionBuilderBefore', + 'LLVMPreferredAlignmentOfGlobal', 'LLVMPreferredAlignmentOfType', + 'LLVMPreserveAllCallConv', 'LLVMPreserveMostCallConv', + 'LLVMPrintMessageAction', 'LLVMPrintModuleToFile', + 'LLVMPrintModuleToString', 'LLVMPrintTypeToString', + 'LLVMPrintValueToString', 'LLVMPrivateLinkage', + 'LLVMProtectedVisibility', 'LLVMPtrToInt', 'LLVMRealOEQ', + 'LLVMRealOGE', 'LLVMRealOGT', 'LLVMRealOLE', 'LLVMRealOLT', + 'LLVMRealONE', 'LLVMRealORD', 'LLVMRealPredicate', + 'LLVMRealPredicateFalse', 'LLVMRealPredicateTrue', + 'LLVMRealPredicate__enumvalues', 'LLVMRealUEQ', 'LLVMRealUGE', + 'LLVMRealUGT', 'LLVMRealULE', 'LLVMRealULT', 'LLVMRealUNE', + 'LLVMRealUNO', 'LLVMRecompileAndRelinkFunction', + 'LLVMRelocDefault', 'LLVMRelocDynamicNoPic', 'LLVMRelocMode', + 'LLVMRelocMode__enumvalues', 'LLVMRelocPIC', 'LLVMRelocROPI', + 'LLVMRelocROPI_RWPI', 'LLVMRelocRWPI', 'LLVMRelocStatic', + 'LLVMRelocationIteratorRef', 'LLVMRemarkArgGetDebugLoc', + 'LLVMRemarkArgGetKey', 'LLVMRemarkArgGetValue', + 'LLVMRemarkArgRef', 'LLVMRemarkDebugLocGetSourceColumn', + 'LLVMRemarkDebugLocGetSourceFilePath', + 'LLVMRemarkDebugLocGetSourceLine', 'LLVMRemarkDebugLocRef', + 'LLVMRemarkEntryDispose', 'LLVMRemarkEntryGetDebugLoc', + 'LLVMRemarkEntryGetFirstArg', 'LLVMRemarkEntryGetFunctionName', + 'LLVMRemarkEntryGetHotness', 'LLVMRemarkEntryGetNextArg', + 'LLVMRemarkEntryGetNumArgs', 'LLVMRemarkEntryGetPassName', + 'LLVMRemarkEntryGetRemarkName', 'LLVMRemarkEntryGetType', + 'LLVMRemarkEntryRef', 'LLVMRemarkParserCreateBitstream', + 'LLVMRemarkParserCreateYAML', 'LLVMRemarkParserDispose', + 'LLVMRemarkParserGetErrorMessage', 'LLVMRemarkParserGetNext', + 'LLVMRemarkParserHasError', 'LLVMRemarkParserRef', + 'LLVMRemarkStringGetData', 'LLVMRemarkStringGetLen', + 'LLVMRemarkStringRef', 'LLVMRemarkType', 'LLVMRemarkTypeAnalysis', + 'LLVMRemarkTypeAnalysisAliasing', + 'LLVMRemarkTypeAnalysisFPCommute', 'LLVMRemarkTypeFailure', + 'LLVMRemarkTypeMissed', 'LLVMRemarkTypePassed', + 'LLVMRemarkTypeUnknown', 'LLVMRemarkVersion', + 'LLVMRemoveBasicBlockFromParent', + 'LLVMRemoveCallSiteEnumAttribute', + 'LLVMRemoveCallSiteStringAttribute', + 'LLVMRemoveEnumAttributeAtIndex', 'LLVMRemoveGlobalIFunc', + 'LLVMRemoveModule', 'LLVMRemoveStringAttributeAtIndex', + 'LLVMReplaceAllUsesWith', 'LLVMResetFatalErrorHandler', + 'LLVMResume', 'LLVMRet', 'LLVMReturnStatusAction', + 'LLVMRunFunction', 'LLVMRunFunctionAsMain', + 'LLVMRunFunctionPassManager', 'LLVMRunPassManager', + 'LLVMRunPasses', 'LLVMRunStaticConstructors', + 'LLVMRunStaticDestructors', 'LLVMSDiv', 'LLVMSExt', 'LLVMSIToFP', + 'LLVMSPIRFUNCCallConv', 'LLVMSPIRKERNELCallConv', 'LLVMSRem', + 'LLVMSameSizeComdatSelectionKind', 'LLVMScalableVectorType', + 'LLVMScalableVectorTypeKind', 'LLVMSearchForAddressOfSymbol', + 'LLVMSectionIteratorRef', 'LLVMSelect', 'LLVMSetAlignment', + 'LLVMSetArgOperand', 'LLVMSetAtomicRMWBinOp', + 'LLVMSetAtomicSingleThread', 'LLVMSetCleanup', + 'LLVMSetCmpXchgFailureOrdering', 'LLVMSetCmpXchgSuccessOrdering', + 'LLVMSetComdat', 'LLVMSetComdatSelectionKind', 'LLVMSetCondition', + 'LLVMSetCurrentDebugLocation', 'LLVMSetCurrentDebugLocation2', + 'LLVMSetDLLStorageClass', 'LLVMSetDataLayout', + 'LLVMSetDisasmOptions', 'LLVMSetExternallyInitialized', + 'LLVMSetFunctionCallConv', 'LLVMSetGC', 'LLVMSetGlobalConstant', + 'LLVMSetGlobalIFuncResolver', 'LLVMSetInitializer', + 'LLVMSetInstDebugLocation', 'LLVMSetInstrParamAlignment', + 'LLVMSetInstructionCallConv', 'LLVMSetIsInBounds', + 'LLVMSetLinkage', 'LLVMSetMetadata', 'LLVMSetModuleDataLayout', + 'LLVMSetModuleIdentifier', 'LLVMSetModuleInlineAsm', + 'LLVMSetModuleInlineAsm2', 'LLVMSetNormalDest', 'LLVMSetOperand', + 'LLVMSetOrdering', 'LLVMSetParamAlignment', + 'LLVMSetParentCatchSwitch', 'LLVMSetPersonalityFn', + 'LLVMSetSection', 'LLVMSetSourceFileName', 'LLVMSetSubprogram', + 'LLVMSetSuccessor', 'LLVMSetTailCall', 'LLVMSetTarget', + 'LLVMSetTargetMachineAsmVerbosity', 'LLVMSetThreadLocal', + 'LLVMSetThreadLocalMode', 'LLVMSetUnnamedAddr', + 'LLVMSetUnnamedAddress', 'LLVMSetUnwindDest', 'LLVMSetValueName', + 'LLVMSetValueName2', 'LLVMSetVisibility', 'LLVMSetVolatile', + 'LLVMSetWeak', 'LLVMShl', 'LLVMShuffleVector', 'LLVMShutdown', + 'LLVMSizeOf', 'LLVMSizeOfTypeInBits', 'LLVMStartMultithreaded', + 'LLVMStopMultithreaded', 'LLVMStore', 'LLVMStoreSizeOfType', + 'LLVMStripModuleDebugInfo', 'LLVMStructCreateNamed', + 'LLVMStructGetTypeAtIndex', 'LLVMStructSetBody', 'LLVMStructType', + 'LLVMStructTypeInContext', 'LLVMStructTypeKind', 'LLVMSub', + 'LLVMSwiftCallConv', 'LLVMSwitch', 'LLVMSymbolIteratorRef', + 'LLVMSymbolLookupCallback', 'LLVMTargetDataRef', + 'LLVMTargetHasAsmBackend', 'LLVMTargetHasJIT', + 'LLVMTargetHasTargetMachine', 'LLVMTargetLibraryInfoRef', + 'LLVMTargetMachineEmitToFile', + 'LLVMTargetMachineEmitToMemoryBuffer', 'LLVMTargetMachineRef', + 'LLVMTargetRef', 'LLVMTemporaryMDNode', 'LLVMThreadLocalMode', + 'LLVMThreadLocalMode__enumvalues', 'LLVMTokenTypeInContext', + 'LLVMTokenTypeKind', 'LLVMTrunc', 'LLVMTypeIsSized', + 'LLVMTypeKind', 'LLVMTypeKind__enumvalues', 'LLVMTypeOf', + 'LLVMTypeRef', 'LLVMUDiv', 'LLVMUIToFP', 'LLVMURem', + 'LLVMUndefValueValueKind', 'LLVMUnnamedAddr', + 'LLVMUnnamedAddr__enumvalues', 'LLVMUnreachable', 'LLVMUseRef', + 'LLVMUserOp1', 'LLVMUserOp2', 'LLVMVAArg', + 'LLVMValueAsBasicBlock', 'LLVMValueAsMetadata', + 'LLVMValueIsBasicBlock', 'LLVMValueKind', + 'LLVMValueKind__enumvalues', 'LLVMValueMetadataEntriesGetKind', + 'LLVMValueMetadataEntriesGetMetadata', 'LLVMValueMetadataEntry', + 'LLVMValueRef', 'LLVMVectorType', 'LLVMVectorTypeKind', + 'LLVMVerifierFailureAction', + 'LLVMVerifierFailureAction__enumvalues', 'LLVMVerifyFunction', + 'LLVMVerifyModule', 'LLVMViewFunctionCFG', + 'LLVMViewFunctionCFGOnly', 'LLVMVisibility', + 'LLVMVisibility__enumvalues', 'LLVMVoidType', + 'LLVMVoidTypeInContext', 'LLVMVoidTypeKind', 'LLVMWeakAnyLinkage', + 'LLVMWeakODRLinkage', 'LLVMWebKitJSCallConv', 'LLVMWin64CallConv', + 'LLVMWriteBitcodeToFD', 'LLVMWriteBitcodeToFile', + 'LLVMWriteBitcodeToFileHandle', 'LLVMWriteBitcodeToMemoryBuffer', + 'LLVMX8664SysVCallConv', 'LLVMX86AMXType', + 'LLVMX86AMXTypeInContext', 'LLVMX86FP80Type', + 'LLVMX86FP80TypeInContext', 'LLVMX86FastcallCallConv', + 'LLVMX86INTRCallConv', 'LLVMX86MMXType', + 'LLVMX86MMXTypeInContext', 'LLVMX86RegCallCallConv', + 'LLVMX86StdcallCallConv', 'LLVMX86ThisCallCallConv', + 'LLVMX86VectorCallCallConv', 'LLVMX86_AMXTypeKind', + 'LLVMX86_FP80TypeKind', 'LLVMX86_MMXTypeKind', 'LLVMXor', + 'LLVMYieldCallback', 'LLVMZExt', 'LLVM_C_ANALYSIS_H', + 'LLVM_C_BITREADER_H', 'LLVM_C_BITWRITER_H', 'LLVM_C_COMDAT_H', + 'LLVM_C_CORE_H', 'LLVM_C_DATATYPES_H', 'LLVM_C_DEBUGINFO_H', + 'LLVM_C_DEPRECATED_H', 'LLVM_C_DISASSEMBLERTYPES_H', + 'LLVM_C_DISASSEMBLER_H', 'LLVM_C_ERRORHANDLING_H', + 'LLVM_C_ERROR_H', 'LLVM_C_EXECUTIONENGINE_H', 'LLVM_C_EXTERNC_H', + 'LLVM_C_INITIALIZATION_H', 'LLVM_C_IRREADER_H', 'LLVM_C_LINKER_H', + 'LLVM_C_LLJIT_H', 'LLVM_C_LTO_H', 'LLVM_C_OBJECT_H', + 'LLVM_C_ORCEE_H', 'LLVM_C_ORC_H', 'LLVM_C_REMARKS_H', + 'LLVM_C_SUPPORT_H', 'LLVM_C_TARGETMACHINE_H', 'LLVM_C_TARGET_H', + 'LLVM_C_TRANSFORMS_AGGRESSIVEINSTCOMBINE_H', + 'LLVM_C_TRANSFORMS_COROUTINES_H', + 'LLVM_C_TRANSFORMS_INSTCOMBINE_H', 'LLVM_C_TRANSFORMS_IPO_H', + 'LLVM_C_TRANSFORMS_PASSBUILDER_H', + 'LLVM_C_TRANSFORMS_PASSMANAGERBUILDER_H', + 'LLVM_C_TRANSFORMS_SCALAR_H', 'LLVM_C_TRANSFORMS_UTILS_H', + 'LLVM_C_TRANSFORMS_VECTORIZE_H', 'LLVM_C_TYPES_H', + 'LTOObjectBuffer', 'LTO_API_VERSION', + 'LTO_CODEGEN_PIC_MODEL_DEFAULT', 'LTO_CODEGEN_PIC_MODEL_DYNAMIC', + 'LTO_CODEGEN_PIC_MODEL_DYNAMIC_NO_PIC', + 'LTO_CODEGEN_PIC_MODEL_STATIC', 'LTO_DEBUG_MODEL_DWARF', + 'LTO_DEBUG_MODEL_NONE', 'LTO_DS_ERROR', 'LTO_DS_NOTE', + 'LTO_DS_REMARK', 'LTO_DS_WARNING', 'LTO_SYMBOL_ALIAS', + 'LTO_SYMBOL_ALIGNMENT_MASK', 'LTO_SYMBOL_COMDAT', + 'LTO_SYMBOL_DEFINITION_MASK', 'LTO_SYMBOL_DEFINITION_REGULAR', + 'LTO_SYMBOL_DEFINITION_TENTATIVE', + 'LTO_SYMBOL_DEFINITION_UNDEFINED', 'LTO_SYMBOL_DEFINITION_WEAK', + 'LTO_SYMBOL_DEFINITION_WEAKUNDEF', 'LTO_SYMBOL_PERMISSIONS_CODE', + 'LTO_SYMBOL_PERMISSIONS_DATA', 'LTO_SYMBOL_PERMISSIONS_MASK', + 'LTO_SYMBOL_PERMISSIONS_RODATA', 'LTO_SYMBOL_SCOPE_DEFAULT', + 'LTO_SYMBOL_SCOPE_DEFAULT_CAN_BE_HIDDEN', + 'LTO_SYMBOL_SCOPE_HIDDEN', 'LTO_SYMBOL_SCOPE_INTERNAL', + 'LTO_SYMBOL_SCOPE_MASK', 'LTO_SYMBOL_SCOPE_PROTECTED', + 'REMARKS_API_VERSION', 'c__EA_LLVMAtomicOrdering', + 'c__EA_LLVMAtomicRMWBinOp', 'c__EA_LLVMBinaryType', + 'c__EA_LLVMCallConv', 'c__EA_LLVMCodeGenFileType', + 'c__EA_LLVMCodeGenOptLevel', 'c__EA_LLVMCodeModel', + 'c__EA_LLVMComdatSelectionKind', 'c__EA_LLVMDIFlags', + 'c__EA_LLVMDLLStorageClass', 'c__EA_LLVMDWARFEmissionKind', + 'c__EA_LLVMDWARFMacinfoRecordType', + 'c__EA_LLVMDWARFSourceLanguage', 'c__EA_LLVMDiagnosticSeverity', + 'c__EA_LLVMInlineAsmDialect', 'c__EA_LLVMIntPredicate', + 'c__EA_LLVMJITSymbolGenericFlags', 'c__EA_LLVMLandingPadClauseTy', + 'c__EA_LLVMLinkage', 'c__EA_LLVMLinkerMode', + 'c__EA_LLVMModuleFlagBehavior', 'c__EA_LLVMOpcode', + 'c__EA_LLVMOrcJITDylibLookupFlags', 'c__EA_LLVMOrcLookupKind', + 'c__EA_LLVMOrcSymbolLookupFlags', 'c__EA_LLVMRealPredicate', + 'c__EA_LLVMRelocMode', 'c__EA_LLVMThreadLocalMode', + 'c__EA_LLVMTypeKind', 'c__EA_LLVMUnnamedAddr', + 'c__EA_LLVMValueKind', 'c__EA_LLVMVerifierFailureAction', + 'c__EA_LLVMVisibility', 'c__EA_lto_codegen_diagnostic_severity_t', + 'c__EA_lto_codegen_model', 'c__EA_lto_debug_model', + 'c__EA_lto_symbol_attributes', 'c__Ea_LLVMAttributeReturnIndex', + 'c__Ea_LLVMMDStringMetadataKind', 'int64_t', 'lto_api_version', + 'lto_bool_t', 'lto_code_gen_t', 'lto_codegen_add_module', + 'lto_codegen_add_must_preserve_symbol', 'lto_codegen_compile', + 'lto_codegen_compile_optimized', 'lto_codegen_compile_to_file', + 'lto_codegen_create', 'lto_codegen_create_in_local_context', + 'lto_codegen_debug_options', 'lto_codegen_debug_options_array', + 'lto_codegen_diagnostic_severity_t', + 'lto_codegen_diagnostic_severity_t__enumvalues', + 'lto_codegen_dispose', 'lto_codegen_model', + 'lto_codegen_model__enumvalues', 'lto_codegen_optimize', + 'lto_codegen_set_assembler_args', + 'lto_codegen_set_assembler_path', 'lto_codegen_set_cpu', + 'lto_codegen_set_debug_model', + 'lto_codegen_set_diagnostic_handler', 'lto_codegen_set_module', + 'lto_codegen_set_pic_model', + 'lto_codegen_set_should_embed_uselists', + 'lto_codegen_set_should_internalize', + 'lto_codegen_write_merged_modules', 'lto_debug_model', + 'lto_debug_model__enumvalues', 'lto_diagnostic_handler_t', + 'lto_get_error_message', 'lto_get_version', + 'lto_initialize_disassembler', 'lto_input_create', + 'lto_input_dispose', 'lto_input_get_dependent_library', + 'lto_input_get_num_dependent_libraries', 'lto_input_t', + 'lto_module_create', 'lto_module_create_from_fd', + 'lto_module_create_from_fd_at_offset', + 'lto_module_create_from_memory', + 'lto_module_create_from_memory_with_path', + 'lto_module_create_in_codegen_context', + 'lto_module_create_in_local_context', 'lto_module_dispose', + 'lto_module_get_linkeropts', 'lto_module_get_macho_cputype', + 'lto_module_get_num_symbols', 'lto_module_get_symbol_attribute', + 'lto_module_get_symbol_name', 'lto_module_get_target_triple', + 'lto_module_has_ctor_dtor', 'lto_module_has_objc_category', + 'lto_module_is_object_file', + 'lto_module_is_object_file_for_target', + 'lto_module_is_object_file_in_memory', + 'lto_module_is_object_file_in_memory_for_target', + 'lto_module_is_thinlto', 'lto_module_set_target_triple', + 'lto_module_t', 'lto_runtime_lib_symbols_list', + 'lto_set_debug_options', 'lto_symbol_attributes', + 'lto_symbol_attributes__enumvalues', 'off_t', 'size_t', + 'struct_LLVMComdat', 'struct_LLVMMCJITCompilerOptions', + 'struct_LLVMOpInfo1', 'struct_LLVMOpInfoSymbol1', + 'struct_LLVMOpaqueAttributeRef', 'struct_LLVMOpaqueBasicBlock', + 'struct_LLVMOpaqueBinary', 'struct_LLVMOpaqueBuilder', + 'struct_LLVMOpaqueContext', 'struct_LLVMOpaqueDIBuilder', + 'struct_LLVMOpaqueDiagnosticInfo', 'struct_LLVMOpaqueError', + 'struct_LLVMOpaqueExecutionEngine', + 'struct_LLVMOpaqueGenericValue', + 'struct_LLVMOpaqueJITEventListener', + 'struct_LLVMOpaqueLTOCodeGenerator', 'struct_LLVMOpaqueLTOInput', + 'struct_LLVMOpaqueLTOModule', + 'struct_LLVMOpaqueMCJITMemoryManager', + 'struct_LLVMOpaqueMemoryBuffer', 'struct_LLVMOpaqueMetadata', + 'struct_LLVMOpaqueModule', 'struct_LLVMOpaqueModuleFlagEntry', + 'struct_LLVMOpaqueModuleProvider', 'struct_LLVMOpaqueNamedMDNode', + 'struct_LLVMOpaqueObjectFile', + 'struct_LLVMOpaquePassBuilderOptions', + 'struct_LLVMOpaquePassManager', + 'struct_LLVMOpaquePassManagerBuilder', + 'struct_LLVMOpaquePassRegistry', + 'struct_LLVMOpaqueRelocationIterator', + 'struct_LLVMOpaqueSectionIterator', + 'struct_LLVMOpaqueSymbolIterator', 'struct_LLVMOpaqueTargetData', + 'struct_LLVMOpaqueTargetLibraryInfotData', + 'struct_LLVMOpaqueTargetMachine', + 'struct_LLVMOpaqueThinLTOCodeGenerator', 'struct_LLVMOpaqueType', + 'struct_LLVMOpaqueUse', 'struct_LLVMOpaqueValue', + 'struct_LLVMOpaqueValueMetadataEntry', + 'struct_LLVMOrcOpaqueDefinitionGenerator', + 'struct_LLVMOrcOpaqueDumpObjects', + 'struct_LLVMOrcOpaqueExecutionSession', + 'struct_LLVMOrcOpaqueIRTransformLayer', + 'struct_LLVMOrcOpaqueIndirectStubsManager', + 'struct_LLVMOrcOpaqueJITDylib', + 'struct_LLVMOrcOpaqueJITTargetMachineBuilder', + 'struct_LLVMOrcOpaqueLLJIT', 'struct_LLVMOrcOpaqueLLJITBuilder', + 'struct_LLVMOrcOpaqueLazyCallThroughManager', + 'struct_LLVMOrcOpaqueLookupState', + 'struct_LLVMOrcOpaqueMaterializationResponsibility', + 'struct_LLVMOrcOpaqueMaterializationUnit', + 'struct_LLVMOrcOpaqueObjectLayer', + 'struct_LLVMOrcOpaqueObjectLinkingLayer', + 'struct_LLVMOrcOpaqueObjectTransformLayer', + 'struct_LLVMOrcOpaqueResourceTracker', + 'struct_LLVMOrcOpaqueSymbolStringPool', + 'struct_LLVMOrcOpaqueSymbolStringPoolEntry', + 'struct_LLVMOrcOpaqueThreadSafeContext', + 'struct_LLVMOrcOpaqueThreadSafeModule', + 'struct_LLVMRemarkOpaqueArg', 'struct_LLVMRemarkOpaqueDebugLoc', + 'struct_LLVMRemarkOpaqueEntry', 'struct_LLVMRemarkOpaqueParser', + 'struct_LLVMRemarkOpaqueString', 'struct_LLVMTarget', + 'struct_c__SA_LLVMJITCSymbolMapPair', + 'struct_c__SA_LLVMJITEvaluatedSymbol', + 'struct_c__SA_LLVMJITSymbolFlags', + 'struct_c__SA_LLVMOrcCDependenceMapPair', + 'struct_c__SA_LLVMOrcCLookupSetElement', + 'struct_c__SA_LLVMOrcCSymbolAliasMapEntry', + 'struct_c__SA_LLVMOrcCSymbolAliasMapPair', + 'struct_c__SA_LLVMOrcCSymbolFlagsMapPair', + 'struct_c__SA_LLVMOrcCSymbolsList', + 'struct_c__SA_LTOObjectBuffer', 'thinlto_code_gen_t', + 'thinlto_codegen_add_cross_referenced_symbol', + 'thinlto_codegen_add_module', + 'thinlto_codegen_add_must_preserve_symbol', + 'thinlto_codegen_disable_codegen', 'thinlto_codegen_dispose', + 'thinlto_codegen_process', 'thinlto_codegen_set_cache_dir', + 'thinlto_codegen_set_cache_entry_expiration', + 'thinlto_codegen_set_cache_pruning_interval', + 'thinlto_codegen_set_cache_size_bytes', + 'thinlto_codegen_set_cache_size_files', + 'thinlto_codegen_set_cache_size_megabytes', + 'thinlto_codegen_set_codegen_only', 'thinlto_codegen_set_cpu', + 'thinlto_codegen_set_final_cache_size_relative_to_available_space', + 'thinlto_codegen_set_pic_model', + 'thinlto_codegen_set_savetemps_dir', 'thinlto_create_codegen', + 'thinlto_debug_options', 'thinlto_module_get_num_object_files', + 'thinlto_module_get_num_objects', 'thinlto_module_get_object', + 'thinlto_module_get_object_file', + 'thinlto_set_generated_objects_dir', 'uint32_t', 'uint64_t', + 'uint8_t'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/pci.py b/tinygrad_repo/tinygrad/runtime/autogen/pci.py new file mode 100644 index 0000000000..82ec9c13df --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/pci.py @@ -0,0 +1,1333 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + + + +LINUX_PCI_REGS_H = True # macro +PCI_CFG_SPACE_SIZE = 256 # macro +PCI_CFG_SPACE_EXP_SIZE = 4096 # macro +PCI_STD_HEADER_SIZEOF = 64 # macro +PCI_STD_NUM_BARS = 6 # macro +PCI_VENDOR_ID = 0x00 # macro +PCI_DEVICE_ID = 0x02 # macro +PCI_COMMAND = 0x04 # macro +PCI_COMMAND_IO = 0x1 # macro +PCI_COMMAND_MEMORY = 0x2 # macro +PCI_COMMAND_MASTER = 0x4 # macro +PCI_COMMAND_SPECIAL = 0x8 # macro +PCI_COMMAND_INVALIDATE = 0x10 # macro +PCI_COMMAND_VGA_PALETTE = 0x20 # macro +PCI_COMMAND_PARITY = 0x40 # macro +PCI_COMMAND_WAIT = 0x80 # macro +PCI_COMMAND_SERR = 0x100 # macro +PCI_COMMAND_FAST_BACK = 0x200 # macro +PCI_COMMAND_INTX_DISABLE = 0x400 # macro +PCI_STATUS = 0x06 # macro +PCI_STATUS_IMM_READY = 0x01 # macro +PCI_STATUS_INTERRUPT = 0x08 # macro +PCI_STATUS_CAP_LIST = 0x10 # macro +PCI_STATUS_66MHZ = 0x20 # macro +PCI_STATUS_UDF = 0x40 # macro +PCI_STATUS_FAST_BACK = 0x80 # macro +PCI_STATUS_PARITY = 0x100 # macro +PCI_STATUS_DEVSEL_MASK = 0x600 # macro +PCI_STATUS_DEVSEL_FAST = 0x000 # macro +PCI_STATUS_DEVSEL_MEDIUM = 0x200 # macro +PCI_STATUS_DEVSEL_SLOW = 0x400 # macro +PCI_STATUS_SIG_TARGET_ABORT = 0x800 # macro +PCI_STATUS_REC_TARGET_ABORT = 0x1000 # macro +PCI_STATUS_REC_MASTER_ABORT = 0x2000 # macro +PCI_STATUS_SIG_SYSTEM_ERROR = 0x4000 # macro +PCI_STATUS_DETECTED_PARITY = 0x8000 # macro +PCI_CLASS_REVISION = 0x08 # macro +PCI_REVISION_ID = 0x08 # macro +PCI_CLASS_PROG = 0x09 # macro +PCI_CLASS_DEVICE = 0x0a # macro +PCI_CACHE_LINE_SIZE = 0x0c # macro +PCI_LATENCY_TIMER = 0x0d # macro +PCI_HEADER_TYPE = 0x0e # macro +PCI_HEADER_TYPE_MASK = 0x7f # macro +PCI_HEADER_TYPE_NORMAL = 0 # macro +PCI_HEADER_TYPE_BRIDGE = 1 # macro +PCI_HEADER_TYPE_CARDBUS = 2 # macro +PCI_BIST = 0x0f # macro +PCI_BIST_CODE_MASK = 0x0f # macro +PCI_BIST_START = 0x40 # macro +PCI_BIST_CAPABLE = 0x80 # macro +PCI_BASE_ADDRESS_0 = 0x10 # macro +PCI_BASE_ADDRESS_1 = 0x14 # macro +PCI_BASE_ADDRESS_2 = 0x18 # macro +PCI_BASE_ADDRESS_3 = 0x1c # macro +PCI_BASE_ADDRESS_4 = 0x20 # macro +PCI_BASE_ADDRESS_5 = 0x24 # macro +PCI_BASE_ADDRESS_SPACE = 0x01 # macro +PCI_BASE_ADDRESS_SPACE_IO = 0x01 # macro +PCI_BASE_ADDRESS_SPACE_MEMORY = 0x00 # macro +PCI_BASE_ADDRESS_MEM_TYPE_MASK = 0x06 # macro +PCI_BASE_ADDRESS_MEM_TYPE_32 = 0x00 # macro +PCI_BASE_ADDRESS_MEM_TYPE_1M = 0x02 # macro +PCI_BASE_ADDRESS_MEM_TYPE_64 = 0x04 # macro +PCI_BASE_ADDRESS_MEM_PREFETCH = 0x08 # macro +PCI_BASE_ADDRESS_MEM_MASK = (~0x0f) # macro +PCI_BASE_ADDRESS_IO_MASK = (~0x03) # macro +PCI_CARDBUS_CIS = 0x28 # macro +PCI_SUBSYSTEM_VENDOR_ID = 0x2c # macro +PCI_SUBSYSTEM_ID = 0x2e # macro +PCI_ROM_ADDRESS = 0x30 # macro +PCI_ROM_ADDRESS_ENABLE = 0x01 # macro +PCI_ROM_ADDRESS_MASK = (~0x7ff) # macro +PCI_CAPABILITY_LIST = 0x34 # macro +PCI_INTERRUPT_LINE = 0x3c # macro +PCI_INTERRUPT_PIN = 0x3d # macro +PCI_MIN_GNT = 0x3e # macro +PCI_MAX_LAT = 0x3f # macro +PCI_PRIMARY_BUS = 0x18 # macro +PCI_SECONDARY_BUS = 0x19 # macro +PCI_SUBORDINATE_BUS = 0x1a # macro +PCI_SEC_LATENCY_TIMER = 0x1b # macro +PCI_IO_BASE = 0x1c # macro +PCI_IO_LIMIT = 0x1d # macro +PCI_IO_RANGE_TYPE_MASK = 0x0f # macro +PCI_IO_RANGE_TYPE_16 = 0x00 # macro +PCI_IO_RANGE_TYPE_32 = 0x01 # macro +PCI_IO_RANGE_MASK = (~0x0f) # macro +PCI_IO_1K_RANGE_MASK = (~0x03) # macro +PCI_SEC_STATUS = 0x1e # macro +PCI_MEMORY_BASE = 0x20 # macro +PCI_MEMORY_LIMIT = 0x22 # macro +PCI_MEMORY_RANGE_TYPE_MASK = 0x0f # macro +PCI_MEMORY_RANGE_MASK = (~0x0f) # macro +PCI_PREF_MEMORY_BASE = 0x24 # macro +PCI_PREF_MEMORY_LIMIT = 0x26 # macro +PCI_PREF_RANGE_TYPE_MASK = 0x0f # macro +PCI_PREF_RANGE_TYPE_32 = 0x00 # macro +PCI_PREF_RANGE_TYPE_64 = 0x01 # macro +PCI_PREF_RANGE_MASK = (~0x0f) # macro +PCI_PREF_BASE_UPPER32 = 0x28 # macro +PCI_PREF_LIMIT_UPPER32 = 0x2c # macro +PCI_IO_BASE_UPPER16 = 0x30 # macro +PCI_IO_LIMIT_UPPER16 = 0x32 # macro +PCI_ROM_ADDRESS1 = 0x38 # macro +PCI_BRIDGE_CONTROL = 0x3e # macro +PCI_BRIDGE_CTL_PARITY = 0x01 # macro +PCI_BRIDGE_CTL_SERR = 0x02 # macro +PCI_BRIDGE_CTL_ISA = 0x04 # macro +PCI_BRIDGE_CTL_VGA = 0x08 # macro +PCI_BRIDGE_CTL_MASTER_ABORT = 0x20 # macro +PCI_BRIDGE_CTL_BUS_RESET = 0x40 # macro +PCI_BRIDGE_CTL_FAST_BACK = 0x80 # macro +PCI_CB_CAPABILITY_LIST = 0x14 # macro +PCI_CB_SEC_STATUS = 0x16 # macro +PCI_CB_PRIMARY_BUS = 0x18 # macro +PCI_CB_CARD_BUS = 0x19 # macro +PCI_CB_SUBORDINATE_BUS = 0x1a # macro +PCI_CB_LATENCY_TIMER = 0x1b # macro +PCI_CB_MEMORY_BASE_0 = 0x1c # macro +PCI_CB_MEMORY_LIMIT_0 = 0x20 # macro +PCI_CB_MEMORY_BASE_1 = 0x24 # macro +PCI_CB_MEMORY_LIMIT_1 = 0x28 # macro +PCI_CB_IO_BASE_0 = 0x2c # macro +PCI_CB_IO_BASE_0_HI = 0x2e # macro +PCI_CB_IO_LIMIT_0 = 0x30 # macro +PCI_CB_IO_LIMIT_0_HI = 0x32 # macro +PCI_CB_IO_BASE_1 = 0x34 # macro +PCI_CB_IO_BASE_1_HI = 0x36 # macro +PCI_CB_IO_LIMIT_1 = 0x38 # macro +PCI_CB_IO_LIMIT_1_HI = 0x3a # macro +PCI_CB_IO_RANGE_MASK = (~0x03) # macro +PCI_CB_BRIDGE_CONTROL = 0x3e # macro +PCI_CB_BRIDGE_CTL_PARITY = 0x01 # macro +PCI_CB_BRIDGE_CTL_SERR = 0x02 # macro +PCI_CB_BRIDGE_CTL_ISA = 0x04 # macro +PCI_CB_BRIDGE_CTL_VGA = 0x08 # macro +PCI_CB_BRIDGE_CTL_MASTER_ABORT = 0x20 # macro +PCI_CB_BRIDGE_CTL_CB_RESET = 0x40 # macro +PCI_CB_BRIDGE_CTL_16BIT_INT = 0x80 # macro +PCI_CB_BRIDGE_CTL_PREFETCH_MEM0 = 0x100 # macro +PCI_CB_BRIDGE_CTL_PREFETCH_MEM1 = 0x200 # macro +PCI_CB_BRIDGE_CTL_POST_WRITES = 0x400 # macro +PCI_CB_SUBSYSTEM_VENDOR_ID = 0x40 # macro +PCI_CB_SUBSYSTEM_ID = 0x42 # macro +PCI_CB_LEGACY_MODE_BASE = 0x44 # macro +PCI_CAP_LIST_ID = 0 # macro +PCI_CAP_ID_PM = 0x01 # macro +PCI_CAP_ID_AGP = 0x02 # macro +PCI_CAP_ID_VPD = 0x03 # macro +PCI_CAP_ID_SLOTID = 0x04 # macro +PCI_CAP_ID_MSI = 0x05 # macro +PCI_CAP_ID_CHSWP = 0x06 # macro +PCI_CAP_ID_PCIX = 0x07 # macro +PCI_CAP_ID_HT = 0x08 # macro +PCI_CAP_ID_VNDR = 0x09 # macro +PCI_CAP_ID_DBG = 0x0A # macro +PCI_CAP_ID_CCRC = 0x0B # macro +PCI_CAP_ID_SHPC = 0x0C # macro +PCI_CAP_ID_SSVID = 0x0D # macro +PCI_CAP_ID_AGP3 = 0x0E # macro +PCI_CAP_ID_SECDEV = 0x0F # macro +PCI_CAP_ID_EXP = 0x10 # macro +PCI_CAP_ID_MSIX = 0x11 # macro +PCI_CAP_ID_SATA = 0x12 # macro +PCI_CAP_ID_AF = 0x13 # macro +PCI_CAP_ID_EA = 0x14 # macro +PCI_CAP_ID_MAX = 0x14 # macro +PCI_CAP_LIST_NEXT = 1 # macro +PCI_CAP_FLAGS = 2 # macro +PCI_CAP_SIZEOF = 4 # macro +PCI_PM_PMC = 2 # macro +PCI_PM_CAP_VER_MASK = 0x0007 # macro +PCI_PM_CAP_PME_CLOCK = 0x0008 # macro +PCI_PM_CAP_RESERVED = 0x0010 # macro +PCI_PM_CAP_DSI = 0x0020 # macro +PCI_PM_CAP_AUX_POWER = 0x01C0 # macro +PCI_PM_CAP_D1 = 0x0200 # macro +PCI_PM_CAP_D2 = 0x0400 # macro +PCI_PM_CAP_PME = 0x0800 # macro +PCI_PM_CAP_PME_MASK = 0xF800 # macro +PCI_PM_CAP_PME_D0 = 0x0800 # macro +PCI_PM_CAP_PME_D1 = 0x1000 # macro +PCI_PM_CAP_PME_D2 = 0x2000 # macro +PCI_PM_CAP_PME_D3hot = 0x4000 # macro +PCI_PM_CAP_PME_D3cold = 0x8000 # macro +PCI_PM_CAP_PME_SHIFT = 11 # macro +PCI_PM_CTRL = 4 # macro +PCI_PM_CTRL_STATE_MASK = 0x0003 # macro +PCI_PM_CTRL_NO_SOFT_RESET = 0x0008 # macro +PCI_PM_CTRL_PME_ENABLE = 0x0100 # macro +PCI_PM_CTRL_DATA_SEL_MASK = 0x1e00 # macro +PCI_PM_CTRL_DATA_SCALE_MASK = 0x6000 # macro +PCI_PM_CTRL_PME_STATUS = 0x8000 # macro +PCI_PM_PPB_EXTENSIONS = 6 # macro +PCI_PM_PPB_B2_B3 = 0x40 # macro +PCI_PM_BPCC_ENABLE = 0x80 # macro +PCI_PM_DATA_REGISTER = 7 # macro +PCI_PM_SIZEOF = 8 # macro +PCI_AGP_VERSION = 2 # macro +PCI_AGP_RFU = 3 # macro +PCI_AGP_STATUS = 4 # macro +PCI_AGP_STATUS_RQ_MASK = 0xff000000 # macro +PCI_AGP_STATUS_SBA = 0x0200 # macro +PCI_AGP_STATUS_64BIT = 0x0020 # macro +PCI_AGP_STATUS_FW = 0x0010 # macro +PCI_AGP_STATUS_RATE4 = 0x0004 # macro +PCI_AGP_STATUS_RATE2 = 0x0002 # macro +PCI_AGP_STATUS_RATE1 = 0x0001 # macro +PCI_AGP_COMMAND = 8 # macro +PCI_AGP_COMMAND_RQ_MASK = 0xff000000 # macro +PCI_AGP_COMMAND_SBA = 0x0200 # macro +PCI_AGP_COMMAND_AGP = 0x0100 # macro +PCI_AGP_COMMAND_64BIT = 0x0020 # macro +PCI_AGP_COMMAND_FW = 0x0010 # macro +PCI_AGP_COMMAND_RATE4 = 0x0004 # macro +PCI_AGP_COMMAND_RATE2 = 0x0002 # macro +PCI_AGP_COMMAND_RATE1 = 0x0001 # macro +PCI_AGP_SIZEOF = 12 # macro +PCI_VPD_ADDR = 2 # macro +PCI_VPD_ADDR_MASK = 0x7fff # macro +PCI_VPD_ADDR_F = 0x8000 # macro +PCI_VPD_DATA = 4 # macro +PCI_CAP_VPD_SIZEOF = 8 # macro +PCI_SID_ESR = 2 # macro +PCI_SID_ESR_NSLOTS = 0x1f # macro +PCI_SID_ESR_FIC = 0x20 # macro +PCI_SID_CHASSIS_NR = 3 # macro +PCI_MSI_FLAGS = 2 # macro +PCI_MSI_FLAGS_ENABLE = 0x0001 # macro +PCI_MSI_FLAGS_QMASK = 0x000e # macro +PCI_MSI_FLAGS_QSIZE = 0x0070 # macro +PCI_MSI_FLAGS_64BIT = 0x0080 # macro +PCI_MSI_FLAGS_MASKBIT = 0x0100 # macro +PCI_MSI_RFU = 3 # macro +PCI_MSI_ADDRESS_LO = 4 # macro +PCI_MSI_ADDRESS_HI = 8 # macro +PCI_MSI_DATA_32 = 8 # macro +PCI_MSI_MASK_32 = 12 # macro +PCI_MSI_PENDING_32 = 16 # macro +PCI_MSI_DATA_64 = 12 # macro +PCI_MSI_MASK_64 = 16 # macro +PCI_MSI_PENDING_64 = 20 # macro +PCI_MSIX_FLAGS = 2 # macro +PCI_MSIX_FLAGS_QSIZE = 0x07FF # macro +PCI_MSIX_FLAGS_MASKALL = 0x4000 # macro +PCI_MSIX_FLAGS_ENABLE = 0x8000 # macro +PCI_MSIX_TABLE = 4 # macro +PCI_MSIX_TABLE_BIR = 0x00000007 # macro +PCI_MSIX_TABLE_OFFSET = 0xfffffff8 # macro +PCI_MSIX_PBA = 8 # macro +PCI_MSIX_PBA_BIR = 0x00000007 # macro +PCI_MSIX_PBA_OFFSET = 0xfffffff8 # macro +PCI_MSIX_FLAGS_BIRMASK = 0x00000007 # macro +PCI_CAP_MSIX_SIZEOF = 12 # macro +PCI_MSIX_ENTRY_SIZE = 16 # macro +PCI_MSIX_ENTRY_LOWER_ADDR = 0 # macro +PCI_MSIX_ENTRY_UPPER_ADDR = 4 # macro +PCI_MSIX_ENTRY_DATA = 8 # macro +PCI_MSIX_ENTRY_VECTOR_CTRL = 12 # macro +PCI_MSIX_ENTRY_CTRL_MASKBIT = 0x00000001 # macro +PCI_CHSWP_CSR = 2 # macro +PCI_CHSWP_DHA = 0x01 # macro +PCI_CHSWP_EIM = 0x02 # macro +PCI_CHSWP_PIE = 0x04 # macro +PCI_CHSWP_LOO = 0x08 # macro +PCI_CHSWP_PI = 0x30 # macro +PCI_CHSWP_EXT = 0x40 # macro +PCI_CHSWP_INS = 0x80 # macro +PCI_AF_LENGTH = 2 # macro +PCI_AF_CAP = 3 # macro +PCI_AF_CAP_TP = 0x01 # macro +PCI_AF_CAP_FLR = 0x02 # macro +PCI_AF_CTRL = 4 # macro +PCI_AF_CTRL_FLR = 0x01 # macro +PCI_AF_STATUS = 5 # macro +PCI_AF_STATUS_TP = 0x01 # macro +PCI_CAP_AF_SIZEOF = 6 # macro +PCI_EA_NUM_ENT = 2 # macro +PCI_EA_NUM_ENT_MASK = 0x3f # macro +PCI_EA_FIRST_ENT = 4 # macro +PCI_EA_FIRST_ENT_BRIDGE = 8 # macro +PCI_EA_ES = 0x00000007 # macro +PCI_EA_BEI = 0x000000f0 # macro +PCI_EA_SEC_BUS_MASK = 0xff # macro +PCI_EA_SUB_BUS_MASK = 0xff00 # macro +PCI_EA_SUB_BUS_SHIFT = 8 # macro +PCI_EA_BEI_BAR0 = 0 # macro +PCI_EA_BEI_BAR5 = 5 # macro +PCI_EA_BEI_BRIDGE = 6 # macro +PCI_EA_BEI_ENI = 7 # macro +PCI_EA_BEI_ROM = 8 # macro +PCI_EA_BEI_VF_BAR0 = 9 # macro +PCI_EA_BEI_VF_BAR5 = 14 # macro +PCI_EA_BEI_RESERVED = 15 # macro +PCI_EA_PP = 0x0000ff00 # macro +PCI_EA_SP = 0x00ff0000 # macro +PCI_EA_P_MEM = 0x00 # macro +PCI_EA_P_MEM_PREFETCH = 0x01 # macro +PCI_EA_P_IO = 0x02 # macro +PCI_EA_P_VF_MEM_PREFETCH = 0x03 # macro +PCI_EA_P_VF_MEM = 0x04 # macro +PCI_EA_P_BRIDGE_MEM = 0x05 # macro +PCI_EA_P_BRIDGE_MEM_PREFETCH = 0x06 # macro +PCI_EA_P_BRIDGE_IO = 0x07 # macro +PCI_EA_P_MEM_RESERVED = 0xfd # macro +PCI_EA_P_IO_RESERVED = 0xfe # macro +PCI_EA_P_UNAVAILABLE = 0xff # macro +PCI_EA_WRITABLE = 0x40000000 # macro +PCI_EA_ENABLE = 0x80000000 # macro +PCI_EA_BASE = 4 # macro +PCI_EA_MAX_OFFSET = 8 # macro +PCI_EA_IS_64 = 0x00000002 # macro +PCI_EA_FIELD_MASK = 0xfffffffc # macro +PCI_X_CMD = 2 # macro +PCI_X_CMD_DPERR_E = 0x0001 # macro +PCI_X_CMD_ERO = 0x0002 # macro +PCI_X_CMD_READ_512 = 0x0000 # macro +PCI_X_CMD_READ_1K = 0x0004 # macro +PCI_X_CMD_READ_2K = 0x0008 # macro +PCI_X_CMD_READ_4K = 0x000c # macro +PCI_X_CMD_MAX_READ = 0x000c # macro +PCI_X_CMD_SPLIT_1 = 0x0000 # macro +PCI_X_CMD_SPLIT_2 = 0x0010 # macro +PCI_X_CMD_SPLIT_3 = 0x0020 # macro +PCI_X_CMD_SPLIT_4 = 0x0030 # macro +PCI_X_CMD_SPLIT_8 = 0x0040 # macro +PCI_X_CMD_SPLIT_12 = 0x0050 # macro +PCI_X_CMD_SPLIT_16 = 0x0060 # macro +PCI_X_CMD_SPLIT_32 = 0x0070 # macro +PCI_X_CMD_MAX_SPLIT = 0x0070 # macro +def PCI_X_CMD_VERSION(x): # macro + return (((x)>>12)&3) +PCI_X_STATUS = 4 # macro +PCI_X_STATUS_DEVFN = 0x000000ff # macro +PCI_X_STATUS_BUS = 0x0000ff00 # macro +PCI_X_STATUS_64BIT = 0x00010000 # macro +PCI_X_STATUS_133MHZ = 0x00020000 # macro +PCI_X_STATUS_SPL_DISC = 0x00040000 # macro +PCI_X_STATUS_UNX_SPL = 0x00080000 # macro +PCI_X_STATUS_COMPLEX = 0x00100000 # macro +PCI_X_STATUS_MAX_READ = 0x00600000 # macro +PCI_X_STATUS_MAX_SPLIT = 0x03800000 # macro +PCI_X_STATUS_MAX_CUM = 0x1c000000 # macro +PCI_X_STATUS_SPL_ERR = 0x20000000 # macro +PCI_X_STATUS_266MHZ = 0x40000000 # macro +PCI_X_STATUS_533MHZ = 0x80000000 # macro +PCI_X_ECC_CSR = 8 # macro +PCI_CAP_PCIX_SIZEOF_V0 = 8 # macro +PCI_CAP_PCIX_SIZEOF_V1 = 24 # macro +PCI_CAP_PCIX_SIZEOF_V2 = 24 # macro +PCI_X_BRIDGE_SSTATUS = 2 # macro +PCI_X_SSTATUS_64BIT = 0x0001 # macro +PCI_X_SSTATUS_133MHZ = 0x0002 # macro +PCI_X_SSTATUS_FREQ = 0x03c0 # macro +PCI_X_SSTATUS_VERS = 0x3000 # macro +PCI_X_SSTATUS_V1 = 0x1000 # macro +PCI_X_SSTATUS_V2 = 0x2000 # macro +PCI_X_SSTATUS_266MHZ = 0x4000 # macro +PCI_X_SSTATUS_533MHZ = 0x8000 # macro +PCI_X_BRIDGE_STATUS = 4 # macro +PCI_SSVID_VENDOR_ID = 4 # macro +PCI_SSVID_DEVICE_ID = 6 # macro +PCI_EXP_FLAGS = 2 # macro +PCI_EXP_FLAGS_VERS = 0x000f # macro +PCI_EXP_FLAGS_TYPE = 0x00f0 # macro +PCI_EXP_TYPE_ENDPOINT = 0x0 # macro +PCI_EXP_TYPE_LEG_END = 0x1 # macro +PCI_EXP_TYPE_ROOT_PORT = 0x4 # macro +PCI_EXP_TYPE_UPSTREAM = 0x5 # macro +PCI_EXP_TYPE_DOWNSTREAM = 0x6 # macro +PCI_EXP_TYPE_PCI_BRIDGE = 0x7 # macro +PCI_EXP_TYPE_PCIE_BRIDGE = 0x8 # macro +PCI_EXP_TYPE_RC_END = 0x9 # macro +PCI_EXP_TYPE_RC_EC = 0xa # macro +PCI_EXP_FLAGS_SLOT = 0x0100 # macro +PCI_EXP_FLAGS_IRQ = 0x3e00 # macro +PCI_EXP_DEVCAP = 4 # macro +PCI_EXP_DEVCAP_PAYLOAD = 0x00000007 # macro +PCI_EXP_DEVCAP_PHANTOM = 0x00000018 # macro +PCI_EXP_DEVCAP_EXT_TAG = 0x00000020 # macro +PCI_EXP_DEVCAP_L0S = 0x000001c0 # macro +PCI_EXP_DEVCAP_L1 = 0x00000e00 # macro +PCI_EXP_DEVCAP_ATN_BUT = 0x00001000 # macro +PCI_EXP_DEVCAP_ATN_IND = 0x00002000 # macro +PCI_EXP_DEVCAP_PWR_IND = 0x00004000 # macro +PCI_EXP_DEVCAP_RBER = 0x00008000 # macro +PCI_EXP_DEVCAP_PWR_VAL = 0x03fc0000 # macro +PCI_EXP_DEVCAP_PWR_SCL = 0x0c000000 # macro +PCI_EXP_DEVCAP_FLR = 0x10000000 # macro +PCI_EXP_DEVCTL = 8 # macro +PCI_EXP_DEVCTL_CERE = 0x0001 # macro +PCI_EXP_DEVCTL_NFERE = 0x0002 # macro +PCI_EXP_DEVCTL_FERE = 0x0004 # macro +PCI_EXP_DEVCTL_URRE = 0x0008 # macro +PCI_EXP_DEVCTL_RELAX_EN = 0x0010 # macro +PCI_EXP_DEVCTL_PAYLOAD = 0x00e0 # macro +PCI_EXP_DEVCTL_PAYLOAD_128B = 0x0000 # macro +PCI_EXP_DEVCTL_PAYLOAD_256B = 0x0020 # macro +PCI_EXP_DEVCTL_PAYLOAD_512B = 0x0040 # macro +PCI_EXP_DEVCTL_PAYLOAD_1024B = 0x0060 # macro +PCI_EXP_DEVCTL_PAYLOAD_2048B = 0x0080 # macro +PCI_EXP_DEVCTL_PAYLOAD_4096B = 0x00a0 # macro +PCI_EXP_DEVCTL_EXT_TAG = 0x0100 # macro +PCI_EXP_DEVCTL_PHANTOM = 0x0200 # macro +PCI_EXP_DEVCTL_AUX_PME = 0x0400 # macro +PCI_EXP_DEVCTL_NOSNOOP_EN = 0x0800 # macro +PCI_EXP_DEVCTL_READRQ = 0x7000 # macro +PCI_EXP_DEVCTL_READRQ_128B = 0x0000 # macro +PCI_EXP_DEVCTL_READRQ_256B = 0x1000 # macro +PCI_EXP_DEVCTL_READRQ_512B = 0x2000 # macro +PCI_EXP_DEVCTL_READRQ_1024B = 0x3000 # macro +PCI_EXP_DEVCTL_READRQ_2048B = 0x4000 # macro +PCI_EXP_DEVCTL_READRQ_4096B = 0x5000 # macro +PCI_EXP_DEVCTL_BCR_FLR = 0x8000 # macro +PCI_EXP_DEVSTA = 10 # macro +PCI_EXP_DEVSTA_CED = 0x0001 # macro +PCI_EXP_DEVSTA_NFED = 0x0002 # macro +PCI_EXP_DEVSTA_FED = 0x0004 # macro +PCI_EXP_DEVSTA_URD = 0x0008 # macro +PCI_EXP_DEVSTA_AUXPD = 0x0010 # macro +PCI_EXP_DEVSTA_TRPND = 0x0020 # macro +PCI_CAP_EXP_RC_ENDPOINT_SIZEOF_V1 = 12 # macro +PCI_EXP_LNKCAP = 12 # macro +PCI_EXP_LNKCAP_SLS = 0x0000000f # macro +PCI_EXP_LNKCAP_SLS_2_5GB = 0x00000001 # macro +PCI_EXP_LNKCAP_SLS_5_0GB = 0x00000002 # macro +PCI_EXP_LNKCAP_SLS_8_0GB = 0x00000003 # macro +PCI_EXP_LNKCAP_SLS_16_0GB = 0x00000004 # macro +PCI_EXP_LNKCAP_SLS_32_0GB = 0x00000005 # macro +PCI_EXP_LNKCAP_SLS_64_0GB = 0x00000006 # macro +PCI_EXP_LNKCAP_MLW = 0x000003f0 # macro +PCI_EXP_LNKCAP_ASPMS = 0x00000c00 # macro +PCI_EXP_LNKCAP_ASPM_L0S = 0x00000400 # macro +PCI_EXP_LNKCAP_ASPM_L1 = 0x00000800 # macro +PCI_EXP_LNKCAP_L0SEL = 0x00007000 # macro +PCI_EXP_LNKCAP_L1EL = 0x00038000 # macro +PCI_EXP_LNKCAP_CLKPM = 0x00040000 # macro +PCI_EXP_LNKCAP_SDERC = 0x00080000 # macro +PCI_EXP_LNKCAP_DLLLARC = 0x00100000 # macro +PCI_EXP_LNKCAP_LBNC = 0x00200000 # macro +PCI_EXP_LNKCAP_PN = 0xff000000 # macro +PCI_EXP_LNKCTL = 16 # macro +PCI_EXP_LNKCTL_ASPMC = 0x0003 # macro +PCI_EXP_LNKCTL_ASPM_L0S = 0x0001 # macro +PCI_EXP_LNKCTL_ASPM_L1 = 0x0002 # macro +PCI_EXP_LNKCTL_RCB = 0x0008 # macro +PCI_EXP_LNKCTL_LD = 0x0010 # macro +PCI_EXP_LNKCTL_RL = 0x0020 # macro +PCI_EXP_LNKCTL_CCC = 0x0040 # macro +PCI_EXP_LNKCTL_ES = 0x0080 # macro +PCI_EXP_LNKCTL_CLKREQ_EN = 0x0100 # macro +PCI_EXP_LNKCTL_HAWD = 0x0200 # macro +PCI_EXP_LNKCTL_LBMIE = 0x0400 # macro +PCI_EXP_LNKCTL_LABIE = 0x0800 # macro +PCI_EXP_LNKSTA = 18 # macro +PCI_EXP_LNKSTA_CLS = 0x000f # macro +PCI_EXP_LNKSTA_CLS_2_5GB = 0x0001 # macro +PCI_EXP_LNKSTA_CLS_5_0GB = 0x0002 # macro +PCI_EXP_LNKSTA_CLS_8_0GB = 0x0003 # macro +PCI_EXP_LNKSTA_CLS_16_0GB = 0x0004 # macro +PCI_EXP_LNKSTA_CLS_32_0GB = 0x0005 # macro +PCI_EXP_LNKSTA_CLS_64_0GB = 0x0006 # macro +PCI_EXP_LNKSTA_NLW = 0x03f0 # macro +PCI_EXP_LNKSTA_NLW_X1 = 0x0010 # macro +PCI_EXP_LNKSTA_NLW_X2 = 0x0020 # macro +PCI_EXP_LNKSTA_NLW_X4 = 0x0040 # macro +PCI_EXP_LNKSTA_NLW_X8 = 0x0080 # macro +PCI_EXP_LNKSTA_NLW_SHIFT = 4 # macro +PCI_EXP_LNKSTA_LT = 0x0800 # macro +PCI_EXP_LNKSTA_SLC = 0x1000 # macro +PCI_EXP_LNKSTA_DLLLA = 0x2000 # macro +PCI_EXP_LNKSTA_LBMS = 0x4000 # macro +PCI_EXP_LNKSTA_LABS = 0x8000 # macro +PCI_CAP_EXP_ENDPOINT_SIZEOF_V1 = 20 # macro +PCI_EXP_SLTCAP = 20 # macro +PCI_EXP_SLTCAP_ABP = 0x00000001 # macro +PCI_EXP_SLTCAP_PCP = 0x00000002 # macro +PCI_EXP_SLTCAP_MRLSP = 0x00000004 # macro +PCI_EXP_SLTCAP_AIP = 0x00000008 # macro +PCI_EXP_SLTCAP_PIP = 0x00000010 # macro +PCI_EXP_SLTCAP_HPS = 0x00000020 # macro +PCI_EXP_SLTCAP_HPC = 0x00000040 # macro +PCI_EXP_SLTCAP_SPLV = 0x00007f80 # macro +PCI_EXP_SLTCAP_SPLS = 0x00018000 # macro +PCI_EXP_SLTCAP_EIP = 0x00020000 # macro +PCI_EXP_SLTCAP_NCCS = 0x00040000 # macro +PCI_EXP_SLTCAP_PSN = 0xfff80000 # macro +PCI_EXP_SLTCTL = 24 # macro +PCI_EXP_SLTCTL_ABPE = 0x0001 # macro +PCI_EXP_SLTCTL_PFDE = 0x0002 # macro +PCI_EXP_SLTCTL_MRLSCE = 0x0004 # macro +PCI_EXP_SLTCTL_PDCE = 0x0008 # macro +PCI_EXP_SLTCTL_CCIE = 0x0010 # macro +PCI_EXP_SLTCTL_HPIE = 0x0020 # macro +PCI_EXP_SLTCTL_AIC = 0x00c0 # macro +PCI_EXP_SLTCTL_ATTN_IND_SHIFT = 6 # macro +PCI_EXP_SLTCTL_ATTN_IND_ON = 0x0040 # macro +PCI_EXP_SLTCTL_ATTN_IND_BLINK = 0x0080 # macro +PCI_EXP_SLTCTL_ATTN_IND_OFF = 0x00c0 # macro +PCI_EXP_SLTCTL_PIC = 0x0300 # macro +PCI_EXP_SLTCTL_PWR_IND_ON = 0x0100 # macro +PCI_EXP_SLTCTL_PWR_IND_BLINK = 0x0200 # macro +PCI_EXP_SLTCTL_PWR_IND_OFF = 0x0300 # macro +PCI_EXP_SLTCTL_PCC = 0x0400 # macro +PCI_EXP_SLTCTL_PWR_ON = 0x0000 # macro +PCI_EXP_SLTCTL_PWR_OFF = 0x0400 # macro +PCI_EXP_SLTCTL_EIC = 0x0800 # macro +PCI_EXP_SLTCTL_DLLSCE = 0x1000 # macro +PCI_EXP_SLTCTL_IBPD_DISABLE = 0x4000 # macro +PCI_EXP_SLTSTA = 26 # macro +PCI_EXP_SLTSTA_ABP = 0x0001 # macro +PCI_EXP_SLTSTA_PFD = 0x0002 # macro +PCI_EXP_SLTSTA_MRLSC = 0x0004 # macro +PCI_EXP_SLTSTA_PDC = 0x0008 # macro +PCI_EXP_SLTSTA_CC = 0x0010 # macro +PCI_EXP_SLTSTA_MRLSS = 0x0020 # macro +PCI_EXP_SLTSTA_PDS = 0x0040 # macro +PCI_EXP_SLTSTA_EIS = 0x0080 # macro +PCI_EXP_SLTSTA_DLLSC = 0x0100 # macro +PCI_EXP_RTCTL = 28 # macro +PCI_EXP_RTCTL_SECEE = 0x0001 # macro +PCI_EXP_RTCTL_SENFEE = 0x0002 # macro +PCI_EXP_RTCTL_SEFEE = 0x0004 # macro +PCI_EXP_RTCTL_PMEIE = 0x0008 # macro +PCI_EXP_RTCTL_CRSSVE = 0x0010 # macro +PCI_EXP_RTCAP = 30 # macro +PCI_EXP_RTCAP_CRSVIS = 0x0001 # macro +PCI_EXP_RTSTA = 32 # macro +PCI_EXP_RTSTA_PME = 0x00010000 # macro +PCI_EXP_RTSTA_PENDING = 0x00020000 # macro +PCI_EXP_DEVCAP2 = 36 # macro +PCI_EXP_DEVCAP2_COMP_TMOUT_DIS = 0x00000010 # macro +PCI_EXP_DEVCAP2_ARI = 0x00000020 # macro +PCI_EXP_DEVCAP2_ATOMIC_ROUTE = 0x00000040 # macro +PCI_EXP_DEVCAP2_ATOMIC_COMP32 = 0x00000080 # macro +PCI_EXP_DEVCAP2_ATOMIC_COMP64 = 0x00000100 # macro +PCI_EXP_DEVCAP2_ATOMIC_COMP128 = 0x00000200 # macro +PCI_EXP_DEVCAP2_LTR = 0x00000800 # macro +PCI_EXP_DEVCAP2_OBFF_MASK = 0x000c0000 # macro +PCI_EXP_DEVCAP2_OBFF_MSG = 0x00040000 # macro +PCI_EXP_DEVCAP2_OBFF_WAKE = 0x00080000 # macro +PCI_EXP_DEVCAP2_EE_PREFIX = 0x00200000 # macro +PCI_EXP_DEVCTL2 = 40 # macro +PCI_EXP_DEVCTL2_COMP_TIMEOUT = 0x000f # macro +PCI_EXP_DEVCTL2_COMP_TMOUT_DIS = 0x0010 # macro +PCI_EXP_DEVCTL2_ARI = 0x0020 # macro +PCI_EXP_DEVCTL2_ATOMIC_REQ = 0x0040 # macro +PCI_EXP_DEVCTL2_ATOMIC_EGRESS_BLOCK = 0x0080 # macro +PCI_EXP_DEVCTL2_IDO_REQ_EN = 0x0100 # macro +PCI_EXP_DEVCTL2_IDO_CMP_EN = 0x0200 # macro +PCI_EXP_DEVCTL2_LTR_EN = 0x0400 # macro +PCI_EXP_DEVCTL2_OBFF_MSGA_EN = 0x2000 # macro +PCI_EXP_DEVCTL2_OBFF_MSGB_EN = 0x4000 # macro +PCI_EXP_DEVCTL2_OBFF_WAKE_EN = 0x6000 # macro +PCI_EXP_DEVSTA2 = 42 # macro +PCI_CAP_EXP_RC_ENDPOINT_SIZEOF_V2 = 44 # macro +PCI_EXP_LNKCAP2 = 44 # macro +PCI_EXP_LNKCAP2_SLS_2_5GB = 0x00000002 # macro +PCI_EXP_LNKCAP2_SLS_5_0GB = 0x00000004 # macro +PCI_EXP_LNKCAP2_SLS_8_0GB = 0x00000008 # macro +PCI_EXP_LNKCAP2_SLS_16_0GB = 0x00000010 # macro +PCI_EXP_LNKCAP2_SLS_32_0GB = 0x00000020 # macro +PCI_EXP_LNKCAP2_SLS_64_0GB = 0x00000040 # macro +PCI_EXP_LNKCAP2_CROSSLINK = 0x00000100 # macro +PCI_EXP_LNKCTL2 = 48 # macro +PCI_EXP_LNKCTL2_TLS = 0x000f # macro +PCI_EXP_LNKCTL2_TLS_2_5GT = 0x0001 # macro +PCI_EXP_LNKCTL2_TLS_5_0GT = 0x0002 # macro +PCI_EXP_LNKCTL2_TLS_8_0GT = 0x0003 # macro +PCI_EXP_LNKCTL2_TLS_16_0GT = 0x0004 # macro +PCI_EXP_LNKCTL2_TLS_32_0GT = 0x0005 # macro +PCI_EXP_LNKCTL2_TLS_64_0GT = 0x0006 # macro +PCI_EXP_LNKCTL2_ENTER_COMP = 0x0010 # macro +PCI_EXP_LNKCTL2_TX_MARGIN = 0x0380 # macro +PCI_EXP_LNKCTL2_HASD = 0x0020 # macro +PCI_EXP_LNKSTA2 = 50 # macro +PCI_CAP_EXP_ENDPOINT_SIZEOF_V2 = 52 # macro +PCI_EXP_SLTCAP2 = 52 # macro +PCI_EXP_SLTCAP2_IBPD = 0x00000001 # macro +PCI_EXP_SLTCTL2 = 56 # macro +PCI_EXP_SLTSTA2 = 58 # macro +def PCI_EXT_CAP_ID(header): # macro + return (header&0x0000ffff) +def PCI_EXT_CAP_VER(header): # macro + return ((header>>16)&0xf) +def PCI_EXT_CAP_NEXT(header): # macro + return ((header>>20)&0xffc) +PCI_EXT_CAP_ID_ERR = 0x01 # macro +PCI_EXT_CAP_ID_VC = 0x02 # macro +PCI_EXT_CAP_ID_DSN = 0x03 # macro +PCI_EXT_CAP_ID_PWR = 0x04 # macro +PCI_EXT_CAP_ID_RCLD = 0x05 # macro +PCI_EXT_CAP_ID_RCILC = 0x06 # macro +PCI_EXT_CAP_ID_RCEC = 0x07 # macro +PCI_EXT_CAP_ID_MFVC = 0x08 # macro +PCI_EXT_CAP_ID_VC9 = 0x09 # macro +PCI_EXT_CAP_ID_RCRB = 0x0A # macro +PCI_EXT_CAP_ID_VNDR = 0x0B # macro +PCI_EXT_CAP_ID_CAC = 0x0C # macro +PCI_EXT_CAP_ID_ACS = 0x0D # macro +PCI_EXT_CAP_ID_ARI = 0x0E # macro +PCI_EXT_CAP_ID_ATS = 0x0F # macro +PCI_EXT_CAP_ID_SRIOV = 0x10 # macro +PCI_EXT_CAP_ID_MRIOV = 0x11 # macro +PCI_EXT_CAP_ID_MCAST = 0x12 # macro +PCI_EXT_CAP_ID_PRI = 0x13 # macro +PCI_EXT_CAP_ID_AMD_XXX = 0x14 # macro +PCI_EXT_CAP_ID_REBAR = 0x15 # macro +PCI_EXT_CAP_ID_DPA = 0x16 # macro +PCI_EXT_CAP_ID_TPH = 0x17 # macro +PCI_EXT_CAP_ID_LTR = 0x18 # macro +PCI_EXT_CAP_ID_SECPCI = 0x19 # macro +PCI_EXT_CAP_ID_PMUX = 0x1A # macro +PCI_EXT_CAP_ID_PASID = 0x1B # macro +PCI_EXT_CAP_ID_DPC = 0x1D # macro +PCI_EXT_CAP_ID_L1SS = 0x1E # macro +PCI_EXT_CAP_ID_PTM = 0x1F # macro +PCI_EXT_CAP_ID_DVSEC = 0x23 # macro +PCI_EXT_CAP_ID_DLF = 0x25 # macro +PCI_EXT_CAP_ID_PL_16GT = 0x26 # macro +PCI_EXT_CAP_ID_MAX = 0x26 # macro +PCI_EXT_CAP_DSN_SIZEOF = 12 # macro +PCI_EXT_CAP_MCAST_ENDPOINT_SIZEOF = 40 # macro +PCI_ERR_UNCOR_STATUS = 4 # macro +PCI_ERR_UNC_UND = 0x00000001 # macro +PCI_ERR_UNC_DLP = 0x00000010 # macro +PCI_ERR_UNC_SURPDN = 0x00000020 # macro +PCI_ERR_UNC_POISON_TLP = 0x00001000 # macro +PCI_ERR_UNC_FCP = 0x00002000 # macro +PCI_ERR_UNC_COMP_TIME = 0x00004000 # macro +PCI_ERR_UNC_COMP_ABORT = 0x00008000 # macro +PCI_ERR_UNC_UNX_COMP = 0x00010000 # macro +PCI_ERR_UNC_RX_OVER = 0x00020000 # macro +PCI_ERR_UNC_MALF_TLP = 0x00040000 # macro +PCI_ERR_UNC_ECRC = 0x00080000 # macro +PCI_ERR_UNC_UNSUP = 0x00100000 # macro +PCI_ERR_UNC_ACSV = 0x00200000 # macro +PCI_ERR_UNC_INTN = 0x00400000 # macro +PCI_ERR_UNC_MCBTLP = 0x00800000 # macro +PCI_ERR_UNC_ATOMEG = 0x01000000 # macro +PCI_ERR_UNC_TLPPRE = 0x02000000 # macro +PCI_ERR_UNCOR_MASK = 8 # macro +PCI_ERR_UNCOR_SEVER = 12 # macro +PCI_ERR_COR_STATUS = 16 # macro +PCI_ERR_COR_RCVR = 0x00000001 # macro +PCI_ERR_COR_BAD_TLP = 0x00000040 # macro +PCI_ERR_COR_BAD_DLLP = 0x00000080 # macro +PCI_ERR_COR_REP_ROLL = 0x00000100 # macro +PCI_ERR_COR_REP_TIMER = 0x00001000 # macro +PCI_ERR_COR_ADV_NFAT = 0x00002000 # macro +PCI_ERR_COR_INTERNAL = 0x00004000 # macro +PCI_ERR_COR_LOG_OVER = 0x00008000 # macro +PCI_ERR_COR_MASK = 20 # macro +PCI_ERR_CAP = 24 # macro +def PCI_ERR_CAP_FEP(x): # macro + return ((x)&31) +PCI_ERR_CAP_ECRC_GENC = 0x00000020 # macro +PCI_ERR_CAP_ECRC_GENE = 0x00000040 # macro +PCI_ERR_CAP_ECRC_CHKC = 0x00000080 # macro +PCI_ERR_CAP_ECRC_CHKE = 0x00000100 # macro +PCI_ERR_HEADER_LOG = 28 # macro +PCI_ERR_ROOT_COMMAND = 44 # macro +PCI_ERR_ROOT_CMD_COR_EN = 0x00000001 # macro +PCI_ERR_ROOT_CMD_NONFATAL_EN = 0x00000002 # macro +PCI_ERR_ROOT_CMD_FATAL_EN = 0x00000004 # macro +PCI_ERR_ROOT_STATUS = 48 # macro +PCI_ERR_ROOT_COR_RCV = 0x00000001 # macro +PCI_ERR_ROOT_MULTI_COR_RCV = 0x00000002 # macro +PCI_ERR_ROOT_UNCOR_RCV = 0x00000004 # macro +PCI_ERR_ROOT_MULTI_UNCOR_RCV = 0x00000008 # macro +PCI_ERR_ROOT_FIRST_FATAL = 0x00000010 # macro +PCI_ERR_ROOT_NONFATAL_RCV = 0x00000020 # macro +PCI_ERR_ROOT_FATAL_RCV = 0x00000040 # macro +PCI_ERR_ROOT_AER_IRQ = 0xf8000000 # macro +PCI_ERR_ROOT_ERR_SRC = 52 # macro +PCI_VC_PORT_CAP1 = 4 # macro +PCI_VC_CAP1_EVCC = 0x00000007 # macro +PCI_VC_CAP1_LPEVCC = 0x00000070 # macro +PCI_VC_CAP1_ARB_SIZE = 0x00000c00 # macro +PCI_VC_PORT_CAP2 = 8 # macro +PCI_VC_CAP2_32_PHASE = 0x00000002 # macro +PCI_VC_CAP2_64_PHASE = 0x00000004 # macro +PCI_VC_CAP2_128_PHASE = 0x00000008 # macro +PCI_VC_CAP2_ARB_OFF = 0xff000000 # macro +PCI_VC_PORT_CTRL = 12 # macro +PCI_VC_PORT_CTRL_LOAD_TABLE = 0x00000001 # macro +PCI_VC_PORT_STATUS = 14 # macro +PCI_VC_PORT_STATUS_TABLE = 0x00000001 # macro +PCI_VC_RES_CAP = 16 # macro +PCI_VC_RES_CAP_32_PHASE = 0x00000002 # macro +PCI_VC_RES_CAP_64_PHASE = 0x00000004 # macro +PCI_VC_RES_CAP_128_PHASE = 0x00000008 # macro +PCI_VC_RES_CAP_128_PHASE_TB = 0x00000010 # macro +PCI_VC_RES_CAP_256_PHASE = 0x00000020 # macro +PCI_VC_RES_CAP_ARB_OFF = 0xff000000 # macro +PCI_VC_RES_CTRL = 20 # macro +PCI_VC_RES_CTRL_LOAD_TABLE = 0x00010000 # macro +PCI_VC_RES_CTRL_ARB_SELECT = 0x000e0000 # macro +PCI_VC_RES_CTRL_ID = 0x07000000 # macro +PCI_VC_RES_CTRL_ENABLE = 0x80000000 # macro +PCI_VC_RES_STATUS = 26 # macro +PCI_VC_RES_STATUS_TABLE = 0x00000001 # macro +PCI_VC_RES_STATUS_NEGO = 0x00000002 # macro +PCI_CAP_VC_BASE_SIZEOF = 0x10 # macro +PCI_CAP_VC_PER_VC_SIZEOF = 0x0C # macro +PCI_PWR_DSR = 4 # macro +PCI_PWR_DATA = 8 # macro +def PCI_PWR_DATA_BASE(x): # macro + return ((x)&0xff) +def PCI_PWR_DATA_SCALE(x): # macro + return (((x)>>8)&3) +def PCI_PWR_DATA_PM_SUB(x): # macro + return (((x)>>10)&7) +def PCI_PWR_DATA_PM_STATE(x): # macro + return (((x)>>13)&3) +def PCI_PWR_DATA_TYPE(x): # macro + return (((x)>>15)&7) +def PCI_PWR_DATA_RAIL(x): # macro + return (((x)>>18)&7) +PCI_PWR_CAP = 12 # macro +def PCI_PWR_CAP_BUDGET(x): # macro + return ((x)&1) +PCI_EXT_CAP_PWR_SIZEOF = 16 # macro +PCI_RCEC_RCIEP_BITMAP = 4 # macro +PCI_RCEC_BUSN = 8 # macro +PCI_RCEC_BUSN_REG_VER = 0x02 # macro +def PCI_RCEC_BUSN_NEXT(x): # macro + return (((x)>>8)&0xff) +def PCI_RCEC_BUSN_LAST(x): # macro + return (((x)>>16)&0xff) +PCI_VNDR_HEADER = 4 # macro +def PCI_VNDR_HEADER_ID(x): # macro + return ((x)&0xffff) +def PCI_VNDR_HEADER_REV(x): # macro + return (((x)>>16)&0xf) +def PCI_VNDR_HEADER_LEN(x): # macro + return (((x)>>20)&0xfff) +HT_3BIT_CAP_MASK = 0xE0 # macro +HT_CAPTYPE_SLAVE = 0x00 # macro +HT_CAPTYPE_HOST = 0x20 # macro +HT_5BIT_CAP_MASK = 0xF8 # macro +HT_CAPTYPE_IRQ = 0x80 # macro +HT_CAPTYPE_REMAPPING_40 = 0xA0 # macro +HT_CAPTYPE_REMAPPING_64 = 0xA2 # macro +HT_CAPTYPE_UNITID_CLUMP = 0x90 # macro +HT_CAPTYPE_EXTCONF = 0x98 # macro +HT_CAPTYPE_MSI_MAPPING = 0xA8 # macro +HT_MSI_FLAGS = 0x02 # macro +HT_MSI_FLAGS_ENABLE = 0x1 # macro +HT_MSI_FLAGS_FIXED = 0x2 # macro +HT_MSI_FIXED_ADDR = 0x00000000FEE00000 # macro +HT_MSI_ADDR_LO = 0x04 # macro +HT_MSI_ADDR_LO_MASK = 0xFFF00000 # macro +HT_MSI_ADDR_HI = 0x08 # macro +HT_CAPTYPE_DIRECT_ROUTE = 0xB0 # macro +HT_CAPTYPE_VCSET = 0xB8 # macro +HT_CAPTYPE_ERROR_RETRY = 0xC0 # macro +HT_CAPTYPE_GEN3 = 0xD0 # macro +HT_CAPTYPE_PM = 0xE0 # macro +HT_CAP_SIZEOF_LONG = 28 # macro +HT_CAP_SIZEOF_SHORT = 24 # macro +PCI_ARI_CAP = 0x04 # macro +PCI_ARI_CAP_MFVC = 0x0001 # macro +PCI_ARI_CAP_ACS = 0x0002 # macro +def PCI_ARI_CAP_NFN(x): # macro + return (((x)>>8)&0xff) +PCI_ARI_CTRL = 0x06 # macro +PCI_ARI_CTRL_MFVC = 0x0001 # macro +PCI_ARI_CTRL_ACS = 0x0002 # macro +def PCI_ARI_CTRL_FG(x): # macro + return (((x)>>4)&7) +PCI_EXT_CAP_ARI_SIZEOF = 8 # macro +PCI_ATS_CAP = 0x04 # macro +def PCI_ATS_CAP_QDEP(x): # macro + return ((x)&0x1f) +PCI_ATS_MAX_QDEP = 32 # macro +PCI_ATS_CAP_PAGE_ALIGNED = 0x0020 # macro +PCI_ATS_CTRL = 0x06 # macro +PCI_ATS_CTRL_ENABLE = 0x8000 # macro +def PCI_ATS_CTRL_STU(x): # macro + return ((x)&0x1f) +PCI_ATS_MIN_STU = 12 # macro +PCI_EXT_CAP_ATS_SIZEOF = 8 # macro +PCI_PRI_CTRL = 0x04 # macro +PCI_PRI_CTRL_ENABLE = 0x0001 # macro +PCI_PRI_CTRL_RESET = 0x0002 # macro +PCI_PRI_STATUS = 0x06 # macro +PCI_PRI_STATUS_RF = 0x0001 # macro +PCI_PRI_STATUS_UPRGI = 0x0002 # macro +PCI_PRI_STATUS_STOPPED = 0x0100 # macro +PCI_PRI_STATUS_PASID = 0x8000 # macro +PCI_PRI_MAX_REQ = 0x08 # macro +PCI_PRI_ALLOC_REQ = 0x0c # macro +PCI_EXT_CAP_PRI_SIZEOF = 16 # macro +PCI_PASID_CAP = 0x04 # macro +PCI_PASID_CAP_EXEC = 0x02 # macro +PCI_PASID_CAP_PRIV = 0x04 # macro +PCI_PASID_CTRL = 0x06 # macro +PCI_PASID_CTRL_ENABLE = 0x01 # macro +PCI_PASID_CTRL_EXEC = 0x02 # macro +PCI_PASID_CTRL_PRIV = 0x04 # macro +PCI_EXT_CAP_PASID_SIZEOF = 8 # macro +PCI_SRIOV_CAP = 0x04 # macro +PCI_SRIOV_CAP_VFM = 0x00000001 # macro +def PCI_SRIOV_CAP_INTR(x): # macro + return ((x)>>21) +PCI_SRIOV_CTRL = 0x08 # macro +PCI_SRIOV_CTRL_VFE = 0x0001 # macro +PCI_SRIOV_CTRL_VFM = 0x0002 # macro +PCI_SRIOV_CTRL_INTR = 0x0004 # macro +PCI_SRIOV_CTRL_MSE = 0x0008 # macro +PCI_SRIOV_CTRL_ARI = 0x0010 # macro +PCI_SRIOV_STATUS = 0x0a # macro +PCI_SRIOV_STATUS_VFM = 0x0001 # macro +PCI_SRIOV_INITIAL_VF = 0x0c # macro +PCI_SRIOV_TOTAL_VF = 0x0e # macro +PCI_SRIOV_NUM_VF = 0x10 # macro +PCI_SRIOV_FUNC_LINK = 0x12 # macro +PCI_SRIOV_VF_OFFSET = 0x14 # macro +PCI_SRIOV_VF_STRIDE = 0x16 # macro +PCI_SRIOV_VF_DID = 0x1a # macro +PCI_SRIOV_SUP_PGSIZE = 0x1c # macro +PCI_SRIOV_SYS_PGSIZE = 0x20 # macro +PCI_SRIOV_BAR = 0x24 # macro +PCI_SRIOV_NUM_BARS = 6 # macro +PCI_SRIOV_VFM = 0x3c # macro +def PCI_SRIOV_VFM_BIR(x): # macro + return ((x)&7) +def PCI_SRIOV_VFM_OFFSET(x): # macro + return ((x)&~7) +PCI_SRIOV_VFM_UA = 0x0 # macro +PCI_SRIOV_VFM_MI = 0x1 # macro +PCI_SRIOV_VFM_MO = 0x2 # macro +PCI_SRIOV_VFM_AV = 0x3 # macro +PCI_EXT_CAP_SRIOV_SIZEOF = 64 # macro +PCI_LTR_MAX_SNOOP_LAT = 0x4 # macro +PCI_LTR_MAX_NOSNOOP_LAT = 0x6 # macro +PCI_LTR_VALUE_MASK = 0x000003ff # macro +PCI_LTR_SCALE_MASK = 0x00001c00 # macro +PCI_LTR_SCALE_SHIFT = 10 # macro +PCI_EXT_CAP_LTR_SIZEOF = 8 # macro +PCI_ACS_CAP = 0x04 # macro +PCI_ACS_SV = 0x0001 # macro +PCI_ACS_TB = 0x0002 # macro +PCI_ACS_RR = 0x0004 # macro +PCI_ACS_CR = 0x0008 # macro +PCI_ACS_UF = 0x0010 # macro +PCI_ACS_EC = 0x0020 # macro +PCI_ACS_DT = 0x0040 # macro +PCI_ACS_EGRESS_BITS = 0x05 # macro +PCI_ACS_CTRL = 0x06 # macro +PCI_ACS_EGRESS_CTL_V = 0x08 # macro +PCI_VSEC_HDR = 4 # macro +PCI_VSEC_HDR_LEN_SHIFT = 20 # macro +PCI_SATA_REGS = 4 # macro +PCI_SATA_REGS_MASK = 0xF # macro +PCI_SATA_REGS_INLINE = 0xF # macro +PCI_SATA_SIZEOF_SHORT = 8 # macro +PCI_SATA_SIZEOF_LONG = 16 # macro +PCI_REBAR_CAP = 4 # macro +PCI_REBAR_CAP_SIZES = 0x00FFFFF0 # macro +PCI_REBAR_CTRL = 8 # macro +PCI_REBAR_CTRL_BAR_IDX = 0x00000007 # macro +PCI_REBAR_CTRL_NBAR_MASK = 0x000000E0 # macro +PCI_REBAR_CTRL_NBAR_SHIFT = 5 # macro +PCI_REBAR_CTRL_BAR_SIZE = 0x00001F00 # macro +PCI_REBAR_CTRL_BAR_SHIFT = 8 # macro +PCI_DPA_CAP = 4 # macro +PCI_DPA_CAP_SUBSTATE_MASK = 0x1F # macro +PCI_DPA_BASE_SIZEOF = 16 # macro +PCI_TPH_CAP = 4 # macro +PCI_TPH_CAP_LOC_MASK = 0x600 # macro +PCI_TPH_LOC_NONE = 0x000 # macro +PCI_TPH_LOC_CAP = 0x200 # macro +PCI_TPH_LOC_MSIX = 0x400 # macro +PCI_TPH_CAP_ST_MASK = 0x07FF0000 # macro +PCI_TPH_CAP_ST_SHIFT = 16 # macro +PCI_TPH_BASE_SIZEOF = 12 # macro +PCI_EXP_DPC_CAP = 4 # macro +PCI_EXP_DPC_IRQ = 0x001F # macro +PCI_EXP_DPC_CAP_RP_EXT = 0x0020 # macro +PCI_EXP_DPC_CAP_POISONED_TLP = 0x0040 # macro +PCI_EXP_DPC_CAP_SW_TRIGGER = 0x0080 # macro +PCI_EXP_DPC_RP_PIO_LOG_SIZE = 0x0F00 # macro +PCI_EXP_DPC_CAP_DL_ACTIVE = 0x1000 # macro +PCI_EXP_DPC_CTL = 6 # macro +PCI_EXP_DPC_CTL_EN_FATAL = 0x0001 # macro +PCI_EXP_DPC_CTL_EN_NONFATAL = 0x0002 # macro +PCI_EXP_DPC_CTL_INT_EN = 0x0008 # macro +PCI_EXP_DPC_STATUS = 8 # macro +PCI_EXP_DPC_STATUS_TRIGGER = 0x0001 # macro +PCI_EXP_DPC_STATUS_TRIGGER_RSN = 0x0006 # macro +PCI_EXP_DPC_STATUS_INTERRUPT = 0x0008 # macro +PCI_EXP_DPC_RP_BUSY = 0x0010 # macro +PCI_EXP_DPC_STATUS_TRIGGER_RSN_EXT = 0x0060 # macro +PCI_EXP_DPC_SOURCE_ID = 10 # macro +PCI_EXP_DPC_RP_PIO_STATUS = 0x0C # macro +PCI_EXP_DPC_RP_PIO_MASK = 0x10 # macro +PCI_EXP_DPC_RP_PIO_SEVERITY = 0x14 # macro +PCI_EXP_DPC_RP_PIO_SYSERROR = 0x18 # macro +PCI_EXP_DPC_RP_PIO_EXCEPTION = 0x1C # macro +PCI_EXP_DPC_RP_PIO_HEADER_LOG = 0x20 # macro +PCI_EXP_DPC_RP_PIO_IMPSPEC_LOG = 0x30 # macro +PCI_EXP_DPC_RP_PIO_TLPPREFIX_LOG = 0x34 # macro +PCI_PTM_CAP = 0x04 # macro +PCI_PTM_CAP_REQ = 0x00000001 # macro +PCI_PTM_CAP_ROOT = 0x00000004 # macro +PCI_PTM_GRANULARITY_MASK = 0x0000FF00 # macro +PCI_PTM_CTRL = 0x08 # macro +PCI_PTM_CTRL_ENABLE = 0x00000001 # macro +PCI_PTM_CTRL_ROOT = 0x00000002 # macro +PCI_L1SS_CAP = 0x04 # macro +PCI_L1SS_CAP_PCIPM_L1_2 = 0x00000001 # macro +PCI_L1SS_CAP_PCIPM_L1_1 = 0x00000002 # macro +PCI_L1SS_CAP_ASPM_L1_2 = 0x00000004 # macro +PCI_L1SS_CAP_ASPM_L1_1 = 0x00000008 # macro +PCI_L1SS_CAP_L1_PM_SS = 0x00000010 # macro +PCI_L1SS_CAP_CM_RESTORE_TIME = 0x0000ff00 # macro +PCI_L1SS_CAP_P_PWR_ON_SCALE = 0x00030000 # macro +PCI_L1SS_CAP_P_PWR_ON_VALUE = 0x00f80000 # macro +PCI_L1SS_CTL1 = 0x08 # macro +PCI_L1SS_CTL1_PCIPM_L1_2 = 0x00000001 # macro +PCI_L1SS_CTL1_PCIPM_L1_1 = 0x00000002 # macro +PCI_L1SS_CTL1_ASPM_L1_2 = 0x00000004 # macro +PCI_L1SS_CTL1_ASPM_L1_1 = 0x00000008 # macro +PCI_L1SS_CTL1_L1_2_MASK = 0x00000005 # macro +PCI_L1SS_CTL1_L1SS_MASK = 0x0000000f # macro +PCI_L1SS_CTL1_CM_RESTORE_TIME = 0x0000ff00 # macro +PCI_L1SS_CTL1_LTR_L12_TH_VALUE = 0x03ff0000 # macro +PCI_L1SS_CTL1_LTR_L12_TH_SCALE = 0xe0000000 # macro +PCI_L1SS_CTL2 = 0x0c # macro +PCI_DVSEC_HEADER1 = 0x4 # macro +PCI_DVSEC_HEADER2 = 0x8 # macro +PCI_DLF_CAP = 0x04 # macro +PCI_DLF_EXCHANGE_ENABLE = 0x80000000 # macro +PCI_PL_16GT_LE_CTRL = 0x20 # macro +PCI_PL_16GT_LE_CTRL_DSP_TX_PRESET_MASK = 0x0000000F # macro +PCI_PL_16GT_LE_CTRL_USP_TX_PRESET_MASK = 0x000000F0 # macro +PCI_PL_16GT_LE_CTRL_USP_TX_PRESET_SHIFT = 4 # macro +__all__ = \ + ['HT_3BIT_CAP_MASK', 'HT_5BIT_CAP_MASK', + 'HT_CAPTYPE_DIRECT_ROUTE', 'HT_CAPTYPE_ERROR_RETRY', + 'HT_CAPTYPE_EXTCONF', 'HT_CAPTYPE_GEN3', 'HT_CAPTYPE_HOST', + 'HT_CAPTYPE_IRQ', 'HT_CAPTYPE_MSI_MAPPING', 'HT_CAPTYPE_PM', + 'HT_CAPTYPE_REMAPPING_40', 'HT_CAPTYPE_REMAPPING_64', + 'HT_CAPTYPE_SLAVE', 'HT_CAPTYPE_UNITID_CLUMP', 'HT_CAPTYPE_VCSET', + 'HT_CAP_SIZEOF_LONG', 'HT_CAP_SIZEOF_SHORT', 'HT_MSI_ADDR_HI', + 'HT_MSI_ADDR_LO', 'HT_MSI_ADDR_LO_MASK', 'HT_MSI_FIXED_ADDR', + 'HT_MSI_FLAGS', 'HT_MSI_FLAGS_ENABLE', 'HT_MSI_FLAGS_FIXED', + 'LINUX_PCI_REGS_H', 'PCI_ACS_CAP', 'PCI_ACS_CR', 'PCI_ACS_CTRL', + 'PCI_ACS_DT', 'PCI_ACS_EC', 'PCI_ACS_EGRESS_BITS', + 'PCI_ACS_EGRESS_CTL_V', 'PCI_ACS_RR', 'PCI_ACS_SV', 'PCI_ACS_TB', + 'PCI_ACS_UF', 'PCI_AF_CAP', 'PCI_AF_CAP_FLR', 'PCI_AF_CAP_TP', + 'PCI_AF_CTRL', 'PCI_AF_CTRL_FLR', 'PCI_AF_LENGTH', + 'PCI_AF_STATUS', 'PCI_AF_STATUS_TP', 'PCI_AGP_COMMAND', + 'PCI_AGP_COMMAND_64BIT', 'PCI_AGP_COMMAND_AGP', + 'PCI_AGP_COMMAND_FW', 'PCI_AGP_COMMAND_RATE1', + 'PCI_AGP_COMMAND_RATE2', 'PCI_AGP_COMMAND_RATE4', + 'PCI_AGP_COMMAND_RQ_MASK', 'PCI_AGP_COMMAND_SBA', 'PCI_AGP_RFU', + 'PCI_AGP_SIZEOF', 'PCI_AGP_STATUS', 'PCI_AGP_STATUS_64BIT', + 'PCI_AGP_STATUS_FW', 'PCI_AGP_STATUS_RATE1', + 'PCI_AGP_STATUS_RATE2', 'PCI_AGP_STATUS_RATE4', + 'PCI_AGP_STATUS_RQ_MASK', 'PCI_AGP_STATUS_SBA', 'PCI_AGP_VERSION', + 'PCI_ARI_CAP', 'PCI_ARI_CAP_ACS', 'PCI_ARI_CAP_MFVC', + 'PCI_ARI_CTRL', 'PCI_ARI_CTRL_ACS', 'PCI_ARI_CTRL_MFVC', + 'PCI_ATS_CAP', 'PCI_ATS_CAP_PAGE_ALIGNED', 'PCI_ATS_CTRL', + 'PCI_ATS_CTRL_ENABLE', 'PCI_ATS_MAX_QDEP', 'PCI_ATS_MIN_STU', + 'PCI_BASE_ADDRESS_0', 'PCI_BASE_ADDRESS_1', 'PCI_BASE_ADDRESS_2', + 'PCI_BASE_ADDRESS_3', 'PCI_BASE_ADDRESS_4', 'PCI_BASE_ADDRESS_5', + 'PCI_BASE_ADDRESS_IO_MASK', 'PCI_BASE_ADDRESS_MEM_MASK', + 'PCI_BASE_ADDRESS_MEM_PREFETCH', 'PCI_BASE_ADDRESS_MEM_TYPE_1M', + 'PCI_BASE_ADDRESS_MEM_TYPE_32', 'PCI_BASE_ADDRESS_MEM_TYPE_64', + 'PCI_BASE_ADDRESS_MEM_TYPE_MASK', 'PCI_BASE_ADDRESS_SPACE', + 'PCI_BASE_ADDRESS_SPACE_IO', 'PCI_BASE_ADDRESS_SPACE_MEMORY', + 'PCI_BIST', 'PCI_BIST_CAPABLE', 'PCI_BIST_CODE_MASK', + 'PCI_BIST_START', 'PCI_BRIDGE_CONTROL', + 'PCI_BRIDGE_CTL_BUS_RESET', 'PCI_BRIDGE_CTL_FAST_BACK', + 'PCI_BRIDGE_CTL_ISA', 'PCI_BRIDGE_CTL_MASTER_ABORT', + 'PCI_BRIDGE_CTL_PARITY', 'PCI_BRIDGE_CTL_SERR', + 'PCI_BRIDGE_CTL_VGA', 'PCI_CACHE_LINE_SIZE', + 'PCI_CAPABILITY_LIST', 'PCI_CAP_AF_SIZEOF', + 'PCI_CAP_EXP_ENDPOINT_SIZEOF_V1', + 'PCI_CAP_EXP_ENDPOINT_SIZEOF_V2', + 'PCI_CAP_EXP_RC_ENDPOINT_SIZEOF_V1', + 'PCI_CAP_EXP_RC_ENDPOINT_SIZEOF_V2', 'PCI_CAP_FLAGS', + 'PCI_CAP_ID_AF', 'PCI_CAP_ID_AGP', 'PCI_CAP_ID_AGP3', + 'PCI_CAP_ID_CCRC', 'PCI_CAP_ID_CHSWP', 'PCI_CAP_ID_DBG', + 'PCI_CAP_ID_EA', 'PCI_CAP_ID_EXP', 'PCI_CAP_ID_HT', + 'PCI_CAP_ID_MAX', 'PCI_CAP_ID_MSI', 'PCI_CAP_ID_MSIX', + 'PCI_CAP_ID_PCIX', 'PCI_CAP_ID_PM', 'PCI_CAP_ID_SATA', + 'PCI_CAP_ID_SECDEV', 'PCI_CAP_ID_SHPC', 'PCI_CAP_ID_SLOTID', + 'PCI_CAP_ID_SSVID', 'PCI_CAP_ID_VNDR', 'PCI_CAP_ID_VPD', + 'PCI_CAP_LIST_ID', 'PCI_CAP_LIST_NEXT', 'PCI_CAP_MSIX_SIZEOF', + 'PCI_CAP_PCIX_SIZEOF_V0', 'PCI_CAP_PCIX_SIZEOF_V1', + 'PCI_CAP_PCIX_SIZEOF_V2', 'PCI_CAP_SIZEOF', + 'PCI_CAP_VC_BASE_SIZEOF', 'PCI_CAP_VC_PER_VC_SIZEOF', + 'PCI_CAP_VPD_SIZEOF', 'PCI_CARDBUS_CIS', 'PCI_CB_BRIDGE_CONTROL', + 'PCI_CB_BRIDGE_CTL_16BIT_INT', 'PCI_CB_BRIDGE_CTL_CB_RESET', + 'PCI_CB_BRIDGE_CTL_ISA', 'PCI_CB_BRIDGE_CTL_MASTER_ABORT', + 'PCI_CB_BRIDGE_CTL_PARITY', 'PCI_CB_BRIDGE_CTL_POST_WRITES', + 'PCI_CB_BRIDGE_CTL_PREFETCH_MEM0', + 'PCI_CB_BRIDGE_CTL_PREFETCH_MEM1', 'PCI_CB_BRIDGE_CTL_SERR', + 'PCI_CB_BRIDGE_CTL_VGA', 'PCI_CB_CAPABILITY_LIST', + 'PCI_CB_CARD_BUS', 'PCI_CB_IO_BASE_0', 'PCI_CB_IO_BASE_0_HI', + 'PCI_CB_IO_BASE_1', 'PCI_CB_IO_BASE_1_HI', 'PCI_CB_IO_LIMIT_0', + 'PCI_CB_IO_LIMIT_0_HI', 'PCI_CB_IO_LIMIT_1', + 'PCI_CB_IO_LIMIT_1_HI', 'PCI_CB_IO_RANGE_MASK', + 'PCI_CB_LATENCY_TIMER', 'PCI_CB_LEGACY_MODE_BASE', + 'PCI_CB_MEMORY_BASE_0', 'PCI_CB_MEMORY_BASE_1', + 'PCI_CB_MEMORY_LIMIT_0', 'PCI_CB_MEMORY_LIMIT_1', + 'PCI_CB_PRIMARY_BUS', 'PCI_CB_SEC_STATUS', + 'PCI_CB_SUBORDINATE_BUS', 'PCI_CB_SUBSYSTEM_ID', + 'PCI_CB_SUBSYSTEM_VENDOR_ID', 'PCI_CFG_SPACE_EXP_SIZE', + 'PCI_CFG_SPACE_SIZE', 'PCI_CHSWP_CSR', 'PCI_CHSWP_DHA', + 'PCI_CHSWP_EIM', 'PCI_CHSWP_EXT', 'PCI_CHSWP_INS', + 'PCI_CHSWP_LOO', 'PCI_CHSWP_PI', 'PCI_CHSWP_PIE', + 'PCI_CLASS_DEVICE', 'PCI_CLASS_PROG', 'PCI_CLASS_REVISION', + 'PCI_COMMAND', 'PCI_COMMAND_FAST_BACK', + 'PCI_COMMAND_INTX_DISABLE', 'PCI_COMMAND_INVALIDATE', + 'PCI_COMMAND_IO', 'PCI_COMMAND_MASTER', 'PCI_COMMAND_MEMORY', + 'PCI_COMMAND_PARITY', 'PCI_COMMAND_SERR', 'PCI_COMMAND_SPECIAL', + 'PCI_COMMAND_VGA_PALETTE', 'PCI_COMMAND_WAIT', 'PCI_DEVICE_ID', + 'PCI_DLF_CAP', 'PCI_DLF_EXCHANGE_ENABLE', 'PCI_DPA_BASE_SIZEOF', + 'PCI_DPA_CAP', 'PCI_DPA_CAP_SUBSTATE_MASK', 'PCI_DVSEC_HEADER1', + 'PCI_DVSEC_HEADER2', 'PCI_EA_BASE', 'PCI_EA_BEI', + 'PCI_EA_BEI_BAR0', 'PCI_EA_BEI_BAR5', 'PCI_EA_BEI_BRIDGE', + 'PCI_EA_BEI_ENI', 'PCI_EA_BEI_RESERVED', 'PCI_EA_BEI_ROM', + 'PCI_EA_BEI_VF_BAR0', 'PCI_EA_BEI_VF_BAR5', 'PCI_EA_ENABLE', + 'PCI_EA_ES', 'PCI_EA_FIELD_MASK', 'PCI_EA_FIRST_ENT', + 'PCI_EA_FIRST_ENT_BRIDGE', 'PCI_EA_IS_64', 'PCI_EA_MAX_OFFSET', + 'PCI_EA_NUM_ENT', 'PCI_EA_NUM_ENT_MASK', 'PCI_EA_PP', + 'PCI_EA_P_BRIDGE_IO', 'PCI_EA_P_BRIDGE_MEM', + 'PCI_EA_P_BRIDGE_MEM_PREFETCH', 'PCI_EA_P_IO', + 'PCI_EA_P_IO_RESERVED', 'PCI_EA_P_MEM', 'PCI_EA_P_MEM_PREFETCH', + 'PCI_EA_P_MEM_RESERVED', 'PCI_EA_P_UNAVAILABLE', + 'PCI_EA_P_VF_MEM', 'PCI_EA_P_VF_MEM_PREFETCH', + 'PCI_EA_SEC_BUS_MASK', 'PCI_EA_SP', 'PCI_EA_SUB_BUS_MASK', + 'PCI_EA_SUB_BUS_SHIFT', 'PCI_EA_WRITABLE', 'PCI_ERR_CAP', + 'PCI_ERR_CAP_ECRC_CHKC', 'PCI_ERR_CAP_ECRC_CHKE', + 'PCI_ERR_CAP_ECRC_GENC', 'PCI_ERR_CAP_ECRC_GENE', + 'PCI_ERR_COR_ADV_NFAT', 'PCI_ERR_COR_BAD_DLLP', + 'PCI_ERR_COR_BAD_TLP', 'PCI_ERR_COR_INTERNAL', + 'PCI_ERR_COR_LOG_OVER', 'PCI_ERR_COR_MASK', 'PCI_ERR_COR_RCVR', + 'PCI_ERR_COR_REP_ROLL', 'PCI_ERR_COR_REP_TIMER', + 'PCI_ERR_COR_STATUS', 'PCI_ERR_HEADER_LOG', + 'PCI_ERR_ROOT_AER_IRQ', 'PCI_ERR_ROOT_CMD_COR_EN', + 'PCI_ERR_ROOT_CMD_FATAL_EN', 'PCI_ERR_ROOT_CMD_NONFATAL_EN', + 'PCI_ERR_ROOT_COMMAND', 'PCI_ERR_ROOT_COR_RCV', + 'PCI_ERR_ROOT_ERR_SRC', 'PCI_ERR_ROOT_FATAL_RCV', + 'PCI_ERR_ROOT_FIRST_FATAL', 'PCI_ERR_ROOT_MULTI_COR_RCV', + 'PCI_ERR_ROOT_MULTI_UNCOR_RCV', 'PCI_ERR_ROOT_NONFATAL_RCV', + 'PCI_ERR_ROOT_STATUS', 'PCI_ERR_ROOT_UNCOR_RCV', + 'PCI_ERR_UNCOR_MASK', 'PCI_ERR_UNCOR_SEVER', + 'PCI_ERR_UNCOR_STATUS', 'PCI_ERR_UNC_ACSV', 'PCI_ERR_UNC_ATOMEG', + 'PCI_ERR_UNC_COMP_ABORT', 'PCI_ERR_UNC_COMP_TIME', + 'PCI_ERR_UNC_DLP', 'PCI_ERR_UNC_ECRC', 'PCI_ERR_UNC_FCP', + 'PCI_ERR_UNC_INTN', 'PCI_ERR_UNC_MALF_TLP', 'PCI_ERR_UNC_MCBTLP', + 'PCI_ERR_UNC_POISON_TLP', 'PCI_ERR_UNC_RX_OVER', + 'PCI_ERR_UNC_SURPDN', 'PCI_ERR_UNC_TLPPRE', 'PCI_ERR_UNC_UND', + 'PCI_ERR_UNC_UNSUP', 'PCI_ERR_UNC_UNX_COMP', 'PCI_EXP_DEVCAP', + 'PCI_EXP_DEVCAP2', 'PCI_EXP_DEVCAP2_ARI', + 'PCI_EXP_DEVCAP2_ATOMIC_COMP128', 'PCI_EXP_DEVCAP2_ATOMIC_COMP32', + 'PCI_EXP_DEVCAP2_ATOMIC_COMP64', 'PCI_EXP_DEVCAP2_ATOMIC_ROUTE', + 'PCI_EXP_DEVCAP2_COMP_TMOUT_DIS', 'PCI_EXP_DEVCAP2_EE_PREFIX', + 'PCI_EXP_DEVCAP2_LTR', 'PCI_EXP_DEVCAP2_OBFF_MASK', + 'PCI_EXP_DEVCAP2_OBFF_MSG', 'PCI_EXP_DEVCAP2_OBFF_WAKE', + 'PCI_EXP_DEVCAP_ATN_BUT', 'PCI_EXP_DEVCAP_ATN_IND', + 'PCI_EXP_DEVCAP_EXT_TAG', 'PCI_EXP_DEVCAP_FLR', + 'PCI_EXP_DEVCAP_L0S', 'PCI_EXP_DEVCAP_L1', + 'PCI_EXP_DEVCAP_PAYLOAD', 'PCI_EXP_DEVCAP_PHANTOM', + 'PCI_EXP_DEVCAP_PWR_IND', 'PCI_EXP_DEVCAP_PWR_SCL', + 'PCI_EXP_DEVCAP_PWR_VAL', 'PCI_EXP_DEVCAP_RBER', 'PCI_EXP_DEVCTL', + 'PCI_EXP_DEVCTL2', 'PCI_EXP_DEVCTL2_ARI', + 'PCI_EXP_DEVCTL2_ATOMIC_EGRESS_BLOCK', + 'PCI_EXP_DEVCTL2_ATOMIC_REQ', 'PCI_EXP_DEVCTL2_COMP_TIMEOUT', + 'PCI_EXP_DEVCTL2_COMP_TMOUT_DIS', 'PCI_EXP_DEVCTL2_IDO_CMP_EN', + 'PCI_EXP_DEVCTL2_IDO_REQ_EN', 'PCI_EXP_DEVCTL2_LTR_EN', + 'PCI_EXP_DEVCTL2_OBFF_MSGA_EN', 'PCI_EXP_DEVCTL2_OBFF_MSGB_EN', + 'PCI_EXP_DEVCTL2_OBFF_WAKE_EN', 'PCI_EXP_DEVCTL_AUX_PME', + 'PCI_EXP_DEVCTL_BCR_FLR', 'PCI_EXP_DEVCTL_CERE', + 'PCI_EXP_DEVCTL_EXT_TAG', 'PCI_EXP_DEVCTL_FERE', + 'PCI_EXP_DEVCTL_NFERE', 'PCI_EXP_DEVCTL_NOSNOOP_EN', + 'PCI_EXP_DEVCTL_PAYLOAD', 'PCI_EXP_DEVCTL_PAYLOAD_1024B', + 'PCI_EXP_DEVCTL_PAYLOAD_128B', 'PCI_EXP_DEVCTL_PAYLOAD_2048B', + 'PCI_EXP_DEVCTL_PAYLOAD_256B', 'PCI_EXP_DEVCTL_PAYLOAD_4096B', + 'PCI_EXP_DEVCTL_PAYLOAD_512B', 'PCI_EXP_DEVCTL_PHANTOM', + 'PCI_EXP_DEVCTL_READRQ', 'PCI_EXP_DEVCTL_READRQ_1024B', + 'PCI_EXP_DEVCTL_READRQ_128B', 'PCI_EXP_DEVCTL_READRQ_2048B', + 'PCI_EXP_DEVCTL_READRQ_256B', 'PCI_EXP_DEVCTL_READRQ_4096B', + 'PCI_EXP_DEVCTL_READRQ_512B', 'PCI_EXP_DEVCTL_RELAX_EN', + 'PCI_EXP_DEVCTL_URRE', 'PCI_EXP_DEVSTA', 'PCI_EXP_DEVSTA2', + 'PCI_EXP_DEVSTA_AUXPD', 'PCI_EXP_DEVSTA_CED', + 'PCI_EXP_DEVSTA_FED', 'PCI_EXP_DEVSTA_NFED', + 'PCI_EXP_DEVSTA_TRPND', 'PCI_EXP_DEVSTA_URD', 'PCI_EXP_DPC_CAP', + 'PCI_EXP_DPC_CAP_DL_ACTIVE', 'PCI_EXP_DPC_CAP_POISONED_TLP', + 'PCI_EXP_DPC_CAP_RP_EXT', 'PCI_EXP_DPC_CAP_SW_TRIGGER', + 'PCI_EXP_DPC_CTL', 'PCI_EXP_DPC_CTL_EN_FATAL', + 'PCI_EXP_DPC_CTL_EN_NONFATAL', 'PCI_EXP_DPC_CTL_INT_EN', + 'PCI_EXP_DPC_IRQ', 'PCI_EXP_DPC_RP_BUSY', + 'PCI_EXP_DPC_RP_PIO_EXCEPTION', 'PCI_EXP_DPC_RP_PIO_HEADER_LOG', + 'PCI_EXP_DPC_RP_PIO_IMPSPEC_LOG', 'PCI_EXP_DPC_RP_PIO_LOG_SIZE', + 'PCI_EXP_DPC_RP_PIO_MASK', 'PCI_EXP_DPC_RP_PIO_SEVERITY', + 'PCI_EXP_DPC_RP_PIO_STATUS', 'PCI_EXP_DPC_RP_PIO_SYSERROR', + 'PCI_EXP_DPC_RP_PIO_TLPPREFIX_LOG', 'PCI_EXP_DPC_SOURCE_ID', + 'PCI_EXP_DPC_STATUS', 'PCI_EXP_DPC_STATUS_INTERRUPT', + 'PCI_EXP_DPC_STATUS_TRIGGER', 'PCI_EXP_DPC_STATUS_TRIGGER_RSN', + 'PCI_EXP_DPC_STATUS_TRIGGER_RSN_EXT', 'PCI_EXP_FLAGS', + 'PCI_EXP_FLAGS_IRQ', 'PCI_EXP_FLAGS_SLOT', 'PCI_EXP_FLAGS_TYPE', + 'PCI_EXP_FLAGS_VERS', 'PCI_EXP_LNKCAP', 'PCI_EXP_LNKCAP2', + 'PCI_EXP_LNKCAP2_CROSSLINK', 'PCI_EXP_LNKCAP2_SLS_16_0GB', + 'PCI_EXP_LNKCAP2_SLS_2_5GB', 'PCI_EXP_LNKCAP2_SLS_32_0GB', + 'PCI_EXP_LNKCAP2_SLS_5_0GB', 'PCI_EXP_LNKCAP2_SLS_64_0GB', + 'PCI_EXP_LNKCAP2_SLS_8_0GB', 'PCI_EXP_LNKCAP_ASPMS', + 'PCI_EXP_LNKCAP_ASPM_L0S', 'PCI_EXP_LNKCAP_ASPM_L1', + 'PCI_EXP_LNKCAP_CLKPM', 'PCI_EXP_LNKCAP_DLLLARC', + 'PCI_EXP_LNKCAP_L0SEL', 'PCI_EXP_LNKCAP_L1EL', + 'PCI_EXP_LNKCAP_LBNC', 'PCI_EXP_LNKCAP_MLW', 'PCI_EXP_LNKCAP_PN', + 'PCI_EXP_LNKCAP_SDERC', 'PCI_EXP_LNKCAP_SLS', + 'PCI_EXP_LNKCAP_SLS_16_0GB', 'PCI_EXP_LNKCAP_SLS_2_5GB', + 'PCI_EXP_LNKCAP_SLS_32_0GB', 'PCI_EXP_LNKCAP_SLS_5_0GB', + 'PCI_EXP_LNKCAP_SLS_64_0GB', 'PCI_EXP_LNKCAP_SLS_8_0GB', + 'PCI_EXP_LNKCTL', 'PCI_EXP_LNKCTL2', 'PCI_EXP_LNKCTL2_ENTER_COMP', + 'PCI_EXP_LNKCTL2_HASD', 'PCI_EXP_LNKCTL2_TLS', + 'PCI_EXP_LNKCTL2_TLS_16_0GT', 'PCI_EXP_LNKCTL2_TLS_2_5GT', + 'PCI_EXP_LNKCTL2_TLS_32_0GT', 'PCI_EXP_LNKCTL2_TLS_5_0GT', + 'PCI_EXP_LNKCTL2_TLS_64_0GT', 'PCI_EXP_LNKCTL2_TLS_8_0GT', + 'PCI_EXP_LNKCTL2_TX_MARGIN', 'PCI_EXP_LNKCTL_ASPMC', + 'PCI_EXP_LNKCTL_ASPM_L0S', 'PCI_EXP_LNKCTL_ASPM_L1', + 'PCI_EXP_LNKCTL_CCC', 'PCI_EXP_LNKCTL_CLKREQ_EN', + 'PCI_EXP_LNKCTL_ES', 'PCI_EXP_LNKCTL_HAWD', + 'PCI_EXP_LNKCTL_LABIE', 'PCI_EXP_LNKCTL_LBMIE', + 'PCI_EXP_LNKCTL_LD', 'PCI_EXP_LNKCTL_RCB', 'PCI_EXP_LNKCTL_RL', + 'PCI_EXP_LNKSTA', 'PCI_EXP_LNKSTA2', 'PCI_EXP_LNKSTA_CLS', + 'PCI_EXP_LNKSTA_CLS_16_0GB', 'PCI_EXP_LNKSTA_CLS_2_5GB', + 'PCI_EXP_LNKSTA_CLS_32_0GB', 'PCI_EXP_LNKSTA_CLS_5_0GB', + 'PCI_EXP_LNKSTA_CLS_64_0GB', 'PCI_EXP_LNKSTA_CLS_8_0GB', + 'PCI_EXP_LNKSTA_DLLLA', 'PCI_EXP_LNKSTA_LABS', + 'PCI_EXP_LNKSTA_LBMS', 'PCI_EXP_LNKSTA_LT', 'PCI_EXP_LNKSTA_NLW', + 'PCI_EXP_LNKSTA_NLW_SHIFT', 'PCI_EXP_LNKSTA_NLW_X1', + 'PCI_EXP_LNKSTA_NLW_X2', 'PCI_EXP_LNKSTA_NLW_X4', + 'PCI_EXP_LNKSTA_NLW_X8', 'PCI_EXP_LNKSTA_SLC', 'PCI_EXP_RTCAP', + 'PCI_EXP_RTCAP_CRSVIS', 'PCI_EXP_RTCTL', 'PCI_EXP_RTCTL_CRSSVE', + 'PCI_EXP_RTCTL_PMEIE', 'PCI_EXP_RTCTL_SECEE', + 'PCI_EXP_RTCTL_SEFEE', 'PCI_EXP_RTCTL_SENFEE', 'PCI_EXP_RTSTA', + 'PCI_EXP_RTSTA_PENDING', 'PCI_EXP_RTSTA_PME', 'PCI_EXP_SLTCAP', + 'PCI_EXP_SLTCAP2', 'PCI_EXP_SLTCAP2_IBPD', 'PCI_EXP_SLTCAP_ABP', + 'PCI_EXP_SLTCAP_AIP', 'PCI_EXP_SLTCAP_EIP', 'PCI_EXP_SLTCAP_HPC', + 'PCI_EXP_SLTCAP_HPS', 'PCI_EXP_SLTCAP_MRLSP', + 'PCI_EXP_SLTCAP_NCCS', 'PCI_EXP_SLTCAP_PCP', 'PCI_EXP_SLTCAP_PIP', + 'PCI_EXP_SLTCAP_PSN', 'PCI_EXP_SLTCAP_SPLS', + 'PCI_EXP_SLTCAP_SPLV', 'PCI_EXP_SLTCTL', 'PCI_EXP_SLTCTL2', + 'PCI_EXP_SLTCTL_ABPE', 'PCI_EXP_SLTCTL_AIC', + 'PCI_EXP_SLTCTL_ATTN_IND_BLINK', 'PCI_EXP_SLTCTL_ATTN_IND_OFF', + 'PCI_EXP_SLTCTL_ATTN_IND_ON', 'PCI_EXP_SLTCTL_ATTN_IND_SHIFT', + 'PCI_EXP_SLTCTL_CCIE', 'PCI_EXP_SLTCTL_DLLSCE', + 'PCI_EXP_SLTCTL_EIC', 'PCI_EXP_SLTCTL_HPIE', + 'PCI_EXP_SLTCTL_IBPD_DISABLE', 'PCI_EXP_SLTCTL_MRLSCE', + 'PCI_EXP_SLTCTL_PCC', 'PCI_EXP_SLTCTL_PDCE', + 'PCI_EXP_SLTCTL_PFDE', 'PCI_EXP_SLTCTL_PIC', + 'PCI_EXP_SLTCTL_PWR_IND_BLINK', 'PCI_EXP_SLTCTL_PWR_IND_OFF', + 'PCI_EXP_SLTCTL_PWR_IND_ON', 'PCI_EXP_SLTCTL_PWR_OFF', + 'PCI_EXP_SLTCTL_PWR_ON', 'PCI_EXP_SLTSTA', 'PCI_EXP_SLTSTA2', + 'PCI_EXP_SLTSTA_ABP', 'PCI_EXP_SLTSTA_CC', 'PCI_EXP_SLTSTA_DLLSC', + 'PCI_EXP_SLTSTA_EIS', 'PCI_EXP_SLTSTA_MRLSC', + 'PCI_EXP_SLTSTA_MRLSS', 'PCI_EXP_SLTSTA_PDC', + 'PCI_EXP_SLTSTA_PDS', 'PCI_EXP_SLTSTA_PFD', + 'PCI_EXP_TYPE_DOWNSTREAM', 'PCI_EXP_TYPE_ENDPOINT', + 'PCI_EXP_TYPE_LEG_END', 'PCI_EXP_TYPE_PCIE_BRIDGE', + 'PCI_EXP_TYPE_PCI_BRIDGE', 'PCI_EXP_TYPE_RC_EC', + 'PCI_EXP_TYPE_RC_END', 'PCI_EXP_TYPE_ROOT_PORT', + 'PCI_EXP_TYPE_UPSTREAM', 'PCI_EXT_CAP_ARI_SIZEOF', + 'PCI_EXT_CAP_ATS_SIZEOF', 'PCI_EXT_CAP_DSN_SIZEOF', + 'PCI_EXT_CAP_ID_ACS', 'PCI_EXT_CAP_ID_AMD_XXX', + 'PCI_EXT_CAP_ID_ARI', 'PCI_EXT_CAP_ID_ATS', 'PCI_EXT_CAP_ID_CAC', + 'PCI_EXT_CAP_ID_DLF', 'PCI_EXT_CAP_ID_DPA', 'PCI_EXT_CAP_ID_DPC', + 'PCI_EXT_CAP_ID_DSN', 'PCI_EXT_CAP_ID_DVSEC', + 'PCI_EXT_CAP_ID_ERR', 'PCI_EXT_CAP_ID_L1SS', 'PCI_EXT_CAP_ID_LTR', + 'PCI_EXT_CAP_ID_MAX', 'PCI_EXT_CAP_ID_MCAST', + 'PCI_EXT_CAP_ID_MFVC', 'PCI_EXT_CAP_ID_MRIOV', + 'PCI_EXT_CAP_ID_PASID', 'PCI_EXT_CAP_ID_PL_16GT', + 'PCI_EXT_CAP_ID_PMUX', 'PCI_EXT_CAP_ID_PRI', 'PCI_EXT_CAP_ID_PTM', + 'PCI_EXT_CAP_ID_PWR', 'PCI_EXT_CAP_ID_RCEC', + 'PCI_EXT_CAP_ID_RCILC', 'PCI_EXT_CAP_ID_RCLD', + 'PCI_EXT_CAP_ID_RCRB', 'PCI_EXT_CAP_ID_REBAR', + 'PCI_EXT_CAP_ID_SECPCI', 'PCI_EXT_CAP_ID_SRIOV', + 'PCI_EXT_CAP_ID_TPH', 'PCI_EXT_CAP_ID_VC', 'PCI_EXT_CAP_ID_VC9', + 'PCI_EXT_CAP_ID_VNDR', 'PCI_EXT_CAP_LTR_SIZEOF', + 'PCI_EXT_CAP_MCAST_ENDPOINT_SIZEOF', 'PCI_EXT_CAP_PASID_SIZEOF', + 'PCI_EXT_CAP_PRI_SIZEOF', 'PCI_EXT_CAP_PWR_SIZEOF', + 'PCI_EXT_CAP_SRIOV_SIZEOF', 'PCI_HEADER_TYPE', + 'PCI_HEADER_TYPE_BRIDGE', 'PCI_HEADER_TYPE_CARDBUS', + 'PCI_HEADER_TYPE_MASK', 'PCI_HEADER_TYPE_NORMAL', + 'PCI_INTERRUPT_LINE', 'PCI_INTERRUPT_PIN', 'PCI_IO_1K_RANGE_MASK', + 'PCI_IO_BASE', 'PCI_IO_BASE_UPPER16', 'PCI_IO_LIMIT', + 'PCI_IO_LIMIT_UPPER16', 'PCI_IO_RANGE_MASK', + 'PCI_IO_RANGE_TYPE_16', 'PCI_IO_RANGE_TYPE_32', + 'PCI_IO_RANGE_TYPE_MASK', 'PCI_L1SS_CAP', + 'PCI_L1SS_CAP_ASPM_L1_1', 'PCI_L1SS_CAP_ASPM_L1_2', + 'PCI_L1SS_CAP_CM_RESTORE_TIME', 'PCI_L1SS_CAP_L1_PM_SS', + 'PCI_L1SS_CAP_PCIPM_L1_1', 'PCI_L1SS_CAP_PCIPM_L1_2', + 'PCI_L1SS_CAP_P_PWR_ON_SCALE', 'PCI_L1SS_CAP_P_PWR_ON_VALUE', + 'PCI_L1SS_CTL1', 'PCI_L1SS_CTL1_ASPM_L1_1', + 'PCI_L1SS_CTL1_ASPM_L1_2', 'PCI_L1SS_CTL1_CM_RESTORE_TIME', + 'PCI_L1SS_CTL1_L1SS_MASK', 'PCI_L1SS_CTL1_L1_2_MASK', + 'PCI_L1SS_CTL1_LTR_L12_TH_SCALE', + 'PCI_L1SS_CTL1_LTR_L12_TH_VALUE', 'PCI_L1SS_CTL1_PCIPM_L1_1', + 'PCI_L1SS_CTL1_PCIPM_L1_2', 'PCI_L1SS_CTL2', 'PCI_LATENCY_TIMER', + 'PCI_LTR_MAX_NOSNOOP_LAT', 'PCI_LTR_MAX_SNOOP_LAT', + 'PCI_LTR_SCALE_MASK', 'PCI_LTR_SCALE_SHIFT', 'PCI_LTR_VALUE_MASK', + 'PCI_MAX_LAT', 'PCI_MEMORY_BASE', 'PCI_MEMORY_LIMIT', + 'PCI_MEMORY_RANGE_MASK', 'PCI_MEMORY_RANGE_TYPE_MASK', + 'PCI_MIN_GNT', 'PCI_MSIX_ENTRY_CTRL_MASKBIT', + 'PCI_MSIX_ENTRY_DATA', 'PCI_MSIX_ENTRY_LOWER_ADDR', + 'PCI_MSIX_ENTRY_SIZE', 'PCI_MSIX_ENTRY_UPPER_ADDR', + 'PCI_MSIX_ENTRY_VECTOR_CTRL', 'PCI_MSIX_FLAGS', + 'PCI_MSIX_FLAGS_BIRMASK', 'PCI_MSIX_FLAGS_ENABLE', + 'PCI_MSIX_FLAGS_MASKALL', 'PCI_MSIX_FLAGS_QSIZE', 'PCI_MSIX_PBA', + 'PCI_MSIX_PBA_BIR', 'PCI_MSIX_PBA_OFFSET', 'PCI_MSIX_TABLE', + 'PCI_MSIX_TABLE_BIR', 'PCI_MSIX_TABLE_OFFSET', + 'PCI_MSI_ADDRESS_HI', 'PCI_MSI_ADDRESS_LO', 'PCI_MSI_DATA_32', + 'PCI_MSI_DATA_64', 'PCI_MSI_FLAGS', 'PCI_MSI_FLAGS_64BIT', + 'PCI_MSI_FLAGS_ENABLE', 'PCI_MSI_FLAGS_MASKBIT', + 'PCI_MSI_FLAGS_QMASK', 'PCI_MSI_FLAGS_QSIZE', 'PCI_MSI_MASK_32', + 'PCI_MSI_MASK_64', 'PCI_MSI_PENDING_32', 'PCI_MSI_PENDING_64', + 'PCI_MSI_RFU', 'PCI_PASID_CAP', 'PCI_PASID_CAP_EXEC', + 'PCI_PASID_CAP_PRIV', 'PCI_PASID_CTRL', 'PCI_PASID_CTRL_ENABLE', + 'PCI_PASID_CTRL_EXEC', 'PCI_PASID_CTRL_PRIV', + 'PCI_PL_16GT_LE_CTRL', 'PCI_PL_16GT_LE_CTRL_DSP_TX_PRESET_MASK', + 'PCI_PL_16GT_LE_CTRL_USP_TX_PRESET_MASK', + 'PCI_PL_16GT_LE_CTRL_USP_TX_PRESET_SHIFT', 'PCI_PM_BPCC_ENABLE', + 'PCI_PM_CAP_AUX_POWER', 'PCI_PM_CAP_D1', 'PCI_PM_CAP_D2', + 'PCI_PM_CAP_DSI', 'PCI_PM_CAP_PME', 'PCI_PM_CAP_PME_CLOCK', + 'PCI_PM_CAP_PME_D0', 'PCI_PM_CAP_PME_D1', 'PCI_PM_CAP_PME_D2', + 'PCI_PM_CAP_PME_D3cold', 'PCI_PM_CAP_PME_D3hot', + 'PCI_PM_CAP_PME_MASK', 'PCI_PM_CAP_PME_SHIFT', + 'PCI_PM_CAP_RESERVED', 'PCI_PM_CAP_VER_MASK', 'PCI_PM_CTRL', + 'PCI_PM_CTRL_DATA_SCALE_MASK', 'PCI_PM_CTRL_DATA_SEL_MASK', + 'PCI_PM_CTRL_NO_SOFT_RESET', 'PCI_PM_CTRL_PME_ENABLE', + 'PCI_PM_CTRL_PME_STATUS', 'PCI_PM_CTRL_STATE_MASK', + 'PCI_PM_DATA_REGISTER', 'PCI_PM_PMC', 'PCI_PM_PPB_B2_B3', + 'PCI_PM_PPB_EXTENSIONS', 'PCI_PM_SIZEOF', 'PCI_PREF_BASE_UPPER32', + 'PCI_PREF_LIMIT_UPPER32', 'PCI_PREF_MEMORY_BASE', + 'PCI_PREF_MEMORY_LIMIT', 'PCI_PREF_RANGE_MASK', + 'PCI_PREF_RANGE_TYPE_32', 'PCI_PREF_RANGE_TYPE_64', + 'PCI_PREF_RANGE_TYPE_MASK', 'PCI_PRIMARY_BUS', + 'PCI_PRI_ALLOC_REQ', 'PCI_PRI_CTRL', 'PCI_PRI_CTRL_ENABLE', + 'PCI_PRI_CTRL_RESET', 'PCI_PRI_MAX_REQ', 'PCI_PRI_STATUS', + 'PCI_PRI_STATUS_PASID', 'PCI_PRI_STATUS_RF', + 'PCI_PRI_STATUS_STOPPED', 'PCI_PRI_STATUS_UPRGI', 'PCI_PTM_CAP', + 'PCI_PTM_CAP_REQ', 'PCI_PTM_CAP_ROOT', 'PCI_PTM_CTRL', + 'PCI_PTM_CTRL_ENABLE', 'PCI_PTM_CTRL_ROOT', + 'PCI_PTM_GRANULARITY_MASK', 'PCI_PWR_CAP', 'PCI_PWR_DATA', + 'PCI_PWR_DSR', 'PCI_RCEC_BUSN', 'PCI_RCEC_BUSN_REG_VER', + 'PCI_RCEC_RCIEP_BITMAP', 'PCI_REBAR_CAP', 'PCI_REBAR_CAP_SIZES', + 'PCI_REBAR_CTRL', 'PCI_REBAR_CTRL_BAR_IDX', + 'PCI_REBAR_CTRL_BAR_SHIFT', 'PCI_REBAR_CTRL_BAR_SIZE', + 'PCI_REBAR_CTRL_NBAR_MASK', 'PCI_REBAR_CTRL_NBAR_SHIFT', + 'PCI_REVISION_ID', 'PCI_ROM_ADDRESS', 'PCI_ROM_ADDRESS1', + 'PCI_ROM_ADDRESS_ENABLE', 'PCI_ROM_ADDRESS_MASK', 'PCI_SATA_REGS', + 'PCI_SATA_REGS_INLINE', 'PCI_SATA_REGS_MASK', + 'PCI_SATA_SIZEOF_LONG', 'PCI_SATA_SIZEOF_SHORT', + 'PCI_SECONDARY_BUS', 'PCI_SEC_LATENCY_TIMER', 'PCI_SEC_STATUS', + 'PCI_SID_CHASSIS_NR', 'PCI_SID_ESR', 'PCI_SID_ESR_FIC', + 'PCI_SID_ESR_NSLOTS', 'PCI_SRIOV_BAR', 'PCI_SRIOV_CAP', + 'PCI_SRIOV_CAP_VFM', 'PCI_SRIOV_CTRL', 'PCI_SRIOV_CTRL_ARI', + 'PCI_SRIOV_CTRL_INTR', 'PCI_SRIOV_CTRL_MSE', 'PCI_SRIOV_CTRL_VFE', + 'PCI_SRIOV_CTRL_VFM', 'PCI_SRIOV_FUNC_LINK', + 'PCI_SRIOV_INITIAL_VF', 'PCI_SRIOV_NUM_BARS', 'PCI_SRIOV_NUM_VF', + 'PCI_SRIOV_STATUS', 'PCI_SRIOV_STATUS_VFM', + 'PCI_SRIOV_SUP_PGSIZE', 'PCI_SRIOV_SYS_PGSIZE', + 'PCI_SRIOV_TOTAL_VF', 'PCI_SRIOV_VFM', 'PCI_SRIOV_VFM_AV', + 'PCI_SRIOV_VFM_MI', 'PCI_SRIOV_VFM_MO', 'PCI_SRIOV_VFM_UA', + 'PCI_SRIOV_VF_DID', 'PCI_SRIOV_VF_OFFSET', 'PCI_SRIOV_VF_STRIDE', + 'PCI_SSVID_DEVICE_ID', 'PCI_SSVID_VENDOR_ID', 'PCI_STATUS', + 'PCI_STATUS_66MHZ', 'PCI_STATUS_CAP_LIST', + 'PCI_STATUS_DETECTED_PARITY', 'PCI_STATUS_DEVSEL_FAST', + 'PCI_STATUS_DEVSEL_MASK', 'PCI_STATUS_DEVSEL_MEDIUM', + 'PCI_STATUS_DEVSEL_SLOW', 'PCI_STATUS_FAST_BACK', + 'PCI_STATUS_IMM_READY', 'PCI_STATUS_INTERRUPT', + 'PCI_STATUS_PARITY', 'PCI_STATUS_REC_MASTER_ABORT', + 'PCI_STATUS_REC_TARGET_ABORT', 'PCI_STATUS_SIG_SYSTEM_ERROR', + 'PCI_STATUS_SIG_TARGET_ABORT', 'PCI_STATUS_UDF', + 'PCI_STD_HEADER_SIZEOF', 'PCI_STD_NUM_BARS', + 'PCI_SUBORDINATE_BUS', 'PCI_SUBSYSTEM_ID', + 'PCI_SUBSYSTEM_VENDOR_ID', 'PCI_TPH_BASE_SIZEOF', 'PCI_TPH_CAP', + 'PCI_TPH_CAP_LOC_MASK', 'PCI_TPH_CAP_ST_MASK', + 'PCI_TPH_CAP_ST_SHIFT', 'PCI_TPH_LOC_CAP', 'PCI_TPH_LOC_MSIX', + 'PCI_TPH_LOC_NONE', 'PCI_VC_CAP1_ARB_SIZE', 'PCI_VC_CAP1_EVCC', + 'PCI_VC_CAP1_LPEVCC', 'PCI_VC_CAP2_128_PHASE', + 'PCI_VC_CAP2_32_PHASE', 'PCI_VC_CAP2_64_PHASE', + 'PCI_VC_CAP2_ARB_OFF', 'PCI_VC_PORT_CAP1', 'PCI_VC_PORT_CAP2', + 'PCI_VC_PORT_CTRL', 'PCI_VC_PORT_CTRL_LOAD_TABLE', + 'PCI_VC_PORT_STATUS', 'PCI_VC_PORT_STATUS_TABLE', + 'PCI_VC_RES_CAP', 'PCI_VC_RES_CAP_128_PHASE', + 'PCI_VC_RES_CAP_128_PHASE_TB', 'PCI_VC_RES_CAP_256_PHASE', + 'PCI_VC_RES_CAP_32_PHASE', 'PCI_VC_RES_CAP_64_PHASE', + 'PCI_VC_RES_CAP_ARB_OFF', 'PCI_VC_RES_CTRL', + 'PCI_VC_RES_CTRL_ARB_SELECT', 'PCI_VC_RES_CTRL_ENABLE', + 'PCI_VC_RES_CTRL_ID', 'PCI_VC_RES_CTRL_LOAD_TABLE', + 'PCI_VC_RES_STATUS', 'PCI_VC_RES_STATUS_NEGO', + 'PCI_VC_RES_STATUS_TABLE', 'PCI_VENDOR_ID', 'PCI_VNDR_HEADER', + 'PCI_VPD_ADDR', 'PCI_VPD_ADDR_F', 'PCI_VPD_ADDR_MASK', + 'PCI_VPD_DATA', 'PCI_VSEC_HDR', 'PCI_VSEC_HDR_LEN_SHIFT', + 'PCI_X_BRIDGE_SSTATUS', 'PCI_X_BRIDGE_STATUS', 'PCI_X_CMD', + 'PCI_X_CMD_DPERR_E', 'PCI_X_CMD_ERO', 'PCI_X_CMD_MAX_READ', + 'PCI_X_CMD_MAX_SPLIT', 'PCI_X_CMD_READ_1K', 'PCI_X_CMD_READ_2K', + 'PCI_X_CMD_READ_4K', 'PCI_X_CMD_READ_512', 'PCI_X_CMD_SPLIT_1', + 'PCI_X_CMD_SPLIT_12', 'PCI_X_CMD_SPLIT_16', 'PCI_X_CMD_SPLIT_2', + 'PCI_X_CMD_SPLIT_3', 'PCI_X_CMD_SPLIT_32', 'PCI_X_CMD_SPLIT_4', + 'PCI_X_CMD_SPLIT_8', 'PCI_X_ECC_CSR', 'PCI_X_SSTATUS_133MHZ', + 'PCI_X_SSTATUS_266MHZ', 'PCI_X_SSTATUS_533MHZ', + 'PCI_X_SSTATUS_64BIT', 'PCI_X_SSTATUS_FREQ', 'PCI_X_SSTATUS_V1', + 'PCI_X_SSTATUS_V2', 'PCI_X_SSTATUS_VERS', 'PCI_X_STATUS', + 'PCI_X_STATUS_133MHZ', 'PCI_X_STATUS_266MHZ', + 'PCI_X_STATUS_533MHZ', 'PCI_X_STATUS_64BIT', 'PCI_X_STATUS_BUS', + 'PCI_X_STATUS_COMPLEX', 'PCI_X_STATUS_DEVFN', + 'PCI_X_STATUS_MAX_CUM', 'PCI_X_STATUS_MAX_READ', + 'PCI_X_STATUS_MAX_SPLIT', 'PCI_X_STATUS_SPL_DISC', + 'PCI_X_STATUS_SPL_ERR', 'PCI_X_STATUS_UNX_SPL'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/sqtt.py b/tinygrad_repo/tinygrad/runtime/autogen/sqtt.py new file mode 100644 index 0000000000..5d246bff15 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/sqtt.py @@ -0,0 +1,1789 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes, os + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +SQTT_FILE_MAGIC_NUMBER = 0x50303042 # macro +SQTT_FILE_VERSION_MAJOR = 1 # macro +SQTT_FILE_VERSION_MINOR = 5 # macro +SQTT_GPU_NAME_MAX_SIZE = 256 # macro +SQTT_MAX_NUM_SE = 32 # macro +SQTT_SA_PER_SE = 2 # macro +SQTT_ACTIVE_PIXEL_PACKER_MASK_DWORDS = 4 # macro +class struct_sqtt_data_info(Structure): + pass + +class union_sqtt_data_info_0(Union): + pass + +union_sqtt_data_info_0._pack_ = 1 # source:False +union_sqtt_data_info_0._fields_ = [ + ('gfx9_write_counter', ctypes.c_uint32), + ('gfx10_dropped_cntr', ctypes.c_uint32), +] + +struct_sqtt_data_info._pack_ = 1 # source:False +struct_sqtt_data_info._anonymous_ = ('_0',) +struct_sqtt_data_info._fields_ = [ + ('cur_offset', ctypes.c_uint32), + ('trace_status', ctypes.c_uint32), + ('_0', union_sqtt_data_info_0), +] + +class struct_sqtt_data_se(Structure): + pass + +struct_sqtt_data_se._pack_ = 1 # source:False +struct_sqtt_data_se._fields_ = [ + ('info', struct_sqtt_data_info), + ('PADDING_0', ctypes.c_ubyte * 4), + ('data_ptr', ctypes.POINTER(None)), + ('shader_engine', ctypes.c_uint32), + ('compute_unit', ctypes.c_uint32), +] + + +# values for enumeration 'sqtt_version' +sqtt_version__enumvalues = { + 0: 'SQTT_VERSION_NONE', + 5: 'SQTT_VERSION_2_2', + 6: 'SQTT_VERSION_2_3', + 7: 'SQTT_VERSION_2_4', + 11: 'SQTT_VERSION_3_2', +} +SQTT_VERSION_NONE = 0 +SQTT_VERSION_2_2 = 5 +SQTT_VERSION_2_3 = 6 +SQTT_VERSION_2_4 = 7 +SQTT_VERSION_3_2 = 11 +sqtt_version = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_file_chunk_type' +sqtt_file_chunk_type__enumvalues = { + 0: 'SQTT_FILE_CHUNK_TYPE_ASIC_INFO', + 1: 'SQTT_FILE_CHUNK_TYPE_SQTT_DESC', + 2: 'SQTT_FILE_CHUNK_TYPE_SQTT_DATA', + 3: 'SQTT_FILE_CHUNK_TYPE_API_INFO', + 4: 'SQTT_FILE_CHUNK_TYPE_RESERVED', + 5: 'SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS', + 6: 'SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION', + 7: 'SQTT_FILE_CHUNK_TYPE_CPU_INFO', + 8: 'SQTT_FILE_CHUNK_TYPE_SPM_DB', + 9: 'SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE', + 10: 'SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS', + 11: 'SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION', + 12: 'SQTT_FILE_CHUNK_TYPE_INSTRUMENTATION_TABLE', + 13: 'SQTT_FILE_CHUNK_TYPE_COUNT', +} +SQTT_FILE_CHUNK_TYPE_ASIC_INFO = 0 +SQTT_FILE_CHUNK_TYPE_SQTT_DESC = 1 +SQTT_FILE_CHUNK_TYPE_SQTT_DATA = 2 +SQTT_FILE_CHUNK_TYPE_API_INFO = 3 +SQTT_FILE_CHUNK_TYPE_RESERVED = 4 +SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS = 5 +SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION = 6 +SQTT_FILE_CHUNK_TYPE_CPU_INFO = 7 +SQTT_FILE_CHUNK_TYPE_SPM_DB = 8 +SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE = 9 +SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS = 10 +SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION = 11 +SQTT_FILE_CHUNK_TYPE_INSTRUMENTATION_TABLE = 12 +SQTT_FILE_CHUNK_TYPE_COUNT = 13 +sqtt_file_chunk_type = ctypes.c_uint32 # enum +class struct_sqtt_file_chunk_id(Structure): + pass + +struct_sqtt_file_chunk_id._pack_ = 1 # source:False +struct_sqtt_file_chunk_id._fields_ = [ + ('type', ctypes.c_int32, 8), + ('index', ctypes.c_int32, 8), + ('reserved', ctypes.c_int32, 16), +] + +class struct_sqtt_file_chunk_header(Structure): + pass + +struct_sqtt_file_chunk_header._pack_ = 1 # source:False +struct_sqtt_file_chunk_header._fields_ = [ + ('chunk_id', struct_sqtt_file_chunk_id), + ('minor_version', ctypes.c_uint16), + ('major_version', ctypes.c_uint16), + ('size_in_bytes', ctypes.c_int32), + ('padding', ctypes.c_int32), +] + +class struct_sqtt_file_header_flags(Structure): + pass + +class union_sqtt_file_header_flags_0(Union): + pass + +class struct_sqtt_file_header_flags_0_0(Structure): + pass + +struct_sqtt_file_header_flags_0_0._pack_ = 1 # source:False +struct_sqtt_file_header_flags_0_0._fields_ = [ + ('is_semaphore_queue_timing_etw', ctypes.c_uint32, 1), + ('no_queue_semaphore_timestamps', ctypes.c_uint32, 1), + ('reserved', ctypes.c_uint32, 30), +] + +union_sqtt_file_header_flags_0._pack_ = 1 # source:False +union_sqtt_file_header_flags_0._anonymous_ = ('_0',) +union_sqtt_file_header_flags_0._fields_ = [ + ('_0', struct_sqtt_file_header_flags_0_0), + ('value', ctypes.c_uint32), +] + +struct_sqtt_file_header_flags._pack_ = 1 # source:False +struct_sqtt_file_header_flags._anonymous_ = ('_0',) +struct_sqtt_file_header_flags._fields_ = [ + ('_0', union_sqtt_file_header_flags_0), +] + +class struct_sqtt_file_header(Structure): + pass + +struct_sqtt_file_header._pack_ = 1 # source:False +struct_sqtt_file_header._fields_ = [ + ('magic_number', ctypes.c_uint32), + ('version_major', ctypes.c_uint32), + ('version_minor', ctypes.c_uint32), + ('flags', struct_sqtt_file_header_flags), + ('chunk_offset', ctypes.c_int32), + ('second', ctypes.c_int32), + ('minute', ctypes.c_int32), + ('hour', ctypes.c_int32), + ('day_in_month', ctypes.c_int32), + ('month', ctypes.c_int32), + ('year', ctypes.c_int32), + ('day_in_week', ctypes.c_int32), + ('day_in_year', ctypes.c_int32), + ('is_daylight_savings', ctypes.c_int32), +] + +class struct_sqtt_file_chunk_cpu_info(Structure): + pass + +struct_sqtt_file_chunk_cpu_info._pack_ = 1 # source:False +struct_sqtt_file_chunk_cpu_info._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('vendor_id', ctypes.c_uint32 * 4), + ('processor_brand', ctypes.c_uint32 * 12), + ('reserved', ctypes.c_uint32 * 2), + ('cpu_timestamp_freq', ctypes.c_uint64), + ('clock_speed', ctypes.c_uint32), + ('num_logical_cores', ctypes.c_uint32), + ('num_physical_cores', ctypes.c_uint32), + ('system_ram_size', ctypes.c_uint32), +] + + +# values for enumeration 'sqtt_file_chunk_asic_info_flags' +sqtt_file_chunk_asic_info_flags__enumvalues = { + 1: 'SQTT_FILE_CHUNK_ASIC_INFO_FLAG_SC_PACKER_NUMBERING', + 2: 'SQTT_FILE_CHUNK_ASIC_INFO_FLAG_PS1_EVENT_TOKENS_ENABLED', +} +SQTT_FILE_CHUNK_ASIC_INFO_FLAG_SC_PACKER_NUMBERING = 1 +SQTT_FILE_CHUNK_ASIC_INFO_FLAG_PS1_EVENT_TOKENS_ENABLED = 2 +sqtt_file_chunk_asic_info_flags = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_gpu_type' +sqtt_gpu_type__enumvalues = { + 0: 'SQTT_GPU_TYPE_UNKNOWN', + 1: 'SQTT_GPU_TYPE_INTEGRATED', + 2: 'SQTT_GPU_TYPE_DISCRETE', + 3: 'SQTT_GPU_TYPE_VIRTUAL', +} +SQTT_GPU_TYPE_UNKNOWN = 0 +SQTT_GPU_TYPE_INTEGRATED = 1 +SQTT_GPU_TYPE_DISCRETE = 2 +SQTT_GPU_TYPE_VIRTUAL = 3 +sqtt_gpu_type = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_gfxip_level' +sqtt_gfxip_level__enumvalues = { + 0: 'SQTT_GFXIP_LEVEL_NONE', + 1: 'SQTT_GFXIP_LEVEL_GFXIP_6', + 2: 'SQTT_GFXIP_LEVEL_GFXIP_7', + 3: 'SQTT_GFXIP_LEVEL_GFXIP_8', + 4: 'SQTT_GFXIP_LEVEL_GFXIP_8_1', + 5: 'SQTT_GFXIP_LEVEL_GFXIP_9', + 7: 'SQTT_GFXIP_LEVEL_GFXIP_10_1', + 9: 'SQTT_GFXIP_LEVEL_GFXIP_10_3', + 12: 'SQTT_GFXIP_LEVEL_GFXIP_11_0', +} +SQTT_GFXIP_LEVEL_NONE = 0 +SQTT_GFXIP_LEVEL_GFXIP_6 = 1 +SQTT_GFXIP_LEVEL_GFXIP_7 = 2 +SQTT_GFXIP_LEVEL_GFXIP_8 = 3 +SQTT_GFXIP_LEVEL_GFXIP_8_1 = 4 +SQTT_GFXIP_LEVEL_GFXIP_9 = 5 +SQTT_GFXIP_LEVEL_GFXIP_10_1 = 7 +SQTT_GFXIP_LEVEL_GFXIP_10_3 = 9 +SQTT_GFXIP_LEVEL_GFXIP_11_0 = 12 +sqtt_gfxip_level = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_memory_type' +sqtt_memory_type__enumvalues = { + 0: 'SQTT_MEMORY_TYPE_UNKNOWN', + 1: 'SQTT_MEMORY_TYPE_DDR', + 2: 'SQTT_MEMORY_TYPE_DDR2', + 3: 'SQTT_MEMORY_TYPE_DDR3', + 4: 'SQTT_MEMORY_TYPE_DDR4', + 5: 'SQTT_MEMORY_TYPE_DDR5', + 16: 'SQTT_MEMORY_TYPE_GDDR3', + 17: 'SQTT_MEMORY_TYPE_GDDR4', + 18: 'SQTT_MEMORY_TYPE_GDDR5', + 19: 'SQTT_MEMORY_TYPE_GDDR6', + 32: 'SQTT_MEMORY_TYPE_HBM', + 33: 'SQTT_MEMORY_TYPE_HBM2', + 34: 'SQTT_MEMORY_TYPE_HBM3', + 48: 'SQTT_MEMORY_TYPE_LPDDR4', + 49: 'SQTT_MEMORY_TYPE_LPDDR5', +} +SQTT_MEMORY_TYPE_UNKNOWN = 0 +SQTT_MEMORY_TYPE_DDR = 1 +SQTT_MEMORY_TYPE_DDR2 = 2 +SQTT_MEMORY_TYPE_DDR3 = 3 +SQTT_MEMORY_TYPE_DDR4 = 4 +SQTT_MEMORY_TYPE_DDR5 = 5 +SQTT_MEMORY_TYPE_GDDR3 = 16 +SQTT_MEMORY_TYPE_GDDR4 = 17 +SQTT_MEMORY_TYPE_GDDR5 = 18 +SQTT_MEMORY_TYPE_GDDR6 = 19 +SQTT_MEMORY_TYPE_HBM = 32 +SQTT_MEMORY_TYPE_HBM2 = 33 +SQTT_MEMORY_TYPE_HBM3 = 34 +SQTT_MEMORY_TYPE_LPDDR4 = 48 +SQTT_MEMORY_TYPE_LPDDR5 = 49 +sqtt_memory_type = ctypes.c_uint32 # enum +class struct_sqtt_file_chunk_asic_info(Structure): + pass + +struct_sqtt_file_chunk_asic_info._pack_ = 1 # source:False +struct_sqtt_file_chunk_asic_info._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('flags', ctypes.c_uint64), + ('trace_shader_core_clock', ctypes.c_uint64), + ('trace_memory_clock', ctypes.c_uint64), + ('device_id', ctypes.c_int32), + ('device_revision_id', ctypes.c_int32), + ('vgprs_per_simd', ctypes.c_int32), + ('sgprs_per_simd', ctypes.c_int32), + ('shader_engines', ctypes.c_int32), + ('compute_unit_per_shader_engine', ctypes.c_int32), + ('simd_per_compute_unit', ctypes.c_int32), + ('wavefronts_per_simd', ctypes.c_int32), + ('minimum_vgpr_alloc', ctypes.c_int32), + ('vgpr_alloc_granularity', ctypes.c_int32), + ('minimum_sgpr_alloc', ctypes.c_int32), + ('sgpr_alloc_granularity', ctypes.c_int32), + ('hardware_contexts', ctypes.c_int32), + ('gpu_type', sqtt_gpu_type), + ('gfxip_level', sqtt_gfxip_level), + ('gpu_index', ctypes.c_int32), + ('gds_size', ctypes.c_int32), + ('gds_per_shader_engine', ctypes.c_int32), + ('ce_ram_size', ctypes.c_int32), + ('ce_ram_size_graphics', ctypes.c_int32), + ('ce_ram_size_compute', ctypes.c_int32), + ('max_number_of_dedicated_cus', ctypes.c_int32), + ('vram_size', ctypes.c_int64), + ('vram_bus_width', ctypes.c_int32), + ('l2_cache_size', ctypes.c_int32), + ('l1_cache_size', ctypes.c_int32), + ('lds_size', ctypes.c_int32), + ('gpu_name', ctypes.c_char * 256), + ('alu_per_clock', ctypes.c_float), + ('texture_per_clock', ctypes.c_float), + ('prims_per_clock', ctypes.c_float), + ('pixels_per_clock', ctypes.c_float), + ('gpu_timestamp_frequency', ctypes.c_uint64), + ('max_shader_core_clock', ctypes.c_uint64), + ('max_memory_clock', ctypes.c_uint64), + ('memory_ops_per_clock', ctypes.c_uint32), + ('memory_chip_type', sqtt_memory_type), + ('lds_granularity', ctypes.c_uint32), + ('cu_mask', ctypes.c_uint16 * 2 * 32), + ('reserved1', ctypes.c_char * 128), + ('active_pixel_packer_mask', ctypes.c_uint32 * 4), + ('reserved2', ctypes.c_char * 16), + ('gl1_cache_size', ctypes.c_uint32), + ('instruction_cache_size', ctypes.c_uint32), + ('scalar_cache_size', ctypes.c_uint32), + ('mall_cache_size', ctypes.c_uint32), + ('padding', ctypes.c_char * 4), +] + + +# values for enumeration 'sqtt_api_type' +sqtt_api_type__enumvalues = { + 0: 'SQTT_API_TYPE_DIRECTX_12', + 1: 'SQTT_API_TYPE_VULKAN', + 2: 'SQTT_API_TYPE_GENERIC', + 3: 'SQTT_API_TYPE_OPENCL', +} +SQTT_API_TYPE_DIRECTX_12 = 0 +SQTT_API_TYPE_VULKAN = 1 +SQTT_API_TYPE_GENERIC = 2 +SQTT_API_TYPE_OPENCL = 3 +sqtt_api_type = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_instruction_trace_mode' +sqtt_instruction_trace_mode__enumvalues = { + 0: 'SQTT_INSTRUCTION_TRACE_DISABLED', + 1: 'SQTT_INSTRUCTION_TRACE_FULL_FRAME', + 2: 'SQTT_INSTRUCTION_TRACE_API_PSO', +} +SQTT_INSTRUCTION_TRACE_DISABLED = 0 +SQTT_INSTRUCTION_TRACE_FULL_FRAME = 1 +SQTT_INSTRUCTION_TRACE_API_PSO = 2 +sqtt_instruction_trace_mode = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_profiling_mode' +sqtt_profiling_mode__enumvalues = { + 0: 'SQTT_PROFILING_MODE_PRESENT', + 1: 'SQTT_PROFILING_MODE_USER_MARKERS', + 2: 'SQTT_PROFILING_MODE_INDEX', + 3: 'SQTT_PROFILING_MODE_TAG', +} +SQTT_PROFILING_MODE_PRESENT = 0 +SQTT_PROFILING_MODE_USER_MARKERS = 1 +SQTT_PROFILING_MODE_INDEX = 2 +SQTT_PROFILING_MODE_TAG = 3 +sqtt_profiling_mode = ctypes.c_uint32 # enum +class union_sqtt_profiling_mode_data(Union): + pass + +class struct_sqtt_profiling_mode_data_user_marker_profiling_data(Structure): + pass + +struct_sqtt_profiling_mode_data_user_marker_profiling_data._pack_ = 1 # source:False +struct_sqtt_profiling_mode_data_user_marker_profiling_data._fields_ = [ + ('start', ctypes.c_char * 256), + ('end', ctypes.c_char * 256), +] + +class struct_sqtt_profiling_mode_data_index_profiling_data(Structure): + pass + +struct_sqtt_profiling_mode_data_index_profiling_data._pack_ = 1 # source:False +struct_sqtt_profiling_mode_data_index_profiling_data._fields_ = [ + ('start', ctypes.c_uint32), + ('end', ctypes.c_uint32), +] + +class struct_sqtt_profiling_mode_data_tag_profiling_data(Structure): + pass + +struct_sqtt_profiling_mode_data_tag_profiling_data._pack_ = 1 # source:False +struct_sqtt_profiling_mode_data_tag_profiling_data._fields_ = [ + ('begin_hi', ctypes.c_uint32), + ('begin_lo', ctypes.c_uint32), + ('end_hi', ctypes.c_uint32), + ('end_lo', ctypes.c_uint32), +] + +union_sqtt_profiling_mode_data._pack_ = 1 # source:False +union_sqtt_profiling_mode_data._fields_ = [ + ('user_marker_profiling_data', struct_sqtt_profiling_mode_data_user_marker_profiling_data), + ('index_profiling_data', struct_sqtt_profiling_mode_data_index_profiling_data), + ('tag_profiling_data', struct_sqtt_profiling_mode_data_tag_profiling_data), + ('PADDING_0', ctypes.c_ubyte * 496), +] + +class union_sqtt_instruction_trace_data(Union): + pass + +class struct_sqtt_instruction_trace_data_api_pso_data(Structure): + pass + +struct_sqtt_instruction_trace_data_api_pso_data._pack_ = 1 # source:False +struct_sqtt_instruction_trace_data_api_pso_data._fields_ = [ + ('api_pso_filter', ctypes.c_uint64), +] + +class struct_sqtt_instruction_trace_data_shader_engine_filter(Structure): + pass + +struct_sqtt_instruction_trace_data_shader_engine_filter._pack_ = 1 # source:False +struct_sqtt_instruction_trace_data_shader_engine_filter._fields_ = [ + ('mask', ctypes.c_uint32), +] + +union_sqtt_instruction_trace_data._pack_ = 1 # source:False +union_sqtt_instruction_trace_data._fields_ = [ + ('api_pso_data', struct_sqtt_instruction_trace_data_api_pso_data), + ('shader_engine_filter', struct_sqtt_instruction_trace_data_shader_engine_filter), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +class struct_sqtt_file_chunk_api_info(Structure): + pass + +struct_sqtt_file_chunk_api_info._pack_ = 1 # source:False +struct_sqtt_file_chunk_api_info._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('api_type', sqtt_api_type), + ('major_version', ctypes.c_uint16), + ('minor_version', ctypes.c_uint16), + ('profiling_mode', sqtt_profiling_mode), + ('reserved', ctypes.c_uint32), + ('profiling_mode_data', union_sqtt_profiling_mode_data), + ('instruction_trace_mode', sqtt_instruction_trace_mode), + ('reserved2', ctypes.c_uint32), + ('instruction_trace_data', union_sqtt_instruction_trace_data), +] + +class struct_sqtt_code_object_database_record(Structure): + pass + +struct_sqtt_code_object_database_record._pack_ = 1 # source:False +struct_sqtt_code_object_database_record._fields_ = [ + ('size', ctypes.c_uint32), +] + +class struct_sqtt_file_chunk_code_object_database(Structure): + pass + +struct_sqtt_file_chunk_code_object_database._pack_ = 1 # source:False +struct_sqtt_file_chunk_code_object_database._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('offset', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('size', ctypes.c_uint32), + ('record_count', ctypes.c_uint32), +] + +class struct_sqtt_code_object_loader_events_record(Structure): + pass + +struct_sqtt_code_object_loader_events_record._pack_ = 1 # source:False +struct_sqtt_code_object_loader_events_record._fields_ = [ + ('loader_event_type', ctypes.c_uint32), + ('reserved', ctypes.c_uint32), + ('base_address', ctypes.c_uint64), + ('code_object_hash', ctypes.c_uint64 * 2), + ('time_stamp', ctypes.c_uint64), +] + +class struct_sqtt_file_chunk_code_object_loader_events(Structure): + pass + +struct_sqtt_file_chunk_code_object_loader_events._pack_ = 1 # source:False +struct_sqtt_file_chunk_code_object_loader_events._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('offset', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('record_size', ctypes.c_uint32), + ('record_count', ctypes.c_uint32), +] + +class struct_sqtt_pso_correlation_record(Structure): + pass + +struct_sqtt_pso_correlation_record._pack_ = 1 # source:False +struct_sqtt_pso_correlation_record._fields_ = [ + ('api_pso_hash', ctypes.c_uint64), + ('pipeline_hash', ctypes.c_uint64 * 2), + ('api_level_obj_name', ctypes.c_char * 64), +] + +class struct_sqtt_file_chunk_pso_correlation(Structure): + pass + +struct_sqtt_file_chunk_pso_correlation._pack_ = 1 # source:False +struct_sqtt_file_chunk_pso_correlation._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('offset', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('record_size', ctypes.c_uint32), + ('record_count', ctypes.c_uint32), +] + +class struct_sqtt_file_chunk_sqtt_desc(Structure): + pass + +class union_sqtt_file_chunk_sqtt_desc_0(Union): + pass + +class struct_sqtt_file_chunk_sqtt_desc_0_v0(Structure): + pass + +struct_sqtt_file_chunk_sqtt_desc_0_v0._pack_ = 1 # source:False +struct_sqtt_file_chunk_sqtt_desc_0_v0._fields_ = [ + ('instrumentation_version', ctypes.c_int32), +] + +class struct_sqtt_file_chunk_sqtt_desc_0_v1(Structure): + pass + +struct_sqtt_file_chunk_sqtt_desc_0_v1._pack_ = 1 # source:False +struct_sqtt_file_chunk_sqtt_desc_0_v1._fields_ = [ + ('instrumentation_spec_version', ctypes.c_int16), + ('instrumentation_api_version', ctypes.c_int16), + ('compute_unit_index', ctypes.c_int32), +] + +union_sqtt_file_chunk_sqtt_desc_0._pack_ = 1 # source:False +union_sqtt_file_chunk_sqtt_desc_0._fields_ = [ + ('v0', struct_sqtt_file_chunk_sqtt_desc_0_v0), + ('v1', struct_sqtt_file_chunk_sqtt_desc_0_v1), +] + +struct_sqtt_file_chunk_sqtt_desc._pack_ = 1 # source:False +struct_sqtt_file_chunk_sqtt_desc._anonymous_ = ('_0',) +struct_sqtt_file_chunk_sqtt_desc._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('shader_engine_index', ctypes.c_int32), + ('sqtt_version', sqtt_version), + ('_0', union_sqtt_file_chunk_sqtt_desc_0), +] + +class struct_sqtt_file_chunk_sqtt_data(Structure): + pass + +struct_sqtt_file_chunk_sqtt_data._pack_ = 1 # source:False +struct_sqtt_file_chunk_sqtt_data._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('offset', ctypes.c_int32), + ('size', ctypes.c_int32), +] + +class struct_sqtt_file_chunk_queue_event_timings(Structure): + pass + +struct_sqtt_file_chunk_queue_event_timings._pack_ = 1 # source:False +struct_sqtt_file_chunk_queue_event_timings._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('queue_info_table_record_count', ctypes.c_uint32), + ('queue_info_table_size', ctypes.c_uint32), + ('queue_event_table_record_count', ctypes.c_uint32), + ('queue_event_table_size', ctypes.c_uint32), +] + + +# values for enumeration 'sqtt_queue_type' +sqtt_queue_type__enumvalues = { + 0: 'SQTT_QUEUE_TYPE_UNKNOWN', + 1: 'SQTT_QUEUE_TYPE_UNIVERSAL', + 2: 'SQTT_QUEUE_TYPE_COMPUTE', + 3: 'SQTT_QUEUE_TYPE_DMA', +} +SQTT_QUEUE_TYPE_UNKNOWN = 0 +SQTT_QUEUE_TYPE_UNIVERSAL = 1 +SQTT_QUEUE_TYPE_COMPUTE = 2 +SQTT_QUEUE_TYPE_DMA = 3 +sqtt_queue_type = ctypes.c_uint32 # enum + +# values for enumeration 'sqtt_engine_type' +sqtt_engine_type__enumvalues = { + 0: 'SQTT_ENGINE_TYPE_UNKNOWN', + 1: 'SQTT_ENGINE_TYPE_UNIVERSAL', + 2: 'SQTT_ENGINE_TYPE_COMPUTE', + 3: 'SQTT_ENGINE_TYPE_EXCLUSIVE_COMPUTE', + 4: 'SQTT_ENGINE_TYPE_DMA', + 7: 'SQTT_ENGINE_TYPE_HIGH_PRIORITY_UNIVERSAL', + 8: 'SQTT_ENGINE_TYPE_HIGH_PRIORITY_GRAPHICS', +} +SQTT_ENGINE_TYPE_UNKNOWN = 0 +SQTT_ENGINE_TYPE_UNIVERSAL = 1 +SQTT_ENGINE_TYPE_COMPUTE = 2 +SQTT_ENGINE_TYPE_EXCLUSIVE_COMPUTE = 3 +SQTT_ENGINE_TYPE_DMA = 4 +SQTT_ENGINE_TYPE_HIGH_PRIORITY_UNIVERSAL = 7 +SQTT_ENGINE_TYPE_HIGH_PRIORITY_GRAPHICS = 8 +sqtt_engine_type = ctypes.c_uint32 # enum +class struct_sqtt_queue_hardware_info(Structure): + pass + +class union_sqtt_queue_hardware_info_0(Union): + pass + +class struct_sqtt_queue_hardware_info_0_0(Structure): + pass + +struct_sqtt_queue_hardware_info_0_0._pack_ = 1 # source:False +struct_sqtt_queue_hardware_info_0_0._fields_ = [ + ('queue_type', ctypes.c_int32, 8), + ('engine_type', ctypes.c_int32, 8), + ('reserved', ctypes.c_int32, 16), +] + +union_sqtt_queue_hardware_info_0._pack_ = 1 # source:False +union_sqtt_queue_hardware_info_0._anonymous_ = ('_0',) +union_sqtt_queue_hardware_info_0._fields_ = [ + ('_0', struct_sqtt_queue_hardware_info_0_0), + ('value', ctypes.c_uint32), +] + +struct_sqtt_queue_hardware_info._pack_ = 1 # source:False +struct_sqtt_queue_hardware_info._anonymous_ = ('_0',) +struct_sqtt_queue_hardware_info._fields_ = [ + ('_0', union_sqtt_queue_hardware_info_0), +] + +class struct_sqtt_queue_info_record(Structure): + pass + +struct_sqtt_queue_info_record._pack_ = 1 # source:False +struct_sqtt_queue_info_record._fields_ = [ + ('queue_id', ctypes.c_uint64), + ('queue_context', ctypes.c_uint64), + ('hardware_info', struct_sqtt_queue_hardware_info), + ('reserved', ctypes.c_uint32), +] + + +# values for enumeration 'sqtt_queue_event_type' +sqtt_queue_event_type__enumvalues = { + 0: 'SQTT_QUEUE_TIMING_EVENT_CMDBUF_SUBMIT', + 1: 'SQTT_QUEUE_TIMING_EVENT_SIGNAL_SEMAPHORE', + 2: 'SQTT_QUEUE_TIMING_EVENT_WAIT_SEMAPHORE', + 3: 'SQTT_QUEUE_TIMING_EVENT_PRESENT', +} +SQTT_QUEUE_TIMING_EVENT_CMDBUF_SUBMIT = 0 +SQTT_QUEUE_TIMING_EVENT_SIGNAL_SEMAPHORE = 1 +SQTT_QUEUE_TIMING_EVENT_WAIT_SEMAPHORE = 2 +SQTT_QUEUE_TIMING_EVENT_PRESENT = 3 +sqtt_queue_event_type = ctypes.c_uint32 # enum +class struct_sqtt_queue_event_record(Structure): + pass + +struct_sqtt_queue_event_record._pack_ = 1 # source:False +struct_sqtt_queue_event_record._fields_ = [ + ('event_type', sqtt_queue_event_type), + ('sqtt_cb_id', ctypes.c_uint32), + ('frame_index', ctypes.c_uint64), + ('queue_info_index', ctypes.c_uint32), + ('submit_sub_index', ctypes.c_uint32), + ('api_id', ctypes.c_uint64), + ('cpu_timestamp', ctypes.c_uint64), + ('gpu_timestamps', ctypes.c_uint64 * 2), +] + +class struct_sqtt_file_chunk_clock_calibration(Structure): + pass + +struct_sqtt_file_chunk_clock_calibration._pack_ = 1 # source:False +struct_sqtt_file_chunk_clock_calibration._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('cpu_timestamp', ctypes.c_uint64), + ('gpu_timestamp', ctypes.c_uint64), + ('reserved', ctypes.c_uint64), +] + + +# values for enumeration 'elf_gfxip_level' +elf_gfxip_level__enumvalues = { + 40: 'EF_AMDGPU_MACH_AMDGCN_GFX801', + 44: 'EF_AMDGPU_MACH_AMDGCN_GFX900', + 51: 'EF_AMDGPU_MACH_AMDGCN_GFX1010', + 54: 'EF_AMDGPU_MACH_AMDGCN_GFX1030', + 65: 'EF_AMDGPU_MACH_AMDGCN_GFX1100', +} +EF_AMDGPU_MACH_AMDGCN_GFX801 = 40 +EF_AMDGPU_MACH_AMDGCN_GFX900 = 44 +EF_AMDGPU_MACH_AMDGCN_GFX1010 = 51 +EF_AMDGPU_MACH_AMDGCN_GFX1030 = 54 +EF_AMDGPU_MACH_AMDGCN_GFX1100 = 65 +elf_gfxip_level = ctypes.c_uint32 # enum +class struct_sqtt_file_chunk_spm_db(Structure): + pass + +struct_sqtt_file_chunk_spm_db._pack_ = 1 # source:False +struct_sqtt_file_chunk_spm_db._fields_ = [ + ('header', struct_sqtt_file_chunk_header), + ('flags', ctypes.c_uint32), + ('preamble_size', ctypes.c_uint32), + ('num_timestamps', ctypes.c_uint32), + ('num_spm_counter_info', ctypes.c_uint32), + ('spm_counter_info_size', ctypes.c_uint32), + ('sample_interval', ctypes.c_uint32), +] + + +# values for enumeration 'rgp_sqtt_marker_identifier' +rgp_sqtt_marker_identifier__enumvalues = { + 0: 'RGP_SQTT_MARKER_IDENTIFIER_EVENT', + 1: 'RGP_SQTT_MARKER_IDENTIFIER_CB_START', + 2: 'RGP_SQTT_MARKER_IDENTIFIER_CB_END', + 3: 'RGP_SQTT_MARKER_IDENTIFIER_BARRIER_START', + 4: 'RGP_SQTT_MARKER_IDENTIFIER_BARRIER_END', + 5: 'RGP_SQTT_MARKER_IDENTIFIER_USER_EVENT', + 6: 'RGP_SQTT_MARKER_IDENTIFIER_GENERAL_API', + 7: 'RGP_SQTT_MARKER_IDENTIFIER_SYNC', + 8: 'RGP_SQTT_MARKER_IDENTIFIER_PRESENT', + 9: 'RGP_SQTT_MARKER_IDENTIFIER_LAYOUT_TRANSITION', + 10: 'RGP_SQTT_MARKER_IDENTIFIER_RENDER_PASS', + 11: 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED2', + 12: 'RGP_SQTT_MARKER_IDENTIFIER_BIND_PIPELINE', + 13: 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED4', + 14: 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED5', + 15: 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED6', +} +RGP_SQTT_MARKER_IDENTIFIER_EVENT = 0 +RGP_SQTT_MARKER_IDENTIFIER_CB_START = 1 +RGP_SQTT_MARKER_IDENTIFIER_CB_END = 2 +RGP_SQTT_MARKER_IDENTIFIER_BARRIER_START = 3 +RGP_SQTT_MARKER_IDENTIFIER_BARRIER_END = 4 +RGP_SQTT_MARKER_IDENTIFIER_USER_EVENT = 5 +RGP_SQTT_MARKER_IDENTIFIER_GENERAL_API = 6 +RGP_SQTT_MARKER_IDENTIFIER_SYNC = 7 +RGP_SQTT_MARKER_IDENTIFIER_PRESENT = 8 +RGP_SQTT_MARKER_IDENTIFIER_LAYOUT_TRANSITION = 9 +RGP_SQTT_MARKER_IDENTIFIER_RENDER_PASS = 10 +RGP_SQTT_MARKER_IDENTIFIER_RESERVED2 = 11 +RGP_SQTT_MARKER_IDENTIFIER_BIND_PIPELINE = 12 +RGP_SQTT_MARKER_IDENTIFIER_RESERVED4 = 13 +RGP_SQTT_MARKER_IDENTIFIER_RESERVED5 = 14 +RGP_SQTT_MARKER_IDENTIFIER_RESERVED6 = 15 +rgp_sqtt_marker_identifier = ctypes.c_uint32 # enum +class union_rgp_sqtt_marker_cb_id(Union): + pass + +class struct_rgp_sqtt_marker_cb_id_per_frame_cb_id(Structure): + pass + +struct_rgp_sqtt_marker_cb_id_per_frame_cb_id._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_id_per_frame_cb_id._fields_ = [ + ('per_frame', ctypes.c_uint32, 1), + ('frame_index', ctypes.c_uint32, 7), + ('cb_index', ctypes.c_uint32, 12), + ('reserved', ctypes.c_uint32, 12), +] + +class struct_rgp_sqtt_marker_cb_id_global_cb_id(Structure): + pass + +struct_rgp_sqtt_marker_cb_id_global_cb_id._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_id_global_cb_id._fields_ = [ + ('per_frame', ctypes.c_uint32, 1), + ('cb_index', ctypes.c_uint32, 19), + ('reserved', ctypes.c_uint32, 12), +] + +union_rgp_sqtt_marker_cb_id._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_id._fields_ = [ + ('per_frame_cb_id', struct_rgp_sqtt_marker_cb_id_per_frame_cb_id), + ('global_cb_id', struct_rgp_sqtt_marker_cb_id_global_cb_id), + ('all', ctypes.c_uint32), +] + +class struct_rgp_sqtt_marker_cb_start(Structure): + pass + +class union_rgp_sqtt_marker_cb_start_0(Union): + pass + +class struct_rgp_sqtt_marker_cb_start_0_0(Structure): + pass + +struct_rgp_sqtt_marker_cb_start_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_start_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('cb_id', ctypes.c_uint32, 20), + ('queue', ctypes.c_uint32, 5), +] + +union_rgp_sqtt_marker_cb_start_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_start_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_cb_start_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_cb_start_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_cb_start_1(Union): + pass + +union_rgp_sqtt_marker_cb_start_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_start_1._fields_ = [ + ('device_id_low', ctypes.c_uint32), + ('dword02', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_cb_start_2(Union): + pass + +union_rgp_sqtt_marker_cb_start_2._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_start_2._fields_ = [ + ('device_id_high', ctypes.c_uint32), + ('dword03', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_cb_start_3(Union): + pass + +union_rgp_sqtt_marker_cb_start_3._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_start_3._fields_ = [ + ('queue_flags', ctypes.c_uint32), + ('dword04', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_cb_start._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_start._anonymous_ = ('_0', '_1', '_2', '_3',) +struct_rgp_sqtt_marker_cb_start._fields_ = [ + ('_0', union_rgp_sqtt_marker_cb_start_0), + ('_1', union_rgp_sqtt_marker_cb_start_1), + ('_2', union_rgp_sqtt_marker_cb_start_2), + ('_3', union_rgp_sqtt_marker_cb_start_3), +] + +class struct_rgp_sqtt_marker_cb_end(Structure): + pass + +class union_rgp_sqtt_marker_cb_end_0(Union): + pass + +class struct_rgp_sqtt_marker_cb_end_0_0(Structure): + pass + +struct_rgp_sqtt_marker_cb_end_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_end_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('cb_id', ctypes.c_uint32, 20), + ('reserved', ctypes.c_uint32, 5), +] + +union_rgp_sqtt_marker_cb_end_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_end_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_cb_end_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_cb_end_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_cb_end_1(Union): + pass + +union_rgp_sqtt_marker_cb_end_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_end_1._fields_ = [ + ('device_id_low', ctypes.c_uint32), + ('dword02', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_cb_end_2(Union): + pass + +union_rgp_sqtt_marker_cb_end_2._pack_ = 1 # source:False +union_rgp_sqtt_marker_cb_end_2._fields_ = [ + ('device_id_high', ctypes.c_uint32), + ('dword03', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_cb_end._pack_ = 1 # source:False +struct_rgp_sqtt_marker_cb_end._anonymous_ = ('_0', '_1', '_2',) +struct_rgp_sqtt_marker_cb_end._fields_ = [ + ('_0', union_rgp_sqtt_marker_cb_end_0), + ('_1', union_rgp_sqtt_marker_cb_end_1), + ('_2', union_rgp_sqtt_marker_cb_end_2), +] + + +# values for enumeration 'rgp_sqtt_marker_general_api_type' +rgp_sqtt_marker_general_api_type__enumvalues = { + 0: 'ApiCmdBindPipeline', + 1: 'ApiCmdBindDescriptorSets', + 2: 'ApiCmdBindIndexBuffer', + 3: 'ApiCmdBindVertexBuffers', + 4: 'ApiCmdDraw', + 5: 'ApiCmdDrawIndexed', + 6: 'ApiCmdDrawIndirect', + 7: 'ApiCmdDrawIndexedIndirect', + 8: 'ApiCmdDrawIndirectCountAMD', + 9: 'ApiCmdDrawIndexedIndirectCountAMD', + 10: 'ApiCmdDispatch', + 11: 'ApiCmdDispatchIndirect', + 12: 'ApiCmdCopyBuffer', + 13: 'ApiCmdCopyImage', + 14: 'ApiCmdBlitImage', + 15: 'ApiCmdCopyBufferToImage', + 16: 'ApiCmdCopyImageToBuffer', + 17: 'ApiCmdUpdateBuffer', + 18: 'ApiCmdFillBuffer', + 19: 'ApiCmdClearColorImage', + 20: 'ApiCmdClearDepthStencilImage', + 21: 'ApiCmdClearAttachments', + 22: 'ApiCmdResolveImage', + 23: 'ApiCmdWaitEvents', + 24: 'ApiCmdPipelineBarrier', + 25: 'ApiCmdBeginQuery', + 26: 'ApiCmdEndQuery', + 27: 'ApiCmdResetQueryPool', + 28: 'ApiCmdWriteTimestamp', + 29: 'ApiCmdCopyQueryPoolResults', + 30: 'ApiCmdPushConstants', + 31: 'ApiCmdBeginRenderPass', + 32: 'ApiCmdNextSubpass', + 33: 'ApiCmdEndRenderPass', + 34: 'ApiCmdExecuteCommands', + 35: 'ApiCmdSetViewport', + 36: 'ApiCmdSetScissor', + 37: 'ApiCmdSetLineWidth', + 38: 'ApiCmdSetDepthBias', + 39: 'ApiCmdSetBlendConstants', + 40: 'ApiCmdSetDepthBounds', + 41: 'ApiCmdSetStencilCompareMask', + 42: 'ApiCmdSetStencilWriteMask', + 43: 'ApiCmdSetStencilReference', + 44: 'ApiCmdDrawIndirectCount', + 45: 'ApiCmdDrawIndexedIndirectCount', + 47: 'ApiCmdDrawMeshTasksEXT', + 48: 'ApiCmdDrawMeshTasksIndirectCountEXT', + 49: 'ApiCmdDrawMeshTasksIndirectEXT', + 8388608: 'ApiRayTracingSeparateCompiled', + 4294967295: 'ApiInvalid', +} +ApiCmdBindPipeline = 0 +ApiCmdBindDescriptorSets = 1 +ApiCmdBindIndexBuffer = 2 +ApiCmdBindVertexBuffers = 3 +ApiCmdDraw = 4 +ApiCmdDrawIndexed = 5 +ApiCmdDrawIndirect = 6 +ApiCmdDrawIndexedIndirect = 7 +ApiCmdDrawIndirectCountAMD = 8 +ApiCmdDrawIndexedIndirectCountAMD = 9 +ApiCmdDispatch = 10 +ApiCmdDispatchIndirect = 11 +ApiCmdCopyBuffer = 12 +ApiCmdCopyImage = 13 +ApiCmdBlitImage = 14 +ApiCmdCopyBufferToImage = 15 +ApiCmdCopyImageToBuffer = 16 +ApiCmdUpdateBuffer = 17 +ApiCmdFillBuffer = 18 +ApiCmdClearColorImage = 19 +ApiCmdClearDepthStencilImage = 20 +ApiCmdClearAttachments = 21 +ApiCmdResolveImage = 22 +ApiCmdWaitEvents = 23 +ApiCmdPipelineBarrier = 24 +ApiCmdBeginQuery = 25 +ApiCmdEndQuery = 26 +ApiCmdResetQueryPool = 27 +ApiCmdWriteTimestamp = 28 +ApiCmdCopyQueryPoolResults = 29 +ApiCmdPushConstants = 30 +ApiCmdBeginRenderPass = 31 +ApiCmdNextSubpass = 32 +ApiCmdEndRenderPass = 33 +ApiCmdExecuteCommands = 34 +ApiCmdSetViewport = 35 +ApiCmdSetScissor = 36 +ApiCmdSetLineWidth = 37 +ApiCmdSetDepthBias = 38 +ApiCmdSetBlendConstants = 39 +ApiCmdSetDepthBounds = 40 +ApiCmdSetStencilCompareMask = 41 +ApiCmdSetStencilWriteMask = 42 +ApiCmdSetStencilReference = 43 +ApiCmdDrawIndirectCount = 44 +ApiCmdDrawIndexedIndirectCount = 45 +ApiCmdDrawMeshTasksEXT = 47 +ApiCmdDrawMeshTasksIndirectCountEXT = 48 +ApiCmdDrawMeshTasksIndirectEXT = 49 +ApiRayTracingSeparateCompiled = 8388608 +ApiInvalid = 4294967295 +rgp_sqtt_marker_general_api_type = ctypes.c_uint32 # enum +class struct_rgp_sqtt_marker_general_api(Structure): + pass + +class union_rgp_sqtt_marker_general_api_0(Union): + pass + +class struct_rgp_sqtt_marker_general_api_0_0(Structure): + pass + +struct_rgp_sqtt_marker_general_api_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_general_api_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('api_type', ctypes.c_uint32, 20), + ('is_end', ctypes.c_uint32, 1), + ('reserved', ctypes.c_uint32, 4), +] + +union_rgp_sqtt_marker_general_api_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_general_api_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_general_api_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_general_api_0_0), + ('dword01', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_general_api._pack_ = 1 # source:False +struct_rgp_sqtt_marker_general_api._anonymous_ = ('_0',) +struct_rgp_sqtt_marker_general_api._fields_ = [ + ('_0', union_rgp_sqtt_marker_general_api_0), +] + + +# values for enumeration 'rgp_sqtt_marker_event_type' +rgp_sqtt_marker_event_type__enumvalues = { + 0: 'EventCmdDraw', + 1: 'EventCmdDrawIndexed', + 2: 'EventCmdDrawIndirect', + 3: 'EventCmdDrawIndexedIndirect', + 4: 'EventCmdDrawIndirectCountAMD', + 5: 'EventCmdDrawIndexedIndirectCountAMD', + 6: 'EventCmdDispatch', + 7: 'EventCmdDispatchIndirect', + 8: 'EventCmdCopyBuffer', + 9: 'EventCmdCopyImage', + 10: 'EventCmdBlitImage', + 11: 'EventCmdCopyBufferToImage', + 12: 'EventCmdCopyImageToBuffer', + 13: 'EventCmdUpdateBuffer', + 14: 'EventCmdFillBuffer', + 15: 'EventCmdClearColorImage', + 16: 'EventCmdClearDepthStencilImage', + 17: 'EventCmdClearAttachments', + 18: 'EventCmdResolveImage', + 19: 'EventCmdWaitEvents', + 20: 'EventCmdPipelineBarrier', + 21: 'EventCmdResetQueryPool', + 22: 'EventCmdCopyQueryPoolResults', + 23: 'EventRenderPassColorClear', + 24: 'EventRenderPassDepthStencilClear', + 25: 'EventRenderPassResolve', + 26: 'EventInternalUnknown', + 27: 'EventCmdDrawIndirectCount', + 28: 'EventCmdDrawIndexedIndirectCount', + 30: 'EventCmdTraceRaysKHR', + 31: 'EventCmdTraceRaysIndirectKHR', + 32: 'EventCmdBuildAccelerationStructuresKHR', + 33: 'EventCmdBuildAccelerationStructuresIndirectKHR', + 34: 'EventCmdCopyAccelerationStructureKHR', + 35: 'EventCmdCopyAccelerationStructureToMemoryKHR', + 36: 'EventCmdCopyMemoryToAccelerationStructureKHR', + 41: 'EventCmdDrawMeshTasksEXT', + 42: 'EventCmdDrawMeshTasksIndirectCountEXT', + 43: 'EventCmdDrawMeshTasksIndirectEXT', + 32767: 'EventUnknown', + 4294967295: 'EventInvalid', +} +EventCmdDraw = 0 +EventCmdDrawIndexed = 1 +EventCmdDrawIndirect = 2 +EventCmdDrawIndexedIndirect = 3 +EventCmdDrawIndirectCountAMD = 4 +EventCmdDrawIndexedIndirectCountAMD = 5 +EventCmdDispatch = 6 +EventCmdDispatchIndirect = 7 +EventCmdCopyBuffer = 8 +EventCmdCopyImage = 9 +EventCmdBlitImage = 10 +EventCmdCopyBufferToImage = 11 +EventCmdCopyImageToBuffer = 12 +EventCmdUpdateBuffer = 13 +EventCmdFillBuffer = 14 +EventCmdClearColorImage = 15 +EventCmdClearDepthStencilImage = 16 +EventCmdClearAttachments = 17 +EventCmdResolveImage = 18 +EventCmdWaitEvents = 19 +EventCmdPipelineBarrier = 20 +EventCmdResetQueryPool = 21 +EventCmdCopyQueryPoolResults = 22 +EventRenderPassColorClear = 23 +EventRenderPassDepthStencilClear = 24 +EventRenderPassResolve = 25 +EventInternalUnknown = 26 +EventCmdDrawIndirectCount = 27 +EventCmdDrawIndexedIndirectCount = 28 +EventCmdTraceRaysKHR = 30 +EventCmdTraceRaysIndirectKHR = 31 +EventCmdBuildAccelerationStructuresKHR = 32 +EventCmdBuildAccelerationStructuresIndirectKHR = 33 +EventCmdCopyAccelerationStructureKHR = 34 +EventCmdCopyAccelerationStructureToMemoryKHR = 35 +EventCmdCopyMemoryToAccelerationStructureKHR = 36 +EventCmdDrawMeshTasksEXT = 41 +EventCmdDrawMeshTasksIndirectCountEXT = 42 +EventCmdDrawMeshTasksIndirectEXT = 43 +EventUnknown = 32767 +EventInvalid = 4294967295 +rgp_sqtt_marker_event_type = ctypes.c_uint32 # enum +class struct_rgp_sqtt_marker_event(Structure): + pass + +class union_rgp_sqtt_marker_event_0(Union): + pass + +class struct_rgp_sqtt_marker_event_0_0(Structure): + pass + +struct_rgp_sqtt_marker_event_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_event_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('api_type', ctypes.c_uint32, 24), + ('has_thread_dims', ctypes.c_uint32, 1), +] + +union_rgp_sqtt_marker_event_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_event_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_event_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_event_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_event_1(Union): + pass + +class struct_rgp_sqtt_marker_event_1_0(Structure): + pass + +struct_rgp_sqtt_marker_event_1_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_event_1_0._fields_ = [ + ('cb_id', ctypes.c_uint32, 20), + ('vertex_offset_reg_idx', ctypes.c_uint32, 4), + ('instance_offset_reg_idx', ctypes.c_uint32, 4), + ('draw_index_reg_idx', ctypes.c_uint32, 4), +] + +union_rgp_sqtt_marker_event_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_event_1._anonymous_ = ('_0',) +union_rgp_sqtt_marker_event_1._fields_ = [ + ('_0', struct_rgp_sqtt_marker_event_1_0), + ('dword02', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_event_2(Union): + pass + +union_rgp_sqtt_marker_event_2._pack_ = 1 # source:False +union_rgp_sqtt_marker_event_2._fields_ = [ + ('cmd_id', ctypes.c_uint32), + ('dword03', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_event._pack_ = 1 # source:False +struct_rgp_sqtt_marker_event._anonymous_ = ('_0', '_1', '_2',) +struct_rgp_sqtt_marker_event._fields_ = [ + ('_0', union_rgp_sqtt_marker_event_0), + ('_1', union_rgp_sqtt_marker_event_1), + ('_2', union_rgp_sqtt_marker_event_2), +] + +class struct_rgp_sqtt_marker_event_with_dims(Structure): + pass + +struct_rgp_sqtt_marker_event_with_dims._pack_ = 1 # source:False +struct_rgp_sqtt_marker_event_with_dims._fields_ = [ + ('event', struct_rgp_sqtt_marker_event), + ('thread_x', ctypes.c_uint32), + ('thread_y', ctypes.c_uint32), + ('thread_z', ctypes.c_uint32), +] + +class struct_rgp_sqtt_marker_barrier_start(Structure): + pass + +class union_rgp_sqtt_marker_barrier_start_0(Union): + pass + +class struct_rgp_sqtt_marker_barrier_start_0_0(Structure): + pass + +struct_rgp_sqtt_marker_barrier_start_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_start_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('cb_id', ctypes.c_uint32, 20), + ('reserved', ctypes.c_uint32, 5), +] + +union_rgp_sqtt_marker_barrier_start_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_barrier_start_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_barrier_start_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_barrier_start_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_barrier_start_1(Union): + pass + +class struct_rgp_sqtt_marker_barrier_start_1_0(Structure): + pass + +struct_rgp_sqtt_marker_barrier_start_1_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_start_1_0._fields_ = [ + ('driver_reason', ctypes.c_uint32, 31), + ('internal', ctypes.c_uint32, 1), +] + +union_rgp_sqtt_marker_barrier_start_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_barrier_start_1._anonymous_ = ('_0',) +union_rgp_sqtt_marker_barrier_start_1._fields_ = [ + ('_0', struct_rgp_sqtt_marker_barrier_start_1_0), + ('dword02', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_barrier_start._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_start._anonymous_ = ('_0', '_1',) +struct_rgp_sqtt_marker_barrier_start._fields_ = [ + ('_0', union_rgp_sqtt_marker_barrier_start_0), + ('_1', union_rgp_sqtt_marker_barrier_start_1), +] + +class struct_rgp_sqtt_marker_barrier_end(Structure): + pass + +class union_rgp_sqtt_marker_barrier_end_0(Union): + pass + +class struct_rgp_sqtt_marker_barrier_end_0_0(Structure): + pass + +struct_rgp_sqtt_marker_barrier_end_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_end_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('cb_id', ctypes.c_uint32, 20), + ('wait_on_eop_ts', ctypes.c_uint32, 1), + ('vs_partial_flush', ctypes.c_uint32, 1), + ('ps_partial_flush', ctypes.c_uint32, 1), + ('cs_partial_flush', ctypes.c_uint32, 1), + ('pfp_sync_me', ctypes.c_uint32, 1), +] + +union_rgp_sqtt_marker_barrier_end_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_barrier_end_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_barrier_end_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_barrier_end_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_barrier_end_1(Union): + pass + +class struct_rgp_sqtt_marker_barrier_end_1_0(Structure): + pass + +struct_rgp_sqtt_marker_barrier_end_1_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_end_1_0._fields_ = [ + ('sync_cp_dma', ctypes.c_uint32, 1), + ('inval_tcp', ctypes.c_uint32, 1), + ('inval_sqI', ctypes.c_uint32, 1), + ('inval_sqK', ctypes.c_uint32, 1), + ('flush_tcc', ctypes.c_uint32, 1), + ('inval_tcc', ctypes.c_uint32, 1), + ('flush_cb', ctypes.c_uint32, 1), + ('inval_cb', ctypes.c_uint32, 1), + ('flush_db', ctypes.c_uint32, 1), + ('inval_db', ctypes.c_uint32, 1), + ('num_layout_transitions', ctypes.c_uint32, 16), + ('inval_gl1', ctypes.c_uint32, 1), + ('wait_on_ts', ctypes.c_uint32, 1), + ('eop_ts_bottom_of_pipe', ctypes.c_uint32, 1), + ('eos_ts_ps_done', ctypes.c_uint32, 1), + ('eos_ts_cs_done', ctypes.c_uint32, 1), + ('reserved', ctypes.c_uint32, 1), +] + +union_rgp_sqtt_marker_barrier_end_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_barrier_end_1._anonymous_ = ('_0',) +union_rgp_sqtt_marker_barrier_end_1._fields_ = [ + ('_0', struct_rgp_sqtt_marker_barrier_end_1_0), + ('dword02', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_barrier_end._pack_ = 1 # source:False +struct_rgp_sqtt_marker_barrier_end._anonymous_ = ('_0', '_1',) +struct_rgp_sqtt_marker_barrier_end._fields_ = [ + ('_0', union_rgp_sqtt_marker_barrier_end_0), + ('_1', union_rgp_sqtt_marker_barrier_end_1), +] + +class struct_rgp_sqtt_marker_layout_transition(Structure): + pass + +class union_rgp_sqtt_marker_layout_transition_0(Union): + pass + +class struct_rgp_sqtt_marker_layout_transition_0_0(Structure): + pass + +struct_rgp_sqtt_marker_layout_transition_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_layout_transition_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('depth_stencil_expand', ctypes.c_uint32, 1), + ('htile_hiz_range_expand', ctypes.c_uint32, 1), + ('depth_stencil_resummarize', ctypes.c_uint32, 1), + ('dcc_decompress', ctypes.c_uint32, 1), + ('fmask_decompress', ctypes.c_uint32, 1), + ('fast_clear_eliminate', ctypes.c_uint32, 1), + ('fmask_color_expand', ctypes.c_uint32, 1), + ('init_mask_ram', ctypes.c_uint32, 1), + ('reserved1', ctypes.c_uint32, 17), +] + +union_rgp_sqtt_marker_layout_transition_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_layout_transition_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_layout_transition_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_layout_transition_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_layout_transition_1(Union): + pass + +class struct_rgp_sqtt_marker_layout_transition_1_0(Structure): + pass + +struct_rgp_sqtt_marker_layout_transition_1_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_layout_transition_1_0._fields_ = [ + ('reserved2', ctypes.c_uint32, 32), +] + +union_rgp_sqtt_marker_layout_transition_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_layout_transition_1._anonymous_ = ('_0',) +union_rgp_sqtt_marker_layout_transition_1._fields_ = [ + ('_0', struct_rgp_sqtt_marker_layout_transition_1_0), + ('dword02', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_layout_transition._pack_ = 1 # source:False +struct_rgp_sqtt_marker_layout_transition._anonymous_ = ('_0', '_1',) +struct_rgp_sqtt_marker_layout_transition._fields_ = [ + ('_0', union_rgp_sqtt_marker_layout_transition_0), + ('_1', union_rgp_sqtt_marker_layout_transition_1), +] + +class struct_rgp_sqtt_marker_user_event(Structure): + pass + +class union_rgp_sqtt_marker_user_event_0(Union): + pass + +class struct_rgp_sqtt_marker_user_event_0_0(Structure): + pass + +struct_rgp_sqtt_marker_user_event_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_user_event_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('reserved0', ctypes.c_uint32, 8), + ('data_type', ctypes.c_uint32, 8), + ('reserved1', ctypes.c_uint32, 12), +] + +union_rgp_sqtt_marker_user_event_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_user_event_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_user_event_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_user_event_0_0), + ('dword01', ctypes.c_uint32), +] + +struct_rgp_sqtt_marker_user_event._pack_ = 1 # source:False +struct_rgp_sqtt_marker_user_event._anonymous_ = ('_0',) +struct_rgp_sqtt_marker_user_event._fields_ = [ + ('_0', union_rgp_sqtt_marker_user_event_0), +] + +class struct_rgp_sqtt_marker_user_event_with_length(Structure): + pass + +struct_rgp_sqtt_marker_user_event_with_length._pack_ = 1 # source:False +struct_rgp_sqtt_marker_user_event_with_length._fields_ = [ + ('user_event', struct_rgp_sqtt_marker_user_event), + ('length', ctypes.c_uint32), +] + + +# values for enumeration 'rgp_sqtt_marker_user_event_type' +rgp_sqtt_marker_user_event_type__enumvalues = { + 0: 'UserEventTrigger', + 1: 'UserEventPop', + 2: 'UserEventPush', + 3: 'UserEventObjectName', +} +UserEventTrigger = 0 +UserEventPop = 1 +UserEventPush = 2 +UserEventObjectName = 3 +rgp_sqtt_marker_user_event_type = ctypes.c_uint32 # enum +class struct_rgp_sqtt_marker_pipeline_bind(Structure): + pass + +class union_rgp_sqtt_marker_pipeline_bind_0(Union): + pass + +class struct_rgp_sqtt_marker_pipeline_bind_0_0(Structure): + pass + +struct_rgp_sqtt_marker_pipeline_bind_0_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_pipeline_bind_0_0._fields_ = [ + ('identifier', ctypes.c_uint32, 4), + ('ext_dwords', ctypes.c_uint32, 3), + ('bind_point', ctypes.c_uint32, 1), + ('cb_id', ctypes.c_uint32, 20), + ('reserved', ctypes.c_uint32, 4), +] + +union_rgp_sqtt_marker_pipeline_bind_0._pack_ = 1 # source:False +union_rgp_sqtt_marker_pipeline_bind_0._anonymous_ = ('_0',) +union_rgp_sqtt_marker_pipeline_bind_0._fields_ = [ + ('_0', struct_rgp_sqtt_marker_pipeline_bind_0_0), + ('dword01', ctypes.c_uint32), +] + +class union_rgp_sqtt_marker_pipeline_bind_1(Union): + pass + +class struct_rgp_sqtt_marker_pipeline_bind_1_0(Structure): + pass + +struct_rgp_sqtt_marker_pipeline_bind_1_0._pack_ = 1 # source:False +struct_rgp_sqtt_marker_pipeline_bind_1_0._fields_ = [ + ('dword02', ctypes.c_uint32), + ('dword03', ctypes.c_uint32), +] + +union_rgp_sqtt_marker_pipeline_bind_1._pack_ = 1 # source:False +union_rgp_sqtt_marker_pipeline_bind_1._anonymous_ = ('_0',) +union_rgp_sqtt_marker_pipeline_bind_1._fields_ = [ + ('api_pso_hash', ctypes.c_uint32 * 2), + ('_0', struct_rgp_sqtt_marker_pipeline_bind_1_0), +] + +struct_rgp_sqtt_marker_pipeline_bind._pack_ = 1 # source:False +struct_rgp_sqtt_marker_pipeline_bind._anonymous_ = ('_0', '_1',) +struct_rgp_sqtt_marker_pipeline_bind._fields_ = [ + ('_0', union_rgp_sqtt_marker_pipeline_bind_0), + ('_1', union_rgp_sqtt_marker_pipeline_bind_1), +] + +__all__ = \ + ['ApiCmdBeginQuery', 'ApiCmdBeginRenderPass', + 'ApiCmdBindDescriptorSets', 'ApiCmdBindIndexBuffer', + 'ApiCmdBindPipeline', 'ApiCmdBindVertexBuffers', + 'ApiCmdBlitImage', 'ApiCmdClearAttachments', + 'ApiCmdClearColorImage', 'ApiCmdClearDepthStencilImage', + 'ApiCmdCopyBuffer', 'ApiCmdCopyBufferToImage', 'ApiCmdCopyImage', + 'ApiCmdCopyImageToBuffer', 'ApiCmdCopyQueryPoolResults', + 'ApiCmdDispatch', 'ApiCmdDispatchIndirect', 'ApiCmdDraw', + 'ApiCmdDrawIndexed', 'ApiCmdDrawIndexedIndirect', + 'ApiCmdDrawIndexedIndirectCount', + 'ApiCmdDrawIndexedIndirectCountAMD', 'ApiCmdDrawIndirect', + 'ApiCmdDrawIndirectCount', 'ApiCmdDrawIndirectCountAMD', + 'ApiCmdDrawMeshTasksEXT', 'ApiCmdDrawMeshTasksIndirectCountEXT', + 'ApiCmdDrawMeshTasksIndirectEXT', 'ApiCmdEndQuery', + 'ApiCmdEndRenderPass', 'ApiCmdExecuteCommands', + 'ApiCmdFillBuffer', 'ApiCmdNextSubpass', 'ApiCmdPipelineBarrier', + 'ApiCmdPushConstants', 'ApiCmdResetQueryPool', + 'ApiCmdResolveImage', 'ApiCmdSetBlendConstants', + 'ApiCmdSetDepthBias', 'ApiCmdSetDepthBounds', + 'ApiCmdSetLineWidth', 'ApiCmdSetScissor', + 'ApiCmdSetStencilCompareMask', 'ApiCmdSetStencilReference', + 'ApiCmdSetStencilWriteMask', 'ApiCmdSetViewport', + 'ApiCmdUpdateBuffer', 'ApiCmdWaitEvents', 'ApiCmdWriteTimestamp', + 'ApiInvalid', 'ApiRayTracingSeparateCompiled', + 'EF_AMDGPU_MACH_AMDGCN_GFX1010', 'EF_AMDGPU_MACH_AMDGCN_GFX1030', + 'EF_AMDGPU_MACH_AMDGCN_GFX1100', 'EF_AMDGPU_MACH_AMDGCN_GFX801', + 'EF_AMDGPU_MACH_AMDGCN_GFX900', 'EventCmdBlitImage', + 'EventCmdBuildAccelerationStructuresIndirectKHR', + 'EventCmdBuildAccelerationStructuresKHR', + 'EventCmdClearAttachments', 'EventCmdClearColorImage', + 'EventCmdClearDepthStencilImage', + 'EventCmdCopyAccelerationStructureKHR', + 'EventCmdCopyAccelerationStructureToMemoryKHR', + 'EventCmdCopyBuffer', 'EventCmdCopyBufferToImage', + 'EventCmdCopyImage', 'EventCmdCopyImageToBuffer', + 'EventCmdCopyMemoryToAccelerationStructureKHR', + 'EventCmdCopyQueryPoolResults', 'EventCmdDispatch', + 'EventCmdDispatchIndirect', 'EventCmdDraw', 'EventCmdDrawIndexed', + 'EventCmdDrawIndexedIndirect', 'EventCmdDrawIndexedIndirectCount', + 'EventCmdDrawIndexedIndirectCountAMD', 'EventCmdDrawIndirect', + 'EventCmdDrawIndirectCount', 'EventCmdDrawIndirectCountAMD', + 'EventCmdDrawMeshTasksEXT', + 'EventCmdDrawMeshTasksIndirectCountEXT', + 'EventCmdDrawMeshTasksIndirectEXT', 'EventCmdFillBuffer', + 'EventCmdPipelineBarrier', 'EventCmdResetQueryPool', + 'EventCmdResolveImage', 'EventCmdTraceRaysIndirectKHR', + 'EventCmdTraceRaysKHR', 'EventCmdUpdateBuffer', + 'EventCmdWaitEvents', 'EventInternalUnknown', 'EventInvalid', + 'EventRenderPassColorClear', 'EventRenderPassDepthStencilClear', + 'EventRenderPassResolve', 'EventUnknown', + 'RGP_SQTT_MARKER_IDENTIFIER_BARRIER_END', + 'RGP_SQTT_MARKER_IDENTIFIER_BARRIER_START', + 'RGP_SQTT_MARKER_IDENTIFIER_BIND_PIPELINE', + 'RGP_SQTT_MARKER_IDENTIFIER_CB_END', + 'RGP_SQTT_MARKER_IDENTIFIER_CB_START', + 'RGP_SQTT_MARKER_IDENTIFIER_EVENT', + 'RGP_SQTT_MARKER_IDENTIFIER_GENERAL_API', + 'RGP_SQTT_MARKER_IDENTIFIER_LAYOUT_TRANSITION', + 'RGP_SQTT_MARKER_IDENTIFIER_PRESENT', + 'RGP_SQTT_MARKER_IDENTIFIER_RENDER_PASS', + 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED2', + 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED4', + 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED5', + 'RGP_SQTT_MARKER_IDENTIFIER_RESERVED6', + 'RGP_SQTT_MARKER_IDENTIFIER_SYNC', + 'RGP_SQTT_MARKER_IDENTIFIER_USER_EVENT', + 'SQTT_ACTIVE_PIXEL_PACKER_MASK_DWORDS', + 'SQTT_API_TYPE_DIRECTX_12', 'SQTT_API_TYPE_GENERIC', + 'SQTT_API_TYPE_OPENCL', 'SQTT_API_TYPE_VULKAN', + 'SQTT_ENGINE_TYPE_COMPUTE', 'SQTT_ENGINE_TYPE_DMA', + 'SQTT_ENGINE_TYPE_EXCLUSIVE_COMPUTE', + 'SQTT_ENGINE_TYPE_HIGH_PRIORITY_GRAPHICS', + 'SQTT_ENGINE_TYPE_HIGH_PRIORITY_UNIVERSAL', + 'SQTT_ENGINE_TYPE_UNIVERSAL', 'SQTT_ENGINE_TYPE_UNKNOWN', + 'SQTT_FILE_CHUNK_ASIC_INFO_FLAG_PS1_EVENT_TOKENS_ENABLED', + 'SQTT_FILE_CHUNK_ASIC_INFO_FLAG_SC_PACKER_NUMBERING', + 'SQTT_FILE_CHUNK_TYPE_API_INFO', 'SQTT_FILE_CHUNK_TYPE_ASIC_INFO', + 'SQTT_FILE_CHUNK_TYPE_CLOCK_CALIBRATION', + 'SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_DATABASE', + 'SQTT_FILE_CHUNK_TYPE_CODE_OBJECT_LOADER_EVENTS', + 'SQTT_FILE_CHUNK_TYPE_COUNT', 'SQTT_FILE_CHUNK_TYPE_CPU_INFO', + 'SQTT_FILE_CHUNK_TYPE_INSTRUMENTATION_TABLE', + 'SQTT_FILE_CHUNK_TYPE_PSO_CORRELATION', + 'SQTT_FILE_CHUNK_TYPE_QUEUE_EVENT_TIMINGS', + 'SQTT_FILE_CHUNK_TYPE_RESERVED', 'SQTT_FILE_CHUNK_TYPE_SPM_DB', + 'SQTT_FILE_CHUNK_TYPE_SQTT_DATA', + 'SQTT_FILE_CHUNK_TYPE_SQTT_DESC', 'SQTT_FILE_MAGIC_NUMBER', + 'SQTT_FILE_VERSION_MAJOR', 'SQTT_FILE_VERSION_MINOR', + 'SQTT_GFXIP_LEVEL_GFXIP_10_1', 'SQTT_GFXIP_LEVEL_GFXIP_10_3', + 'SQTT_GFXIP_LEVEL_GFXIP_11_0', 'SQTT_GFXIP_LEVEL_GFXIP_6', + 'SQTT_GFXIP_LEVEL_GFXIP_7', 'SQTT_GFXIP_LEVEL_GFXIP_8', + 'SQTT_GFXIP_LEVEL_GFXIP_8_1', 'SQTT_GFXIP_LEVEL_GFXIP_9', + 'SQTT_GFXIP_LEVEL_NONE', 'SQTT_GPU_NAME_MAX_SIZE', + 'SQTT_GPU_TYPE_DISCRETE', 'SQTT_GPU_TYPE_INTEGRATED', + 'SQTT_GPU_TYPE_UNKNOWN', 'SQTT_GPU_TYPE_VIRTUAL', + 'SQTT_INSTRUCTION_TRACE_API_PSO', + 'SQTT_INSTRUCTION_TRACE_DISABLED', + 'SQTT_INSTRUCTION_TRACE_FULL_FRAME', 'SQTT_MAX_NUM_SE', + 'SQTT_MEMORY_TYPE_DDR', 'SQTT_MEMORY_TYPE_DDR2', + 'SQTT_MEMORY_TYPE_DDR3', 'SQTT_MEMORY_TYPE_DDR4', + 'SQTT_MEMORY_TYPE_DDR5', 'SQTT_MEMORY_TYPE_GDDR3', + 'SQTT_MEMORY_TYPE_GDDR4', 'SQTT_MEMORY_TYPE_GDDR5', + 'SQTT_MEMORY_TYPE_GDDR6', 'SQTT_MEMORY_TYPE_HBM', + 'SQTT_MEMORY_TYPE_HBM2', 'SQTT_MEMORY_TYPE_HBM3', + 'SQTT_MEMORY_TYPE_LPDDR4', 'SQTT_MEMORY_TYPE_LPDDR5', + 'SQTT_MEMORY_TYPE_UNKNOWN', 'SQTT_PROFILING_MODE_INDEX', + 'SQTT_PROFILING_MODE_PRESENT', 'SQTT_PROFILING_MODE_TAG', + 'SQTT_PROFILING_MODE_USER_MARKERS', + 'SQTT_QUEUE_TIMING_EVENT_CMDBUF_SUBMIT', + 'SQTT_QUEUE_TIMING_EVENT_PRESENT', + 'SQTT_QUEUE_TIMING_EVENT_SIGNAL_SEMAPHORE', + 'SQTT_QUEUE_TIMING_EVENT_WAIT_SEMAPHORE', + 'SQTT_QUEUE_TYPE_COMPUTE', 'SQTT_QUEUE_TYPE_DMA', + 'SQTT_QUEUE_TYPE_UNIVERSAL', 'SQTT_QUEUE_TYPE_UNKNOWN', + 'SQTT_SA_PER_SE', 'SQTT_VERSION_2_2', 'SQTT_VERSION_2_3', + 'SQTT_VERSION_2_4', 'SQTT_VERSION_3_2', 'SQTT_VERSION_NONE', + 'UserEventObjectName', 'UserEventPop', 'UserEventPush', + 'UserEventTrigger', 'elf_gfxip_level', + 'rgp_sqtt_marker_event_type', 'rgp_sqtt_marker_general_api_type', + 'rgp_sqtt_marker_identifier', 'rgp_sqtt_marker_user_event_type', + 'sqtt_api_type', 'sqtt_engine_type', + 'sqtt_file_chunk_asic_info_flags', 'sqtt_file_chunk_type', + 'sqtt_gfxip_level', 'sqtt_gpu_type', + 'sqtt_instruction_trace_mode', 'sqtt_memory_type', + 'sqtt_profiling_mode', 'sqtt_queue_event_type', 'sqtt_queue_type', + 'sqtt_version', 'struct_rgp_sqtt_marker_barrier_end', + 'struct_rgp_sqtt_marker_barrier_end_0_0', + 'struct_rgp_sqtt_marker_barrier_end_1_0', + 'struct_rgp_sqtt_marker_barrier_start', + 'struct_rgp_sqtt_marker_barrier_start_0_0', + 'struct_rgp_sqtt_marker_barrier_start_1_0', + 'struct_rgp_sqtt_marker_cb_end', + 'struct_rgp_sqtt_marker_cb_end_0_0', + 'struct_rgp_sqtt_marker_cb_id_global_cb_id', + 'struct_rgp_sqtt_marker_cb_id_per_frame_cb_id', + 'struct_rgp_sqtt_marker_cb_start', + 'struct_rgp_sqtt_marker_cb_start_0_0', + 'struct_rgp_sqtt_marker_event', + 'struct_rgp_sqtt_marker_event_0_0', + 'struct_rgp_sqtt_marker_event_1_0', + 'struct_rgp_sqtt_marker_event_with_dims', + 'struct_rgp_sqtt_marker_general_api', + 'struct_rgp_sqtt_marker_general_api_0_0', + 'struct_rgp_sqtt_marker_layout_transition', + 'struct_rgp_sqtt_marker_layout_transition_0_0', + 'struct_rgp_sqtt_marker_layout_transition_1_0', + 'struct_rgp_sqtt_marker_pipeline_bind', + 'struct_rgp_sqtt_marker_pipeline_bind_0_0', + 'struct_rgp_sqtt_marker_pipeline_bind_1_0', + 'struct_rgp_sqtt_marker_user_event', + 'struct_rgp_sqtt_marker_user_event_0_0', + 'struct_rgp_sqtt_marker_user_event_with_length', + 'struct_sqtt_code_object_database_record', + 'struct_sqtt_code_object_loader_events_record', + 'struct_sqtt_data_info', 'struct_sqtt_data_se', + 'struct_sqtt_file_chunk_api_info', + 'struct_sqtt_file_chunk_asic_info', + 'struct_sqtt_file_chunk_clock_calibration', + 'struct_sqtt_file_chunk_code_object_database', + 'struct_sqtt_file_chunk_code_object_loader_events', + 'struct_sqtt_file_chunk_cpu_info', + 'struct_sqtt_file_chunk_header', 'struct_sqtt_file_chunk_id', + 'struct_sqtt_file_chunk_pso_correlation', + 'struct_sqtt_file_chunk_queue_event_timings', + 'struct_sqtt_file_chunk_spm_db', + 'struct_sqtt_file_chunk_sqtt_data', + 'struct_sqtt_file_chunk_sqtt_desc', + 'struct_sqtt_file_chunk_sqtt_desc_0_v0', + 'struct_sqtt_file_chunk_sqtt_desc_0_v1', + 'struct_sqtt_file_header', 'struct_sqtt_file_header_flags', + 'struct_sqtt_file_header_flags_0_0', + 'struct_sqtt_instruction_trace_data_api_pso_data', + 'struct_sqtt_instruction_trace_data_shader_engine_filter', + 'struct_sqtt_profiling_mode_data_index_profiling_data', + 'struct_sqtt_profiling_mode_data_tag_profiling_data', + 'struct_sqtt_profiling_mode_data_user_marker_profiling_data', + 'struct_sqtt_pso_correlation_record', + 'struct_sqtt_queue_event_record', + 'struct_sqtt_queue_hardware_info', + 'struct_sqtt_queue_hardware_info_0_0', + 'struct_sqtt_queue_info_record', + 'union_rgp_sqtt_marker_barrier_end_0', + 'union_rgp_sqtt_marker_barrier_end_1', + 'union_rgp_sqtt_marker_barrier_start_0', + 'union_rgp_sqtt_marker_barrier_start_1', + 'union_rgp_sqtt_marker_cb_end_0', + 'union_rgp_sqtt_marker_cb_end_1', + 'union_rgp_sqtt_marker_cb_end_2', 'union_rgp_sqtt_marker_cb_id', + 'union_rgp_sqtt_marker_cb_start_0', + 'union_rgp_sqtt_marker_cb_start_1', + 'union_rgp_sqtt_marker_cb_start_2', + 'union_rgp_sqtt_marker_cb_start_3', + 'union_rgp_sqtt_marker_event_0', 'union_rgp_sqtt_marker_event_1', + 'union_rgp_sqtt_marker_event_2', + 'union_rgp_sqtt_marker_general_api_0', + 'union_rgp_sqtt_marker_layout_transition_0', + 'union_rgp_sqtt_marker_layout_transition_1', + 'union_rgp_sqtt_marker_pipeline_bind_0', + 'union_rgp_sqtt_marker_pipeline_bind_1', + 'union_rgp_sqtt_marker_user_event_0', 'union_sqtt_data_info_0', + 'union_sqtt_file_chunk_sqtt_desc_0', + 'union_sqtt_file_header_flags_0', + 'union_sqtt_instruction_trace_data', + 'union_sqtt_profiling_mode_data', + 'union_sqtt_queue_hardware_info_0'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/vfio.py b/tinygrad_repo/tinygrad/runtime/autogen/vfio.py new file mode 100644 index 0000000000..2cc7377e82 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/vfio.py @@ -0,0 +1,891 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes + + +from tinygrad.runtime.support.hcq import FileIOInterface +import functools + +def _do_ioctl_io(__idir, __base, __nr, __fd:FileIOInterface, val=0, __len=0): + return __fd.ioctl((__idir<<30) | (__len<<16) | (__base<<8) | __nr, val) + +def _do_ioctl(__idir, __base, __nr, __user_struct, __fd:FileIOInterface, __val=None, **kwargs): + ret = __fd.ioctl((__idir<<30) | (ctypes.sizeof(made := (__made or __user_struct(**kwargs)))<<16) | (__base<<8) | __nr, made) + if ret != 0: raise RuntimeError(f"ioctl returned {ret}") + return made + +def _IO(base, nr): return functools.partial(_do_ioctl_io, 0, ord(base) if isinstance(base, str) else base, nr) +def _IOW(base, nr, type): return functools.partial(_do_ioctl, 1, ord(base) if isinstance(base, str) else base, nr, type) +def _IOR(base, nr, type): return functools.partial(_do_ioctl, 2, ord(base) if isinstance(base, str) else base, nr, type) +def _IOWR(base, nr, type): return functools.partial(_do_ioctl, 3, ord(base) if isinstance(base, str) else base, nr, type) + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + + + +VFIO_H = True # macro +VFIO_API_VERSION = 0 # macro +VFIO_TYPE1_IOMMU = 1 # macro +VFIO_SPAPR_TCE_IOMMU = 2 # macro +VFIO_TYPE1v2_IOMMU = 3 # macro +VFIO_DMA_CC_IOMMU = 4 # macro +VFIO_EEH = 5 # macro +VFIO_TYPE1_NESTING_IOMMU = 6 # macro +VFIO_SPAPR_TCE_v2_IOMMU = 7 # macro +VFIO_NOIOMMU_IOMMU = 8 # macro +VFIO_UNMAP_ALL = 9 # macro +VFIO_UPDATE_VADDR = 10 # macro +VFIO_TYPE = (';') # macro +VFIO_BASE = 100 # macro +VFIO_GET_API_VERSION = _IO ( ( ';' ) , 100 + 0 ) # macro (from list) +VFIO_CHECK_EXTENSION = _IO ( ( ';' ) , 100 + 1 ) # macro (from list) +VFIO_SET_IOMMU = _IO ( ( ';' ) , 100 + 2 ) # macro (from list) +VFIO_GROUP_FLAGS_VIABLE = (1<<0) # macro +VFIO_GROUP_FLAGS_CONTAINER_SET = (1<<1) # macro +VFIO_GROUP_GET_STATUS = _IO ( ( ';' ) , 100 + 3 ) # macro (from list) +VFIO_GROUP_SET_CONTAINER = _IO ( ( ';' ) , 100 + 4 ) # macro (from list) +VFIO_GROUP_UNSET_CONTAINER = _IO ( ( ';' ) , 100 + 5 ) # macro (from list) +VFIO_GROUP_GET_DEVICE_FD = _IO ( ( ';' ) , 100 + 6 ) # macro (from list) +VFIO_DEVICE_FLAGS_RESET = (1<<0) # macro +VFIO_DEVICE_FLAGS_PCI = (1<<1) # macro +VFIO_DEVICE_FLAGS_PLATFORM = (1<<2) # macro +VFIO_DEVICE_FLAGS_AMBA = (1<<3) # macro +VFIO_DEVICE_FLAGS_CCW = (1<<4) # macro +VFIO_DEVICE_FLAGS_AP = (1<<5) # macro +VFIO_DEVICE_FLAGS_FSL_MC = (1<<6) # macro +VFIO_DEVICE_FLAGS_CAPS = (1<<7) # macro +VFIO_DEVICE_GET_INFO = _IO ( ( ';' ) , 100 + 7 ) # macro (from list) +VFIO_DEVICE_API_PCI_STRING = "vfio-pci" # macro +VFIO_DEVICE_API_PLATFORM_STRING = "vfio-platform" # macro +VFIO_DEVICE_API_AMBA_STRING = "vfio-amba" # macro +VFIO_DEVICE_API_CCW_STRING = "vfio-ccw" # macro +VFIO_DEVICE_API_AP_STRING = "vfio-ap" # macro +VFIO_DEVICE_INFO_CAP_ZPCI_BASE = 1 # macro +VFIO_DEVICE_INFO_CAP_ZPCI_GROUP = 2 # macro +VFIO_DEVICE_INFO_CAP_ZPCI_UTIL = 3 # macro +VFIO_DEVICE_INFO_CAP_ZPCI_PFIP = 4 # macro +VFIO_REGION_INFO_FLAG_READ = (1<<0) # macro +VFIO_REGION_INFO_FLAG_WRITE = (1<<1) # macro +VFIO_REGION_INFO_FLAG_MMAP = (1<<2) # macro +VFIO_REGION_INFO_FLAG_CAPS = (1<<3) # macro +VFIO_DEVICE_GET_REGION_INFO = _IO ( ( ';' ) , 100 + 8 ) # macro (from list) +VFIO_REGION_INFO_CAP_SPARSE_MMAP = 1 # macro +VFIO_REGION_INFO_CAP_TYPE = 2 # macro +VFIO_REGION_TYPE_PCI_VENDOR_TYPE = (1<<31) # macro +VFIO_REGION_TYPE_PCI_VENDOR_MASK = (0xffff) # macro +VFIO_REGION_TYPE_GFX = (1) # macro +VFIO_REGION_TYPE_CCW = (2) # macro +VFIO_REGION_TYPE_MIGRATION = (3) # macro +VFIO_REGION_SUBTYPE_INTEL_IGD_OPREGION = (1) # macro +VFIO_REGION_SUBTYPE_INTEL_IGD_HOST_CFG = (2) # macro +VFIO_REGION_SUBTYPE_INTEL_IGD_LPC_CFG = (3) # macro +VFIO_REGION_SUBTYPE_NVIDIA_NVLINK2_RAM = (1) # macro +VFIO_REGION_SUBTYPE_IBM_NVLINK2_ATSD = (1) # macro +VFIO_REGION_SUBTYPE_GFX_EDID = (1) # macro +VFIO_DEVICE_GFX_LINK_STATE_UP = 1 # macro +VFIO_DEVICE_GFX_LINK_STATE_DOWN = 2 # macro +VFIO_REGION_SUBTYPE_CCW_ASYNC_CMD = (1) # macro +VFIO_REGION_SUBTYPE_CCW_SCHIB = (2) # macro +VFIO_REGION_SUBTYPE_CCW_CRW = (3) # macro +VFIO_REGION_SUBTYPE_MIGRATION = (1) # macro +VFIO_DEVICE_STATE_STOP = (0) # macro +VFIO_DEVICE_STATE_RUNNING = (1<<0) # macro +VFIO_DEVICE_STATE_SAVING = (1<<1) # macro +VFIO_DEVICE_STATE_RESUMING = (1<<2) # macro +VFIO_DEVICE_STATE_MASK = ((1<<0)|(1<<1)|(1<<2)) # macro +# def VFIO_DEVICE_STATE_VALID(state): # macro +# return (state&(1<<2)?(state&((1<<0)|(1<<1)|(1<<2)))==(1<<2):1) +def VFIO_DEVICE_STATE_IS_ERROR(state): # macro + return ((state&((1<<0)|(1<<1)|(1<<2)))==((1<<1)|(1<<2))) +# def VFIO_DEVICE_STATE_SET_ERROR(state): # macro +# return ((state&~((1<<0)|(1<<1)|(1<<2)))|VFIO_DEVICE_SATE_SAVING|(1<<2)) +VFIO_REGION_INFO_CAP_MSIX_MAPPABLE = 3 # macro +VFIO_REGION_INFO_CAP_NVLINK2_SSATGT = 4 # macro +VFIO_REGION_INFO_CAP_NVLINK2_LNKSPD = 5 # macro +VFIO_IRQ_INFO_EVENTFD = (1<<0) # macro +VFIO_IRQ_INFO_MASKABLE = (1<<1) # macro +VFIO_IRQ_INFO_AUTOMASKED = (1<<2) # macro +VFIO_IRQ_INFO_NORESIZE = (1<<3) # macro +VFIO_DEVICE_GET_IRQ_INFO = _IO ( ( ';' ) , 100 + 9 ) # macro (from list) +VFIO_IRQ_SET_DATA_NONE = (1<<0) # macro +VFIO_IRQ_SET_DATA_BOOL = (1<<1) # macro +VFIO_IRQ_SET_DATA_EVENTFD = (1<<2) # macro +VFIO_IRQ_SET_ACTION_MASK = (1<<3) # macro +VFIO_IRQ_SET_ACTION_UNMASK = (1<<4) # macro +VFIO_IRQ_SET_ACTION_TRIGGER = (1<<5) # macro +VFIO_DEVICE_SET_IRQS = _IO ( ( ';' ) , 100 + 10 ) # macro (from list) +VFIO_IRQ_SET_DATA_TYPE_MASK = ((1<<0)|(1<<1)|(1<<2)) # macro +VFIO_IRQ_SET_ACTION_TYPE_MASK = ((1<<3)|(1<<4)|(1<<5)) # macro +VFIO_DEVICE_RESET = _IO ( ( ';' ) , 100 + 11 ) # macro (from list) +VFIO_DEVICE_GET_PCI_HOT_RESET_INFO = _IO ( ( ';' ) , 100 + 12 ) # macro (from list) +VFIO_DEVICE_PCI_HOT_RESET = _IO ( ( ';' ) , 100 + 13 ) # macro (from list) +VFIO_GFX_PLANE_TYPE_PROBE = (1<<0) # macro +VFIO_GFX_PLANE_TYPE_DMABUF = (1<<1) # macro +VFIO_GFX_PLANE_TYPE_REGION = (1<<2) # macro +VFIO_DEVICE_QUERY_GFX_PLANE = _IO ( ( ';' ) , 100 + 14 ) # macro (from list) +VFIO_DEVICE_GET_GFX_DMABUF = _IO ( ( ';' ) , 100 + 15 ) # macro (from list) +VFIO_DEVICE_IOEVENTFD_8 = (1<<0) # macro +VFIO_DEVICE_IOEVENTFD_16 = (1<<1) # macro +VFIO_DEVICE_IOEVENTFD_32 = (1<<2) # macro +VFIO_DEVICE_IOEVENTFD_64 = (1<<3) # macro +VFIO_DEVICE_IOEVENTFD_SIZE_MASK = (0xf) # macro +VFIO_DEVICE_IOEVENTFD = _IO ( ( ';' ) , 100 + 16 ) # macro (from list) +VFIO_DEVICE_FEATURE_MASK = (0xffff) # macro +VFIO_DEVICE_FEATURE_GET = (1<<16) # macro +VFIO_DEVICE_FEATURE_SET = (1<<17) # macro +VFIO_DEVICE_FEATURE_PROBE = (1<<18) # macro +VFIO_DEVICE_FEATURE = _IO ( ( ';' ) , 100 + 17 ) # macro (from list) +VFIO_DEVICE_FEATURE_PCI_VF_TOKEN = (0) # macro +VFIO_IOMMU_INFO_PGSIZES = (1<<0) # macro +VFIO_IOMMU_INFO_CAPS = (1<<1) # macro +VFIO_IOMMU_TYPE1_INFO_CAP_IOVA_RANGE = 1 # macro +VFIO_IOMMU_TYPE1_INFO_CAP_MIGRATION = 2 # macro +VFIO_IOMMU_TYPE1_INFO_DMA_AVAIL = 3 # macro +VFIO_IOMMU_GET_INFO = _IO ( ( ';' ) , 100 + 12 ) # macro (from list) +VFIO_DMA_MAP_FLAG_READ = (1<<0) # macro +VFIO_DMA_MAP_FLAG_WRITE = (1<<1) # macro +VFIO_DMA_MAP_FLAG_VADDR = (1<<2) # macro +VFIO_IOMMU_MAP_DMA = _IO ( ( ';' ) , 100 + 13 ) # macro (from list) +VFIO_DMA_UNMAP_FLAG_GET_DIRTY_BITMAP = (1<<0) # macro +VFIO_DMA_UNMAP_FLAG_ALL = (1<<1) # macro +VFIO_DMA_UNMAP_FLAG_VADDR = (1<<2) # macro +VFIO_IOMMU_UNMAP_DMA = _IO ( ( ';' ) , 100 + 14 ) # macro (from list) +VFIO_IOMMU_ENABLE = _IO ( ( ';' ) , 100 + 15 ) # macro (from list) +VFIO_IOMMU_DISABLE = _IO ( ( ';' ) , 100 + 16 ) # macro (from list) +VFIO_IOMMU_DIRTY_PAGES_FLAG_START = (1<<0) # macro +VFIO_IOMMU_DIRTY_PAGES_FLAG_STOP = (1<<1) # macro +VFIO_IOMMU_DIRTY_PAGES_FLAG_GET_BITMAP = (1<<2) # macro +VFIO_IOMMU_DIRTY_PAGES = _IO ( ( ';' ) , 100 + 17 ) # macro (from list) +VFIO_IOMMU_SPAPR_INFO_DDW = (1<<0) # macro +VFIO_IOMMU_SPAPR_TCE_GET_INFO = _IO ( ( ';' ) , 100 + 12 ) # macro (from list) +VFIO_EEH_PE_DISABLE = 0 # macro +VFIO_EEH_PE_ENABLE = 1 # macro +VFIO_EEH_PE_UNFREEZE_IO = 2 # macro +VFIO_EEH_PE_UNFREEZE_DMA = 3 # macro +VFIO_EEH_PE_GET_STATE = 4 # macro +VFIO_EEH_PE_STATE_NORMAL = 0 # macro +VFIO_EEH_PE_STATE_RESET = 1 # macro +VFIO_EEH_PE_STATE_STOPPED = 2 # macro +VFIO_EEH_PE_STATE_STOPPED_DMA = 4 # macro +VFIO_EEH_PE_STATE_UNAVAIL = 5 # macro +VFIO_EEH_PE_RESET_DEACTIVATE = 5 # macro +VFIO_EEH_PE_RESET_HOT = 6 # macro +VFIO_EEH_PE_RESET_FUNDAMENTAL = 7 # macro +VFIO_EEH_PE_CONFIGURE = 8 # macro +VFIO_EEH_PE_INJECT_ERR = 9 # macro +VFIO_EEH_PE_OP = _IO ( ( ';' ) , 100 + 21 ) # macro (from list) +VFIO_IOMMU_SPAPR_REGISTER_MEMORY = _IO ( ( ';' ) , 100 + 17 ) # macro (from list) +VFIO_IOMMU_SPAPR_UNREGISTER_MEMORY = _IO ( ( ';' ) , 100 + 18 ) # macro (from list) +VFIO_IOMMU_SPAPR_TCE_CREATE = _IO ( ( ';' ) , 100 + 19 ) # macro (from list) +VFIO_IOMMU_SPAPR_TCE_REMOVE = _IO ( ( ';' ) , 100 + 20 ) # macro (from list) +class struct_vfio_info_cap_header(Structure): + pass + +struct_vfio_info_cap_header._pack_ = 1 # source:False +struct_vfio_info_cap_header._fields_ = [ + ('id', ctypes.c_uint16), + ('version', ctypes.c_uint16), + ('next', ctypes.c_uint32), +] + +class struct_vfio_group_status(Structure): + pass + +struct_vfio_group_status._pack_ = 1 # source:False +struct_vfio_group_status._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), +] + +class struct_vfio_device_info(Structure): + pass + +struct_vfio_device_info._pack_ = 1 # source:False +struct_vfio_device_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('num_regions', ctypes.c_uint32), + ('num_irqs', ctypes.c_uint32), + ('cap_offset', ctypes.c_uint32), +] + +class struct_vfio_region_info(Structure): + pass + +struct_vfio_region_info._pack_ = 1 # source:False +struct_vfio_region_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('index', ctypes.c_uint32), + ('cap_offset', ctypes.c_uint32), + ('size', ctypes.c_uint64), + ('offset', ctypes.c_uint64), +] + +class struct_vfio_region_sparse_mmap_area(Structure): + pass + +struct_vfio_region_sparse_mmap_area._pack_ = 1 # source:False +struct_vfio_region_sparse_mmap_area._fields_ = [ + ('offset', ctypes.c_uint64), + ('size', ctypes.c_uint64), +] + +class struct_vfio_region_info_cap_sparse_mmap(Structure): + pass + +struct_vfio_region_info_cap_sparse_mmap._pack_ = 1 # source:False +struct_vfio_region_info_cap_sparse_mmap._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('nr_areas', ctypes.c_uint32), + ('reserved', ctypes.c_uint32), + ('areas', struct_vfio_region_sparse_mmap_area * 0), +] + +class struct_vfio_region_info_cap_type(Structure): + pass + +struct_vfio_region_info_cap_type._pack_ = 1 # source:False +struct_vfio_region_info_cap_type._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('type', ctypes.c_uint32), + ('subtype', ctypes.c_uint32), +] + +class struct_vfio_region_gfx_edid(Structure): + pass + +struct_vfio_region_gfx_edid._pack_ = 1 # source:False +struct_vfio_region_gfx_edid._fields_ = [ + ('edid_offset', ctypes.c_uint32), + ('edid_max_size', ctypes.c_uint32), + ('edid_size', ctypes.c_uint32), + ('max_xres', ctypes.c_uint32), + ('max_yres', ctypes.c_uint32), + ('link_state', ctypes.c_uint32), +] + +class struct_vfio_device_migration_info(Structure): + pass + +struct_vfio_device_migration_info._pack_ = 1 # source:False +struct_vfio_device_migration_info._fields_ = [ + ('device_state', ctypes.c_uint32), + ('reserved', ctypes.c_uint32), + ('pending_bytes', ctypes.c_uint64), + ('data_offset', ctypes.c_uint64), + ('data_size', ctypes.c_uint64), +] + +class struct_vfio_region_info_cap_nvlink2_ssatgt(Structure): + pass + +struct_vfio_region_info_cap_nvlink2_ssatgt._pack_ = 1 # source:False +struct_vfio_region_info_cap_nvlink2_ssatgt._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('tgt', ctypes.c_uint64), +] + +class struct_vfio_region_info_cap_nvlink2_lnkspd(Structure): + pass + +struct_vfio_region_info_cap_nvlink2_lnkspd._pack_ = 1 # source:False +struct_vfio_region_info_cap_nvlink2_lnkspd._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('link_speed', ctypes.c_uint32), + ('__pad', ctypes.c_uint32), +] + +class struct_vfio_irq_info(Structure): + pass + +struct_vfio_irq_info._pack_ = 1 # source:False +struct_vfio_irq_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('index', ctypes.c_uint32), + ('count', ctypes.c_uint32), +] + +class struct_vfio_irq_set(Structure): + pass + +struct_vfio_irq_set._pack_ = 1 # source:False +struct_vfio_irq_set._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('index', ctypes.c_uint32), + ('start', ctypes.c_uint32), + ('count', ctypes.c_uint32), + ('data', ctypes.c_int * 1), +] + + +# values for enumeration 'c__Ea_VFIO_PCI_BAR0_REGION_INDEX' +c__Ea_VFIO_PCI_BAR0_REGION_INDEX__enumvalues = { + 0: 'VFIO_PCI_BAR0_REGION_INDEX', + 1: 'VFIO_PCI_BAR1_REGION_INDEX', + 2: 'VFIO_PCI_BAR2_REGION_INDEX', + 3: 'VFIO_PCI_BAR3_REGION_INDEX', + 4: 'VFIO_PCI_BAR4_REGION_INDEX', + 5: 'VFIO_PCI_BAR5_REGION_INDEX', + 6: 'VFIO_PCI_ROM_REGION_INDEX', + 7: 'VFIO_PCI_CONFIG_REGION_INDEX', + 8: 'VFIO_PCI_VGA_REGION_INDEX', + 9: 'VFIO_PCI_NUM_REGIONS', +} +VFIO_PCI_BAR0_REGION_INDEX = 0 +VFIO_PCI_BAR1_REGION_INDEX = 1 +VFIO_PCI_BAR2_REGION_INDEX = 2 +VFIO_PCI_BAR3_REGION_INDEX = 3 +VFIO_PCI_BAR4_REGION_INDEX = 4 +VFIO_PCI_BAR5_REGION_INDEX = 5 +VFIO_PCI_ROM_REGION_INDEX = 6 +VFIO_PCI_CONFIG_REGION_INDEX = 7 +VFIO_PCI_VGA_REGION_INDEX = 8 +VFIO_PCI_NUM_REGIONS = 9 +c__Ea_VFIO_PCI_BAR0_REGION_INDEX = ctypes.c_uint32 # enum + +# values for enumeration 'c__Ea_VFIO_PCI_INTX_IRQ_INDEX' +c__Ea_VFIO_PCI_INTX_IRQ_INDEX__enumvalues = { + 0: 'VFIO_PCI_INTX_IRQ_INDEX', + 1: 'VFIO_PCI_MSI_IRQ_INDEX', + 2: 'VFIO_PCI_MSIX_IRQ_INDEX', + 3: 'VFIO_PCI_ERR_IRQ_INDEX', + 4: 'VFIO_PCI_REQ_IRQ_INDEX', + 5: 'VFIO_PCI_NUM_IRQS', +} +VFIO_PCI_INTX_IRQ_INDEX = 0 +VFIO_PCI_MSI_IRQ_INDEX = 1 +VFIO_PCI_MSIX_IRQ_INDEX = 2 +VFIO_PCI_ERR_IRQ_INDEX = 3 +VFIO_PCI_REQ_IRQ_INDEX = 4 +VFIO_PCI_NUM_IRQS = 5 +c__Ea_VFIO_PCI_INTX_IRQ_INDEX = ctypes.c_uint32 # enum + +# values for enumeration 'c__Ea_VFIO_CCW_CONFIG_REGION_INDEX' +c__Ea_VFIO_CCW_CONFIG_REGION_INDEX__enumvalues = { + 0: 'VFIO_CCW_CONFIG_REGION_INDEX', + 1: 'VFIO_CCW_NUM_REGIONS', +} +VFIO_CCW_CONFIG_REGION_INDEX = 0 +VFIO_CCW_NUM_REGIONS = 1 +c__Ea_VFIO_CCW_CONFIG_REGION_INDEX = ctypes.c_uint32 # enum + +# values for enumeration 'c__Ea_VFIO_CCW_IO_IRQ_INDEX' +c__Ea_VFIO_CCW_IO_IRQ_INDEX__enumvalues = { + 0: 'VFIO_CCW_IO_IRQ_INDEX', + 1: 'VFIO_CCW_CRW_IRQ_INDEX', + 2: 'VFIO_CCW_REQ_IRQ_INDEX', + 3: 'VFIO_CCW_NUM_IRQS', +} +VFIO_CCW_IO_IRQ_INDEX = 0 +VFIO_CCW_CRW_IRQ_INDEX = 1 +VFIO_CCW_REQ_IRQ_INDEX = 2 +VFIO_CCW_NUM_IRQS = 3 +c__Ea_VFIO_CCW_IO_IRQ_INDEX = ctypes.c_uint32 # enum +class struct_vfio_pci_dependent_device(Structure): + pass + +struct_vfio_pci_dependent_device._pack_ = 1 # source:False +struct_vfio_pci_dependent_device._fields_ = [ + ('group_id', ctypes.c_uint32), + ('segment', ctypes.c_uint16), + ('bus', ctypes.c_ubyte), + ('devfn', ctypes.c_ubyte), +] + +class struct_vfio_pci_hot_reset_info(Structure): + pass + +struct_vfio_pci_hot_reset_info._pack_ = 1 # source:False +struct_vfio_pci_hot_reset_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('count', ctypes.c_uint32), + ('devices', struct_vfio_pci_dependent_device * 0), +] + +class struct_vfio_pci_hot_reset(Structure): + pass + +struct_vfio_pci_hot_reset._pack_ = 1 # source:False +struct_vfio_pci_hot_reset._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('count', ctypes.c_uint32), + ('group_fds', ctypes.c_int32 * 0), +] + +class struct_vfio_device_gfx_plane_info(Structure): + pass + +class union_vfio_device_gfx_plane_info_0(Union): + pass + +union_vfio_device_gfx_plane_info_0._pack_ = 1 # source:False +union_vfio_device_gfx_plane_info_0._fields_ = [ + ('region_index', ctypes.c_uint32), + ('dmabuf_id', ctypes.c_uint32), +] + +struct_vfio_device_gfx_plane_info._pack_ = 1 # source:False +struct_vfio_device_gfx_plane_info._anonymous_ = ('_0',) +struct_vfio_device_gfx_plane_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('drm_plane_type', ctypes.c_uint32), + ('drm_format', ctypes.c_uint32), + ('drm_format_mod', ctypes.c_uint64), + ('width', ctypes.c_uint32), + ('height', ctypes.c_uint32), + ('stride', ctypes.c_uint32), + ('size', ctypes.c_uint32), + ('x_pos', ctypes.c_uint32), + ('y_pos', ctypes.c_uint32), + ('x_hot', ctypes.c_uint32), + ('y_hot', ctypes.c_uint32), + ('_0', union_vfio_device_gfx_plane_info_0), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +class struct_vfio_device_ioeventfd(Structure): + pass + +struct_vfio_device_ioeventfd._pack_ = 1 # source:False +struct_vfio_device_ioeventfd._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('offset', ctypes.c_uint64), + ('data', ctypes.c_uint64), + ('fd', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +class struct_vfio_device_feature(Structure): + pass + +struct_vfio_device_feature._pack_ = 1 # source:False +struct_vfio_device_feature._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('data', ctypes.c_ubyte * 0), +] + +class struct_vfio_iommu_type1_info(Structure): + pass + +struct_vfio_iommu_type1_info._pack_ = 1 # source:False +struct_vfio_iommu_type1_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('iova_pgsizes', ctypes.c_uint64), + ('cap_offset', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +class struct_vfio_iova_range(Structure): + pass + +struct_vfio_iova_range._pack_ = 1 # source:False +struct_vfio_iova_range._fields_ = [ + ('start', ctypes.c_uint64), + ('end', ctypes.c_uint64), +] + +class struct_vfio_iommu_type1_info_cap_iova_range(Structure): + pass + +struct_vfio_iommu_type1_info_cap_iova_range._pack_ = 1 # source:False +struct_vfio_iommu_type1_info_cap_iova_range._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('nr_iovas', ctypes.c_uint32), + ('reserved', ctypes.c_uint32), + ('iova_ranges', struct_vfio_iova_range * 0), +] + +class struct_vfio_iommu_type1_info_cap_migration(Structure): + pass + +struct_vfio_iommu_type1_info_cap_migration._pack_ = 1 # source:False +struct_vfio_iommu_type1_info_cap_migration._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('flags', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('pgsize_bitmap', ctypes.c_uint64), + ('max_dirty_bitmap_size', ctypes.c_uint64), +] + +class struct_vfio_iommu_type1_info_dma_avail(Structure): + pass + +struct_vfio_iommu_type1_info_dma_avail._pack_ = 1 # source:False +struct_vfio_iommu_type1_info_dma_avail._fields_ = [ + ('header', struct_vfio_info_cap_header), + ('avail', ctypes.c_uint32), +] + +class struct_vfio_iommu_type1_dma_map(Structure): + pass + +struct_vfio_iommu_type1_dma_map._pack_ = 1 # source:False +struct_vfio_iommu_type1_dma_map._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('vaddr', ctypes.c_uint64), + ('iova', ctypes.c_uint64), + ('size', ctypes.c_uint64), +] + +class struct_vfio_bitmap(Structure): + pass + +struct_vfio_bitmap._pack_ = 1 # source:False +struct_vfio_bitmap._fields_ = [ + ('pgsize', ctypes.c_uint64), + ('size', ctypes.c_uint64), + ('data', ctypes.POINTER(ctypes.c_uint64)), +] + +class struct_vfio_iommu_type1_dma_unmap(Structure): + pass + +struct_vfio_iommu_type1_dma_unmap._pack_ = 1 # source:False +struct_vfio_iommu_type1_dma_unmap._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('iova', ctypes.c_uint64), + ('size', ctypes.c_uint64), + ('data', ctypes.c_ubyte * 0), +] + +class struct_vfio_iommu_type1_dirty_bitmap(Structure): + pass + +struct_vfio_iommu_type1_dirty_bitmap._pack_ = 1 # source:False +struct_vfio_iommu_type1_dirty_bitmap._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('data', ctypes.c_ubyte * 0), +] + +class struct_vfio_iommu_type1_dirty_bitmap_get(Structure): + pass + +struct_vfio_iommu_type1_dirty_bitmap_get._pack_ = 1 # source:False +struct_vfio_iommu_type1_dirty_bitmap_get._fields_ = [ + ('iova', ctypes.c_uint64), + ('size', ctypes.c_uint64), + ('bitmap', struct_vfio_bitmap), +] + +class struct_vfio_iommu_spapr_tce_ddw_info(Structure): + pass + +struct_vfio_iommu_spapr_tce_ddw_info._pack_ = 1 # source:False +struct_vfio_iommu_spapr_tce_ddw_info._fields_ = [ + ('pgsizes', ctypes.c_uint64), + ('max_dynamic_windows_supported', ctypes.c_uint32), + ('levels', ctypes.c_uint32), +] + +class struct_vfio_iommu_spapr_tce_info(Structure): + pass + +struct_vfio_iommu_spapr_tce_info._pack_ = 1 # source:False +struct_vfio_iommu_spapr_tce_info._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('dma32_window_start', ctypes.c_uint32), + ('dma32_window_size', ctypes.c_uint32), + ('ddw', struct_vfio_iommu_spapr_tce_ddw_info), +] + +class struct_vfio_eeh_pe_err(Structure): + pass + +struct_vfio_eeh_pe_err._pack_ = 1 # source:False +struct_vfio_eeh_pe_err._fields_ = [ + ('type', ctypes.c_uint32), + ('func', ctypes.c_uint32), + ('addr', ctypes.c_uint64), + ('mask', ctypes.c_uint64), +] + +class struct_vfio_eeh_pe_op(Structure): + pass + +class union_vfio_eeh_pe_op_0(Union): + _pack_ = 1 # source:False + _fields_ = [ + ('err', struct_vfio_eeh_pe_err), + ] + +struct_vfio_eeh_pe_op._pack_ = 1 # source:False +struct_vfio_eeh_pe_op._anonymous_ = ('_0',) +struct_vfio_eeh_pe_op._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('op', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('_0', union_vfio_eeh_pe_op_0), +] + +class struct_vfio_iommu_spapr_register_memory(Structure): + pass + +struct_vfio_iommu_spapr_register_memory._pack_ = 1 # source:False +struct_vfio_iommu_spapr_register_memory._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('vaddr', ctypes.c_uint64), + ('size', ctypes.c_uint64), +] + +class struct_vfio_iommu_spapr_tce_create(Structure): + pass + +struct_vfio_iommu_spapr_tce_create._pack_ = 1 # source:False +struct_vfio_iommu_spapr_tce_create._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('page_shift', ctypes.c_uint32), + ('__resv1', ctypes.c_uint32), + ('window_size', ctypes.c_uint64), + ('levels', ctypes.c_uint32), + ('__resv2', ctypes.c_uint32), + ('start_addr', ctypes.c_uint64), +] + +class struct_vfio_iommu_spapr_tce_remove(Structure): + pass + +struct_vfio_iommu_spapr_tce_remove._pack_ = 1 # source:False +struct_vfio_iommu_spapr_tce_remove._fields_ = [ + ('argsz', ctypes.c_uint32), + ('flags', ctypes.c_uint32), + ('start_addr', ctypes.c_uint64), +] + +__all__ = \ + ['VFIO_API_VERSION', 'VFIO_BASE', 'VFIO_CCW_CONFIG_REGION_INDEX', + 'VFIO_CCW_CRW_IRQ_INDEX', 'VFIO_CCW_IO_IRQ_INDEX', + 'VFIO_CCW_NUM_IRQS', 'VFIO_CCW_NUM_REGIONS', + 'VFIO_CCW_REQ_IRQ_INDEX', 'VFIO_DEVICE_API_AMBA_STRING', + 'VFIO_DEVICE_API_AP_STRING', 'VFIO_DEVICE_API_CCW_STRING', + 'VFIO_DEVICE_API_PCI_STRING', 'VFIO_DEVICE_API_PLATFORM_STRING', + 'VFIO_DEVICE_FEATURE_GET', 'VFIO_DEVICE_FEATURE_MASK', + 'VFIO_DEVICE_FEATURE_PCI_VF_TOKEN', 'VFIO_DEVICE_FEATURE_PROBE', + 'VFIO_DEVICE_FEATURE_SET', 'VFIO_DEVICE_FLAGS_AMBA', + 'VFIO_DEVICE_FLAGS_AP', 'VFIO_DEVICE_FLAGS_CAPS', + 'VFIO_DEVICE_FLAGS_CCW', 'VFIO_DEVICE_FLAGS_FSL_MC', + 'VFIO_DEVICE_FLAGS_PCI', 'VFIO_DEVICE_FLAGS_PLATFORM', + 'VFIO_DEVICE_FLAGS_RESET', 'VFIO_DEVICE_GFX_LINK_STATE_DOWN', + 'VFIO_DEVICE_GFX_LINK_STATE_UP', 'VFIO_DEVICE_INFO_CAP_ZPCI_BASE', + 'VFIO_DEVICE_INFO_CAP_ZPCI_GROUP', + 'VFIO_DEVICE_INFO_CAP_ZPCI_PFIP', + 'VFIO_DEVICE_INFO_CAP_ZPCI_UTIL', 'VFIO_DEVICE_IOEVENTFD_16', + 'VFIO_DEVICE_IOEVENTFD_32', 'VFIO_DEVICE_IOEVENTFD_64', + 'VFIO_DEVICE_IOEVENTFD_8', 'VFIO_DEVICE_IOEVENTFD_SIZE_MASK', + 'VFIO_DEVICE_STATE_MASK', 'VFIO_DEVICE_STATE_RESUMING', + 'VFIO_DEVICE_STATE_RUNNING', 'VFIO_DEVICE_STATE_SAVING', + 'VFIO_DEVICE_STATE_STOP', 'VFIO_DMA_CC_IOMMU', + 'VFIO_DMA_MAP_FLAG_READ', 'VFIO_DMA_MAP_FLAG_VADDR', + 'VFIO_DMA_MAP_FLAG_WRITE', 'VFIO_DMA_UNMAP_FLAG_ALL', + 'VFIO_DMA_UNMAP_FLAG_GET_DIRTY_BITMAP', + 'VFIO_DMA_UNMAP_FLAG_VADDR', 'VFIO_EEH', 'VFIO_EEH_PE_CONFIGURE', + 'VFIO_EEH_PE_DISABLE', 'VFIO_EEH_PE_ENABLE', + 'VFIO_EEH_PE_GET_STATE', 'VFIO_EEH_PE_INJECT_ERR', + 'VFIO_EEH_PE_RESET_DEACTIVATE', 'VFIO_EEH_PE_RESET_FUNDAMENTAL', + 'VFIO_EEH_PE_RESET_HOT', 'VFIO_EEH_PE_STATE_NORMAL', + 'VFIO_EEH_PE_STATE_RESET', 'VFIO_EEH_PE_STATE_STOPPED', + 'VFIO_EEH_PE_STATE_STOPPED_DMA', 'VFIO_EEH_PE_STATE_UNAVAIL', + 'VFIO_EEH_PE_UNFREEZE_DMA', 'VFIO_EEH_PE_UNFREEZE_IO', + 'VFIO_GFX_PLANE_TYPE_DMABUF', 'VFIO_GFX_PLANE_TYPE_PROBE', + 'VFIO_GFX_PLANE_TYPE_REGION', 'VFIO_GROUP_FLAGS_CONTAINER_SET', + 'VFIO_GROUP_FLAGS_VIABLE', 'VFIO_H', + 'VFIO_IOMMU_DIRTY_PAGES_FLAG_GET_BITMAP', + 'VFIO_IOMMU_DIRTY_PAGES_FLAG_START', + 'VFIO_IOMMU_DIRTY_PAGES_FLAG_STOP', 'VFIO_IOMMU_INFO_CAPS', + 'VFIO_IOMMU_INFO_PGSIZES', 'VFIO_IOMMU_SPAPR_INFO_DDW', + 'VFIO_IOMMU_TYPE1_INFO_CAP_IOVA_RANGE', + 'VFIO_IOMMU_TYPE1_INFO_CAP_MIGRATION', + 'VFIO_IOMMU_TYPE1_INFO_DMA_AVAIL', 'VFIO_IRQ_INFO_AUTOMASKED', + 'VFIO_IRQ_INFO_EVENTFD', 'VFIO_IRQ_INFO_MASKABLE', + 'VFIO_IRQ_INFO_NORESIZE', 'VFIO_IRQ_SET_ACTION_MASK', + 'VFIO_IRQ_SET_ACTION_TRIGGER', 'VFIO_IRQ_SET_ACTION_TYPE_MASK', + 'VFIO_IRQ_SET_ACTION_UNMASK', 'VFIO_IRQ_SET_DATA_BOOL', + 'VFIO_IRQ_SET_DATA_EVENTFD', 'VFIO_IRQ_SET_DATA_NONE', + 'VFIO_IRQ_SET_DATA_TYPE_MASK', 'VFIO_NOIOMMU_IOMMU', + 'VFIO_PCI_BAR0_REGION_INDEX', 'VFIO_PCI_BAR1_REGION_INDEX', + 'VFIO_PCI_BAR2_REGION_INDEX', 'VFIO_PCI_BAR3_REGION_INDEX', + 'VFIO_PCI_BAR4_REGION_INDEX', 'VFIO_PCI_BAR5_REGION_INDEX', + 'VFIO_PCI_CONFIG_REGION_INDEX', 'VFIO_PCI_ERR_IRQ_INDEX', + 'VFIO_PCI_INTX_IRQ_INDEX', 'VFIO_PCI_MSIX_IRQ_INDEX', + 'VFIO_PCI_MSI_IRQ_INDEX', 'VFIO_PCI_NUM_IRQS', + 'VFIO_PCI_NUM_REGIONS', 'VFIO_PCI_REQ_IRQ_INDEX', + 'VFIO_PCI_ROM_REGION_INDEX', 'VFIO_PCI_VGA_REGION_INDEX', + 'VFIO_REGION_INFO_CAP_MSIX_MAPPABLE', + 'VFIO_REGION_INFO_CAP_NVLINK2_LNKSPD', + 'VFIO_REGION_INFO_CAP_NVLINK2_SSATGT', + 'VFIO_REGION_INFO_CAP_SPARSE_MMAP', 'VFIO_REGION_INFO_CAP_TYPE', + 'VFIO_REGION_INFO_FLAG_CAPS', 'VFIO_REGION_INFO_FLAG_MMAP', + 'VFIO_REGION_INFO_FLAG_READ', 'VFIO_REGION_INFO_FLAG_WRITE', + 'VFIO_REGION_SUBTYPE_CCW_ASYNC_CMD', + 'VFIO_REGION_SUBTYPE_CCW_CRW', 'VFIO_REGION_SUBTYPE_CCW_SCHIB', + 'VFIO_REGION_SUBTYPE_GFX_EDID', + 'VFIO_REGION_SUBTYPE_IBM_NVLINK2_ATSD', + 'VFIO_REGION_SUBTYPE_INTEL_IGD_HOST_CFG', + 'VFIO_REGION_SUBTYPE_INTEL_IGD_LPC_CFG', + 'VFIO_REGION_SUBTYPE_INTEL_IGD_OPREGION', + 'VFIO_REGION_SUBTYPE_MIGRATION', + 'VFIO_REGION_SUBTYPE_NVIDIA_NVLINK2_RAM', 'VFIO_REGION_TYPE_CCW', + 'VFIO_REGION_TYPE_GFX', 'VFIO_REGION_TYPE_MIGRATION', + 'VFIO_REGION_TYPE_PCI_VENDOR_MASK', + 'VFIO_REGION_TYPE_PCI_VENDOR_TYPE', 'VFIO_SPAPR_TCE_IOMMU', + 'VFIO_SPAPR_TCE_v2_IOMMU', 'VFIO_TYPE', 'VFIO_TYPE1_IOMMU', + 'VFIO_TYPE1_NESTING_IOMMU', 'VFIO_TYPE1v2_IOMMU', + 'VFIO_UNMAP_ALL', 'VFIO_UPDATE_VADDR', '_IO', '_IOR', '_IOW', + '_IOWR', 'c__Ea_VFIO_CCW_CONFIG_REGION_INDEX', + 'c__Ea_VFIO_CCW_IO_IRQ_INDEX', 'c__Ea_VFIO_PCI_BAR0_REGION_INDEX', + 'c__Ea_VFIO_PCI_INTX_IRQ_INDEX', 'struct_vfio_bitmap', + 'struct_vfio_device_feature', 'struct_vfio_device_gfx_plane_info', + 'struct_vfio_device_info', 'struct_vfio_device_ioeventfd', + 'struct_vfio_device_migration_info', 'struct_vfio_eeh_pe_err', + 'struct_vfio_eeh_pe_op', 'struct_vfio_group_status', + 'struct_vfio_info_cap_header', + 'struct_vfio_iommu_spapr_register_memory', + 'struct_vfio_iommu_spapr_tce_create', + 'struct_vfio_iommu_spapr_tce_ddw_info', + 'struct_vfio_iommu_spapr_tce_info', + 'struct_vfio_iommu_spapr_tce_remove', + 'struct_vfio_iommu_type1_dirty_bitmap', + 'struct_vfio_iommu_type1_dirty_bitmap_get', + 'struct_vfio_iommu_type1_dma_map', + 'struct_vfio_iommu_type1_dma_unmap', + 'struct_vfio_iommu_type1_info', + 'struct_vfio_iommu_type1_info_cap_iova_range', + 'struct_vfio_iommu_type1_info_cap_migration', + 'struct_vfio_iommu_type1_info_dma_avail', + 'struct_vfio_iova_range', 'struct_vfio_irq_info', + 'struct_vfio_irq_set', 'struct_vfio_pci_dependent_device', + 'struct_vfio_pci_hot_reset', 'struct_vfio_pci_hot_reset_info', + 'struct_vfio_region_gfx_edid', 'struct_vfio_region_info', + 'struct_vfio_region_info_cap_nvlink2_lnkspd', + 'struct_vfio_region_info_cap_nvlink2_ssatgt', + 'struct_vfio_region_info_cap_sparse_mmap', + 'struct_vfio_region_info_cap_type', + 'struct_vfio_region_sparse_mmap_area', + 'union_vfio_device_gfx_plane_info_0', 'union_vfio_eeh_pe_op_0'] diff --git a/tinygrad_repo/tinygrad/runtime/autogen/webgpu.py b/tinygrad_repo/tinygrad/runtime/autogen/webgpu.py new file mode 100644 index 0000000000..a1bd4c7565 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/autogen/webgpu.py @@ -0,0 +1,6994 @@ +# mypy: ignore-errors +# -*- coding: utf-8 -*- +# +# TARGET arch is: [] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes, tinygrad.runtime.support.webgpu as webgpu_support + + +class AsDictMixin: + @classmethod + def as_dict(cls, self): + result = {} + if not isinstance(self, AsDictMixin): + # not a structure, assume it's already a python object + return self + if not hasattr(cls, "_fields_"): + return result + # sys.version_info >= (3, 5) + # for (field, *_) in cls._fields_: # noqa + for field_tuple in cls._fields_: # noqa + field = field_tuple[0] + if field.startswith('PADDING_'): + continue + value = getattr(self, field) + type_ = type(value) + if hasattr(value, "_length_") and hasattr(value, "_type_"): + # array + if not hasattr(type_, "as_dict"): + value = [v for v in value] + else: + type_ = type_._type_ + value = [type_.as_dict(v) for v in value] + elif hasattr(value, "contents") and hasattr(value, "_type_"): + # pointer + try: + if not hasattr(type_, "as_dict"): + value = value.contents + else: + type_ = type_._type_ + value = type_.as_dict(value.contents) + except ValueError: + # nullptr + value = None + elif isinstance(value, AsDictMixin): + # other structure + value = type_.as_dict(value) + result[field] = value + return result + + +class Structure(ctypes.Structure, AsDictMixin): + + def __init__(self, *args, **kwds): + # We don't want to use positional arguments fill PADDING_* fields + + args = dict(zip(self.__class__._field_names_(), args)) + args.update(kwds) + super(Structure, self).__init__(**args) + + @classmethod + def _field_names_(cls): + if hasattr(cls, '_fields_'): + return (f[0] for f in cls._fields_ if not f[0].startswith('PADDING')) + else: + return () + + @classmethod + def get_type(cls, field): + for f in cls._fields_: + if f[0] == field: + return f[1] + return None + + @classmethod + def bind(cls, bound_fields): + fields = {} + for name, type_ in cls._fields_: + if hasattr(type_, "restype"): + if name in bound_fields: + if bound_fields[name] is None: + fields[name] = type_() + else: + # use a closure to capture the callback from the loop scope + fields[name] = ( + type_((lambda callback: lambda *args: callback(*args))( + bound_fields[name])) + ) + del bound_fields[name] + else: + # default callback implementation (does nothing) + try: + default_ = type_(0).restype().value + except TypeError: + default_ = None + fields[name] = type_(( + lambda default_: lambda *args: default_)(default_)) + else: + # not a callback function, use default initialization + if name in bound_fields: + fields[name] = bound_fields[name] + del bound_fields[name] + else: + fields[name] = type_() + if len(bound_fields) != 0: + raise ValueError( + "Cannot bind the following unknown callback(s) {}.{}".format( + cls.__name__, bound_fields.keys() + )) + return cls(**fields) + + +class Union(ctypes.Union, AsDictMixin): + pass + + + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + +def string_cast(char_pointer, encoding='utf-8', errors='strict'): + value = ctypes.cast(char_pointer, ctypes.c_char_p).value + if value is not None and encoding is not None: + value = value.decode(encoding, errors=errors) + return value + + +def char_pointer_cast(string, encoding='utf-8'): + if encoding is not None: + try: + string = string.encode(encoding) + except AttributeError: + # In Python3, bytes has no encode attribute + pass + string = ctypes.c_char_p(string) + return ctypes.cast(string, ctypes.POINTER(ctypes.c_char)) + + + +class FunctionFactoryStub: + def __getattr__(self, _): + return ctypes.CFUNCTYPE(lambda y:y) + +# libraries['webgpu'] explanation +# As you did not list (-l libraryname.so) a library that exports this function +# This is a non-working stub instead. +# You can either re-run clan2py with -l /path/to/library.so +# Or manually fix this by comment the ctypes.CDLL loading +_libraries = {} +_libraries['webgpu'] = ctypes.CDLL(webgpu_support.WEBGPU_PATH) # ctypes.CDLL('webgpu') + + +WGPUFlags = ctypes.c_uint64 +WGPUBool = ctypes.c_uint32 +class struct_WGPUAdapterImpl(Structure): + pass + +WGPUAdapter = ctypes.POINTER(struct_WGPUAdapterImpl) +class struct_WGPUBindGroupImpl(Structure): + pass + +WGPUBindGroup = ctypes.POINTER(struct_WGPUBindGroupImpl) +class struct_WGPUBindGroupLayoutImpl(Structure): + pass + +WGPUBindGroupLayout = ctypes.POINTER(struct_WGPUBindGroupLayoutImpl) +class struct_WGPUBufferImpl(Structure): + pass + +WGPUBuffer = ctypes.POINTER(struct_WGPUBufferImpl) +class struct_WGPUCommandBufferImpl(Structure): + pass + +WGPUCommandBuffer = ctypes.POINTER(struct_WGPUCommandBufferImpl) +class struct_WGPUCommandEncoderImpl(Structure): + pass + +WGPUCommandEncoder = ctypes.POINTER(struct_WGPUCommandEncoderImpl) +class struct_WGPUComputePassEncoderImpl(Structure): + pass + +WGPUComputePassEncoder = ctypes.POINTER(struct_WGPUComputePassEncoderImpl) +class struct_WGPUComputePipelineImpl(Structure): + pass + +WGPUComputePipeline = ctypes.POINTER(struct_WGPUComputePipelineImpl) +class struct_WGPUDeviceImpl(Structure): + pass + +WGPUDevice = ctypes.POINTER(struct_WGPUDeviceImpl) +class struct_WGPUExternalTextureImpl(Structure): + pass + +WGPUExternalTexture = ctypes.POINTER(struct_WGPUExternalTextureImpl) +class struct_WGPUInstanceImpl(Structure): + pass + +WGPUInstance = ctypes.POINTER(struct_WGPUInstanceImpl) +class struct_WGPUPipelineLayoutImpl(Structure): + pass + +WGPUPipelineLayout = ctypes.POINTER(struct_WGPUPipelineLayoutImpl) +class struct_WGPUQuerySetImpl(Structure): + pass + +WGPUQuerySet = ctypes.POINTER(struct_WGPUQuerySetImpl) +class struct_WGPUQueueImpl(Structure): + pass + +WGPUQueue = ctypes.POINTER(struct_WGPUQueueImpl) +class struct_WGPURenderBundleImpl(Structure): + pass + +WGPURenderBundle = ctypes.POINTER(struct_WGPURenderBundleImpl) +class struct_WGPURenderBundleEncoderImpl(Structure): + pass + +WGPURenderBundleEncoder = ctypes.POINTER(struct_WGPURenderBundleEncoderImpl) +class struct_WGPURenderPassEncoderImpl(Structure): + pass + +WGPURenderPassEncoder = ctypes.POINTER(struct_WGPURenderPassEncoderImpl) +class struct_WGPURenderPipelineImpl(Structure): + pass + +WGPURenderPipeline = ctypes.POINTER(struct_WGPURenderPipelineImpl) +class struct_WGPUSamplerImpl(Structure): + pass + +WGPUSampler = ctypes.POINTER(struct_WGPUSamplerImpl) +class struct_WGPUShaderModuleImpl(Structure): + pass + +WGPUShaderModule = ctypes.POINTER(struct_WGPUShaderModuleImpl) +class struct_WGPUSharedBufferMemoryImpl(Structure): + pass + +WGPUSharedBufferMemory = ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl) +class struct_WGPUSharedFenceImpl(Structure): + pass + +WGPUSharedFence = ctypes.POINTER(struct_WGPUSharedFenceImpl) +class struct_WGPUSharedTextureMemoryImpl(Structure): + pass + +WGPUSharedTextureMemory = ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl) +class struct_WGPUSurfaceImpl(Structure): + pass + +WGPUSurface = ctypes.POINTER(struct_WGPUSurfaceImpl) +class struct_WGPUTextureImpl(Structure): + pass + +WGPUTexture = ctypes.POINTER(struct_WGPUTextureImpl) +class struct_WGPUTextureViewImpl(Structure): + pass + +WGPUTextureView = ctypes.POINTER(struct_WGPUTextureViewImpl) + +# values for enumeration 'WGPUWGSLFeatureName' +WGPUWGSLFeatureName__enumvalues = { + 1: 'WGPUWGSLFeatureName_ReadonlyAndReadwriteStorageTextures', + 2: 'WGPUWGSLFeatureName_Packed4x8IntegerDotProduct', + 3: 'WGPUWGSLFeatureName_UnrestrictedPointerParameters', + 4: 'WGPUWGSLFeatureName_PointerCompositeAccess', + 327680: 'WGPUWGSLFeatureName_ChromiumTestingUnimplemented', + 327681: 'WGPUWGSLFeatureName_ChromiumTestingUnsafeExperimental', + 327682: 'WGPUWGSLFeatureName_ChromiumTestingExperimental', + 327683: 'WGPUWGSLFeatureName_ChromiumTestingShippedWithKillswitch', + 327684: 'WGPUWGSLFeatureName_ChromiumTestingShipped', + 2147483647: 'WGPUWGSLFeatureName_Force32', +} +WGPUWGSLFeatureName_ReadonlyAndReadwriteStorageTextures = 1 +WGPUWGSLFeatureName_Packed4x8IntegerDotProduct = 2 +WGPUWGSLFeatureName_UnrestrictedPointerParameters = 3 +WGPUWGSLFeatureName_PointerCompositeAccess = 4 +WGPUWGSLFeatureName_ChromiumTestingUnimplemented = 327680 +WGPUWGSLFeatureName_ChromiumTestingUnsafeExperimental = 327681 +WGPUWGSLFeatureName_ChromiumTestingExperimental = 327682 +WGPUWGSLFeatureName_ChromiumTestingShippedWithKillswitch = 327683 +WGPUWGSLFeatureName_ChromiumTestingShipped = 327684 +WGPUWGSLFeatureName_Force32 = 2147483647 +WGPUWGSLFeatureName = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUAdapterType' +WGPUAdapterType__enumvalues = { + 1: 'WGPUAdapterType_DiscreteGPU', + 2: 'WGPUAdapterType_IntegratedGPU', + 3: 'WGPUAdapterType_CPU', + 4: 'WGPUAdapterType_Unknown', + 2147483647: 'WGPUAdapterType_Force32', +} +WGPUAdapterType_DiscreteGPU = 1 +WGPUAdapterType_IntegratedGPU = 2 +WGPUAdapterType_CPU = 3 +WGPUAdapterType_Unknown = 4 +WGPUAdapterType_Force32 = 2147483647 +WGPUAdapterType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUAddressMode' +WGPUAddressMode__enumvalues = { + 0: 'WGPUAddressMode_Undefined', + 1: 'WGPUAddressMode_ClampToEdge', + 2: 'WGPUAddressMode_Repeat', + 3: 'WGPUAddressMode_MirrorRepeat', + 2147483647: 'WGPUAddressMode_Force32', +} +WGPUAddressMode_Undefined = 0 +WGPUAddressMode_ClampToEdge = 1 +WGPUAddressMode_Repeat = 2 +WGPUAddressMode_MirrorRepeat = 3 +WGPUAddressMode_Force32 = 2147483647 +WGPUAddressMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUAlphaMode' +WGPUAlphaMode__enumvalues = { + 1: 'WGPUAlphaMode_Opaque', + 2: 'WGPUAlphaMode_Premultiplied', + 3: 'WGPUAlphaMode_Unpremultiplied', + 2147483647: 'WGPUAlphaMode_Force32', +} +WGPUAlphaMode_Opaque = 1 +WGPUAlphaMode_Premultiplied = 2 +WGPUAlphaMode_Unpremultiplied = 3 +WGPUAlphaMode_Force32 = 2147483647 +WGPUAlphaMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBackendType' +WGPUBackendType__enumvalues = { + 0: 'WGPUBackendType_Undefined', + 1: 'WGPUBackendType_Null', + 2: 'WGPUBackendType_WebGPU', + 3: 'WGPUBackendType_D3D11', + 4: 'WGPUBackendType_D3D12', + 5: 'WGPUBackendType_Metal', + 6: 'WGPUBackendType_Vulkan', + 7: 'WGPUBackendType_OpenGL', + 8: 'WGPUBackendType_OpenGLES', + 2147483647: 'WGPUBackendType_Force32', +} +WGPUBackendType_Undefined = 0 +WGPUBackendType_Null = 1 +WGPUBackendType_WebGPU = 2 +WGPUBackendType_D3D11 = 3 +WGPUBackendType_D3D12 = 4 +WGPUBackendType_Metal = 5 +WGPUBackendType_Vulkan = 6 +WGPUBackendType_OpenGL = 7 +WGPUBackendType_OpenGLES = 8 +WGPUBackendType_Force32 = 2147483647 +WGPUBackendType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBlendFactor' +WGPUBlendFactor__enumvalues = { + 0: 'WGPUBlendFactor_Undefined', + 1: 'WGPUBlendFactor_Zero', + 2: 'WGPUBlendFactor_One', + 3: 'WGPUBlendFactor_Src', + 4: 'WGPUBlendFactor_OneMinusSrc', + 5: 'WGPUBlendFactor_SrcAlpha', + 6: 'WGPUBlendFactor_OneMinusSrcAlpha', + 7: 'WGPUBlendFactor_Dst', + 8: 'WGPUBlendFactor_OneMinusDst', + 9: 'WGPUBlendFactor_DstAlpha', + 10: 'WGPUBlendFactor_OneMinusDstAlpha', + 11: 'WGPUBlendFactor_SrcAlphaSaturated', + 12: 'WGPUBlendFactor_Constant', + 13: 'WGPUBlendFactor_OneMinusConstant', + 14: 'WGPUBlendFactor_Src1', + 15: 'WGPUBlendFactor_OneMinusSrc1', + 16: 'WGPUBlendFactor_Src1Alpha', + 17: 'WGPUBlendFactor_OneMinusSrc1Alpha', + 2147483647: 'WGPUBlendFactor_Force32', +} +WGPUBlendFactor_Undefined = 0 +WGPUBlendFactor_Zero = 1 +WGPUBlendFactor_One = 2 +WGPUBlendFactor_Src = 3 +WGPUBlendFactor_OneMinusSrc = 4 +WGPUBlendFactor_SrcAlpha = 5 +WGPUBlendFactor_OneMinusSrcAlpha = 6 +WGPUBlendFactor_Dst = 7 +WGPUBlendFactor_OneMinusDst = 8 +WGPUBlendFactor_DstAlpha = 9 +WGPUBlendFactor_OneMinusDstAlpha = 10 +WGPUBlendFactor_SrcAlphaSaturated = 11 +WGPUBlendFactor_Constant = 12 +WGPUBlendFactor_OneMinusConstant = 13 +WGPUBlendFactor_Src1 = 14 +WGPUBlendFactor_OneMinusSrc1 = 15 +WGPUBlendFactor_Src1Alpha = 16 +WGPUBlendFactor_OneMinusSrc1Alpha = 17 +WGPUBlendFactor_Force32 = 2147483647 +WGPUBlendFactor = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBlendOperation' +WGPUBlendOperation__enumvalues = { + 0: 'WGPUBlendOperation_Undefined', + 1: 'WGPUBlendOperation_Add', + 2: 'WGPUBlendOperation_Subtract', + 3: 'WGPUBlendOperation_ReverseSubtract', + 4: 'WGPUBlendOperation_Min', + 5: 'WGPUBlendOperation_Max', + 2147483647: 'WGPUBlendOperation_Force32', +} +WGPUBlendOperation_Undefined = 0 +WGPUBlendOperation_Add = 1 +WGPUBlendOperation_Subtract = 2 +WGPUBlendOperation_ReverseSubtract = 3 +WGPUBlendOperation_Min = 4 +WGPUBlendOperation_Max = 5 +WGPUBlendOperation_Force32 = 2147483647 +WGPUBlendOperation = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBufferBindingType' +WGPUBufferBindingType__enumvalues = { + 0: 'WGPUBufferBindingType_BindingNotUsed', + 1: 'WGPUBufferBindingType_Uniform', + 2: 'WGPUBufferBindingType_Storage', + 3: 'WGPUBufferBindingType_ReadOnlyStorage', + 2147483647: 'WGPUBufferBindingType_Force32', +} +WGPUBufferBindingType_BindingNotUsed = 0 +WGPUBufferBindingType_Uniform = 1 +WGPUBufferBindingType_Storage = 2 +WGPUBufferBindingType_ReadOnlyStorage = 3 +WGPUBufferBindingType_Force32 = 2147483647 +WGPUBufferBindingType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBufferMapAsyncStatus' +WGPUBufferMapAsyncStatus__enumvalues = { + 1: 'WGPUBufferMapAsyncStatus_Success', + 2: 'WGPUBufferMapAsyncStatus_InstanceDropped', + 3: 'WGPUBufferMapAsyncStatus_ValidationError', + 4: 'WGPUBufferMapAsyncStatus_Unknown', + 5: 'WGPUBufferMapAsyncStatus_DeviceLost', + 6: 'WGPUBufferMapAsyncStatus_DestroyedBeforeCallback', + 7: 'WGPUBufferMapAsyncStatus_UnmappedBeforeCallback', + 8: 'WGPUBufferMapAsyncStatus_MappingAlreadyPending', + 9: 'WGPUBufferMapAsyncStatus_OffsetOutOfRange', + 10: 'WGPUBufferMapAsyncStatus_SizeOutOfRange', + 2147483647: 'WGPUBufferMapAsyncStatus_Force32', +} +WGPUBufferMapAsyncStatus_Success = 1 +WGPUBufferMapAsyncStatus_InstanceDropped = 2 +WGPUBufferMapAsyncStatus_ValidationError = 3 +WGPUBufferMapAsyncStatus_Unknown = 4 +WGPUBufferMapAsyncStatus_DeviceLost = 5 +WGPUBufferMapAsyncStatus_DestroyedBeforeCallback = 6 +WGPUBufferMapAsyncStatus_UnmappedBeforeCallback = 7 +WGPUBufferMapAsyncStatus_MappingAlreadyPending = 8 +WGPUBufferMapAsyncStatus_OffsetOutOfRange = 9 +WGPUBufferMapAsyncStatus_SizeOutOfRange = 10 +WGPUBufferMapAsyncStatus_Force32 = 2147483647 +WGPUBufferMapAsyncStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUBufferMapState' +WGPUBufferMapState__enumvalues = { + 1: 'WGPUBufferMapState_Unmapped', + 2: 'WGPUBufferMapState_Pending', + 3: 'WGPUBufferMapState_Mapped', + 2147483647: 'WGPUBufferMapState_Force32', +} +WGPUBufferMapState_Unmapped = 1 +WGPUBufferMapState_Pending = 2 +WGPUBufferMapState_Mapped = 3 +WGPUBufferMapState_Force32 = 2147483647 +WGPUBufferMapState = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCallbackMode' +WGPUCallbackMode__enumvalues = { + 1: 'WGPUCallbackMode_WaitAnyOnly', + 2: 'WGPUCallbackMode_AllowProcessEvents', + 3: 'WGPUCallbackMode_AllowSpontaneous', + 2147483647: 'WGPUCallbackMode_Force32', +} +WGPUCallbackMode_WaitAnyOnly = 1 +WGPUCallbackMode_AllowProcessEvents = 2 +WGPUCallbackMode_AllowSpontaneous = 3 +WGPUCallbackMode_Force32 = 2147483647 +WGPUCallbackMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCompareFunction' +WGPUCompareFunction__enumvalues = { + 0: 'WGPUCompareFunction_Undefined', + 1: 'WGPUCompareFunction_Never', + 2: 'WGPUCompareFunction_Less', + 3: 'WGPUCompareFunction_Equal', + 4: 'WGPUCompareFunction_LessEqual', + 5: 'WGPUCompareFunction_Greater', + 6: 'WGPUCompareFunction_NotEqual', + 7: 'WGPUCompareFunction_GreaterEqual', + 8: 'WGPUCompareFunction_Always', + 2147483647: 'WGPUCompareFunction_Force32', +} +WGPUCompareFunction_Undefined = 0 +WGPUCompareFunction_Never = 1 +WGPUCompareFunction_Less = 2 +WGPUCompareFunction_Equal = 3 +WGPUCompareFunction_LessEqual = 4 +WGPUCompareFunction_Greater = 5 +WGPUCompareFunction_NotEqual = 6 +WGPUCompareFunction_GreaterEqual = 7 +WGPUCompareFunction_Always = 8 +WGPUCompareFunction_Force32 = 2147483647 +WGPUCompareFunction = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCompilationInfoRequestStatus' +WGPUCompilationInfoRequestStatus__enumvalues = { + 1: 'WGPUCompilationInfoRequestStatus_Success', + 2: 'WGPUCompilationInfoRequestStatus_InstanceDropped', + 3: 'WGPUCompilationInfoRequestStatus_Error', + 4: 'WGPUCompilationInfoRequestStatus_DeviceLost', + 5: 'WGPUCompilationInfoRequestStatus_Unknown', + 2147483647: 'WGPUCompilationInfoRequestStatus_Force32', +} +WGPUCompilationInfoRequestStatus_Success = 1 +WGPUCompilationInfoRequestStatus_InstanceDropped = 2 +WGPUCompilationInfoRequestStatus_Error = 3 +WGPUCompilationInfoRequestStatus_DeviceLost = 4 +WGPUCompilationInfoRequestStatus_Unknown = 5 +WGPUCompilationInfoRequestStatus_Force32 = 2147483647 +WGPUCompilationInfoRequestStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCompilationMessageType' +WGPUCompilationMessageType__enumvalues = { + 1: 'WGPUCompilationMessageType_Error', + 2: 'WGPUCompilationMessageType_Warning', + 3: 'WGPUCompilationMessageType_Info', + 2147483647: 'WGPUCompilationMessageType_Force32', +} +WGPUCompilationMessageType_Error = 1 +WGPUCompilationMessageType_Warning = 2 +WGPUCompilationMessageType_Info = 3 +WGPUCompilationMessageType_Force32 = 2147483647 +WGPUCompilationMessageType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCompositeAlphaMode' +WGPUCompositeAlphaMode__enumvalues = { + 0: 'WGPUCompositeAlphaMode_Auto', + 1: 'WGPUCompositeAlphaMode_Opaque', + 2: 'WGPUCompositeAlphaMode_Premultiplied', + 3: 'WGPUCompositeAlphaMode_Unpremultiplied', + 4: 'WGPUCompositeAlphaMode_Inherit', + 2147483647: 'WGPUCompositeAlphaMode_Force32', +} +WGPUCompositeAlphaMode_Auto = 0 +WGPUCompositeAlphaMode_Opaque = 1 +WGPUCompositeAlphaMode_Premultiplied = 2 +WGPUCompositeAlphaMode_Unpremultiplied = 3 +WGPUCompositeAlphaMode_Inherit = 4 +WGPUCompositeAlphaMode_Force32 = 2147483647 +WGPUCompositeAlphaMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCreatePipelineAsyncStatus' +WGPUCreatePipelineAsyncStatus__enumvalues = { + 1: 'WGPUCreatePipelineAsyncStatus_Success', + 2: 'WGPUCreatePipelineAsyncStatus_InstanceDropped', + 3: 'WGPUCreatePipelineAsyncStatus_ValidationError', + 4: 'WGPUCreatePipelineAsyncStatus_InternalError', + 5: 'WGPUCreatePipelineAsyncStatus_DeviceLost', + 6: 'WGPUCreatePipelineAsyncStatus_DeviceDestroyed', + 7: 'WGPUCreatePipelineAsyncStatus_Unknown', + 2147483647: 'WGPUCreatePipelineAsyncStatus_Force32', +} +WGPUCreatePipelineAsyncStatus_Success = 1 +WGPUCreatePipelineAsyncStatus_InstanceDropped = 2 +WGPUCreatePipelineAsyncStatus_ValidationError = 3 +WGPUCreatePipelineAsyncStatus_InternalError = 4 +WGPUCreatePipelineAsyncStatus_DeviceLost = 5 +WGPUCreatePipelineAsyncStatus_DeviceDestroyed = 6 +WGPUCreatePipelineAsyncStatus_Unknown = 7 +WGPUCreatePipelineAsyncStatus_Force32 = 2147483647 +WGPUCreatePipelineAsyncStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUCullMode' +WGPUCullMode__enumvalues = { + 0: 'WGPUCullMode_Undefined', + 1: 'WGPUCullMode_None', + 2: 'WGPUCullMode_Front', + 3: 'WGPUCullMode_Back', + 2147483647: 'WGPUCullMode_Force32', +} +WGPUCullMode_Undefined = 0 +WGPUCullMode_None = 1 +WGPUCullMode_Front = 2 +WGPUCullMode_Back = 3 +WGPUCullMode_Force32 = 2147483647 +WGPUCullMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUDeviceLostReason' +WGPUDeviceLostReason__enumvalues = { + 1: 'WGPUDeviceLostReason_Unknown', + 2: 'WGPUDeviceLostReason_Destroyed', + 3: 'WGPUDeviceLostReason_InstanceDropped', + 4: 'WGPUDeviceLostReason_FailedCreation', + 2147483647: 'WGPUDeviceLostReason_Force32', +} +WGPUDeviceLostReason_Unknown = 1 +WGPUDeviceLostReason_Destroyed = 2 +WGPUDeviceLostReason_InstanceDropped = 3 +WGPUDeviceLostReason_FailedCreation = 4 +WGPUDeviceLostReason_Force32 = 2147483647 +WGPUDeviceLostReason = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUErrorFilter' +WGPUErrorFilter__enumvalues = { + 1: 'WGPUErrorFilter_Validation', + 2: 'WGPUErrorFilter_OutOfMemory', + 3: 'WGPUErrorFilter_Internal', + 2147483647: 'WGPUErrorFilter_Force32', +} +WGPUErrorFilter_Validation = 1 +WGPUErrorFilter_OutOfMemory = 2 +WGPUErrorFilter_Internal = 3 +WGPUErrorFilter_Force32 = 2147483647 +WGPUErrorFilter = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUErrorType' +WGPUErrorType__enumvalues = { + 1: 'WGPUErrorType_NoError', + 2: 'WGPUErrorType_Validation', + 3: 'WGPUErrorType_OutOfMemory', + 4: 'WGPUErrorType_Internal', + 5: 'WGPUErrorType_Unknown', + 6: 'WGPUErrorType_DeviceLost', + 2147483647: 'WGPUErrorType_Force32', +} +WGPUErrorType_NoError = 1 +WGPUErrorType_Validation = 2 +WGPUErrorType_OutOfMemory = 3 +WGPUErrorType_Internal = 4 +WGPUErrorType_Unknown = 5 +WGPUErrorType_DeviceLost = 6 +WGPUErrorType_Force32 = 2147483647 +WGPUErrorType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUExternalTextureRotation' +WGPUExternalTextureRotation__enumvalues = { + 1: 'WGPUExternalTextureRotation_Rotate0Degrees', + 2: 'WGPUExternalTextureRotation_Rotate90Degrees', + 3: 'WGPUExternalTextureRotation_Rotate180Degrees', + 4: 'WGPUExternalTextureRotation_Rotate270Degrees', + 2147483647: 'WGPUExternalTextureRotation_Force32', +} +WGPUExternalTextureRotation_Rotate0Degrees = 1 +WGPUExternalTextureRotation_Rotate90Degrees = 2 +WGPUExternalTextureRotation_Rotate180Degrees = 3 +WGPUExternalTextureRotation_Rotate270Degrees = 4 +WGPUExternalTextureRotation_Force32 = 2147483647 +WGPUExternalTextureRotation = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUFeatureLevel' +WGPUFeatureLevel__enumvalues = { + 0: 'WGPUFeatureLevel_Undefined', + 1: 'WGPUFeatureLevel_Compatibility', + 2: 'WGPUFeatureLevel_Core', + 2147483647: 'WGPUFeatureLevel_Force32', +} +WGPUFeatureLevel_Undefined = 0 +WGPUFeatureLevel_Compatibility = 1 +WGPUFeatureLevel_Core = 2 +WGPUFeatureLevel_Force32 = 2147483647 +WGPUFeatureLevel = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUFeatureName' +WGPUFeatureName__enumvalues = { + 1: 'WGPUFeatureName_DepthClipControl', + 2: 'WGPUFeatureName_Depth32FloatStencil8', + 3: 'WGPUFeatureName_TimestampQuery', + 4: 'WGPUFeatureName_TextureCompressionBC', + 5: 'WGPUFeatureName_TextureCompressionETC2', + 6: 'WGPUFeatureName_TextureCompressionASTC', + 7: 'WGPUFeatureName_IndirectFirstInstance', + 8: 'WGPUFeatureName_ShaderF16', + 9: 'WGPUFeatureName_RG11B10UfloatRenderable', + 10: 'WGPUFeatureName_BGRA8UnormStorage', + 11: 'WGPUFeatureName_Float32Filterable', + 12: 'WGPUFeatureName_Float32Blendable', + 13: 'WGPUFeatureName_Subgroups', + 14: 'WGPUFeatureName_SubgroupsF16', + 327680: 'WGPUFeatureName_DawnInternalUsages', + 327681: 'WGPUFeatureName_DawnMultiPlanarFormats', + 327682: 'WGPUFeatureName_DawnNative', + 327683: 'WGPUFeatureName_ChromiumExperimentalTimestampQueryInsidePasses', + 327684: 'WGPUFeatureName_ImplicitDeviceSynchronization', + 327685: 'WGPUFeatureName_ChromiumExperimentalImmediateData', + 327686: 'WGPUFeatureName_TransientAttachments', + 327687: 'WGPUFeatureName_MSAARenderToSingleSampled', + 327688: 'WGPUFeatureName_DualSourceBlending', + 327689: 'WGPUFeatureName_D3D11MultithreadProtected', + 327690: 'WGPUFeatureName_ANGLETextureSharing', + 327691: 'WGPUFeatureName_PixelLocalStorageCoherent', + 327692: 'WGPUFeatureName_PixelLocalStorageNonCoherent', + 327693: 'WGPUFeatureName_Unorm16TextureFormats', + 327694: 'WGPUFeatureName_Snorm16TextureFormats', + 327695: 'WGPUFeatureName_MultiPlanarFormatExtendedUsages', + 327696: 'WGPUFeatureName_MultiPlanarFormatP010', + 327697: 'WGPUFeatureName_HostMappedPointer', + 327698: 'WGPUFeatureName_MultiPlanarRenderTargets', + 327699: 'WGPUFeatureName_MultiPlanarFormatNv12a', + 327700: 'WGPUFeatureName_FramebufferFetch', + 327701: 'WGPUFeatureName_BufferMapExtendedUsages', + 327702: 'WGPUFeatureName_AdapterPropertiesMemoryHeaps', + 327703: 'WGPUFeatureName_AdapterPropertiesD3D', + 327704: 'WGPUFeatureName_AdapterPropertiesVk', + 327705: 'WGPUFeatureName_R8UnormStorage', + 327706: 'WGPUFeatureName_FormatCapabilities', + 327707: 'WGPUFeatureName_DrmFormatCapabilities', + 327708: 'WGPUFeatureName_Norm16TextureFormats', + 327709: 'WGPUFeatureName_MultiPlanarFormatNv16', + 327710: 'WGPUFeatureName_MultiPlanarFormatNv24', + 327711: 'WGPUFeatureName_MultiPlanarFormatP210', + 327712: 'WGPUFeatureName_MultiPlanarFormatP410', + 327713: 'WGPUFeatureName_SharedTextureMemoryVkDedicatedAllocation', + 327714: 'WGPUFeatureName_SharedTextureMemoryAHardwareBuffer', + 327715: 'WGPUFeatureName_SharedTextureMemoryDmaBuf', + 327716: 'WGPUFeatureName_SharedTextureMemoryOpaqueFD', + 327717: 'WGPUFeatureName_SharedTextureMemoryZirconHandle', + 327718: 'WGPUFeatureName_SharedTextureMemoryDXGISharedHandle', + 327719: 'WGPUFeatureName_SharedTextureMemoryD3D11Texture2D', + 327720: 'WGPUFeatureName_SharedTextureMemoryIOSurface', + 327721: 'WGPUFeatureName_SharedTextureMemoryEGLImage', + 327722: 'WGPUFeatureName_SharedFenceVkSemaphoreOpaqueFD', + 327723: 'WGPUFeatureName_SharedFenceSyncFD', + 327724: 'WGPUFeatureName_SharedFenceVkSemaphoreZirconHandle', + 327725: 'WGPUFeatureName_SharedFenceDXGISharedHandle', + 327726: 'WGPUFeatureName_SharedFenceMTLSharedEvent', + 327727: 'WGPUFeatureName_SharedBufferMemoryD3D12Resource', + 327728: 'WGPUFeatureName_StaticSamplers', + 327729: 'WGPUFeatureName_YCbCrVulkanSamplers', + 327730: 'WGPUFeatureName_ShaderModuleCompilationOptions', + 327731: 'WGPUFeatureName_DawnLoadResolveTexture', + 327732: 'WGPUFeatureName_DawnPartialLoadResolveTexture', + 327733: 'WGPUFeatureName_MultiDrawIndirect', + 327734: 'WGPUFeatureName_ClipDistances', + 327735: 'WGPUFeatureName_DawnTexelCopyBufferRowAlignment', + 327736: 'WGPUFeatureName_FlexibleTextureViews', + 2147483647: 'WGPUFeatureName_Force32', +} +WGPUFeatureName_DepthClipControl = 1 +WGPUFeatureName_Depth32FloatStencil8 = 2 +WGPUFeatureName_TimestampQuery = 3 +WGPUFeatureName_TextureCompressionBC = 4 +WGPUFeatureName_TextureCompressionETC2 = 5 +WGPUFeatureName_TextureCompressionASTC = 6 +WGPUFeatureName_IndirectFirstInstance = 7 +WGPUFeatureName_ShaderF16 = 8 +WGPUFeatureName_RG11B10UfloatRenderable = 9 +WGPUFeatureName_BGRA8UnormStorage = 10 +WGPUFeatureName_Float32Filterable = 11 +WGPUFeatureName_Float32Blendable = 12 +WGPUFeatureName_Subgroups = 13 +WGPUFeatureName_SubgroupsF16 = 14 +WGPUFeatureName_DawnInternalUsages = 327680 +WGPUFeatureName_DawnMultiPlanarFormats = 327681 +WGPUFeatureName_DawnNative = 327682 +WGPUFeatureName_ChromiumExperimentalTimestampQueryInsidePasses = 327683 +WGPUFeatureName_ImplicitDeviceSynchronization = 327684 +WGPUFeatureName_ChromiumExperimentalImmediateData = 327685 +WGPUFeatureName_TransientAttachments = 327686 +WGPUFeatureName_MSAARenderToSingleSampled = 327687 +WGPUFeatureName_DualSourceBlending = 327688 +WGPUFeatureName_D3D11MultithreadProtected = 327689 +WGPUFeatureName_ANGLETextureSharing = 327690 +WGPUFeatureName_PixelLocalStorageCoherent = 327691 +WGPUFeatureName_PixelLocalStorageNonCoherent = 327692 +WGPUFeatureName_Unorm16TextureFormats = 327693 +WGPUFeatureName_Snorm16TextureFormats = 327694 +WGPUFeatureName_MultiPlanarFormatExtendedUsages = 327695 +WGPUFeatureName_MultiPlanarFormatP010 = 327696 +WGPUFeatureName_HostMappedPointer = 327697 +WGPUFeatureName_MultiPlanarRenderTargets = 327698 +WGPUFeatureName_MultiPlanarFormatNv12a = 327699 +WGPUFeatureName_FramebufferFetch = 327700 +WGPUFeatureName_BufferMapExtendedUsages = 327701 +WGPUFeatureName_AdapterPropertiesMemoryHeaps = 327702 +WGPUFeatureName_AdapterPropertiesD3D = 327703 +WGPUFeatureName_AdapterPropertiesVk = 327704 +WGPUFeatureName_R8UnormStorage = 327705 +WGPUFeatureName_FormatCapabilities = 327706 +WGPUFeatureName_DrmFormatCapabilities = 327707 +WGPUFeatureName_Norm16TextureFormats = 327708 +WGPUFeatureName_MultiPlanarFormatNv16 = 327709 +WGPUFeatureName_MultiPlanarFormatNv24 = 327710 +WGPUFeatureName_MultiPlanarFormatP210 = 327711 +WGPUFeatureName_MultiPlanarFormatP410 = 327712 +WGPUFeatureName_SharedTextureMemoryVkDedicatedAllocation = 327713 +WGPUFeatureName_SharedTextureMemoryAHardwareBuffer = 327714 +WGPUFeatureName_SharedTextureMemoryDmaBuf = 327715 +WGPUFeatureName_SharedTextureMemoryOpaqueFD = 327716 +WGPUFeatureName_SharedTextureMemoryZirconHandle = 327717 +WGPUFeatureName_SharedTextureMemoryDXGISharedHandle = 327718 +WGPUFeatureName_SharedTextureMemoryD3D11Texture2D = 327719 +WGPUFeatureName_SharedTextureMemoryIOSurface = 327720 +WGPUFeatureName_SharedTextureMemoryEGLImage = 327721 +WGPUFeatureName_SharedFenceVkSemaphoreOpaqueFD = 327722 +WGPUFeatureName_SharedFenceSyncFD = 327723 +WGPUFeatureName_SharedFenceVkSemaphoreZirconHandle = 327724 +WGPUFeatureName_SharedFenceDXGISharedHandle = 327725 +WGPUFeatureName_SharedFenceMTLSharedEvent = 327726 +WGPUFeatureName_SharedBufferMemoryD3D12Resource = 327727 +WGPUFeatureName_StaticSamplers = 327728 +WGPUFeatureName_YCbCrVulkanSamplers = 327729 +WGPUFeatureName_ShaderModuleCompilationOptions = 327730 +WGPUFeatureName_DawnLoadResolveTexture = 327731 +WGPUFeatureName_DawnPartialLoadResolveTexture = 327732 +WGPUFeatureName_MultiDrawIndirect = 327733 +WGPUFeatureName_ClipDistances = 327734 +WGPUFeatureName_DawnTexelCopyBufferRowAlignment = 327735 +WGPUFeatureName_FlexibleTextureViews = 327736 +WGPUFeatureName_Force32 = 2147483647 +WGPUFeatureName = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUFilterMode' +WGPUFilterMode__enumvalues = { + 0: 'WGPUFilterMode_Undefined', + 1: 'WGPUFilterMode_Nearest', + 2: 'WGPUFilterMode_Linear', + 2147483647: 'WGPUFilterMode_Force32', +} +WGPUFilterMode_Undefined = 0 +WGPUFilterMode_Nearest = 1 +WGPUFilterMode_Linear = 2 +WGPUFilterMode_Force32 = 2147483647 +WGPUFilterMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUFrontFace' +WGPUFrontFace__enumvalues = { + 0: 'WGPUFrontFace_Undefined', + 1: 'WGPUFrontFace_CCW', + 2: 'WGPUFrontFace_CW', + 2147483647: 'WGPUFrontFace_Force32', +} +WGPUFrontFace_Undefined = 0 +WGPUFrontFace_CCW = 1 +WGPUFrontFace_CW = 2 +WGPUFrontFace_Force32 = 2147483647 +WGPUFrontFace = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUIndexFormat' +WGPUIndexFormat__enumvalues = { + 0: 'WGPUIndexFormat_Undefined', + 1: 'WGPUIndexFormat_Uint16', + 2: 'WGPUIndexFormat_Uint32', + 2147483647: 'WGPUIndexFormat_Force32', +} +WGPUIndexFormat_Undefined = 0 +WGPUIndexFormat_Uint16 = 1 +WGPUIndexFormat_Uint32 = 2 +WGPUIndexFormat_Force32 = 2147483647 +WGPUIndexFormat = ctypes.c_uint32 # enum + +# values for enumeration 'WGPULoadOp' +WGPULoadOp__enumvalues = { + 0: 'WGPULoadOp_Undefined', + 1: 'WGPULoadOp_Load', + 2: 'WGPULoadOp_Clear', + 327683: 'WGPULoadOp_ExpandResolveTexture', + 2147483647: 'WGPULoadOp_Force32', +} +WGPULoadOp_Undefined = 0 +WGPULoadOp_Load = 1 +WGPULoadOp_Clear = 2 +WGPULoadOp_ExpandResolveTexture = 327683 +WGPULoadOp_Force32 = 2147483647 +WGPULoadOp = ctypes.c_uint32 # enum + +# values for enumeration 'WGPULoggingType' +WGPULoggingType__enumvalues = { + 1: 'WGPULoggingType_Verbose', + 2: 'WGPULoggingType_Info', + 3: 'WGPULoggingType_Warning', + 4: 'WGPULoggingType_Error', + 2147483647: 'WGPULoggingType_Force32', +} +WGPULoggingType_Verbose = 1 +WGPULoggingType_Info = 2 +WGPULoggingType_Warning = 3 +WGPULoggingType_Error = 4 +WGPULoggingType_Force32 = 2147483647 +WGPULoggingType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUMapAsyncStatus' +WGPUMapAsyncStatus__enumvalues = { + 1: 'WGPUMapAsyncStatus_Success', + 2: 'WGPUMapAsyncStatus_InstanceDropped', + 3: 'WGPUMapAsyncStatus_Error', + 4: 'WGPUMapAsyncStatus_Aborted', + 5: 'WGPUMapAsyncStatus_Unknown', + 2147483647: 'WGPUMapAsyncStatus_Force32', +} +WGPUMapAsyncStatus_Success = 1 +WGPUMapAsyncStatus_InstanceDropped = 2 +WGPUMapAsyncStatus_Error = 3 +WGPUMapAsyncStatus_Aborted = 4 +WGPUMapAsyncStatus_Unknown = 5 +WGPUMapAsyncStatus_Force32 = 2147483647 +WGPUMapAsyncStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUMipmapFilterMode' +WGPUMipmapFilterMode__enumvalues = { + 0: 'WGPUMipmapFilterMode_Undefined', + 1: 'WGPUMipmapFilterMode_Nearest', + 2: 'WGPUMipmapFilterMode_Linear', + 2147483647: 'WGPUMipmapFilterMode_Force32', +} +WGPUMipmapFilterMode_Undefined = 0 +WGPUMipmapFilterMode_Nearest = 1 +WGPUMipmapFilterMode_Linear = 2 +WGPUMipmapFilterMode_Force32 = 2147483647 +WGPUMipmapFilterMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUOptionalBool' +WGPUOptionalBool__enumvalues = { + 0: 'WGPUOptionalBool_False', + 1: 'WGPUOptionalBool_True', + 2: 'WGPUOptionalBool_Undefined', + 2147483647: 'WGPUOptionalBool_Force32', +} +WGPUOptionalBool_False = 0 +WGPUOptionalBool_True = 1 +WGPUOptionalBool_Undefined = 2 +WGPUOptionalBool_Force32 = 2147483647 +WGPUOptionalBool = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUPopErrorScopeStatus' +WGPUPopErrorScopeStatus__enumvalues = { + 1: 'WGPUPopErrorScopeStatus_Success', + 2: 'WGPUPopErrorScopeStatus_InstanceDropped', + 2147483647: 'WGPUPopErrorScopeStatus_Force32', +} +WGPUPopErrorScopeStatus_Success = 1 +WGPUPopErrorScopeStatus_InstanceDropped = 2 +WGPUPopErrorScopeStatus_Force32 = 2147483647 +WGPUPopErrorScopeStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUPowerPreference' +WGPUPowerPreference__enumvalues = { + 0: 'WGPUPowerPreference_Undefined', + 1: 'WGPUPowerPreference_LowPower', + 2: 'WGPUPowerPreference_HighPerformance', + 2147483647: 'WGPUPowerPreference_Force32', +} +WGPUPowerPreference_Undefined = 0 +WGPUPowerPreference_LowPower = 1 +WGPUPowerPreference_HighPerformance = 2 +WGPUPowerPreference_Force32 = 2147483647 +WGPUPowerPreference = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUPresentMode' +WGPUPresentMode__enumvalues = { + 1: 'WGPUPresentMode_Fifo', + 2: 'WGPUPresentMode_FifoRelaxed', + 3: 'WGPUPresentMode_Immediate', + 4: 'WGPUPresentMode_Mailbox', + 2147483647: 'WGPUPresentMode_Force32', +} +WGPUPresentMode_Fifo = 1 +WGPUPresentMode_FifoRelaxed = 2 +WGPUPresentMode_Immediate = 3 +WGPUPresentMode_Mailbox = 4 +WGPUPresentMode_Force32 = 2147483647 +WGPUPresentMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUPrimitiveTopology' +WGPUPrimitiveTopology__enumvalues = { + 0: 'WGPUPrimitiveTopology_Undefined', + 1: 'WGPUPrimitiveTopology_PointList', + 2: 'WGPUPrimitiveTopology_LineList', + 3: 'WGPUPrimitiveTopology_LineStrip', + 4: 'WGPUPrimitiveTopology_TriangleList', + 5: 'WGPUPrimitiveTopology_TriangleStrip', + 2147483647: 'WGPUPrimitiveTopology_Force32', +} +WGPUPrimitiveTopology_Undefined = 0 +WGPUPrimitiveTopology_PointList = 1 +WGPUPrimitiveTopology_LineList = 2 +WGPUPrimitiveTopology_LineStrip = 3 +WGPUPrimitiveTopology_TriangleList = 4 +WGPUPrimitiveTopology_TriangleStrip = 5 +WGPUPrimitiveTopology_Force32 = 2147483647 +WGPUPrimitiveTopology = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUQueryType' +WGPUQueryType__enumvalues = { + 1: 'WGPUQueryType_Occlusion', + 2: 'WGPUQueryType_Timestamp', + 2147483647: 'WGPUQueryType_Force32', +} +WGPUQueryType_Occlusion = 1 +WGPUQueryType_Timestamp = 2 +WGPUQueryType_Force32 = 2147483647 +WGPUQueryType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUQueueWorkDoneStatus' +WGPUQueueWorkDoneStatus__enumvalues = { + 1: 'WGPUQueueWorkDoneStatus_Success', + 2: 'WGPUQueueWorkDoneStatus_InstanceDropped', + 3: 'WGPUQueueWorkDoneStatus_Error', + 4: 'WGPUQueueWorkDoneStatus_Unknown', + 5: 'WGPUQueueWorkDoneStatus_DeviceLost', + 2147483647: 'WGPUQueueWorkDoneStatus_Force32', +} +WGPUQueueWorkDoneStatus_Success = 1 +WGPUQueueWorkDoneStatus_InstanceDropped = 2 +WGPUQueueWorkDoneStatus_Error = 3 +WGPUQueueWorkDoneStatus_Unknown = 4 +WGPUQueueWorkDoneStatus_DeviceLost = 5 +WGPUQueueWorkDoneStatus_Force32 = 2147483647 +WGPUQueueWorkDoneStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPURequestAdapterStatus' +WGPURequestAdapterStatus__enumvalues = { + 1: 'WGPURequestAdapterStatus_Success', + 2: 'WGPURequestAdapterStatus_InstanceDropped', + 3: 'WGPURequestAdapterStatus_Unavailable', + 4: 'WGPURequestAdapterStatus_Error', + 5: 'WGPURequestAdapterStatus_Unknown', + 2147483647: 'WGPURequestAdapterStatus_Force32', +} +WGPURequestAdapterStatus_Success = 1 +WGPURequestAdapterStatus_InstanceDropped = 2 +WGPURequestAdapterStatus_Unavailable = 3 +WGPURequestAdapterStatus_Error = 4 +WGPURequestAdapterStatus_Unknown = 5 +WGPURequestAdapterStatus_Force32 = 2147483647 +WGPURequestAdapterStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPURequestDeviceStatus' +WGPURequestDeviceStatus__enumvalues = { + 1: 'WGPURequestDeviceStatus_Success', + 2: 'WGPURequestDeviceStatus_InstanceDropped', + 3: 'WGPURequestDeviceStatus_Error', + 4: 'WGPURequestDeviceStatus_Unknown', + 2147483647: 'WGPURequestDeviceStatus_Force32', +} +WGPURequestDeviceStatus_Success = 1 +WGPURequestDeviceStatus_InstanceDropped = 2 +WGPURequestDeviceStatus_Error = 3 +WGPURequestDeviceStatus_Unknown = 4 +WGPURequestDeviceStatus_Force32 = 2147483647 +WGPURequestDeviceStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUSType' +WGPUSType__enumvalues = { + 1: 'WGPUSType_ShaderSourceSPIRV', + 2: 'WGPUSType_ShaderSourceWGSL', + 3: 'WGPUSType_RenderPassMaxDrawCount', + 4: 'WGPUSType_SurfaceSourceMetalLayer', + 5: 'WGPUSType_SurfaceSourceWindowsHWND', + 6: 'WGPUSType_SurfaceSourceXlibWindow', + 7: 'WGPUSType_SurfaceSourceWaylandSurface', + 8: 'WGPUSType_SurfaceSourceAndroidNativeWindow', + 9: 'WGPUSType_SurfaceSourceXCBWindow', + 10: 'WGPUSType_AdapterPropertiesSubgroups', + 131072: 'WGPUSType_TextureBindingViewDimensionDescriptor', + 262144: 'WGPUSType_SurfaceSourceCanvasHTMLSelector_Emscripten', + 327680: 'WGPUSType_SurfaceDescriptorFromWindowsCoreWindow', + 327681: 'WGPUSType_ExternalTextureBindingEntry', + 327682: 'WGPUSType_ExternalTextureBindingLayout', + 327683: 'WGPUSType_SurfaceDescriptorFromWindowsSwapChainPanel', + 327684: 'WGPUSType_DawnTextureInternalUsageDescriptor', + 327685: 'WGPUSType_DawnEncoderInternalUsageDescriptor', + 327686: 'WGPUSType_DawnInstanceDescriptor', + 327687: 'WGPUSType_DawnCacheDeviceDescriptor', + 327688: 'WGPUSType_DawnAdapterPropertiesPowerPreference', + 327689: 'WGPUSType_DawnBufferDescriptorErrorInfoFromWireClient', + 327690: 'WGPUSType_DawnTogglesDescriptor', + 327691: 'WGPUSType_DawnShaderModuleSPIRVOptionsDescriptor', + 327692: 'WGPUSType_RequestAdapterOptionsLUID', + 327693: 'WGPUSType_RequestAdapterOptionsGetGLProc', + 327694: 'WGPUSType_RequestAdapterOptionsD3D11Device', + 327695: 'WGPUSType_DawnRenderPassColorAttachmentRenderToSingleSampled', + 327696: 'WGPUSType_RenderPassPixelLocalStorage', + 327697: 'WGPUSType_PipelineLayoutPixelLocalStorage', + 327698: 'WGPUSType_BufferHostMappedPointer', + 327699: 'WGPUSType_DawnExperimentalSubgroupLimits', + 327700: 'WGPUSType_AdapterPropertiesMemoryHeaps', + 327701: 'WGPUSType_AdapterPropertiesD3D', + 327702: 'WGPUSType_AdapterPropertiesVk', + 327703: 'WGPUSType_DawnWireWGSLControl', + 327704: 'WGPUSType_DawnWGSLBlocklist', + 327705: 'WGPUSType_DrmFormatCapabilities', + 327706: 'WGPUSType_ShaderModuleCompilationOptions', + 327707: 'WGPUSType_ColorTargetStateExpandResolveTextureDawn', + 327708: 'WGPUSType_RenderPassDescriptorExpandResolveRect', + 327709: 'WGPUSType_SharedTextureMemoryVkDedicatedAllocationDescriptor', + 327710: 'WGPUSType_SharedTextureMemoryAHardwareBufferDescriptor', + 327711: 'WGPUSType_SharedTextureMemoryDmaBufDescriptor', + 327712: 'WGPUSType_SharedTextureMemoryOpaqueFDDescriptor', + 327713: 'WGPUSType_SharedTextureMemoryZirconHandleDescriptor', + 327714: 'WGPUSType_SharedTextureMemoryDXGISharedHandleDescriptor', + 327715: 'WGPUSType_SharedTextureMemoryD3D11Texture2DDescriptor', + 327716: 'WGPUSType_SharedTextureMemoryIOSurfaceDescriptor', + 327717: 'WGPUSType_SharedTextureMemoryEGLImageDescriptor', + 327718: 'WGPUSType_SharedTextureMemoryInitializedBeginState', + 327719: 'WGPUSType_SharedTextureMemoryInitializedEndState', + 327720: 'WGPUSType_SharedTextureMemoryVkImageLayoutBeginState', + 327721: 'WGPUSType_SharedTextureMemoryVkImageLayoutEndState', + 327722: 'WGPUSType_SharedTextureMemoryD3DSwapchainBeginState', + 327723: 'WGPUSType_SharedFenceVkSemaphoreOpaqueFDDescriptor', + 327724: 'WGPUSType_SharedFenceVkSemaphoreOpaqueFDExportInfo', + 327725: 'WGPUSType_SharedFenceSyncFDDescriptor', + 327726: 'WGPUSType_SharedFenceSyncFDExportInfo', + 327727: 'WGPUSType_SharedFenceVkSemaphoreZirconHandleDescriptor', + 327728: 'WGPUSType_SharedFenceVkSemaphoreZirconHandleExportInfo', + 327729: 'WGPUSType_SharedFenceDXGISharedHandleDescriptor', + 327730: 'WGPUSType_SharedFenceDXGISharedHandleExportInfo', + 327731: 'WGPUSType_SharedFenceMTLSharedEventDescriptor', + 327732: 'WGPUSType_SharedFenceMTLSharedEventExportInfo', + 327733: 'WGPUSType_SharedBufferMemoryD3D12ResourceDescriptor', + 327734: 'WGPUSType_StaticSamplerBindingLayout', + 327735: 'WGPUSType_YCbCrVkDescriptor', + 327736: 'WGPUSType_SharedTextureMemoryAHardwareBufferProperties', + 327737: 'WGPUSType_AHardwareBufferProperties', + 327738: 'WGPUSType_DawnExperimentalImmediateDataLimits', + 327739: 'WGPUSType_DawnTexelCopyBufferRowAlignmentLimits', + 2147483647: 'WGPUSType_Force32', +} +WGPUSType_ShaderSourceSPIRV = 1 +WGPUSType_ShaderSourceWGSL = 2 +WGPUSType_RenderPassMaxDrawCount = 3 +WGPUSType_SurfaceSourceMetalLayer = 4 +WGPUSType_SurfaceSourceWindowsHWND = 5 +WGPUSType_SurfaceSourceXlibWindow = 6 +WGPUSType_SurfaceSourceWaylandSurface = 7 +WGPUSType_SurfaceSourceAndroidNativeWindow = 8 +WGPUSType_SurfaceSourceXCBWindow = 9 +WGPUSType_AdapterPropertiesSubgroups = 10 +WGPUSType_TextureBindingViewDimensionDescriptor = 131072 +WGPUSType_SurfaceSourceCanvasHTMLSelector_Emscripten = 262144 +WGPUSType_SurfaceDescriptorFromWindowsCoreWindow = 327680 +WGPUSType_ExternalTextureBindingEntry = 327681 +WGPUSType_ExternalTextureBindingLayout = 327682 +WGPUSType_SurfaceDescriptorFromWindowsSwapChainPanel = 327683 +WGPUSType_DawnTextureInternalUsageDescriptor = 327684 +WGPUSType_DawnEncoderInternalUsageDescriptor = 327685 +WGPUSType_DawnInstanceDescriptor = 327686 +WGPUSType_DawnCacheDeviceDescriptor = 327687 +WGPUSType_DawnAdapterPropertiesPowerPreference = 327688 +WGPUSType_DawnBufferDescriptorErrorInfoFromWireClient = 327689 +WGPUSType_DawnTogglesDescriptor = 327690 +WGPUSType_DawnShaderModuleSPIRVOptionsDescriptor = 327691 +WGPUSType_RequestAdapterOptionsLUID = 327692 +WGPUSType_RequestAdapterOptionsGetGLProc = 327693 +WGPUSType_RequestAdapterOptionsD3D11Device = 327694 +WGPUSType_DawnRenderPassColorAttachmentRenderToSingleSampled = 327695 +WGPUSType_RenderPassPixelLocalStorage = 327696 +WGPUSType_PipelineLayoutPixelLocalStorage = 327697 +WGPUSType_BufferHostMappedPointer = 327698 +WGPUSType_DawnExperimentalSubgroupLimits = 327699 +WGPUSType_AdapterPropertiesMemoryHeaps = 327700 +WGPUSType_AdapterPropertiesD3D = 327701 +WGPUSType_AdapterPropertiesVk = 327702 +WGPUSType_DawnWireWGSLControl = 327703 +WGPUSType_DawnWGSLBlocklist = 327704 +WGPUSType_DrmFormatCapabilities = 327705 +WGPUSType_ShaderModuleCompilationOptions = 327706 +WGPUSType_ColorTargetStateExpandResolveTextureDawn = 327707 +WGPUSType_RenderPassDescriptorExpandResolveRect = 327708 +WGPUSType_SharedTextureMemoryVkDedicatedAllocationDescriptor = 327709 +WGPUSType_SharedTextureMemoryAHardwareBufferDescriptor = 327710 +WGPUSType_SharedTextureMemoryDmaBufDescriptor = 327711 +WGPUSType_SharedTextureMemoryOpaqueFDDescriptor = 327712 +WGPUSType_SharedTextureMemoryZirconHandleDescriptor = 327713 +WGPUSType_SharedTextureMemoryDXGISharedHandleDescriptor = 327714 +WGPUSType_SharedTextureMemoryD3D11Texture2DDescriptor = 327715 +WGPUSType_SharedTextureMemoryIOSurfaceDescriptor = 327716 +WGPUSType_SharedTextureMemoryEGLImageDescriptor = 327717 +WGPUSType_SharedTextureMemoryInitializedBeginState = 327718 +WGPUSType_SharedTextureMemoryInitializedEndState = 327719 +WGPUSType_SharedTextureMemoryVkImageLayoutBeginState = 327720 +WGPUSType_SharedTextureMemoryVkImageLayoutEndState = 327721 +WGPUSType_SharedTextureMemoryD3DSwapchainBeginState = 327722 +WGPUSType_SharedFenceVkSemaphoreOpaqueFDDescriptor = 327723 +WGPUSType_SharedFenceVkSemaphoreOpaqueFDExportInfo = 327724 +WGPUSType_SharedFenceSyncFDDescriptor = 327725 +WGPUSType_SharedFenceSyncFDExportInfo = 327726 +WGPUSType_SharedFenceVkSemaphoreZirconHandleDescriptor = 327727 +WGPUSType_SharedFenceVkSemaphoreZirconHandleExportInfo = 327728 +WGPUSType_SharedFenceDXGISharedHandleDescriptor = 327729 +WGPUSType_SharedFenceDXGISharedHandleExportInfo = 327730 +WGPUSType_SharedFenceMTLSharedEventDescriptor = 327731 +WGPUSType_SharedFenceMTLSharedEventExportInfo = 327732 +WGPUSType_SharedBufferMemoryD3D12ResourceDescriptor = 327733 +WGPUSType_StaticSamplerBindingLayout = 327734 +WGPUSType_YCbCrVkDescriptor = 327735 +WGPUSType_SharedTextureMemoryAHardwareBufferProperties = 327736 +WGPUSType_AHardwareBufferProperties = 327737 +WGPUSType_DawnExperimentalImmediateDataLimits = 327738 +WGPUSType_DawnTexelCopyBufferRowAlignmentLimits = 327739 +WGPUSType_Force32 = 2147483647 +WGPUSType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUSamplerBindingType' +WGPUSamplerBindingType__enumvalues = { + 0: 'WGPUSamplerBindingType_BindingNotUsed', + 1: 'WGPUSamplerBindingType_Filtering', + 2: 'WGPUSamplerBindingType_NonFiltering', + 3: 'WGPUSamplerBindingType_Comparison', + 2147483647: 'WGPUSamplerBindingType_Force32', +} +WGPUSamplerBindingType_BindingNotUsed = 0 +WGPUSamplerBindingType_Filtering = 1 +WGPUSamplerBindingType_NonFiltering = 2 +WGPUSamplerBindingType_Comparison = 3 +WGPUSamplerBindingType_Force32 = 2147483647 +WGPUSamplerBindingType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUSharedFenceType' +WGPUSharedFenceType__enumvalues = { + 1: 'WGPUSharedFenceType_VkSemaphoreOpaqueFD', + 2: 'WGPUSharedFenceType_SyncFD', + 3: 'WGPUSharedFenceType_VkSemaphoreZirconHandle', + 4: 'WGPUSharedFenceType_DXGISharedHandle', + 5: 'WGPUSharedFenceType_MTLSharedEvent', + 2147483647: 'WGPUSharedFenceType_Force32', +} +WGPUSharedFenceType_VkSemaphoreOpaqueFD = 1 +WGPUSharedFenceType_SyncFD = 2 +WGPUSharedFenceType_VkSemaphoreZirconHandle = 3 +WGPUSharedFenceType_DXGISharedHandle = 4 +WGPUSharedFenceType_MTLSharedEvent = 5 +WGPUSharedFenceType_Force32 = 2147483647 +WGPUSharedFenceType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUStatus' +WGPUStatus__enumvalues = { + 1: 'WGPUStatus_Success', + 2: 'WGPUStatus_Error', + 2147483647: 'WGPUStatus_Force32', +} +WGPUStatus_Success = 1 +WGPUStatus_Error = 2 +WGPUStatus_Force32 = 2147483647 +WGPUStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUStencilOperation' +WGPUStencilOperation__enumvalues = { + 0: 'WGPUStencilOperation_Undefined', + 1: 'WGPUStencilOperation_Keep', + 2: 'WGPUStencilOperation_Zero', + 3: 'WGPUStencilOperation_Replace', + 4: 'WGPUStencilOperation_Invert', + 5: 'WGPUStencilOperation_IncrementClamp', + 6: 'WGPUStencilOperation_DecrementClamp', + 7: 'WGPUStencilOperation_IncrementWrap', + 8: 'WGPUStencilOperation_DecrementWrap', + 2147483647: 'WGPUStencilOperation_Force32', +} +WGPUStencilOperation_Undefined = 0 +WGPUStencilOperation_Keep = 1 +WGPUStencilOperation_Zero = 2 +WGPUStencilOperation_Replace = 3 +WGPUStencilOperation_Invert = 4 +WGPUStencilOperation_IncrementClamp = 5 +WGPUStencilOperation_DecrementClamp = 6 +WGPUStencilOperation_IncrementWrap = 7 +WGPUStencilOperation_DecrementWrap = 8 +WGPUStencilOperation_Force32 = 2147483647 +WGPUStencilOperation = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUStorageTextureAccess' +WGPUStorageTextureAccess__enumvalues = { + 0: 'WGPUStorageTextureAccess_BindingNotUsed', + 1: 'WGPUStorageTextureAccess_WriteOnly', + 2: 'WGPUStorageTextureAccess_ReadOnly', + 3: 'WGPUStorageTextureAccess_ReadWrite', + 2147483647: 'WGPUStorageTextureAccess_Force32', +} +WGPUStorageTextureAccess_BindingNotUsed = 0 +WGPUStorageTextureAccess_WriteOnly = 1 +WGPUStorageTextureAccess_ReadOnly = 2 +WGPUStorageTextureAccess_ReadWrite = 3 +WGPUStorageTextureAccess_Force32 = 2147483647 +WGPUStorageTextureAccess = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUStoreOp' +WGPUStoreOp__enumvalues = { + 0: 'WGPUStoreOp_Undefined', + 1: 'WGPUStoreOp_Store', + 2: 'WGPUStoreOp_Discard', + 2147483647: 'WGPUStoreOp_Force32', +} +WGPUStoreOp_Undefined = 0 +WGPUStoreOp_Store = 1 +WGPUStoreOp_Discard = 2 +WGPUStoreOp_Force32 = 2147483647 +WGPUStoreOp = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUSurfaceGetCurrentTextureStatus' +WGPUSurfaceGetCurrentTextureStatus__enumvalues = { + 1: 'WGPUSurfaceGetCurrentTextureStatus_Success', + 2: 'WGPUSurfaceGetCurrentTextureStatus_Timeout', + 3: 'WGPUSurfaceGetCurrentTextureStatus_Outdated', + 4: 'WGPUSurfaceGetCurrentTextureStatus_Lost', + 5: 'WGPUSurfaceGetCurrentTextureStatus_OutOfMemory', + 6: 'WGPUSurfaceGetCurrentTextureStatus_DeviceLost', + 7: 'WGPUSurfaceGetCurrentTextureStatus_Error', + 2147483647: 'WGPUSurfaceGetCurrentTextureStatus_Force32', +} +WGPUSurfaceGetCurrentTextureStatus_Success = 1 +WGPUSurfaceGetCurrentTextureStatus_Timeout = 2 +WGPUSurfaceGetCurrentTextureStatus_Outdated = 3 +WGPUSurfaceGetCurrentTextureStatus_Lost = 4 +WGPUSurfaceGetCurrentTextureStatus_OutOfMemory = 5 +WGPUSurfaceGetCurrentTextureStatus_DeviceLost = 6 +WGPUSurfaceGetCurrentTextureStatus_Error = 7 +WGPUSurfaceGetCurrentTextureStatus_Force32 = 2147483647 +WGPUSurfaceGetCurrentTextureStatus = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUTextureAspect' +WGPUTextureAspect__enumvalues = { + 0: 'WGPUTextureAspect_Undefined', + 1: 'WGPUTextureAspect_All', + 2: 'WGPUTextureAspect_StencilOnly', + 3: 'WGPUTextureAspect_DepthOnly', + 327680: 'WGPUTextureAspect_Plane0Only', + 327681: 'WGPUTextureAspect_Plane1Only', + 327682: 'WGPUTextureAspect_Plane2Only', + 2147483647: 'WGPUTextureAspect_Force32', +} +WGPUTextureAspect_Undefined = 0 +WGPUTextureAspect_All = 1 +WGPUTextureAspect_StencilOnly = 2 +WGPUTextureAspect_DepthOnly = 3 +WGPUTextureAspect_Plane0Only = 327680 +WGPUTextureAspect_Plane1Only = 327681 +WGPUTextureAspect_Plane2Only = 327682 +WGPUTextureAspect_Force32 = 2147483647 +WGPUTextureAspect = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUTextureDimension' +WGPUTextureDimension__enumvalues = { + 0: 'WGPUTextureDimension_Undefined', + 1: 'WGPUTextureDimension_1D', + 2: 'WGPUTextureDimension_2D', + 3: 'WGPUTextureDimension_3D', + 2147483647: 'WGPUTextureDimension_Force32', +} +WGPUTextureDimension_Undefined = 0 +WGPUTextureDimension_1D = 1 +WGPUTextureDimension_2D = 2 +WGPUTextureDimension_3D = 3 +WGPUTextureDimension_Force32 = 2147483647 +WGPUTextureDimension = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUTextureFormat' +WGPUTextureFormat__enumvalues = { + 0: 'WGPUTextureFormat_Undefined', + 1: 'WGPUTextureFormat_R8Unorm', + 2: 'WGPUTextureFormat_R8Snorm', + 3: 'WGPUTextureFormat_R8Uint', + 4: 'WGPUTextureFormat_R8Sint', + 5: 'WGPUTextureFormat_R16Uint', + 6: 'WGPUTextureFormat_R16Sint', + 7: 'WGPUTextureFormat_R16Float', + 8: 'WGPUTextureFormat_RG8Unorm', + 9: 'WGPUTextureFormat_RG8Snorm', + 10: 'WGPUTextureFormat_RG8Uint', + 11: 'WGPUTextureFormat_RG8Sint', + 12: 'WGPUTextureFormat_R32Float', + 13: 'WGPUTextureFormat_R32Uint', + 14: 'WGPUTextureFormat_R32Sint', + 15: 'WGPUTextureFormat_RG16Uint', + 16: 'WGPUTextureFormat_RG16Sint', + 17: 'WGPUTextureFormat_RG16Float', + 18: 'WGPUTextureFormat_RGBA8Unorm', + 19: 'WGPUTextureFormat_RGBA8UnormSrgb', + 20: 'WGPUTextureFormat_RGBA8Snorm', + 21: 'WGPUTextureFormat_RGBA8Uint', + 22: 'WGPUTextureFormat_RGBA8Sint', + 23: 'WGPUTextureFormat_BGRA8Unorm', + 24: 'WGPUTextureFormat_BGRA8UnormSrgb', + 25: 'WGPUTextureFormat_RGB10A2Uint', + 26: 'WGPUTextureFormat_RGB10A2Unorm', + 27: 'WGPUTextureFormat_RG11B10Ufloat', + 28: 'WGPUTextureFormat_RGB9E5Ufloat', + 29: 'WGPUTextureFormat_RG32Float', + 30: 'WGPUTextureFormat_RG32Uint', + 31: 'WGPUTextureFormat_RG32Sint', + 32: 'WGPUTextureFormat_RGBA16Uint', + 33: 'WGPUTextureFormat_RGBA16Sint', + 34: 'WGPUTextureFormat_RGBA16Float', + 35: 'WGPUTextureFormat_RGBA32Float', + 36: 'WGPUTextureFormat_RGBA32Uint', + 37: 'WGPUTextureFormat_RGBA32Sint', + 38: 'WGPUTextureFormat_Stencil8', + 39: 'WGPUTextureFormat_Depth16Unorm', + 40: 'WGPUTextureFormat_Depth24Plus', + 41: 'WGPUTextureFormat_Depth24PlusStencil8', + 42: 'WGPUTextureFormat_Depth32Float', + 43: 'WGPUTextureFormat_Depth32FloatStencil8', + 44: 'WGPUTextureFormat_BC1RGBAUnorm', + 45: 'WGPUTextureFormat_BC1RGBAUnormSrgb', + 46: 'WGPUTextureFormat_BC2RGBAUnorm', + 47: 'WGPUTextureFormat_BC2RGBAUnormSrgb', + 48: 'WGPUTextureFormat_BC3RGBAUnorm', + 49: 'WGPUTextureFormat_BC3RGBAUnormSrgb', + 50: 'WGPUTextureFormat_BC4RUnorm', + 51: 'WGPUTextureFormat_BC4RSnorm', + 52: 'WGPUTextureFormat_BC5RGUnorm', + 53: 'WGPUTextureFormat_BC5RGSnorm', + 54: 'WGPUTextureFormat_BC6HRGBUfloat', + 55: 'WGPUTextureFormat_BC6HRGBFloat', + 56: 'WGPUTextureFormat_BC7RGBAUnorm', + 57: 'WGPUTextureFormat_BC7RGBAUnormSrgb', + 58: 'WGPUTextureFormat_ETC2RGB8Unorm', + 59: 'WGPUTextureFormat_ETC2RGB8UnormSrgb', + 60: 'WGPUTextureFormat_ETC2RGB8A1Unorm', + 61: 'WGPUTextureFormat_ETC2RGB8A1UnormSrgb', + 62: 'WGPUTextureFormat_ETC2RGBA8Unorm', + 63: 'WGPUTextureFormat_ETC2RGBA8UnormSrgb', + 64: 'WGPUTextureFormat_EACR11Unorm', + 65: 'WGPUTextureFormat_EACR11Snorm', + 66: 'WGPUTextureFormat_EACRG11Unorm', + 67: 'WGPUTextureFormat_EACRG11Snorm', + 68: 'WGPUTextureFormat_ASTC4x4Unorm', + 69: 'WGPUTextureFormat_ASTC4x4UnormSrgb', + 70: 'WGPUTextureFormat_ASTC5x4Unorm', + 71: 'WGPUTextureFormat_ASTC5x4UnormSrgb', + 72: 'WGPUTextureFormat_ASTC5x5Unorm', + 73: 'WGPUTextureFormat_ASTC5x5UnormSrgb', + 74: 'WGPUTextureFormat_ASTC6x5Unorm', + 75: 'WGPUTextureFormat_ASTC6x5UnormSrgb', + 76: 'WGPUTextureFormat_ASTC6x6Unorm', + 77: 'WGPUTextureFormat_ASTC6x6UnormSrgb', + 78: 'WGPUTextureFormat_ASTC8x5Unorm', + 79: 'WGPUTextureFormat_ASTC8x5UnormSrgb', + 80: 'WGPUTextureFormat_ASTC8x6Unorm', + 81: 'WGPUTextureFormat_ASTC8x6UnormSrgb', + 82: 'WGPUTextureFormat_ASTC8x8Unorm', + 83: 'WGPUTextureFormat_ASTC8x8UnormSrgb', + 84: 'WGPUTextureFormat_ASTC10x5Unorm', + 85: 'WGPUTextureFormat_ASTC10x5UnormSrgb', + 86: 'WGPUTextureFormat_ASTC10x6Unorm', + 87: 'WGPUTextureFormat_ASTC10x6UnormSrgb', + 88: 'WGPUTextureFormat_ASTC10x8Unorm', + 89: 'WGPUTextureFormat_ASTC10x8UnormSrgb', + 90: 'WGPUTextureFormat_ASTC10x10Unorm', + 91: 'WGPUTextureFormat_ASTC10x10UnormSrgb', + 92: 'WGPUTextureFormat_ASTC12x10Unorm', + 93: 'WGPUTextureFormat_ASTC12x10UnormSrgb', + 94: 'WGPUTextureFormat_ASTC12x12Unorm', + 95: 'WGPUTextureFormat_ASTC12x12UnormSrgb', + 327680: 'WGPUTextureFormat_R16Unorm', + 327681: 'WGPUTextureFormat_RG16Unorm', + 327682: 'WGPUTextureFormat_RGBA16Unorm', + 327683: 'WGPUTextureFormat_R16Snorm', + 327684: 'WGPUTextureFormat_RG16Snorm', + 327685: 'WGPUTextureFormat_RGBA16Snorm', + 327686: 'WGPUTextureFormat_R8BG8Biplanar420Unorm', + 327687: 'WGPUTextureFormat_R10X6BG10X6Biplanar420Unorm', + 327688: 'WGPUTextureFormat_R8BG8A8Triplanar420Unorm', + 327689: 'WGPUTextureFormat_R8BG8Biplanar422Unorm', + 327690: 'WGPUTextureFormat_R8BG8Biplanar444Unorm', + 327691: 'WGPUTextureFormat_R10X6BG10X6Biplanar422Unorm', + 327692: 'WGPUTextureFormat_R10X6BG10X6Biplanar444Unorm', + 327693: 'WGPUTextureFormat_External', + 2147483647: 'WGPUTextureFormat_Force32', +} +WGPUTextureFormat_Undefined = 0 +WGPUTextureFormat_R8Unorm = 1 +WGPUTextureFormat_R8Snorm = 2 +WGPUTextureFormat_R8Uint = 3 +WGPUTextureFormat_R8Sint = 4 +WGPUTextureFormat_R16Uint = 5 +WGPUTextureFormat_R16Sint = 6 +WGPUTextureFormat_R16Float = 7 +WGPUTextureFormat_RG8Unorm = 8 +WGPUTextureFormat_RG8Snorm = 9 +WGPUTextureFormat_RG8Uint = 10 +WGPUTextureFormat_RG8Sint = 11 +WGPUTextureFormat_R32Float = 12 +WGPUTextureFormat_R32Uint = 13 +WGPUTextureFormat_R32Sint = 14 +WGPUTextureFormat_RG16Uint = 15 +WGPUTextureFormat_RG16Sint = 16 +WGPUTextureFormat_RG16Float = 17 +WGPUTextureFormat_RGBA8Unorm = 18 +WGPUTextureFormat_RGBA8UnormSrgb = 19 +WGPUTextureFormat_RGBA8Snorm = 20 +WGPUTextureFormat_RGBA8Uint = 21 +WGPUTextureFormat_RGBA8Sint = 22 +WGPUTextureFormat_BGRA8Unorm = 23 +WGPUTextureFormat_BGRA8UnormSrgb = 24 +WGPUTextureFormat_RGB10A2Uint = 25 +WGPUTextureFormat_RGB10A2Unorm = 26 +WGPUTextureFormat_RG11B10Ufloat = 27 +WGPUTextureFormat_RGB9E5Ufloat = 28 +WGPUTextureFormat_RG32Float = 29 +WGPUTextureFormat_RG32Uint = 30 +WGPUTextureFormat_RG32Sint = 31 +WGPUTextureFormat_RGBA16Uint = 32 +WGPUTextureFormat_RGBA16Sint = 33 +WGPUTextureFormat_RGBA16Float = 34 +WGPUTextureFormat_RGBA32Float = 35 +WGPUTextureFormat_RGBA32Uint = 36 +WGPUTextureFormat_RGBA32Sint = 37 +WGPUTextureFormat_Stencil8 = 38 +WGPUTextureFormat_Depth16Unorm = 39 +WGPUTextureFormat_Depth24Plus = 40 +WGPUTextureFormat_Depth24PlusStencil8 = 41 +WGPUTextureFormat_Depth32Float = 42 +WGPUTextureFormat_Depth32FloatStencil8 = 43 +WGPUTextureFormat_BC1RGBAUnorm = 44 +WGPUTextureFormat_BC1RGBAUnormSrgb = 45 +WGPUTextureFormat_BC2RGBAUnorm = 46 +WGPUTextureFormat_BC2RGBAUnormSrgb = 47 +WGPUTextureFormat_BC3RGBAUnorm = 48 +WGPUTextureFormat_BC3RGBAUnormSrgb = 49 +WGPUTextureFormat_BC4RUnorm = 50 +WGPUTextureFormat_BC4RSnorm = 51 +WGPUTextureFormat_BC5RGUnorm = 52 +WGPUTextureFormat_BC5RGSnorm = 53 +WGPUTextureFormat_BC6HRGBUfloat = 54 +WGPUTextureFormat_BC6HRGBFloat = 55 +WGPUTextureFormat_BC7RGBAUnorm = 56 +WGPUTextureFormat_BC7RGBAUnormSrgb = 57 +WGPUTextureFormat_ETC2RGB8Unorm = 58 +WGPUTextureFormat_ETC2RGB8UnormSrgb = 59 +WGPUTextureFormat_ETC2RGB8A1Unorm = 60 +WGPUTextureFormat_ETC2RGB8A1UnormSrgb = 61 +WGPUTextureFormat_ETC2RGBA8Unorm = 62 +WGPUTextureFormat_ETC2RGBA8UnormSrgb = 63 +WGPUTextureFormat_EACR11Unorm = 64 +WGPUTextureFormat_EACR11Snorm = 65 +WGPUTextureFormat_EACRG11Unorm = 66 +WGPUTextureFormat_EACRG11Snorm = 67 +WGPUTextureFormat_ASTC4x4Unorm = 68 +WGPUTextureFormat_ASTC4x4UnormSrgb = 69 +WGPUTextureFormat_ASTC5x4Unorm = 70 +WGPUTextureFormat_ASTC5x4UnormSrgb = 71 +WGPUTextureFormat_ASTC5x5Unorm = 72 +WGPUTextureFormat_ASTC5x5UnormSrgb = 73 +WGPUTextureFormat_ASTC6x5Unorm = 74 +WGPUTextureFormat_ASTC6x5UnormSrgb = 75 +WGPUTextureFormat_ASTC6x6Unorm = 76 +WGPUTextureFormat_ASTC6x6UnormSrgb = 77 +WGPUTextureFormat_ASTC8x5Unorm = 78 +WGPUTextureFormat_ASTC8x5UnormSrgb = 79 +WGPUTextureFormat_ASTC8x6Unorm = 80 +WGPUTextureFormat_ASTC8x6UnormSrgb = 81 +WGPUTextureFormat_ASTC8x8Unorm = 82 +WGPUTextureFormat_ASTC8x8UnormSrgb = 83 +WGPUTextureFormat_ASTC10x5Unorm = 84 +WGPUTextureFormat_ASTC10x5UnormSrgb = 85 +WGPUTextureFormat_ASTC10x6Unorm = 86 +WGPUTextureFormat_ASTC10x6UnormSrgb = 87 +WGPUTextureFormat_ASTC10x8Unorm = 88 +WGPUTextureFormat_ASTC10x8UnormSrgb = 89 +WGPUTextureFormat_ASTC10x10Unorm = 90 +WGPUTextureFormat_ASTC10x10UnormSrgb = 91 +WGPUTextureFormat_ASTC12x10Unorm = 92 +WGPUTextureFormat_ASTC12x10UnormSrgb = 93 +WGPUTextureFormat_ASTC12x12Unorm = 94 +WGPUTextureFormat_ASTC12x12UnormSrgb = 95 +WGPUTextureFormat_R16Unorm = 327680 +WGPUTextureFormat_RG16Unorm = 327681 +WGPUTextureFormat_RGBA16Unorm = 327682 +WGPUTextureFormat_R16Snorm = 327683 +WGPUTextureFormat_RG16Snorm = 327684 +WGPUTextureFormat_RGBA16Snorm = 327685 +WGPUTextureFormat_R8BG8Biplanar420Unorm = 327686 +WGPUTextureFormat_R10X6BG10X6Biplanar420Unorm = 327687 +WGPUTextureFormat_R8BG8A8Triplanar420Unorm = 327688 +WGPUTextureFormat_R8BG8Biplanar422Unorm = 327689 +WGPUTextureFormat_R8BG8Biplanar444Unorm = 327690 +WGPUTextureFormat_R10X6BG10X6Biplanar422Unorm = 327691 +WGPUTextureFormat_R10X6BG10X6Biplanar444Unorm = 327692 +WGPUTextureFormat_External = 327693 +WGPUTextureFormat_Force32 = 2147483647 +WGPUTextureFormat = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUTextureSampleType' +WGPUTextureSampleType__enumvalues = { + 0: 'WGPUTextureSampleType_BindingNotUsed', + 1: 'WGPUTextureSampleType_Float', + 2: 'WGPUTextureSampleType_UnfilterableFloat', + 3: 'WGPUTextureSampleType_Depth', + 4: 'WGPUTextureSampleType_Sint', + 5: 'WGPUTextureSampleType_Uint', + 2147483647: 'WGPUTextureSampleType_Force32', +} +WGPUTextureSampleType_BindingNotUsed = 0 +WGPUTextureSampleType_Float = 1 +WGPUTextureSampleType_UnfilterableFloat = 2 +WGPUTextureSampleType_Depth = 3 +WGPUTextureSampleType_Sint = 4 +WGPUTextureSampleType_Uint = 5 +WGPUTextureSampleType_Force32 = 2147483647 +WGPUTextureSampleType = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUTextureViewDimension' +WGPUTextureViewDimension__enumvalues = { + 0: 'WGPUTextureViewDimension_Undefined', + 1: 'WGPUTextureViewDimension_1D', + 2: 'WGPUTextureViewDimension_2D', + 3: 'WGPUTextureViewDimension_2DArray', + 4: 'WGPUTextureViewDimension_Cube', + 5: 'WGPUTextureViewDimension_CubeArray', + 6: 'WGPUTextureViewDimension_3D', + 2147483647: 'WGPUTextureViewDimension_Force32', +} +WGPUTextureViewDimension_Undefined = 0 +WGPUTextureViewDimension_1D = 1 +WGPUTextureViewDimension_2D = 2 +WGPUTextureViewDimension_2DArray = 3 +WGPUTextureViewDimension_Cube = 4 +WGPUTextureViewDimension_CubeArray = 5 +WGPUTextureViewDimension_3D = 6 +WGPUTextureViewDimension_Force32 = 2147483647 +WGPUTextureViewDimension = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUVertexFormat' +WGPUVertexFormat__enumvalues = { + 1: 'WGPUVertexFormat_Uint8', + 2: 'WGPUVertexFormat_Uint8x2', + 3: 'WGPUVertexFormat_Uint8x4', + 4: 'WGPUVertexFormat_Sint8', + 5: 'WGPUVertexFormat_Sint8x2', + 6: 'WGPUVertexFormat_Sint8x4', + 7: 'WGPUVertexFormat_Unorm8', + 8: 'WGPUVertexFormat_Unorm8x2', + 9: 'WGPUVertexFormat_Unorm8x4', + 10: 'WGPUVertexFormat_Snorm8', + 11: 'WGPUVertexFormat_Snorm8x2', + 12: 'WGPUVertexFormat_Snorm8x4', + 13: 'WGPUVertexFormat_Uint16', + 14: 'WGPUVertexFormat_Uint16x2', + 15: 'WGPUVertexFormat_Uint16x4', + 16: 'WGPUVertexFormat_Sint16', + 17: 'WGPUVertexFormat_Sint16x2', + 18: 'WGPUVertexFormat_Sint16x4', + 19: 'WGPUVertexFormat_Unorm16', + 20: 'WGPUVertexFormat_Unorm16x2', + 21: 'WGPUVertexFormat_Unorm16x4', + 22: 'WGPUVertexFormat_Snorm16', + 23: 'WGPUVertexFormat_Snorm16x2', + 24: 'WGPUVertexFormat_Snorm16x4', + 25: 'WGPUVertexFormat_Float16', + 26: 'WGPUVertexFormat_Float16x2', + 27: 'WGPUVertexFormat_Float16x4', + 28: 'WGPUVertexFormat_Float32', + 29: 'WGPUVertexFormat_Float32x2', + 30: 'WGPUVertexFormat_Float32x3', + 31: 'WGPUVertexFormat_Float32x4', + 32: 'WGPUVertexFormat_Uint32', + 33: 'WGPUVertexFormat_Uint32x2', + 34: 'WGPUVertexFormat_Uint32x3', + 35: 'WGPUVertexFormat_Uint32x4', + 36: 'WGPUVertexFormat_Sint32', + 37: 'WGPUVertexFormat_Sint32x2', + 38: 'WGPUVertexFormat_Sint32x3', + 39: 'WGPUVertexFormat_Sint32x4', + 40: 'WGPUVertexFormat_Unorm10_10_10_2', + 41: 'WGPUVertexFormat_Unorm8x4BGRA', + 2147483647: 'WGPUVertexFormat_Force32', +} +WGPUVertexFormat_Uint8 = 1 +WGPUVertexFormat_Uint8x2 = 2 +WGPUVertexFormat_Uint8x4 = 3 +WGPUVertexFormat_Sint8 = 4 +WGPUVertexFormat_Sint8x2 = 5 +WGPUVertexFormat_Sint8x4 = 6 +WGPUVertexFormat_Unorm8 = 7 +WGPUVertexFormat_Unorm8x2 = 8 +WGPUVertexFormat_Unorm8x4 = 9 +WGPUVertexFormat_Snorm8 = 10 +WGPUVertexFormat_Snorm8x2 = 11 +WGPUVertexFormat_Snorm8x4 = 12 +WGPUVertexFormat_Uint16 = 13 +WGPUVertexFormat_Uint16x2 = 14 +WGPUVertexFormat_Uint16x4 = 15 +WGPUVertexFormat_Sint16 = 16 +WGPUVertexFormat_Sint16x2 = 17 +WGPUVertexFormat_Sint16x4 = 18 +WGPUVertexFormat_Unorm16 = 19 +WGPUVertexFormat_Unorm16x2 = 20 +WGPUVertexFormat_Unorm16x4 = 21 +WGPUVertexFormat_Snorm16 = 22 +WGPUVertexFormat_Snorm16x2 = 23 +WGPUVertexFormat_Snorm16x4 = 24 +WGPUVertexFormat_Float16 = 25 +WGPUVertexFormat_Float16x2 = 26 +WGPUVertexFormat_Float16x4 = 27 +WGPUVertexFormat_Float32 = 28 +WGPUVertexFormat_Float32x2 = 29 +WGPUVertexFormat_Float32x3 = 30 +WGPUVertexFormat_Float32x4 = 31 +WGPUVertexFormat_Uint32 = 32 +WGPUVertexFormat_Uint32x2 = 33 +WGPUVertexFormat_Uint32x3 = 34 +WGPUVertexFormat_Uint32x4 = 35 +WGPUVertexFormat_Sint32 = 36 +WGPUVertexFormat_Sint32x2 = 37 +WGPUVertexFormat_Sint32x3 = 38 +WGPUVertexFormat_Sint32x4 = 39 +WGPUVertexFormat_Unorm10_10_10_2 = 40 +WGPUVertexFormat_Unorm8x4BGRA = 41 +WGPUVertexFormat_Force32 = 2147483647 +WGPUVertexFormat = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUVertexStepMode' +WGPUVertexStepMode__enumvalues = { + 0: 'WGPUVertexStepMode_Undefined', + 1: 'WGPUVertexStepMode_Vertex', + 2: 'WGPUVertexStepMode_Instance', + 2147483647: 'WGPUVertexStepMode_Force32', +} +WGPUVertexStepMode_Undefined = 0 +WGPUVertexStepMode_Vertex = 1 +WGPUVertexStepMode_Instance = 2 +WGPUVertexStepMode_Force32 = 2147483647 +WGPUVertexStepMode = ctypes.c_uint32 # enum + +# values for enumeration 'WGPUWaitStatus' +WGPUWaitStatus__enumvalues = { + 1: 'WGPUWaitStatus_Success', + 2: 'WGPUWaitStatus_TimedOut', + 3: 'WGPUWaitStatus_UnsupportedTimeout', + 4: 'WGPUWaitStatus_UnsupportedCount', + 5: 'WGPUWaitStatus_UnsupportedMixedSources', + 6: 'WGPUWaitStatus_Unknown', + 2147483647: 'WGPUWaitStatus_Force32', +} +WGPUWaitStatus_Success = 1 +WGPUWaitStatus_TimedOut = 2 +WGPUWaitStatus_UnsupportedTimeout = 3 +WGPUWaitStatus_UnsupportedCount = 4 +WGPUWaitStatus_UnsupportedMixedSources = 5 +WGPUWaitStatus_Unknown = 6 +WGPUWaitStatus_Force32 = 2147483647 +WGPUWaitStatus = ctypes.c_uint32 # enum +WGPUBufferUsage = ctypes.c_uint64 +WGPUBufferUsage_None = 0x0000000000000000 # Variable ctypes.c_uint64 +WGPUBufferUsage_MapRead = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUBufferUsage_MapWrite = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUBufferUsage_CopySrc = 0x0000000000000004 # Variable ctypes.c_uint64 +WGPUBufferUsage_CopyDst = 0x0000000000000008 # Variable ctypes.c_uint64 +WGPUBufferUsage_Index = 0x0000000000000010 # Variable ctypes.c_uint64 +WGPUBufferUsage_Vertex = 0x0000000000000020 # Variable ctypes.c_uint64 +WGPUBufferUsage_Uniform = 0x0000000000000040 # Variable ctypes.c_uint64 +WGPUBufferUsage_Storage = 0x0000000000000080 # Variable ctypes.c_uint64 +WGPUBufferUsage_Indirect = 0x0000000000000100 # Variable ctypes.c_uint64 +WGPUBufferUsage_QueryResolve = 0x0000000000000200 # Variable ctypes.c_uint64 +WGPUColorWriteMask = ctypes.c_uint64 +WGPUColorWriteMask_None = 0x0000000000000000 # Variable ctypes.c_uint64 +WGPUColorWriteMask_Red = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUColorWriteMask_Green = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUColorWriteMask_Blue = 0x0000000000000004 # Variable ctypes.c_uint64 +WGPUColorWriteMask_Alpha = 0x0000000000000008 # Variable ctypes.c_uint64 +WGPUColorWriteMask_All = 0x000000000000000F # Variable ctypes.c_uint64 +WGPUHeapProperty = ctypes.c_uint64 +WGPUHeapProperty_DeviceLocal = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUHeapProperty_HostVisible = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUHeapProperty_HostCoherent = 0x0000000000000004 # Variable ctypes.c_uint64 +WGPUHeapProperty_HostUncached = 0x0000000000000008 # Variable ctypes.c_uint64 +WGPUHeapProperty_HostCached = 0x0000000000000010 # Variable ctypes.c_uint64 +WGPUMapMode = ctypes.c_uint64 +WGPUMapMode_None = 0x0000000000000000 # Variable ctypes.c_uint64 +WGPUMapMode_Read = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUMapMode_Write = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUShaderStage = ctypes.c_uint64 +WGPUShaderStage_None = 0x0000000000000000 # Variable ctypes.c_uint64 +WGPUShaderStage_Vertex = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUShaderStage_Fragment = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUShaderStage_Compute = 0x0000000000000004 # Variable ctypes.c_uint64 +WGPUTextureUsage = ctypes.c_uint64 +WGPUTextureUsage_None = 0x0000000000000000 # Variable ctypes.c_uint64 +WGPUTextureUsage_CopySrc = 0x0000000000000001 # Variable ctypes.c_uint64 +WGPUTextureUsage_CopyDst = 0x0000000000000002 # Variable ctypes.c_uint64 +WGPUTextureUsage_TextureBinding = 0x0000000000000004 # Variable ctypes.c_uint64 +WGPUTextureUsage_StorageBinding = 0x0000000000000008 # Variable ctypes.c_uint64 +WGPUTextureUsage_RenderAttachment = 0x0000000000000010 # Variable ctypes.c_uint64 +WGPUTextureUsage_TransientAttachment = 0x0000000000000020 # Variable ctypes.c_uint64 +WGPUTextureUsage_StorageAttachment = 0x0000000000000040 # Variable ctypes.c_uint64 +WGPUBufferMapCallback = ctypes.CFUNCTYPE(None, WGPUBufferMapAsyncStatus, ctypes.POINTER(None)) +WGPUCallback = ctypes.CFUNCTYPE(None, ctypes.POINTER(None)) +class struct_WGPUCompilationInfo(Structure): + pass + +WGPUCompilationInfoCallback = ctypes.CFUNCTYPE(None, WGPUCompilationInfoRequestStatus, ctypes.POINTER(struct_WGPUCompilationInfo), ctypes.POINTER(None)) +class struct_WGPUStringView(Structure): + pass + +struct_WGPUStringView._pack_ = 1 # source:False +struct_WGPUStringView._fields_ = [ + ('data', ctypes.POINTER(ctypes.c_char)), + ('length', ctypes.c_uint64), +] + +WGPUCreateComputePipelineAsyncCallback = ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView, ctypes.POINTER(None)) +WGPUCreateRenderPipelineAsyncCallback = ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView, ctypes.POINTER(None)) +WGPUDawnLoadCacheDataFunction = ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None)) +WGPUDawnStoreCacheDataFunction = ctypes.CFUNCTYPE(None, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None)) +WGPUDeviceLostCallback = ctypes.CFUNCTYPE(None, WGPUDeviceLostReason, struct_WGPUStringView, ctypes.POINTER(None)) +WGPUDeviceLostCallbackNew = ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUDeviceLostReason, struct_WGPUStringView, ctypes.POINTER(None)) +WGPUErrorCallback = ctypes.CFUNCTYPE(None, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None)) +WGPULoggingCallback = ctypes.CFUNCTYPE(None, WGPULoggingType, struct_WGPUStringView, ctypes.POINTER(None)) +WGPUPopErrorScopeCallback = ctypes.CFUNCTYPE(None, WGPUPopErrorScopeStatus, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None)) +WGPUProc = ctypes.CFUNCTYPE(None) +WGPUQueueWorkDoneCallback = ctypes.CFUNCTYPE(None, WGPUQueueWorkDoneStatus, ctypes.POINTER(None)) +WGPURequestAdapterCallback = ctypes.CFUNCTYPE(None, WGPURequestAdapterStatus, ctypes.POINTER(struct_WGPUAdapterImpl), struct_WGPUStringView, ctypes.POINTER(None)) +WGPURequestDeviceCallback = ctypes.CFUNCTYPE(None, WGPURequestDeviceStatus, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView, ctypes.POINTER(None)) +WGPUBufferMapCallback2 = ctypes.CFUNCTYPE(None, WGPUMapAsyncStatus, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUCompilationInfoCallback2 = ctypes.CFUNCTYPE(None, WGPUCompilationInfoRequestStatus, ctypes.POINTER(struct_WGPUCompilationInfo), ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUCreateComputePipelineAsyncCallback2 = ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUCreateRenderPipelineAsyncCallback2 = ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUDeviceLostCallback2 = ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUDeviceLostReason, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUPopErrorScopeCallback2 = ctypes.CFUNCTYPE(None, WGPUPopErrorScopeStatus, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUQueueWorkDoneCallback2 = ctypes.CFUNCTYPE(None, WGPUQueueWorkDoneStatus, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPURequestAdapterCallback2 = ctypes.CFUNCTYPE(None, WGPURequestAdapterStatus, ctypes.POINTER(struct_WGPUAdapterImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPURequestDeviceCallback2 = ctypes.CFUNCTYPE(None, WGPURequestDeviceStatus, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +WGPUUncapturedErrorCallback = ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None)) +class struct_WGPUChainedStruct(Structure): + pass + +struct_WGPUChainedStruct._pack_ = 1 # source:False +struct_WGPUChainedStruct._fields_ = [ + ('next', ctypes.POINTER(struct_WGPUChainedStruct)), + ('sType', WGPUSType), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUChainedStruct = struct_WGPUChainedStruct +class struct_WGPUChainedStructOut(Structure): + pass + +struct_WGPUChainedStructOut._pack_ = 1 # source:False +struct_WGPUChainedStructOut._fields_ = [ + ('next', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('sType', WGPUSType), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUChainedStructOut = struct_WGPUChainedStructOut +class struct_WGPUBufferMapCallbackInfo2(Structure): + pass + +struct_WGPUBufferMapCallbackInfo2._pack_ = 1 # source:False +struct_WGPUBufferMapCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUMapAsyncStatus, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUBufferMapCallbackInfo2 = struct_WGPUBufferMapCallbackInfo2 +class struct_WGPUCompilationInfoCallbackInfo2(Structure): + pass + +struct_WGPUCompilationInfoCallbackInfo2._pack_ = 1 # source:False +struct_WGPUCompilationInfoCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCompilationInfoRequestStatus, ctypes.POINTER(struct_WGPUCompilationInfo), ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUCompilationInfoCallbackInfo2 = struct_WGPUCompilationInfoCallbackInfo2 +class struct_WGPUCreateComputePipelineAsyncCallbackInfo2(Structure): + pass + +struct_WGPUCreateComputePipelineAsyncCallbackInfo2._pack_ = 1 # source:False +struct_WGPUCreateComputePipelineAsyncCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUCreateComputePipelineAsyncCallbackInfo2 = struct_WGPUCreateComputePipelineAsyncCallbackInfo2 +class struct_WGPUCreateRenderPipelineAsyncCallbackInfo2(Structure): + pass + +struct_WGPUCreateRenderPipelineAsyncCallbackInfo2._pack_ = 1 # source:False +struct_WGPUCreateRenderPipelineAsyncCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUCreateRenderPipelineAsyncCallbackInfo2 = struct_WGPUCreateRenderPipelineAsyncCallbackInfo2 +class struct_WGPUDeviceLostCallbackInfo2(Structure): + pass + +struct_WGPUDeviceLostCallbackInfo2._pack_ = 1 # source:False +struct_WGPUDeviceLostCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUDeviceLostReason, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUDeviceLostCallbackInfo2 = struct_WGPUDeviceLostCallbackInfo2 +class struct_WGPUPopErrorScopeCallbackInfo2(Structure): + pass + +struct_WGPUPopErrorScopeCallbackInfo2._pack_ = 1 # source:False +struct_WGPUPopErrorScopeCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUPopErrorScopeStatus, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUPopErrorScopeCallbackInfo2 = struct_WGPUPopErrorScopeCallbackInfo2 +class struct_WGPUQueueWorkDoneCallbackInfo2(Structure): + pass + +struct_WGPUQueueWorkDoneCallbackInfo2._pack_ = 1 # source:False +struct_WGPUQueueWorkDoneCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUQueueWorkDoneStatus, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUQueueWorkDoneCallbackInfo2 = struct_WGPUQueueWorkDoneCallbackInfo2 +class struct_WGPURequestAdapterCallbackInfo2(Structure): + pass + +struct_WGPURequestAdapterCallbackInfo2._pack_ = 1 # source:False +struct_WGPURequestAdapterCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPURequestAdapterStatus, ctypes.POINTER(struct_WGPUAdapterImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPURequestAdapterCallbackInfo2 = struct_WGPURequestAdapterCallbackInfo2 +class struct_WGPURequestDeviceCallbackInfo2(Structure): + pass + +struct_WGPURequestDeviceCallbackInfo2._pack_ = 1 # source:False +struct_WGPURequestDeviceCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPURequestDeviceStatus, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPURequestDeviceCallbackInfo2 = struct_WGPURequestDeviceCallbackInfo2 +class struct_WGPUUncapturedErrorCallbackInfo2(Structure): + pass + +struct_WGPUUncapturedErrorCallbackInfo2._pack_ = 1 # source:False +struct_WGPUUncapturedErrorCallbackInfo2._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('callback', ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None), ctypes.POINTER(None))), + ('userdata1', ctypes.POINTER(None)), + ('userdata2', ctypes.POINTER(None)), +] + +WGPUUncapturedErrorCallbackInfo2 = struct_WGPUUncapturedErrorCallbackInfo2 +class struct_WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER(Structure): + pass + +struct_WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER._pack_ = 1 # source:False +struct_WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER._fields_ = [ + ('unused', ctypes.c_uint32), +] + +WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER = struct_WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER +class struct_WGPUAdapterPropertiesD3D(Structure): + pass + +struct_WGPUAdapterPropertiesD3D._pack_ = 1 # source:False +struct_WGPUAdapterPropertiesD3D._fields_ = [ + ('chain', WGPUChainedStructOut), + ('shaderModel', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUAdapterPropertiesD3D = struct_WGPUAdapterPropertiesD3D +class struct_WGPUAdapterPropertiesSubgroups(Structure): + pass + +struct_WGPUAdapterPropertiesSubgroups._pack_ = 1 # source:False +struct_WGPUAdapterPropertiesSubgroups._fields_ = [ + ('chain', WGPUChainedStructOut), + ('subgroupMinSize', ctypes.c_uint32), + ('subgroupMaxSize', ctypes.c_uint32), +] + +WGPUAdapterPropertiesSubgroups = struct_WGPUAdapterPropertiesSubgroups +class struct_WGPUAdapterPropertiesVk(Structure): + pass + +struct_WGPUAdapterPropertiesVk._pack_ = 1 # source:False +struct_WGPUAdapterPropertiesVk._fields_ = [ + ('chain', WGPUChainedStructOut), + ('driverVersion', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUAdapterPropertiesVk = struct_WGPUAdapterPropertiesVk +class struct_WGPUBindGroupEntry(Structure): + pass + +struct_WGPUBindGroupEntry._pack_ = 1 # source:False +struct_WGPUBindGroupEntry._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('binding', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('buffer', ctypes.POINTER(struct_WGPUBufferImpl)), + ('offset', ctypes.c_uint64), + ('size', ctypes.c_uint64), + ('sampler', ctypes.POINTER(struct_WGPUSamplerImpl)), + ('textureView', ctypes.POINTER(struct_WGPUTextureViewImpl)), +] + +WGPUBindGroupEntry = struct_WGPUBindGroupEntry +class struct_WGPUBlendComponent(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('operation', WGPUBlendOperation), + ('srcFactor', WGPUBlendFactor), + ('dstFactor', WGPUBlendFactor), + ] + +WGPUBlendComponent = struct_WGPUBlendComponent +class struct_WGPUBufferBindingLayout(Structure): + pass + +struct_WGPUBufferBindingLayout._pack_ = 1 # source:False +struct_WGPUBufferBindingLayout._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('type', WGPUBufferBindingType), + ('hasDynamicOffset', ctypes.c_uint32), + ('minBindingSize', ctypes.c_uint64), +] + +WGPUBufferBindingLayout = struct_WGPUBufferBindingLayout +class struct_WGPUBufferHostMappedPointer(Structure): + pass + +struct_WGPUBufferHostMappedPointer._pack_ = 1 # source:False +struct_WGPUBufferHostMappedPointer._fields_ = [ + ('chain', WGPUChainedStruct), + ('pointer', ctypes.POINTER(None)), + ('disposeCallback', ctypes.CFUNCTYPE(None, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUBufferHostMappedPointer = struct_WGPUBufferHostMappedPointer +class struct_WGPUBufferMapCallbackInfo(Structure): + pass + +struct_WGPUBufferMapCallbackInfo._pack_ = 1 # source:False +struct_WGPUBufferMapCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUBufferMapAsyncStatus, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUBufferMapCallbackInfo = struct_WGPUBufferMapCallbackInfo +class struct_WGPUColor(Structure): + pass + +struct_WGPUColor._pack_ = 1 # source:False +struct_WGPUColor._fields_ = [ + ('r', ctypes.c_double), + ('g', ctypes.c_double), + ('b', ctypes.c_double), + ('a', ctypes.c_double), +] + +WGPUColor = struct_WGPUColor +class struct_WGPUColorTargetStateExpandResolveTextureDawn(Structure): + pass + +struct_WGPUColorTargetStateExpandResolveTextureDawn._pack_ = 1 # source:False +struct_WGPUColorTargetStateExpandResolveTextureDawn._fields_ = [ + ('chain', WGPUChainedStruct), + ('enabled', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUColorTargetStateExpandResolveTextureDawn = struct_WGPUColorTargetStateExpandResolveTextureDawn +class struct_WGPUCompilationInfoCallbackInfo(Structure): + pass + +struct_WGPUCompilationInfoCallbackInfo._pack_ = 1 # source:False +struct_WGPUCompilationInfoCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCompilationInfoRequestStatus, ctypes.POINTER(struct_WGPUCompilationInfo), ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUCompilationInfoCallbackInfo = struct_WGPUCompilationInfoCallbackInfo +class struct_WGPUComputePassTimestampWrites(Structure): + pass + +struct_WGPUComputePassTimestampWrites._pack_ = 1 # source:False +struct_WGPUComputePassTimestampWrites._fields_ = [ + ('querySet', ctypes.POINTER(struct_WGPUQuerySetImpl)), + ('beginningOfPassWriteIndex', ctypes.c_uint32), + ('endOfPassWriteIndex', ctypes.c_uint32), +] + +WGPUComputePassTimestampWrites = struct_WGPUComputePassTimestampWrites +class struct_WGPUCopyTextureForBrowserOptions(Structure): + pass + +struct_WGPUCopyTextureForBrowserOptions._pack_ = 1 # source:False +struct_WGPUCopyTextureForBrowserOptions._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('flipY', ctypes.c_uint32), + ('needsColorSpaceConversion', ctypes.c_uint32), + ('srcAlphaMode', WGPUAlphaMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('srcTransferFunctionParameters', ctypes.POINTER(ctypes.c_float)), + ('conversionMatrix', ctypes.POINTER(ctypes.c_float)), + ('dstTransferFunctionParameters', ctypes.POINTER(ctypes.c_float)), + ('dstAlphaMode', WGPUAlphaMode), + ('internalUsage', ctypes.c_uint32), +] + +WGPUCopyTextureForBrowserOptions = struct_WGPUCopyTextureForBrowserOptions +class struct_WGPUCreateComputePipelineAsyncCallbackInfo(Structure): + pass + +struct_WGPUCreateComputePipelineAsyncCallbackInfo._pack_ = 1 # source:False +struct_WGPUCreateComputePipelineAsyncCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUCreateComputePipelineAsyncCallbackInfo = struct_WGPUCreateComputePipelineAsyncCallbackInfo +class struct_WGPUCreateRenderPipelineAsyncCallbackInfo(Structure): + pass + +struct_WGPUCreateRenderPipelineAsyncCallbackInfo._pack_ = 1 # source:False +struct_WGPUCreateRenderPipelineAsyncCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUCreateRenderPipelineAsyncCallbackInfo = struct_WGPUCreateRenderPipelineAsyncCallbackInfo +class struct_WGPUDawnWGSLBlocklist(Structure): + pass + +struct_WGPUDawnWGSLBlocklist._pack_ = 1 # source:False +struct_WGPUDawnWGSLBlocklist._fields_ = [ + ('chain', WGPUChainedStruct), + ('blocklistedFeatureCount', ctypes.c_uint64), + ('blocklistedFeatures', ctypes.POINTER(ctypes.POINTER(ctypes.c_char))), +] + +WGPUDawnWGSLBlocklist = struct_WGPUDawnWGSLBlocklist +class struct_WGPUDawnAdapterPropertiesPowerPreference(Structure): + pass + +struct_WGPUDawnAdapterPropertiesPowerPreference._pack_ = 1 # source:False +struct_WGPUDawnAdapterPropertiesPowerPreference._fields_ = [ + ('chain', WGPUChainedStructOut), + ('powerPreference', WGPUPowerPreference), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnAdapterPropertiesPowerPreference = struct_WGPUDawnAdapterPropertiesPowerPreference +class struct_WGPUDawnBufferDescriptorErrorInfoFromWireClient(Structure): + pass + +struct_WGPUDawnBufferDescriptorErrorInfoFromWireClient._pack_ = 1 # source:False +struct_WGPUDawnBufferDescriptorErrorInfoFromWireClient._fields_ = [ + ('chain', WGPUChainedStruct), + ('outOfMemory', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnBufferDescriptorErrorInfoFromWireClient = struct_WGPUDawnBufferDescriptorErrorInfoFromWireClient +class struct_WGPUDawnEncoderInternalUsageDescriptor(Structure): + pass + +struct_WGPUDawnEncoderInternalUsageDescriptor._pack_ = 1 # source:False +struct_WGPUDawnEncoderInternalUsageDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('useInternalUsages', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnEncoderInternalUsageDescriptor = struct_WGPUDawnEncoderInternalUsageDescriptor +class struct_WGPUDawnExperimentalImmediateDataLimits(Structure): + pass + +struct_WGPUDawnExperimentalImmediateDataLimits._pack_ = 1 # source:False +struct_WGPUDawnExperimentalImmediateDataLimits._fields_ = [ + ('chain', WGPUChainedStructOut), + ('maxImmediateDataRangeByteSize', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnExperimentalImmediateDataLimits = struct_WGPUDawnExperimentalImmediateDataLimits +class struct_WGPUDawnExperimentalSubgroupLimits(Structure): + pass + +struct_WGPUDawnExperimentalSubgroupLimits._pack_ = 1 # source:False +struct_WGPUDawnExperimentalSubgroupLimits._fields_ = [ + ('chain', WGPUChainedStructOut), + ('minSubgroupSize', ctypes.c_uint32), + ('maxSubgroupSize', ctypes.c_uint32), +] + +WGPUDawnExperimentalSubgroupLimits = struct_WGPUDawnExperimentalSubgroupLimits +class struct_WGPUDawnRenderPassColorAttachmentRenderToSingleSampled(Structure): + pass + +struct_WGPUDawnRenderPassColorAttachmentRenderToSingleSampled._pack_ = 1 # source:False +struct_WGPUDawnRenderPassColorAttachmentRenderToSingleSampled._fields_ = [ + ('chain', WGPUChainedStruct), + ('implicitSampleCount', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnRenderPassColorAttachmentRenderToSingleSampled = struct_WGPUDawnRenderPassColorAttachmentRenderToSingleSampled +class struct_WGPUDawnShaderModuleSPIRVOptionsDescriptor(Structure): + pass + +struct_WGPUDawnShaderModuleSPIRVOptionsDescriptor._pack_ = 1 # source:False +struct_WGPUDawnShaderModuleSPIRVOptionsDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('allowNonUniformDerivatives', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnShaderModuleSPIRVOptionsDescriptor = struct_WGPUDawnShaderModuleSPIRVOptionsDescriptor +class struct_WGPUDawnTexelCopyBufferRowAlignmentLimits(Structure): + pass + +struct_WGPUDawnTexelCopyBufferRowAlignmentLimits._pack_ = 1 # source:False +struct_WGPUDawnTexelCopyBufferRowAlignmentLimits._fields_ = [ + ('chain', WGPUChainedStructOut), + ('minTexelCopyBufferRowAlignment', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnTexelCopyBufferRowAlignmentLimits = struct_WGPUDawnTexelCopyBufferRowAlignmentLimits +class struct_WGPUDawnTextureInternalUsageDescriptor(Structure): + pass + +struct_WGPUDawnTextureInternalUsageDescriptor._pack_ = 1 # source:False +struct_WGPUDawnTextureInternalUsageDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('internalUsage', ctypes.c_uint64), +] + +WGPUDawnTextureInternalUsageDescriptor = struct_WGPUDawnTextureInternalUsageDescriptor +class struct_WGPUDawnTogglesDescriptor(Structure): + pass + +struct_WGPUDawnTogglesDescriptor._pack_ = 1 # source:False +struct_WGPUDawnTogglesDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('enabledToggleCount', ctypes.c_uint64), + ('enabledToggles', ctypes.POINTER(ctypes.POINTER(ctypes.c_char))), + ('disabledToggleCount', ctypes.c_uint64), + ('disabledToggles', ctypes.POINTER(ctypes.POINTER(ctypes.c_char))), +] + +WGPUDawnTogglesDescriptor = struct_WGPUDawnTogglesDescriptor +class struct_WGPUDawnWireWGSLControl(Structure): + pass + +struct_WGPUDawnWireWGSLControl._pack_ = 1 # source:False +struct_WGPUDawnWireWGSLControl._fields_ = [ + ('chain', WGPUChainedStruct), + ('enableExperimental', ctypes.c_uint32), + ('enableUnsafe', ctypes.c_uint32), + ('enableTesting', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDawnWireWGSLControl = struct_WGPUDawnWireWGSLControl +class struct_WGPUDeviceLostCallbackInfo(Structure): + pass + +struct_WGPUDeviceLostCallbackInfo._pack_ = 1 # source:False +struct_WGPUDeviceLostCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, ctypes.POINTER(ctypes.POINTER(struct_WGPUDeviceImpl)), WGPUDeviceLostReason, struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUDeviceLostCallbackInfo = struct_WGPUDeviceLostCallbackInfo +class struct_WGPUDrmFormatProperties(Structure): + pass + +struct_WGPUDrmFormatProperties._pack_ = 1 # source:False +struct_WGPUDrmFormatProperties._fields_ = [ + ('modifier', ctypes.c_uint64), + ('modifierPlaneCount', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUDrmFormatProperties = struct_WGPUDrmFormatProperties +class struct_WGPUExtent2D(Structure): + pass + +struct_WGPUExtent2D._pack_ = 1 # source:False +struct_WGPUExtent2D._fields_ = [ + ('width', ctypes.c_uint32), + ('height', ctypes.c_uint32), +] + +WGPUExtent2D = struct_WGPUExtent2D +class struct_WGPUExtent3D(Structure): + pass + +struct_WGPUExtent3D._pack_ = 1 # source:False +struct_WGPUExtent3D._fields_ = [ + ('width', ctypes.c_uint32), + ('height', ctypes.c_uint32), + ('depthOrArrayLayers', ctypes.c_uint32), +] + +WGPUExtent3D = struct_WGPUExtent3D +class struct_WGPUExternalTextureBindingEntry(Structure): + pass + +struct_WGPUExternalTextureBindingEntry._pack_ = 1 # source:False +struct_WGPUExternalTextureBindingEntry._fields_ = [ + ('chain', WGPUChainedStruct), + ('externalTexture', ctypes.POINTER(struct_WGPUExternalTextureImpl)), +] + +WGPUExternalTextureBindingEntry = struct_WGPUExternalTextureBindingEntry +class struct_WGPUExternalTextureBindingLayout(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('chain', WGPUChainedStruct), + ] + +WGPUExternalTextureBindingLayout = struct_WGPUExternalTextureBindingLayout +class struct_WGPUFormatCapabilities(Structure): + pass + +struct_WGPUFormatCapabilities._pack_ = 1 # source:False +struct_WGPUFormatCapabilities._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), +] + +WGPUFormatCapabilities = struct_WGPUFormatCapabilities +class struct_WGPUFuture(Structure): + pass + +struct_WGPUFuture._pack_ = 1 # source:False +struct_WGPUFuture._fields_ = [ + ('id', ctypes.c_uint64), +] + +WGPUFuture = struct_WGPUFuture +class struct_WGPUInstanceFeatures(Structure): + pass + +struct_WGPUInstanceFeatures._pack_ = 1 # source:False +struct_WGPUInstanceFeatures._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('timedWaitAnyEnable', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('timedWaitAnyMaxCount', ctypes.c_uint64), +] + +WGPUInstanceFeatures = struct_WGPUInstanceFeatures +class struct_WGPULimits(Structure): + pass + +struct_WGPULimits._pack_ = 1 # source:False +struct_WGPULimits._fields_ = [ + ('maxTextureDimension1D', ctypes.c_uint32), + ('maxTextureDimension2D', ctypes.c_uint32), + ('maxTextureDimension3D', ctypes.c_uint32), + ('maxTextureArrayLayers', ctypes.c_uint32), + ('maxBindGroups', ctypes.c_uint32), + ('maxBindGroupsPlusVertexBuffers', ctypes.c_uint32), + ('maxBindingsPerBindGroup', ctypes.c_uint32), + ('maxDynamicUniformBuffersPerPipelineLayout', ctypes.c_uint32), + ('maxDynamicStorageBuffersPerPipelineLayout', ctypes.c_uint32), + ('maxSampledTexturesPerShaderStage', ctypes.c_uint32), + ('maxSamplersPerShaderStage', ctypes.c_uint32), + ('maxStorageBuffersPerShaderStage', ctypes.c_uint32), + ('maxStorageTexturesPerShaderStage', ctypes.c_uint32), + ('maxUniformBuffersPerShaderStage', ctypes.c_uint32), + ('maxUniformBufferBindingSize', ctypes.c_uint64), + ('maxStorageBufferBindingSize', ctypes.c_uint64), + ('minUniformBufferOffsetAlignment', ctypes.c_uint32), + ('minStorageBufferOffsetAlignment', ctypes.c_uint32), + ('maxVertexBuffers', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('maxBufferSize', ctypes.c_uint64), + ('maxVertexAttributes', ctypes.c_uint32), + ('maxVertexBufferArrayStride', ctypes.c_uint32), + ('maxInterStageShaderComponents', ctypes.c_uint32), + ('maxInterStageShaderVariables', ctypes.c_uint32), + ('maxColorAttachments', ctypes.c_uint32), + ('maxColorAttachmentBytesPerSample', ctypes.c_uint32), + ('maxComputeWorkgroupStorageSize', ctypes.c_uint32), + ('maxComputeInvocationsPerWorkgroup', ctypes.c_uint32), + ('maxComputeWorkgroupSizeX', ctypes.c_uint32), + ('maxComputeWorkgroupSizeY', ctypes.c_uint32), + ('maxComputeWorkgroupSizeZ', ctypes.c_uint32), + ('maxComputeWorkgroupsPerDimension', ctypes.c_uint32), + ('maxStorageBuffersInVertexStage', ctypes.c_uint32), + ('maxStorageTexturesInVertexStage', ctypes.c_uint32), + ('maxStorageBuffersInFragmentStage', ctypes.c_uint32), + ('maxStorageTexturesInFragmentStage', ctypes.c_uint32), +] + +WGPULimits = struct_WGPULimits +class struct_WGPUMemoryHeapInfo(Structure): + pass + +struct_WGPUMemoryHeapInfo._pack_ = 1 # source:False +struct_WGPUMemoryHeapInfo._fields_ = [ + ('properties', ctypes.c_uint64), + ('size', ctypes.c_uint64), +] + +WGPUMemoryHeapInfo = struct_WGPUMemoryHeapInfo +class struct_WGPUMultisampleState(Structure): + pass + +struct_WGPUMultisampleState._pack_ = 1 # source:False +struct_WGPUMultisampleState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('count', ctypes.c_uint32), + ('mask', ctypes.c_uint32), + ('alphaToCoverageEnabled', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUMultisampleState = struct_WGPUMultisampleState +class struct_WGPUOrigin2D(Structure): + pass + +struct_WGPUOrigin2D._pack_ = 1 # source:False +struct_WGPUOrigin2D._fields_ = [ + ('x', ctypes.c_uint32), + ('y', ctypes.c_uint32), +] + +WGPUOrigin2D = struct_WGPUOrigin2D +class struct_WGPUOrigin3D(Structure): + pass + +struct_WGPUOrigin3D._pack_ = 1 # source:False +struct_WGPUOrigin3D._fields_ = [ + ('x', ctypes.c_uint32), + ('y', ctypes.c_uint32), + ('z', ctypes.c_uint32), +] + +WGPUOrigin3D = struct_WGPUOrigin3D +class struct_WGPUPipelineLayoutStorageAttachment(Structure): + pass + +struct_WGPUPipelineLayoutStorageAttachment._pack_ = 1 # source:False +struct_WGPUPipelineLayoutStorageAttachment._fields_ = [ + ('offset', ctypes.c_uint64), + ('format', WGPUTextureFormat), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUPipelineLayoutStorageAttachment = struct_WGPUPipelineLayoutStorageAttachment +class struct_WGPUPopErrorScopeCallbackInfo(Structure): + pass + +struct_WGPUPopErrorScopeCallbackInfo._pack_ = 1 # source:False +struct_WGPUPopErrorScopeCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUPopErrorScopeStatus, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None))), + ('oldCallback', ctypes.CFUNCTYPE(None, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUPopErrorScopeCallbackInfo = struct_WGPUPopErrorScopeCallbackInfo +class struct_WGPUPrimitiveState(Structure): + pass + +struct_WGPUPrimitiveState._pack_ = 1 # source:False +struct_WGPUPrimitiveState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('topology', WGPUPrimitiveTopology), + ('stripIndexFormat', WGPUIndexFormat), + ('frontFace', WGPUFrontFace), + ('cullMode', WGPUCullMode), + ('unclippedDepth', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUPrimitiveState = struct_WGPUPrimitiveState +class struct_WGPUQueueWorkDoneCallbackInfo(Structure): + pass + +struct_WGPUQueueWorkDoneCallbackInfo._pack_ = 1 # source:False +struct_WGPUQueueWorkDoneCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPUQueueWorkDoneStatus, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUQueueWorkDoneCallbackInfo = struct_WGPUQueueWorkDoneCallbackInfo +class struct_WGPURenderPassDepthStencilAttachment(Structure): + pass + +struct_WGPURenderPassDepthStencilAttachment._pack_ = 1 # source:False +struct_WGPURenderPassDepthStencilAttachment._fields_ = [ + ('view', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('depthLoadOp', WGPULoadOp), + ('depthStoreOp', WGPUStoreOp), + ('depthClearValue', ctypes.c_float), + ('depthReadOnly', ctypes.c_uint32), + ('stencilLoadOp', WGPULoadOp), + ('stencilStoreOp', WGPUStoreOp), + ('stencilClearValue', ctypes.c_uint32), + ('stencilReadOnly', ctypes.c_uint32), +] + +WGPURenderPassDepthStencilAttachment = struct_WGPURenderPassDepthStencilAttachment +class struct_WGPURenderPassDescriptorExpandResolveRect(Structure): + pass + +struct_WGPURenderPassDescriptorExpandResolveRect._pack_ = 1 # source:False +struct_WGPURenderPassDescriptorExpandResolveRect._fields_ = [ + ('chain', WGPUChainedStruct), + ('x', ctypes.c_uint32), + ('y', ctypes.c_uint32), + ('width', ctypes.c_uint32), + ('height', ctypes.c_uint32), +] + +WGPURenderPassDescriptorExpandResolveRect = struct_WGPURenderPassDescriptorExpandResolveRect +class struct_WGPURenderPassMaxDrawCount(Structure): + pass + +struct_WGPURenderPassMaxDrawCount._pack_ = 1 # source:False +struct_WGPURenderPassMaxDrawCount._fields_ = [ + ('chain', WGPUChainedStruct), + ('maxDrawCount', ctypes.c_uint64), +] + +WGPURenderPassMaxDrawCount = struct_WGPURenderPassMaxDrawCount +class struct_WGPURenderPassTimestampWrites(Structure): + pass + +struct_WGPURenderPassTimestampWrites._pack_ = 1 # source:False +struct_WGPURenderPassTimestampWrites._fields_ = [ + ('querySet', ctypes.POINTER(struct_WGPUQuerySetImpl)), + ('beginningOfPassWriteIndex', ctypes.c_uint32), + ('endOfPassWriteIndex', ctypes.c_uint32), +] + +WGPURenderPassTimestampWrites = struct_WGPURenderPassTimestampWrites +class struct_WGPURequestAdapterCallbackInfo(Structure): + pass + +struct_WGPURequestAdapterCallbackInfo._pack_ = 1 # source:False +struct_WGPURequestAdapterCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPURequestAdapterStatus, ctypes.POINTER(struct_WGPUAdapterImpl), struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPURequestAdapterCallbackInfo = struct_WGPURequestAdapterCallbackInfo +class struct_WGPURequestAdapterOptions(Structure): + pass + +struct_WGPURequestAdapterOptions._pack_ = 1 # source:False +struct_WGPURequestAdapterOptions._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('compatibleSurface', ctypes.POINTER(struct_WGPUSurfaceImpl)), + ('featureLevel', WGPUFeatureLevel), + ('powerPreference', WGPUPowerPreference), + ('backendType', WGPUBackendType), + ('forceFallbackAdapter', ctypes.c_uint32), + ('compatibilityMode', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPURequestAdapterOptions = struct_WGPURequestAdapterOptions +class struct_WGPURequestDeviceCallbackInfo(Structure): + pass + +struct_WGPURequestDeviceCallbackInfo._pack_ = 1 # source:False +struct_WGPURequestDeviceCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('mode', WGPUCallbackMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('callback', ctypes.CFUNCTYPE(None, WGPURequestDeviceStatus, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPURequestDeviceCallbackInfo = struct_WGPURequestDeviceCallbackInfo +class struct_WGPUSamplerBindingLayout(Structure): + pass + +struct_WGPUSamplerBindingLayout._pack_ = 1 # source:False +struct_WGPUSamplerBindingLayout._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('type', WGPUSamplerBindingType), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSamplerBindingLayout = struct_WGPUSamplerBindingLayout +class struct_WGPUShaderModuleCompilationOptions(Structure): + pass + +struct_WGPUShaderModuleCompilationOptions._pack_ = 1 # source:False +struct_WGPUShaderModuleCompilationOptions._fields_ = [ + ('chain', WGPUChainedStruct), + ('strictMath', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUShaderModuleCompilationOptions = struct_WGPUShaderModuleCompilationOptions +class struct_WGPUShaderSourceSPIRV(Structure): + pass + +struct_WGPUShaderSourceSPIRV._pack_ = 1 # source:False +struct_WGPUShaderSourceSPIRV._fields_ = [ + ('chain', WGPUChainedStruct), + ('codeSize', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('code', ctypes.POINTER(ctypes.c_uint32)), +] + +WGPUShaderSourceSPIRV = struct_WGPUShaderSourceSPIRV +class struct_WGPUSharedBufferMemoryBeginAccessDescriptor(Structure): + pass + +struct_WGPUSharedBufferMemoryBeginAccessDescriptor._pack_ = 1 # source:False +struct_WGPUSharedBufferMemoryBeginAccessDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('initialized', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('fenceCount', ctypes.c_uint64), + ('fences', ctypes.POINTER(ctypes.POINTER(struct_WGPUSharedFenceImpl))), + ('signaledValues', ctypes.POINTER(ctypes.c_uint64)), +] + +WGPUSharedBufferMemoryBeginAccessDescriptor = struct_WGPUSharedBufferMemoryBeginAccessDescriptor +class struct_WGPUSharedBufferMemoryEndAccessState(Structure): + pass + +struct_WGPUSharedBufferMemoryEndAccessState._pack_ = 1 # source:False +struct_WGPUSharedBufferMemoryEndAccessState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('initialized', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('fenceCount', ctypes.c_uint64), + ('fences', ctypes.POINTER(ctypes.POINTER(struct_WGPUSharedFenceImpl))), + ('signaledValues', ctypes.POINTER(ctypes.c_uint64)), +] + +WGPUSharedBufferMemoryEndAccessState = struct_WGPUSharedBufferMemoryEndAccessState +class struct_WGPUSharedBufferMemoryProperties(Structure): + pass + +struct_WGPUSharedBufferMemoryProperties._pack_ = 1 # source:False +struct_WGPUSharedBufferMemoryProperties._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('usage', ctypes.c_uint64), + ('size', ctypes.c_uint64), +] + +WGPUSharedBufferMemoryProperties = struct_WGPUSharedBufferMemoryProperties +class struct_WGPUSharedFenceDXGISharedHandleDescriptor(Structure): + pass + +struct_WGPUSharedFenceDXGISharedHandleDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceDXGISharedHandleDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.POINTER(None)), +] + +WGPUSharedFenceDXGISharedHandleDescriptor = struct_WGPUSharedFenceDXGISharedHandleDescriptor +class struct_WGPUSharedFenceDXGISharedHandleExportInfo(Structure): + pass + +struct_WGPUSharedFenceDXGISharedHandleExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceDXGISharedHandleExportInfo._fields_ = [ + ('chain', WGPUChainedStructOut), + ('handle', ctypes.POINTER(None)), +] + +WGPUSharedFenceDXGISharedHandleExportInfo = struct_WGPUSharedFenceDXGISharedHandleExportInfo +class struct_WGPUSharedFenceMTLSharedEventDescriptor(Structure): + pass + +struct_WGPUSharedFenceMTLSharedEventDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceMTLSharedEventDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('sharedEvent', ctypes.POINTER(None)), +] + +WGPUSharedFenceMTLSharedEventDescriptor = struct_WGPUSharedFenceMTLSharedEventDescriptor +class struct_WGPUSharedFenceMTLSharedEventExportInfo(Structure): + pass + +struct_WGPUSharedFenceMTLSharedEventExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceMTLSharedEventExportInfo._fields_ = [ + ('chain', WGPUChainedStructOut), + ('sharedEvent', ctypes.POINTER(None)), +] + +WGPUSharedFenceMTLSharedEventExportInfo = struct_WGPUSharedFenceMTLSharedEventExportInfo +class struct_WGPUSharedFenceExportInfo(Structure): + pass + +struct_WGPUSharedFenceExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceExportInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('type', WGPUSharedFenceType), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceExportInfo = struct_WGPUSharedFenceExportInfo +class struct_WGPUSharedFenceSyncFDDescriptor(Structure): + pass + +struct_WGPUSharedFenceSyncFDDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceSyncFDDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceSyncFDDescriptor = struct_WGPUSharedFenceSyncFDDescriptor +class struct_WGPUSharedFenceSyncFDExportInfo(Structure): + pass + +struct_WGPUSharedFenceSyncFDExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceSyncFDExportInfo._fields_ = [ + ('chain', WGPUChainedStructOut), + ('handle', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceSyncFDExportInfo = struct_WGPUSharedFenceSyncFDExportInfo +class struct_WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor(Structure): + pass + +struct_WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor = struct_WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor +class struct_WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo(Structure): + pass + +struct_WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo._fields_ = [ + ('chain', WGPUChainedStructOut), + ('handle', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo = struct_WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo +class struct_WGPUSharedFenceVkSemaphoreZirconHandleDescriptor(Structure): + pass + +struct_WGPUSharedFenceVkSemaphoreZirconHandleDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceVkSemaphoreZirconHandleDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceVkSemaphoreZirconHandleDescriptor = struct_WGPUSharedFenceVkSemaphoreZirconHandleDescriptor +class struct_WGPUSharedFenceVkSemaphoreZirconHandleExportInfo(Structure): + pass + +struct_WGPUSharedFenceVkSemaphoreZirconHandleExportInfo._pack_ = 1 # source:False +struct_WGPUSharedFenceVkSemaphoreZirconHandleExportInfo._fields_ = [ + ('chain', WGPUChainedStructOut), + ('handle', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedFenceVkSemaphoreZirconHandleExportInfo = struct_WGPUSharedFenceVkSemaphoreZirconHandleExportInfo +class struct_WGPUSharedTextureMemoryD3DSwapchainBeginState(Structure): + pass + +struct_WGPUSharedTextureMemoryD3DSwapchainBeginState._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryD3DSwapchainBeginState._fields_ = [ + ('chain', WGPUChainedStruct), + ('isSwapchain', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryD3DSwapchainBeginState = struct_WGPUSharedTextureMemoryD3DSwapchainBeginState +class struct_WGPUSharedTextureMemoryDXGISharedHandleDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryDXGISharedHandleDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryDXGISharedHandleDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.POINTER(None)), + ('useKeyedMutex', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryDXGISharedHandleDescriptor = struct_WGPUSharedTextureMemoryDXGISharedHandleDescriptor +class struct_WGPUSharedTextureMemoryEGLImageDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryEGLImageDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryEGLImageDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('image', ctypes.POINTER(None)), +] + +WGPUSharedTextureMemoryEGLImageDescriptor = struct_WGPUSharedTextureMemoryEGLImageDescriptor +class struct_WGPUSharedTextureMemoryIOSurfaceDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryIOSurfaceDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryIOSurfaceDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('ioSurface', ctypes.POINTER(None)), +] + +WGPUSharedTextureMemoryIOSurfaceDescriptor = struct_WGPUSharedTextureMemoryIOSurfaceDescriptor +class struct_WGPUSharedTextureMemoryAHardwareBufferDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryAHardwareBufferDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryAHardwareBufferDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('handle', ctypes.POINTER(None)), + ('useExternalFormat', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryAHardwareBufferDescriptor = struct_WGPUSharedTextureMemoryAHardwareBufferDescriptor +class struct_WGPUSharedTextureMemoryBeginAccessDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryBeginAccessDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryBeginAccessDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('concurrentRead', ctypes.c_uint32), + ('initialized', ctypes.c_uint32), + ('fenceCount', ctypes.c_uint64), + ('fences', ctypes.POINTER(ctypes.POINTER(struct_WGPUSharedFenceImpl))), + ('signaledValues', ctypes.POINTER(ctypes.c_uint64)), +] + +WGPUSharedTextureMemoryBeginAccessDescriptor = struct_WGPUSharedTextureMemoryBeginAccessDescriptor +class struct_WGPUSharedTextureMemoryDmaBufPlane(Structure): + pass + +struct_WGPUSharedTextureMemoryDmaBufPlane._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryDmaBufPlane._fields_ = [ + ('fd', ctypes.c_int32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('offset', ctypes.c_uint64), + ('stride', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryDmaBufPlane = struct_WGPUSharedTextureMemoryDmaBufPlane +class struct_WGPUSharedTextureMemoryEndAccessState(Structure): + pass + +struct_WGPUSharedTextureMemoryEndAccessState._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryEndAccessState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('initialized', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('fenceCount', ctypes.c_uint64), + ('fences', ctypes.POINTER(ctypes.POINTER(struct_WGPUSharedFenceImpl))), + ('signaledValues', ctypes.POINTER(ctypes.c_uint64)), +] + +WGPUSharedTextureMemoryEndAccessState = struct_WGPUSharedTextureMemoryEndAccessState +class struct_WGPUSharedTextureMemoryOpaqueFDDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryOpaqueFDDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryOpaqueFDDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('vkImageCreateInfo', ctypes.POINTER(None)), + ('memoryFD', ctypes.c_int32), + ('memoryTypeIndex', ctypes.c_uint32), + ('allocationSize', ctypes.c_uint64), + ('dedicatedAllocation', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryOpaqueFDDescriptor = struct_WGPUSharedTextureMemoryOpaqueFDDescriptor +class struct_WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('dedicatedAllocation', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor = struct_WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor +class struct_WGPUSharedTextureMemoryVkImageLayoutBeginState(Structure): + pass + +struct_WGPUSharedTextureMemoryVkImageLayoutBeginState._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryVkImageLayoutBeginState._fields_ = [ + ('chain', WGPUChainedStruct), + ('oldLayout', ctypes.c_int32), + ('newLayout', ctypes.c_int32), +] + +WGPUSharedTextureMemoryVkImageLayoutBeginState = struct_WGPUSharedTextureMemoryVkImageLayoutBeginState +class struct_WGPUSharedTextureMemoryVkImageLayoutEndState(Structure): + pass + +struct_WGPUSharedTextureMemoryVkImageLayoutEndState._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryVkImageLayoutEndState._fields_ = [ + ('chain', WGPUChainedStructOut), + ('oldLayout', ctypes.c_int32), + ('newLayout', ctypes.c_int32), +] + +WGPUSharedTextureMemoryVkImageLayoutEndState = struct_WGPUSharedTextureMemoryVkImageLayoutEndState +class struct_WGPUSharedTextureMemoryZirconHandleDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryZirconHandleDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryZirconHandleDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('memoryFD', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('allocationSize', ctypes.c_uint64), +] + +WGPUSharedTextureMemoryZirconHandleDescriptor = struct_WGPUSharedTextureMemoryZirconHandleDescriptor +class struct_WGPUStaticSamplerBindingLayout(Structure): + pass + +struct_WGPUStaticSamplerBindingLayout._pack_ = 1 # source:False +struct_WGPUStaticSamplerBindingLayout._fields_ = [ + ('chain', WGPUChainedStruct), + ('sampler', ctypes.POINTER(struct_WGPUSamplerImpl)), + ('sampledTextureBinding', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUStaticSamplerBindingLayout = struct_WGPUStaticSamplerBindingLayout +class struct_WGPUStencilFaceState(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('compare', WGPUCompareFunction), + ('failOp', WGPUStencilOperation), + ('depthFailOp', WGPUStencilOperation), + ('passOp', WGPUStencilOperation), + ] + +WGPUStencilFaceState = struct_WGPUStencilFaceState +class struct_WGPUStorageTextureBindingLayout(Structure): + pass + +struct_WGPUStorageTextureBindingLayout._pack_ = 1 # source:False +struct_WGPUStorageTextureBindingLayout._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('access', WGPUStorageTextureAccess), + ('format', WGPUTextureFormat), + ('viewDimension', WGPUTextureViewDimension), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUStorageTextureBindingLayout = struct_WGPUStorageTextureBindingLayout +WGPUStringView = struct_WGPUStringView +class struct_WGPUSupportedFeatures(Structure): + pass + +struct_WGPUSupportedFeatures._pack_ = 1 # source:False +struct_WGPUSupportedFeatures._fields_ = [ + ('featureCount', ctypes.c_uint64), + ('features', ctypes.POINTER(WGPUFeatureName)), +] + +WGPUSupportedFeatures = struct_WGPUSupportedFeatures +class struct_WGPUSurfaceCapabilities(Structure): + pass + +struct_WGPUSurfaceCapabilities._pack_ = 1 # source:False +struct_WGPUSurfaceCapabilities._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('usages', ctypes.c_uint64), + ('formatCount', ctypes.c_uint64), + ('formats', ctypes.POINTER(WGPUTextureFormat)), + ('presentModeCount', ctypes.c_uint64), + ('presentModes', ctypes.POINTER(WGPUPresentMode)), + ('alphaModeCount', ctypes.c_uint64), + ('alphaModes', ctypes.POINTER(WGPUCompositeAlphaMode)), +] + +WGPUSurfaceCapabilities = struct_WGPUSurfaceCapabilities +class struct_WGPUSurfaceConfiguration(Structure): + pass + +struct_WGPUSurfaceConfiguration._pack_ = 1 # source:False +struct_WGPUSurfaceConfiguration._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('device', ctypes.POINTER(struct_WGPUDeviceImpl)), + ('format', WGPUTextureFormat), + ('PADDING_0', ctypes.c_ubyte * 4), + ('usage', ctypes.c_uint64), + ('viewFormatCount', ctypes.c_uint64), + ('viewFormats', ctypes.POINTER(WGPUTextureFormat)), + ('alphaMode', WGPUCompositeAlphaMode), + ('width', ctypes.c_uint32), + ('height', ctypes.c_uint32), + ('presentMode', WGPUPresentMode), +] + +WGPUSurfaceConfiguration = struct_WGPUSurfaceConfiguration +class struct_WGPUSurfaceDescriptorFromWindowsCoreWindow(Structure): + pass + +struct_WGPUSurfaceDescriptorFromWindowsCoreWindow._pack_ = 1 # source:False +struct_WGPUSurfaceDescriptorFromWindowsCoreWindow._fields_ = [ + ('chain', WGPUChainedStruct), + ('coreWindow', ctypes.POINTER(None)), +] + +WGPUSurfaceDescriptorFromWindowsCoreWindow = struct_WGPUSurfaceDescriptorFromWindowsCoreWindow +class struct_WGPUSurfaceDescriptorFromWindowsSwapChainPanel(Structure): + pass + +struct_WGPUSurfaceDescriptorFromWindowsSwapChainPanel._pack_ = 1 # source:False +struct_WGPUSurfaceDescriptorFromWindowsSwapChainPanel._fields_ = [ + ('chain', WGPUChainedStruct), + ('swapChainPanel', ctypes.POINTER(None)), +] + +WGPUSurfaceDescriptorFromWindowsSwapChainPanel = struct_WGPUSurfaceDescriptorFromWindowsSwapChainPanel +class struct_WGPUSurfaceSourceXCBWindow(Structure): + pass + +struct_WGPUSurfaceSourceXCBWindow._pack_ = 1 # source:False +struct_WGPUSurfaceSourceXCBWindow._fields_ = [ + ('chain', WGPUChainedStruct), + ('connection', ctypes.POINTER(None)), + ('window', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUSurfaceSourceXCBWindow = struct_WGPUSurfaceSourceXCBWindow +class struct_WGPUSurfaceSourceAndroidNativeWindow(Structure): + pass + +struct_WGPUSurfaceSourceAndroidNativeWindow._pack_ = 1 # source:False +struct_WGPUSurfaceSourceAndroidNativeWindow._fields_ = [ + ('chain', WGPUChainedStruct), + ('window', ctypes.POINTER(None)), +] + +WGPUSurfaceSourceAndroidNativeWindow = struct_WGPUSurfaceSourceAndroidNativeWindow +class struct_WGPUSurfaceSourceMetalLayer(Structure): + pass + +struct_WGPUSurfaceSourceMetalLayer._pack_ = 1 # source:False +struct_WGPUSurfaceSourceMetalLayer._fields_ = [ + ('chain', WGPUChainedStruct), + ('layer', ctypes.POINTER(None)), +] + +WGPUSurfaceSourceMetalLayer = struct_WGPUSurfaceSourceMetalLayer +class struct_WGPUSurfaceSourceWaylandSurface(Structure): + pass + +struct_WGPUSurfaceSourceWaylandSurface._pack_ = 1 # source:False +struct_WGPUSurfaceSourceWaylandSurface._fields_ = [ + ('chain', WGPUChainedStruct), + ('display', ctypes.POINTER(None)), + ('surface', ctypes.POINTER(None)), +] + +WGPUSurfaceSourceWaylandSurface = struct_WGPUSurfaceSourceWaylandSurface +class struct_WGPUSurfaceSourceWindowsHWND(Structure): + pass + +struct_WGPUSurfaceSourceWindowsHWND._pack_ = 1 # source:False +struct_WGPUSurfaceSourceWindowsHWND._fields_ = [ + ('chain', WGPUChainedStruct), + ('hinstance', ctypes.POINTER(None)), + ('hwnd', ctypes.POINTER(None)), +] + +WGPUSurfaceSourceWindowsHWND = struct_WGPUSurfaceSourceWindowsHWND +class struct_WGPUSurfaceSourceXlibWindow(Structure): + pass + +struct_WGPUSurfaceSourceXlibWindow._pack_ = 1 # source:False +struct_WGPUSurfaceSourceXlibWindow._fields_ = [ + ('chain', WGPUChainedStruct), + ('display', ctypes.POINTER(None)), + ('window', ctypes.c_uint64), +] + +WGPUSurfaceSourceXlibWindow = struct_WGPUSurfaceSourceXlibWindow +class struct_WGPUSurfaceTexture(Structure): + pass + +struct_WGPUSurfaceTexture._pack_ = 1 # source:False +struct_WGPUSurfaceTexture._fields_ = [ + ('texture', ctypes.POINTER(struct_WGPUTextureImpl)), + ('suboptimal', ctypes.c_uint32), + ('status', WGPUSurfaceGetCurrentTextureStatus), +] + +WGPUSurfaceTexture = struct_WGPUSurfaceTexture +class struct_WGPUTextureBindingLayout(Structure): + pass + +struct_WGPUTextureBindingLayout._pack_ = 1 # source:False +struct_WGPUTextureBindingLayout._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('sampleType', WGPUTextureSampleType), + ('viewDimension', WGPUTextureViewDimension), + ('multisampled', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUTextureBindingLayout = struct_WGPUTextureBindingLayout +class struct_WGPUTextureBindingViewDimensionDescriptor(Structure): + pass + +struct_WGPUTextureBindingViewDimensionDescriptor._pack_ = 1 # source:False +struct_WGPUTextureBindingViewDimensionDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('textureBindingViewDimension', WGPUTextureViewDimension), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUTextureBindingViewDimensionDescriptor = struct_WGPUTextureBindingViewDimensionDescriptor +class struct_WGPUTextureDataLayout(Structure): + pass + +struct_WGPUTextureDataLayout._pack_ = 1 # source:False +struct_WGPUTextureDataLayout._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('offset', ctypes.c_uint64), + ('bytesPerRow', ctypes.c_uint32), + ('rowsPerImage', ctypes.c_uint32), +] + +WGPUTextureDataLayout = struct_WGPUTextureDataLayout +class struct_WGPUUncapturedErrorCallbackInfo(Structure): + pass + +struct_WGPUUncapturedErrorCallbackInfo._pack_ = 1 # source:False +struct_WGPUUncapturedErrorCallbackInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('callback', ctypes.CFUNCTYPE(None, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None))), + ('userdata', ctypes.POINTER(None)), +] + +WGPUUncapturedErrorCallbackInfo = struct_WGPUUncapturedErrorCallbackInfo +class struct_WGPUVertexAttribute(Structure): + pass + +struct_WGPUVertexAttribute._pack_ = 1 # source:False +struct_WGPUVertexAttribute._fields_ = [ + ('format', WGPUVertexFormat), + ('PADDING_0', ctypes.c_ubyte * 4), + ('offset', ctypes.c_uint64), + ('shaderLocation', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), +] + +WGPUVertexAttribute = struct_WGPUVertexAttribute +class struct_WGPUYCbCrVkDescriptor(Structure): + pass + +struct_WGPUYCbCrVkDescriptor._pack_ = 1 # source:False +struct_WGPUYCbCrVkDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('vkFormat', ctypes.c_uint32), + ('vkYCbCrModel', ctypes.c_uint32), + ('vkYCbCrRange', ctypes.c_uint32), + ('vkComponentSwizzleRed', ctypes.c_uint32), + ('vkComponentSwizzleGreen', ctypes.c_uint32), + ('vkComponentSwizzleBlue', ctypes.c_uint32), + ('vkComponentSwizzleAlpha', ctypes.c_uint32), + ('vkXChromaOffset', ctypes.c_uint32), + ('vkYChromaOffset', ctypes.c_uint32), + ('vkChromaFilter', WGPUFilterMode), + ('forceExplicitReconstruction', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('externalFormat', ctypes.c_uint64), +] + +WGPUYCbCrVkDescriptor = struct_WGPUYCbCrVkDescriptor +class struct_WGPUAHardwareBufferProperties(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('yCbCrInfo', WGPUYCbCrVkDescriptor), + ] + +WGPUAHardwareBufferProperties = struct_WGPUAHardwareBufferProperties +class struct_WGPUAdapterInfo(Structure): + pass + +struct_WGPUAdapterInfo._pack_ = 1 # source:False +struct_WGPUAdapterInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('vendor', WGPUStringView), + ('architecture', WGPUStringView), + ('device', WGPUStringView), + ('description', WGPUStringView), + ('backendType', WGPUBackendType), + ('adapterType', WGPUAdapterType), + ('vendorID', ctypes.c_uint32), + ('deviceID', ctypes.c_uint32), + ('compatibilityMode', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUAdapterInfo = struct_WGPUAdapterInfo +class struct_WGPUAdapterPropertiesMemoryHeaps(Structure): + pass + +struct_WGPUAdapterPropertiesMemoryHeaps._pack_ = 1 # source:False +struct_WGPUAdapterPropertiesMemoryHeaps._fields_ = [ + ('chain', WGPUChainedStructOut), + ('heapCount', ctypes.c_uint64), + ('heapInfo', ctypes.POINTER(struct_WGPUMemoryHeapInfo)), +] + +WGPUAdapterPropertiesMemoryHeaps = struct_WGPUAdapterPropertiesMemoryHeaps +class struct_WGPUBindGroupDescriptor(Structure): + pass + +struct_WGPUBindGroupDescriptor._pack_ = 1 # source:False +struct_WGPUBindGroupDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('layout', ctypes.POINTER(struct_WGPUBindGroupLayoutImpl)), + ('entryCount', ctypes.c_uint64), + ('entries', ctypes.POINTER(struct_WGPUBindGroupEntry)), +] + +WGPUBindGroupDescriptor = struct_WGPUBindGroupDescriptor +class struct_WGPUBindGroupLayoutEntry(Structure): + pass + +struct_WGPUBindGroupLayoutEntry._pack_ = 1 # source:False +struct_WGPUBindGroupLayoutEntry._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('binding', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('visibility', ctypes.c_uint64), + ('buffer', WGPUBufferBindingLayout), + ('sampler', WGPUSamplerBindingLayout), + ('texture', WGPUTextureBindingLayout), + ('storageTexture', WGPUStorageTextureBindingLayout), +] + +WGPUBindGroupLayoutEntry = struct_WGPUBindGroupLayoutEntry +class struct_WGPUBlendState(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('color', WGPUBlendComponent), + ('alpha', WGPUBlendComponent), + ] + +WGPUBlendState = struct_WGPUBlendState +class struct_WGPUBufferDescriptor(Structure): + pass + +struct_WGPUBufferDescriptor._pack_ = 1 # source:False +struct_WGPUBufferDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('usage', ctypes.c_uint64), + ('size', ctypes.c_uint64), + ('mappedAtCreation', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUBufferDescriptor = struct_WGPUBufferDescriptor +class struct_WGPUCommandBufferDescriptor(Structure): + pass + +struct_WGPUCommandBufferDescriptor._pack_ = 1 # source:False +struct_WGPUCommandBufferDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUCommandBufferDescriptor = struct_WGPUCommandBufferDescriptor +class struct_WGPUCommandEncoderDescriptor(Structure): + pass + +struct_WGPUCommandEncoderDescriptor._pack_ = 1 # source:False +struct_WGPUCommandEncoderDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUCommandEncoderDescriptor = struct_WGPUCommandEncoderDescriptor +class struct_WGPUCompilationMessage(Structure): + pass + +struct_WGPUCompilationMessage._pack_ = 1 # source:False +struct_WGPUCompilationMessage._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('message', WGPUStringView), + ('type', WGPUCompilationMessageType), + ('PADDING_0', ctypes.c_ubyte * 4), + ('lineNum', ctypes.c_uint64), + ('linePos', ctypes.c_uint64), + ('offset', ctypes.c_uint64), + ('length', ctypes.c_uint64), + ('utf16LinePos', ctypes.c_uint64), + ('utf16Offset', ctypes.c_uint64), + ('utf16Length', ctypes.c_uint64), +] + +WGPUCompilationMessage = struct_WGPUCompilationMessage +class struct_WGPUComputePassDescriptor(Structure): + pass + +struct_WGPUComputePassDescriptor._pack_ = 1 # source:False +struct_WGPUComputePassDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('timestampWrites', ctypes.POINTER(struct_WGPUComputePassTimestampWrites)), +] + +WGPUComputePassDescriptor = struct_WGPUComputePassDescriptor +class struct_WGPUConstantEntry(Structure): + pass + +struct_WGPUConstantEntry._pack_ = 1 # source:False +struct_WGPUConstantEntry._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('key', WGPUStringView), + ('value', ctypes.c_double), +] + +WGPUConstantEntry = struct_WGPUConstantEntry +class struct_WGPUDawnCacheDeviceDescriptor(Structure): + pass + +struct_WGPUDawnCacheDeviceDescriptor._pack_ = 1 # source:False +struct_WGPUDawnCacheDeviceDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('isolationKey', WGPUStringView), + ('loadDataFunction', ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None))), + ('storeDataFunction', ctypes.CFUNCTYPE(None, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(None))), + ('functionUserdata', ctypes.POINTER(None)), +] + +WGPUDawnCacheDeviceDescriptor = struct_WGPUDawnCacheDeviceDescriptor +class struct_WGPUDepthStencilState(Structure): + pass + +struct_WGPUDepthStencilState._pack_ = 1 # source:False +struct_WGPUDepthStencilState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('format', WGPUTextureFormat), + ('depthWriteEnabled', WGPUOptionalBool), + ('depthCompare', WGPUCompareFunction), + ('stencilFront', WGPUStencilFaceState), + ('stencilBack', WGPUStencilFaceState), + ('stencilReadMask', ctypes.c_uint32), + ('stencilWriteMask', ctypes.c_uint32), + ('depthBias', ctypes.c_int32), + ('depthBiasSlopeScale', ctypes.c_float), + ('depthBiasClamp', ctypes.c_float), +] + +WGPUDepthStencilState = struct_WGPUDepthStencilState +class struct_WGPUDrmFormatCapabilities(Structure): + pass + +struct_WGPUDrmFormatCapabilities._pack_ = 1 # source:False +struct_WGPUDrmFormatCapabilities._fields_ = [ + ('chain', WGPUChainedStructOut), + ('propertiesCount', ctypes.c_uint64), + ('properties', ctypes.POINTER(struct_WGPUDrmFormatProperties)), +] + +WGPUDrmFormatCapabilities = struct_WGPUDrmFormatCapabilities +class struct_WGPUExternalTextureDescriptor(Structure): + pass + +struct_WGPUExternalTextureDescriptor._pack_ = 1 # source:False +struct_WGPUExternalTextureDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('plane0', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('plane1', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('cropOrigin', WGPUOrigin2D), + ('cropSize', WGPUExtent2D), + ('apparentSize', WGPUExtent2D), + ('doYuvToRgbConversionOnly', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('yuvToRgbConversionMatrix', ctypes.POINTER(ctypes.c_float)), + ('srcTransferFunctionParameters', ctypes.POINTER(ctypes.c_float)), + ('dstTransferFunctionParameters', ctypes.POINTER(ctypes.c_float)), + ('gamutConversionMatrix', ctypes.POINTER(ctypes.c_float)), + ('mirrored', ctypes.c_uint32), + ('rotation', WGPUExternalTextureRotation), +] + +WGPUExternalTextureDescriptor = struct_WGPUExternalTextureDescriptor +class struct_WGPUFutureWaitInfo(Structure): + pass + +struct_WGPUFutureWaitInfo._pack_ = 1 # source:False +struct_WGPUFutureWaitInfo._fields_ = [ + ('future', WGPUFuture), + ('completed', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUFutureWaitInfo = struct_WGPUFutureWaitInfo +class struct_WGPUImageCopyBuffer(Structure): + pass + +struct_WGPUImageCopyBuffer._pack_ = 1 # source:False +struct_WGPUImageCopyBuffer._fields_ = [ + ('layout', WGPUTextureDataLayout), + ('buffer', ctypes.POINTER(struct_WGPUBufferImpl)), +] + +WGPUImageCopyBuffer = struct_WGPUImageCopyBuffer +class struct_WGPUImageCopyExternalTexture(Structure): + pass + +struct_WGPUImageCopyExternalTexture._pack_ = 1 # source:False +struct_WGPUImageCopyExternalTexture._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('externalTexture', ctypes.POINTER(struct_WGPUExternalTextureImpl)), + ('origin', WGPUOrigin3D), + ('naturalSize', WGPUExtent2D), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUImageCopyExternalTexture = struct_WGPUImageCopyExternalTexture +class struct_WGPUImageCopyTexture(Structure): + pass + +struct_WGPUImageCopyTexture._pack_ = 1 # source:False +struct_WGPUImageCopyTexture._fields_ = [ + ('texture', ctypes.POINTER(struct_WGPUTextureImpl)), + ('mipLevel', ctypes.c_uint32), + ('origin', WGPUOrigin3D), + ('aspect', WGPUTextureAspect), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUImageCopyTexture = struct_WGPUImageCopyTexture +class struct_WGPUInstanceDescriptor(Structure): + pass + +struct_WGPUInstanceDescriptor._pack_ = 1 # source:False +struct_WGPUInstanceDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('features', WGPUInstanceFeatures), +] + +WGPUInstanceDescriptor = struct_WGPUInstanceDescriptor +class struct_WGPUPipelineLayoutDescriptor(Structure): + pass + +struct_WGPUPipelineLayoutDescriptor._pack_ = 1 # source:False +struct_WGPUPipelineLayoutDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('bindGroupLayoutCount', ctypes.c_uint64), + ('bindGroupLayouts', ctypes.POINTER(ctypes.POINTER(struct_WGPUBindGroupLayoutImpl))), + ('immediateDataRangeByteSize', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), +] + +WGPUPipelineLayoutDescriptor = struct_WGPUPipelineLayoutDescriptor +class struct_WGPUPipelineLayoutPixelLocalStorage(Structure): + pass + +struct_WGPUPipelineLayoutPixelLocalStorage._pack_ = 1 # source:False +struct_WGPUPipelineLayoutPixelLocalStorage._fields_ = [ + ('chain', WGPUChainedStruct), + ('totalPixelLocalStorageSize', ctypes.c_uint64), + ('storageAttachmentCount', ctypes.c_uint64), + ('storageAttachments', ctypes.POINTER(struct_WGPUPipelineLayoutStorageAttachment)), +] + +WGPUPipelineLayoutPixelLocalStorage = struct_WGPUPipelineLayoutPixelLocalStorage +class struct_WGPUQuerySetDescriptor(Structure): + pass + +struct_WGPUQuerySetDescriptor._pack_ = 1 # source:False +struct_WGPUQuerySetDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('type', WGPUQueryType), + ('count', ctypes.c_uint32), +] + +WGPUQuerySetDescriptor = struct_WGPUQuerySetDescriptor +class struct_WGPUQueueDescriptor(Structure): + pass + +struct_WGPUQueueDescriptor._pack_ = 1 # source:False +struct_WGPUQueueDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUQueueDescriptor = struct_WGPUQueueDescriptor +class struct_WGPURenderBundleDescriptor(Structure): + pass + +struct_WGPURenderBundleDescriptor._pack_ = 1 # source:False +struct_WGPURenderBundleDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPURenderBundleDescriptor = struct_WGPURenderBundleDescriptor +class struct_WGPURenderBundleEncoderDescriptor(Structure): + pass + +struct_WGPURenderBundleEncoderDescriptor._pack_ = 1 # source:False +struct_WGPURenderBundleEncoderDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('colorFormatCount', ctypes.c_uint64), + ('colorFormats', ctypes.POINTER(WGPUTextureFormat)), + ('depthStencilFormat', WGPUTextureFormat), + ('sampleCount', ctypes.c_uint32), + ('depthReadOnly', ctypes.c_uint32), + ('stencilReadOnly', ctypes.c_uint32), +] + +WGPURenderBundleEncoderDescriptor = struct_WGPURenderBundleEncoderDescriptor +class struct_WGPURenderPassColorAttachment(Structure): + pass + +struct_WGPURenderPassColorAttachment._pack_ = 1 # source:False +struct_WGPURenderPassColorAttachment._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('view', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('depthSlice', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('resolveTarget', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('loadOp', WGPULoadOp), + ('storeOp', WGPUStoreOp), + ('clearValue', WGPUColor), +] + +WGPURenderPassColorAttachment = struct_WGPURenderPassColorAttachment +class struct_WGPURenderPassStorageAttachment(Structure): + pass + +struct_WGPURenderPassStorageAttachment._pack_ = 1 # source:False +struct_WGPURenderPassStorageAttachment._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('offset', ctypes.c_uint64), + ('storage', ctypes.POINTER(struct_WGPUTextureViewImpl)), + ('loadOp', WGPULoadOp), + ('storeOp', WGPUStoreOp), + ('clearValue', WGPUColor), +] + +WGPURenderPassStorageAttachment = struct_WGPURenderPassStorageAttachment +class struct_WGPURequiredLimits(Structure): + pass + +struct_WGPURequiredLimits._pack_ = 1 # source:False +struct_WGPURequiredLimits._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('limits', WGPULimits), +] + +WGPURequiredLimits = struct_WGPURequiredLimits +class struct_WGPUSamplerDescriptor(Structure): + pass + +struct_WGPUSamplerDescriptor._pack_ = 1 # source:False +struct_WGPUSamplerDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('addressModeU', WGPUAddressMode), + ('addressModeV', WGPUAddressMode), + ('addressModeW', WGPUAddressMode), + ('magFilter', WGPUFilterMode), + ('minFilter', WGPUFilterMode), + ('mipmapFilter', WGPUMipmapFilterMode), + ('lodMinClamp', ctypes.c_float), + ('lodMaxClamp', ctypes.c_float), + ('compare', WGPUCompareFunction), + ('maxAnisotropy', ctypes.c_uint16), + ('PADDING_0', ctypes.c_ubyte * 2), +] + +WGPUSamplerDescriptor = struct_WGPUSamplerDescriptor +class struct_WGPUShaderModuleDescriptor(Structure): + pass + +struct_WGPUShaderModuleDescriptor._pack_ = 1 # source:False +struct_WGPUShaderModuleDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUShaderModuleDescriptor = struct_WGPUShaderModuleDescriptor +class struct_WGPUShaderSourceWGSL(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('chain', WGPUChainedStruct), + ('code', WGPUStringView), + ] + +WGPUShaderSourceWGSL = struct_WGPUShaderSourceWGSL +class struct_WGPUSharedBufferMemoryDescriptor(Structure): + pass + +struct_WGPUSharedBufferMemoryDescriptor._pack_ = 1 # source:False +struct_WGPUSharedBufferMemoryDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUSharedBufferMemoryDescriptor = struct_WGPUSharedBufferMemoryDescriptor +class struct_WGPUSharedFenceDescriptor(Structure): + pass + +struct_WGPUSharedFenceDescriptor._pack_ = 1 # source:False +struct_WGPUSharedFenceDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUSharedFenceDescriptor = struct_WGPUSharedFenceDescriptor +class struct_WGPUSharedTextureMemoryAHardwareBufferProperties(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('chain', WGPUChainedStructOut), + ('yCbCrInfo', WGPUYCbCrVkDescriptor), + ] + +WGPUSharedTextureMemoryAHardwareBufferProperties = struct_WGPUSharedTextureMemoryAHardwareBufferProperties +class struct_WGPUSharedTextureMemoryDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUSharedTextureMemoryDescriptor = struct_WGPUSharedTextureMemoryDescriptor +class struct_WGPUSharedTextureMemoryDmaBufDescriptor(Structure): + pass + +struct_WGPUSharedTextureMemoryDmaBufDescriptor._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryDmaBufDescriptor._fields_ = [ + ('chain', WGPUChainedStruct), + ('size', WGPUExtent3D), + ('drmFormat', ctypes.c_uint32), + ('drmModifier', ctypes.c_uint64), + ('planeCount', ctypes.c_uint64), + ('planes', ctypes.POINTER(struct_WGPUSharedTextureMemoryDmaBufPlane)), +] + +WGPUSharedTextureMemoryDmaBufDescriptor = struct_WGPUSharedTextureMemoryDmaBufDescriptor +class struct_WGPUSharedTextureMemoryProperties(Structure): + pass + +struct_WGPUSharedTextureMemoryProperties._pack_ = 1 # source:False +struct_WGPUSharedTextureMemoryProperties._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('usage', ctypes.c_uint64), + ('size', WGPUExtent3D), + ('format', WGPUTextureFormat), +] + +WGPUSharedTextureMemoryProperties = struct_WGPUSharedTextureMemoryProperties +class struct_WGPUSupportedLimits(Structure): + pass + +struct_WGPUSupportedLimits._pack_ = 1 # source:False +struct_WGPUSupportedLimits._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStructOut)), + ('limits', WGPULimits), +] + +WGPUSupportedLimits = struct_WGPUSupportedLimits +class struct_WGPUSurfaceDescriptor(Structure): + pass + +struct_WGPUSurfaceDescriptor._pack_ = 1 # source:False +struct_WGPUSurfaceDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), +] + +WGPUSurfaceDescriptor = struct_WGPUSurfaceDescriptor +class struct_WGPUSurfaceSourceCanvasHTMLSelector_Emscripten(Structure): + _pack_ = 1 # source:False + _fields_ = [ + ('chain', WGPUChainedStruct), + ('selector', WGPUStringView), + ] + +WGPUSurfaceSourceCanvasHTMLSelector_Emscripten = struct_WGPUSurfaceSourceCanvasHTMLSelector_Emscripten +class struct_WGPUTextureDescriptor(Structure): + pass + +struct_WGPUTextureDescriptor._pack_ = 1 # source:False +struct_WGPUTextureDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('usage', ctypes.c_uint64), + ('dimension', WGPUTextureDimension), + ('size', WGPUExtent3D), + ('format', WGPUTextureFormat), + ('mipLevelCount', ctypes.c_uint32), + ('sampleCount', ctypes.c_uint32), + ('PADDING_0', ctypes.c_ubyte * 4), + ('viewFormatCount', ctypes.c_uint64), + ('viewFormats', ctypes.POINTER(WGPUTextureFormat)), +] + +WGPUTextureDescriptor = struct_WGPUTextureDescriptor +class struct_WGPUTextureViewDescriptor(Structure): + pass + +struct_WGPUTextureViewDescriptor._pack_ = 1 # source:False +struct_WGPUTextureViewDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('format', WGPUTextureFormat), + ('dimension', WGPUTextureViewDimension), + ('baseMipLevel', ctypes.c_uint32), + ('mipLevelCount', ctypes.c_uint32), + ('baseArrayLayer', ctypes.c_uint32), + ('arrayLayerCount', ctypes.c_uint32), + ('aspect', WGPUTextureAspect), + ('PADDING_0', ctypes.c_ubyte * 4), + ('usage', ctypes.c_uint64), +] + +WGPUTextureViewDescriptor = struct_WGPUTextureViewDescriptor +class struct_WGPUVertexBufferLayout(Structure): + pass + +struct_WGPUVertexBufferLayout._pack_ = 1 # source:False +struct_WGPUVertexBufferLayout._fields_ = [ + ('arrayStride', ctypes.c_uint64), + ('stepMode', WGPUVertexStepMode), + ('PADDING_0', ctypes.c_ubyte * 4), + ('attributeCount', ctypes.c_uint64), + ('attributes', ctypes.POINTER(struct_WGPUVertexAttribute)), +] + +WGPUVertexBufferLayout = struct_WGPUVertexBufferLayout +class struct_WGPUBindGroupLayoutDescriptor(Structure): + pass + +struct_WGPUBindGroupLayoutDescriptor._pack_ = 1 # source:False +struct_WGPUBindGroupLayoutDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('entryCount', ctypes.c_uint64), + ('entries', ctypes.POINTER(struct_WGPUBindGroupLayoutEntry)), +] + +WGPUBindGroupLayoutDescriptor = struct_WGPUBindGroupLayoutDescriptor +class struct_WGPUColorTargetState(Structure): + pass + +struct_WGPUColorTargetState._pack_ = 1 # source:False +struct_WGPUColorTargetState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('format', WGPUTextureFormat), + ('PADDING_0', ctypes.c_ubyte * 4), + ('blend', ctypes.POINTER(struct_WGPUBlendState)), + ('writeMask', ctypes.c_uint64), +] + +WGPUColorTargetState = struct_WGPUColorTargetState +struct_WGPUCompilationInfo._pack_ = 1 # source:False +struct_WGPUCompilationInfo._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('messageCount', ctypes.c_uint64), + ('messages', ctypes.POINTER(struct_WGPUCompilationMessage)), +] + +WGPUCompilationInfo = struct_WGPUCompilationInfo +class struct_WGPUComputeState(Structure): + pass + +struct_WGPUComputeState._pack_ = 1 # source:False +struct_WGPUComputeState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('module', ctypes.POINTER(struct_WGPUShaderModuleImpl)), + ('entryPoint', WGPUStringView), + ('constantCount', ctypes.c_uint64), + ('constants', ctypes.POINTER(struct_WGPUConstantEntry)), +] + +WGPUComputeState = struct_WGPUComputeState +class struct_WGPUDeviceDescriptor(Structure): + pass + +struct_WGPUDeviceDescriptor._pack_ = 1 # source:False +struct_WGPUDeviceDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('requiredFeatureCount', ctypes.c_uint64), + ('requiredFeatures', ctypes.POINTER(WGPUFeatureName)), + ('requiredLimits', ctypes.POINTER(struct_WGPURequiredLimits)), + ('defaultQueue', WGPUQueueDescriptor), + ('deviceLostCallbackInfo2', WGPUDeviceLostCallbackInfo2), + ('uncapturedErrorCallbackInfo2', WGPUUncapturedErrorCallbackInfo2), +] + +WGPUDeviceDescriptor = struct_WGPUDeviceDescriptor +class struct_WGPURenderPassDescriptor(Structure): + pass + +struct_WGPURenderPassDescriptor._pack_ = 1 # source:False +struct_WGPURenderPassDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('colorAttachmentCount', ctypes.c_uint64), + ('colorAttachments', ctypes.POINTER(struct_WGPURenderPassColorAttachment)), + ('depthStencilAttachment', ctypes.POINTER(struct_WGPURenderPassDepthStencilAttachment)), + ('occlusionQuerySet', ctypes.POINTER(struct_WGPUQuerySetImpl)), + ('timestampWrites', ctypes.POINTER(struct_WGPURenderPassTimestampWrites)), +] + +WGPURenderPassDescriptor = struct_WGPURenderPassDescriptor +class struct_WGPURenderPassPixelLocalStorage(Structure): + pass + +struct_WGPURenderPassPixelLocalStorage._pack_ = 1 # source:False +struct_WGPURenderPassPixelLocalStorage._fields_ = [ + ('chain', WGPUChainedStruct), + ('totalPixelLocalStorageSize', ctypes.c_uint64), + ('storageAttachmentCount', ctypes.c_uint64), + ('storageAttachments', ctypes.POINTER(struct_WGPURenderPassStorageAttachment)), +] + +WGPURenderPassPixelLocalStorage = struct_WGPURenderPassPixelLocalStorage +class struct_WGPUVertexState(Structure): + pass + +struct_WGPUVertexState._pack_ = 1 # source:False +struct_WGPUVertexState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('module', ctypes.POINTER(struct_WGPUShaderModuleImpl)), + ('entryPoint', WGPUStringView), + ('constantCount', ctypes.c_uint64), + ('constants', ctypes.POINTER(struct_WGPUConstantEntry)), + ('bufferCount', ctypes.c_uint64), + ('buffers', ctypes.POINTER(struct_WGPUVertexBufferLayout)), +] + +WGPUVertexState = struct_WGPUVertexState +class struct_WGPUComputePipelineDescriptor(Structure): + pass + +struct_WGPUComputePipelineDescriptor._pack_ = 1 # source:False +struct_WGPUComputePipelineDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('layout', ctypes.POINTER(struct_WGPUPipelineLayoutImpl)), + ('compute', WGPUComputeState), +] + +WGPUComputePipelineDescriptor = struct_WGPUComputePipelineDescriptor +class struct_WGPUFragmentState(Structure): + pass + +struct_WGPUFragmentState._pack_ = 1 # source:False +struct_WGPUFragmentState._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('module', ctypes.POINTER(struct_WGPUShaderModuleImpl)), + ('entryPoint', WGPUStringView), + ('constantCount', ctypes.c_uint64), + ('constants', ctypes.POINTER(struct_WGPUConstantEntry)), + ('targetCount', ctypes.c_uint64), + ('targets', ctypes.POINTER(struct_WGPUColorTargetState)), +] + +WGPUFragmentState = struct_WGPUFragmentState +class struct_WGPURenderPipelineDescriptor(Structure): + pass + +struct_WGPURenderPipelineDescriptor._pack_ = 1 # source:False +struct_WGPURenderPipelineDescriptor._fields_ = [ + ('nextInChain', ctypes.POINTER(struct_WGPUChainedStruct)), + ('label', WGPUStringView), + ('layout', ctypes.POINTER(struct_WGPUPipelineLayoutImpl)), + ('vertex', WGPUVertexState), + ('primitive', WGPUPrimitiveState), + ('depthStencil', ctypes.POINTER(struct_WGPUDepthStencilState)), + ('multisample', WGPUMultisampleState), + ('fragment', ctypes.POINTER(struct_WGPUFragmentState)), +] + +WGPURenderPipelineDescriptor = struct_WGPURenderPipelineDescriptor +WGPURenderPassDescriptorMaxDrawCount = struct_WGPURenderPassMaxDrawCount +WGPUShaderModuleSPIRVDescriptor = struct_WGPUShaderSourceSPIRV +WGPUShaderModuleWGSLDescriptor = struct_WGPUShaderSourceWGSL +WGPUSurfaceDescriptorFromAndroidNativeWindow = struct_WGPUSurfaceSourceAndroidNativeWindow +WGPUSurfaceDescriptorFromCanvasHTMLSelector = struct_WGPUSurfaceSourceCanvasHTMLSelector_Emscripten +WGPUSurfaceDescriptorFromMetalLayer = struct_WGPUSurfaceSourceMetalLayer +WGPUSurfaceDescriptorFromWaylandSurface = struct_WGPUSurfaceSourceWaylandSurface +WGPUSurfaceDescriptorFromWindowsHWND = struct_WGPUSurfaceSourceWindowsHWND +WGPUSurfaceDescriptorFromXcbWindow = struct_WGPUSurfaceSourceXCBWindow +WGPUSurfaceDescriptorFromXlibWindow = struct_WGPUSurfaceSourceXlibWindow +WGPUProcAdapterInfoFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUAdapterInfo) +WGPUProcAdapterPropertiesMemoryHeapsFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUAdapterPropertiesMemoryHeaps) +WGPUProcCreateInstance = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPUInstanceDescriptor)) +WGPUProcDrmFormatCapabilitiesFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUDrmFormatCapabilities) +WGPUProcGetInstanceFeatures = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUInstanceFeatures)) +WGPUProcGetProcAddress = ctypes.CFUNCTYPE(ctypes.CFUNCTYPE(None), struct_WGPUStringView) +WGPUProcSharedBufferMemoryEndAccessStateFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUSharedBufferMemoryEndAccessState) +WGPUProcSharedTextureMemoryEndAccessStateFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUSharedTextureMemoryEndAccessState) +WGPUProcSupportedFeaturesFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUSupportedFeatures) +WGPUProcSurfaceCapabilitiesFreeMembers = ctypes.CFUNCTYPE(None, struct_WGPUSurfaceCapabilities) +WGPUProcAdapterCreateDevice = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUDeviceDescriptor)) +WGPUProcAdapterGetFeatures = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUSupportedFeatures)) +WGPUProcAdapterGetFormatCapabilities = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUAdapterImpl), WGPUTextureFormat, ctypes.POINTER(struct_WGPUFormatCapabilities)) +WGPUProcAdapterGetInfo = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUAdapterInfo)) +WGPUProcAdapterGetInstance = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPUAdapterImpl)) +WGPUProcAdapterGetLimits = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUSupportedLimits)) +WGPUProcAdapterHasFeature = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUAdapterImpl), WGPUFeatureName) +WGPUProcAdapterRequestDevice = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUDeviceDescriptor), ctypes.CFUNCTYPE(None, WGPURequestDeviceStatus, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcAdapterRequestDevice2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUDeviceDescriptor), struct_WGPURequestDeviceCallbackInfo2) +WGPUProcAdapterRequestDeviceF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUDeviceDescriptor), struct_WGPURequestDeviceCallbackInfo) +WGPUProcAdapterAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUAdapterImpl)) +WGPUProcAdapterRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUAdapterImpl)) +WGPUProcBindGroupSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupImpl), struct_WGPUStringView) +WGPUProcBindGroupAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupImpl)) +WGPUProcBindGroupRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupImpl)) +WGPUProcBindGroupLayoutSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupLayoutImpl), struct_WGPUStringView) +WGPUProcBindGroupLayoutAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupLayoutImpl)) +WGPUProcBindGroupLayoutRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBindGroupLayoutImpl)) +WGPUProcBufferDestroy = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferGetConstMappedRange = ctypes.CFUNCTYPE(ctypes.POINTER(None), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcBufferGetMapState = ctypes.CFUNCTYPE(WGPUBufferMapState, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferGetMappedRange = ctypes.CFUNCTYPE(ctypes.POINTER(None), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcBufferGetSize = ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferGetUsage = ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferMapAsync = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64, ctypes.c_uint64, ctypes.CFUNCTYPE(None, WGPUBufferMapAsyncStatus, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcBufferMapAsync2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64, ctypes.c_uint64, struct_WGPUBufferMapCallbackInfo2) +WGPUProcBufferMapAsyncF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64, ctypes.c_uint64, struct_WGPUBufferMapCallbackInfo) +WGPUProcBufferSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl), struct_WGPUStringView) +WGPUProcBufferUnmap = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcBufferRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUBufferImpl)) +WGPUProcCommandBufferSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandBufferImpl), struct_WGPUStringView) +WGPUProcCommandBufferAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandBufferImpl)) +WGPUProcCommandBufferRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandBufferImpl)) +WGPUProcCommandEncoderBeginComputePass = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUComputePassDescriptor)) +WGPUProcCommandEncoderBeginRenderPass = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPURenderPassDescriptor)) +WGPUProcCommandEncoderClearBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcCommandEncoderCopyBufferToBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcCommandEncoderCopyBufferToTexture = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUImageCopyBuffer), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D)) +WGPUProcCommandEncoderCopyTextureToBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyBuffer), ctypes.POINTER(struct_WGPUExtent3D)) +WGPUProcCommandEncoderCopyTextureToTexture = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D)) +WGPUProcCommandEncoderFinish = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUCommandBufferImpl), ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUCommandBufferDescriptor)) +WGPUProcCommandEncoderInjectValidationError = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), struct_WGPUStringView) +WGPUProcCommandEncoderInsertDebugMarker = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), struct_WGPUStringView) +WGPUProcCommandEncoderPopDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl)) +WGPUProcCommandEncoderPushDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), struct_WGPUStringView) +WGPUProcCommandEncoderResolveQuerySet = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUQuerySetImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcCommandEncoderSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), struct_WGPUStringView) +WGPUProcCommandEncoderWriteBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.c_ubyte), ctypes.c_uint64) +WGPUProcCommandEncoderWriteTimestamp = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUQuerySetImpl), ctypes.c_uint32) +WGPUProcCommandEncoderAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl)) +WGPUProcCommandEncoderRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUCommandEncoderImpl)) +WGPUProcComputePassEncoderDispatchWorkgroups = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32) +WGPUProcComputePassEncoderDispatchWorkgroupsIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcComputePassEncoderEnd = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl)) +WGPUProcComputePassEncoderInsertDebugMarker = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), struct_WGPUStringView) +WGPUProcComputePassEncoderPopDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl)) +WGPUProcComputePassEncoderPushDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), struct_WGPUStringView) +WGPUProcComputePassEncoderSetBindGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.c_uint32, ctypes.POINTER(struct_WGPUBindGroupImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.c_uint32)) +WGPUProcComputePassEncoderSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), struct_WGPUStringView) +WGPUProcComputePassEncoderSetPipeline = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.POINTER(struct_WGPUComputePipelineImpl)) +WGPUProcComputePassEncoderWriteTimestamp = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl), ctypes.POINTER(struct_WGPUQuerySetImpl), ctypes.c_uint32) +WGPUProcComputePassEncoderAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl)) +WGPUProcComputePassEncoderRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePassEncoderImpl)) +WGPUProcComputePipelineGetBindGroupLayout = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBindGroupLayoutImpl), ctypes.POINTER(struct_WGPUComputePipelineImpl), ctypes.c_uint32) +WGPUProcComputePipelineSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView) +WGPUProcComputePipelineAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePipelineImpl)) +WGPUProcComputePipelineRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUComputePipelineImpl)) +WGPUProcDeviceCreateBindGroup = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBindGroupImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUBindGroupDescriptor)) +WGPUProcDeviceCreateBindGroupLayout = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBindGroupLayoutImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUBindGroupLayoutDescriptor)) +WGPUProcDeviceCreateBuffer = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBufferImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUBufferDescriptor)) +WGPUProcDeviceCreateCommandEncoder = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUCommandEncoderImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUCommandEncoderDescriptor)) +WGPUProcDeviceCreateComputePipeline = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUComputePipelineImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUComputePipelineDescriptor)) +WGPUProcDeviceCreateComputePipelineAsync = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUComputePipelineDescriptor), ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPUComputePipelineImpl), struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcDeviceCreateComputePipelineAsync2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUComputePipelineDescriptor), struct_WGPUCreateComputePipelineAsyncCallbackInfo2) +WGPUProcDeviceCreateComputePipelineAsyncF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUComputePipelineDescriptor), struct_WGPUCreateComputePipelineAsyncCallbackInfo) +WGPUProcDeviceCreateErrorBuffer = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBufferImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUBufferDescriptor)) +WGPUProcDeviceCreateErrorExternalTexture = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUExternalTextureImpl), ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceCreateErrorShaderModule = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUShaderModuleImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUShaderModuleDescriptor), struct_WGPUStringView) +WGPUProcDeviceCreateErrorTexture = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUTextureDescriptor)) +WGPUProcDeviceCreateExternalTexture = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUExternalTextureImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUExternalTextureDescriptor)) +WGPUProcDeviceCreatePipelineLayout = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUPipelineLayoutImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUPipelineLayoutDescriptor)) +WGPUProcDeviceCreateQuerySet = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUQuerySetImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUQuerySetDescriptor)) +WGPUProcDeviceCreateRenderBundleEncoder = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPURenderBundleEncoderDescriptor)) +WGPUProcDeviceCreateRenderPipeline = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPURenderPipelineImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPURenderPipelineDescriptor)) +WGPUProcDeviceCreateRenderPipelineAsync = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPURenderPipelineDescriptor), ctypes.CFUNCTYPE(None, WGPUCreatePipelineAsyncStatus, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcDeviceCreateRenderPipelineAsync2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPURenderPipelineDescriptor), struct_WGPUCreateRenderPipelineAsyncCallbackInfo2) +WGPUProcDeviceCreateRenderPipelineAsyncF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPURenderPipelineDescriptor), struct_WGPUCreateRenderPipelineAsyncCallbackInfo) +WGPUProcDeviceCreateSampler = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUSamplerImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSamplerDescriptor)) +WGPUProcDeviceCreateShaderModule = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUShaderModuleImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUShaderModuleDescriptor)) +WGPUProcDeviceCreateTexture = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUTextureDescriptor)) +WGPUProcDeviceDestroy = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceForceLoss = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), WGPUDeviceLostReason, struct_WGPUStringView) +WGPUProcDeviceGetAHardwareBufferProperties = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(None), ctypes.POINTER(struct_WGPUAHardwareBufferProperties)) +WGPUProcDeviceGetAdapter = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceGetAdapterInfo = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUAdapterInfo)) +WGPUProcDeviceGetFeatures = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSupportedFeatures)) +WGPUProcDeviceGetLimits = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSupportedLimits)) +WGPUProcDeviceGetLostFuture = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceGetQueue = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUQueueImpl), ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceHasFeature = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUDeviceImpl), WGPUFeatureName) +WGPUProcDeviceImportSharedBufferMemory = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSharedBufferMemoryDescriptor)) +WGPUProcDeviceImportSharedFence = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUSharedFenceImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSharedFenceDescriptor)) +WGPUProcDeviceImportSharedTextureMemory = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUSharedTextureMemoryDescriptor)) +WGPUProcDeviceInjectError = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), WGPUErrorType, struct_WGPUStringView) +WGPUProcDevicePopErrorScope = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.CFUNCTYPE(None, WGPUErrorType, struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcDevicePopErrorScope2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUPopErrorScopeCallbackInfo2) +WGPUProcDevicePopErrorScopeF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUPopErrorScopeCallbackInfo) +WGPUProcDevicePushErrorScope = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), WGPUErrorFilter) +WGPUProcDeviceSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), struct_WGPUStringView) +WGPUProcDeviceSetLoggingCallback = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.CFUNCTYPE(None, WGPULoggingType, struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcDeviceTick = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceValidateTextureDescriptor = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl), ctypes.POINTER(struct_WGPUTextureDescriptor)) +WGPUProcDeviceAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcDeviceRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUDeviceImpl)) +WGPUProcExternalTextureDestroy = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl)) +WGPUProcExternalTextureExpire = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl)) +WGPUProcExternalTextureRefresh = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl)) +WGPUProcExternalTextureSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl), struct_WGPUStringView) +WGPUProcExternalTextureAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl)) +WGPUProcExternalTextureRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUExternalTextureImpl)) +WGPUProcInstanceCreateSurface = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUSurfaceImpl), ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPUSurfaceDescriptor)) +WGPUProcInstanceEnumerateWGSLLanguageFeatures = ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(WGPUWGSLFeatureName)) +WGPUProcInstanceHasWGSLLanguageFeature = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUInstanceImpl), WGPUWGSLFeatureName) +WGPUProcInstanceProcessEvents = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUInstanceImpl)) +WGPUProcInstanceRequestAdapter = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPURequestAdapterOptions), ctypes.CFUNCTYPE(None, WGPURequestAdapterStatus, ctypes.POINTER(struct_WGPUAdapterImpl), struct_WGPUStringView, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcInstanceRequestAdapter2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPURequestAdapterOptions), struct_WGPURequestAdapterCallbackInfo2) +WGPUProcInstanceRequestAdapterF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.POINTER(struct_WGPURequestAdapterOptions), struct_WGPURequestAdapterCallbackInfo) +WGPUProcInstanceWaitAny = ctypes.CFUNCTYPE(WGPUWaitStatus, ctypes.POINTER(struct_WGPUInstanceImpl), ctypes.c_uint64, ctypes.POINTER(struct_WGPUFutureWaitInfo), ctypes.c_uint64) +WGPUProcInstanceAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUInstanceImpl)) +WGPUProcInstanceRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUInstanceImpl)) +WGPUProcPipelineLayoutSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUPipelineLayoutImpl), struct_WGPUStringView) +WGPUProcPipelineLayoutAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUPipelineLayoutImpl)) +WGPUProcPipelineLayoutRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUPipelineLayoutImpl)) +WGPUProcQuerySetDestroy = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQuerySetImpl)) +WGPUProcQuerySetGetCount = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUQuerySetImpl)) +WGPUProcQuerySetGetType = ctypes.CFUNCTYPE(WGPUQueryType, ctypes.POINTER(struct_WGPUQuerySetImpl)) +WGPUProcQuerySetSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQuerySetImpl), struct_WGPUStringView) +WGPUProcQuerySetAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQuerySetImpl)) +WGPUProcQuerySetRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQuerySetImpl)) +WGPUProcQueueCopyExternalTextureForBrowser = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.POINTER(struct_WGPUImageCopyExternalTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D), ctypes.POINTER(struct_WGPUCopyTextureForBrowserOptions)) +WGPUProcQueueCopyTextureForBrowser = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D), ctypes.POINTER(struct_WGPUCopyTextureForBrowserOptions)) +WGPUProcQueueOnSubmittedWorkDone = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.CFUNCTYPE(None, WGPUQueueWorkDoneStatus, ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcQueueOnSubmittedWorkDone2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUQueueImpl), struct_WGPUQueueWorkDoneCallbackInfo2) +WGPUProcQueueOnSubmittedWorkDoneF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUQueueImpl), struct_WGPUQueueWorkDoneCallbackInfo) +WGPUProcQueueSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), struct_WGPUStringView) +WGPUProcQueueSubmit = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.POINTER(struct_WGPUCommandBufferImpl))) +WGPUProcQueueWriteBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.POINTER(None), ctypes.c_uint64) +WGPUProcQueueWriteTexture = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(None), ctypes.c_uint64, ctypes.POINTER(struct_WGPUTextureDataLayout), ctypes.POINTER(struct_WGPUExtent3D)) +WGPUProcQueueAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl)) +WGPUProcQueueRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUQueueImpl)) +WGPUProcRenderBundleSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleImpl), struct_WGPUStringView) +WGPUProcRenderBundleAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleImpl)) +WGPUProcRenderBundleRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleImpl)) +WGPUProcRenderBundleEncoderDraw = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32) +WGPUProcRenderBundleEncoderDrawIndexed = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_int32, ctypes.c_uint32) +WGPUProcRenderBundleEncoderDrawIndexedIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderBundleEncoderDrawIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderBundleEncoderFinish = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPURenderBundleImpl), ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPURenderBundleDescriptor)) +WGPUProcRenderBundleEncoderInsertDebugMarker = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), struct_WGPUStringView) +WGPUProcRenderBundleEncoderPopDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl)) +WGPUProcRenderBundleEncoderPushDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), struct_WGPUStringView) +WGPUProcRenderBundleEncoderSetBindGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.c_uint32, ctypes.POINTER(struct_WGPUBindGroupImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.c_uint32)) +WGPUProcRenderBundleEncoderSetIndexBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), WGPUIndexFormat, ctypes.c_uint64, ctypes.c_uint64) +WGPUProcRenderBundleEncoderSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), struct_WGPUStringView) +WGPUProcRenderBundleEncoderSetPipeline = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.POINTER(struct_WGPURenderPipelineImpl)) +WGPUProcRenderBundleEncoderSetVertexBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl), ctypes.c_uint32, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcRenderBundleEncoderAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl)) +WGPUProcRenderBundleEncoderRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderBundleEncoderImpl)) +WGPUProcRenderPassEncoderBeginOcclusionQuery = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32) +WGPUProcRenderPassEncoderDraw = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32) +WGPUProcRenderPassEncoderDrawIndexed = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_int32, ctypes.c_uint32) +WGPUProcRenderPassEncoderDrawIndexedIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderPassEncoderDrawIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderPassEncoderEnd = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPassEncoderEndOcclusionQuery = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPassEncoderExecuteBundles = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.POINTER(struct_WGPURenderBundleImpl))) +WGPUProcRenderPassEncoderInsertDebugMarker = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), struct_WGPUStringView) +WGPUProcRenderPassEncoderMultiDrawIndexedIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint32, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderPassEncoderMultiDrawIndirect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint32, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64) +WGPUProcRenderPassEncoderPixelLocalStorageBarrier = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPassEncoderPopDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPassEncoderPushDebugGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), struct_WGPUStringView) +WGPUProcRenderPassEncoderSetBindGroup = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32, ctypes.POINTER(struct_WGPUBindGroupImpl), ctypes.c_uint64, ctypes.POINTER(ctypes.c_uint32)) +WGPUProcRenderPassEncoderSetBlendConstant = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUColor)) +WGPUProcRenderPassEncoderSetIndexBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUBufferImpl), WGPUIndexFormat, ctypes.c_uint64, ctypes.c_uint64) +WGPUProcRenderPassEncoderSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), struct_WGPUStringView) +WGPUProcRenderPassEncoderSetPipeline = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPURenderPipelineImpl)) +WGPUProcRenderPassEncoderSetScissorRect = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32, ctypes.c_uint32) +WGPUProcRenderPassEncoderSetStencilReference = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32) +WGPUProcRenderPassEncoderSetVertexBuffer = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_uint32, ctypes.POINTER(struct_WGPUBufferImpl), ctypes.c_uint64, ctypes.c_uint64) +WGPUProcRenderPassEncoderSetViewport = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float) +WGPUProcRenderPassEncoderWriteTimestamp = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl), ctypes.POINTER(struct_WGPUQuerySetImpl), ctypes.c_uint32) +WGPUProcRenderPassEncoderAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPassEncoderRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPassEncoderImpl)) +WGPUProcRenderPipelineGetBindGroupLayout = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBindGroupLayoutImpl), ctypes.POINTER(struct_WGPURenderPipelineImpl), ctypes.c_uint32) +WGPUProcRenderPipelineSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPipelineImpl), struct_WGPUStringView) +WGPUProcRenderPipelineAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPipelineImpl)) +WGPUProcRenderPipelineRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPURenderPipelineImpl)) +WGPUProcSamplerSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSamplerImpl), struct_WGPUStringView) +WGPUProcSamplerAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSamplerImpl)) +WGPUProcSamplerRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSamplerImpl)) +WGPUProcShaderModuleGetCompilationInfo = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUShaderModuleImpl), ctypes.CFUNCTYPE(None, WGPUCompilationInfoRequestStatus, ctypes.POINTER(struct_WGPUCompilationInfo), ctypes.POINTER(None)), ctypes.POINTER(None)) +WGPUProcShaderModuleGetCompilationInfo2 = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUShaderModuleImpl), struct_WGPUCompilationInfoCallbackInfo2) +WGPUProcShaderModuleGetCompilationInfoF = ctypes.CFUNCTYPE(struct_WGPUFuture, ctypes.POINTER(struct_WGPUShaderModuleImpl), struct_WGPUCompilationInfoCallbackInfo) +WGPUProcShaderModuleSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUShaderModuleImpl), struct_WGPUStringView) +WGPUProcShaderModuleAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUShaderModuleImpl)) +WGPUProcShaderModuleRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUShaderModuleImpl)) +WGPUProcSharedBufferMemoryBeginAccess = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.POINTER(struct_WGPUSharedBufferMemoryBeginAccessDescriptor)) +WGPUProcSharedBufferMemoryCreateBuffer = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUBufferImpl), ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), ctypes.POINTER(struct_WGPUBufferDescriptor)) +WGPUProcSharedBufferMemoryEndAccess = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), ctypes.POINTER(struct_WGPUBufferImpl), ctypes.POINTER(struct_WGPUSharedBufferMemoryEndAccessState)) +WGPUProcSharedBufferMemoryGetProperties = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), ctypes.POINTER(struct_WGPUSharedBufferMemoryProperties)) +WGPUProcSharedBufferMemoryIsDeviceLost = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl)) +WGPUProcSharedBufferMemorySetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl), struct_WGPUStringView) +WGPUProcSharedBufferMemoryAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl)) +WGPUProcSharedBufferMemoryRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedBufferMemoryImpl)) +WGPUProcSharedFenceExportInfo = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedFenceImpl), ctypes.POINTER(struct_WGPUSharedFenceExportInfo)) +WGPUProcSharedFenceAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedFenceImpl)) +WGPUProcSharedFenceRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedFenceImpl)) +WGPUProcSharedTextureMemoryBeginAccess = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUSharedTextureMemoryBeginAccessDescriptor)) +WGPUProcSharedTextureMemoryCreateTexture = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), ctypes.POINTER(struct_WGPUTextureDescriptor)) +WGPUProcSharedTextureMemoryEndAccess = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUSharedTextureMemoryEndAccessState)) +WGPUProcSharedTextureMemoryGetProperties = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), ctypes.POINTER(struct_WGPUSharedTextureMemoryProperties)) +WGPUProcSharedTextureMemoryIsDeviceLost = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl)) +WGPUProcSharedTextureMemorySetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl), struct_WGPUStringView) +WGPUProcSharedTextureMemoryAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl)) +WGPUProcSharedTextureMemoryRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSharedTextureMemoryImpl)) +WGPUProcSurfaceConfigure = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl), ctypes.POINTER(struct_WGPUSurfaceConfiguration)) +WGPUProcSurfaceGetCapabilities = ctypes.CFUNCTYPE(WGPUStatus, ctypes.POINTER(struct_WGPUSurfaceImpl), ctypes.POINTER(struct_WGPUAdapterImpl), ctypes.POINTER(struct_WGPUSurfaceCapabilities)) +WGPUProcSurfaceGetCurrentTexture = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl), ctypes.POINTER(struct_WGPUSurfaceTexture)) +WGPUProcSurfacePresent = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl)) +WGPUProcSurfaceSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl), struct_WGPUStringView) +WGPUProcSurfaceUnconfigure = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl)) +WGPUProcSurfaceAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl)) +WGPUProcSurfaceRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUSurfaceImpl)) +WGPUProcTextureCreateErrorView = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUTextureViewImpl), ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUTextureViewDescriptor)) +WGPUProcTextureCreateView = ctypes.CFUNCTYPE(ctypes.POINTER(struct_WGPUTextureViewImpl), ctypes.POINTER(struct_WGPUTextureImpl), ctypes.POINTER(struct_WGPUTextureViewDescriptor)) +WGPUProcTextureDestroy = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetDepthOrArrayLayers = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetDimension = ctypes.CFUNCTYPE(WGPUTextureDimension, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetFormat = ctypes.CFUNCTYPE(WGPUTextureFormat, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetHeight = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetMipLevelCount = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetSampleCount = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetUsage = ctypes.CFUNCTYPE(ctypes.c_uint64, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureGetWidth = ctypes.CFUNCTYPE(ctypes.c_uint32, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureImpl), struct_WGPUStringView) +WGPUProcTextureAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureImpl)) +WGPUProcTextureViewSetLabel = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureViewImpl), struct_WGPUStringView) +WGPUProcTextureViewAddRef = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureViewImpl)) +WGPUProcTextureViewRelease = ctypes.CFUNCTYPE(None, ctypes.POINTER(struct_WGPUTextureViewImpl)) +try: + wgpuAdapterInfoFreeMembers = _libraries['webgpu'].wgpuAdapterInfoFreeMembers + wgpuAdapterInfoFreeMembers.restype = None + wgpuAdapterInfoFreeMembers.argtypes = [WGPUAdapterInfo] +except AttributeError: + pass +try: + wgpuAdapterPropertiesMemoryHeapsFreeMembers = _libraries['webgpu'].wgpuAdapterPropertiesMemoryHeapsFreeMembers + wgpuAdapterPropertiesMemoryHeapsFreeMembers.restype = None + wgpuAdapterPropertiesMemoryHeapsFreeMembers.argtypes = [WGPUAdapterPropertiesMemoryHeaps] +except AttributeError: + pass +try: + wgpuCreateInstance = _libraries['webgpu'].wgpuCreateInstance + wgpuCreateInstance.restype = WGPUInstance + wgpuCreateInstance.argtypes = [ctypes.POINTER(struct_WGPUInstanceDescriptor)] +except AttributeError: + pass +try: + wgpuDrmFormatCapabilitiesFreeMembers = _libraries['webgpu'].wgpuDrmFormatCapabilitiesFreeMembers + wgpuDrmFormatCapabilitiesFreeMembers.restype = None + wgpuDrmFormatCapabilitiesFreeMembers.argtypes = [WGPUDrmFormatCapabilities] +except AttributeError: + pass +try: + wgpuGetInstanceFeatures = _libraries['webgpu'].wgpuGetInstanceFeatures + wgpuGetInstanceFeatures.restype = WGPUStatus + wgpuGetInstanceFeatures.argtypes = [ctypes.POINTER(struct_WGPUInstanceFeatures)] +except AttributeError: + pass +try: + wgpuGetProcAddress = _libraries['webgpu'].wgpuGetProcAddress + wgpuGetProcAddress.restype = WGPUProc + wgpuGetProcAddress.argtypes = [WGPUStringView] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryEndAccessStateFreeMembers = _libraries['webgpu'].wgpuSharedBufferMemoryEndAccessStateFreeMembers + wgpuSharedBufferMemoryEndAccessStateFreeMembers.restype = None + wgpuSharedBufferMemoryEndAccessStateFreeMembers.argtypes = [WGPUSharedBufferMemoryEndAccessState] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryEndAccessStateFreeMembers = _libraries['webgpu'].wgpuSharedTextureMemoryEndAccessStateFreeMembers + wgpuSharedTextureMemoryEndAccessStateFreeMembers.restype = None + wgpuSharedTextureMemoryEndAccessStateFreeMembers.argtypes = [WGPUSharedTextureMemoryEndAccessState] +except AttributeError: + pass +try: + wgpuSupportedFeaturesFreeMembers = _libraries['webgpu'].wgpuSupportedFeaturesFreeMembers + wgpuSupportedFeaturesFreeMembers.restype = None + wgpuSupportedFeaturesFreeMembers.argtypes = [WGPUSupportedFeatures] +except AttributeError: + pass +try: + wgpuSurfaceCapabilitiesFreeMembers = _libraries['webgpu'].wgpuSurfaceCapabilitiesFreeMembers + wgpuSurfaceCapabilitiesFreeMembers.restype = None + wgpuSurfaceCapabilitiesFreeMembers.argtypes = [WGPUSurfaceCapabilities] +except AttributeError: + pass +try: + wgpuAdapterCreateDevice = _libraries['webgpu'].wgpuAdapterCreateDevice + wgpuAdapterCreateDevice.restype = WGPUDevice + wgpuAdapterCreateDevice.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUDeviceDescriptor)] +except AttributeError: + pass +try: + wgpuAdapterGetFeatures = _libraries['webgpu'].wgpuAdapterGetFeatures + wgpuAdapterGetFeatures.restype = None + wgpuAdapterGetFeatures.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUSupportedFeatures)] +except AttributeError: + pass +try: + wgpuAdapterGetFormatCapabilities = _libraries['webgpu'].wgpuAdapterGetFormatCapabilities + wgpuAdapterGetFormatCapabilities.restype = WGPUStatus + wgpuAdapterGetFormatCapabilities.argtypes = [WGPUAdapter, WGPUTextureFormat, ctypes.POINTER(struct_WGPUFormatCapabilities)] +except AttributeError: + pass +try: + wgpuAdapterGetInfo = _libraries['webgpu'].wgpuAdapterGetInfo + wgpuAdapterGetInfo.restype = WGPUStatus + wgpuAdapterGetInfo.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUAdapterInfo)] +except AttributeError: + pass +try: + wgpuAdapterGetInstance = _libraries['webgpu'].wgpuAdapterGetInstance + wgpuAdapterGetInstance.restype = WGPUInstance + wgpuAdapterGetInstance.argtypes = [WGPUAdapter] +except AttributeError: + pass +try: + wgpuAdapterGetLimits = _libraries['webgpu'].wgpuAdapterGetLimits + wgpuAdapterGetLimits.restype = WGPUStatus + wgpuAdapterGetLimits.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUSupportedLimits)] +except AttributeError: + pass +try: + wgpuAdapterHasFeature = _libraries['webgpu'].wgpuAdapterHasFeature + wgpuAdapterHasFeature.restype = WGPUBool + wgpuAdapterHasFeature.argtypes = [WGPUAdapter, WGPUFeatureName] +except AttributeError: + pass +try: + wgpuAdapterRequestDevice = _libraries['webgpu'].wgpuAdapterRequestDevice + wgpuAdapterRequestDevice.restype = None + wgpuAdapterRequestDevice.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUDeviceDescriptor), WGPURequestDeviceCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuAdapterRequestDevice2 = _libraries['webgpu'].wgpuAdapterRequestDevice2 + wgpuAdapterRequestDevice2.restype = WGPUFuture + wgpuAdapterRequestDevice2.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUDeviceDescriptor), WGPURequestDeviceCallbackInfo2] +except AttributeError: + pass +try: + wgpuAdapterRequestDeviceF = _libraries['webgpu'].wgpuAdapterRequestDeviceF + wgpuAdapterRequestDeviceF.restype = WGPUFuture + wgpuAdapterRequestDeviceF.argtypes = [WGPUAdapter, ctypes.POINTER(struct_WGPUDeviceDescriptor), WGPURequestDeviceCallbackInfo] +except AttributeError: + pass +try: + wgpuAdapterAddRef = _libraries['webgpu'].wgpuAdapterAddRef + wgpuAdapterAddRef.restype = None + wgpuAdapterAddRef.argtypes = [WGPUAdapter] +except AttributeError: + pass +try: + wgpuAdapterRelease = _libraries['webgpu'].wgpuAdapterRelease + wgpuAdapterRelease.restype = None + wgpuAdapterRelease.argtypes = [WGPUAdapter] +except AttributeError: + pass +try: + wgpuBindGroupSetLabel = _libraries['webgpu'].wgpuBindGroupSetLabel + wgpuBindGroupSetLabel.restype = None + wgpuBindGroupSetLabel.argtypes = [WGPUBindGroup, WGPUStringView] +except AttributeError: + pass +try: + wgpuBindGroupAddRef = _libraries['webgpu'].wgpuBindGroupAddRef + wgpuBindGroupAddRef.restype = None + wgpuBindGroupAddRef.argtypes = [WGPUBindGroup] +except AttributeError: + pass +try: + wgpuBindGroupRelease = _libraries['webgpu'].wgpuBindGroupRelease + wgpuBindGroupRelease.restype = None + wgpuBindGroupRelease.argtypes = [WGPUBindGroup] +except AttributeError: + pass +try: + wgpuBindGroupLayoutSetLabel = _libraries['webgpu'].wgpuBindGroupLayoutSetLabel + wgpuBindGroupLayoutSetLabel.restype = None + wgpuBindGroupLayoutSetLabel.argtypes = [WGPUBindGroupLayout, WGPUStringView] +except AttributeError: + pass +try: + wgpuBindGroupLayoutAddRef = _libraries['webgpu'].wgpuBindGroupLayoutAddRef + wgpuBindGroupLayoutAddRef.restype = None + wgpuBindGroupLayoutAddRef.argtypes = [WGPUBindGroupLayout] +except AttributeError: + pass +try: + wgpuBindGroupLayoutRelease = _libraries['webgpu'].wgpuBindGroupLayoutRelease + wgpuBindGroupLayoutRelease.restype = None + wgpuBindGroupLayoutRelease.argtypes = [WGPUBindGroupLayout] +except AttributeError: + pass +try: + wgpuBufferDestroy = _libraries['webgpu'].wgpuBufferDestroy + wgpuBufferDestroy.restype = None + wgpuBufferDestroy.argtypes = [WGPUBuffer] +except AttributeError: + pass +size_t = ctypes.c_uint64 +try: + wgpuBufferGetConstMappedRange = _libraries['webgpu'].wgpuBufferGetConstMappedRange + wgpuBufferGetConstMappedRange.restype = ctypes.POINTER(None) + wgpuBufferGetConstMappedRange.argtypes = [WGPUBuffer, size_t, size_t] +except AttributeError: + pass +try: + wgpuBufferGetMapState = _libraries['webgpu'].wgpuBufferGetMapState + wgpuBufferGetMapState.restype = WGPUBufferMapState + wgpuBufferGetMapState.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuBufferGetMappedRange = _libraries['webgpu'].wgpuBufferGetMappedRange + wgpuBufferGetMappedRange.restype = ctypes.POINTER(None) + wgpuBufferGetMappedRange.argtypes = [WGPUBuffer, size_t, size_t] +except AttributeError: + pass +uint64_t = ctypes.c_uint64 +try: + wgpuBufferGetSize = _libraries['webgpu'].wgpuBufferGetSize + wgpuBufferGetSize.restype = uint64_t + wgpuBufferGetSize.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuBufferGetUsage = _libraries['webgpu'].wgpuBufferGetUsage + wgpuBufferGetUsage.restype = WGPUBufferUsage + wgpuBufferGetUsage.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuBufferMapAsync = _libraries['webgpu'].wgpuBufferMapAsync + wgpuBufferMapAsync.restype = None + wgpuBufferMapAsync.argtypes = [WGPUBuffer, WGPUMapMode, size_t, size_t, WGPUBufferMapCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuBufferMapAsync2 = _libraries['webgpu'].wgpuBufferMapAsync2 + wgpuBufferMapAsync2.restype = WGPUFuture + wgpuBufferMapAsync2.argtypes = [WGPUBuffer, WGPUMapMode, size_t, size_t, WGPUBufferMapCallbackInfo2] +except AttributeError: + pass +try: + wgpuBufferMapAsyncF = _libraries['webgpu'].wgpuBufferMapAsyncF + wgpuBufferMapAsyncF.restype = WGPUFuture + wgpuBufferMapAsyncF.argtypes = [WGPUBuffer, WGPUMapMode, size_t, size_t, WGPUBufferMapCallbackInfo] +except AttributeError: + pass +try: + wgpuBufferSetLabel = _libraries['webgpu'].wgpuBufferSetLabel + wgpuBufferSetLabel.restype = None + wgpuBufferSetLabel.argtypes = [WGPUBuffer, WGPUStringView] +except AttributeError: + pass +try: + wgpuBufferUnmap = _libraries['webgpu'].wgpuBufferUnmap + wgpuBufferUnmap.restype = None + wgpuBufferUnmap.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuBufferAddRef = _libraries['webgpu'].wgpuBufferAddRef + wgpuBufferAddRef.restype = None + wgpuBufferAddRef.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuBufferRelease = _libraries['webgpu'].wgpuBufferRelease + wgpuBufferRelease.restype = None + wgpuBufferRelease.argtypes = [WGPUBuffer] +except AttributeError: + pass +try: + wgpuCommandBufferSetLabel = _libraries['webgpu'].wgpuCommandBufferSetLabel + wgpuCommandBufferSetLabel.restype = None + wgpuCommandBufferSetLabel.argtypes = [WGPUCommandBuffer, WGPUStringView] +except AttributeError: + pass +try: + wgpuCommandBufferAddRef = _libraries['webgpu'].wgpuCommandBufferAddRef + wgpuCommandBufferAddRef.restype = None + wgpuCommandBufferAddRef.argtypes = [WGPUCommandBuffer] +except AttributeError: + pass +try: + wgpuCommandBufferRelease = _libraries['webgpu'].wgpuCommandBufferRelease + wgpuCommandBufferRelease.restype = None + wgpuCommandBufferRelease.argtypes = [WGPUCommandBuffer] +except AttributeError: + pass +try: + wgpuCommandEncoderBeginComputePass = _libraries['webgpu'].wgpuCommandEncoderBeginComputePass + wgpuCommandEncoderBeginComputePass.restype = WGPUComputePassEncoder + wgpuCommandEncoderBeginComputePass.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPUComputePassDescriptor)] +except AttributeError: + pass +try: + wgpuCommandEncoderBeginRenderPass = _libraries['webgpu'].wgpuCommandEncoderBeginRenderPass + wgpuCommandEncoderBeginRenderPass.restype = WGPURenderPassEncoder + wgpuCommandEncoderBeginRenderPass.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPURenderPassDescriptor)] +except AttributeError: + pass +try: + wgpuCommandEncoderClearBuffer = _libraries['webgpu'].wgpuCommandEncoderClearBuffer + wgpuCommandEncoderClearBuffer.restype = None + wgpuCommandEncoderClearBuffer.argtypes = [WGPUCommandEncoder, WGPUBuffer, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuCommandEncoderCopyBufferToBuffer = _libraries['webgpu'].wgpuCommandEncoderCopyBufferToBuffer + wgpuCommandEncoderCopyBufferToBuffer.restype = None + wgpuCommandEncoderCopyBufferToBuffer.argtypes = [WGPUCommandEncoder, WGPUBuffer, uint64_t, WGPUBuffer, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuCommandEncoderCopyBufferToTexture = _libraries['webgpu'].wgpuCommandEncoderCopyBufferToTexture + wgpuCommandEncoderCopyBufferToTexture.restype = None + wgpuCommandEncoderCopyBufferToTexture.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPUImageCopyBuffer), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D)] +except AttributeError: + pass +try: + wgpuCommandEncoderCopyTextureToBuffer = _libraries['webgpu'].wgpuCommandEncoderCopyTextureToBuffer + wgpuCommandEncoderCopyTextureToBuffer.restype = None + wgpuCommandEncoderCopyTextureToBuffer.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyBuffer), ctypes.POINTER(struct_WGPUExtent3D)] +except AttributeError: + pass +try: + wgpuCommandEncoderCopyTextureToTexture = _libraries['webgpu'].wgpuCommandEncoderCopyTextureToTexture + wgpuCommandEncoderCopyTextureToTexture.restype = None + wgpuCommandEncoderCopyTextureToTexture.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D)] +except AttributeError: + pass +try: + wgpuCommandEncoderFinish = _libraries['webgpu'].wgpuCommandEncoderFinish + wgpuCommandEncoderFinish.restype = WGPUCommandBuffer + wgpuCommandEncoderFinish.argtypes = [WGPUCommandEncoder, ctypes.POINTER(struct_WGPUCommandBufferDescriptor)] +except AttributeError: + pass +try: + wgpuCommandEncoderInjectValidationError = _libraries['webgpu'].wgpuCommandEncoderInjectValidationError + wgpuCommandEncoderInjectValidationError.restype = None + wgpuCommandEncoderInjectValidationError.argtypes = [WGPUCommandEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuCommandEncoderInsertDebugMarker = _libraries['webgpu'].wgpuCommandEncoderInsertDebugMarker + wgpuCommandEncoderInsertDebugMarker.restype = None + wgpuCommandEncoderInsertDebugMarker.argtypes = [WGPUCommandEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuCommandEncoderPopDebugGroup = _libraries['webgpu'].wgpuCommandEncoderPopDebugGroup + wgpuCommandEncoderPopDebugGroup.restype = None + wgpuCommandEncoderPopDebugGroup.argtypes = [WGPUCommandEncoder] +except AttributeError: + pass +try: + wgpuCommandEncoderPushDebugGroup = _libraries['webgpu'].wgpuCommandEncoderPushDebugGroup + wgpuCommandEncoderPushDebugGroup.restype = None + wgpuCommandEncoderPushDebugGroup.argtypes = [WGPUCommandEncoder, WGPUStringView] +except AttributeError: + pass +uint32_t = ctypes.c_uint32 +try: + wgpuCommandEncoderResolveQuerySet = _libraries['webgpu'].wgpuCommandEncoderResolveQuerySet + wgpuCommandEncoderResolveQuerySet.restype = None + wgpuCommandEncoderResolveQuerySet.argtypes = [WGPUCommandEncoder, WGPUQuerySet, uint32_t, uint32_t, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuCommandEncoderSetLabel = _libraries['webgpu'].wgpuCommandEncoderSetLabel + wgpuCommandEncoderSetLabel.restype = None + wgpuCommandEncoderSetLabel.argtypes = [WGPUCommandEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuCommandEncoderWriteBuffer = _libraries['webgpu'].wgpuCommandEncoderWriteBuffer + wgpuCommandEncoderWriteBuffer.restype = None + wgpuCommandEncoderWriteBuffer.argtypes = [WGPUCommandEncoder, WGPUBuffer, uint64_t, ctypes.POINTER(ctypes.c_ubyte), uint64_t] +except AttributeError: + pass +try: + wgpuCommandEncoderWriteTimestamp = _libraries['webgpu'].wgpuCommandEncoderWriteTimestamp + wgpuCommandEncoderWriteTimestamp.restype = None + wgpuCommandEncoderWriteTimestamp.argtypes = [WGPUCommandEncoder, WGPUQuerySet, uint32_t] +except AttributeError: + pass +try: + wgpuCommandEncoderAddRef = _libraries['webgpu'].wgpuCommandEncoderAddRef + wgpuCommandEncoderAddRef.restype = None + wgpuCommandEncoderAddRef.argtypes = [WGPUCommandEncoder] +except AttributeError: + pass +try: + wgpuCommandEncoderRelease = _libraries['webgpu'].wgpuCommandEncoderRelease + wgpuCommandEncoderRelease.restype = None + wgpuCommandEncoderRelease.argtypes = [WGPUCommandEncoder] +except AttributeError: + pass +try: + wgpuComputePassEncoderDispatchWorkgroups = _libraries['webgpu'].wgpuComputePassEncoderDispatchWorkgroups + wgpuComputePassEncoderDispatchWorkgroups.restype = None + wgpuComputePassEncoderDispatchWorkgroups.argtypes = [WGPUComputePassEncoder, uint32_t, uint32_t, uint32_t] +except AttributeError: + pass +try: + wgpuComputePassEncoderDispatchWorkgroupsIndirect = _libraries['webgpu'].wgpuComputePassEncoderDispatchWorkgroupsIndirect + wgpuComputePassEncoderDispatchWorkgroupsIndirect.restype = None + wgpuComputePassEncoderDispatchWorkgroupsIndirect.argtypes = [WGPUComputePassEncoder, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuComputePassEncoderEnd = _libraries['webgpu'].wgpuComputePassEncoderEnd + wgpuComputePassEncoderEnd.restype = None + wgpuComputePassEncoderEnd.argtypes = [WGPUComputePassEncoder] +except AttributeError: + pass +try: + wgpuComputePassEncoderInsertDebugMarker = _libraries['webgpu'].wgpuComputePassEncoderInsertDebugMarker + wgpuComputePassEncoderInsertDebugMarker.restype = None + wgpuComputePassEncoderInsertDebugMarker.argtypes = [WGPUComputePassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuComputePassEncoderPopDebugGroup = _libraries['webgpu'].wgpuComputePassEncoderPopDebugGroup + wgpuComputePassEncoderPopDebugGroup.restype = None + wgpuComputePassEncoderPopDebugGroup.argtypes = [WGPUComputePassEncoder] +except AttributeError: + pass +try: + wgpuComputePassEncoderPushDebugGroup = _libraries['webgpu'].wgpuComputePassEncoderPushDebugGroup + wgpuComputePassEncoderPushDebugGroup.restype = None + wgpuComputePassEncoderPushDebugGroup.argtypes = [WGPUComputePassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuComputePassEncoderSetBindGroup = _libraries['webgpu'].wgpuComputePassEncoderSetBindGroup + wgpuComputePassEncoderSetBindGroup.restype = None + wgpuComputePassEncoderSetBindGroup.argtypes = [WGPUComputePassEncoder, uint32_t, WGPUBindGroup, size_t, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + wgpuComputePassEncoderSetLabel = _libraries['webgpu'].wgpuComputePassEncoderSetLabel + wgpuComputePassEncoderSetLabel.restype = None + wgpuComputePassEncoderSetLabel.argtypes = [WGPUComputePassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuComputePassEncoderSetPipeline = _libraries['webgpu'].wgpuComputePassEncoderSetPipeline + wgpuComputePassEncoderSetPipeline.restype = None + wgpuComputePassEncoderSetPipeline.argtypes = [WGPUComputePassEncoder, WGPUComputePipeline] +except AttributeError: + pass +try: + wgpuComputePassEncoderWriteTimestamp = _libraries['webgpu'].wgpuComputePassEncoderWriteTimestamp + wgpuComputePassEncoderWriteTimestamp.restype = None + wgpuComputePassEncoderWriteTimestamp.argtypes = [WGPUComputePassEncoder, WGPUQuerySet, uint32_t] +except AttributeError: + pass +try: + wgpuComputePassEncoderAddRef = _libraries['webgpu'].wgpuComputePassEncoderAddRef + wgpuComputePassEncoderAddRef.restype = None + wgpuComputePassEncoderAddRef.argtypes = [WGPUComputePassEncoder] +except AttributeError: + pass +try: + wgpuComputePassEncoderRelease = _libraries['webgpu'].wgpuComputePassEncoderRelease + wgpuComputePassEncoderRelease.restype = None + wgpuComputePassEncoderRelease.argtypes = [WGPUComputePassEncoder] +except AttributeError: + pass +try: + wgpuComputePipelineGetBindGroupLayout = _libraries['webgpu'].wgpuComputePipelineGetBindGroupLayout + wgpuComputePipelineGetBindGroupLayout.restype = WGPUBindGroupLayout + wgpuComputePipelineGetBindGroupLayout.argtypes = [WGPUComputePipeline, uint32_t] +except AttributeError: + pass +try: + wgpuComputePipelineSetLabel = _libraries['webgpu'].wgpuComputePipelineSetLabel + wgpuComputePipelineSetLabel.restype = None + wgpuComputePipelineSetLabel.argtypes = [WGPUComputePipeline, WGPUStringView] +except AttributeError: + pass +try: + wgpuComputePipelineAddRef = _libraries['webgpu'].wgpuComputePipelineAddRef + wgpuComputePipelineAddRef.restype = None + wgpuComputePipelineAddRef.argtypes = [WGPUComputePipeline] +except AttributeError: + pass +try: + wgpuComputePipelineRelease = _libraries['webgpu'].wgpuComputePipelineRelease + wgpuComputePipelineRelease.restype = None + wgpuComputePipelineRelease.argtypes = [WGPUComputePipeline] +except AttributeError: + pass +try: + wgpuDeviceCreateBindGroup = _libraries['webgpu'].wgpuDeviceCreateBindGroup + wgpuDeviceCreateBindGroup.restype = WGPUBindGroup + wgpuDeviceCreateBindGroup.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUBindGroupDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateBindGroupLayout = _libraries['webgpu'].wgpuDeviceCreateBindGroupLayout + wgpuDeviceCreateBindGroupLayout.restype = WGPUBindGroupLayout + wgpuDeviceCreateBindGroupLayout.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUBindGroupLayoutDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateBuffer = _libraries['webgpu'].wgpuDeviceCreateBuffer + wgpuDeviceCreateBuffer.restype = WGPUBuffer + wgpuDeviceCreateBuffer.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUBufferDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateCommandEncoder = _libraries['webgpu'].wgpuDeviceCreateCommandEncoder + wgpuDeviceCreateCommandEncoder.restype = WGPUCommandEncoder + wgpuDeviceCreateCommandEncoder.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUCommandEncoderDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateComputePipeline = _libraries['webgpu'].wgpuDeviceCreateComputePipeline + wgpuDeviceCreateComputePipeline.restype = WGPUComputePipeline + wgpuDeviceCreateComputePipeline.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUComputePipelineDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateComputePipelineAsync = _libraries['webgpu'].wgpuDeviceCreateComputePipelineAsync + wgpuDeviceCreateComputePipelineAsync.restype = None + wgpuDeviceCreateComputePipelineAsync.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUComputePipelineDescriptor), WGPUCreateComputePipelineAsyncCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuDeviceCreateComputePipelineAsync2 = _libraries['webgpu'].wgpuDeviceCreateComputePipelineAsync2 + wgpuDeviceCreateComputePipelineAsync2.restype = WGPUFuture + wgpuDeviceCreateComputePipelineAsync2.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUComputePipelineDescriptor), WGPUCreateComputePipelineAsyncCallbackInfo2] +except AttributeError: + pass +try: + wgpuDeviceCreateComputePipelineAsyncF = _libraries['webgpu'].wgpuDeviceCreateComputePipelineAsyncF + wgpuDeviceCreateComputePipelineAsyncF.restype = WGPUFuture + wgpuDeviceCreateComputePipelineAsyncF.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUComputePipelineDescriptor), WGPUCreateComputePipelineAsyncCallbackInfo] +except AttributeError: + pass +try: + wgpuDeviceCreateErrorBuffer = _libraries['webgpu'].wgpuDeviceCreateErrorBuffer + wgpuDeviceCreateErrorBuffer.restype = WGPUBuffer + wgpuDeviceCreateErrorBuffer.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUBufferDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateErrorExternalTexture = _libraries['webgpu'].wgpuDeviceCreateErrorExternalTexture + wgpuDeviceCreateErrorExternalTexture.restype = WGPUExternalTexture + wgpuDeviceCreateErrorExternalTexture.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceCreateErrorShaderModule = _libraries['webgpu'].wgpuDeviceCreateErrorShaderModule + wgpuDeviceCreateErrorShaderModule.restype = WGPUShaderModule + wgpuDeviceCreateErrorShaderModule.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUShaderModuleDescriptor), WGPUStringView] +except AttributeError: + pass +try: + wgpuDeviceCreateErrorTexture = _libraries['webgpu'].wgpuDeviceCreateErrorTexture + wgpuDeviceCreateErrorTexture.restype = WGPUTexture + wgpuDeviceCreateErrorTexture.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUTextureDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateExternalTexture = _libraries['webgpu'].wgpuDeviceCreateExternalTexture + wgpuDeviceCreateExternalTexture.restype = WGPUExternalTexture + wgpuDeviceCreateExternalTexture.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUExternalTextureDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreatePipelineLayout = _libraries['webgpu'].wgpuDeviceCreatePipelineLayout + wgpuDeviceCreatePipelineLayout.restype = WGPUPipelineLayout + wgpuDeviceCreatePipelineLayout.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUPipelineLayoutDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateQuerySet = _libraries['webgpu'].wgpuDeviceCreateQuerySet + wgpuDeviceCreateQuerySet.restype = WGPUQuerySet + wgpuDeviceCreateQuerySet.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUQuerySetDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateRenderBundleEncoder = _libraries['webgpu'].wgpuDeviceCreateRenderBundleEncoder + wgpuDeviceCreateRenderBundleEncoder.restype = WGPURenderBundleEncoder + wgpuDeviceCreateRenderBundleEncoder.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPURenderBundleEncoderDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateRenderPipeline = _libraries['webgpu'].wgpuDeviceCreateRenderPipeline + wgpuDeviceCreateRenderPipeline.restype = WGPURenderPipeline + wgpuDeviceCreateRenderPipeline.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPURenderPipelineDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateRenderPipelineAsync = _libraries['webgpu'].wgpuDeviceCreateRenderPipelineAsync + wgpuDeviceCreateRenderPipelineAsync.restype = None + wgpuDeviceCreateRenderPipelineAsync.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPURenderPipelineDescriptor), WGPUCreateRenderPipelineAsyncCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuDeviceCreateRenderPipelineAsync2 = _libraries['webgpu'].wgpuDeviceCreateRenderPipelineAsync2 + wgpuDeviceCreateRenderPipelineAsync2.restype = WGPUFuture + wgpuDeviceCreateRenderPipelineAsync2.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPURenderPipelineDescriptor), WGPUCreateRenderPipelineAsyncCallbackInfo2] +except AttributeError: + pass +try: + wgpuDeviceCreateRenderPipelineAsyncF = _libraries['webgpu'].wgpuDeviceCreateRenderPipelineAsyncF + wgpuDeviceCreateRenderPipelineAsyncF.restype = WGPUFuture + wgpuDeviceCreateRenderPipelineAsyncF.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPURenderPipelineDescriptor), WGPUCreateRenderPipelineAsyncCallbackInfo] +except AttributeError: + pass +try: + wgpuDeviceCreateSampler = _libraries['webgpu'].wgpuDeviceCreateSampler + wgpuDeviceCreateSampler.restype = WGPUSampler + wgpuDeviceCreateSampler.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSamplerDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateShaderModule = _libraries['webgpu'].wgpuDeviceCreateShaderModule + wgpuDeviceCreateShaderModule.restype = WGPUShaderModule + wgpuDeviceCreateShaderModule.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUShaderModuleDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceCreateTexture = _libraries['webgpu'].wgpuDeviceCreateTexture + wgpuDeviceCreateTexture.restype = WGPUTexture + wgpuDeviceCreateTexture.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUTextureDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceDestroy = _libraries['webgpu'].wgpuDeviceDestroy + wgpuDeviceDestroy.restype = None + wgpuDeviceDestroy.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceForceLoss = _libraries['webgpu'].wgpuDeviceForceLoss + wgpuDeviceForceLoss.restype = None + wgpuDeviceForceLoss.argtypes = [WGPUDevice, WGPUDeviceLostReason, WGPUStringView] +except AttributeError: + pass +try: + wgpuDeviceGetAHardwareBufferProperties = _libraries['webgpu'].wgpuDeviceGetAHardwareBufferProperties + wgpuDeviceGetAHardwareBufferProperties.restype = WGPUStatus + wgpuDeviceGetAHardwareBufferProperties.argtypes = [WGPUDevice, ctypes.POINTER(None), ctypes.POINTER(struct_WGPUAHardwareBufferProperties)] +except AttributeError: + pass +try: + wgpuDeviceGetAdapter = _libraries['webgpu'].wgpuDeviceGetAdapter + wgpuDeviceGetAdapter.restype = WGPUAdapter + wgpuDeviceGetAdapter.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceGetAdapterInfo = _libraries['webgpu'].wgpuDeviceGetAdapterInfo + wgpuDeviceGetAdapterInfo.restype = WGPUStatus + wgpuDeviceGetAdapterInfo.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUAdapterInfo)] +except AttributeError: + pass +try: + wgpuDeviceGetFeatures = _libraries['webgpu'].wgpuDeviceGetFeatures + wgpuDeviceGetFeatures.restype = None + wgpuDeviceGetFeatures.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSupportedFeatures)] +except AttributeError: + pass +try: + wgpuDeviceGetLimits = _libraries['webgpu'].wgpuDeviceGetLimits + wgpuDeviceGetLimits.restype = WGPUStatus + wgpuDeviceGetLimits.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSupportedLimits)] +except AttributeError: + pass +try: + wgpuDeviceGetLostFuture = _libraries['webgpu'].wgpuDeviceGetLostFuture + wgpuDeviceGetLostFuture.restype = WGPUFuture + wgpuDeviceGetLostFuture.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceGetQueue = _libraries['webgpu'].wgpuDeviceGetQueue + wgpuDeviceGetQueue.restype = WGPUQueue + wgpuDeviceGetQueue.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceHasFeature = _libraries['webgpu'].wgpuDeviceHasFeature + wgpuDeviceHasFeature.restype = WGPUBool + wgpuDeviceHasFeature.argtypes = [WGPUDevice, WGPUFeatureName] +except AttributeError: + pass +try: + wgpuDeviceImportSharedBufferMemory = _libraries['webgpu'].wgpuDeviceImportSharedBufferMemory + wgpuDeviceImportSharedBufferMemory.restype = WGPUSharedBufferMemory + wgpuDeviceImportSharedBufferMemory.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSharedBufferMemoryDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceImportSharedFence = _libraries['webgpu'].wgpuDeviceImportSharedFence + wgpuDeviceImportSharedFence.restype = WGPUSharedFence + wgpuDeviceImportSharedFence.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSharedFenceDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceImportSharedTextureMemory = _libraries['webgpu'].wgpuDeviceImportSharedTextureMemory + wgpuDeviceImportSharedTextureMemory.restype = WGPUSharedTextureMemory + wgpuDeviceImportSharedTextureMemory.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUSharedTextureMemoryDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceInjectError = _libraries['webgpu'].wgpuDeviceInjectError + wgpuDeviceInjectError.restype = None + wgpuDeviceInjectError.argtypes = [WGPUDevice, WGPUErrorType, WGPUStringView] +except AttributeError: + pass +try: + wgpuDevicePopErrorScope = _libraries['webgpu'].wgpuDevicePopErrorScope + wgpuDevicePopErrorScope.restype = None + wgpuDevicePopErrorScope.argtypes = [WGPUDevice, WGPUErrorCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuDevicePopErrorScope2 = _libraries['webgpu'].wgpuDevicePopErrorScope2 + wgpuDevicePopErrorScope2.restype = WGPUFuture + wgpuDevicePopErrorScope2.argtypes = [WGPUDevice, WGPUPopErrorScopeCallbackInfo2] +except AttributeError: + pass +try: + wgpuDevicePopErrorScopeF = _libraries['webgpu'].wgpuDevicePopErrorScopeF + wgpuDevicePopErrorScopeF.restype = WGPUFuture + wgpuDevicePopErrorScopeF.argtypes = [WGPUDevice, WGPUPopErrorScopeCallbackInfo] +except AttributeError: + pass +try: + wgpuDevicePushErrorScope = _libraries['webgpu'].wgpuDevicePushErrorScope + wgpuDevicePushErrorScope.restype = None + wgpuDevicePushErrorScope.argtypes = [WGPUDevice, WGPUErrorFilter] +except AttributeError: + pass +try: + wgpuDeviceSetLabel = _libraries['webgpu'].wgpuDeviceSetLabel + wgpuDeviceSetLabel.restype = None + wgpuDeviceSetLabel.argtypes = [WGPUDevice, WGPUStringView] +except AttributeError: + pass +try: + wgpuDeviceSetLoggingCallback = _libraries['webgpu'].wgpuDeviceSetLoggingCallback + wgpuDeviceSetLoggingCallback.restype = None + wgpuDeviceSetLoggingCallback.argtypes = [WGPUDevice, WGPULoggingCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuDeviceTick = _libraries['webgpu'].wgpuDeviceTick + wgpuDeviceTick.restype = None + wgpuDeviceTick.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceValidateTextureDescriptor = _libraries['webgpu'].wgpuDeviceValidateTextureDescriptor + wgpuDeviceValidateTextureDescriptor.restype = None + wgpuDeviceValidateTextureDescriptor.argtypes = [WGPUDevice, ctypes.POINTER(struct_WGPUTextureDescriptor)] +except AttributeError: + pass +try: + wgpuDeviceAddRef = _libraries['webgpu'].wgpuDeviceAddRef + wgpuDeviceAddRef.restype = None + wgpuDeviceAddRef.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuDeviceRelease = _libraries['webgpu'].wgpuDeviceRelease + wgpuDeviceRelease.restype = None + wgpuDeviceRelease.argtypes = [WGPUDevice] +except AttributeError: + pass +try: + wgpuExternalTextureDestroy = _libraries['webgpu'].wgpuExternalTextureDestroy + wgpuExternalTextureDestroy.restype = None + wgpuExternalTextureDestroy.argtypes = [WGPUExternalTexture] +except AttributeError: + pass +try: + wgpuExternalTextureExpire = _libraries['webgpu'].wgpuExternalTextureExpire + wgpuExternalTextureExpire.restype = None + wgpuExternalTextureExpire.argtypes = [WGPUExternalTexture] +except AttributeError: + pass +try: + wgpuExternalTextureRefresh = _libraries['webgpu'].wgpuExternalTextureRefresh + wgpuExternalTextureRefresh.restype = None + wgpuExternalTextureRefresh.argtypes = [WGPUExternalTexture] +except AttributeError: + pass +try: + wgpuExternalTextureSetLabel = _libraries['webgpu'].wgpuExternalTextureSetLabel + wgpuExternalTextureSetLabel.restype = None + wgpuExternalTextureSetLabel.argtypes = [WGPUExternalTexture, WGPUStringView] +except AttributeError: + pass +try: + wgpuExternalTextureAddRef = _libraries['webgpu'].wgpuExternalTextureAddRef + wgpuExternalTextureAddRef.restype = None + wgpuExternalTextureAddRef.argtypes = [WGPUExternalTexture] +except AttributeError: + pass +try: + wgpuExternalTextureRelease = _libraries['webgpu'].wgpuExternalTextureRelease + wgpuExternalTextureRelease.restype = None + wgpuExternalTextureRelease.argtypes = [WGPUExternalTexture] +except AttributeError: + pass +try: + wgpuInstanceCreateSurface = _libraries['webgpu'].wgpuInstanceCreateSurface + wgpuInstanceCreateSurface.restype = WGPUSurface + wgpuInstanceCreateSurface.argtypes = [WGPUInstance, ctypes.POINTER(struct_WGPUSurfaceDescriptor)] +except AttributeError: + pass +try: + wgpuInstanceEnumerateWGSLLanguageFeatures = _libraries['webgpu'].wgpuInstanceEnumerateWGSLLanguageFeatures + wgpuInstanceEnumerateWGSLLanguageFeatures.restype = size_t + wgpuInstanceEnumerateWGSLLanguageFeatures.argtypes = [WGPUInstance, ctypes.POINTER(WGPUWGSLFeatureName)] +except AttributeError: + pass +try: + wgpuInstanceHasWGSLLanguageFeature = _libraries['webgpu'].wgpuInstanceHasWGSLLanguageFeature + wgpuInstanceHasWGSLLanguageFeature.restype = WGPUBool + wgpuInstanceHasWGSLLanguageFeature.argtypes = [WGPUInstance, WGPUWGSLFeatureName] +except AttributeError: + pass +try: + wgpuInstanceProcessEvents = _libraries['webgpu'].wgpuInstanceProcessEvents + wgpuInstanceProcessEvents.restype = None + wgpuInstanceProcessEvents.argtypes = [WGPUInstance] +except AttributeError: + pass +try: + wgpuInstanceRequestAdapter = _libraries['webgpu'].wgpuInstanceRequestAdapter + wgpuInstanceRequestAdapter.restype = None + wgpuInstanceRequestAdapter.argtypes = [WGPUInstance, ctypes.POINTER(struct_WGPURequestAdapterOptions), WGPURequestAdapterCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuInstanceRequestAdapter2 = _libraries['webgpu'].wgpuInstanceRequestAdapter2 + wgpuInstanceRequestAdapter2.restype = WGPUFuture + wgpuInstanceRequestAdapter2.argtypes = [WGPUInstance, ctypes.POINTER(struct_WGPURequestAdapterOptions), WGPURequestAdapterCallbackInfo2] +except AttributeError: + pass +try: + wgpuInstanceRequestAdapterF = _libraries['webgpu'].wgpuInstanceRequestAdapterF + wgpuInstanceRequestAdapterF.restype = WGPUFuture + wgpuInstanceRequestAdapterF.argtypes = [WGPUInstance, ctypes.POINTER(struct_WGPURequestAdapterOptions), WGPURequestAdapterCallbackInfo] +except AttributeError: + pass +try: + wgpuInstanceWaitAny = _libraries['webgpu'].wgpuInstanceWaitAny + wgpuInstanceWaitAny.restype = WGPUWaitStatus + wgpuInstanceWaitAny.argtypes = [WGPUInstance, size_t, ctypes.POINTER(struct_WGPUFutureWaitInfo), uint64_t] +except AttributeError: + pass +try: + wgpuInstanceAddRef = _libraries['webgpu'].wgpuInstanceAddRef + wgpuInstanceAddRef.restype = None + wgpuInstanceAddRef.argtypes = [WGPUInstance] +except AttributeError: + pass +try: + wgpuInstanceRelease = _libraries['webgpu'].wgpuInstanceRelease + wgpuInstanceRelease.restype = None + wgpuInstanceRelease.argtypes = [WGPUInstance] +except AttributeError: + pass +try: + wgpuPipelineLayoutSetLabel = _libraries['webgpu'].wgpuPipelineLayoutSetLabel + wgpuPipelineLayoutSetLabel.restype = None + wgpuPipelineLayoutSetLabel.argtypes = [WGPUPipelineLayout, WGPUStringView] +except AttributeError: + pass +try: + wgpuPipelineLayoutAddRef = _libraries['webgpu'].wgpuPipelineLayoutAddRef + wgpuPipelineLayoutAddRef.restype = None + wgpuPipelineLayoutAddRef.argtypes = [WGPUPipelineLayout] +except AttributeError: + pass +try: + wgpuPipelineLayoutRelease = _libraries['webgpu'].wgpuPipelineLayoutRelease + wgpuPipelineLayoutRelease.restype = None + wgpuPipelineLayoutRelease.argtypes = [WGPUPipelineLayout] +except AttributeError: + pass +try: + wgpuQuerySetDestroy = _libraries['webgpu'].wgpuQuerySetDestroy + wgpuQuerySetDestroy.restype = None + wgpuQuerySetDestroy.argtypes = [WGPUQuerySet] +except AttributeError: + pass +try: + wgpuQuerySetGetCount = _libraries['webgpu'].wgpuQuerySetGetCount + wgpuQuerySetGetCount.restype = uint32_t + wgpuQuerySetGetCount.argtypes = [WGPUQuerySet] +except AttributeError: + pass +try: + wgpuQuerySetGetType = _libraries['webgpu'].wgpuQuerySetGetType + wgpuQuerySetGetType.restype = WGPUQueryType + wgpuQuerySetGetType.argtypes = [WGPUQuerySet] +except AttributeError: + pass +try: + wgpuQuerySetSetLabel = _libraries['webgpu'].wgpuQuerySetSetLabel + wgpuQuerySetSetLabel.restype = None + wgpuQuerySetSetLabel.argtypes = [WGPUQuerySet, WGPUStringView] +except AttributeError: + pass +try: + wgpuQuerySetAddRef = _libraries['webgpu'].wgpuQuerySetAddRef + wgpuQuerySetAddRef.restype = None + wgpuQuerySetAddRef.argtypes = [WGPUQuerySet] +except AttributeError: + pass +try: + wgpuQuerySetRelease = _libraries['webgpu'].wgpuQuerySetRelease + wgpuQuerySetRelease.restype = None + wgpuQuerySetRelease.argtypes = [WGPUQuerySet] +except AttributeError: + pass +try: + wgpuQueueCopyExternalTextureForBrowser = _libraries['webgpu'].wgpuQueueCopyExternalTextureForBrowser + wgpuQueueCopyExternalTextureForBrowser.restype = None + wgpuQueueCopyExternalTextureForBrowser.argtypes = [WGPUQueue, ctypes.POINTER(struct_WGPUImageCopyExternalTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D), ctypes.POINTER(struct_WGPUCopyTextureForBrowserOptions)] +except AttributeError: + pass +try: + wgpuQueueCopyTextureForBrowser = _libraries['webgpu'].wgpuQueueCopyTextureForBrowser + wgpuQueueCopyTextureForBrowser.restype = None + wgpuQueueCopyTextureForBrowser.argtypes = [WGPUQueue, ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(struct_WGPUExtent3D), ctypes.POINTER(struct_WGPUCopyTextureForBrowserOptions)] +except AttributeError: + pass +try: + wgpuQueueOnSubmittedWorkDone = _libraries['webgpu'].wgpuQueueOnSubmittedWorkDone + wgpuQueueOnSubmittedWorkDone.restype = None + wgpuQueueOnSubmittedWorkDone.argtypes = [WGPUQueue, WGPUQueueWorkDoneCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuQueueOnSubmittedWorkDone2 = _libraries['webgpu'].wgpuQueueOnSubmittedWorkDone2 + wgpuQueueOnSubmittedWorkDone2.restype = WGPUFuture + wgpuQueueOnSubmittedWorkDone2.argtypes = [WGPUQueue, WGPUQueueWorkDoneCallbackInfo2] +except AttributeError: + pass +try: + wgpuQueueOnSubmittedWorkDoneF = _libraries['webgpu'].wgpuQueueOnSubmittedWorkDoneF + wgpuQueueOnSubmittedWorkDoneF.restype = WGPUFuture + wgpuQueueOnSubmittedWorkDoneF.argtypes = [WGPUQueue, WGPUQueueWorkDoneCallbackInfo] +except AttributeError: + pass +try: + wgpuQueueSetLabel = _libraries['webgpu'].wgpuQueueSetLabel + wgpuQueueSetLabel.restype = None + wgpuQueueSetLabel.argtypes = [WGPUQueue, WGPUStringView] +except AttributeError: + pass +try: + wgpuQueueSubmit = _libraries['webgpu'].wgpuQueueSubmit + wgpuQueueSubmit.restype = None + wgpuQueueSubmit.argtypes = [WGPUQueue, size_t, ctypes.POINTER(ctypes.POINTER(struct_WGPUCommandBufferImpl))] +except AttributeError: + pass +try: + wgpuQueueWriteBuffer = _libraries['webgpu'].wgpuQueueWriteBuffer + wgpuQueueWriteBuffer.restype = None + wgpuQueueWriteBuffer.argtypes = [WGPUQueue, WGPUBuffer, uint64_t, ctypes.POINTER(None), size_t] +except AttributeError: + pass +try: + wgpuQueueWriteTexture = _libraries['webgpu'].wgpuQueueWriteTexture + wgpuQueueWriteTexture.restype = None + wgpuQueueWriteTexture.argtypes = [WGPUQueue, ctypes.POINTER(struct_WGPUImageCopyTexture), ctypes.POINTER(None), size_t, ctypes.POINTER(struct_WGPUTextureDataLayout), ctypes.POINTER(struct_WGPUExtent3D)] +except AttributeError: + pass +try: + wgpuQueueAddRef = _libraries['webgpu'].wgpuQueueAddRef + wgpuQueueAddRef.restype = None + wgpuQueueAddRef.argtypes = [WGPUQueue] +except AttributeError: + pass +try: + wgpuQueueRelease = _libraries['webgpu'].wgpuQueueRelease + wgpuQueueRelease.restype = None + wgpuQueueRelease.argtypes = [WGPUQueue] +except AttributeError: + pass +try: + wgpuRenderBundleSetLabel = _libraries['webgpu'].wgpuRenderBundleSetLabel + wgpuRenderBundleSetLabel.restype = None + wgpuRenderBundleSetLabel.argtypes = [WGPURenderBundle, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderBundleAddRef = _libraries['webgpu'].wgpuRenderBundleAddRef + wgpuRenderBundleAddRef.restype = None + wgpuRenderBundleAddRef.argtypes = [WGPURenderBundle] +except AttributeError: + pass +try: + wgpuRenderBundleRelease = _libraries['webgpu'].wgpuRenderBundleRelease + wgpuRenderBundleRelease.restype = None + wgpuRenderBundleRelease.argtypes = [WGPURenderBundle] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderDraw = _libraries['webgpu'].wgpuRenderBundleEncoderDraw + wgpuRenderBundleEncoderDraw.restype = None + wgpuRenderBundleEncoderDraw.argtypes = [WGPURenderBundleEncoder, uint32_t, uint32_t, uint32_t, uint32_t] +except AttributeError: + pass +int32_t = ctypes.c_int32 +try: + wgpuRenderBundleEncoderDrawIndexed = _libraries['webgpu'].wgpuRenderBundleEncoderDrawIndexed + wgpuRenderBundleEncoderDrawIndexed.restype = None + wgpuRenderBundleEncoderDrawIndexed.argtypes = [WGPURenderBundleEncoder, uint32_t, uint32_t, uint32_t, int32_t, uint32_t] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderDrawIndexedIndirect = _libraries['webgpu'].wgpuRenderBundleEncoderDrawIndexedIndirect + wgpuRenderBundleEncoderDrawIndexedIndirect.restype = None + wgpuRenderBundleEncoderDrawIndexedIndirect.argtypes = [WGPURenderBundleEncoder, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderDrawIndirect = _libraries['webgpu'].wgpuRenderBundleEncoderDrawIndirect + wgpuRenderBundleEncoderDrawIndirect.restype = None + wgpuRenderBundleEncoderDrawIndirect.argtypes = [WGPURenderBundleEncoder, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderFinish = _libraries['webgpu'].wgpuRenderBundleEncoderFinish + wgpuRenderBundleEncoderFinish.restype = WGPURenderBundle + wgpuRenderBundleEncoderFinish.argtypes = [WGPURenderBundleEncoder, ctypes.POINTER(struct_WGPURenderBundleDescriptor)] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderInsertDebugMarker = _libraries['webgpu'].wgpuRenderBundleEncoderInsertDebugMarker + wgpuRenderBundleEncoderInsertDebugMarker.restype = None + wgpuRenderBundleEncoderInsertDebugMarker.argtypes = [WGPURenderBundleEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderPopDebugGroup = _libraries['webgpu'].wgpuRenderBundleEncoderPopDebugGroup + wgpuRenderBundleEncoderPopDebugGroup.restype = None + wgpuRenderBundleEncoderPopDebugGroup.argtypes = [WGPURenderBundleEncoder] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderPushDebugGroup = _libraries['webgpu'].wgpuRenderBundleEncoderPushDebugGroup + wgpuRenderBundleEncoderPushDebugGroup.restype = None + wgpuRenderBundleEncoderPushDebugGroup.argtypes = [WGPURenderBundleEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderSetBindGroup = _libraries['webgpu'].wgpuRenderBundleEncoderSetBindGroup + wgpuRenderBundleEncoderSetBindGroup.restype = None + wgpuRenderBundleEncoderSetBindGroup.argtypes = [WGPURenderBundleEncoder, uint32_t, WGPUBindGroup, size_t, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderSetIndexBuffer = _libraries['webgpu'].wgpuRenderBundleEncoderSetIndexBuffer + wgpuRenderBundleEncoderSetIndexBuffer.restype = None + wgpuRenderBundleEncoderSetIndexBuffer.argtypes = [WGPURenderBundleEncoder, WGPUBuffer, WGPUIndexFormat, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderSetLabel = _libraries['webgpu'].wgpuRenderBundleEncoderSetLabel + wgpuRenderBundleEncoderSetLabel.restype = None + wgpuRenderBundleEncoderSetLabel.argtypes = [WGPURenderBundleEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderSetPipeline = _libraries['webgpu'].wgpuRenderBundleEncoderSetPipeline + wgpuRenderBundleEncoderSetPipeline.restype = None + wgpuRenderBundleEncoderSetPipeline.argtypes = [WGPURenderBundleEncoder, WGPURenderPipeline] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderSetVertexBuffer = _libraries['webgpu'].wgpuRenderBundleEncoderSetVertexBuffer + wgpuRenderBundleEncoderSetVertexBuffer.restype = None + wgpuRenderBundleEncoderSetVertexBuffer.argtypes = [WGPURenderBundleEncoder, uint32_t, WGPUBuffer, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderAddRef = _libraries['webgpu'].wgpuRenderBundleEncoderAddRef + wgpuRenderBundleEncoderAddRef.restype = None + wgpuRenderBundleEncoderAddRef.argtypes = [WGPURenderBundleEncoder] +except AttributeError: + pass +try: + wgpuRenderBundleEncoderRelease = _libraries['webgpu'].wgpuRenderBundleEncoderRelease + wgpuRenderBundleEncoderRelease.restype = None + wgpuRenderBundleEncoderRelease.argtypes = [WGPURenderBundleEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderBeginOcclusionQuery = _libraries['webgpu'].wgpuRenderPassEncoderBeginOcclusionQuery + wgpuRenderPassEncoderBeginOcclusionQuery.restype = None + wgpuRenderPassEncoderBeginOcclusionQuery.argtypes = [WGPURenderPassEncoder, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderDraw = _libraries['webgpu'].wgpuRenderPassEncoderDraw + wgpuRenderPassEncoderDraw.restype = None + wgpuRenderPassEncoderDraw.argtypes = [WGPURenderPassEncoder, uint32_t, uint32_t, uint32_t, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderDrawIndexed = _libraries['webgpu'].wgpuRenderPassEncoderDrawIndexed + wgpuRenderPassEncoderDrawIndexed.restype = None + wgpuRenderPassEncoderDrawIndexed.argtypes = [WGPURenderPassEncoder, uint32_t, uint32_t, uint32_t, int32_t, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderDrawIndexedIndirect = _libraries['webgpu'].wgpuRenderPassEncoderDrawIndexedIndirect + wgpuRenderPassEncoderDrawIndexedIndirect.restype = None + wgpuRenderPassEncoderDrawIndexedIndirect.argtypes = [WGPURenderPassEncoder, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderDrawIndirect = _libraries['webgpu'].wgpuRenderPassEncoderDrawIndirect + wgpuRenderPassEncoderDrawIndirect.restype = None + wgpuRenderPassEncoderDrawIndirect.argtypes = [WGPURenderPassEncoder, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderEnd = _libraries['webgpu'].wgpuRenderPassEncoderEnd + wgpuRenderPassEncoderEnd.restype = None + wgpuRenderPassEncoderEnd.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderEndOcclusionQuery = _libraries['webgpu'].wgpuRenderPassEncoderEndOcclusionQuery + wgpuRenderPassEncoderEndOcclusionQuery.restype = None + wgpuRenderPassEncoderEndOcclusionQuery.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderExecuteBundles = _libraries['webgpu'].wgpuRenderPassEncoderExecuteBundles + wgpuRenderPassEncoderExecuteBundles.restype = None + wgpuRenderPassEncoderExecuteBundles.argtypes = [WGPURenderPassEncoder, size_t, ctypes.POINTER(ctypes.POINTER(struct_WGPURenderBundleImpl))] +except AttributeError: + pass +try: + wgpuRenderPassEncoderInsertDebugMarker = _libraries['webgpu'].wgpuRenderPassEncoderInsertDebugMarker + wgpuRenderPassEncoderInsertDebugMarker.restype = None + wgpuRenderPassEncoderInsertDebugMarker.argtypes = [WGPURenderPassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderPassEncoderMultiDrawIndexedIndirect = _libraries['webgpu'].wgpuRenderPassEncoderMultiDrawIndexedIndirect + wgpuRenderPassEncoderMultiDrawIndexedIndirect.restype = None + wgpuRenderPassEncoderMultiDrawIndexedIndirect.argtypes = [WGPURenderPassEncoder, WGPUBuffer, uint64_t, uint32_t, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderMultiDrawIndirect = _libraries['webgpu'].wgpuRenderPassEncoderMultiDrawIndirect + wgpuRenderPassEncoderMultiDrawIndirect.restype = None + wgpuRenderPassEncoderMultiDrawIndirect.argtypes = [WGPURenderPassEncoder, WGPUBuffer, uint64_t, uint32_t, WGPUBuffer, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderPixelLocalStorageBarrier = _libraries['webgpu'].wgpuRenderPassEncoderPixelLocalStorageBarrier + wgpuRenderPassEncoderPixelLocalStorageBarrier.restype = None + wgpuRenderPassEncoderPixelLocalStorageBarrier.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderPopDebugGroup = _libraries['webgpu'].wgpuRenderPassEncoderPopDebugGroup + wgpuRenderPassEncoderPopDebugGroup.restype = None + wgpuRenderPassEncoderPopDebugGroup.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderPushDebugGroup = _libraries['webgpu'].wgpuRenderPassEncoderPushDebugGroup + wgpuRenderPassEncoderPushDebugGroup.restype = None + wgpuRenderPassEncoderPushDebugGroup.argtypes = [WGPURenderPassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetBindGroup = _libraries['webgpu'].wgpuRenderPassEncoderSetBindGroup + wgpuRenderPassEncoderSetBindGroup.restype = None + wgpuRenderPassEncoderSetBindGroup.argtypes = [WGPURenderPassEncoder, uint32_t, WGPUBindGroup, size_t, ctypes.POINTER(ctypes.c_uint32)] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetBlendConstant = _libraries['webgpu'].wgpuRenderPassEncoderSetBlendConstant + wgpuRenderPassEncoderSetBlendConstant.restype = None + wgpuRenderPassEncoderSetBlendConstant.argtypes = [WGPURenderPassEncoder, ctypes.POINTER(struct_WGPUColor)] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetIndexBuffer = _libraries['webgpu'].wgpuRenderPassEncoderSetIndexBuffer + wgpuRenderPassEncoderSetIndexBuffer.restype = None + wgpuRenderPassEncoderSetIndexBuffer.argtypes = [WGPURenderPassEncoder, WGPUBuffer, WGPUIndexFormat, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetLabel = _libraries['webgpu'].wgpuRenderPassEncoderSetLabel + wgpuRenderPassEncoderSetLabel.restype = None + wgpuRenderPassEncoderSetLabel.argtypes = [WGPURenderPassEncoder, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetPipeline = _libraries['webgpu'].wgpuRenderPassEncoderSetPipeline + wgpuRenderPassEncoderSetPipeline.restype = None + wgpuRenderPassEncoderSetPipeline.argtypes = [WGPURenderPassEncoder, WGPURenderPipeline] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetScissorRect = _libraries['webgpu'].wgpuRenderPassEncoderSetScissorRect + wgpuRenderPassEncoderSetScissorRect.restype = None + wgpuRenderPassEncoderSetScissorRect.argtypes = [WGPURenderPassEncoder, uint32_t, uint32_t, uint32_t, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetStencilReference = _libraries['webgpu'].wgpuRenderPassEncoderSetStencilReference + wgpuRenderPassEncoderSetStencilReference.restype = None + wgpuRenderPassEncoderSetStencilReference.argtypes = [WGPURenderPassEncoder, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetVertexBuffer = _libraries['webgpu'].wgpuRenderPassEncoderSetVertexBuffer + wgpuRenderPassEncoderSetVertexBuffer.restype = None + wgpuRenderPassEncoderSetVertexBuffer.argtypes = [WGPURenderPassEncoder, uint32_t, WGPUBuffer, uint64_t, uint64_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderSetViewport = _libraries['webgpu'].wgpuRenderPassEncoderSetViewport + wgpuRenderPassEncoderSetViewport.restype = None + wgpuRenderPassEncoderSetViewport.argtypes = [WGPURenderPassEncoder, ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float, ctypes.c_float] +except AttributeError: + pass +try: + wgpuRenderPassEncoderWriteTimestamp = _libraries['webgpu'].wgpuRenderPassEncoderWriteTimestamp + wgpuRenderPassEncoderWriteTimestamp.restype = None + wgpuRenderPassEncoderWriteTimestamp.argtypes = [WGPURenderPassEncoder, WGPUQuerySet, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPassEncoderAddRef = _libraries['webgpu'].wgpuRenderPassEncoderAddRef + wgpuRenderPassEncoderAddRef.restype = None + wgpuRenderPassEncoderAddRef.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPassEncoderRelease = _libraries['webgpu'].wgpuRenderPassEncoderRelease + wgpuRenderPassEncoderRelease.restype = None + wgpuRenderPassEncoderRelease.argtypes = [WGPURenderPassEncoder] +except AttributeError: + pass +try: + wgpuRenderPipelineGetBindGroupLayout = _libraries['webgpu'].wgpuRenderPipelineGetBindGroupLayout + wgpuRenderPipelineGetBindGroupLayout.restype = WGPUBindGroupLayout + wgpuRenderPipelineGetBindGroupLayout.argtypes = [WGPURenderPipeline, uint32_t] +except AttributeError: + pass +try: + wgpuRenderPipelineSetLabel = _libraries['webgpu'].wgpuRenderPipelineSetLabel + wgpuRenderPipelineSetLabel.restype = None + wgpuRenderPipelineSetLabel.argtypes = [WGPURenderPipeline, WGPUStringView] +except AttributeError: + pass +try: + wgpuRenderPipelineAddRef = _libraries['webgpu'].wgpuRenderPipelineAddRef + wgpuRenderPipelineAddRef.restype = None + wgpuRenderPipelineAddRef.argtypes = [WGPURenderPipeline] +except AttributeError: + pass +try: + wgpuRenderPipelineRelease = _libraries['webgpu'].wgpuRenderPipelineRelease + wgpuRenderPipelineRelease.restype = None + wgpuRenderPipelineRelease.argtypes = [WGPURenderPipeline] +except AttributeError: + pass +try: + wgpuSamplerSetLabel = _libraries['webgpu'].wgpuSamplerSetLabel + wgpuSamplerSetLabel.restype = None + wgpuSamplerSetLabel.argtypes = [WGPUSampler, WGPUStringView] +except AttributeError: + pass +try: + wgpuSamplerAddRef = _libraries['webgpu'].wgpuSamplerAddRef + wgpuSamplerAddRef.restype = None + wgpuSamplerAddRef.argtypes = [WGPUSampler] +except AttributeError: + pass +try: + wgpuSamplerRelease = _libraries['webgpu'].wgpuSamplerRelease + wgpuSamplerRelease.restype = None + wgpuSamplerRelease.argtypes = [WGPUSampler] +except AttributeError: + pass +try: + wgpuShaderModuleGetCompilationInfo = _libraries['webgpu'].wgpuShaderModuleGetCompilationInfo + wgpuShaderModuleGetCompilationInfo.restype = None + wgpuShaderModuleGetCompilationInfo.argtypes = [WGPUShaderModule, WGPUCompilationInfoCallback, ctypes.POINTER(None)] +except AttributeError: + pass +try: + wgpuShaderModuleGetCompilationInfo2 = _libraries['webgpu'].wgpuShaderModuleGetCompilationInfo2 + wgpuShaderModuleGetCompilationInfo2.restype = WGPUFuture + wgpuShaderModuleGetCompilationInfo2.argtypes = [WGPUShaderModule, WGPUCompilationInfoCallbackInfo2] +except AttributeError: + pass +try: + wgpuShaderModuleGetCompilationInfoF = _libraries['webgpu'].wgpuShaderModuleGetCompilationInfoF + wgpuShaderModuleGetCompilationInfoF.restype = WGPUFuture + wgpuShaderModuleGetCompilationInfoF.argtypes = [WGPUShaderModule, WGPUCompilationInfoCallbackInfo] +except AttributeError: + pass +try: + wgpuShaderModuleSetLabel = _libraries['webgpu'].wgpuShaderModuleSetLabel + wgpuShaderModuleSetLabel.restype = None + wgpuShaderModuleSetLabel.argtypes = [WGPUShaderModule, WGPUStringView] +except AttributeError: + pass +try: + wgpuShaderModuleAddRef = _libraries['webgpu'].wgpuShaderModuleAddRef + wgpuShaderModuleAddRef.restype = None + wgpuShaderModuleAddRef.argtypes = [WGPUShaderModule] +except AttributeError: + pass +try: + wgpuShaderModuleRelease = _libraries['webgpu'].wgpuShaderModuleRelease + wgpuShaderModuleRelease.restype = None + wgpuShaderModuleRelease.argtypes = [WGPUShaderModule] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryBeginAccess = _libraries['webgpu'].wgpuSharedBufferMemoryBeginAccess + wgpuSharedBufferMemoryBeginAccess.restype = WGPUStatus + wgpuSharedBufferMemoryBeginAccess.argtypes = [WGPUSharedBufferMemory, WGPUBuffer, ctypes.POINTER(struct_WGPUSharedBufferMemoryBeginAccessDescriptor)] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryCreateBuffer = _libraries['webgpu'].wgpuSharedBufferMemoryCreateBuffer + wgpuSharedBufferMemoryCreateBuffer.restype = WGPUBuffer + wgpuSharedBufferMemoryCreateBuffer.argtypes = [WGPUSharedBufferMemory, ctypes.POINTER(struct_WGPUBufferDescriptor)] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryEndAccess = _libraries['webgpu'].wgpuSharedBufferMemoryEndAccess + wgpuSharedBufferMemoryEndAccess.restype = WGPUStatus + wgpuSharedBufferMemoryEndAccess.argtypes = [WGPUSharedBufferMemory, WGPUBuffer, ctypes.POINTER(struct_WGPUSharedBufferMemoryEndAccessState)] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryGetProperties = _libraries['webgpu'].wgpuSharedBufferMemoryGetProperties + wgpuSharedBufferMemoryGetProperties.restype = WGPUStatus + wgpuSharedBufferMemoryGetProperties.argtypes = [WGPUSharedBufferMemory, ctypes.POINTER(struct_WGPUSharedBufferMemoryProperties)] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryIsDeviceLost = _libraries['webgpu'].wgpuSharedBufferMemoryIsDeviceLost + wgpuSharedBufferMemoryIsDeviceLost.restype = WGPUBool + wgpuSharedBufferMemoryIsDeviceLost.argtypes = [WGPUSharedBufferMemory] +except AttributeError: + pass +try: + wgpuSharedBufferMemorySetLabel = _libraries['webgpu'].wgpuSharedBufferMemorySetLabel + wgpuSharedBufferMemorySetLabel.restype = None + wgpuSharedBufferMemorySetLabel.argtypes = [WGPUSharedBufferMemory, WGPUStringView] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryAddRef = _libraries['webgpu'].wgpuSharedBufferMemoryAddRef + wgpuSharedBufferMemoryAddRef.restype = None + wgpuSharedBufferMemoryAddRef.argtypes = [WGPUSharedBufferMemory] +except AttributeError: + pass +try: + wgpuSharedBufferMemoryRelease = _libraries['webgpu'].wgpuSharedBufferMemoryRelease + wgpuSharedBufferMemoryRelease.restype = None + wgpuSharedBufferMemoryRelease.argtypes = [WGPUSharedBufferMemory] +except AttributeError: + pass +try: + wgpuSharedFenceExportInfo = _libraries['webgpu'].wgpuSharedFenceExportInfo + wgpuSharedFenceExportInfo.restype = None + wgpuSharedFenceExportInfo.argtypes = [WGPUSharedFence, ctypes.POINTER(struct_WGPUSharedFenceExportInfo)] +except AttributeError: + pass +try: + wgpuSharedFenceAddRef = _libraries['webgpu'].wgpuSharedFenceAddRef + wgpuSharedFenceAddRef.restype = None + wgpuSharedFenceAddRef.argtypes = [WGPUSharedFence] +except AttributeError: + pass +try: + wgpuSharedFenceRelease = _libraries['webgpu'].wgpuSharedFenceRelease + wgpuSharedFenceRelease.restype = None + wgpuSharedFenceRelease.argtypes = [WGPUSharedFence] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryBeginAccess = _libraries['webgpu'].wgpuSharedTextureMemoryBeginAccess + wgpuSharedTextureMemoryBeginAccess.restype = WGPUStatus + wgpuSharedTextureMemoryBeginAccess.argtypes = [WGPUSharedTextureMemory, WGPUTexture, ctypes.POINTER(struct_WGPUSharedTextureMemoryBeginAccessDescriptor)] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryCreateTexture = _libraries['webgpu'].wgpuSharedTextureMemoryCreateTexture + wgpuSharedTextureMemoryCreateTexture.restype = WGPUTexture + wgpuSharedTextureMemoryCreateTexture.argtypes = [WGPUSharedTextureMemory, ctypes.POINTER(struct_WGPUTextureDescriptor)] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryEndAccess = _libraries['webgpu'].wgpuSharedTextureMemoryEndAccess + wgpuSharedTextureMemoryEndAccess.restype = WGPUStatus + wgpuSharedTextureMemoryEndAccess.argtypes = [WGPUSharedTextureMemory, WGPUTexture, ctypes.POINTER(struct_WGPUSharedTextureMemoryEndAccessState)] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryGetProperties = _libraries['webgpu'].wgpuSharedTextureMemoryGetProperties + wgpuSharedTextureMemoryGetProperties.restype = WGPUStatus + wgpuSharedTextureMemoryGetProperties.argtypes = [WGPUSharedTextureMemory, ctypes.POINTER(struct_WGPUSharedTextureMemoryProperties)] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryIsDeviceLost = _libraries['webgpu'].wgpuSharedTextureMemoryIsDeviceLost + wgpuSharedTextureMemoryIsDeviceLost.restype = WGPUBool + wgpuSharedTextureMemoryIsDeviceLost.argtypes = [WGPUSharedTextureMemory] +except AttributeError: + pass +try: + wgpuSharedTextureMemorySetLabel = _libraries['webgpu'].wgpuSharedTextureMemorySetLabel + wgpuSharedTextureMemorySetLabel.restype = None + wgpuSharedTextureMemorySetLabel.argtypes = [WGPUSharedTextureMemory, WGPUStringView] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryAddRef = _libraries['webgpu'].wgpuSharedTextureMemoryAddRef + wgpuSharedTextureMemoryAddRef.restype = None + wgpuSharedTextureMemoryAddRef.argtypes = [WGPUSharedTextureMemory] +except AttributeError: + pass +try: + wgpuSharedTextureMemoryRelease = _libraries['webgpu'].wgpuSharedTextureMemoryRelease + wgpuSharedTextureMemoryRelease.restype = None + wgpuSharedTextureMemoryRelease.argtypes = [WGPUSharedTextureMemory] +except AttributeError: + pass +try: + wgpuSurfaceConfigure = _libraries['webgpu'].wgpuSurfaceConfigure + wgpuSurfaceConfigure.restype = None + wgpuSurfaceConfigure.argtypes = [WGPUSurface, ctypes.POINTER(struct_WGPUSurfaceConfiguration)] +except AttributeError: + pass +try: + wgpuSurfaceGetCapabilities = _libraries['webgpu'].wgpuSurfaceGetCapabilities + wgpuSurfaceGetCapabilities.restype = WGPUStatus + wgpuSurfaceGetCapabilities.argtypes = [WGPUSurface, WGPUAdapter, ctypes.POINTER(struct_WGPUSurfaceCapabilities)] +except AttributeError: + pass +try: + wgpuSurfaceGetCurrentTexture = _libraries['webgpu'].wgpuSurfaceGetCurrentTexture + wgpuSurfaceGetCurrentTexture.restype = None + wgpuSurfaceGetCurrentTexture.argtypes = [WGPUSurface, ctypes.POINTER(struct_WGPUSurfaceTexture)] +except AttributeError: + pass +try: + wgpuSurfacePresent = _libraries['webgpu'].wgpuSurfacePresent + wgpuSurfacePresent.restype = None + wgpuSurfacePresent.argtypes = [WGPUSurface] +except AttributeError: + pass +try: + wgpuSurfaceSetLabel = _libraries['webgpu'].wgpuSurfaceSetLabel + wgpuSurfaceSetLabel.restype = None + wgpuSurfaceSetLabel.argtypes = [WGPUSurface, WGPUStringView] +except AttributeError: + pass +try: + wgpuSurfaceUnconfigure = _libraries['webgpu'].wgpuSurfaceUnconfigure + wgpuSurfaceUnconfigure.restype = None + wgpuSurfaceUnconfigure.argtypes = [WGPUSurface] +except AttributeError: + pass +try: + wgpuSurfaceAddRef = _libraries['webgpu'].wgpuSurfaceAddRef + wgpuSurfaceAddRef.restype = None + wgpuSurfaceAddRef.argtypes = [WGPUSurface] +except AttributeError: + pass +try: + wgpuSurfaceRelease = _libraries['webgpu'].wgpuSurfaceRelease + wgpuSurfaceRelease.restype = None + wgpuSurfaceRelease.argtypes = [WGPUSurface] +except AttributeError: + pass +try: + wgpuTextureCreateErrorView = _libraries['webgpu'].wgpuTextureCreateErrorView + wgpuTextureCreateErrorView.restype = WGPUTextureView + wgpuTextureCreateErrorView.argtypes = [WGPUTexture, ctypes.POINTER(struct_WGPUTextureViewDescriptor)] +except AttributeError: + pass +try: + wgpuTextureCreateView = _libraries['webgpu'].wgpuTextureCreateView + wgpuTextureCreateView.restype = WGPUTextureView + wgpuTextureCreateView.argtypes = [WGPUTexture, ctypes.POINTER(struct_WGPUTextureViewDescriptor)] +except AttributeError: + pass +try: + wgpuTextureDestroy = _libraries['webgpu'].wgpuTextureDestroy + wgpuTextureDestroy.restype = None + wgpuTextureDestroy.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetDepthOrArrayLayers = _libraries['webgpu'].wgpuTextureGetDepthOrArrayLayers + wgpuTextureGetDepthOrArrayLayers.restype = uint32_t + wgpuTextureGetDepthOrArrayLayers.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetDimension = _libraries['webgpu'].wgpuTextureGetDimension + wgpuTextureGetDimension.restype = WGPUTextureDimension + wgpuTextureGetDimension.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetFormat = _libraries['webgpu'].wgpuTextureGetFormat + wgpuTextureGetFormat.restype = WGPUTextureFormat + wgpuTextureGetFormat.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetHeight = _libraries['webgpu'].wgpuTextureGetHeight + wgpuTextureGetHeight.restype = uint32_t + wgpuTextureGetHeight.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetMipLevelCount = _libraries['webgpu'].wgpuTextureGetMipLevelCount + wgpuTextureGetMipLevelCount.restype = uint32_t + wgpuTextureGetMipLevelCount.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetSampleCount = _libraries['webgpu'].wgpuTextureGetSampleCount + wgpuTextureGetSampleCount.restype = uint32_t + wgpuTextureGetSampleCount.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetUsage = _libraries['webgpu'].wgpuTextureGetUsage + wgpuTextureGetUsage.restype = WGPUTextureUsage + wgpuTextureGetUsage.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureGetWidth = _libraries['webgpu'].wgpuTextureGetWidth + wgpuTextureGetWidth.restype = uint32_t + wgpuTextureGetWidth.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureSetLabel = _libraries['webgpu'].wgpuTextureSetLabel + wgpuTextureSetLabel.restype = None + wgpuTextureSetLabel.argtypes = [WGPUTexture, WGPUStringView] +except AttributeError: + pass +try: + wgpuTextureAddRef = _libraries['webgpu'].wgpuTextureAddRef + wgpuTextureAddRef.restype = None + wgpuTextureAddRef.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureRelease = _libraries['webgpu'].wgpuTextureRelease + wgpuTextureRelease.restype = None + wgpuTextureRelease.argtypes = [WGPUTexture] +except AttributeError: + pass +try: + wgpuTextureViewSetLabel = _libraries['webgpu'].wgpuTextureViewSetLabel + wgpuTextureViewSetLabel.restype = None + wgpuTextureViewSetLabel.argtypes = [WGPUTextureView, WGPUStringView] +except AttributeError: + pass +try: + wgpuTextureViewAddRef = _libraries['webgpu'].wgpuTextureViewAddRef + wgpuTextureViewAddRef.restype = None + wgpuTextureViewAddRef.argtypes = [WGPUTextureView] +except AttributeError: + pass +try: + wgpuTextureViewRelease = _libraries['webgpu'].wgpuTextureViewRelease + wgpuTextureViewRelease.restype = None + wgpuTextureViewRelease.argtypes = [WGPUTextureView] +except AttributeError: + pass +__all__ = \ + ['WGPUAHardwareBufferProperties', 'WGPUAdapter', + 'WGPUAdapterInfo', 'WGPUAdapterPropertiesD3D', + 'WGPUAdapterPropertiesMemoryHeaps', + 'WGPUAdapterPropertiesSubgroups', 'WGPUAdapterPropertiesVk', + 'WGPUAdapterType', 'WGPUAdapterType_CPU', + 'WGPUAdapterType_DiscreteGPU', 'WGPUAdapterType_Force32', + 'WGPUAdapterType_IntegratedGPU', 'WGPUAdapterType_Unknown', + 'WGPUAddressMode', 'WGPUAddressMode_ClampToEdge', + 'WGPUAddressMode_Force32', 'WGPUAddressMode_MirrorRepeat', + 'WGPUAddressMode_Repeat', 'WGPUAddressMode_Undefined', + 'WGPUAlphaMode', 'WGPUAlphaMode_Force32', 'WGPUAlphaMode_Opaque', + 'WGPUAlphaMode_Premultiplied', 'WGPUAlphaMode_Unpremultiplied', + 'WGPUBackendType', 'WGPUBackendType_D3D11', + 'WGPUBackendType_D3D12', 'WGPUBackendType_Force32', + 'WGPUBackendType_Metal', 'WGPUBackendType_Null', + 'WGPUBackendType_OpenGL', 'WGPUBackendType_OpenGLES', + 'WGPUBackendType_Undefined', 'WGPUBackendType_Vulkan', + 'WGPUBackendType_WebGPU', 'WGPUBindGroup', + 'WGPUBindGroupDescriptor', 'WGPUBindGroupEntry', + 'WGPUBindGroupLayout', 'WGPUBindGroupLayoutDescriptor', + 'WGPUBindGroupLayoutEntry', 'WGPUBlendComponent', + 'WGPUBlendFactor', 'WGPUBlendFactor_Constant', + 'WGPUBlendFactor_Dst', 'WGPUBlendFactor_DstAlpha', + 'WGPUBlendFactor_Force32', 'WGPUBlendFactor_One', + 'WGPUBlendFactor_OneMinusConstant', 'WGPUBlendFactor_OneMinusDst', + 'WGPUBlendFactor_OneMinusDstAlpha', 'WGPUBlendFactor_OneMinusSrc', + 'WGPUBlendFactor_OneMinusSrc1', + 'WGPUBlendFactor_OneMinusSrc1Alpha', + 'WGPUBlendFactor_OneMinusSrcAlpha', 'WGPUBlendFactor_Src', + 'WGPUBlendFactor_Src1', 'WGPUBlendFactor_Src1Alpha', + 'WGPUBlendFactor_SrcAlpha', 'WGPUBlendFactor_SrcAlphaSaturated', + 'WGPUBlendFactor_Undefined', 'WGPUBlendFactor_Zero', + 'WGPUBlendOperation', 'WGPUBlendOperation_Add', + 'WGPUBlendOperation_Force32', 'WGPUBlendOperation_Max', + 'WGPUBlendOperation_Min', 'WGPUBlendOperation_ReverseSubtract', + 'WGPUBlendOperation_Subtract', 'WGPUBlendOperation_Undefined', + 'WGPUBlendState', 'WGPUBool', 'WGPUBuffer', + 'WGPUBufferBindingLayout', 'WGPUBufferBindingType', + 'WGPUBufferBindingType_BindingNotUsed', + 'WGPUBufferBindingType_Force32', + 'WGPUBufferBindingType_ReadOnlyStorage', + 'WGPUBufferBindingType_Storage', 'WGPUBufferBindingType_Uniform', + 'WGPUBufferDescriptor', 'WGPUBufferHostMappedPointer', + 'WGPUBufferMapAsyncStatus', + 'WGPUBufferMapAsyncStatus_DestroyedBeforeCallback', + 'WGPUBufferMapAsyncStatus_DeviceLost', + 'WGPUBufferMapAsyncStatus_Force32', + 'WGPUBufferMapAsyncStatus_InstanceDropped', + 'WGPUBufferMapAsyncStatus_MappingAlreadyPending', + 'WGPUBufferMapAsyncStatus_OffsetOutOfRange', + 'WGPUBufferMapAsyncStatus_SizeOutOfRange', + 'WGPUBufferMapAsyncStatus_Success', + 'WGPUBufferMapAsyncStatus_Unknown', + 'WGPUBufferMapAsyncStatus_UnmappedBeforeCallback', + 'WGPUBufferMapAsyncStatus_ValidationError', + 'WGPUBufferMapCallback', 'WGPUBufferMapCallback2', + 'WGPUBufferMapCallbackInfo', 'WGPUBufferMapCallbackInfo2', + 'WGPUBufferMapState', 'WGPUBufferMapState_Force32', + 'WGPUBufferMapState_Mapped', 'WGPUBufferMapState_Pending', + 'WGPUBufferMapState_Unmapped', 'WGPUBufferUsage', + 'WGPUBufferUsage_CopyDst', 'WGPUBufferUsage_CopySrc', + 'WGPUBufferUsage_Index', 'WGPUBufferUsage_Indirect', + 'WGPUBufferUsage_MapRead', 'WGPUBufferUsage_MapWrite', + 'WGPUBufferUsage_None', 'WGPUBufferUsage_QueryResolve', + 'WGPUBufferUsage_Storage', 'WGPUBufferUsage_Uniform', + 'WGPUBufferUsage_Vertex', 'WGPUCallback', 'WGPUCallbackMode', + 'WGPUCallbackMode_AllowProcessEvents', + 'WGPUCallbackMode_AllowSpontaneous', 'WGPUCallbackMode_Force32', + 'WGPUCallbackMode_WaitAnyOnly', 'WGPUChainedStruct', + 'WGPUChainedStructOut', 'WGPUColor', 'WGPUColorTargetState', + 'WGPUColorTargetStateExpandResolveTextureDawn', + 'WGPUColorWriteMask', 'WGPUColorWriteMask_All', + 'WGPUColorWriteMask_Alpha', 'WGPUColorWriteMask_Blue', + 'WGPUColorWriteMask_Green', 'WGPUColorWriteMask_None', + 'WGPUColorWriteMask_Red', 'WGPUCommandBuffer', + 'WGPUCommandBufferDescriptor', 'WGPUCommandEncoder', + 'WGPUCommandEncoderDescriptor', 'WGPUCompareFunction', + 'WGPUCompareFunction_Always', 'WGPUCompareFunction_Equal', + 'WGPUCompareFunction_Force32', 'WGPUCompareFunction_Greater', + 'WGPUCompareFunction_GreaterEqual', 'WGPUCompareFunction_Less', + 'WGPUCompareFunction_LessEqual', 'WGPUCompareFunction_Never', + 'WGPUCompareFunction_NotEqual', 'WGPUCompareFunction_Undefined', + 'WGPUCompilationInfo', 'WGPUCompilationInfoCallback', + 'WGPUCompilationInfoCallback2', 'WGPUCompilationInfoCallbackInfo', + 'WGPUCompilationInfoCallbackInfo2', + 'WGPUCompilationInfoRequestStatus', + 'WGPUCompilationInfoRequestStatus_DeviceLost', + 'WGPUCompilationInfoRequestStatus_Error', + 'WGPUCompilationInfoRequestStatus_Force32', + 'WGPUCompilationInfoRequestStatus_InstanceDropped', + 'WGPUCompilationInfoRequestStatus_Success', + 'WGPUCompilationInfoRequestStatus_Unknown', + 'WGPUCompilationMessage', 'WGPUCompilationMessageType', + 'WGPUCompilationMessageType_Error', + 'WGPUCompilationMessageType_Force32', + 'WGPUCompilationMessageType_Info', + 'WGPUCompilationMessageType_Warning', 'WGPUCompositeAlphaMode', + 'WGPUCompositeAlphaMode_Auto', 'WGPUCompositeAlphaMode_Force32', + 'WGPUCompositeAlphaMode_Inherit', 'WGPUCompositeAlphaMode_Opaque', + 'WGPUCompositeAlphaMode_Premultiplied', + 'WGPUCompositeAlphaMode_Unpremultiplied', + 'WGPUComputePassDescriptor', 'WGPUComputePassEncoder', + 'WGPUComputePassTimestampWrites', 'WGPUComputePipeline', + 'WGPUComputePipelineDescriptor', 'WGPUComputeState', + 'WGPUConstantEntry', 'WGPUCopyTextureForBrowserOptions', + 'WGPUCreateComputePipelineAsyncCallback', + 'WGPUCreateComputePipelineAsyncCallback2', + 'WGPUCreateComputePipelineAsyncCallbackInfo', + 'WGPUCreateComputePipelineAsyncCallbackInfo2', + 'WGPUCreatePipelineAsyncStatus', + 'WGPUCreatePipelineAsyncStatus_DeviceDestroyed', + 'WGPUCreatePipelineAsyncStatus_DeviceLost', + 'WGPUCreatePipelineAsyncStatus_Force32', + 'WGPUCreatePipelineAsyncStatus_InstanceDropped', + 'WGPUCreatePipelineAsyncStatus_InternalError', + 'WGPUCreatePipelineAsyncStatus_Success', + 'WGPUCreatePipelineAsyncStatus_Unknown', + 'WGPUCreatePipelineAsyncStatus_ValidationError', + 'WGPUCreateRenderPipelineAsyncCallback', + 'WGPUCreateRenderPipelineAsyncCallback2', + 'WGPUCreateRenderPipelineAsyncCallbackInfo', + 'WGPUCreateRenderPipelineAsyncCallbackInfo2', 'WGPUCullMode', + 'WGPUCullMode_Back', 'WGPUCullMode_Force32', 'WGPUCullMode_Front', + 'WGPUCullMode_None', 'WGPUCullMode_Undefined', + 'WGPUDawnAdapterPropertiesPowerPreference', + 'WGPUDawnBufferDescriptorErrorInfoFromWireClient', + 'WGPUDawnCacheDeviceDescriptor', + 'WGPUDawnEncoderInternalUsageDescriptor', + 'WGPUDawnExperimentalImmediateDataLimits', + 'WGPUDawnExperimentalSubgroupLimits', + 'WGPUDawnLoadCacheDataFunction', + 'WGPUDawnRenderPassColorAttachmentRenderToSingleSampled', + 'WGPUDawnShaderModuleSPIRVOptionsDescriptor', + 'WGPUDawnStoreCacheDataFunction', + 'WGPUDawnTexelCopyBufferRowAlignmentLimits', + 'WGPUDawnTextureInternalUsageDescriptor', + 'WGPUDawnTogglesDescriptor', 'WGPUDawnWGSLBlocklist', + 'WGPUDawnWireWGSLControl', 'WGPUDepthStencilState', 'WGPUDevice', + 'WGPUDeviceDescriptor', 'WGPUDeviceLostCallback', + 'WGPUDeviceLostCallback2', 'WGPUDeviceLostCallbackInfo', + 'WGPUDeviceLostCallbackInfo2', 'WGPUDeviceLostCallbackNew', + 'WGPUDeviceLostReason', 'WGPUDeviceLostReason_Destroyed', + 'WGPUDeviceLostReason_FailedCreation', + 'WGPUDeviceLostReason_Force32', + 'WGPUDeviceLostReason_InstanceDropped', + 'WGPUDeviceLostReason_Unknown', 'WGPUDrmFormatCapabilities', + 'WGPUDrmFormatProperties', 'WGPUErrorCallback', 'WGPUErrorFilter', + 'WGPUErrorFilter_Force32', 'WGPUErrorFilter_Internal', + 'WGPUErrorFilter_OutOfMemory', 'WGPUErrorFilter_Validation', + 'WGPUErrorType', 'WGPUErrorType_DeviceLost', + 'WGPUErrorType_Force32', 'WGPUErrorType_Internal', + 'WGPUErrorType_NoError', 'WGPUErrorType_OutOfMemory', + 'WGPUErrorType_Unknown', 'WGPUErrorType_Validation', + 'WGPUExtent2D', 'WGPUExtent3D', 'WGPUExternalTexture', + 'WGPUExternalTextureBindingEntry', + 'WGPUExternalTextureBindingLayout', + 'WGPUExternalTextureDescriptor', 'WGPUExternalTextureRotation', + 'WGPUExternalTextureRotation_Force32', + 'WGPUExternalTextureRotation_Rotate0Degrees', + 'WGPUExternalTextureRotation_Rotate180Degrees', + 'WGPUExternalTextureRotation_Rotate270Degrees', + 'WGPUExternalTextureRotation_Rotate90Degrees', 'WGPUFeatureLevel', + 'WGPUFeatureLevel_Compatibility', 'WGPUFeatureLevel_Core', + 'WGPUFeatureLevel_Force32', 'WGPUFeatureLevel_Undefined', + 'WGPUFeatureName', 'WGPUFeatureName_ANGLETextureSharing', + 'WGPUFeatureName_AdapterPropertiesD3D', + 'WGPUFeatureName_AdapterPropertiesMemoryHeaps', + 'WGPUFeatureName_AdapterPropertiesVk', + 'WGPUFeatureName_BGRA8UnormStorage', + 'WGPUFeatureName_BufferMapExtendedUsages', + 'WGPUFeatureName_ChromiumExperimentalImmediateData', + 'WGPUFeatureName_ChromiumExperimentalTimestampQueryInsidePasses', + 'WGPUFeatureName_ClipDistances', + 'WGPUFeatureName_D3D11MultithreadProtected', + 'WGPUFeatureName_DawnInternalUsages', + 'WGPUFeatureName_DawnLoadResolveTexture', + 'WGPUFeatureName_DawnMultiPlanarFormats', + 'WGPUFeatureName_DawnNative', + 'WGPUFeatureName_DawnPartialLoadResolveTexture', + 'WGPUFeatureName_DawnTexelCopyBufferRowAlignment', + 'WGPUFeatureName_Depth32FloatStencil8', + 'WGPUFeatureName_DepthClipControl', + 'WGPUFeatureName_DrmFormatCapabilities', + 'WGPUFeatureName_DualSourceBlending', + 'WGPUFeatureName_FlexibleTextureViews', + 'WGPUFeatureName_Float32Blendable', + 'WGPUFeatureName_Float32Filterable', 'WGPUFeatureName_Force32', + 'WGPUFeatureName_FormatCapabilities', + 'WGPUFeatureName_FramebufferFetch', + 'WGPUFeatureName_HostMappedPointer', + 'WGPUFeatureName_ImplicitDeviceSynchronization', + 'WGPUFeatureName_IndirectFirstInstance', + 'WGPUFeatureName_MSAARenderToSingleSampled', + 'WGPUFeatureName_MultiDrawIndirect', + 'WGPUFeatureName_MultiPlanarFormatExtendedUsages', + 'WGPUFeatureName_MultiPlanarFormatNv12a', + 'WGPUFeatureName_MultiPlanarFormatNv16', + 'WGPUFeatureName_MultiPlanarFormatNv24', + 'WGPUFeatureName_MultiPlanarFormatP010', + 'WGPUFeatureName_MultiPlanarFormatP210', + 'WGPUFeatureName_MultiPlanarFormatP410', + 'WGPUFeatureName_MultiPlanarRenderTargets', + 'WGPUFeatureName_Norm16TextureFormats', + 'WGPUFeatureName_PixelLocalStorageCoherent', + 'WGPUFeatureName_PixelLocalStorageNonCoherent', + 'WGPUFeatureName_R8UnormStorage', + 'WGPUFeatureName_RG11B10UfloatRenderable', + 'WGPUFeatureName_ShaderF16', + 'WGPUFeatureName_ShaderModuleCompilationOptions', + 'WGPUFeatureName_SharedBufferMemoryD3D12Resource', + 'WGPUFeatureName_SharedFenceDXGISharedHandle', + 'WGPUFeatureName_SharedFenceMTLSharedEvent', + 'WGPUFeatureName_SharedFenceSyncFD', + 'WGPUFeatureName_SharedFenceVkSemaphoreOpaqueFD', + 'WGPUFeatureName_SharedFenceVkSemaphoreZirconHandle', + 'WGPUFeatureName_SharedTextureMemoryAHardwareBuffer', + 'WGPUFeatureName_SharedTextureMemoryD3D11Texture2D', + 'WGPUFeatureName_SharedTextureMemoryDXGISharedHandle', + 'WGPUFeatureName_SharedTextureMemoryDmaBuf', + 'WGPUFeatureName_SharedTextureMemoryEGLImage', + 'WGPUFeatureName_SharedTextureMemoryIOSurface', + 'WGPUFeatureName_SharedTextureMemoryOpaqueFD', + 'WGPUFeatureName_SharedTextureMemoryVkDedicatedAllocation', + 'WGPUFeatureName_SharedTextureMemoryZirconHandle', + 'WGPUFeatureName_Snorm16TextureFormats', + 'WGPUFeatureName_StaticSamplers', 'WGPUFeatureName_Subgroups', + 'WGPUFeatureName_SubgroupsF16', + 'WGPUFeatureName_TextureCompressionASTC', + 'WGPUFeatureName_TextureCompressionBC', + 'WGPUFeatureName_TextureCompressionETC2', + 'WGPUFeatureName_TimestampQuery', + 'WGPUFeatureName_TransientAttachments', + 'WGPUFeatureName_Unorm16TextureFormats', + 'WGPUFeatureName_YCbCrVulkanSamplers', 'WGPUFilterMode', + 'WGPUFilterMode_Force32', 'WGPUFilterMode_Linear', + 'WGPUFilterMode_Nearest', 'WGPUFilterMode_Undefined', 'WGPUFlags', + 'WGPUFormatCapabilities', 'WGPUFragmentState', 'WGPUFrontFace', + 'WGPUFrontFace_CCW', 'WGPUFrontFace_CW', 'WGPUFrontFace_Force32', + 'WGPUFrontFace_Undefined', 'WGPUFuture', 'WGPUFutureWaitInfo', + 'WGPUHeapProperty', 'WGPUHeapProperty_DeviceLocal', + 'WGPUHeapProperty_HostCached', 'WGPUHeapProperty_HostCoherent', + 'WGPUHeapProperty_HostUncached', 'WGPUHeapProperty_HostVisible', + 'WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER', 'WGPUImageCopyBuffer', + 'WGPUImageCopyExternalTexture', 'WGPUImageCopyTexture', + 'WGPUIndexFormat', 'WGPUIndexFormat_Force32', + 'WGPUIndexFormat_Uint16', 'WGPUIndexFormat_Uint32', + 'WGPUIndexFormat_Undefined', 'WGPUInstance', + 'WGPUInstanceDescriptor', 'WGPUInstanceFeatures', 'WGPULimits', + 'WGPULoadOp', 'WGPULoadOp_Clear', + 'WGPULoadOp_ExpandResolveTexture', 'WGPULoadOp_Force32', + 'WGPULoadOp_Load', 'WGPULoadOp_Undefined', 'WGPULoggingCallback', + 'WGPULoggingType', 'WGPULoggingType_Error', + 'WGPULoggingType_Force32', 'WGPULoggingType_Info', + 'WGPULoggingType_Verbose', 'WGPULoggingType_Warning', + 'WGPUMapAsyncStatus', 'WGPUMapAsyncStatus_Aborted', + 'WGPUMapAsyncStatus_Error', 'WGPUMapAsyncStatus_Force32', + 'WGPUMapAsyncStatus_InstanceDropped', + 'WGPUMapAsyncStatus_Success', 'WGPUMapAsyncStatus_Unknown', + 'WGPUMapMode', 'WGPUMapMode_None', 'WGPUMapMode_Read', + 'WGPUMapMode_Write', 'WGPUMemoryHeapInfo', 'WGPUMipmapFilterMode', + 'WGPUMipmapFilterMode_Force32', 'WGPUMipmapFilterMode_Linear', + 'WGPUMipmapFilterMode_Nearest', 'WGPUMipmapFilterMode_Undefined', + 'WGPUMultisampleState', 'WGPUOptionalBool', + 'WGPUOptionalBool_False', 'WGPUOptionalBool_Force32', + 'WGPUOptionalBool_True', 'WGPUOptionalBool_Undefined', + 'WGPUOrigin2D', 'WGPUOrigin3D', 'WGPUPipelineLayout', + 'WGPUPipelineLayoutDescriptor', + 'WGPUPipelineLayoutPixelLocalStorage', + 'WGPUPipelineLayoutStorageAttachment', + 'WGPUPopErrorScopeCallback', 'WGPUPopErrorScopeCallback2', + 'WGPUPopErrorScopeCallbackInfo', 'WGPUPopErrorScopeCallbackInfo2', + 'WGPUPopErrorScopeStatus', 'WGPUPopErrorScopeStatus_Force32', + 'WGPUPopErrorScopeStatus_InstanceDropped', + 'WGPUPopErrorScopeStatus_Success', 'WGPUPowerPreference', + 'WGPUPowerPreference_Force32', + 'WGPUPowerPreference_HighPerformance', + 'WGPUPowerPreference_LowPower', 'WGPUPowerPreference_Undefined', + 'WGPUPresentMode', 'WGPUPresentMode_Fifo', + 'WGPUPresentMode_FifoRelaxed', 'WGPUPresentMode_Force32', + 'WGPUPresentMode_Immediate', 'WGPUPresentMode_Mailbox', + 'WGPUPrimitiveState', 'WGPUPrimitiveTopology', + 'WGPUPrimitiveTopology_Force32', 'WGPUPrimitiveTopology_LineList', + 'WGPUPrimitiveTopology_LineStrip', + 'WGPUPrimitiveTopology_PointList', + 'WGPUPrimitiveTopology_TriangleList', + 'WGPUPrimitiveTopology_TriangleStrip', + 'WGPUPrimitiveTopology_Undefined', 'WGPUProc', + 'WGPUProcAdapterAddRef', 'WGPUProcAdapterCreateDevice', + 'WGPUProcAdapterGetFeatures', + 'WGPUProcAdapterGetFormatCapabilities', 'WGPUProcAdapterGetInfo', + 'WGPUProcAdapterGetInstance', 'WGPUProcAdapterGetLimits', + 'WGPUProcAdapterHasFeature', 'WGPUProcAdapterInfoFreeMembers', + 'WGPUProcAdapterPropertiesMemoryHeapsFreeMembers', + 'WGPUProcAdapterRelease', 'WGPUProcAdapterRequestDevice', + 'WGPUProcAdapterRequestDevice2', 'WGPUProcAdapterRequestDeviceF', + 'WGPUProcBindGroupAddRef', 'WGPUProcBindGroupLayoutAddRef', + 'WGPUProcBindGroupLayoutRelease', + 'WGPUProcBindGroupLayoutSetLabel', 'WGPUProcBindGroupRelease', + 'WGPUProcBindGroupSetLabel', 'WGPUProcBufferAddRef', + 'WGPUProcBufferDestroy', 'WGPUProcBufferGetConstMappedRange', + 'WGPUProcBufferGetMapState', 'WGPUProcBufferGetMappedRange', + 'WGPUProcBufferGetSize', 'WGPUProcBufferGetUsage', + 'WGPUProcBufferMapAsync', 'WGPUProcBufferMapAsync2', + 'WGPUProcBufferMapAsyncF', 'WGPUProcBufferRelease', + 'WGPUProcBufferSetLabel', 'WGPUProcBufferUnmap', + 'WGPUProcCommandBufferAddRef', 'WGPUProcCommandBufferRelease', + 'WGPUProcCommandBufferSetLabel', 'WGPUProcCommandEncoderAddRef', + 'WGPUProcCommandEncoderBeginComputePass', + 'WGPUProcCommandEncoderBeginRenderPass', + 'WGPUProcCommandEncoderClearBuffer', + 'WGPUProcCommandEncoderCopyBufferToBuffer', + 'WGPUProcCommandEncoderCopyBufferToTexture', + 'WGPUProcCommandEncoderCopyTextureToBuffer', + 'WGPUProcCommandEncoderCopyTextureToTexture', + 'WGPUProcCommandEncoderFinish', + 'WGPUProcCommandEncoderInjectValidationError', + 'WGPUProcCommandEncoderInsertDebugMarker', + 'WGPUProcCommandEncoderPopDebugGroup', + 'WGPUProcCommandEncoderPushDebugGroup', + 'WGPUProcCommandEncoderRelease', + 'WGPUProcCommandEncoderResolveQuerySet', + 'WGPUProcCommandEncoderSetLabel', + 'WGPUProcCommandEncoderWriteBuffer', + 'WGPUProcCommandEncoderWriteTimestamp', + 'WGPUProcComputePassEncoderAddRef', + 'WGPUProcComputePassEncoderDispatchWorkgroups', + 'WGPUProcComputePassEncoderDispatchWorkgroupsIndirect', + 'WGPUProcComputePassEncoderEnd', + 'WGPUProcComputePassEncoderInsertDebugMarker', + 'WGPUProcComputePassEncoderPopDebugGroup', + 'WGPUProcComputePassEncoderPushDebugGroup', + 'WGPUProcComputePassEncoderRelease', + 'WGPUProcComputePassEncoderSetBindGroup', + 'WGPUProcComputePassEncoderSetLabel', + 'WGPUProcComputePassEncoderSetPipeline', + 'WGPUProcComputePassEncoderWriteTimestamp', + 'WGPUProcComputePipelineAddRef', + 'WGPUProcComputePipelineGetBindGroupLayout', + 'WGPUProcComputePipelineRelease', + 'WGPUProcComputePipelineSetLabel', 'WGPUProcCreateInstance', + 'WGPUProcDeviceAddRef', 'WGPUProcDeviceCreateBindGroup', + 'WGPUProcDeviceCreateBindGroupLayout', + 'WGPUProcDeviceCreateBuffer', + 'WGPUProcDeviceCreateCommandEncoder', + 'WGPUProcDeviceCreateComputePipeline', + 'WGPUProcDeviceCreateComputePipelineAsync', + 'WGPUProcDeviceCreateComputePipelineAsync2', + 'WGPUProcDeviceCreateComputePipelineAsyncF', + 'WGPUProcDeviceCreateErrorBuffer', + 'WGPUProcDeviceCreateErrorExternalTexture', + 'WGPUProcDeviceCreateErrorShaderModule', + 'WGPUProcDeviceCreateErrorTexture', + 'WGPUProcDeviceCreateExternalTexture', + 'WGPUProcDeviceCreatePipelineLayout', + 'WGPUProcDeviceCreateQuerySet', + 'WGPUProcDeviceCreateRenderBundleEncoder', + 'WGPUProcDeviceCreateRenderPipeline', + 'WGPUProcDeviceCreateRenderPipelineAsync', + 'WGPUProcDeviceCreateRenderPipelineAsync2', + 'WGPUProcDeviceCreateRenderPipelineAsyncF', + 'WGPUProcDeviceCreateSampler', 'WGPUProcDeviceCreateShaderModule', + 'WGPUProcDeviceCreateTexture', 'WGPUProcDeviceDestroy', + 'WGPUProcDeviceForceLoss', + 'WGPUProcDeviceGetAHardwareBufferProperties', + 'WGPUProcDeviceGetAdapter', 'WGPUProcDeviceGetAdapterInfo', + 'WGPUProcDeviceGetFeatures', 'WGPUProcDeviceGetLimits', + 'WGPUProcDeviceGetLostFuture', 'WGPUProcDeviceGetQueue', + 'WGPUProcDeviceHasFeature', + 'WGPUProcDeviceImportSharedBufferMemory', + 'WGPUProcDeviceImportSharedFence', + 'WGPUProcDeviceImportSharedTextureMemory', + 'WGPUProcDeviceInjectError', 'WGPUProcDevicePopErrorScope', + 'WGPUProcDevicePopErrorScope2', 'WGPUProcDevicePopErrorScopeF', + 'WGPUProcDevicePushErrorScope', 'WGPUProcDeviceRelease', + 'WGPUProcDeviceSetLabel', 'WGPUProcDeviceSetLoggingCallback', + 'WGPUProcDeviceTick', 'WGPUProcDeviceValidateTextureDescriptor', + 'WGPUProcDrmFormatCapabilitiesFreeMembers', + 'WGPUProcExternalTextureAddRef', 'WGPUProcExternalTextureDestroy', + 'WGPUProcExternalTextureExpire', 'WGPUProcExternalTextureRefresh', + 'WGPUProcExternalTextureRelease', + 'WGPUProcExternalTextureSetLabel', 'WGPUProcGetInstanceFeatures', + 'WGPUProcGetProcAddress', 'WGPUProcInstanceAddRef', + 'WGPUProcInstanceCreateSurface', + 'WGPUProcInstanceEnumerateWGSLLanguageFeatures', + 'WGPUProcInstanceHasWGSLLanguageFeature', + 'WGPUProcInstanceProcessEvents', 'WGPUProcInstanceRelease', + 'WGPUProcInstanceRequestAdapter', + 'WGPUProcInstanceRequestAdapter2', + 'WGPUProcInstanceRequestAdapterF', 'WGPUProcInstanceWaitAny', + 'WGPUProcPipelineLayoutAddRef', 'WGPUProcPipelineLayoutRelease', + 'WGPUProcPipelineLayoutSetLabel', 'WGPUProcQuerySetAddRef', + 'WGPUProcQuerySetDestroy', 'WGPUProcQuerySetGetCount', + 'WGPUProcQuerySetGetType', 'WGPUProcQuerySetRelease', + 'WGPUProcQuerySetSetLabel', 'WGPUProcQueueAddRef', + 'WGPUProcQueueCopyExternalTextureForBrowser', + 'WGPUProcQueueCopyTextureForBrowser', + 'WGPUProcQueueOnSubmittedWorkDone', + 'WGPUProcQueueOnSubmittedWorkDone2', + 'WGPUProcQueueOnSubmittedWorkDoneF', 'WGPUProcQueueRelease', + 'WGPUProcQueueSetLabel', 'WGPUProcQueueSubmit', + 'WGPUProcQueueWriteBuffer', 'WGPUProcQueueWriteTexture', + 'WGPUProcRenderBundleAddRef', 'WGPUProcRenderBundleEncoderAddRef', + 'WGPUProcRenderBundleEncoderDraw', + 'WGPUProcRenderBundleEncoderDrawIndexed', + 'WGPUProcRenderBundleEncoderDrawIndexedIndirect', + 'WGPUProcRenderBundleEncoderDrawIndirect', + 'WGPUProcRenderBundleEncoderFinish', + 'WGPUProcRenderBundleEncoderInsertDebugMarker', + 'WGPUProcRenderBundleEncoderPopDebugGroup', + 'WGPUProcRenderBundleEncoderPushDebugGroup', + 'WGPUProcRenderBundleEncoderRelease', + 'WGPUProcRenderBundleEncoderSetBindGroup', + 'WGPUProcRenderBundleEncoderSetIndexBuffer', + 'WGPUProcRenderBundleEncoderSetLabel', + 'WGPUProcRenderBundleEncoderSetPipeline', + 'WGPUProcRenderBundleEncoderSetVertexBuffer', + 'WGPUProcRenderBundleRelease', 'WGPUProcRenderBundleSetLabel', + 'WGPUProcRenderPassEncoderAddRef', + 'WGPUProcRenderPassEncoderBeginOcclusionQuery', + 'WGPUProcRenderPassEncoderDraw', + 'WGPUProcRenderPassEncoderDrawIndexed', + 'WGPUProcRenderPassEncoderDrawIndexedIndirect', + 'WGPUProcRenderPassEncoderDrawIndirect', + 'WGPUProcRenderPassEncoderEnd', + 'WGPUProcRenderPassEncoderEndOcclusionQuery', + 'WGPUProcRenderPassEncoderExecuteBundles', + 'WGPUProcRenderPassEncoderInsertDebugMarker', + 'WGPUProcRenderPassEncoderMultiDrawIndexedIndirect', + 'WGPUProcRenderPassEncoderMultiDrawIndirect', + 'WGPUProcRenderPassEncoderPixelLocalStorageBarrier', + 'WGPUProcRenderPassEncoderPopDebugGroup', + 'WGPUProcRenderPassEncoderPushDebugGroup', + 'WGPUProcRenderPassEncoderRelease', + 'WGPUProcRenderPassEncoderSetBindGroup', + 'WGPUProcRenderPassEncoderSetBlendConstant', + 'WGPUProcRenderPassEncoderSetIndexBuffer', + 'WGPUProcRenderPassEncoderSetLabel', + 'WGPUProcRenderPassEncoderSetPipeline', + 'WGPUProcRenderPassEncoderSetScissorRect', + 'WGPUProcRenderPassEncoderSetStencilReference', + 'WGPUProcRenderPassEncoderSetVertexBuffer', + 'WGPUProcRenderPassEncoderSetViewport', + 'WGPUProcRenderPassEncoderWriteTimestamp', + 'WGPUProcRenderPipelineAddRef', + 'WGPUProcRenderPipelineGetBindGroupLayout', + 'WGPUProcRenderPipelineRelease', 'WGPUProcRenderPipelineSetLabel', + 'WGPUProcSamplerAddRef', 'WGPUProcSamplerRelease', + 'WGPUProcSamplerSetLabel', 'WGPUProcShaderModuleAddRef', + 'WGPUProcShaderModuleGetCompilationInfo', + 'WGPUProcShaderModuleGetCompilationInfo2', + 'WGPUProcShaderModuleGetCompilationInfoF', + 'WGPUProcShaderModuleRelease', 'WGPUProcShaderModuleSetLabel', + 'WGPUProcSharedBufferMemoryAddRef', + 'WGPUProcSharedBufferMemoryBeginAccess', + 'WGPUProcSharedBufferMemoryCreateBuffer', + 'WGPUProcSharedBufferMemoryEndAccess', + 'WGPUProcSharedBufferMemoryEndAccessStateFreeMembers', + 'WGPUProcSharedBufferMemoryGetProperties', + 'WGPUProcSharedBufferMemoryIsDeviceLost', + 'WGPUProcSharedBufferMemoryRelease', + 'WGPUProcSharedBufferMemorySetLabel', 'WGPUProcSharedFenceAddRef', + 'WGPUProcSharedFenceExportInfo', 'WGPUProcSharedFenceRelease', + 'WGPUProcSharedTextureMemoryAddRef', + 'WGPUProcSharedTextureMemoryBeginAccess', + 'WGPUProcSharedTextureMemoryCreateTexture', + 'WGPUProcSharedTextureMemoryEndAccess', + 'WGPUProcSharedTextureMemoryEndAccessStateFreeMembers', + 'WGPUProcSharedTextureMemoryGetProperties', + 'WGPUProcSharedTextureMemoryIsDeviceLost', + 'WGPUProcSharedTextureMemoryRelease', + 'WGPUProcSharedTextureMemorySetLabel', + 'WGPUProcSupportedFeaturesFreeMembers', 'WGPUProcSurfaceAddRef', + 'WGPUProcSurfaceCapabilitiesFreeMembers', + 'WGPUProcSurfaceConfigure', 'WGPUProcSurfaceGetCapabilities', + 'WGPUProcSurfaceGetCurrentTexture', 'WGPUProcSurfacePresent', + 'WGPUProcSurfaceRelease', 'WGPUProcSurfaceSetLabel', + 'WGPUProcSurfaceUnconfigure', 'WGPUProcTextureAddRef', + 'WGPUProcTextureCreateErrorView', 'WGPUProcTextureCreateView', + 'WGPUProcTextureDestroy', 'WGPUProcTextureGetDepthOrArrayLayers', + 'WGPUProcTextureGetDimension', 'WGPUProcTextureGetFormat', + 'WGPUProcTextureGetHeight', 'WGPUProcTextureGetMipLevelCount', + 'WGPUProcTextureGetSampleCount', 'WGPUProcTextureGetUsage', + 'WGPUProcTextureGetWidth', 'WGPUProcTextureRelease', + 'WGPUProcTextureSetLabel', 'WGPUProcTextureViewAddRef', + 'WGPUProcTextureViewRelease', 'WGPUProcTextureViewSetLabel', + 'WGPUQuerySet', 'WGPUQuerySetDescriptor', 'WGPUQueryType', + 'WGPUQueryType_Force32', 'WGPUQueryType_Occlusion', + 'WGPUQueryType_Timestamp', 'WGPUQueue', 'WGPUQueueDescriptor', + 'WGPUQueueWorkDoneCallback', 'WGPUQueueWorkDoneCallback2', + 'WGPUQueueWorkDoneCallbackInfo', 'WGPUQueueWorkDoneCallbackInfo2', + 'WGPUQueueWorkDoneStatus', 'WGPUQueueWorkDoneStatus_DeviceLost', + 'WGPUQueueWorkDoneStatus_Error', + 'WGPUQueueWorkDoneStatus_Force32', + 'WGPUQueueWorkDoneStatus_InstanceDropped', + 'WGPUQueueWorkDoneStatus_Success', + 'WGPUQueueWorkDoneStatus_Unknown', 'WGPURenderBundle', + 'WGPURenderBundleDescriptor', 'WGPURenderBundleEncoder', + 'WGPURenderBundleEncoderDescriptor', + 'WGPURenderPassColorAttachment', + 'WGPURenderPassDepthStencilAttachment', + 'WGPURenderPassDescriptor', + 'WGPURenderPassDescriptorExpandResolveRect', + 'WGPURenderPassDescriptorMaxDrawCount', 'WGPURenderPassEncoder', + 'WGPURenderPassMaxDrawCount', 'WGPURenderPassPixelLocalStorage', + 'WGPURenderPassStorageAttachment', + 'WGPURenderPassTimestampWrites', 'WGPURenderPipeline', + 'WGPURenderPipelineDescriptor', 'WGPURequestAdapterCallback', + 'WGPURequestAdapterCallback2', 'WGPURequestAdapterCallbackInfo', + 'WGPURequestAdapterCallbackInfo2', 'WGPURequestAdapterOptions', + 'WGPURequestAdapterStatus', 'WGPURequestAdapterStatus_Error', + 'WGPURequestAdapterStatus_Force32', + 'WGPURequestAdapterStatus_InstanceDropped', + 'WGPURequestAdapterStatus_Success', + 'WGPURequestAdapterStatus_Unavailable', + 'WGPURequestAdapterStatus_Unknown', 'WGPURequestDeviceCallback', + 'WGPURequestDeviceCallback2', 'WGPURequestDeviceCallbackInfo', + 'WGPURequestDeviceCallbackInfo2', 'WGPURequestDeviceStatus', + 'WGPURequestDeviceStatus_Error', + 'WGPURequestDeviceStatus_Force32', + 'WGPURequestDeviceStatus_InstanceDropped', + 'WGPURequestDeviceStatus_Success', + 'WGPURequestDeviceStatus_Unknown', 'WGPURequiredLimits', + 'WGPUSType', 'WGPUSType_AHardwareBufferProperties', + 'WGPUSType_AdapterPropertiesD3D', + 'WGPUSType_AdapterPropertiesMemoryHeaps', + 'WGPUSType_AdapterPropertiesSubgroups', + 'WGPUSType_AdapterPropertiesVk', + 'WGPUSType_BufferHostMappedPointer', + 'WGPUSType_ColorTargetStateExpandResolveTextureDawn', + 'WGPUSType_DawnAdapterPropertiesPowerPreference', + 'WGPUSType_DawnBufferDescriptorErrorInfoFromWireClient', + 'WGPUSType_DawnCacheDeviceDescriptor', + 'WGPUSType_DawnEncoderInternalUsageDescriptor', + 'WGPUSType_DawnExperimentalImmediateDataLimits', + 'WGPUSType_DawnExperimentalSubgroupLimits', + 'WGPUSType_DawnInstanceDescriptor', + 'WGPUSType_DawnRenderPassColorAttachmentRenderToSingleSampled', + 'WGPUSType_DawnShaderModuleSPIRVOptionsDescriptor', + 'WGPUSType_DawnTexelCopyBufferRowAlignmentLimits', + 'WGPUSType_DawnTextureInternalUsageDescriptor', + 'WGPUSType_DawnTogglesDescriptor', 'WGPUSType_DawnWGSLBlocklist', + 'WGPUSType_DawnWireWGSLControl', + 'WGPUSType_DrmFormatCapabilities', + 'WGPUSType_ExternalTextureBindingEntry', + 'WGPUSType_ExternalTextureBindingLayout', 'WGPUSType_Force32', + 'WGPUSType_PipelineLayoutPixelLocalStorage', + 'WGPUSType_RenderPassDescriptorExpandResolveRect', + 'WGPUSType_RenderPassMaxDrawCount', + 'WGPUSType_RenderPassPixelLocalStorage', + 'WGPUSType_RequestAdapterOptionsD3D11Device', + 'WGPUSType_RequestAdapterOptionsGetGLProc', + 'WGPUSType_RequestAdapterOptionsLUID', + 'WGPUSType_ShaderModuleCompilationOptions', + 'WGPUSType_ShaderSourceSPIRV', 'WGPUSType_ShaderSourceWGSL', + 'WGPUSType_SharedBufferMemoryD3D12ResourceDescriptor', + 'WGPUSType_SharedFenceDXGISharedHandleDescriptor', + 'WGPUSType_SharedFenceDXGISharedHandleExportInfo', + 'WGPUSType_SharedFenceMTLSharedEventDescriptor', + 'WGPUSType_SharedFenceMTLSharedEventExportInfo', + 'WGPUSType_SharedFenceSyncFDDescriptor', + 'WGPUSType_SharedFenceSyncFDExportInfo', + 'WGPUSType_SharedFenceVkSemaphoreOpaqueFDDescriptor', + 'WGPUSType_SharedFenceVkSemaphoreOpaqueFDExportInfo', + 'WGPUSType_SharedFenceVkSemaphoreZirconHandleDescriptor', + 'WGPUSType_SharedFenceVkSemaphoreZirconHandleExportInfo', + 'WGPUSType_SharedTextureMemoryAHardwareBufferDescriptor', + 'WGPUSType_SharedTextureMemoryAHardwareBufferProperties', + 'WGPUSType_SharedTextureMemoryD3D11Texture2DDescriptor', + 'WGPUSType_SharedTextureMemoryD3DSwapchainBeginState', + 'WGPUSType_SharedTextureMemoryDXGISharedHandleDescriptor', + 'WGPUSType_SharedTextureMemoryDmaBufDescriptor', + 'WGPUSType_SharedTextureMemoryEGLImageDescriptor', + 'WGPUSType_SharedTextureMemoryIOSurfaceDescriptor', + 'WGPUSType_SharedTextureMemoryInitializedBeginState', + 'WGPUSType_SharedTextureMemoryInitializedEndState', + 'WGPUSType_SharedTextureMemoryOpaqueFDDescriptor', + 'WGPUSType_SharedTextureMemoryVkDedicatedAllocationDescriptor', + 'WGPUSType_SharedTextureMemoryVkImageLayoutBeginState', + 'WGPUSType_SharedTextureMemoryVkImageLayoutEndState', + 'WGPUSType_SharedTextureMemoryZirconHandleDescriptor', + 'WGPUSType_StaticSamplerBindingLayout', + 'WGPUSType_SurfaceDescriptorFromWindowsCoreWindow', + 'WGPUSType_SurfaceDescriptorFromWindowsSwapChainPanel', + 'WGPUSType_SurfaceSourceAndroidNativeWindow', + 'WGPUSType_SurfaceSourceCanvasHTMLSelector_Emscripten', + 'WGPUSType_SurfaceSourceMetalLayer', + 'WGPUSType_SurfaceSourceWaylandSurface', + 'WGPUSType_SurfaceSourceWindowsHWND', + 'WGPUSType_SurfaceSourceXCBWindow', + 'WGPUSType_SurfaceSourceXlibWindow', + 'WGPUSType_TextureBindingViewDimensionDescriptor', + 'WGPUSType_YCbCrVkDescriptor', 'WGPUSampler', + 'WGPUSamplerBindingLayout', 'WGPUSamplerBindingType', + 'WGPUSamplerBindingType_BindingNotUsed', + 'WGPUSamplerBindingType_Comparison', + 'WGPUSamplerBindingType_Filtering', + 'WGPUSamplerBindingType_Force32', + 'WGPUSamplerBindingType_NonFiltering', 'WGPUSamplerDescriptor', + 'WGPUShaderModule', 'WGPUShaderModuleCompilationOptions', + 'WGPUShaderModuleDescriptor', 'WGPUShaderModuleSPIRVDescriptor', + 'WGPUShaderModuleWGSLDescriptor', 'WGPUShaderSourceSPIRV', + 'WGPUShaderSourceWGSL', 'WGPUShaderStage', + 'WGPUShaderStage_Compute', 'WGPUShaderStage_Fragment', + 'WGPUShaderStage_None', 'WGPUShaderStage_Vertex', + 'WGPUSharedBufferMemory', + 'WGPUSharedBufferMemoryBeginAccessDescriptor', + 'WGPUSharedBufferMemoryDescriptor', + 'WGPUSharedBufferMemoryEndAccessState', + 'WGPUSharedBufferMemoryProperties', 'WGPUSharedFence', + 'WGPUSharedFenceDXGISharedHandleDescriptor', + 'WGPUSharedFenceDXGISharedHandleExportInfo', + 'WGPUSharedFenceDescriptor', 'WGPUSharedFenceExportInfo', + 'WGPUSharedFenceMTLSharedEventDescriptor', + 'WGPUSharedFenceMTLSharedEventExportInfo', + 'WGPUSharedFenceSyncFDDescriptor', + 'WGPUSharedFenceSyncFDExportInfo', 'WGPUSharedFenceType', + 'WGPUSharedFenceType_DXGISharedHandle', + 'WGPUSharedFenceType_Force32', + 'WGPUSharedFenceType_MTLSharedEvent', + 'WGPUSharedFenceType_SyncFD', + 'WGPUSharedFenceType_VkSemaphoreOpaqueFD', + 'WGPUSharedFenceType_VkSemaphoreZirconHandle', + 'WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor', + 'WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo', + 'WGPUSharedFenceVkSemaphoreZirconHandleDescriptor', + 'WGPUSharedFenceVkSemaphoreZirconHandleExportInfo', + 'WGPUSharedTextureMemory', + 'WGPUSharedTextureMemoryAHardwareBufferDescriptor', + 'WGPUSharedTextureMemoryAHardwareBufferProperties', + 'WGPUSharedTextureMemoryBeginAccessDescriptor', + 'WGPUSharedTextureMemoryD3DSwapchainBeginState', + 'WGPUSharedTextureMemoryDXGISharedHandleDescriptor', + 'WGPUSharedTextureMemoryDescriptor', + 'WGPUSharedTextureMemoryDmaBufDescriptor', + 'WGPUSharedTextureMemoryDmaBufPlane', + 'WGPUSharedTextureMemoryEGLImageDescriptor', + 'WGPUSharedTextureMemoryEndAccessState', + 'WGPUSharedTextureMemoryIOSurfaceDescriptor', + 'WGPUSharedTextureMemoryOpaqueFDDescriptor', + 'WGPUSharedTextureMemoryProperties', + 'WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor', + 'WGPUSharedTextureMemoryVkImageLayoutBeginState', + 'WGPUSharedTextureMemoryVkImageLayoutEndState', + 'WGPUSharedTextureMemoryZirconHandleDescriptor', + 'WGPUStaticSamplerBindingLayout', 'WGPUStatus', + 'WGPUStatus_Error', 'WGPUStatus_Force32', 'WGPUStatus_Success', + 'WGPUStencilFaceState', 'WGPUStencilOperation', + 'WGPUStencilOperation_DecrementClamp', + 'WGPUStencilOperation_DecrementWrap', + 'WGPUStencilOperation_Force32', + 'WGPUStencilOperation_IncrementClamp', + 'WGPUStencilOperation_IncrementWrap', + 'WGPUStencilOperation_Invert', 'WGPUStencilOperation_Keep', + 'WGPUStencilOperation_Replace', 'WGPUStencilOperation_Undefined', + 'WGPUStencilOperation_Zero', 'WGPUStorageTextureAccess', + 'WGPUStorageTextureAccess_BindingNotUsed', + 'WGPUStorageTextureAccess_Force32', + 'WGPUStorageTextureAccess_ReadOnly', + 'WGPUStorageTextureAccess_ReadWrite', + 'WGPUStorageTextureAccess_WriteOnly', + 'WGPUStorageTextureBindingLayout', 'WGPUStoreOp', + 'WGPUStoreOp_Discard', 'WGPUStoreOp_Force32', 'WGPUStoreOp_Store', + 'WGPUStoreOp_Undefined', 'WGPUStringView', + 'WGPUSupportedFeatures', 'WGPUSupportedLimits', 'WGPUSurface', + 'WGPUSurfaceCapabilities', 'WGPUSurfaceConfiguration', + 'WGPUSurfaceDescriptor', + 'WGPUSurfaceDescriptorFromAndroidNativeWindow', + 'WGPUSurfaceDescriptorFromCanvasHTMLSelector', + 'WGPUSurfaceDescriptorFromMetalLayer', + 'WGPUSurfaceDescriptorFromWaylandSurface', + 'WGPUSurfaceDescriptorFromWindowsCoreWindow', + 'WGPUSurfaceDescriptorFromWindowsHWND', + 'WGPUSurfaceDescriptorFromWindowsSwapChainPanel', + 'WGPUSurfaceDescriptorFromXcbWindow', + 'WGPUSurfaceDescriptorFromXlibWindow', + 'WGPUSurfaceGetCurrentTextureStatus', + 'WGPUSurfaceGetCurrentTextureStatus_DeviceLost', + 'WGPUSurfaceGetCurrentTextureStatus_Error', + 'WGPUSurfaceGetCurrentTextureStatus_Force32', + 'WGPUSurfaceGetCurrentTextureStatus_Lost', + 'WGPUSurfaceGetCurrentTextureStatus_OutOfMemory', + 'WGPUSurfaceGetCurrentTextureStatus_Outdated', + 'WGPUSurfaceGetCurrentTextureStatus_Success', + 'WGPUSurfaceGetCurrentTextureStatus_Timeout', + 'WGPUSurfaceSourceAndroidNativeWindow', + 'WGPUSurfaceSourceCanvasHTMLSelector_Emscripten', + 'WGPUSurfaceSourceMetalLayer', 'WGPUSurfaceSourceWaylandSurface', + 'WGPUSurfaceSourceWindowsHWND', 'WGPUSurfaceSourceXCBWindow', + 'WGPUSurfaceSourceXlibWindow', 'WGPUSurfaceTexture', + 'WGPUTexture', 'WGPUTextureAspect', 'WGPUTextureAspect_All', + 'WGPUTextureAspect_DepthOnly', 'WGPUTextureAspect_Force32', + 'WGPUTextureAspect_Plane0Only', 'WGPUTextureAspect_Plane1Only', + 'WGPUTextureAspect_Plane2Only', 'WGPUTextureAspect_StencilOnly', + 'WGPUTextureAspect_Undefined', 'WGPUTextureBindingLayout', + 'WGPUTextureBindingViewDimensionDescriptor', + 'WGPUTextureDataLayout', 'WGPUTextureDescriptor', + 'WGPUTextureDimension', 'WGPUTextureDimension_1D', + 'WGPUTextureDimension_2D', 'WGPUTextureDimension_3D', + 'WGPUTextureDimension_Force32', 'WGPUTextureDimension_Undefined', + 'WGPUTextureFormat', 'WGPUTextureFormat_ASTC10x10Unorm', + 'WGPUTextureFormat_ASTC10x10UnormSrgb', + 'WGPUTextureFormat_ASTC10x5Unorm', + 'WGPUTextureFormat_ASTC10x5UnormSrgb', + 'WGPUTextureFormat_ASTC10x6Unorm', + 'WGPUTextureFormat_ASTC10x6UnormSrgb', + 'WGPUTextureFormat_ASTC10x8Unorm', + 'WGPUTextureFormat_ASTC10x8UnormSrgb', + 'WGPUTextureFormat_ASTC12x10Unorm', + 'WGPUTextureFormat_ASTC12x10UnormSrgb', + 'WGPUTextureFormat_ASTC12x12Unorm', + 'WGPUTextureFormat_ASTC12x12UnormSrgb', + 'WGPUTextureFormat_ASTC4x4Unorm', + 'WGPUTextureFormat_ASTC4x4UnormSrgb', + 'WGPUTextureFormat_ASTC5x4Unorm', + 'WGPUTextureFormat_ASTC5x4UnormSrgb', + 'WGPUTextureFormat_ASTC5x5Unorm', + 'WGPUTextureFormat_ASTC5x5UnormSrgb', + 'WGPUTextureFormat_ASTC6x5Unorm', + 'WGPUTextureFormat_ASTC6x5UnormSrgb', + 'WGPUTextureFormat_ASTC6x6Unorm', + 'WGPUTextureFormat_ASTC6x6UnormSrgb', + 'WGPUTextureFormat_ASTC8x5Unorm', + 'WGPUTextureFormat_ASTC8x5UnormSrgb', + 'WGPUTextureFormat_ASTC8x6Unorm', + 'WGPUTextureFormat_ASTC8x6UnormSrgb', + 'WGPUTextureFormat_ASTC8x8Unorm', + 'WGPUTextureFormat_ASTC8x8UnormSrgb', + 'WGPUTextureFormat_BC1RGBAUnorm', + 'WGPUTextureFormat_BC1RGBAUnormSrgb', + 'WGPUTextureFormat_BC2RGBAUnorm', + 'WGPUTextureFormat_BC2RGBAUnormSrgb', + 'WGPUTextureFormat_BC3RGBAUnorm', + 'WGPUTextureFormat_BC3RGBAUnormSrgb', + 'WGPUTextureFormat_BC4RSnorm', 'WGPUTextureFormat_BC4RUnorm', + 'WGPUTextureFormat_BC5RGSnorm', 'WGPUTextureFormat_BC5RGUnorm', + 'WGPUTextureFormat_BC6HRGBFloat', + 'WGPUTextureFormat_BC6HRGBUfloat', + 'WGPUTextureFormat_BC7RGBAUnorm', + 'WGPUTextureFormat_BC7RGBAUnormSrgb', + 'WGPUTextureFormat_BGRA8Unorm', + 'WGPUTextureFormat_BGRA8UnormSrgb', + 'WGPUTextureFormat_Depth16Unorm', 'WGPUTextureFormat_Depth24Plus', + 'WGPUTextureFormat_Depth24PlusStencil8', + 'WGPUTextureFormat_Depth32Float', + 'WGPUTextureFormat_Depth32FloatStencil8', + 'WGPUTextureFormat_EACR11Snorm', 'WGPUTextureFormat_EACR11Unorm', + 'WGPUTextureFormat_EACRG11Snorm', + 'WGPUTextureFormat_EACRG11Unorm', + 'WGPUTextureFormat_ETC2RGB8A1Unorm', + 'WGPUTextureFormat_ETC2RGB8A1UnormSrgb', + 'WGPUTextureFormat_ETC2RGB8Unorm', + 'WGPUTextureFormat_ETC2RGB8UnormSrgb', + 'WGPUTextureFormat_ETC2RGBA8Unorm', + 'WGPUTextureFormat_ETC2RGBA8UnormSrgb', + 'WGPUTextureFormat_External', 'WGPUTextureFormat_Force32', + 'WGPUTextureFormat_R10X6BG10X6Biplanar420Unorm', + 'WGPUTextureFormat_R10X6BG10X6Biplanar422Unorm', + 'WGPUTextureFormat_R10X6BG10X6Biplanar444Unorm', + 'WGPUTextureFormat_R16Float', 'WGPUTextureFormat_R16Sint', + 'WGPUTextureFormat_R16Snorm', 'WGPUTextureFormat_R16Uint', + 'WGPUTextureFormat_R16Unorm', 'WGPUTextureFormat_R32Float', + 'WGPUTextureFormat_R32Sint', 'WGPUTextureFormat_R32Uint', + 'WGPUTextureFormat_R8BG8A8Triplanar420Unorm', + 'WGPUTextureFormat_R8BG8Biplanar420Unorm', + 'WGPUTextureFormat_R8BG8Biplanar422Unorm', + 'WGPUTextureFormat_R8BG8Biplanar444Unorm', + 'WGPUTextureFormat_R8Sint', 'WGPUTextureFormat_R8Snorm', + 'WGPUTextureFormat_R8Uint', 'WGPUTextureFormat_R8Unorm', + 'WGPUTextureFormat_RG11B10Ufloat', 'WGPUTextureFormat_RG16Float', + 'WGPUTextureFormat_RG16Sint', 'WGPUTextureFormat_RG16Snorm', + 'WGPUTextureFormat_RG16Uint', 'WGPUTextureFormat_RG16Unorm', + 'WGPUTextureFormat_RG32Float', 'WGPUTextureFormat_RG32Sint', + 'WGPUTextureFormat_RG32Uint', 'WGPUTextureFormat_RG8Sint', + 'WGPUTextureFormat_RG8Snorm', 'WGPUTextureFormat_RG8Uint', + 'WGPUTextureFormat_RG8Unorm', 'WGPUTextureFormat_RGB10A2Uint', + 'WGPUTextureFormat_RGB10A2Unorm', + 'WGPUTextureFormat_RGB9E5Ufloat', 'WGPUTextureFormat_RGBA16Float', + 'WGPUTextureFormat_RGBA16Sint', 'WGPUTextureFormat_RGBA16Snorm', + 'WGPUTextureFormat_RGBA16Uint', 'WGPUTextureFormat_RGBA16Unorm', + 'WGPUTextureFormat_RGBA32Float', 'WGPUTextureFormat_RGBA32Sint', + 'WGPUTextureFormat_RGBA32Uint', 'WGPUTextureFormat_RGBA8Sint', + 'WGPUTextureFormat_RGBA8Snorm', 'WGPUTextureFormat_RGBA8Uint', + 'WGPUTextureFormat_RGBA8Unorm', + 'WGPUTextureFormat_RGBA8UnormSrgb', 'WGPUTextureFormat_Stencil8', + 'WGPUTextureFormat_Undefined', 'WGPUTextureSampleType', + 'WGPUTextureSampleType_BindingNotUsed', + 'WGPUTextureSampleType_Depth', 'WGPUTextureSampleType_Float', + 'WGPUTextureSampleType_Force32', 'WGPUTextureSampleType_Sint', + 'WGPUTextureSampleType_Uint', + 'WGPUTextureSampleType_UnfilterableFloat', 'WGPUTextureUsage', + 'WGPUTextureUsage_CopyDst', 'WGPUTextureUsage_CopySrc', + 'WGPUTextureUsage_None', 'WGPUTextureUsage_RenderAttachment', + 'WGPUTextureUsage_StorageAttachment', + 'WGPUTextureUsage_StorageBinding', + 'WGPUTextureUsage_TextureBinding', + 'WGPUTextureUsage_TransientAttachment', 'WGPUTextureView', + 'WGPUTextureViewDescriptor', 'WGPUTextureViewDimension', + 'WGPUTextureViewDimension_1D', 'WGPUTextureViewDimension_2D', + 'WGPUTextureViewDimension_2DArray', 'WGPUTextureViewDimension_3D', + 'WGPUTextureViewDimension_Cube', + 'WGPUTextureViewDimension_CubeArray', + 'WGPUTextureViewDimension_Force32', + 'WGPUTextureViewDimension_Undefined', + 'WGPUUncapturedErrorCallback', 'WGPUUncapturedErrorCallbackInfo', + 'WGPUUncapturedErrorCallbackInfo2', 'WGPUVertexAttribute', + 'WGPUVertexBufferLayout', 'WGPUVertexFormat', + 'WGPUVertexFormat_Float16', 'WGPUVertexFormat_Float16x2', + 'WGPUVertexFormat_Float16x4', 'WGPUVertexFormat_Float32', + 'WGPUVertexFormat_Float32x2', 'WGPUVertexFormat_Float32x3', + 'WGPUVertexFormat_Float32x4', 'WGPUVertexFormat_Force32', + 'WGPUVertexFormat_Sint16', 'WGPUVertexFormat_Sint16x2', + 'WGPUVertexFormat_Sint16x4', 'WGPUVertexFormat_Sint32', + 'WGPUVertexFormat_Sint32x2', 'WGPUVertexFormat_Sint32x3', + 'WGPUVertexFormat_Sint32x4', 'WGPUVertexFormat_Sint8', + 'WGPUVertexFormat_Sint8x2', 'WGPUVertexFormat_Sint8x4', + 'WGPUVertexFormat_Snorm16', 'WGPUVertexFormat_Snorm16x2', + 'WGPUVertexFormat_Snorm16x4', 'WGPUVertexFormat_Snorm8', + 'WGPUVertexFormat_Snorm8x2', 'WGPUVertexFormat_Snorm8x4', + 'WGPUVertexFormat_Uint16', 'WGPUVertexFormat_Uint16x2', + 'WGPUVertexFormat_Uint16x4', 'WGPUVertexFormat_Uint32', + 'WGPUVertexFormat_Uint32x2', 'WGPUVertexFormat_Uint32x3', + 'WGPUVertexFormat_Uint32x4', 'WGPUVertexFormat_Uint8', + 'WGPUVertexFormat_Uint8x2', 'WGPUVertexFormat_Uint8x4', + 'WGPUVertexFormat_Unorm10_10_10_2', 'WGPUVertexFormat_Unorm16', + 'WGPUVertexFormat_Unorm16x2', 'WGPUVertexFormat_Unorm16x4', + 'WGPUVertexFormat_Unorm8', 'WGPUVertexFormat_Unorm8x2', + 'WGPUVertexFormat_Unorm8x4', 'WGPUVertexFormat_Unorm8x4BGRA', + 'WGPUVertexState', 'WGPUVertexStepMode', + 'WGPUVertexStepMode_Force32', 'WGPUVertexStepMode_Instance', + 'WGPUVertexStepMode_Undefined', 'WGPUVertexStepMode_Vertex', + 'WGPUWGSLFeatureName', + 'WGPUWGSLFeatureName_ChromiumTestingExperimental', + 'WGPUWGSLFeatureName_ChromiumTestingShipped', + 'WGPUWGSLFeatureName_ChromiumTestingShippedWithKillswitch', + 'WGPUWGSLFeatureName_ChromiumTestingUnimplemented', + 'WGPUWGSLFeatureName_ChromiumTestingUnsafeExperimental', + 'WGPUWGSLFeatureName_Force32', + 'WGPUWGSLFeatureName_Packed4x8IntegerDotProduct', + 'WGPUWGSLFeatureName_PointerCompositeAccess', + 'WGPUWGSLFeatureName_ReadonlyAndReadwriteStorageTextures', + 'WGPUWGSLFeatureName_UnrestrictedPointerParameters', + 'WGPUWaitStatus', 'WGPUWaitStatus_Force32', + 'WGPUWaitStatus_Success', 'WGPUWaitStatus_TimedOut', + 'WGPUWaitStatus_Unknown', 'WGPUWaitStatus_UnsupportedCount', + 'WGPUWaitStatus_UnsupportedMixedSources', + 'WGPUWaitStatus_UnsupportedTimeout', 'WGPUYCbCrVkDescriptor', + 'int32_t', 'size_t', 'struct_WGPUAHardwareBufferProperties', + 'struct_WGPUAdapterImpl', 'struct_WGPUAdapterInfo', + 'struct_WGPUAdapterPropertiesD3D', + 'struct_WGPUAdapterPropertiesMemoryHeaps', + 'struct_WGPUAdapterPropertiesSubgroups', + 'struct_WGPUAdapterPropertiesVk', + 'struct_WGPUBindGroupDescriptor', 'struct_WGPUBindGroupEntry', + 'struct_WGPUBindGroupImpl', + 'struct_WGPUBindGroupLayoutDescriptor', + 'struct_WGPUBindGroupLayoutEntry', + 'struct_WGPUBindGroupLayoutImpl', 'struct_WGPUBlendComponent', + 'struct_WGPUBlendState', 'struct_WGPUBufferBindingLayout', + 'struct_WGPUBufferDescriptor', + 'struct_WGPUBufferHostMappedPointer', 'struct_WGPUBufferImpl', + 'struct_WGPUBufferMapCallbackInfo', + 'struct_WGPUBufferMapCallbackInfo2', 'struct_WGPUChainedStruct', + 'struct_WGPUChainedStructOut', 'struct_WGPUColor', + 'struct_WGPUColorTargetState', + 'struct_WGPUColorTargetStateExpandResolveTextureDawn', + 'struct_WGPUCommandBufferDescriptor', + 'struct_WGPUCommandBufferImpl', + 'struct_WGPUCommandEncoderDescriptor', + 'struct_WGPUCommandEncoderImpl', 'struct_WGPUCompilationInfo', + 'struct_WGPUCompilationInfoCallbackInfo', + 'struct_WGPUCompilationInfoCallbackInfo2', + 'struct_WGPUCompilationMessage', + 'struct_WGPUComputePassDescriptor', + 'struct_WGPUComputePassEncoderImpl', + 'struct_WGPUComputePassTimestampWrites', + 'struct_WGPUComputePipelineDescriptor', + 'struct_WGPUComputePipelineImpl', 'struct_WGPUComputeState', + 'struct_WGPUConstantEntry', + 'struct_WGPUCopyTextureForBrowserOptions', + 'struct_WGPUCreateComputePipelineAsyncCallbackInfo', + 'struct_WGPUCreateComputePipelineAsyncCallbackInfo2', + 'struct_WGPUCreateRenderPipelineAsyncCallbackInfo', + 'struct_WGPUCreateRenderPipelineAsyncCallbackInfo2', + 'struct_WGPUDawnAdapterPropertiesPowerPreference', + 'struct_WGPUDawnBufferDescriptorErrorInfoFromWireClient', + 'struct_WGPUDawnCacheDeviceDescriptor', + 'struct_WGPUDawnEncoderInternalUsageDescriptor', + 'struct_WGPUDawnExperimentalImmediateDataLimits', + 'struct_WGPUDawnExperimentalSubgroupLimits', + 'struct_WGPUDawnRenderPassColorAttachmentRenderToSingleSampled', + 'struct_WGPUDawnShaderModuleSPIRVOptionsDescriptor', + 'struct_WGPUDawnTexelCopyBufferRowAlignmentLimits', + 'struct_WGPUDawnTextureInternalUsageDescriptor', + 'struct_WGPUDawnTogglesDescriptor', + 'struct_WGPUDawnWGSLBlocklist', 'struct_WGPUDawnWireWGSLControl', + 'struct_WGPUDepthStencilState', 'struct_WGPUDeviceDescriptor', + 'struct_WGPUDeviceImpl', 'struct_WGPUDeviceLostCallbackInfo', + 'struct_WGPUDeviceLostCallbackInfo2', + 'struct_WGPUDrmFormatCapabilities', + 'struct_WGPUDrmFormatProperties', 'struct_WGPUExtent2D', + 'struct_WGPUExtent3D', 'struct_WGPUExternalTextureBindingEntry', + 'struct_WGPUExternalTextureBindingLayout', + 'struct_WGPUExternalTextureDescriptor', + 'struct_WGPUExternalTextureImpl', 'struct_WGPUFormatCapabilities', + 'struct_WGPUFragmentState', 'struct_WGPUFuture', + 'struct_WGPUFutureWaitInfo', + 'struct_WGPUINTERNAL__HAVE_EMDAWNWEBGPU_HEADER', + 'struct_WGPUImageCopyBuffer', + 'struct_WGPUImageCopyExternalTexture', + 'struct_WGPUImageCopyTexture', 'struct_WGPUInstanceDescriptor', + 'struct_WGPUInstanceFeatures', 'struct_WGPUInstanceImpl', + 'struct_WGPULimits', 'struct_WGPUMemoryHeapInfo', + 'struct_WGPUMultisampleState', 'struct_WGPUOrigin2D', + 'struct_WGPUOrigin3D', 'struct_WGPUPipelineLayoutDescriptor', + 'struct_WGPUPipelineLayoutImpl', + 'struct_WGPUPipelineLayoutPixelLocalStorage', + 'struct_WGPUPipelineLayoutStorageAttachment', + 'struct_WGPUPopErrorScopeCallbackInfo', + 'struct_WGPUPopErrorScopeCallbackInfo2', + 'struct_WGPUPrimitiveState', 'struct_WGPUQuerySetDescriptor', + 'struct_WGPUQuerySetImpl', 'struct_WGPUQueueDescriptor', + 'struct_WGPUQueueImpl', 'struct_WGPUQueueWorkDoneCallbackInfo', + 'struct_WGPUQueueWorkDoneCallbackInfo2', + 'struct_WGPURenderBundleDescriptor', + 'struct_WGPURenderBundleEncoderDescriptor', + 'struct_WGPURenderBundleEncoderImpl', + 'struct_WGPURenderBundleImpl', + 'struct_WGPURenderPassColorAttachment', + 'struct_WGPURenderPassDepthStencilAttachment', + 'struct_WGPURenderPassDescriptor', + 'struct_WGPURenderPassDescriptorExpandResolveRect', + 'struct_WGPURenderPassEncoderImpl', + 'struct_WGPURenderPassMaxDrawCount', + 'struct_WGPURenderPassPixelLocalStorage', + 'struct_WGPURenderPassStorageAttachment', + 'struct_WGPURenderPassTimestampWrites', + 'struct_WGPURenderPipelineDescriptor', + 'struct_WGPURenderPipelineImpl', + 'struct_WGPURequestAdapterCallbackInfo', + 'struct_WGPURequestAdapterCallbackInfo2', + 'struct_WGPURequestAdapterOptions', + 'struct_WGPURequestDeviceCallbackInfo', + 'struct_WGPURequestDeviceCallbackInfo2', + 'struct_WGPURequiredLimits', 'struct_WGPUSamplerBindingLayout', + 'struct_WGPUSamplerDescriptor', 'struct_WGPUSamplerImpl', + 'struct_WGPUShaderModuleCompilationOptions', + 'struct_WGPUShaderModuleDescriptor', + 'struct_WGPUShaderModuleImpl', 'struct_WGPUShaderSourceSPIRV', + 'struct_WGPUShaderSourceWGSL', + 'struct_WGPUSharedBufferMemoryBeginAccessDescriptor', + 'struct_WGPUSharedBufferMemoryDescriptor', + 'struct_WGPUSharedBufferMemoryEndAccessState', + 'struct_WGPUSharedBufferMemoryImpl', + 'struct_WGPUSharedBufferMemoryProperties', + 'struct_WGPUSharedFenceDXGISharedHandleDescriptor', + 'struct_WGPUSharedFenceDXGISharedHandleExportInfo', + 'struct_WGPUSharedFenceDescriptor', + 'struct_WGPUSharedFenceExportInfo', 'struct_WGPUSharedFenceImpl', + 'struct_WGPUSharedFenceMTLSharedEventDescriptor', + 'struct_WGPUSharedFenceMTLSharedEventExportInfo', + 'struct_WGPUSharedFenceSyncFDDescriptor', + 'struct_WGPUSharedFenceSyncFDExportInfo', + 'struct_WGPUSharedFenceVkSemaphoreOpaqueFDDescriptor', + 'struct_WGPUSharedFenceVkSemaphoreOpaqueFDExportInfo', + 'struct_WGPUSharedFenceVkSemaphoreZirconHandleDescriptor', + 'struct_WGPUSharedFenceVkSemaphoreZirconHandleExportInfo', + 'struct_WGPUSharedTextureMemoryAHardwareBufferDescriptor', + 'struct_WGPUSharedTextureMemoryAHardwareBufferProperties', + 'struct_WGPUSharedTextureMemoryBeginAccessDescriptor', + 'struct_WGPUSharedTextureMemoryD3DSwapchainBeginState', + 'struct_WGPUSharedTextureMemoryDXGISharedHandleDescriptor', + 'struct_WGPUSharedTextureMemoryDescriptor', + 'struct_WGPUSharedTextureMemoryDmaBufDescriptor', + 'struct_WGPUSharedTextureMemoryDmaBufPlane', + 'struct_WGPUSharedTextureMemoryEGLImageDescriptor', + 'struct_WGPUSharedTextureMemoryEndAccessState', + 'struct_WGPUSharedTextureMemoryIOSurfaceDescriptor', + 'struct_WGPUSharedTextureMemoryImpl', + 'struct_WGPUSharedTextureMemoryOpaqueFDDescriptor', + 'struct_WGPUSharedTextureMemoryProperties', + 'struct_WGPUSharedTextureMemoryVkDedicatedAllocationDescriptor', + 'struct_WGPUSharedTextureMemoryVkImageLayoutBeginState', + 'struct_WGPUSharedTextureMemoryVkImageLayoutEndState', + 'struct_WGPUSharedTextureMemoryZirconHandleDescriptor', + 'struct_WGPUStaticSamplerBindingLayout', + 'struct_WGPUStencilFaceState', + 'struct_WGPUStorageTextureBindingLayout', 'struct_WGPUStringView', + 'struct_WGPUSupportedFeatures', 'struct_WGPUSupportedLimits', + 'struct_WGPUSurfaceCapabilities', + 'struct_WGPUSurfaceConfiguration', 'struct_WGPUSurfaceDescriptor', + 'struct_WGPUSurfaceDescriptorFromWindowsCoreWindow', + 'struct_WGPUSurfaceDescriptorFromWindowsSwapChainPanel', + 'struct_WGPUSurfaceImpl', + 'struct_WGPUSurfaceSourceAndroidNativeWindow', + 'struct_WGPUSurfaceSourceCanvasHTMLSelector_Emscripten', + 'struct_WGPUSurfaceSourceMetalLayer', + 'struct_WGPUSurfaceSourceWaylandSurface', + 'struct_WGPUSurfaceSourceWindowsHWND', + 'struct_WGPUSurfaceSourceXCBWindow', + 'struct_WGPUSurfaceSourceXlibWindow', 'struct_WGPUSurfaceTexture', + 'struct_WGPUTextureBindingLayout', + 'struct_WGPUTextureBindingViewDimensionDescriptor', + 'struct_WGPUTextureDataLayout', 'struct_WGPUTextureDescriptor', + 'struct_WGPUTextureImpl', 'struct_WGPUTextureViewDescriptor', + 'struct_WGPUTextureViewImpl', + 'struct_WGPUUncapturedErrorCallbackInfo', + 'struct_WGPUUncapturedErrorCallbackInfo2', + 'struct_WGPUVertexAttribute', 'struct_WGPUVertexBufferLayout', + 'struct_WGPUVertexState', 'struct_WGPUYCbCrVkDescriptor', + 'uint32_t', 'uint64_t', 'wgpuAdapterAddRef', + 'wgpuAdapterCreateDevice', 'wgpuAdapterGetFeatures', + 'wgpuAdapterGetFormatCapabilities', 'wgpuAdapterGetInfo', + 'wgpuAdapterGetInstance', 'wgpuAdapterGetLimits', + 'wgpuAdapterHasFeature', 'wgpuAdapterInfoFreeMembers', + 'wgpuAdapterPropertiesMemoryHeapsFreeMembers', + 'wgpuAdapterRelease', 'wgpuAdapterRequestDevice', + 'wgpuAdapterRequestDevice2', 'wgpuAdapterRequestDeviceF', + 'wgpuBindGroupAddRef', 'wgpuBindGroupLayoutAddRef', + 'wgpuBindGroupLayoutRelease', 'wgpuBindGroupLayoutSetLabel', + 'wgpuBindGroupRelease', 'wgpuBindGroupSetLabel', + 'wgpuBufferAddRef', 'wgpuBufferDestroy', + 'wgpuBufferGetConstMappedRange', 'wgpuBufferGetMapState', + 'wgpuBufferGetMappedRange', 'wgpuBufferGetSize', + 'wgpuBufferGetUsage', 'wgpuBufferMapAsync', 'wgpuBufferMapAsync2', + 'wgpuBufferMapAsyncF', 'wgpuBufferRelease', 'wgpuBufferSetLabel', + 'wgpuBufferUnmap', 'wgpuCommandBufferAddRef', + 'wgpuCommandBufferRelease', 'wgpuCommandBufferSetLabel', + 'wgpuCommandEncoderAddRef', 'wgpuCommandEncoderBeginComputePass', + 'wgpuCommandEncoderBeginRenderPass', + 'wgpuCommandEncoderClearBuffer', + 'wgpuCommandEncoderCopyBufferToBuffer', + 'wgpuCommandEncoderCopyBufferToTexture', + 'wgpuCommandEncoderCopyTextureToBuffer', + 'wgpuCommandEncoderCopyTextureToTexture', + 'wgpuCommandEncoderFinish', + 'wgpuCommandEncoderInjectValidationError', + 'wgpuCommandEncoderInsertDebugMarker', + 'wgpuCommandEncoderPopDebugGroup', + 'wgpuCommandEncoderPushDebugGroup', 'wgpuCommandEncoderRelease', + 'wgpuCommandEncoderResolveQuerySet', 'wgpuCommandEncoderSetLabel', + 'wgpuCommandEncoderWriteBuffer', + 'wgpuCommandEncoderWriteTimestamp', + 'wgpuComputePassEncoderAddRef', + 'wgpuComputePassEncoderDispatchWorkgroups', + 'wgpuComputePassEncoderDispatchWorkgroupsIndirect', + 'wgpuComputePassEncoderEnd', + 'wgpuComputePassEncoderInsertDebugMarker', + 'wgpuComputePassEncoderPopDebugGroup', + 'wgpuComputePassEncoderPushDebugGroup', + 'wgpuComputePassEncoderRelease', + 'wgpuComputePassEncoderSetBindGroup', + 'wgpuComputePassEncoderSetLabel', + 'wgpuComputePassEncoderSetPipeline', + 'wgpuComputePassEncoderWriteTimestamp', + 'wgpuComputePipelineAddRef', + 'wgpuComputePipelineGetBindGroupLayout', + 'wgpuComputePipelineRelease', 'wgpuComputePipelineSetLabel', + 'wgpuCreateInstance', 'wgpuDeviceAddRef', + 'wgpuDeviceCreateBindGroup', 'wgpuDeviceCreateBindGroupLayout', + 'wgpuDeviceCreateBuffer', 'wgpuDeviceCreateCommandEncoder', + 'wgpuDeviceCreateComputePipeline', + 'wgpuDeviceCreateComputePipelineAsync', + 'wgpuDeviceCreateComputePipelineAsync2', + 'wgpuDeviceCreateComputePipelineAsyncF', + 'wgpuDeviceCreateErrorBuffer', + 'wgpuDeviceCreateErrorExternalTexture', + 'wgpuDeviceCreateErrorShaderModule', + 'wgpuDeviceCreateErrorTexture', 'wgpuDeviceCreateExternalTexture', + 'wgpuDeviceCreatePipelineLayout', 'wgpuDeviceCreateQuerySet', + 'wgpuDeviceCreateRenderBundleEncoder', + 'wgpuDeviceCreateRenderPipeline', + 'wgpuDeviceCreateRenderPipelineAsync', + 'wgpuDeviceCreateRenderPipelineAsync2', + 'wgpuDeviceCreateRenderPipelineAsyncF', 'wgpuDeviceCreateSampler', + 'wgpuDeviceCreateShaderModule', 'wgpuDeviceCreateTexture', + 'wgpuDeviceDestroy', 'wgpuDeviceForceLoss', + 'wgpuDeviceGetAHardwareBufferProperties', 'wgpuDeviceGetAdapter', + 'wgpuDeviceGetAdapterInfo', 'wgpuDeviceGetFeatures', + 'wgpuDeviceGetLimits', 'wgpuDeviceGetLostFuture', + 'wgpuDeviceGetQueue', 'wgpuDeviceHasFeature', + 'wgpuDeviceImportSharedBufferMemory', + 'wgpuDeviceImportSharedFence', + 'wgpuDeviceImportSharedTextureMemory', 'wgpuDeviceInjectError', + 'wgpuDevicePopErrorScope', 'wgpuDevicePopErrorScope2', + 'wgpuDevicePopErrorScopeF', 'wgpuDevicePushErrorScope', + 'wgpuDeviceRelease', 'wgpuDeviceSetLabel', + 'wgpuDeviceSetLoggingCallback', 'wgpuDeviceTick', + 'wgpuDeviceValidateTextureDescriptor', + 'wgpuDrmFormatCapabilitiesFreeMembers', + 'wgpuExternalTextureAddRef', 'wgpuExternalTextureDestroy', + 'wgpuExternalTextureExpire', 'wgpuExternalTextureRefresh', + 'wgpuExternalTextureRelease', 'wgpuExternalTextureSetLabel', + 'wgpuGetInstanceFeatures', 'wgpuGetProcAddress', + 'wgpuInstanceAddRef', 'wgpuInstanceCreateSurface', + 'wgpuInstanceEnumerateWGSLLanguageFeatures', + 'wgpuInstanceHasWGSLLanguageFeature', 'wgpuInstanceProcessEvents', + 'wgpuInstanceRelease', 'wgpuInstanceRequestAdapter', + 'wgpuInstanceRequestAdapter2', 'wgpuInstanceRequestAdapterF', + 'wgpuInstanceWaitAny', 'wgpuPipelineLayoutAddRef', + 'wgpuPipelineLayoutRelease', 'wgpuPipelineLayoutSetLabel', + 'wgpuQuerySetAddRef', 'wgpuQuerySetDestroy', + 'wgpuQuerySetGetCount', 'wgpuQuerySetGetType', + 'wgpuQuerySetRelease', 'wgpuQuerySetSetLabel', 'wgpuQueueAddRef', + 'wgpuQueueCopyExternalTextureForBrowser', + 'wgpuQueueCopyTextureForBrowser', 'wgpuQueueOnSubmittedWorkDone', + 'wgpuQueueOnSubmittedWorkDone2', 'wgpuQueueOnSubmittedWorkDoneF', + 'wgpuQueueRelease', 'wgpuQueueSetLabel', 'wgpuQueueSubmit', + 'wgpuQueueWriteBuffer', 'wgpuQueueWriteTexture', + 'wgpuRenderBundleAddRef', 'wgpuRenderBundleEncoderAddRef', + 'wgpuRenderBundleEncoderDraw', + 'wgpuRenderBundleEncoderDrawIndexed', + 'wgpuRenderBundleEncoderDrawIndexedIndirect', + 'wgpuRenderBundleEncoderDrawIndirect', + 'wgpuRenderBundleEncoderFinish', + 'wgpuRenderBundleEncoderInsertDebugMarker', + 'wgpuRenderBundleEncoderPopDebugGroup', + 'wgpuRenderBundleEncoderPushDebugGroup', + 'wgpuRenderBundleEncoderRelease', + 'wgpuRenderBundleEncoderSetBindGroup', + 'wgpuRenderBundleEncoderSetIndexBuffer', + 'wgpuRenderBundleEncoderSetLabel', + 'wgpuRenderBundleEncoderSetPipeline', + 'wgpuRenderBundleEncoderSetVertexBuffer', + 'wgpuRenderBundleRelease', 'wgpuRenderBundleSetLabel', + 'wgpuRenderPassEncoderAddRef', + 'wgpuRenderPassEncoderBeginOcclusionQuery', + 'wgpuRenderPassEncoderDraw', 'wgpuRenderPassEncoderDrawIndexed', + 'wgpuRenderPassEncoderDrawIndexedIndirect', + 'wgpuRenderPassEncoderDrawIndirect', 'wgpuRenderPassEncoderEnd', + 'wgpuRenderPassEncoderEndOcclusionQuery', + 'wgpuRenderPassEncoderExecuteBundles', + 'wgpuRenderPassEncoderInsertDebugMarker', + 'wgpuRenderPassEncoderMultiDrawIndexedIndirect', + 'wgpuRenderPassEncoderMultiDrawIndirect', + 'wgpuRenderPassEncoderPixelLocalStorageBarrier', + 'wgpuRenderPassEncoderPopDebugGroup', + 'wgpuRenderPassEncoderPushDebugGroup', + 'wgpuRenderPassEncoderRelease', + 'wgpuRenderPassEncoderSetBindGroup', + 'wgpuRenderPassEncoderSetBlendConstant', + 'wgpuRenderPassEncoderSetIndexBuffer', + 'wgpuRenderPassEncoderSetLabel', + 'wgpuRenderPassEncoderSetPipeline', + 'wgpuRenderPassEncoderSetScissorRect', + 'wgpuRenderPassEncoderSetStencilReference', + 'wgpuRenderPassEncoderSetVertexBuffer', + 'wgpuRenderPassEncoderSetViewport', + 'wgpuRenderPassEncoderWriteTimestamp', 'wgpuRenderPipelineAddRef', + 'wgpuRenderPipelineGetBindGroupLayout', + 'wgpuRenderPipelineRelease', 'wgpuRenderPipelineSetLabel', + 'wgpuSamplerAddRef', 'wgpuSamplerRelease', 'wgpuSamplerSetLabel', + 'wgpuShaderModuleAddRef', 'wgpuShaderModuleGetCompilationInfo', + 'wgpuShaderModuleGetCompilationInfo2', + 'wgpuShaderModuleGetCompilationInfoF', 'wgpuShaderModuleRelease', + 'wgpuShaderModuleSetLabel', 'wgpuSharedBufferMemoryAddRef', + 'wgpuSharedBufferMemoryBeginAccess', + 'wgpuSharedBufferMemoryCreateBuffer', + 'wgpuSharedBufferMemoryEndAccess', + 'wgpuSharedBufferMemoryEndAccessStateFreeMembers', + 'wgpuSharedBufferMemoryGetProperties', + 'wgpuSharedBufferMemoryIsDeviceLost', + 'wgpuSharedBufferMemoryRelease', 'wgpuSharedBufferMemorySetLabel', + 'wgpuSharedFenceAddRef', 'wgpuSharedFenceExportInfo', + 'wgpuSharedFenceRelease', 'wgpuSharedTextureMemoryAddRef', + 'wgpuSharedTextureMemoryBeginAccess', + 'wgpuSharedTextureMemoryCreateTexture', + 'wgpuSharedTextureMemoryEndAccess', + 'wgpuSharedTextureMemoryEndAccessStateFreeMembers', + 'wgpuSharedTextureMemoryGetProperties', + 'wgpuSharedTextureMemoryIsDeviceLost', + 'wgpuSharedTextureMemoryRelease', + 'wgpuSharedTextureMemorySetLabel', + 'wgpuSupportedFeaturesFreeMembers', 'wgpuSurfaceAddRef', + 'wgpuSurfaceCapabilitiesFreeMembers', 'wgpuSurfaceConfigure', + 'wgpuSurfaceGetCapabilities', 'wgpuSurfaceGetCurrentTexture', + 'wgpuSurfacePresent', 'wgpuSurfaceRelease', 'wgpuSurfaceSetLabel', + 'wgpuSurfaceUnconfigure', 'wgpuTextureAddRef', + 'wgpuTextureCreateErrorView', 'wgpuTextureCreateView', + 'wgpuTextureDestroy', 'wgpuTextureGetDepthOrArrayLayers', + 'wgpuTextureGetDimension', 'wgpuTextureGetFormat', + 'wgpuTextureGetHeight', 'wgpuTextureGetMipLevelCount', + 'wgpuTextureGetSampleCount', 'wgpuTextureGetUsage', + 'wgpuTextureGetWidth', 'wgpuTextureRelease', + 'wgpuTextureSetLabel', 'wgpuTextureViewAddRef', + 'wgpuTextureViewRelease', 'wgpuTextureViewSetLabel'] diff --git a/tinygrad_repo/tinygrad/runtime/graph/cpu.py b/tinygrad_repo/tinygrad/runtime/graph/cpu.py new file mode 100644 index 0000000000..390c35a204 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/graph/cpu.py @@ -0,0 +1,67 @@ +from typing import cast, TypeVar, Generic, get_args as get_typing_args +import itertools +from tinygrad.helpers import dedup, flatten, DEBUG, to_function_name +from tinygrad.engine.jit import GraphRunner, GraphException +from tinygrad.device import Buffer +from tinygrad.engine.realize import ExecItem, CompiledRunner +from tinygrad.uop.ops import Variable +from tinygrad.dtype import DType, dtypes +from tinygrad.renderer.cstyle import ClangRenderer +from tinygrad.renderer.llvmir import LLVMRenderer, ldt + +T = TypeVar('T') +class BatchedGraph(Generic[T], GraphRunner): + def __init__(self, device, jit_cache: list[ExecItem], input_rawbuffers: list[Buffer], var_vals: dict[Variable, int]): + renderer_class = get_typing_args(getattr(self, "__orig_bases__")[0])[0] + if not issubclass(type(device.renderer), renderer_class) and not isinstance(device.renderer, renderer_class): raise GraphException + + super().__init__(jit_cache, input_rawbuffers, var_vals) + self.base_bufs = dedup(b.base for ji in jit_cache for b in ji.bufs if b is not None and b not in input_rawbuffers) + self.base_rawbufs = [b._buf for b in self.base_bufs] + + targs = [(f"arg{i}", x.dtype.ptr()) for i,x in enumerate(input_rawbuffers)] + \ + [(f"cbuf{i}", dtypes.char.ptr()) for i in range(len(self.base_bufs))] + \ + sorted([(f"{v.expr}", dtypes.int) for v in var_vals]) + code = self._prepare_code(device.renderer, jit_cache, input_rawbuffers, targs) + if DEBUG >= 4: print(code) + self.clprg = device.runtime("batched", device.compiler.compile_cached(code)) + + def _prepare_code(self, renderer:T, jit_cache:list[ExecItem], input_rawbuffers:list[Buffer], targs:list[tuple[str, DType]]) -> str: return "" + def __call__(self, rawbufs: list[Buffer], var_vals: dict[Variable, int], wait=False): + return self.clprg(*[x._buf for x in rawbufs], *self.base_rawbufs, *[x[1] for x in sorted(var_vals.items(), key=lambda x: x[0].expr)], wait=wait) + +class CPUGraph(BatchedGraph[ClangRenderer]): + def _prepare_code(self, renderer:ClangRenderer, jit_cache:list[ExecItem], input_rawbuffers:list[Buffer], targs:list[tuple[str, DType]]) -> str: + def render_arg(buf): + if buf in input_rawbuffers: return f"arg{input_rawbuffers.index(buf)}" + return f"({renderer.render_dtype(buf.dtype)}*)(cbuf{self.base_bufs.index(buf.base)} + {buf.offset})" + + batched = ["void batched("+','.join([f"{renderer.render_dtype(x[1])} {x[0]}" for x in targs])+") {"] + for i, ji in enumerate(jit_cache): + args = [render_arg(buf) for buf in ji.bufs] + [x.expr for x in cast(CompiledRunner, ji.prg).p.vars] + batched.append(f" {to_function_name(cast(CompiledRunner, ji.prg).p.name)}({','.join(args)});") + batched.append("}") + + prep = [renderer._render(cast(CompiledRunner, ji.prg).p.uops or []) for i,ji in enumerate(jit_cache)] + funcs = dedup(renderer._render_body(prep[i][0], *prep[i][1:], cast(CompiledRunner, ji.prg).p.uops, + ["static", "__attribute__((always_inline))"]) for i,ji in enumerate(jit_cache)) + defines = dedup(itertools.chain.from_iterable(renderer._render_defines(cast(CompiledRunner, ji.prg).p.uops) for ji in jit_cache)) + entry = renderer._render_entry("batched", [(t[0], (t[1], False)) for t in targs]) + return '\n'.join(defines) + '\n' + '\n'.join([''.join(f) for f in funcs]) + '\n'.join(batched) + '\n' + entry + +class LLVMGraph(BatchedGraph[LLVMRenderer]): + def _prepare_code(self, renderer, jit_cache:list[ExecItem], input_rawbuffers:list[Buffer], targs:list[tuple[str, DType]]) -> str: + out = [] + for i,ji in enumerate(jit_cache): + args = [] + for j,buf in enumerate(cast(list[Buffer], ji.bufs)): + arg = f"%arg{input_rawbuffers.index(buf)}" if buf in input_rawbuffers else f"%b{i}_{j}" + if buf not in input_rawbuffers: out.append(f" {arg} = getelementptr inbounds i8,ptr %cbuf{self.base_bufs.index(buf.base)},i64 {buf.offset}") + args.append(f"{ldt(buf.dtype.ptr())} {arg}") + args += [f"{ldt(x.dtype)} %{x.expr}" for x in cast(CompiledRunner, ji.prg).p.vars] + out.append(f" call void @{to_function_name(cast(CompiledRunner, ji.prg).p.name)}({','.join(args)})") + + kernels = dedup(tuple(renderer._render_kernel(cast(CompiledRunner, ji.prg).p.uops, ["internal"]) for i,ji in enumerate(jit_cache))) + kernels += [((), renderer._render_fn("batched", [(f"%{x[0]}", x[1]) for x in targs], out))] + assert flatten(x[0] for x in kernels) == [] # global definitions are not used in CPU mode right now + return "\n".join([x[1] for x in kernels] + [renderer._render_footer(cast(CompiledRunner, ji.prg).p.uops)]) diff --git a/tinygrad_repo/tinygrad/runtime/graph/cuda.py b/tinygrad_repo/tinygrad/runtime/graph/cuda.py index c9feadf260..7ab99ad0bd 100644 --- a/tinygrad_repo/tinygrad/runtime/graph/cuda.py +++ b/tinygrad_repo/tinygrad/runtime/graph/cuda.py @@ -1,10 +1,10 @@ import ctypes -from typing import Any, Optional, cast +from typing import Any, cast import tinygrad.runtime.autogen.cuda as cuda from tinygrad.helpers import init_c_var, dedup from tinygrad.device import Buffer, Device from tinygrad.runtime.ops_cuda import CUDADevice, check, encode_args, cu_time_execution -from tinygrad.ops import Variable +from tinygrad.uop.ops import Variable from tinygrad.engine.realize import ExecItem, BufferXfer, CompiledRunner from tinygrad.engine.jit import MultiGraphRunner, GraphException @@ -28,7 +28,7 @@ class CUDAGraph(MultiGraphRunner): deps = self._access_resources([x.base for x in ji.bufs if x is not None], ji.prg.p.outs, new_dependency=new_node) c_deps = (cuda.CUgraphNode*len(deps))(*deps) if deps else None - c_args, vargs = encode_args([cast(Buffer, x)._buf for x in ji.bufs], [var_vals[x] for x in ji.prg.p.vars]) + c_args, vargs = encode_args([cast(Buffer, x)._buf for x in ji.bufs], [var_vals.get(x, ji.fixedvars.get(x)) for x in ji.prg.p.vars]) kern_params = cuda.CUDA_KERNEL_NODE_PARAMS(ji.prg._prg.prg, *global_size, *local_size, 0, None, vargs) check(cuda.cuGraphAddKernelNode(ctypes.byref(new_node), self.graph, c_deps, len(deps), ctypes.byref(kern_params))) @@ -48,7 +48,7 @@ class CUDAGraph(MultiGraphRunner): self.instance = init_c_var(cuda.CUgraphExec(), lambda x: check(cuda.cuGraphInstantiate_v2(ctypes.byref(x), self.graph, None, None, 0))) - def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> Optional[float]: + def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> float|None: # Update rawbuffers in the c_args struct. for (j,i),input_idx in self.input_replace.items(): if not self.updatable_nodes[j][3]: setattr(self.updatable_nodes[j][2], f'f{i}', input_rawbuffers[input_idx]._buf) diff --git a/tinygrad_repo/tinygrad/runtime/graph/hcq.py b/tinygrad_repo/tinygrad/runtime/graph/hcq.py index 352c5476da..4bcf17dba5 100644 --- a/tinygrad_repo/tinygrad/runtime/graph/hcq.py +++ b/tinygrad_repo/tinygrad/runtime/graph/hcq.py @@ -1,10 +1,10 @@ import collections, time -from typing import Any, cast, Optional -from tinygrad.helpers import round_up, PROFILE +from typing import Any, cast +from tinygrad.helpers import round_up, PROFILE, merge_dicts from tinygrad.runtime.support.hcq import HCQCompiled, HCQAllocator, HCQSignal, HCQBuffer, HWQueue, HCQArgsState, BumpAllocator from tinygrad.device import Buffer, BufferSpec, Compiled, Device, ProfileGraphEntry, ProfileGraphEvent from tinygrad.dtype import dtypes -from tinygrad.ops import UOp, Variable +from tinygrad.uop.ops import UOp, Variable from tinygrad.engine.realize import ExecItem, BufferXfer, CompiledRunner from tinygrad.engine.jit import MultiGraphRunner @@ -31,18 +31,19 @@ class HCQGraph(MultiGraphRunner): # Fill initial arguments. self.ji_args: dict[int, HCQArgsState] = {} - kargs_alloc: dict[Compiled, BumpAllocator] = {dev:BumpAllocator(buf.size, start=cast(int, buf.va_addr)) for dev,buf in self.kernargs_bufs.items()} + kargs_alloc: dict[Compiled, BumpAllocator] = {dev:BumpAllocator(buf.size) for dev,buf in self.kernargs_bufs.items()} for j,ji in enumerate(jit_cache): if not isinstance(ji.prg, CompiledRunner): continue - self.ji_args[j] = ji.prg._prg.fill_kernargs(self.hcq_bufs[j], ji.prg.p.vars, kargs_alloc[ji.prg.dev].alloc(ji.prg._prg.kernargs_alloc_size, 16)) + argsbuf = self.kernargs_bufs[ji.prg.dev].offset(kargs_alloc[ji.prg.dev].alloc(ji.prg._prg.kernargs_alloc_size, 16)) + self.ji_args[j] = ji.prg._prg.fill_kernargs(self.hcq_bufs[j], ji.prg.p.vars, argsbuf) # Schedule Dependencies. # There are two types of queues on each device: copy and compute. Both must synchronize with all external operations before launching any # graph-related tasks. This synchronization uses a global timeline signal per device. Within the graph, the compute queue coordinates with # global operations and sets a kickoff signal. Any queue accessing a buffer from another device waits for this signal from the device’s # compute queue to ensure exclusive access. The compute queue signals the completion of the graph, synchronizing with the device's copy queue. - self.ji_schedule: dict[int, tuple[HCQCompiled, HWQueue, list, list, HCQSignal, Optional[int]]] = {} + self.ji_schedule: dict[int, tuple[HCQCompiled, HWQueue, list, list, HCQSignal, int|None]] = {} self.comp_queues: dict[HCQCompiled, HWQueue] = {dev: dev.hw_compute_queue_t() for dev in self.devices} self.copy_queues: dict[HCQCompiled, HWQueue] = {} # lazy allocation @@ -57,15 +58,20 @@ class HCQGraph(MultiGraphRunner): self.prog_graph_deps: list[list[int]] = [] self.prof_graph_entries: list[ProfileGraphEntry] = [] - last_j: dict[HWQueue, Optional[int]] = collections.defaultdict(lambda: None) - queue_access: dict[HWQueue, dict[HWQueue, Optional[int]]] = collections.defaultdict(lambda: collections.defaultdict(lambda: None)) + last_j: dict[HWQueue, int|None] = collections.defaultdict(lambda: None) + queue_access: dict[HWQueue, dict[HWQueue, int|None]] = collections.defaultdict(lambda: collections.defaultdict(lambda: None)) dev_access: dict[HWQueue, set[HCQCompiled]] = collections.defaultdict(set) for dev, queue in self.comp_queues.items(): dev_access[queue].add(dev) + self.fixedvars: dict[HCQCompiled, dict[Variable, int]] = {} + for j,ji in enumerate(jit_cache): enqueue_dev: HCQCompiled = ji.prg.dev if (is_exec_prg:=isinstance(ji.prg, CompiledRunner)) else Device[ji.bufs[1].device] #type:ignore + # set any fixedvars on the device + self.fixedvars[enqueue_dev] = merge_dicts([self.fixedvars.get(enqueue_dev, {}), ji.fixedvars]) + if is_exec_prg: enqueue_queue = self.comp_queues[enqueue_dev] else: @@ -125,7 +131,7 @@ class HCQGraph(MultiGraphRunner): # Create variable timeline signals for each device. timeline_sigaddrs = {dev: UOp.variable(f"timeline_sig_{dev.device_id}", 0, 0xffffffffffffffff, dtype=dtypes.uint64) for dev in self.devices} self.virt_timeline_vals = {dev: UOp.variable(f"timeline_var_{dev.device_id}", 0, 0xffffffff, dtype=dtypes.uint32) for dev in self.devices} - self.virt_timeline_signals = {dev: dev.signal_t(base_addr=timeline_sigaddrs[dev], timeline_for_device=dev) for dev in self.devices} + self.virt_timeline_signals = {dev: dev.signal_t(base_buf=HCQBuffer(timeline_sigaddrs[dev], 16), timeline_for_device=dev) for dev in self.devices} for dev in self.devices: self.comp_queues[dev].memory_barrier().wait(self.virt_timeline_signals[dev], self.virt_timeline_vals[dev]) \ @@ -164,7 +170,7 @@ class HCQGraph(MultiGraphRunner): self.last_timeline: dict[HCQCompiled, tuple[HCQSignal, int]] = {dev: (dev.timeline_signal, 0) for dev in self.devices} self.queue_signals_to_reset = [self.signals[q] for q in list(self.comp_queues.values()) + list(self.copy_queues.values()) if q in self.signals] - def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> Optional[float]: + def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> float|None: # Wait and restore signals self.kickoff_value += 1 for dev in self.devices: self.last_timeline[dev][0].wait(self.last_timeline[dev][1]) @@ -175,17 +181,16 @@ class HCQGraph(MultiGraphRunner): hcq_var_vals = {self.kickoff_var: self.kickoff_value, **var_vals, **{var: dev.timeline_value - 1 for dev, var in self.virt_timeline_vals.items()}, - **{sig.base_addr: dev.timeline_signal.base_addr for dev, sig in self.virt_timeline_signals.items()}} + **{sig.base_buf.va_addr: dev.timeline_signal.base_buf.va_addr for dev, sig in self.virt_timeline_signals.items()}} # Update rawbuffers for (j,i),input_idx in self.input_replace.items(): hcq_var_vals[self.input_replace_to_var.get((j,i))] = input_rawbuffers[input_idx]._buf.va_addr for dev in self.devices: - self.comp_queues[dev].submit(dev, hcq_var_vals) - if (copy_queue:=self.copy_queues.get(dev, None)) is not None: copy_queue.submit(dev, hcq_var_vals) + self.comp_queues[dev].submit(dev, hcq_var_vals_local:=hcq_var_vals|self.fixedvars.get(dev, {})) + if (copy_queue:=self.copy_queues.get(dev, None)) is not None: copy_queue.submit(dev, hcq_var_vals_local) - self.last_timeline[dev] = (dev.timeline_signal, dev.timeline_value) - dev.timeline_value += 1 + self.last_timeline[dev] = (dev.timeline_signal, dev.next_timeline()) if wait: st = time.perf_counter() diff --git a/tinygrad_repo/tinygrad/runtime/graph/metal.py b/tinygrad_repo/tinygrad/runtime/graph/metal.py index b45fce0855..d8fd14abec 100644 --- a/tinygrad_repo/tinygrad/runtime/graph/metal.py +++ b/tinygrad_repo/tinygrad/runtime/graph/metal.py @@ -1,11 +1,11 @@ -from typing import Any, cast, Optional -import ctypes +from typing import Any, cast +import ctypes, re from tinygrad.dtype import dtypes -from tinygrad.helpers import dedup, getenv +from tinygrad.helpers import dedup, getenv, merge_dicts from tinygrad.device import Buffer from tinygrad.engine.realize import ExecItem, CompiledRunner from tinygrad.engine.jit import GraphRunner, GraphException -from tinygrad.ops import Variable +from tinygrad.uop.ops import Variable from tinygrad.runtime.ops_metal import wait_check, msg, libobjc, to_struct, objc_instance,\ MTLResourceOptions, cmdbuf_st_time, cmdbuf_en_time, objc_id, to_ns_str @@ -22,60 +22,61 @@ class MetalGraph(GraphRunner): if not all(isinstance(ji.prg, CompiledRunner) for ji in jit_cache): raise GraphException # create metal batch exec - icb_descriptor = msg(libobjc.objc_getClass(b"MTLIndirectCommandBufferDescriptor"), "new", restype=objc_instance) - msg(icb_descriptor, "setCommandTypes:", MTLIndirectCommandType.MTLIndirectCommandTypeConcurrentDispatch) - msg(icb_descriptor, "setInheritBuffers:", False) - msg(icb_descriptor, "setInheritPipelineState:", False) - msg(icb_descriptor, "setMaxKernelBufferBindCount:", 31) - - self.icb = msg(self.dev.sysdevice, "newIndirectCommandBufferWithDescriptor:maxCommandCount:options:", - icb_descriptor, len(jit_cache), MTLResourceOptions.MTLResourceCPUCacheModeDefaultCache, restype=objc_instance) + icb_descriptor = msg("new", objc_instance)(libobjc.objc_getClass(b"MTLIndirectCommandBufferDescriptor")) + msg("setCommandTypes:")(icb_descriptor, MTLIndirectCommandType.MTLIndirectCommandTypeConcurrentDispatch) + msg("setInheritBuffers:")(icb_descriptor, False) + msg("setInheritPipelineState:")(icb_descriptor, False) + msg("setMaxKernelBufferBindCount:")(icb_descriptor, 31) + + self.icb = msg("newIndirectCommandBufferWithDescriptor:maxCommandCount:options:", objc_instance)(self.dev.sysdevice, + icb_descriptor, len(jit_cache), MTLResourceOptions.MTLResourceCPUCacheModeDefaultCache) if self.icb.value is None: raise GraphException("create indirect command buffer failed, does your system support this?") - icb_label = bytes(msg(msg(self.icb, "description", restype=objc_instance), "UTF8String", restype=ctypes.c_char_p)).decode() - self.needs_icb_fix = int("AGXG15XFamilyIndirectCommandBuffer" not in icb_label) # not required on M3 + icb_label = bytes(msg("UTF8String", ctypes.c_char_p)(msg("description", objc_instance)(self.icb))).decode() + self.needs_icb_fix = int((m := re.search(r'AGXG(\d+)XFamily', icb_label)) is None or int(m.group(1)) < 15) # not required on M3+ - if len(self.vars): self.int_buf = self.dev.allocator.alloc(len(self.vars)*dtypes.int32.itemsize) - all_resources = [self.int_buf.buf] if len(self.vars) else [] - all_pipelines = [] + self.fixedvars = merge_dicts([ji.fixedvars for ji in jit_cache]) + self.varlist = self.vars + list(self.fixedvars.keys()) + if len(self.varlist): self.int_buf = self.dev.allocator.alloc(len(self.varlist)*dtypes.int32.itemsize) + + all_pipelines, all_resources = [], [self.int_buf.buf] if len(self.varlist) else [] for j,ji in enumerate(jit_cache): prg: CompiledRunner = cast(CompiledRunner, ji.prg) - icb_command = msg(self.icb, "indirectComputeCommandAtIndex:", j, restype=objc_instance) + icb_command = msg("indirectComputeCommandAtIndex:", objc_instance)(self.icb, j) all_pipelines.append(prg._prg.pipeline_state) - msg(icb_command, "setComputePipelineState:", prg._prg.pipeline_state) + msg("setComputePipelineState:")(icb_command, prg._prg.pipeline_state) for i,b in enumerate(ji.bufs): if b is not None and b not in input_rawbuffers: - msg(icb_command, "setKernelBuffer:offset:atIndex:", b._buf.buf, b._buf.offset, i) + msg("setKernelBuffer:offset:atIndex:")(icb_command, b._buf.buf, b._buf.offset, i) all_resources.append(b._buf.buf) - for i,v in enumerate(prg.p.vars): msg(icb_command, "setKernelBuffer:offset:atIndex:", self.int_buf.buf, self.vars.index(v)*4, len(ji.bufs)+i) + for i,v in enumerate(prg.p.vars): msg("setKernelBuffer:offset:atIndex:")(icb_command, self.int_buf.buf, self.varlist.index(v)*4, len(ji.bufs)+i) global_size, local_size = prg.p.launch_dims(var_vals) - msg(icb_command, "concurrentDispatchThreadgroups:threadsPerThreadgroup:", to_struct(*global_size), to_struct(*local_size)) - msg(icb_command, "setBarrier") + msg("concurrentDispatchThreadgroups:threadsPerThreadgroup:")(icb_command, to_struct(*global_size), to_struct(*local_size)) + msg("setBarrier")(icb_command) self.all_resources = dedup(all_resources) self.all_pipelines = dedup(all_pipelines) self.command_buffer: Any = None - if len(self.vars): self.int_buf_view = self.dev.allocator._as_buffer(self.int_buf).cast('i') + if len(self.varlist): self.int_buf_view = self.dev.allocator._as_buffer(self.int_buf).cast('i') + for var in self.fixedvars: self.int_buf_view[self.varlist.index(var)] = self.fixedvars[var] self.range = to_struct(0, len(jit_cache)) - def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> Optional[float]: - + def __call__(self, input_rawbuffers: list[Buffer], var_vals: dict[Variable, int], wait=False) -> float|None: if self.command_buffer is not None and self.command_buffer in self.dev.mtl_buffers_in_flight: wait_check(self.command_buffer) - all_resources = dedup(self.all_resources + [x._buf.buf for x in input_rawbuffers]) + all_resources = dedup(self.all_resources + [input_rawbuffers[input_idx]._buf.buf for input_idx in self.input_replace.values()]) for (j,i),input_idx in self.input_replace.items(): - computeCommand = msg(self.icb, "indirectComputeCommandAtIndex:", j, restype=objc_id) - msg(computeCommand, "setKernelBuffer:offset:atIndex:", input_rawbuffers[input_idx]._buf.buf, - input_rawbuffers[input_idx]._buf.offset, i) + computeCommand = msg("indirectComputeCommandAtIndex:", objc_id)(self.icb, j) + msg("setKernelBuffer:offset:atIndex:")(computeCommand, input_rawbuffers[input_idx]._buf.buf, input_rawbuffers[input_idx]._buf.offset, i) for j, global_dims, local_dims in self.updated_launch_dims(var_vals): - computeCommand = msg(self.icb, "indirectComputeCommandAtIndex:", j, restype=objc_id) - msg(computeCommand, "concurrentDispatchThreadgroups:threadsPerThreadgroup:", to_struct(*global_dims), to_struct(*local_dims)) - for j, var in enumerate(self.vars): self.int_buf_view[j] = var_vals[var] + computeCommand = msg("indirectComputeCommandAtIndex:", objc_id)(self.icb, j) + msg("concurrentDispatchThreadgroups:threadsPerThreadgroup:")(computeCommand, to_struct(*global_dims), to_struct(*local_dims)) + for var in self.vars: self.int_buf_view[self.varlist.index(var)] = var_vals[var] - command_buffer = msg(self.dev.mtl_queue, "commandBuffer", restype=objc_instance) - encoder = msg(command_buffer, "computeCommandEncoder", restype=objc_instance) - msg(encoder, "useResources:count:usage:", (objc_id * len(all_resources))(*all_resources), len(all_resources), + command_buffer = msg("commandBuffer", objc_instance)(self.dev.mtl_queue) + encoder = msg("computeCommandEncoder", objc_instance)(command_buffer) + msg("useResources:count:usage:")(encoder, (objc_id * len(all_resources))(*all_resources), len(all_resources), MTLResourceUsage.MTLResourceUsageRead | MTLResourceUsage.MTLResourceUsageWrite) # NOTE: the pipelines likely need to be added to the used resources to fix the crash on M1/M2, but I haven't figured out how @@ -85,13 +86,13 @@ class MetalGraph(GraphRunner): # to repro the crash (which can also crash other running GPU apps), run with FIX_METAL_ICB=0 if getenv("FIX_METAL_ICB", self.needs_icb_fix): for ps in self.all_pipelines: - msg(encoder, "setComputePipelineState:", ps) - msg(encoder, "dispatchThreadgroups:threadsPerThreadgroup:", to_struct(0,0,0), to_struct(0,0,0)) + msg("setComputePipelineState:")(encoder, ps) + msg("dispatchThreadgroups:threadsPerThreadgroup:")(encoder, to_struct(0,0,0), to_struct(0,0,0)) - msg(encoder, "executeCommandsInBuffer:withRange:", self.icb, self.range) - msg(encoder, "endEncoding") - msg(command_buffer, "setLabel:", to_ns_str(f"batched {len(self.jit_cache)}")) - msg(command_buffer, "commit") + msg("executeCommandsInBuffer:withRange:")(encoder, self.icb, self.range) + msg("endEncoding")(encoder) + msg("setLabel:")(command_buffer, to_ns_str(f"batched {len(self.jit_cache)}")) + msg("commit")(command_buffer) self.command_buffer = command_buffer self.dev.mtl_buffers_in_flight.append(command_buffer) diff --git a/tinygrad_repo/tinygrad/runtime/graph/remote.py b/tinygrad_repo/tinygrad/runtime/graph/remote.py new file mode 100644 index 0000000000..04c6dbdbc9 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/graph/remote.py @@ -0,0 +1,40 @@ +from tinygrad.uop.ops import Variable +from tinygrad.engine.jit import GraphRunner, MultiGraphRunner, GraphException +from tinygrad.engine.realize import CompiledRunner, BufferXfer, ExecItem +from tinygrad.device import Device, Buffer +from tinygrad.runtime.ops_remote import RemoteDevice, GraphComputeItem, Transfer, GraphAlloc, GraphFree, GraphExec +from tinygrad.helpers import unwrap, flatten, dedup, all_same +from typing import cast + +class RemoteGraph(GraphRunner): + def __init__(self, jit_cache: list[ExecItem], rawbufs: list[Buffer], var_vals: dict[Variable, int]): + super().__init__(jit_cache, rawbufs, var_vals) + self.devices = dedup(flatten([[Device[unwrap(buf).device] for buf in ji.bufs] for ji in jit_cache])) + if not all_same([d.conn for d in self.devices]): raise GraphException(f"Cross-host remote graph is not supported ({self.devices})") + self.iids = sorted(self.input_replace.values()) + def _process_ji(ji: ExecItem): + match ji.prg: + case CompiledRunner(): + return GraphComputeItem(ji.prg.dev.session, ji.prg._prg.name, ji.prg._prg.datahash, tuple(unwrap(buf)._buf for buf in ji.bufs), + tuple(ji.prg.p.vars), ji.fixedvars, tuple(ji.prg.p.ins), tuple(ji.prg.p.outs), + tuple(ji.prg.p.global_size) if ji.prg.p.global_size is not None else None, + tuple(ji.prg.p.local_size) if ji.prg.p.local_size is not None else None) + case BufferXfer(): + dest, src = ji.bufs[0:2] + assert dest is not None and src is not None, ji + return Transfer(session=cast(RemoteDevice, Device[dest.device]).session, buffer_num=dest._buf, + ssession=cast(RemoteDevice, Device[src.device]).session, sbuffer_num=src._buf) + self.graph_num = next(self.devices[0].graph_num) + self.devices[0].q(GraphAlloc(self.graph_num, tuple(_process_ji(ji) for ji in jit_cache), self.map_rawbufs(rawbufs), var_vals)) + + def __del__(self): + self.devices[0].q(GraphFree(self.graph_num)) + + def map_rawbufs(self, rawbufs:list[Buffer]): + return tuple((cast(RemoteDevice, Device[rawbufs[i].device]).session, rawbufs[i]._buf) for i in self.iids) + + def __call__(self, rawbufs: list[Buffer], var_vals: dict[Variable, int], wait=False): + self.devices[0].q(GraphExec(self.graph_num, self.map_rawbufs(rawbufs), var_vals, wait)) + if wait: return float(self.devices[0].conn.batch_submit()) + +class RemoteMultiGraph(RemoteGraph, MultiGraphRunner): pass diff --git a/tinygrad_repo/tinygrad/runtime/ops_amd.py b/tinygrad_repo/tinygrad/runtime/ops_amd.py index 8619aaa2ac..e3ebb360a9 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_amd.py +++ b/tinygrad_repo/tinygrad/runtime/ops_amd.py @@ -1,167 +1,337 @@ from __future__ import annotations -from typing import Any, Optional, cast -import os, ctypes, ctypes.util, functools, pathlib, mmap, errno, array, contextlib, sys +from typing import Any, cast, ClassVar +import os, ctypes, ctypes.util, struct, hashlib, functools, importlib, mmap, errno, array, contextlib, sys, select, weakref assert sys.platform != 'win32' from dataclasses import dataclass -from tinygrad.runtime.support.hcq import HCQCompiled, HCQAllocator, HCQBuffer, HWQueue, CLikeArgsState, HCQSignal, HCQProgram -from tinygrad.ops import sint -from tinygrad.device import BufferSpec -from tinygrad.helpers import getenv, to_mv, round_up, data64_le, mv_address +from tinygrad.runtime.support.hcq import HCQCompiled, HCQAllocator, HCQBuffer, HWQueue, CLikeArgsState, HCQSignal, HCQProgram, FileIOInterface +from tinygrad.runtime.support.hcq import MMIOInterface +from tinygrad.uop.ops import sint +from tinygrad.device import Compiled, ProfileEvent, BufferSpec, CPUProgram, PROFILE +from tinygrad.helpers import getenv, to_mv, round_up, data64_le, all_same, flatten, DEBUG, OSX from tinygrad.renderer.cstyle import AMDRenderer -from tinygrad.runtime.autogen import kfd, hsa, amd_gpu, libc -from tinygrad.runtime.support.compiler_hip import AMDCompiler +from tinygrad.renderer.llvmir import AMDLLVMRenderer +from tinygrad.runtime.autogen import kfd, hsa, libc, pci, vfio, sqtt +from tinygrad.runtime.autogen.am import am +from tinygrad.runtime.support.compiler_amd import HIPCompiler, AMDLLVMCompiler from tinygrad.runtime.support.elf import elf_loader +from tinygrad.runtime.support.am.amdev import AMDev, AMMapping +from tinygrad.runtime.support.amd import AMDReg, AMDIP, import_module, setup_pci_bars +from tinygrad.runtime.support.usb import ASM24Controller, USBMMIOInterface if getenv("IOCTL"): import extra.hip_gpu_driver.hip_ioctl # noqa: F401 # pylint: disable=unused-import -if getenv("MOCKGPU"): import extra.mockgpu.mockgpu # noqa: F401 # pylint: disable=unused-import - -def is_usable_gpu(gpu_id): - with contextlib.suppress(OSError): return int(pathlib.Path(gpu_id).read_text()) != 0 - return False - -regBIF_BX_PF1_GPU_HDP_FLUSH_REQ, regBIF_BX_PF1_GPU_HDP_FLUSH_DONE = 0x0106, 0x0107 EVENT_INDEX_PARTIAL_FLUSH = 4 # based on a comment in nvd.h +WAIT_REG_MEM_FUNCTION_EQ = 3 # == +WAIT_REG_MEM_FUNCTION_NEQ = 4 # != WAIT_REG_MEM_FUNCTION_GEQ = 5 # >= -COMPUTE_SHADER_EN, FORCE_START_AT_000, CS_W32_EN = (1 << 0), (1 << 2), (1 << 15) - -def gfxreg(reg): return reg + 0x00001260 - amd_gpu.PACKET3_SET_SH_REG_START -def nbioreg(reg): return reg + 0x00000d20 # NBIO_BASE__INST0_SEG2 - class AMDSignal(HCQSignal): - def __init__(self, base_addr:Optional[int]=None, **kwargs): - super().__init__(AMDDevice.signals_pool.pop() if base_addr is None else base_addr, **kwargs, timestamp_divider=100) - - def __del__(self): - if isinstance(self.base_addr, int): AMDDevice.signals_pool.append(self.base_addr) + def __init__(self, base_buf:HCQBuffer|None=None, **kwargs): + super().__init__(base_buf, **kwargs, timestamp_divider=100, dev_t=AMDDevice) def _sleep(self, time_spent_waiting_ms:int): # Resonable to sleep for long workloads (which take more than 2s) and only timeline signals. - if time_spent_waiting_ms > 2000 and self.timeline_for_device is not None: - kfd.AMDKFD_IOC_WAIT_EVENTS(AMDDevice.kfd, events_ptr=self.timeline_for_device.queue_event_arr_ptr, num_events=1, wait_for_all=1, timeout=200) + if time_spent_waiting_ms > 2000 and self.timeline_for_device is not None: self.timeline_for_device.dev_iface.sleep(200) class AMDComputeQueue(HWQueue): + def __init__(self, dev:AMDDevice): + self.dev, self.soc, self.pm4, self.gc, self.nbio = dev, dev.soc, dev.pm4, dev.gc, dev.nbio + super().__init__() + def __del__(self): if self.binded_device is not None: self.binded_device.allocator.free(self.hw_page, self.hw_page.size, BufferSpec(cpu_access=True, nolru=True, uncached=True)) - def pkt3(self, cmd, *vals): self.q(amd_gpu.PACKET3(cmd, len(vals) - 1), *vals) + def pkt3(self, cmd, *vals): self.q(self.pm4.PACKET3(cmd, len(vals) - 1), *vals) + + def wreg(self, reg:AMDReg, *args:sint, **kwargs:int): + if bool(args) == bool(kwargs): raise RuntimeError('One (and only one) of *args or **kwargs must be specified') + if self.pm4.PACKET3_SET_SH_REG_START <= reg.addr < self.pm4.PACKET3_SET_SH_REG_END: + set_packet, set_packet_start = self.pm4.PACKET3_SET_SH_REG, self.pm4.PACKET3_SET_SH_REG_START + elif self.pm4.PACKET3_SET_UCONFIG_REG_START <= reg.addr < self.pm4.PACKET3_SET_UCONFIG_REG_START + 2**16-1: + set_packet, set_packet_start = self.pm4.PACKET3_SET_UCONFIG_REG, self.pm4.PACKET3_SET_UCONFIG_REG_START + else: raise RuntimeError(f'Cannot set {reg.name} ({reg.addr}) via pm4 packet') + self.pkt3(set_packet, reg.addr - set_packet_start, *(args or (reg.encode(**kwargs),))) + + @contextlib.contextmanager + def pred_exec(self, xcc_mask:int): + if self.dev.xccs > 1: + self.pkt3(self.pm4.PACKET3_PRED_EXEC, xcc_mask << 24) + prev_len = len(self._q) + yield + if self.dev.xccs > 1: + self._q[prev_len-1] |= (len(self._q) - prev_len) def wait_reg_mem(self, value, mask=0xffffffff, mem=None, reg_req=None, reg_done=None): - wrm_info_dw = amd_gpu.WAIT_REG_MEM_MEM_SPACE(int(mem is not None)) | amd_gpu.WAIT_REG_MEM_OPERATION(int(mem is None)) \ - | amd_gpu.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_GEQ) | amd_gpu.WAIT_REG_MEM_ENGINE(0) + wrm_info_dw = self.pm4.WAIT_REG_MEM_MEM_SPACE(int(mem is not None)) | self.pm4.WAIT_REG_MEM_OPERATION(int(mem is None)) \ + | self.pm4.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_GEQ) | self.pm4.WAIT_REG_MEM_ENGINE(0) - self.pkt3(amd_gpu.PACKET3_WAIT_REG_MEM, wrm_info_dw, *(data64_le(mem) if mem is not None else (reg_req, reg_done)), value, mask, 4) + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, wrm_info_dw, *(data64_le(mem) if mem is not None else (reg_req, reg_done)), value, mask, 4) def acquire_mem(self, addr=0x0, sz=(1 << 64)-1, gli=1, glm=1, glk=1, glv=1, gl1=1, gl2=1): - cache_flags_dw = amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLI_INV(gli) \ - | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_INV(glm) | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_WB(glm) \ - | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_INV(glk) | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_WB(glk) \ - | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLV_INV(glv) | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL1_INV(gl1) \ - | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_INV(gl2) | amd_gpu.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_WB(gl2) + if self.dev.target >= (10,0,0): + cache_flags_dw = self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLI_INV(gli) \ + | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_INV(glm) | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLM_WB(glm) \ + | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_INV(glk) | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLK_WB(glk) \ + | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GLV_INV(glv) | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL1_INV(gl1) \ + | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_INV(gl2) | self.pm4.PACKET3_ACQUIRE_MEM_GCR_CNTL_GL2_WB(gl2) + + self.pkt3(self.pm4.PACKET3_ACQUIRE_MEM, 0, *data64_le(sz), *data64_le(addr), 0, cache_flags_dw) + else: + cp_coher_cntl = self.pm4.PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_ICACHE_ACTION_ENA(gli) | \ + self.pm4.PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_SH_KCACHE_ACTION_ENA(glk) | \ + self.pm4.PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_ACTION_ENA(gl2) | \ + self.pm4.PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TCL1_ACTION_ENA(gl1) | \ + self.pm4.PACKET3_ACQUIRE_MEM_CP_COHER_CNTL_TC_WB_ACTION_ENA(gl2) + self.pkt3(self.pm4.PACKET3_ACQUIRE_MEM, cp_coher_cntl, *data64_le(sz), *data64_le(addr), 0x0000000A) + + def release_mem(self, address=0x0, value=0, data_sel=0, int_sel=2, ctxid=0, cache_flush=False): + if self.dev.target >= (10,0,0): + cache_flags_dw = 0 if not cache_flush else (self.pm4.PACKET3_RELEASE_MEM_GCR_GLV_INV | self.pm4.PACKET3_RELEASE_MEM_GCR_GL1_INV \ + | self.pm4.PACKET3_RELEASE_MEM_GCR_GL2_INV | self.pm4.PACKET3_RELEASE_MEM_GCR_GLM_WB \ + | self.pm4.PACKET3_RELEASE_MEM_GCR_GLM_INV | self.pm4.PACKET3_RELEASE_MEM_GCR_GL2_WB | self.pm4.PACKET3_RELEASE_MEM_GCR_SEQ) + + event_dw = self.pm4.PACKET3_RELEASE_MEM_EVENT_TYPE(self.pm4.CACHE_FLUSH_AND_INV_TS_EVENT) \ + | self.pm4.PACKET3_RELEASE_MEM_EVENT_INDEX(self.pm4.event_index__mec_release_mem__end_of_pipe) + + memsel_dw = self.pm4.PACKET3_RELEASE_MEM_DATA_SEL(data_sel) | self.pm4.PACKET3_RELEASE_MEM_INT_SEL(int_sel) \ + | self.pm4.PACKET3_RELEASE_MEM_DST_SEL(0) + else: + cache_flags_dw = 0 if not cache_flush else (self.pm4.EOP_TC_WB_ACTION_EN | self.pm4.EOP_TC_NC_ACTION_EN) - self.pkt3(amd_gpu.PACKET3_ACQUIRE_MEM, 0, *data64_le(sz), *data64_le(addr), 0, cache_flags_dw) + event_dw = self.pm4.EVENT_TYPE(self.pm4.CACHE_FLUSH_AND_INV_TS_EVENT) | self.pm4.EVENT_INDEX(self.pm4.event_index__mec_release_mem__end_of_pipe) - def release_mem(self, address, value, data_sel, int_sel, ctxid=0, cache_flush=False): - cache_flags_dw = 0 if not cache_flush else (amd_gpu.PACKET3_RELEASE_MEM_GCR_GLV_INV | amd_gpu.PACKET3_RELEASE_MEM_GCR_GL1_INV \ - | amd_gpu.PACKET3_RELEASE_MEM_GCR_GL2_INV | amd_gpu.PACKET3_RELEASE_MEM_GCR_GLM_WB \ - | amd_gpu.PACKET3_RELEASE_MEM_GCR_GLM_INV | amd_gpu.PACKET3_RELEASE_MEM_GCR_GL2_WB | amd_gpu.PACKET3_RELEASE_MEM_GCR_SEQ) + memsel_dw = self.pm4.DATA_SEL(data_sel) | self.pm4.INT_SEL(int_sel) - event_dw = amd_gpu.PACKET3_RELEASE_MEM_EVENT_TYPE(amd_gpu.CACHE_FLUSH_AND_INV_TS_EVENT) \ - | amd_gpu.PACKET3_RELEASE_MEM_EVENT_INDEX(amd_gpu.event_index__mec_release_mem__end_of_pipe) + ctxid = 0 - memsel_dw = amd_gpu.PACKET3_RELEASE_MEM_DATA_SEL(data_sel) | amd_gpu.PACKET3_RELEASE_MEM_INT_SEL(int_sel) | amd_gpu.PACKET3_RELEASE_MEM_DST_SEL(0) + self.pkt3(self.pm4.PACKET3_RELEASE_MEM, event_dw | cache_flags_dw, memsel_dw, *data64_le(address), *data64_le(value), ctxid) - self.pkt3(amd_gpu.PACKET3_RELEASE_MEM, event_dw | cache_flags_dw, memsel_dw, *data64_le(address), *data64_le(value), ctxid) + def xcc_barrier(self): + if self.dev.xcc_sync is None: return self + assert self.dev.xccs == 8, 'only 8 XCCs supported' + a, b = self.dev.xcc_sync + mem_eq = self.pm4.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_EQ) | self.pm4.WAIT_REG_MEM_MEM_SPACE(1) + self.pkt3(self.pm4.PACKET3_ATOMIC_MEM, self.soc.TC_OP_ATOMIC_ADD_RTN_32, *data64_le(a.value_addr), *data64_le(1), *data64_le(0), 0x10) # a += 1 + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, mem_eq, *data64_le(a.value_addr), 0, 0b111, 0x80) # a == 0 (mod 8) via bitmask + self.pkt3(self.pm4.PACKET3_ATOMIC_MEM, self.soc.TC_OP_ATOMIC_ADD_RTN_32, *data64_le(b.value_addr), *data64_le(1), *data64_le(0), 0x10) # b += 1 + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, mem_eq, *data64_le(b.value_addr), 0, 0b111, 0x80) # b == 0 (mod 8) via bitmask + return self def memory_barrier(self): - self.wait_reg_mem(reg_req=nbioreg(regBIF_BX_PF1_GPU_HDP_FLUSH_REQ), reg_done=nbioreg(regBIF_BX_PF1_GPU_HDP_FLUSH_DONE), value=0xffffffff) + pf = '' if self.nbio.version[0] == 2 else '0' if self.nbio.version[:2] != (7, 11) else '1' + self.wait_reg_mem(reg_req=getattr(self.nbio, f'regBIF_BX_PF{pf}_GPU_HDP_FLUSH_REQ').addr, + reg_done=getattr(self.nbio, f'regBIF_BX_PF{pf}_GPU_HDP_FLUSH_DONE').addr, value=0xffffffff) self.acquire_mem() return self + def xcc_config(self): + self.wreg(self.gc.regCOMPUTE_TG_CHUNK_SIZE, 1) + for xcc_id in range(self.dev.xccs): + with self.pred_exec(xcc_mask=1 << xcc_id): + self.wreg(self.dev.regCOMPUTE_CURRENT_LOGIC_XCC_ID, xcc_id) + return self + + def spi_config(self, tracing:bool): + self.wreg(self.gc.regSPI_CONFIG_CNTL, ps_pkr_priority_cntl=3, exp_priority_order=3, gpr_write_priority=0x2c688, + enable_sqg_bop_events=int(tracing), enable_sqg_top_events=int(tracing)) + + ### SQTT ### + + def sqtt_userdata(self, data, *extra_dwords): + data_ints = [x[0] for x in struct.iter_unpack('>12) + self.wreg(self.gc.regSQ_THREAD_TRACE_BUF0_SIZE, base_hi=buf0_hi, size=buf0s[se].size>>12) + self.wreg(self.gc.regSQ_THREAD_TRACE_BUF0_BASE, base_lo=buf0_lo) + # NOTE: SQTT can only trace instructions on one simd per se, this selects first simd in first wgp in first sa. + # For RGP to display instruction trace it has to see it on first SE. Howerver ACE/MEC/whatever does the dispatching starting with second se, + # and on amdgpu/non-AM it also does weird things with dispatch order inside se: around 7 times out of 10 it starts from the last cu, but + # sometimes not, especially if the kernel has more than one wavefront which means that kernels with small global size might get unlucky and + # be dispatched on something else and not be seen in instruction tracing tab. You can force the wavefronts of a kernel to be dispatched on the + # CUs you want to by disabling other CUs via bits in regCOMPUTE_STATIC_THREAD_MGMT_SE and trace even kernels that only have one wavefront. + self.wreg(self.gc.regSQ_THREAD_TRACE_MASK, wtype_include=self.soc.SQ_TT_WTYPE_INCLUDE_CS_BIT, simd_sel=0, wgp_sel=0, sa_sel=0) + REG_INCLUDE = self.soc.SQ_TT_TOKEN_MASK_SQDEC_BIT | self.soc.SQ_TT_TOKEN_MASK_SHDEC_BIT | self.soc.SQ_TT_TOKEN_MASK_GFXUDEC_BIT | \ + self.soc.SQ_TT_TOKEN_MASK_COMP_BIT | self.soc.SQ_TT_TOKEN_MASK_CONTEXT_BIT | self.soc.SQ_TT_TOKEN_MASK_CONTEXT_BIT + TOKEN_EXCLUDE = 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_PERF_SHIFT + if not (se_mask >> se) & 0b1: + TOKEN_EXCLUDE |= 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_VMEMEXEC_SHIFT | 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_ALUEXEC_SHIFT | \ + 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_VALUINST_SHIFT | 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_IMMEDIATE_SHIFT | \ + 1 << self.soc.SQ_TT_TOKEN_EXCLUDE_INST_SHIFT + self.wreg(self.gc.regSQ_THREAD_TRACE_TOKEN_MASK, reg_include=REG_INCLUDE, token_exclude=TOKEN_EXCLUDE, bop_events_token_include=1) + # Enable SQTT + self.sqtt_config(tracing=True) + # Restore global broadcasting + self.wreg(self.gc.regGRBM_GFX_INDEX, se_broadcast_writes=1, sa_broadcast_writes=1, instance_broadcast_writes=1) + self.wreg(self.gc.regCOMPUTE_THREAD_TRACE_ENABLE, 1) + self.memory_barrier() + return self + + # Magic values from src/amd/common/ac_sqtt.c:ac_sqtt_emit_stop and src/amd/common/ac_sqtt.c:ac_sqtt_emit_wait + def sqtt_stop(self, ses: int, wptrs: HCQBuffer): + self.memory_barrier() + # Start shutting everything down + self.wreg(self.gc.regCOMPUTE_THREAD_TRACE_ENABLE, 0) + self.pkt3(self.pm4.PACKET3_EVENT_WRITE, self.pm4.EVENT_TYPE(self.soc.THREAD_TRACE_FINISH) | self.pm4.EVENT_INDEX(0)) + # For each SE wait for finish to complete and copy regSQ_THREAD_TRACE_WPTR to know where in the buffer trace data ends + for se in range(ses): + self.wreg(self.gc.regGRBM_GFX_INDEX, se_index=se, instance_broadcast_writes=1) + # Wait for FINISH_PENDING==0 + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, self.pm4.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_EQ), + self.gc.regSQ_THREAD_TRACE_STATUS.addr, 0, 0, self.gc.SQ_THREAD_TRACE_STATUS__FINISH_PENDING_MASK, 4) + # Wait for FINISH_DONE!=0 + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, self.pm4.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_NEQ), + self.gc.regSQ_THREAD_TRACE_STATUS.addr, 0, 0, self.gc.SQ_THREAD_TRACE_STATUS__FINISH_DONE_MASK, 4) + # Disable SQTT + self.sqtt_config(tracing=False) + # Wait for BUSY==0 + self.pkt3(self.pm4.PACKET3_WAIT_REG_MEM, self.pm4.WAIT_REG_MEM_FUNCTION(WAIT_REG_MEM_FUNCTION_EQ), + self.gc.regSQ_THREAD_TRACE_STATUS.addr, 0, 0, self.gc.SQ_THREAD_TRACE_STATUS__BUSY_MASK, 4) + # Copy WPTR to memory (src_sel = perf, dst_sel = tc_l2, wr_confirm = True) + self.pkt3(self.pm4.PACKET3_COPY_DATA, 1 << 20 | 2 << 8 | 4, self.gc.regSQ_THREAD_TRACE_WPTR.addr, 0, *data64_le(wptrs.va_addr+(se*4))) + # Restore global broadcasting + self.wreg(self.gc.regGRBM_GFX_INDEX, se_broadcast_writes=1, sa_broadcast_writes=1, instance_broadcast_writes=1) + self.spi_config(tracing=False) + self.memory_barrier() + return self + + def sqtt_prg_marker(self, prg:AMDProgram, global_size:tuple[sint, ...]): + BIND_POINT_COMPUTE = 1 + + self.sqtt_userdata(sqtt.struct_rgp_sqtt_marker_pipeline_bind( + _0=sqtt.union_rgp_sqtt_marker_pipeline_bind_0(_0=sqtt.struct_rgp_sqtt_marker_pipeline_bind_0_0( + identifier=sqtt.RGP_SQTT_MARKER_IDENTIFIER_BIND_PIPELINE, bind_point=BIND_POINT_COMPUTE)), + _1=sqtt.union_rgp_sqtt_marker_pipeline_bind_1(api_pso_hash=data64_le(prg.libhash[0])))) + + self.sqtt_userdata(sqtt.struct_rgp_sqtt_marker_event( + _0=sqtt.union_rgp_sqtt_marker_event_0(_0=sqtt.struct_rgp_sqtt_marker_event_0_0(has_thread_dims=1)), + _2=sqtt.union_rgp_sqtt_marker_event_2(cmd_id=prg.dev.cmd_id)), *global_size) + + prg.dev.cmd_id += 1 + def exec(self, prg:AMDProgram, args_state:CLikeArgsState, global_size:tuple[sint, ...], local_size:tuple[sint, ...]): self.bind_args_state(args_state) self.acquire_mem(gli=0, gl2=0) + user_regs = [] if prg.enable_private_segment_sgpr: + assert self.dev.xccs == 1, "Only architected flat scratch is suppored on multi-xcc" scratch_hilo = data64_le(prg.dev.scratch.va_addr) # sgpr word1 bit31 enables swizzle # sgpr word3 = 0x14 << 12 | 2 << 28 | 2 << 21 | 1 << 23 - user_regs = [scratch_hilo[0], scratch_hilo[1] | 1 << 31, 0xffffffff, 0x20c14000] if prg.enable_private_segment_sgpr else [] - else: user_regs = [] + user_regs = [scratch_hilo[0], scratch_hilo[1] | 1 << 31, 0xffffffff, 0x20c14000] + if prg.enable_dispatch_ptr: - dp = hsa.hsa_kernel_dispatch_packet_t.from_address(dp_addr:=args_state.ptr + prg.kernargs_segment_size) + dp = (dp_t:=hsa.hsa_kernel_dispatch_packet_t).from_address(cast(int, (disp_buf:=args_state.buf.offset(prg.kernargs_segment_size)).va_addr)) + + self.bind_sints(*local_size, mem=disp_buf.cpu_view(), struct_t=dp_t, start_field='workgroup_size_x', fmt='H') + self.bind_sints(*[g*l for g,l in zip(global_size, local_size)], mem=disp_buf.cpu_view(), struct_t=dp_t, start_field='grid_size_x', fmt='I') + dp.group_segment_size, dp.private_segment_size, dp.kernarg_address = prg.group_segment_size, prg.private_segment_size, args_state.buf.va_addr + user_regs += [*data64_le(disp_buf.va_addr)] - self.bind_sints(*local_size, struct=dp, start_field='workgroup_size_x', fmt='H') - self.bind_sints(*[g*l for g,l in zip(global_size, local_size)], struct=dp, start_field='grid_size_x', fmt='I') - dp.group_segment_size, dp.private_segment_size, dp.kernarg_address = prg.group_segment_size, prg.private_segment_size, args_state.ptr - user_regs += [*data64_le(dp_addr)] + user_regs += [*data64_le(args_state.buf.va_addr)] - user_regs += [*data64_le(args_state.ptr)] + if prg.dev.sqtt_enabled: self.sqtt_prg_marker(prg, global_size) + + self.wreg(self.gc.regCOMPUTE_PGM_LO, *data64_le(prg.prog_addr >> 8)) + self.wreg(self.gc.regCOMPUTE_PGM_RSRC1, prg.rsrc1, prg.rsrc2) + self.wreg(self.gc.regCOMPUTE_PGM_RSRC3, prg.rsrc3) + self.wreg(self.gc.regCOMPUTE_TMPRING_SIZE, prg.dev.tmpring_size) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_PGM_LO), *data64_le(prg.prog_addr >> 8)) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_PGM_RSRC1), prg.rsrc1, prg.rsrc2) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_PGM_RSRC3), 0) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_TMPRING_SIZE), prg.dev.tmpring_size) if prg.dev.has_scratch_base_registers: - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_DISPATCH_SCRATCH_BASE_LO), *data64_le(prg.dev.scratch.va_addr >> 8)) - if prg.dev.target < 110000: self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.mmCP_COHER_START_DELAY), 0x20) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_RESTART_X), 0, 0, 0, 0) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_STATIC_THREAD_MGMT_SE0), 0xFFFFFFFF, 0xFFFFFFFF) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_STATIC_THREAD_MGMT_SE2), 0xFFFFFFFF, 0xFFFFFFFF) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_STATIC_THREAD_MGMT_SE4), 0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFFFF) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_USER_DATA_0), *user_regs) - - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_START_X), 0, 0, 0, *local_size, 0, 0) - self.pkt3(amd_gpu.PACKET3_SET_SH_REG, gfxreg(amd_gpu.regCOMPUTE_RESOURCE_LIMITS), 0) - - self.pkt3(amd_gpu.PACKET3_DISPATCH_DIRECT, *global_size, CS_W32_EN | FORCE_START_AT_000 | COMPUTE_SHADER_EN) - self.pkt3(amd_gpu.PACKET3_EVENT_WRITE, amd_gpu.EVENT_TYPE(amd_gpu.CS_PARTIAL_FLUSH) | amd_gpu.EVENT_INDEX(EVENT_INDEX_PARTIAL_FLUSH)) + for xcc_id in range(self.dev.xccs): + with self.pred_exec(xcc_mask=1<> 8)) + + if (10,0,0) <= prg.dev.target < (11,0,0): self.wreg(self.gc.mmCP_COHER_START_DELAY, 0x20) + + self.wreg(self.gc.regCOMPUTE_RESTART_X, 0, 0, 0) + self.wreg(self.gc.regCOMPUTE_STATIC_THREAD_MGMT_SE0, 0xFFFFFFFF, 0xFFFFFFFF) + self.wreg(self.gc.regCOMPUTE_STATIC_THREAD_MGMT_SE2, 0xFFFFFFFF, 0xFFFFFFFF) + if prg.dev.target >= (11,0,0): self.wreg(self.gc.regCOMPUTE_STATIC_THREAD_MGMT_SE4, 0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFFFF) + + self.wreg(self.gc.regCOMPUTE_USER_DATA_0, *user_regs) + self.wreg(self.gc.regCOMPUTE_RESOURCE_LIMITS, 0) + + self.wreg(self.gc.regCOMPUTE_START_X, 0, 0, 0, *local_size, 0, 0) + + gfx10p = {'cs_w32_en': int(prg.wave32)} if prg.dev.target >= (10,0,0) else {} + DISPATCH_INITIATOR = self.gc.regCOMPUTE_DISPATCH_INITIATOR.encode(**gfx10p, force_start_at_000=1, compute_shader_en=1) + self.pkt3(self.pm4.PACKET3_DISPATCH_DIRECT, *global_size, DISPATCH_INITIATOR) + + if prg.dev.sqtt_enabled: self.pkt3(self.pm4.PACKET3_EVENT_WRITE, self.pm4.EVENT_TYPE(self.soc.THREAD_TRACE_MARKER) | self.pm4.EVENT_INDEX(0)) + self.pkt3(self.pm4.PACKET3_EVENT_WRITE, self.pm4.EVENT_TYPE(self.soc.CS_PARTIAL_FLUSH) | self.pm4.EVENT_INDEX(EVENT_INDEX_PARTIAL_FLUSH)) + + if self.dev.xccs > 1: + self.release_mem(cache_flush=True) + self.acquire_mem(gli=0) + self.xcc_barrier() return self def wait(self, signal:AMDSignal, value:sint=0): self.wait_reg_mem(mem=signal.value_addr, value=value, mask=0xffffffff) + if self.dev.xccs > 1: self.xcc_barrier() return self def timestamp(self, signal:AMDSignal): - self.release_mem(signal.timestamp_addr, 0, amd_gpu.data_sel__mec_release_mem__send_gpu_clock_counter, amd_gpu.int_sel__mec_release_mem__none) + with self.pred_exec(xcc_mask=0b1): + self.release_mem(signal.timestamp_addr, 0, self.pm4.data_sel__mec_release_mem__send_gpu_clock_counter, self.pm4.int_sel__mec_release_mem__none) return self def signal(self, signal:AMDSignal, value:sint=0): - # NOTE: this needs an EOP buffer on the queue or it will NULL pointer - self.release_mem(signal.value_addr, value, amd_gpu.data_sel__mec_release_mem__send_32_bit_low, - amd_gpu.int_sel__mec_release_mem__send_interrupt_after_write_confirm, cache_flush=True) - - if (dev:=signal.timeline_for_device) is not None: - self.release_mem(dev.queue_event_mailbox_ptr, dev.queue_event.event_id, amd_gpu.data_sel__mec_release_mem__send_32_bit_low, - amd_gpu.int_sel__mec_release_mem__send_interrupt_after_write_confirm, ctxid=dev.queue_event.event_id) + with self.pred_exec(xcc_mask=0b1): + # NOTE: this needs an EOP buffer on the queue or it will NULL pointer + self.release_mem(signal.value_addr, value, self.pm4.data_sel__mec_release_mem__send_32_bit_low, + self.pm4.int_sel__mec_release_mem__send_interrupt_after_write_confirm, cache_flush=True) + + if (dev:=signal.timeline_for_device) is not None and not dev.is_am(): + self.release_mem(dev.queue_event_mailbox_ptr, dev.queue_event.event_id, self.pm4.data_sel__mec_release_mem__send_32_bit_low, + self.pm4.int_sel__mec_release_mem__send_interrupt_after_write_confirm, ctxid=dev.queue_event.event_id) return self def bind(self, dev:AMDDevice): self.binded_device = dev self.hw_page = dev.allocator.alloc(len(self._q) * 4, BufferSpec(cpu_access=True, nolru=True, uncached=True)) - hw_view = to_mv(self.hw_page.va_addr, self.hw_page.size).cast("I") + hw_view = self.hw_page.cpu_view().view(fmt='I') for i, value in enumerate(self._q): hw_view[i] = value - self.indirect_cmd = [amd_gpu.PACKET3(amd_gpu.PACKET3_INDIRECT_BUFFER, 2), *data64_le(self.hw_page.va_addr), - len(self._q) | amd_gpu.INDIRECT_BUFFER_VALID] + self.indirect_cmd = [self.pm4.PACKET3(self.pm4.PACKET3_INDIRECT_BUFFER, 2), *data64_le(self.hw_page.va_addr), + len(self._q) | self.pm4.INDIRECT_BUFFER_VALID] self._q = hw_view return self def _submit(self, dev:AMDDevice): cmds = self.indirect_cmd if dev == self.binded_device else self._q + # WORKAROUND: PACKET3_PRED_EXEC doesn't work in rings, only in IBs, create a fake IB inside a ring to work around that + if self.dev.xccs > 1 and dev != self.binded_device: + ib_end = ((dev.compute_queue.put_value + 5) % len(dev.compute_queue.ring)) + len(cmds) + ib_pad = len(dev.compute_queue.ring) - (ib_end - len(cmds)) if ib_end > len(dev.compute_queue.ring) else 0 + ib_ptr = dev.compute_queue.ring.addr + ((dev.compute_queue.put_value + 5 + ib_pad) % len(dev.compute_queue.ring)) * 4 + cmds = [self.pm4.PACKET3(self.pm4.PACKET3_INDIRECT_BUFFER, 2), *data64_le(ib_ptr), len(cmds) | self.pm4.INDIRECT_BUFFER_VALID, + self.pm4.PACKET3(self.pm4.PACKET3_NOP, ib_pad + len(cmds) - 1), *((0,) * ib_pad), *cmds] for i, value in enumerate(cmds): dev.compute_queue.ring[(dev.compute_queue.put_value + i) % len(dev.compute_queue.ring)] = value dev.compute_queue.put_value += len(cmds) - dev.compute_queue.write_ptr[0] = dev.compute_queue.put_value - dev.compute_queue.doorbell[0] = dev.compute_queue.put_value + dev.compute_queue.signal_doorbell(dev) -SDMA_MAX_COPY_SIZE = 0x400000 class AMDCopyQueue(HWQueue): - def __init__(self): - self.internal_cmd_sizes = [] + def __init__(self, dev, max_copy_size=0x40000000): + self.dev, self.sdma, self.internal_cmd_sizes, self.max_copy_size = dev, dev.sdma, [], max_copy_size super().__init__() def q(self, *arr): @@ -169,137 +339,228 @@ class AMDCopyQueue(HWQueue): self.internal_cmd_sizes.append(len(arr)) def copy(self, dest:sint, src:sint, copy_size:int): - copied, copy_commands = 0, (copy_size + SDMA_MAX_COPY_SIZE - 1) // SDMA_MAX_COPY_SIZE + copied, copy_commands = 0, (copy_size + self.max_copy_size - 1) // self.max_copy_size for _ in range(copy_commands): - step_copy_size = min(copy_size - copied, SDMA_MAX_COPY_SIZE) + step_copy_size = min(copy_size - copied, self.max_copy_size) - self.q(amd_gpu.SDMA_OP_COPY | amd_gpu.SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(amd_gpu.SDMA_SUBOP_COPY_LINEAR), - amd_gpu.SDMA_PKT_COPY_LINEAR_COUNT_COUNT(step_copy_size - 1), 0, *data64_le(src + copied), *data64_le(dest + copied)) + self.q(self.sdma.SDMA_OP_COPY | self.sdma.SDMA_PKT_COPY_LINEAR_HEADER_SUB_OP(self.sdma.SDMA_SUBOP_COPY_LINEAR), + self.sdma.SDMA_PKT_COPY_LINEAR_COUNT_COUNT(step_copy_size - 1), 0, *data64_le(src + copied), *data64_le(dest + copied)) copied += step_copy_size return self def signal(self, signal:AMDSignal, value:sint=0): - self.q(amd_gpu.SDMA_OP_FENCE | amd_gpu.SDMA_PKT_FENCE_HEADER_MTYPE(3), *data64_le(signal.value_addr), value) + fence_flags = self.sdma.SDMA_PKT_FENCE_HEADER_MTYPE(3) if self.dev.target >= (10,0,0) else 0 + self.q(self.sdma.SDMA_OP_FENCE | fence_flags, *data64_le(signal.value_addr), value) - if (dev:=signal.timeline_for_device) is not None: - self.q(amd_gpu.SDMA_OP_FENCE | amd_gpu.SDMA_PKT_FENCE_HEADER_MTYPE(3), *data64_le(dev.queue_event_mailbox_ptr), dev.queue_event.event_id) - self.q(amd_gpu.SDMA_OP_TRAP, amd_gpu.SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(dev.queue_event.event_id)) + if (dev:=signal.timeline_for_device) is not None and not dev.is_am(): + self.q(self.sdma.SDMA_OP_FENCE | fence_flags, *data64_le(dev.queue_event_mailbox_ptr), dev.queue_event.event_id) + self.q(self.sdma.SDMA_OP_TRAP, self.sdma.SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(dev.queue_event.event_id)) + elif dev is not None and dev.is_am(): self.q(self.sdma.SDMA_OP_TRAP, self.sdma.SDMA_PKT_TRAP_INT_CONTEXT_INT_CONTEXT(0)) return self def wait(self, signal:AMDSignal, value:sint=0): - self.q(amd_gpu.SDMA_OP_POLL_REGMEM | amd_gpu.SDMA_PKT_POLL_REGMEM_HEADER_FUNC(WAIT_REG_MEM_FUNCTION_GEQ) | \ - amd_gpu.SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(1), *data64_le(signal.value_addr), value, 0xffffffff, - amd_gpu.SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(0x04) | amd_gpu.SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(0xfff)) + self.q(self.sdma.SDMA_OP_POLL_REGMEM | self.sdma.SDMA_PKT_POLL_REGMEM_HEADER_FUNC(WAIT_REG_MEM_FUNCTION_GEQ) | \ + self.sdma.SDMA_PKT_POLL_REGMEM_HEADER_MEM_POLL(1), *data64_le(signal.value_addr), value, 0xffffffff, + self.sdma.SDMA_PKT_POLL_REGMEM_DW5_INTERVAL(0x04) | self.sdma.SDMA_PKT_POLL_REGMEM_DW5_RETRY_COUNT(0xfff)) return self def timestamp(self, signal:AMDSignal): - self.q(amd_gpu.SDMA_OP_TIMESTAMP | amd_gpu.SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(amd_gpu.SDMA_SUBOP_TIMESTAMP_GET_GLOBAL), + self.q(self.sdma.SDMA_OP_TIMESTAMP | self.sdma.SDMA_PKT_TIMESTAMP_GET_HEADER_SUB_OP(self.sdma.SDMA_SUBOP_TIMESTAMP_GET_GLOBAL), *data64_le(signal.timestamp_addr)) return self + def bind(self, dev:AMDDevice): + if not getenv("AMD_SDMA_BIND", 0) or not dev.is_am(): return + + self.binded_device = dev + self.hw_page = dev.allocator.alloc((qsz:=round_up(len(self._q), 8)) * 4, BufferSpec(cpu_access=True, nolru=True, uncached=True)) + hw_view = self.hw_page.cpu_view().view(fmt='I') + for i in range(qsz): hw_view[i] = self._q[i] if i < len(self._q) else 0 + + self.indirect_cmd = [self.sdma.SDMA_OP_INDIRECT | self.sdma.SDMA_PKT_INDIRECT_HEADER_VMID(0), *data64_le(self.hw_page.va_addr), qsz, + *data64_le(0)] + self._q, self.cmd_sizes = hw_view, [len(self.indirect_cmd)] + def _submit(self, dev:AMDDevice): - if dev.sdma_queue.put_value - dev.sdma_queue.read_ptr[0] > dev.sdma_queue.ring.nbytes: raise RuntimeError("SDMA queue overrun") + # usb devices run in single-step mode, so they can't overrun the queue. + if not dev.is_usb() and dev.sdma_queue.put_value - dev.sdma_queue.read_ptr > dev.sdma_queue.ring.nbytes: raise RuntimeError("SDMA queue overrun") + + if self.binded_device == dev: + # An IB packet must end on a 8 DW boundary. + add = (8 - (((dev.sdma_queue.put_value % 32) // 4) + len(self.indirect_cmd) % 8)) % 8 + cmds, cmd_sizes = ([0] * add) + self.indirect_cmd, [len(self.indirect_cmd) + add] + + if len(cmds) * 4 >= (dev.sdma_queue.ring.nbytes - dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes): + cmds, cmd_sizes = [0, 0] + self.indirect_cmd, [8] + else: cmds, cmd_sizes = self._q, self.internal_cmd_sizes tail_blit_dword = 0 - for cmdsz in self.internal_cmd_sizes: + for cmdsz in cmd_sizes: if (tail_blit_dword + cmdsz) * 4 >= dev.sdma_queue.ring.nbytes - dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes: break tail_blit_dword += cmdsz + # Force align of submits to hit our usb layer write cache. + if dev.is_usb() and (rem_packet_cnt := len(cmds) - tail_blit_dword) > 0: tail_blit_dword = 0 + start_idx = (dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes) // 4 - dev.sdma_queue.ring[start_idx : start_idx + tail_blit_dword] = array.array('I', self._q[:tail_blit_dword]) + dev.sdma_queue.ring[start_idx : start_idx + tail_blit_dword] = array.array('I', cmds[:tail_blit_dword]) dev.sdma_queue.put_value += tail_blit_dword * 4 - if (rem_packet_cnt := len(self._q) - tail_blit_dword) > 0: + if (rem_packet_cnt := len(cmds) - tail_blit_dword) > 0: zero_fill = dev.sdma_queue.ring.nbytes - dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes - ctypes.memset(mv_address(dev.sdma_queue.ring) + (dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes), 0, zero_fill) + dev.sdma_queue.ring.view(dev.sdma_queue.put_value % dev.sdma_queue.ring.nbytes, zero_fill, fmt='B')[:] = bytes(zero_fill) dev.sdma_queue.put_value += zero_fill - dev.sdma_queue.ring[0:rem_packet_cnt] = array.array('I', self._q[tail_blit_dword:]) + dev.sdma_queue.ring[0:rem_packet_cnt] = array.array('I', cmds[tail_blit_dword:]) dev.sdma_queue.put_value += rem_packet_cnt * 4 - dev.sdma_queue.write_ptr[0] = dev.sdma_queue.put_value - dev.sdma_queue.doorbell[0] = dev.sdma_queue.put_value + dev.sdma_queue.signal_doorbell(dev) class AMDProgram(HCQProgram): def __init__(self, dev:AMDDevice, name:str, lib:bytes): # TODO; this API needs the type signature of the function and global_size/local_size - self.dev: AMDDevice = dev - self.name, self.lib = name, lib - image, sections, _ = elf_loader(self.lib) - self.lib_gpu = self.dev.allocator.alloc(round_up(image.nbytes, 0x1000), BufferSpec(cpu_access=True, nolru=True)) - ctypes.memmove(self.lib_gpu.va_addr, mv_address(image), image.nbytes) + self.dev, self.name, self.lib = dev, name, lib - entry_point = min(sh.header.sh_addr for sh in sections if sh.header.sh_type == libc.SHT_PROGBITS and sh.header.sh_flags & libc.SHF_ALLOC) - self.group_segment_size = image[entry_point:entry_point+4].cast("I")[0] - self.private_segment_size = image[entry_point+4:entry_point+8].cast("I")[0] - self.kernargs_segment_size = image[entry_point+8:entry_point+12].cast("I")[0] + image, sections, _ = elf_loader(self.lib) + self.lib_gpu = self.dev.allocator.alloc(round_up(image.nbytes, 0x1000), buf_spec:=BufferSpec(cpu_access=True, nolru=True)) + self.dev.allocator._copyin(self.lib_gpu, image) + self.dev.synchronize() + rodata_entry = next((sh.header.sh_addr for sh in sections if sh.name == ".rodata"), -1) + text_entry = next((sh.header.sh_addr for sh in sections if sh.name == ".text"), -1) + assert rodata_entry >= 0 and text_entry >= 0, ".text or .rodata section not found" + self.group_segment_size = image[rodata_entry:rodata_entry+4].cast("I")[0] + self.private_segment_size = image[rodata_entry+4:rodata_entry+8].cast("I")[0] + self.kernargs_segment_size = image[rodata_entry+8:rodata_entry+12].cast("I")[0] lds_size = ((self.group_segment_size + 511) // 512) & 0x1FF - if lds_size > (self.dev.properties['lds_size_in_kb'] * 1024) // 512: raise RuntimeError("Too many resources requsted: group_segment_size") - if self.private_segment_size > self.dev.max_private_segment_size: raise RuntimeError("Too many resources requsted: private_segment_size") + if lds_size > (self.dev.dev_iface.props['lds_size_in_kb'] * 1024) // 512: raise RuntimeError("Too many resources requested: group_segment_size") + + # Ensure scratch size + self.dev._ensure_has_local_memory(self.private_segment_size) - code = hsa.amd_kernel_code_t.from_address(self.lib_gpu.va_addr + entry_point) # NOTE: this is wrong, it's not this object - assert code.kernel_code_properties & 0x400 == 0x400 # ENABLE_WAVEFRONT_SIZE32 + # NOTE: this is wrong, it's not this object. pad it, since it might be smaller than the struct + code = hsa.amd_kernel_code_t.from_buffer_copy(bytes(image[rodata_entry:rodata_entry+256]) + b'\x00'*256) + self.wave32: bool = code.kernel_code_properties & 0x400 == 0x400 # Set rsrc1.priv=1 on gfx11 to workaround cwsr. - self.rsrc1: int = code.compute_pgm_rsrc1 | ((1 << 20) if 110000 <= self.dev.target < 120000 else 0) + self.rsrc1: int = code.compute_pgm_rsrc1 | ((1 << 20) if (11,0,0) <= self.dev.target < (12,0,0) else 0) self.rsrc2: int = code.compute_pgm_rsrc2 | (lds_size << 15) - self.prog_addr: int = self.lib_gpu.va_addr + entry_point + code.kernel_code_entry_byte_offset - + self.rsrc3: int = image[rodata_entry+44:rodata_entry+48].cast("I")[0] # NOTE: kernel descriptor, not in amd_kernel_code_t struct + self.prog_addr: int = self.lib_gpu.va_addr + rodata_entry + code.kernel_code_entry_byte_offset + if code.kernel_code_entry_byte_offset == 0: self.prog_addr = self.lib_gpu.va_addr + text_entry # Some programs use hsa_kernel_dispatch_packet_t to read workgroup sizes during execution. # The packet is represented as a pointer and set up in SGPRs. Space for the packet is allocated as part of the kernel arguments. self.enable_dispatch_ptr: int = code.kernel_code_properties & hsa.AMD_KERNEL_CODE_PROPERTIES_ENABLE_SGPR_DISPATCH_PTR self.enable_private_segment_sgpr: int = code.kernel_code_properties & hsa.AMD_KERNEL_CODE_PROPERTIES_ENABLE_SGPR_PRIVATE_SEGMENT_BUFFER additional_alloc_sz = ctypes.sizeof(hsa.hsa_kernel_dispatch_packet_t) if self.enable_dispatch_ptr else 0 - super().__init__(CLikeArgsState, self.dev, self.name, kernargs_alloc_size=self.kernargs_segment_size+additional_alloc_sz) + if dev.sqtt_enabled: self.libhash: tuple[int, int] = struct.unpack(' HCQBuffer: - if options.host: return self.dev._gpu_alloc(size, host=True) - if options.cpu_access and options.uncached: return self.dev._gpu_alloc(size, uncached=True) - return self.dev._gpu_alloc(size, cpu_access=options.cpu_access) + return self.dev.dev_iface.alloc(size, host=options.host, uncached=options.uncached, cpu_access=options.cpu_access) def _free(self, opaque, options:BufferSpec): self.dev.synchronize() - self.dev._gpu_free(opaque) + self.dev.dev_iface.free(opaque) + + def map(self, buf:HCQBuffer): self.dev.dev_iface.map(buf._base if buf._base is not None else buf) - def map(self, buf:HCQBuffer): self.dev._gpu_map(buf._base if buf._base is not None else buf) +MAP_FIXED, MAP_NORESERVE, MAP_LOCKED = 0x10, 0x400, 0 if OSX else 0x2000 -MAP_FIXED, MAP_NORESERVE = 0x10, 0x400 +@dataclass(frozen=True) +class ProfileSQTTEvent(ProfileEvent): device:str; se:int; blob:bytes; itrace:bool # noqa: E702 @dataclass class AMDQueueDesc: - ring: memoryview - read_ptr: memoryview - write_ptr: memoryview - doorbell: memoryview + ring: MMIOInterface + read_ptrs: list[MMIOInterface] + write_ptrs: list[MMIOInterface] + doorbells: list[MMIOInterface] put_value: int = 0 -class AMDDevice(HCQCompiled): - kfd:int = -1 - event_page:Any = None # TODO: fix types in kfd, Optional[kfd.struct_kfd_ioctl_alloc_memory_of_gpu_args] - signals_page:Any = None - signals_pool:list[int] = [] - gpus:list[pathlib.Path] = [] + @property + def read_ptr(self): return min(p[0] for p in self.read_ptrs) - def _gpu_map(self, mem:HCQBuffer): - if self.gpu_id in getattr(mem.meta, "mapped_gpu_ids", []): return - mem.meta.__setattr__("mapped_gpu_ids", getattr(mem.meta, "mapped_gpu_ids", []) + [self.gpu_id]) - c_gpus = (ctypes.c_int32 * len(mem.meta.mapped_gpu_ids))(*mem.meta.mapped_gpu_ids) - stm = kfd.AMDKFD_IOC_MAP_MEMORY_TO_GPU(self.kfd, handle=mem.meta.handle, device_ids_array_ptr=ctypes.addressof(c_gpus), - n_devices=len(mem.meta.mapped_gpu_ids)) - assert stm.n_success == len(mem.meta.mapped_gpu_ids) + @classmethod + def multi(cls, *queues: AMDQueueDesc): + assert all_same([(q.ring.addr, q.put_value) for q in queues]), f"All queues must have the same ring and put_value: {queues}" + return cls(ring=queues[0].ring, put_value=queues[0].put_value, doorbells=flatten(q.doorbells for q in queues), + read_ptrs=flatten(q.read_ptrs for q in queues), write_ptrs=flatten(q.write_ptrs for q in queues)) + + def signal_doorbell(self, dev): + for write_ptr in self.write_ptrs: write_ptr[0] = self.put_value + + # Ensure all prior writes are visible to the GPU. + if CPUProgram.atomic_lib is not None: CPUProgram.atomic_lib.atomic_thread_fence(__ATOMIC_SEQ_CST:=5) + + # Flush hdp if queue is in dev mem. + if dev.is_am() and not dev.is_usb() and getenv("AMD_ALLOC_QUEUE_DEV_MEM", 1): dev.dev_iface.adev.gmc.flush_hdp() + for doorbell in self.doorbells: doorbell[0] = self.put_value + +class KFDIface: + kfd:FileIOInterface|None = None + event_page:HCQBuffer|None = None + gpus:list[FileIOInterface] = [] + + def _is_usable_gpu(self, gpu_id): + with contextlib.suppress(OSError): return int(gpu_id.read()) != 0 + return False + + def __init__(self, dev, device_id): + self.dev = dev - def _gpu_alloc(self, size:int, host=False, uncached=False, cpu_access=False) -> HCQBuffer: + kfd_topo_path = "/sys/devices/virtual/kfd/kfd/topology/nodes" + + # Initialize KFD interface during first run + if KFDIface.kfd is None: + KFDIface.kfd = FileIOInterface("/dev/kfd", os.O_RDWR) + gpus = [g for g in FileIOInterface(kfd_topo_path).listdir() if self._is_usable_gpu(FileIOInterface(f"{kfd_topo_path}/{g}/gpu_id"))] + gpus = sorted(gpus, key=lambda x: int(x.split('/')[-1])) + visible_devices = [int(x) for x in (getenv('VISIBLE_DEVICES', getenv('HIP_VISIBLE_DEVICES', ''))).split(',') if x.strip()] + KFDIface.gpus = [gpus[x] for x in visible_devices] if visible_devices else gpus + + if device_id >= len(KFDIface.gpus): raise RuntimeError(f"No device found for {device_id}. Requesting more devices than the system has?") + + self.gpu_id = int(FileIOInterface(f"{kfd_topo_path}/{KFDIface.gpus[device_id]}/gpu_id").read()) + self.props = {(p:=l.split())[0]: int(p[1]) for l in FileIOInterface(f"{kfd_topo_path}/{KFDIface.gpus[device_id]}/properties").read().splitlines()} + ip_base = f"/sys/class/drm/renderD{self.props['drm_render_minor']}/device/ip_discovery/die/0" + id2ip = {am.GC_HWID: am.GC_HWIP, am.SDMA0_HWID: am.SDMA0_HWIP, am.NBIF_HWID: am.NBIF_HWIP} + self.ip_versions = {id2ip[int(hwid)]:tuple(int(FileIOInterface(f'{ip_base}/{hwid}/0/{part}').read()) for part in ['major', 'minor', 'revision']) + for hwid in FileIOInterface(ip_base).listdir() if hwid.isnumeric() and int(hwid) in id2ip} + self.ip_offsets = {id2ip[int(hwid)]:tuple(int(x, 16) for x in FileIOInterface(f'{ip_base}/{hwid}/0/base_addr').read().splitlines()) + for hwid in FileIOInterface(ip_base).listdir() if hwid.isnumeric() and int(hwid) in id2ip} + self.drm_fd = FileIOInterface(f"/dev/dri/renderD{self.props['drm_render_minor']}", os.O_RDWR) + + kfd.AMDKFD_IOC_ACQUIRE_VM(KFDIface.kfd, drm_fd=self.drm_fd.fd, gpu_id=self.gpu_id) + + # Set these for our device. + if KFDIface.event_page is None: + KFDIface.event_page = self.alloc(0x8000, uncached=True) + kfd.AMDKFD_IOC_CREATE_EVENT(KFDIface.kfd, event_page_offset=KFDIface.event_page.meta.handle) + else: self.map(KFDIface.event_page) + + # Event to wait for queues completion + self.dev.queue_event = kfd.AMDKFD_IOC_CREATE_EVENT(KFDIface.kfd, event_type=kfd.KFD_IOC_EVENT_SIGNAL, auto_reset=1) + self.dev.queue_event_mailbox_ptr = KFDIface.event_page.va_addr + self.dev.queue_event.event_slot_index * 8 + self.queue_event_arr = (kfd.struct_kfd_event_data)(event_id=self.dev.queue_event.event_id) + self.queue_event_arr_ptr = ctypes.addressof(self.queue_event_arr) + + # OS events to collect memory and hardware faults + self.mem_fault_event = kfd.AMDKFD_IOC_CREATE_EVENT(KFDIface.kfd, event_type=kfd.KFD_IOC_EVENT_MEMORY) + self.hw_fault_event = kfd.AMDKFD_IOC_CREATE_EVENT(KFDIface.kfd, event_type=kfd.KFD_IOC_EVENT_HW_EXCEPTION) + + def alloc(self, size:int, host=False, uncached=False, cpu_access=False) -> HCQBuffer: flags = kfd.KFD_IOC_ALLOC_MEM_FLAGS_WRITABLE | kfd.KFD_IOC_ALLOC_MEM_FLAGS_EXECUTABLE | kfd.KFD_IOC_ALLOC_MEM_FLAGS_NO_SUBSTITUTE if uncached: flags |= kfd.KFD_IOC_ALLOC_MEM_FLAGS_COHERENT | kfd.KFD_IOC_ALLOC_MEM_FLAGS_UNCACHED | kfd.KFD_IOC_ALLOC_MEM_FLAGS_GTT @@ -307,135 +568,407 @@ class AMDDevice(HCQCompiled): if cpu_access or host: flags |= kfd.KFD_IOC_ALLOC_MEM_FLAGS_PUBLIC - if host: buf = addr = libc.mmap(0, size, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | mmap.MAP_ANONYMOUS, -1, 0) - else: buf, addr = 0, libc.mmap(0, size, 0, mmap.MAP_PRIVATE | mmap.MAP_ANONYMOUS | MAP_NORESERVE, -1, 0) + if flags & kfd.KFD_IOC_ALLOC_MEM_FLAGS_USERPTR: + buf = addr = FileIOInterface.anon_mmap(0, size, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | mmap.MAP_ANONYMOUS, 0) + else: buf, addr = 0, FileIOInterface.anon_mmap(0, size, 0, mmap.MAP_PRIVATE | mmap.MAP_ANONYMOUS | MAP_NORESERVE, 0) assert addr != 0xffffffffffffffff try: mem = kfd.AMDKFD_IOC_ALLOC_MEMORY_OF_GPU(self.kfd, va_addr=addr, size=size, base=addr, length=size, gpu_id=self.gpu_id, - flags=flags, mmap_offset=buf, cpu_addr=addr) + flags=flags, mmap_offset=buf) except OSError as e: if e.errno == errno.EINVAL and (flags & kfd.KFD_IOC_ALLOC_MEM_FLAGS_VRAM) and cpu_access: raise MemoryError("Cannot allocate host-visible VRAM. Ensure the resizable BAR option is enabled on your system.") from e if e.errno == errno.ENOMEM: raise MemoryError("Cannot allocate memory: no memory is available.") from e raise - if not host: - buf = libc.mmap(mem.va_addr, mem.size, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_FIXED, self.drm_fd, mem.mmap_offset) + if not (flags & kfd.KFD_IOC_ALLOC_MEM_FLAGS_USERPTR): + buf = self.drm_fd.mmap(mem.va_addr, mem.size, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_FIXED, mem.mmap_offset) assert addr == buf == mem.va_addr - self._gpu_map(hcqbuf:=HCQBuffer(mem.va_addr, mem.size, meta=mem)) + self.map(hcqbuf:=HCQBuffer(mem.va_addr, mem.size, meta=mem, view=MMIOInterface(mem.va_addr, mem.size, fmt='B') if cpu_access or host else None)) return hcqbuf - def _gpu_free(self, mem:HCQBuffer): + def free(self, mem): if len(gpus:=getattr(mem.meta, "mapped_gpu_ids", [])): c_gpus = (ctypes.c_int32 * len(gpus))(*gpus) stm = kfd.AMDKFD_IOC_UNMAP_MEMORY_FROM_GPU(self.kfd, handle=mem.meta.handle, device_ids_array_ptr=ctypes.addressof(c_gpus), n_devices=len(gpus)) assert stm.n_success == len(gpus) - libc.munmap(mem.va_addr, mem.size) + if mem.va_addr: FileIOInterface.munmap(mem.va_addr, mem.size) kfd.AMDKFD_IOC_FREE_MEMORY_OF_GPU(self.kfd, handle=mem.meta.handle) - def __init__(self, device:str=""): - if AMDDevice.kfd == -1: - AMDDevice.kfd = os.open("/dev/kfd", os.O_RDWR) - gpus = [g.parent for g in pathlib.Path("/sys/devices/virtual/kfd/kfd/topology/nodes").glob("*/gpu_id") if is_usable_gpu(g)] - gpus = sorted(gpus, key=lambda x: int(x.name.split('/')[-1])) + def map(self, mem): + if self.gpu_id in getattr(mem.meta, "mapped_gpu_ids", []): return + mem.meta.__setattr__("mapped_gpu_ids", getattr(mem.meta, "mapped_gpu_ids", []) + [self.gpu_id]) + c_gpus = (ctypes.c_int32 * len(mem.meta.mapped_gpu_ids))(*mem.meta.mapped_gpu_ids) + stm = kfd.AMDKFD_IOC_MAP_MEMORY_TO_GPU(self.kfd, handle=mem.meta.handle, device_ids_array_ptr=ctypes.addressof(c_gpus), + n_devices=len(mem.meta.mapped_gpu_ids)) + assert stm.n_success == len(mem.meta.mapped_gpu_ids) + + def create_queue(self, queue_type, ring, gart, eop_buffer=None, cwsr_buffer=None, ctl_stack_size=0, ctx_save_restore_size=0, xcc_id=0): + queue = kfd.AMDKFD_IOC_CREATE_QUEUE(KFDIface.kfd, ring_base_address=ring.va_addr, ring_size=ring.size, gpu_id=self.gpu_id, + queue_type=queue_type, queue_percentage=kfd.KFD_MAX_QUEUE_PERCENTAGE|(xcc_id<<8), queue_priority=kfd.KFD_MAX_QUEUE_PRIORITY, + eop_buffer_address=eop_buffer.va_addr if eop_buffer else 0, eop_buffer_size=eop_buffer.size if eop_buffer else 0, ctl_stack_size=ctl_stack_size, + ctx_save_restore_address=cwsr_buffer.va_addr if cwsr_buffer else 0, ctx_save_restore_size=ctx_save_restore_size, + write_pointer_address=gart.va_addr, read_pointer_address=gart.va_addr + 8 * (xcc_id + 1)) + + if not hasattr(self, 'doorbells'): + self.doorbells_base = queue.doorbell_offset & (~0x1fff) # doorbell is two pages + self.doorbells = cast(FileIOInterface, KFDIface.kfd).mmap(0, 0x2000, mmap.PROT_READ|mmap.PROT_WRITE, mmap.MAP_SHARED, self.doorbells_base) + + return AMDQueueDesc(ring=MMIOInterface(ring.va_addr, ring.size, fmt='I'), read_ptrs=[MMIOInterface(queue.read_pointer_address, 8, fmt='Q')], + write_ptrs=[MMIOInterface(queue.write_pointer_address, 8, fmt='Q')], + doorbells=[MMIOInterface(self.doorbells + queue.doorbell_offset - self.doorbells_base, 8, fmt='Q')]) + + def sleep(self, tm:int): kfd.AMDKFD_IOC_WAIT_EVENTS(KFDIface.kfd, events_ptr=self.queue_event_arr_ptr, num_events=1, wait_for_all=1, timeout=tm) + + def on_device_hang(self): + def _collect_str(st): return ' '.join(f'{k[0]}={getattr(st, k[0])}' for k in st._fields_) + + report = [] + for evnt in [self.mem_fault_event, self.hw_fault_event]: + ev = (kfd.struct_kfd_event_data)(event_id=evnt.event_id) + kfd.AMDKFD_IOC_WAIT_EVENTS(KFDIface.kfd, events_ptr=ctypes.addressof(ev), num_events=1, wait_for_all=1) + if evnt == self.mem_fault_event and ev.memory_exception_data.gpu_id: + report += [f"MMU fault: 0x{ev.memory_exception_data.va:X} | {_collect_str(ev.memory_exception_data.failure)}"] + if evnt == self.hw_fault_event and ev.hw_exception_data.gpu_id: report += [f"HW fault: {_collect_str(ev.hw_exception_data)}"] + + raise RuntimeError("\n".join(report)) + +@dataclass +class AMAllocationMeta: owner:AMDDevice; mapped_devs:list[AMDDevice]; mapping:AMMapping; has_cpu_mapping:bool # noqa: E702 + +class PCIIface: + supported_devs:list[int] = [0x744c, 0x7480, 0x7550] + vfio_fd:FileIOInterface|None = None + gpus:list[Any] = [] + + def __init__(self, dev, dev_id): + self.dev = dev + + if first_dev:=len(PCIIface.gpus) == 0: + for pcibus in FileIOInterface("/sys/bus/pci/devices").listdir(): + vendor = int(FileIOInterface(f"/sys/bus/pci/devices/{pcibus}/vendor").read(), 16) + device = int(FileIOInterface(f"/sys/bus/pci/devices/{pcibus}/device").read(), 16) + if vendor == 0x1002 and device in PCIIface.supported_devs: PCIIface.gpus.append(pcibus) + PCIIface.gpus = sorted(PCIIface.gpus) + + # TODO: visible_devices should be handled layer above this? visible_devices = [int(x) for x in (getenv('VISIBLE_DEVICES', getenv('HIP_VISIBLE_DEVICES', ''))).split(',') if x.strip()] - AMDDevice.gpus = [gpus[x] for x in visible_devices] if visible_devices else gpus + PCIIface.gpus = [PCIIface.gpus[x] for x in visible_devices] if visible_devices else PCIIface.gpus + + self.pcibus = PCIIface.gpus[dev_id] + + # Unbind the device from the kernel driver + if FileIOInterface.exists(f"/sys/bus/pci/devices/{self.pcibus}/driver"): + FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/driver/unbind", os.O_WRONLY).write(self.pcibus) + + supported_sizes = int(FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/resource0_resize", os.O_RDONLY).read(), 16) + try: FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/resource0_resize", os.O_RDWR).write(str(supported_sizes.bit_length() - 1)) + except OSError as e: raise RuntimeError(f"Cannot resize BAR: {e}. Ensure the resizable BAR option is enabled on your system.") from e + + # Try to init vfio. Use it if success. + if getenv("VFIO", 0): + try: + if first_dev: + if not FileIOInterface.exists("/sys/module/vfio"): os.system("sudo modprobe vfio-pci disable_idle_d3=1") + + FileIOInterface("/sys/module/vfio/parameters/enable_unsafe_noiommu_mode", os.O_RDWR).write("1") + PCIIface.vfio_fd = FileIOInterface("/dev/vfio/vfio", os.O_RDWR) + vfio.VFIO_CHECK_EXTENSION(PCIIface.vfio_fd, vfio.VFIO_NOIOMMU_IOMMU) + + FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/driver_override", os.O_WRONLY).write("vfio-pci") + FileIOInterface("/sys/bus/pci/drivers_probe", os.O_WRONLY).write(self.pcibus) + + iommu_group = FileIOInterface.readlink(f"/sys/bus/pci/devices/{self.pcibus}/iommu_group").split('/')[-1] + except OSError as e: + if DEBUG >= 1: print(f"am {self.pcibus}: failed to init vfio-pci module (run `sudo modprobe vfio-pci`): {e}.") + PCIIface.vfio_fd = None + + # Init vfio for the device + if PCIIface.vfio_fd is not None: + self.vfio_group = FileIOInterface(f"/dev/vfio/noiommu-{iommu_group}", os.O_RDWR) + vfio.VFIO_GROUP_SET_CONTAINER(self.vfio_group, ctypes.c_int(PCIIface.vfio_fd.fd)) + + if first_dev: vfio.VFIO_SET_IOMMU(PCIIface.vfio_fd, vfio.VFIO_NOIOMMU_IOMMU) + self.vfio_dev = FileIOInterface(fd=vfio.VFIO_GROUP_GET_DEVICE_FD(self.vfio_group, ctypes.create_string_buffer(self.pcibus.encode()))) + + self.irq_fd = FileIOInterface.eventfd(0, 0) + self.irq_poller = select.poll() + self.irq_poller.register(self.irq_fd.fd, select.POLLIN) + + irqs = vfio.struct_vfio_irq_set(index=vfio.VFIO_PCI_MSI_IRQ_INDEX, flags=vfio.VFIO_IRQ_SET_DATA_EVENTFD|vfio.VFIO_IRQ_SET_ACTION_TRIGGER, + argsz=ctypes.sizeof(vfio.struct_vfio_irq_set), count=1, data=(ctypes.c_int * 1)(self.irq_fd.fd)) + vfio.VFIO_DEVICE_SET_IRQS(self.vfio_dev, irqs) + else: FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/enable", os.O_RDWR).write("1") + + self.pagemap = FileIOInterface("/proc/self/pagemap", os.O_RDONLY) + self.cfg_fd = FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/config", os.O_RDWR | os.O_SYNC | os.O_CLOEXEC) + self.bar_fds = {b: FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/resource{b}", os.O_RDWR | os.O_SYNC | os.O_CLOEXEC) for b in [0, 2, 5]} + + bar_info = FileIOInterface(f"/sys/bus/pci/devices/{self.pcibus}/resource", os.O_RDONLY).read().splitlines() + self.bar_info = {j:(int(start,16), int(end,16), int(flgs,16)) for j,(start,end,flgs) in enumerate(l.split() for l in bar_info)} + + self._setup_adev(self.pcibus, self._map_pci_range(0), dbell:=self._map_pci_range(2, fmt='Q'), self._map_pci_range(5, fmt='I')) + self.doorbell_cpu_addr = dbell.addr + + pci_cmd = int.from_bytes(self.cfg_fd.read(2, binary=True, offset=pci.PCI_COMMAND), byteorder='little') | pci.PCI_COMMAND_MASTER + self.cfg_fd.write(pci_cmd.to_bytes(2, byteorder='little'), binary=True, offset=pci.PCI_COMMAND) + + def _setup_adev(self, name, vram:MMIOInterface, doorbell:MMIOInterface, mmio:MMIOInterface, dma_regions:list[tuple[int, MMIOInterface]]|None=None): + self.adev = AMDev(name, vram, doorbell, mmio, dma_regions) + self.ip_versions = self.adev.ip_ver + self.ip_offsets = {hwip: tuple(instances[0]) for hwip,instances in self.adev.regs_offset.items()} + + gfxver = int(f"{self.adev.ip_ver[am.GC_HWIP][0]:02d}{self.adev.ip_ver[am.GC_HWIP][1]:02d}{self.adev.ip_ver[am.GC_HWIP][2]:02d}") + array_count = self.adev.gc_info.gc_num_sa_per_se * self.adev.gc_info.gc_num_se + simd_count = 2 * array_count * (self.adev.gc_info.gc_num_wgp0_per_sa + self.adev.gc_info.gc_num_wgp1_per_sa) + self.props = {'simd_count': 2 * simd_count, 'simd_per_cu': 2, 'array_count': array_count, 'gfx_target_version': gfxver, + 'max_slots_scratch_cu': self.adev.gc_info.gc_max_scratch_slots_per_cu, 'max_waves_per_simd': self.adev.gc_info.gc_max_waves_per_simd, + 'simd_arrays_per_engine': self.adev.gc_info.gc_num_sa_per_se, 'lds_size_in_kb': self.adev.gc_info.gc_lds_size} + + def _map_pci_range(self, bar, off=0, addr=0, size=None, fmt='B'): + fd, sz = self.bar_fds[bar], size or (self.bar_info[bar][1] - self.bar_info[bar][0] + 1) + libc.madvise(loc:=fd.mmap(addr, sz, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | (MAP_FIXED if addr else 0), off), sz, libc.MADV_DONTFORK) + assert loc != 0xffffffffffffffff, f"Failed to mmap {size} bytes at {hex(addr)}" + return MMIOInterface(loc, sz, fmt=fmt) + + def alloc(self, size:int, host=False, uncached=False, cpu_access=False): + if host or (not getenv("AMD_ALLOC_QUEUE_DEV_MEM", 1) and uncached and cpu_access): # host or gtt-like memory. + vaddr = self.adev.mm.alloc_vaddr(size:=round_up(size, mmap.PAGESIZE), align=mmap.PAGESIZE) + va = FileIOInterface.anon_mmap(vaddr, size, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | mmap.MAP_ANONYMOUS | MAP_LOCKED | MAP_FIXED, 0) + assert va != 0xffffffffffffffff, f"Failed to mmap {size} bytes at {hex(vaddr)}" + + # Read pagemap to get the physical address of each page. The pages are locked. + self.pagemap.seek(va // mmap.PAGESIZE * 8) + paddrs = [((x & ((1<<55) - 1)) * mmap.PAGESIZE, mmap.PAGESIZE) for x in array.array('Q', self.pagemap.read(size//mmap.PAGESIZE*8, binary=True))] + am_mapping = self.adev.mm.map_range(vaddr, size, paddrs, system=True, snooped=True, uncached=True) + return HCQBuffer(vaddr, size, meta=AMAllocationMeta(self.dev, [self.dev], am_mapping, has_cpu_mapping=cpu_access), + view=MMIOInterface(am_mapping.va_addr, size, fmt='B')) + + am_mapping = self.adev.mm.valloc(size:=round_up(size, 4 << 10), uncached=uncached, contigous=cpu_access) + if cpu_access: self._map_pci_range(bar=0, off=am_mapping.paddrs[0][0], addr=am_mapping.va_addr, size=am_mapping.size) + return HCQBuffer(am_mapping.va_addr, size, meta=AMAllocationMeta(self.dev, [self.dev], am_mapping, has_cpu_mapping=cpu_access), + view=MMIOInterface(am_mapping.va_addr, size, fmt='B') if cpu_access else None) + + def free(self, mem): + for dev in mem.meta.mapped_devs[1:]: dev.dev_iface.adev.mm.unmap_range(mem.va_addr, mem.size) + if not mem.meta.mapping.system: self.adev.mm.vfree(mem.meta.mapping) + if mem.meta.owner == self.dev and mem.meta.has_cpu_mapping: FileIOInterface.munmap(mem.va_addr, mem.size) + + def map(self, mem): + # Check if the memory is already mapped on this device + if self.dev in mem.meta.mapped_devs: return + mem.meta.mapped_devs.append(self.dev) + + paddrs = [(paddr if mem.meta.mapping.system else (paddr+mem.meta.owner.dev_iface.bar_info[0][0]), size) for paddr,size in mem.meta.mapping.paddrs] + self.adev.mm.map_range(mem.va_addr, mem.size, paddrs, system=True, snooped=mem.meta.mapping.snooped, uncached=mem.meta.mapping.uncached) + + def create_queue(self, queue_type, ring, gart, eop_buffer=None, cwsr_buffer=None, ctl_stack_size=0, ctx_save_restore_size=0, xcc_id=0): + assert cwsr_buffer is None, "no cwsr buffer for am" + + if queue_type == kfd.KFD_IOC_QUEUE_TYPE_SDMA: + self.adev.sdma.setup_ring(ring_addr=ring.va_addr, ring_size=ring.size, rptr_addr=gart.va_addr, wptr_addr=gart.va_addr+0x10, + doorbell=(doorbell_index:=am.AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0), pipe=0, queue=0) + else: + self.adev.gfx.setup_ring(ring_addr=ring.va_addr, ring_size=ring.size, rptr_addr=gart.va_addr, wptr_addr=gart.va_addr+0x10, + eop_addr=eop_buffer.va_addr, eop_size=eop_buffer.size, doorbell=(doorbell_index:=am.AMDGPU_NAVI10_DOORBELL_MEC_RING0), pipe=0, queue=0) - self.device_id = int(device.split(":")[1]) if ":" in device else 0 - if self.device_id >= len(AMDDevice.gpus): raise RuntimeError(f"No device found for {device}. Requesting more devices than the system has?") - - with open(f"{AMDDevice.gpus[self.device_id]}/gpu_id", "r") as f: self.gpu_id = int(f.read()) - with open(f"{AMDDevice.gpus[self.device_id]}/properties", "r") as f: self.properties = {line.split()[0]: int(line.split()[1]) for line in f} - self.drm_fd = os.open(f"/dev/dri/renderD{self.properties['drm_render_minor']}", os.O_RDWR) - self.target = int(self.properties['gfx_target_version']) - self.arch = "gfx%d%x%x" % (self.target // 10000, (self.target // 100) % 100, self.target % 100) - if self.target < 100300 or self.target >= 120000: raise RuntimeError(f"Unsupported arch: {self.arch}") - - kfd.AMDKFD_IOC_ACQUIRE_VM(AMDDevice.kfd, drm_fd=self.drm_fd, gpu_id=self.gpu_id) - - if AMDDevice.event_page is None: - AMDDevice.signals_page = self._gpu_alloc(16 * 65536, uncached=True) - AMDDevice.event_page = self._gpu_alloc(0x8000, uncached=True) - AMDDevice.signals_pool = [self.signals_page.va_addr + off for off in range(0, AMDDevice.signals_page.size, 16)] - kfd.AMDKFD_IOC_CREATE_EVENT(AMDDevice.kfd, event_page_offset=AMDDevice.event_page.meta.handle) + return AMDQueueDesc(ring=MMIOInterface(ring.va_addr, ring.size, fmt='I'), read_ptrs=[MMIOInterface(gart.va_addr, 8, fmt='Q')], + write_ptrs=[MMIOInterface(gart.va_addr+0x10, 8, fmt='Q')], doorbells=[MMIOInterface(self.doorbell_cpu_addr + doorbell_index * 8, 8, fmt='Q')]) + + def sleep(self, timeout): + if PCIIface.vfio_fd is not None and (events_cnt:=len(self.irq_poller.poll(timeout))): + self.irq_fd.read(8 * events_cnt) + self.adev.ih.interrupt_handler() + + def on_device_hang(self): + for d in self.dev.devices: d.dev_iface.adev.gmc.on_interrupt() + raise RuntimeError("Device hang detected") + + def device_fini(self): self.adev.fini() + +class USBIface(PCIIface): + def __init__(self, dev, dev_id): + self.dev = dev + self.usb = ASM24Controller() + self.bars = setup_pci_bars(self.usb, gpu_bus=4, mem_base=0x10000000, pref_mem_base=(32 << 30)) + + self._setup_adev(f"usb:{dev_id}", USBMMIOInterface(self.usb, *self.bars[0], fmt='B'), USBMMIOInterface(self.usb, *self.bars[2], fmt='Q'), + USBMMIOInterface(self.usb, *self.bars[5], fmt='I'), dma_regions=[(0x200000, self._dma_view(0xf000, 0x80000))]) + self.usb._pci_cacheable += [self.bars[2]] # doorbell region is cacheable + + # special regions + self.copy_bufs = [self._dma_region(ctrl_addr=0xf000, sys_addr=0x200000, size=0x80000)] + self.sys_buf, self.sys_next_off = self._dma_region(ctrl_addr=0xa000, sys_addr=0x820000, size=0x1000), 0x800 + + def _dma_view(self, ctrl_addr, size): return USBMMIOInterface(self.usb, ctrl_addr, size, fmt='B', pcimem=False) + def _dma_region(self, ctrl_addr, sys_addr, size): + region = self.adev.mm.map_range(vaddr:=self.adev.mm.alloc_vaddr(size=size), size, [(sys_addr, size)], system=True, snooped=False, uncached=True) + return HCQBuffer(vaddr, size, meta=AMAllocationMeta(self.dev, [self.dev], region, has_cpu_mapping=False), view=self._dma_view(ctrl_addr, size)) + + def alloc(self, size:int, host=False, uncached=False, cpu_access=False): + if (host or (uncached and cpu_access)) and self.sys_next_off + size < self.sys_buf.size: + self.sys_next_off += size + return self.sys_buf.offset(self.sys_next_off - size, size) + + am_mapping = self.adev.mm.valloc(size:=round_up(size, 4 << 10), uncached=uncached, contigous=cpu_access) + return HCQBuffer(am_mapping.va_addr, size, meta=AMAllocationMeta(self.dev, [self.dev], am_mapping, has_cpu_mapping=False), + view=USBMMIOInterface(self.usb, self.bars[0][0] + am_mapping.paddrs[0][0], size, fmt='B') if cpu_access else None) + + def create_queue(self, queue_type, ring, gart, eop_buffer=None, cwsr_buffer=None, ctl_stack_size=0, ctx_save_restore_size=0, xcc_id=0): + if queue_type == kfd.KFD_IOC_QUEUE_TYPE_SDMA: + self.adev.sdma.setup_ring(ring_addr=ring.va_addr, ring_size=ring.size, rptr_addr=gart.va_addr, wptr_addr=gart.va_addr+0x10, + doorbell=(doorbell_index:=am.AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0), pipe=0, queue=0) else: - self._gpu_map(AMDDevice.signals_page) - self._gpu_map(AMDDevice.event_page) + self.adev.gfx.setup_ring(ring_addr=ring.va_addr, ring_size=ring.size, rptr_addr=gart.va_addr, wptr_addr=gart.va_addr+0x10, + eop_addr=eop_buffer.va_addr, eop_size=eop_buffer.size, doorbell=(doorbell_index:=am.AMDGPU_NAVI10_DOORBELL_MEC_RING0), pipe=0, queue=0) + self.usb._pci_cacheable += [(ring.cpu_view().addr, ring.size)] - # Scratch setup - max_cu_id = self.properties['simd_count'] // self.properties['simd_per_cu'] - 1 - max_wave_id = self.properties['max_waves_per_simd'] * self.properties['simd_per_cu'] - 1 - self.max_private_segment_size = 4096 - # =gfx11 requires 256 - wave_scratch_len = round_up(((max_wave_id + 1) * self.max_private_segment_size), 256 if self.target >= 110000 else 1024) - self.scratch_len = (max_cu_id + 1) * self.properties['max_slots_scratch_cu'] * wave_scratch_len - self.scratch = self._gpu_alloc(self.scratch_len) - self.has_scratch_base_registers = self.target >= 110000 - engines = self.properties['array_count'] // self.properties['simd_arrays_per_engine'] - waves = wave_scratch_len // (256 if self.target >= 110000 else 1024) - # >=gfx11 wavesize is per SE - wavesize = self.scratch_len // ((wave_scratch_len * engines) if self.target >= 110000 else wave_scratch_len) - self.tmpring_size = waves << 12 | wavesize + return AMDQueueDesc(ring=ring.cpu_view().view(fmt='I'), doorbells=[self.adev.doorbell64.view(doorbell_index * 8, 8, fmt='Q')], + read_ptrs=[gart.cpu_view().view(size=8, fmt='Q')], write_ptrs=[gart.cpu_view().view(offset=0x10, size=8, fmt='Q')]) + +class AMDDevice(HCQCompiled): + devices: ClassVar[list[HCQCompiled]] = [] + signal_pages: ClassVar[list[HCQBuffer]] = [] + signal_pool: ClassVar[list[HCQBuffer]] = [] + + def is_am(self) -> bool: return isinstance(self.dev_iface, (PCIIface, USBIface)) + def is_usb(self) -> bool: return isinstance(self.dev_iface, USBIface) + + def _select_iface(self): + if len(nm:=getenv("AMD_IFACE", "")) > 0: return getattr(sys.modules[__name__], f"{nm.upper()}Iface")(self, self.device_id) + + errs:str = "" + for iface_t in (KFDIface, PCIIface, USBIface): + try: return iface_t(self, self.device_id) + except (RuntimeError, FileNotFoundError, BlockingIOError, IndexError) as e: errs += f"\n{iface_t.__name__}: {type(e).__name__}: {e}" + raise RuntimeError(f"Cannot find a usable interface for AMD:{self.device_id}:{errs}") + + def __init__(self, device:str=""): + self.device_id = int(device.split(":")[1]) if ":" in device else 0 + self.dev_iface = self._select_iface() + self.target:tuple[int, ...] = ((trgt:=self.dev_iface.props['gfx_target_version']) // 10000, (trgt // 100) % 100, trgt % 100) + self.arch = "gfx%d%x%x" % self.target + if self.target < (9,4,2) or self.target >= (13,0,0): raise RuntimeError(f"Unsupported arch: {self.arch}") + if DEBUG >= 1: print(f"AMDDevice: opening {self.device_id} with target {self.target} arch {self.arch}") + + self.max_cu_id = self.dev_iface.props['simd_count'] // self.dev_iface.props['simd_per_cu'] // self.dev_iface.props.get('num_xcc', 1) - 1 + self.max_wave_id = (self.dev_iface.props['max_waves_per_simd'] * self.dev_iface.props['simd_per_cu'] - 1) if self.target >= (10,1,0) else \ + (min((self.max_cu_id+1)*40, self.dev_iface.props['array_count'] // self.dev_iface.props['simd_arrays_per_engine'] * 512) - 1) + self.xccs = self.dev_iface.props.get('num_xcc', 1) if getenv("XCCS", 1) else 1 + self.has_scratch_base_registers = self.target >= (11,0,0) or self.target == (9,4,2) # this is what llvm refers to as "architected flat scratch" # https://gitlab.freedesktop.org/agd5f/linux/-/blob/a1fc9f584c4aaf8bc1ebfa459fc57a3f26a290d8/drivers/gpu/drm/amd/amdkfd/kfd_queue.c#L391 sgrp_size_per_cu, lds_size_per_cu, hwreg_size_per_cu = 0x4000, 0x10000, 0x1000 - vgpr_size_per_cu = 0x60000 if self.target in {110000, 110001, 120000, 120001} else 0x40000 - wg_data_size = round_up((vgpr_size_per_cu + sgrp_size_per_cu + lds_size_per_cu + hwreg_size_per_cu) * (max_cu_id + 1), mmap.PAGESIZE) - ctl_stack_size = round_up(12 * (max_cu_id + 1) * (max_wave_id + 1) + 8 + 40, mmap.PAGESIZE) - self.debug_memory_size = round_up((max_cu_id + 1) * (max_wave_id + 1) * 32, 64) - - self.compute_queue = self._alloc_queue(kfd.KFD_IOC_QUEUE_TYPE_COMPUTE, 0x100000, ctx_save_restore_size=wg_data_size + ctl_stack_size, - eop_buffer_size=0x1000, ctl_stack_size=ctl_stack_size) - self.sdma_queue = self._alloc_queue(kfd.KFD_IOC_QUEUE_TYPE_SDMA, 0x100000) - - self.queue_event = kfd.AMDKFD_IOC_CREATE_EVENT(AMDDevice.kfd, event_type=kfd.KFD_IOC_EVENT_SIGNAL, auto_reset=1) - self.queue_event_mailbox_ptr = AMDDevice.event_page.va_addr + self.queue_event.event_slot_index * 8 - self.queue_event_arr = (kfd.struct_kfd_event_data)(event_id=self.queue_event.event_id) - self.queue_event_arr_ptr = ctypes.addressof(self.queue_event_arr) + vgpr_size_per_cu = 0x60000 if self.target in {(11,0,0), (11,0,1), (12,0,0), (12,0,1)} else \ + 0x80000 if (self.target[:2]) == (9,4) or self.target in {(9,0,8), (9,0,10)} else 0x40000 + wg_data_size = round_up((vgpr_size_per_cu + sgrp_size_per_cu + lds_size_per_cu + hwreg_size_per_cu) * (self.max_cu_id + 1), mmap.PAGESIZE) + ctl_stack_size = round_up(12 * (self.max_cu_id + 1) * (self.max_wave_id + 1) + 8 + 40, mmap.PAGESIZE) if self.target >= (10,1,0) else \ + round_up((self.max_wave_id + 1) * 8 + 8 + 40, mmap.PAGESIZE) + debug_memory_size = round_up((self.max_cu_id + 1 if self.target >= (10,1,0) else 1) * (self.max_wave_id + 1) * 32, 64) + if self.target[0] == 10: ctl_stack_size = min(ctl_stack_size, 0x7000) - self.mem_fault_event = kfd.AMDKFD_IOC_CREATE_EVENT(AMDDevice.kfd, event_type=kfd.KFD_IOC_EVENT_MEMORY) - self.hw_fault_event = kfd.AMDKFD_IOC_CREATE_EVENT(AMDDevice.kfd, event_type=kfd.KFD_IOC_EVENT_HW_EXCEPTION) + self.soc = importlib.import_module(f"tinygrad.runtime.autogen.am.{({9: 'vega10', 10: 'navi10', 11: 'soc21', 12: 'soc24'}[self.target[0]])}") + self.pm4 = importlib.import_module(f"tinygrad.runtime.autogen.am.pm4_{'nv' if self.target[0] >= 10 else 'soc15'}") + self.sdma = import_module('sdma', min(self.dev_iface.ip_versions[am.SDMA0_HWIP], (6, 0, 0))) + self.gc = AMDIP('gc', self.dev_iface.ip_versions[am.GC_HWIP], self.dev_iface.ip_offsets[am.GC_HWIP]) - super().__init__(device, AMDAllocator(self), AMDRenderer(), AMDCompiler(self.arch), functools.partial(AMDProgram, self), - AMDSignal, AMDComputeQueue, AMDCopyQueue) + # Define the regCOMPUTE_CURRENT_LOGIC_XCC_ID register, which is missing from the asic_regs files. + if self.target[:2] == (9,4): self.regCOMPUTE_CURRENT_LOGIC_XCC_ID = AMDReg("regCOMPUTE_CURRENT_LOGIC_XCC_ID", 0xe25, 0, {}, self.gc.bases) - def _alloc_queue(self, queue_type, ring_size, ctx_save_restore_size=None, eop_buffer_size=None, ctl_stack_size=0) -> AMDQueueDesc: - gart = self._gpu_alloc(0x1000, uncached=True) - ring = self._gpu_alloc(ring_size, uncached=True) - cwsr_ctx = self._gpu_alloc(round_up(ctx_save_restore_size + self.debug_memory_size, mmap.PAGESIZE)) if ctx_save_restore_size else None - eop_buffer = self._gpu_alloc(eop_buffer_size) if eop_buffer_size else None - queue = kfd.AMDKFD_IOC_CREATE_QUEUE(AMDDevice.kfd, ring_base_address=ring.va_addr, ring_size=ring.size, gpu_id=self.gpu_id, - queue_type=queue_type, queue_percentage=kfd.KFD_MAX_QUEUE_PERCENTAGE, queue_priority=kfd.KFD_MAX_QUEUE_PRIORITY, - eop_buffer_address=eop_buffer.va_addr if eop_buffer else 0, eop_buffer_size=eop_buffer.size if eop_buffer else 0, ctl_stack_size=ctl_stack_size, - ctx_save_restore_address=cwsr_ctx.va_addr if cwsr_ctx else 0, ctx_save_restore_size=ctx_save_restore_size if cwsr_ctx else 0, - write_pointer_address=gart.va_addr, read_pointer_address=gart.va_addr + 8) + nbio_name = 'nbio' if self.target[0] < 12 else 'nbif' + nbio_pad = (0,) if self.target[0] == 9 else () + self.nbio = AMDIP(nbio_name, self.dev_iface.ip_versions[am.NBIF_HWIP], nbio_pad+self.dev_iface.ip_offsets[am.NBIF_HWIP]) - if not hasattr(self, 'doorbells'): - self.doorbells_base = queue.doorbell_offset & (~0x1fff) # doorbell is two pages - self.doorbells = libc.mmap(0, 0x2000, mmap.PROT_READ|mmap.PROT_WRITE, mmap.MAP_SHARED, AMDDevice.kfd, self.doorbells_base) + self.compute_queue = self.create_queue(kfd.KFD_IOC_QUEUE_TYPE_COMPUTE, 0x2000 if self.is_usb() else 0x800000, eop_buffer_size=0x1000, + ctx_save_restore_size=0 if self.is_am() else wg_data_size + ctl_stack_size, ctl_stack_size=ctl_stack_size, debug_memory_size=debug_memory_size) - return AMDQueueDesc(ring=to_mv(cast(int, ring.va_addr), ring_size).cast("I"), - read_ptr=to_mv(queue.read_pointer_address, 8).cast("Q"), write_ptr=to_mv(queue.write_pointer_address, 8).cast("Q"), - doorbell=to_mv(self.doorbells + queue.doorbell_offset - self.doorbells_base, 8).cast("Q")) + max_copy_size = 0x40000000 if self.dev_iface.ip_versions[am.SDMA0_HWIP][0] >= 5 else 0x400000 + self.sdma_queue = self.create_queue(kfd.KFD_IOC_QUEUE_TYPE_SDMA, 0x200 if self.is_usb() else 0x800000) - def invalidate_caches(self): - AMDComputeQueue().memory_barrier().signal(self.timeline_signal, self.timeline_value).submit(self) - self.timeline_value += 1 - self.synchronize() + super().__init__(device, AMDAllocator(self), AMDLLVMRenderer(self.arch) if getenv("AMD_LLVM", 0) else AMDRenderer(self.arch), + AMDLLVMCompiler(self.arch) if getenv("AMD_LLVM", 0) else HIPCompiler(self.arch), functools.partial(AMDProgram, self), + AMDSignal, functools.partial(AMDComputeQueue, self), functools.partial(AMDCopyQueue, self, max_copy_size=max_copy_size), + kernargs_size=(8 << 10) if self.is_usb() else (16 << 20), sigalloc_size=0x100 if self.is_usb() else 0x1000) - def on_device_hang(self): - report = [] + # Scratch setup + self.max_private_segment_size = 0 + self._ensure_has_local_memory(128) # set default scratch size to 128 bytes per thread + + # XCC setup + self.xcc_sync: tuple[AMDSignal, AMDSignal]|None = None + if self.xccs > 1: + self.xcc_sync_area = self.allocator.alloc(0x1000, BufferSpec(nolru=True, cpu_access=True)) + self.xcc_sync = (AMDSignal(base_buf=self.xcc_sync_area), AMDSignal(base_buf=self.xcc_sync_area.offset(256))) + AMDComputeQueue(self).xcc_config().submit(self) + + # SQTT is disabled by default because of runtime overhead and big file sizes (~200mb to Tensor.full() two 4096x4096 tensors and matmul them) + self.sqtt_enabled = PROFILE and bool(getenv("SQTT", 0)) + if self.sqtt_enabled: + if self.arch != 'gfx1100': raise RuntimeError('SQ Thread Tracing is only supported on 7900XTX') + if not self.is_am() and (ppfeaturemask:=int(FileIOInterface('/sys/module/amdgpu/parameters/ppfeaturemask', os.O_RDONLY).read(), 16))&0x8000: + raise RuntimeError("SQTT can't be enabled because of hardware bug, to workaround either use AMD_IFACE=PCI or add " + f"ppfeaturemask={(ppfeaturemask&~0x8000):#x} (current {ppfeaturemask=:#x} & ~PP_GFXOFF_MASK) to amdgpu module parameters\n" + "For more information read https://github.com/tinygrad/tinygrad/blob/master/extra/sqtt/README.md") + SQTT_BUFFER_SIZE = getenv("SQTT_BUFFER_SIZE", 256) # in mb, per shader engine + SQTT_NUM = self.dev_iface.props['array_count'] // self.dev_iface.props['simd_arrays_per_engine'] + self.sqtt_buffers = [self.allocator.alloc(SQTT_BUFFER_SIZE*1024*1024, BufferSpec(cpu_access=True, nolru=True)) for _ in range(SQTT_NUM)] + self.sqtt_itrace_se_mask = getenv("SQTT_ITRACE_SE_MASK", 2) # -1 enable all, 0 disable all, >0 bitmask for where to enable instruction tracing + self.cmd_id = 0 + AMDComputeQueue(self).sqtt_start(self.sqtt_buffers, self.sqtt_itrace_se_mask).submit(self) + + def create_queue(self, queue_type, ring_size, ctx_save_restore_size=0, eop_buffer_size=0, ctl_stack_size=0, debug_memory_size=0): + ring = self.dev_iface.alloc(ring_size, uncached=True, cpu_access=True) + gart = self.dev_iface.alloc(0x100, uncached=True, cpu_access=True) + + cwsr_buffer_size = round_up((ctx_save_restore_size + debug_memory_size) * self.dev_iface.props.get('num_xcc', 1), mmap.PAGESIZE) + cwsr_buffer = self.dev_iface.alloc(cwsr_buffer_size) if ctx_save_restore_size else None + eop_buffer = self.dev_iface.alloc(eop_buffer_size) if eop_buffer_size else None + + return AMDQueueDesc.multi(*(self.dev_iface.create_queue(queue_type, ring, gart, eop_buffer=eop_buffer, cwsr_buffer=cwsr_buffer, xcc_id=xcc_id, + ctx_save_restore_size=ctx_save_restore_size, ctl_stack_size=ctl_stack_size) + for xcc_id in range(self.xccs if queue_type == kfd.KFD_IOC_QUEUE_TYPE_COMPUTE else 1))) + + def _ensure_has_local_memory(self, required): + if self.max_private_segment_size >= required: return - ev = (kfd.struct_kfd_event_data)(event_id=self.mem_fault_event.event_id) - kfd.AMDKFD_IOC_WAIT_EVENTS(AMDDevice.kfd, events_ptr=ctypes.addressof(ev), num_events=1, wait_for_all=1) - if ev.memory_exception_data.gpu_id: - pfstatus = ' '.join(f'{k[0]}={getattr(ev.memory_exception_data.failure, k[0])}' for k in ev.memory_exception_data.failure._fields_) - report += [f"MMU fault: 0x{ev.memory_exception_data.va:X} | {pfstatus}"] + # =gfx11 requires 256 + wave_scratch_len = round_up(((self.max_wave_id + 1) * required), 256 if self.target >= (11,0,0) else 1024) + + scratch_size = (self.max_cu_id+1)*self.dev_iface.props['max_slots_scratch_cu']*wave_scratch_len # per xcc + self.scratch, ok = self._realloc(getattr(self, 'scratch', None), scratch_size*self.xccs) + if ok: + engines = self.dev_iface.props['array_count'] // self.dev_iface.props['simd_arrays_per_engine'] + waves = wave_scratch_len // (256 if self.target >= (11,0,0) else 1024) + # >=gfx11 wavesize is per SE + wavesize = scratch_size // ((wave_scratch_len * engines) if self.target >= (11,0,0) else wave_scratch_len) + self.tmpring_size = waves << 12 | wavesize + self.max_private_segment_size = required - ev = (kfd.struct_kfd_event_data)(event_id=self.hw_fault_event.event_id) - kfd.AMDKFD_IOC_WAIT_EVENTS(AMDDevice.kfd, events_ptr=ctypes.addressof(ev), num_events=1, wait_for_all=1) - if ev.hw_exception_data.gpu_id: - report += [f"HW fault: {' '.join(f'{k[0]}={getattr(ev.hw_exception_data, k[0])}' for k in ev.hw_exception_data._fields_)}"] + def invalidate_caches(self): + AMDComputeQueue(self).memory_barrier().signal(self.timeline_signal, self.next_timeline()).submit(self) + self.synchronize() - raise RuntimeError("\n".join(report)) + def on_device_hang(self): self.dev_iface.on_device_hang() + + def _at_profile_finalize(self): + if self.sqtt_enabled: + wptrs_buf = self.allocator.alloc(round_up(len(self.sqtt_buffers), 0x1000), BufferSpec(cpu_access=True, nolru=True)) + wptrs = to_mv(wptrs_buf.va_addr, wptrs_buf.size) + AMDComputeQueue(self).sqtt_stop(len(self.sqtt_buffers), wptrs_buf).signal(self.timeline_signal, self.next_timeline()).submit(self) + self.synchronize() + if DEBUG>=2: print('Saving SQTT in profile...') + for i,buf0 in enumerate(self.sqtt_buffers): + wptr = ((struct.unpack('=2: print(f'Se {i} blob size {wptr:#x}') + assert wptr >= 0 and wptr <= buf0.size, f"{wptr} > {buf0.size}, should never happen" + # When sqtt buffer overflows, wptr stops at the last dword + if wptr >= buf0.size-32: print(f"WARNING: SQTT BUFFER IS FULL (SE {i})! INCREASE SQTT BUFFER SIZE WITH SQTT_BUFFER_SIZE=X (in MB)") + self.allocator._copyout(sqtt_buf:=memoryview(bytearray(wptr)), buf0) + Compiled.profile_events += [ProfileSQTTEvent(self.device, i, bytes(sqtt_buf), bool((self.sqtt_itrace_se_mask >> i) & 0b1))] + super()._at_profile_finalize() + + def finalize(self): + try: self.synchronize() # Try to finalize device in any case. + except RuntimeError as e: print(f"{self.device} synchronization failed before finalizing: {e}") + if hasattr(self.dev_iface, 'device_fini'): self.dev_iface.device_fini() diff --git a/tinygrad_repo/tinygrad/runtime/ops_clang.py b/tinygrad_repo/tinygrad/runtime/ops_clang.py deleted file mode 100644 index aef1e195ab..0000000000 --- a/tinygrad_repo/tinygrad/runtime/ops_clang.py +++ /dev/null @@ -1,32 +0,0 @@ -import ctypes, subprocess, pathlib, tempfile -from tinygrad.device import Compiled, Compiler, MallocAllocator -from tinygrad.helpers import cpu_time_execution, cpu_objdump -from tinygrad.renderer.cstyle import ClangRenderer - -class ClangCompiler(Compiler): - def __init__(self, cachekey="compile_clang", args:list[str]|None=None, objdump_tool='objdump'): - self.args = ['-march=native'] if args is None else args - self.objdump_tool = objdump_tool - super().__init__(cachekey) - - def compile(self, src:str) -> bytes: - # TODO: remove file write. sadly clang doesn't like the use of /dev/stdout here - with tempfile.NamedTemporaryFile(delete=True) as output_file: - subprocess.check_output(['clang', '-shared', *self.args, '-O2', '-Wall', '-Werror', '-x', 'c', '-fPIC', '-ffreestanding', '-nostdlib', - '-', '-o', str(output_file.name)], input=src.encode('utf-8')) - return pathlib.Path(output_file.name).read_bytes() - - def disassemble(self, lib:bytes): return cpu_objdump(lib, self.objdump_tool) - -class ClangProgram: - def __init__(self, name:str, lib:bytes): - self.name, self.lib = name, lib - # write to disk so we can load it - with tempfile.NamedTemporaryFile(delete=True) as cached_file_path: - pathlib.Path(cached_file_path.name).write_bytes(lib) - self.fxn = ctypes.CDLL(str(cached_file_path.name))[name] - - def __call__(self, *bufs, vals=(), wait=False): return cpu_time_execution(lambda: self.fxn(*bufs, *vals), enable=wait) - -class ClangDevice(Compiled): - def __init__(self, device:str): super().__init__(device, MallocAllocator, ClangRenderer(), ClangCompiler(), ClangProgram) diff --git a/tinygrad_repo/tinygrad/runtime/ops_cloud.py b/tinygrad_repo/tinygrad/runtime/ops_cloud.py deleted file mode 100644 index e1550c5eb4..0000000000 --- a/tinygrad_repo/tinygrad/runtime/ops_cloud.py +++ /dev/null @@ -1,220 +0,0 @@ -# the CLOUD=1 device is a process boundary between the frontend/runtime -# normally tinygrad is frontend <-> middleware <-> runtime <-> hardware -# with CLOUD tinygrad is frontend <-> middleware <-> CloudDevice ///HTTP/// cloud_server <-> runtime <-> hardware -# this client and server can be on the same machine, same network, or just same internet -# it should be a secure (example: no use of pickle) boundary. HTTP is used for RPC - -from __future__ import annotations -from typing import Optional, Any -from collections import defaultdict -from dataclasses import dataclass, field -import multiprocessing, functools, http.client, hashlib, json, time, os, binascii, struct, ast, contextlib -from http.server import HTTPServer, BaseHTTPRequestHandler -from tinygrad.renderer import Renderer -from tinygrad.dtype import dtypes -from tinygrad.helpers import getenv, DEBUG, fromimport, unwrap, Timing -from tinygrad.device import Compiled, Allocator, Compiler, Device, BufferSpec - -# ***** API ***** - -class CloudRequest: pass - -@dataclass(frozen=True) -class BufferAlloc(CloudRequest): buffer_num: int; size: int; options: BufferSpec # noqa: E702 - -@dataclass(frozen=True) -class BufferFree(CloudRequest): buffer_num: int # noqa: E702 - -@dataclass(frozen=True) -class CopyIn(CloudRequest): buffer_num: int; datahash: str # noqa: E702 - -@dataclass(frozen=True) -class CopyOut(CloudRequest): buffer_num: int - -@dataclass(frozen=True) -class ProgramAlloc(CloudRequest): name: str; datahash: str # noqa: E702 - -@dataclass(frozen=True) -class ProgramFree(CloudRequest): name: str; datahash: str # noqa: E702 - -@dataclass(frozen=True) -class ProgramExec(CloudRequest): - name: str; datahash: str; bufs: tuple[int, ...]; vals: tuple[int, ...] # noqa: E702 - global_size: Optional[tuple[int, ...]]; local_size: Optional[tuple[int, ...]]; wait: bool # noqa: E702 - -# for safe deserialization -whitelist = {x.__name__:x for x in [BufferAlloc, BufferFree, CopyIn, CopyOut, ProgramAlloc, ProgramFree, ProgramExec, BufferSpec]} -eval_fxns = {ast.Constant: lambda x: x.value, ast.Tuple: lambda x: tuple(map(safe_eval, x.elts)), ast.List: lambda x: list(map(safe_eval, x.elts)), - ast.Call: lambda x: safe_eval(x.func)(*[safe_eval(arg) for arg in x.args], **{kwarg.arg: safe_eval(kwarg.value) for kwarg in x.keywords}), - ast.Name: lambda x: whitelist[x.id], ast.Attribute: lambda x: {"imagef": dtypes.imagef, "imageh": dtypes.imageh}[x.attr]} -def safe_eval(node): return eval_fxns[node.__class__](node) - -class BatchRequest: - def __init__(self): - self._q: list[CloudRequest] = [] - self._h: dict[str, bytes] = {} - def h(self, d:bytes) -> str: - binhash = hashlib.sha256(d).digest() - self._h[datahash:=binascii.hexlify(binhash).decode()] = binhash+struct.pack(" bytes: - self.h(repr(self._q).encode()) - return b''.join(self._h.values()) - def deserialize(self, dat:bytes) -> BatchRequest: - ptr = 0 - while ptr < len(dat): - datahash, datalen = binascii.hexlify(dat[ptr:ptr+0x20]).decode(), struct.unpack("= 1: print(c) - match c: - case BufferAlloc(): - assert c.buffer_num not in session.buffers, f"buffer {c.buffer_num} already allocated" - session.buffers[c.buffer_num] = (Device[CloudHandler.device].allocator.alloc(c.size, c.options), c.size, c.options) - case BufferFree(): - buf,sz,buffer_options = session.buffers[c.buffer_num] - Device[CloudHandler.device].allocator.free(buf,sz,buffer_options) - del session.buffers[c.buffer_num] - case CopyIn(): Device[CloudHandler.device].allocator._copyin(session.buffers[c.buffer_num][0], memoryview(bytearray(req._h[c.datahash]))) - case CopyOut(): - buf,sz,_ = session.buffers[c.buffer_num] - Device[CloudHandler.device].allocator._copyout(memoryview(ret:=bytearray(sz)), buf) - case ProgramAlloc(): - lib = Device[CloudHandler.device].compiler.compile_cached(req._h[c.datahash].decode()) - session.programs[(c.name, c.datahash)] = Device[CloudHandler.device].runtime(c.name, lib) - case ProgramFree(): del session.programs[(c.name, c.datahash)] - case ProgramExec(): - bufs = [session.buffers[x][0] for x in c.bufs] - extra_args = {k:v for k,v in [("global_size", c.global_size), ("local_size", c.local_size)] if v is not None} - r = session.programs[(c.name, c.datahash)](*bufs, vals=c.vals, wait=c.wait, **extra_args) - if r is not None: ret = str(r).encode() - elif self.path == "/renderer" and method == "GET": - cls, args = Device[CloudHandler.device].renderer.__reduce__() - ret = json.dumps((cls.__module__, cls.__name__, args)).encode() - else: status_code = 404 - self.send_response(status_code) - self.send_header('Content-Length', str(len(ret))) - self.end_headers() - return self.wfile.write(ret) - - def do_GET(self): return self._do("GET") - def do_POST(self): return self._do("POST") - -def cloud_server(port:int): - multiprocessing.current_process().name = "MainProcess" - CloudHandler.device = getenv("CLOUDDEV", "METAL") if Device.DEFAULT == "CLOUD" else Device.DEFAULT - print(f"start cloud server on {port} with device {CloudHandler.device}") - server = HTTPServer(('', port), CloudHandler) - server.serve_forever() - -# ***** frontend ***** - -class CloudAllocator(Allocator): - def __init__(self, dev:CloudDevice): - self.device = dev - super().__init__() - # TODO: ideally we shouldn't have to deal with images here - def _alloc(self, size:int, options:BufferSpec) -> int: - self.device.buffer_num += 1 - self.device.req.q(BufferAlloc(self.device.buffer_num, size, options)) - return self.device.buffer_num - # TODO: options should not be here in any Allocator - def _free(self, opaque:int, options): self.device.req.q(BufferFree(opaque)) - def _copyin(self, dest:int, src:memoryview): self.device.req.q(CopyIn(dest, self.device.req.h(bytes(src)))) - def _copyout(self, dest:memoryview, src:int): - self.device.req.q(CopyOut(src)) - resp = self.device.batch_submit() - assert len(resp) == len(dest), f"buffer length mismatch {len(resp)} != {len(dest)}" - dest[:] = resp - -class CloudProgram: - def __init__(self, dev:CloudDevice, name:str, lib:bytes): - self.dev, self.name = dev, name - self.datahash = self.dev.req.h(lib) - self.dev.req.q(ProgramAlloc(self.name, self.datahash)) - super().__init__() - def __del__(self): self.dev.req.q(ProgramFree(self.name, self.datahash)) - - def __call__(self, *bufs, global_size=None, local_size=None, vals:tuple[int, ...]=(), wait=False): - self.dev.req.q(ProgramExec(self.name, self.datahash, bufs, vals, global_size, local_size, wait)) - if wait: return float(self.dev.batch_submit()) - -class CloudDevice(Compiled): - def __init__(self, device:str): - if (host:=getenv("HOST", "")) != "": self.host = host - else: - p = multiprocessing.Process(target=cloud_server, args=(6667,)) - p.daemon = True - p.start() - self.host = "127.0.0.1:6667" - - # state for the connection - self.session = binascii.hexlify(os.urandom(0x10)).decode() - self.buffer_num = 0 - self.req: BatchRequest = BatchRequest() - - if DEBUG >= 1: print(f"cloud with host {self.host}") - while 1: - try: - self.conn = http.client.HTTPConnection(self.host, timeout=60.0) - clouddev = json.loads(self.send("GET", "renderer").decode()) - break - except Exception as e: - print(e) - time.sleep(0.1) - if DEBUG >= 1: print(f"remote has device {clouddev}") - # TODO: how to we have BEAM be cached on the backend? this should just send a specification of the compute. rethink what goes in Renderer - if not clouddev[0].startswith("tinygrad.renderer.") or not clouddev[1].endswith("Renderer"): raise RuntimeError(f"bad renderer {clouddev}") - renderer_class = fromimport(clouddev[0], clouddev[1]) # TODO: is this secure? - if not issubclass(renderer_class, Renderer): raise RuntimeError(f"renderer isn't a Renderer {clouddev}") - super().__init__(device, CloudAllocator(self), renderer_class(*clouddev[2]), Compiler(), functools.partial(CloudProgram, self)) - - def __del__(self): - # TODO: this is never being called - # TODO: should close the whole session - with contextlib.suppress(ConnectionRefusedError, http.client.CannotSendRequest, http.client.RemoteDisconnected): self.batch_submit() - - def batch_submit(self): - data = self.req.serialize() - with Timing(f"*** send {len(self.req._q):-3d} requests {len(self.req._h):-3d} hashes with len {len(data)/1024:.2f} kB in ", enabled=DEBUG>=1): - ret = self.send("POST", "batch", data) - self.req = BatchRequest() - return ret - - def send(self, method, path, data:Optional[bytes]=None) -> bytes: - # TODO: retry logic - self.conn.request(method, "/"+path, data, headers={"Cookie": f"session={self.session}"}) - response = self.conn.getresponse() - assert response.status == 200, f"failed on {method} {path}" - return response.read() - -if __name__ == "__main__": cloud_server(getenv("PORT", 6667)) diff --git a/tinygrad_repo/tinygrad/runtime/ops_cpu.py b/tinygrad_repo/tinygrad/runtime/ops_cpu.py new file mode 100644 index 0000000000..e180a0a6b3 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/ops_cpu.py @@ -0,0 +1,26 @@ +import functools, platform, subprocess, sys +from tinygrad.helpers import capstone_flatdump, getenv +from tinygrad.device import Compiled, Compiler, MallocAllocator, CPUProgram +from tinygrad.runtime.support.elf import jit_loader +from tinygrad.renderer.cstyle import ClangRenderer + +class ClangJITCompiler(Compiler): + def __init__(self, cachekey="compile_clang_jit"): super().__init__(cachekey) + + def compile(self, src:str) -> bytes: + # -fno-math-errno is required for __builtin_sqrt to become an instruction instead of a function call + # x18 is a reserved platform register. It is clobbered on context switch in macos and is used to store TEB pointer in windows on arm, don't use it + target = 'x86_64' if sys.platform == 'win32' else platform.machine() + args = ['-march=native', f'--target={target}-none-unknown-elf', '-O2', '-fPIC', '-ffreestanding', '-fno-math-errno', '-nostdlib', '-fno-ident'] + arch_args = ['-ffixed-x18'] if target == 'arm64' else [] + obj = subprocess.check_output([getenv("CC", 'clang'), '-c', '-x', 'c', *args, *arch_args, '-', '-o', '-'], input=src.encode('utf-8')) + return jit_loader(obj) + + def disassemble(self, lib:bytes): return capstone_flatdump(lib) + +class ClangDevice(Compiled): + def __init__(self, device:str): + from tinygrad.runtime.graph.cpu import CPUGraph + super().__init__(device, MallocAllocator, ClangRenderer(), ClangJITCompiler(), CPUProgram, functools.partial(CPUGraph, self)) + +CPUDevice = ClangDevice \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/runtime/ops_cuda.py b/tinygrad_repo/tinygrad/runtime/ops_cuda.py index 910522e0c0..866eb1bcee 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_cuda.py +++ b/tinygrad_repo/tinygrad/runtime/ops_cuda.py @@ -7,6 +7,7 @@ from tinygrad.renderer.ptx import PTXRenderer from tinygrad.runtime.autogen import cuda from tinygrad.runtime.support.compiler_cuda import cuda_disassemble, pretty_ptx, CUDACompiler, PTXCompiler, PTX if getenv("IOCTL"): import extra.nv_gpu_driver.nv_ioctl # noqa: F401 # pylint: disable=unused-import +if MOCKGPU:=getenv("MOCKGPU"): from test.mockgpu.cuda import cuda # type: ignore # pylint: disable=reimported def check(status): if status != 0: raise RuntimeError(f"CUDA Error {status}, {ctypes.string_at(init_c_var(ctypes.POINTER(ctypes.c_char)(), lambda x: cuda.cuGetErrorString(status, ctypes.byref(x)))).decode()}") # noqa: E501 @@ -33,7 +34,7 @@ class CUDAProgram: def __init__(self, dev:CUDADevice, name:str, lib:bytes, smem:int=0): self.dev, self.name, self.lib, self.smem = dev, name, lib, smem if DEBUG >= 5: print("\n".join([f"{i+1:>3} {line}" for i, line in enumerate(pretty_ptx(lib.decode('utf-8')).split("\n"))])) - if DEBUG >= 6: cuda_disassemble(lib, dev.arch) + if DEBUG >= 7: cuda_disassemble(lib, dev.arch) check(cuda.cuCtxSetCurrent(self.dev.context)) self.module = cuda.CUmodule() @@ -53,31 +54,32 @@ class CUDAProgram: check(cuda.cuCtxSetCurrent(self.dev.context)) if not hasattr(self, "vargs"): self.c_args, self.vargs = encode_args(args, vals) + + # HACK: For MOCKGPU send the args struct itself. + if MOCKGPU: self.vargs = self.c_args # type: ignore[assignment] else: for i in range(len(args)): self.c_args.__setattr__(f'f{i}', args[i]) for i in range(len(vals)): self.c_args.__setattr__(f'v{i}', vals[i]) return cu_time_execution(lambda: check(cuda.cuLaunchKernel(self.prg, *global_size, *local_size, self.smem, None, None, self.vargs)), enable=wait) -class CUDAAllocator(LRUAllocator): - def __init__(self, device:CUDADevice): - self.device = device - super().__init__() +class CUDAAllocator(LRUAllocator['CUDADevice']): def _alloc(self, size, options:BufferSpec): - check(cuda.cuCtxSetCurrent(self.device.context)) + check(cuda.cuCtxSetCurrent(self.dev.context)) + if options.external_ptr: return cuda.CUdeviceptr_v2(options.external_ptr) if options.host: return init_c_var(ctypes.c_void_p(), lambda x: check(cuda.cuMemHostAlloc(ctypes.byref(x), size, 0x01))) return init_c_var(cuda.CUdeviceptr(), lambda x: check(cuda.cuMemAlloc_v2(ctypes.byref(x), size))) def _free(self, opaque, options:BufferSpec): if options.host: check(cuda.cuMemFreeHost(opaque)) else: check(cuda.cuMemFree_v2(opaque)) def _copyin(self, dest, src:memoryview): - check(cuda.cuCtxSetCurrent(self.device.context)) + check(cuda.cuCtxSetCurrent(self.dev.context)) host_mem = self.alloc(len(src), BufferSpec(host=True)) - self.device.pending_copyin.append((host_mem, len(src), BufferSpec(host=True))) + self.dev.pending_copyin.append((host_mem, len(src), BufferSpec(host=True))) ctypes.memmove(host_mem, from_mv(src), len(src)) check(cuda.cuMemcpyHtoDAsync_v2(dest, host_mem, len(src), None)) def _copyout(self, dest:memoryview, src): CUDADevice.synchronize_system() - check(cuda.cuCtxSetCurrent(self.device.context)) + check(cuda.cuCtxSetCurrent(self.dev.context)) check(cuda.cuMemcpyDtoH_v2(from_mv(dest), src, len(dest))) def _transfer(self, dest, src, sz:int, src_dev, dest_dev): check(cuda.cuCtxSetCurrent(src_dev.context)) @@ -114,7 +116,7 @@ class CUDADevice(Compiled): from tinygrad.runtime.graph.cuda import CUDAGraph super().__init__(device, CUDAAllocator(self), PTXRenderer(self.arch) if PTX else CUDARenderer(self.arch), - PTXCompiler(self.arch) if PTX else CUDACompiler(self.arch), functools.partial(CUDAProgram, self), graph=CUDAGraph) + PTXCompiler(self.arch) if PTX else CUDACompiler(self.arch), functools.partial(CUDAProgram, self), None if MOCKGPU else CUDAGraph) def synchronize(self): check(cuda.cuCtxSetCurrent(self.context)) diff --git a/tinygrad_repo/tinygrad/runtime/ops_disk.py b/tinygrad_repo/tinygrad/runtime/ops_disk.py index c5740283ea..fb680340b4 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_disk.py +++ b/tinygrad_repo/tinygrad/runtime/ops_disk.py @@ -1,4 +1,3 @@ -from __future__ import annotations import os, sys, mmap, io, ctypes, ctypes.util, contextlib from typing import Optional, Generator, Callable from tinygrad.helpers import OSX, round_up @@ -7,12 +6,68 @@ with contextlib.suppress(ImportError): import _posixshmem from tinygrad.runtime.autogen import io_uring, libc +class DiskDevice(Compiled): + _tried_io_uring_init = False + + def __init__(self, device:str): + if not DiskDevice._tried_io_uring_init: self._iouring_setup() + + self.size: Optional[int] = None + self.fd: Optional[int] = None + self.count = 0 + super().__init__(device, DiskAllocator(self), None, None, None) + def _might_open(self, size): + self.count += 1 + assert self.size is None or size <= self.size, f"can't reopen Disk tensor with larger size, opened with {self.size}, tried to open with {size}" + if self.size is not None: return + filename = self.device[len("disk:"):] + self.size = size + + if sys.platform != "win32" and filename.startswith("shm:"): + fd = _posixshmem.shm_open("/"+filename[4:].lstrip("/"), os.O_RDWR, 0o600) + self.mem = mmap.mmap(fd, self.size, mmap.MAP_SHARED | MAP_POPULATE | MAP_LOCKED) + os.close(fd) + else: + try: self.fd = os.open(filename, os.O_RDWR|os.O_CREAT|getattr(os, "O_DIRECT", 0)) + except OSError: self.fd = os.open(filename, os.O_RDWR|os.O_CREAT) + if os.fstat(self.fd).st_size < self.size: os.ftruncate(self.fd, self.size) + self.mem = mmap.mmap(self.fd, self.size) + if hasattr(self.mem, 'madvise') and (hp := getattr(mmap, "MADV_HUGEPAGE", None)) is not None: + with contextlib.suppress(OSError): self.mem.madvise(hp) # some systems have transparent_hugepage disabled + def _might_close(self): + self.count -= 1 + if self.count == 0: + if self.fd is not None: os.close(self.fd) + self.size = None + def _iouring_setup(self): + DiskDevice._tried_io_uring_init = True + + if sys.platform == 'linux' and not hasattr(sys, "getandroidapilevel"): + fd = libc.syscall(io_uring.NR_io_uring_setup, 4096, ctypes.byref(p:=io_uring.struct_io_uring_params())) + if fd < 0: return + + sq_ptr = libc.mmap(0, p.sq_off.array + p.sq_entries * 4, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, 0) + cq_ptr = libc.mmap(0, p.cq_off.cqes + p.cq_entries * ctypes.sizeof(io_uring.struct_io_uring_cqe), + mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, io_uring.IORING_OFF_CQ_RING) + sqes = libc.mmap(0, p.sq_entries * ctypes.sizeof(io_uring.struct_io_uring_sqe), + mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, io_uring.IORING_OFF_SQES) + + def u32ptr(val): return ctypes.cast(val, ctypes.POINTER(ctypes.c_uint32)) + sqdesc = io_uring.struct_io_uring_sq(khead=u32ptr(sq_ptr+p.sq_off.head), ktail=u32ptr(sq_ptr+p.sq_off.tail), + array=u32ptr(sq_ptr+p.sq_off.array), + kring_mask=u32ptr(sq_ptr+p.sq_off.ring_mask), sqes=ctypes.cast(sqes, ctypes.POINTER(io_uring.struct_io_uring_sqe))) + + cqdesc = io_uring.struct_io_uring_cq(khead=u32ptr(cq_ptr+p.cq_off.head), ktail=u32ptr(cq_ptr+p.cq_off.tail), + kring_mask=u32ptr(sq_ptr+p.cq_off.ring_mask), cqes=ctypes.cast(cq_ptr+p.cq_off.cqes, ctypes.POINTER(io_uring.struct_io_uring_cqe))) + + DiskDevice.io_uring = io_uring.struct_io_uring(ring_fd=fd, sq=sqdesc, cq=cqdesc) # type: ignore + class DiskBuffer: def __init__(self, device:DiskDevice, size:int, offset=0): self.device, self.size, self.offset = device, size, offset def __repr__(self): return f"" def _buf(self) -> memoryview: - assert self.device.mem is not None, "DiskBuffer wasn't opened" + assert hasattr(self.device, "mem"), f"DiskBuffer wasn't opened: {self.device.device}" return memoryview(self.device.mem)[self.offset:self.offset+self.size] MAP_LOCKED, MAP_POPULATE = 0 if OSX else 0x2000, getattr(mmap, "MAP_POPULATE", 0 if OSX else 0x008000) @@ -29,7 +84,8 @@ class DiskAllocator(Allocator): # OSX doesn't seem great at mmap, this is faster with io.FileIO(self.dev.fd, "a+b", closefd=False) as fo: fo.seek(src.offset) - fo.readinto(dest) + bytes_read = 0 + while (n := fo.readinto(dest[bytes_read:])) is not None and n > 0: bytes_read += n else: dest[:] = src._buf() @@ -66,59 +122,3 @@ class DiskAllocator(Allocator): processed_reqs_cnt += 1 def _offset(self, buf:DiskBuffer, size:int, offset:int): return DiskBuffer(buf.device, size, offset) - -class DiskDevice(Compiled): - _tried_io_uring_init = False - - def __init__(self, device:str): - if not DiskDevice._tried_io_uring_init: self._iouring_setup() - - self.size: Optional[int] = None - self.fd: Optional[int] = None - self.count = 0 - super().__init__(device, DiskAllocator(self), None, None, None) - def _might_open(self, size): - self.count += 1 - assert self.size is None or size <= self.size, f"can't reopen Disk tensor with larger size, opened with {self.size}, tried to open with {size}" - if self.size is not None: return - filename = self.device[len("disk:"):] - self.size = size - - if sys.platform != "win32" and filename.startswith("shm:"): - fd = _posixshmem.shm_open("/"+filename[4:].lstrip("/"), os.O_RDWR, 0o600) - self.mem = mmap.mmap(fd, self.size, mmap.MAP_SHARED | MAP_POPULATE | MAP_LOCKED) - os.close(fd) - else: - try: self.fd = os.open(filename, os.O_RDWR|os.O_CREAT|getattr(os, "O_DIRECT", 0)) - except OSError: self.fd = os.open(filename, os.O_RDWR|os.O_CREAT) - if os.fstat(self.fd).st_size < self.size: os.ftruncate(self.fd, self.size) - self.mem = mmap.mmap(self.fd, self.size) - if hasattr(self.mem, 'madvise') and (hp := getattr(mmap, "MADV_HUGEPAGE", None)) is not None: - with contextlib.suppress(OSError): self.mem.madvise(hp) # some systems have transparent_hugepage disabled - def _might_close(self): - self.count -= 1 - if self.count == 0: - if self.fd is not None: os.close(self.fd) - self.size = None - def _iouring_setup(self): - DiskDevice._tried_io_uring_init = True - - if sys.platform == 'linux' and not hasattr(sys, "getandroidapilevel"): - fd = libc.syscall(io_uring.NR_io_uring_setup, 4096, ctypes.byref(p:=io_uring.struct_io_uring_params())) - if fd < 0: return - - sq_ptr = libc.mmap(0, p.sq_off.array + p.sq_entries * 4, mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, 0) - cq_ptr = libc.mmap(0, p.cq_off.cqes + p.cq_entries * ctypes.sizeof(io_uring.struct_io_uring_cqe), - mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, io_uring.IORING_OFF_CQ_RING) - sqes = libc.mmap(0, p.sq_entries * ctypes.sizeof(io_uring.struct_io_uring_sqe), - mmap.PROT_READ | mmap.PROT_WRITE, mmap.MAP_SHARED | MAP_POPULATE, fd, io_uring.IORING_OFF_SQES) - - def u32ptr(val): return ctypes.cast(val, ctypes.POINTER(ctypes.c_uint32)) - sqdesc = io_uring.struct_io_uring_sq(khead=u32ptr(sq_ptr+p.sq_off.head), ktail=u32ptr(sq_ptr+p.sq_off.tail), - array=u32ptr(sq_ptr+p.sq_off.array), - kring_mask=u32ptr(sq_ptr+p.sq_off.ring_mask), sqes=ctypes.cast(sqes, ctypes.POINTER(io_uring.struct_io_uring_sqe))) - - cqdesc = io_uring.struct_io_uring_cq(khead=u32ptr(cq_ptr+p.cq_off.head), ktail=u32ptr(cq_ptr+p.cq_off.tail), - kring_mask=u32ptr(sq_ptr+p.cq_off.ring_mask), cqes=ctypes.cast(cq_ptr+p.cq_off.cqes, ctypes.POINTER(io_uring.struct_io_uring_cqe))) - - DiskDevice.io_uring = io_uring.struct_io_uring(ring_fd=fd, sq=sqdesc, cq=cqdesc) # type: ignore diff --git a/tinygrad_repo/extra/backends/ops_dsp.py b/tinygrad_repo/tinygrad/runtime/ops_dsp.py similarity index 51% rename from tinygrad_repo/extra/backends/ops_dsp.py rename to tinygrad_repo/tinygrad/runtime/ops_dsp.py index 7cac17c6c1..3264be212f 100644 --- a/tinygrad_repo/extra/backends/ops_dsp.py +++ b/tinygrad_repo/tinygrad/runtime/ops_dsp.py @@ -1,33 +1,57 @@ from __future__ import annotations -from typing import Tuple, Any, List -import ctypes, os, mmap, tempfile, pathlib, array, functools, threading, contextlib, sys +import ctypes, os, mmap, tempfile, pathlib, array, functools, threading, contextlib, sys, subprocess, struct assert sys.platform != 'win32' -from tinygrad.device import BufferSpec, Compiled, Allocator +from tinygrad.device import BufferSpec, Compiled, Allocator, Compiler, MallocAllocator from tinygrad.dtype import dtypes, DType, PtrDType -from tinygrad.ops import Ops, UOp -from tinygrad.helpers import from_mv, getenv, round_up, mv_address, to_mv -from tinygrad.runtime.ops_clang import ClangCompiler +from tinygrad.uop.ops import Ops, UOp +from tinygrad.helpers import from_mv, getenv, round_up, mv_address, to_mv, cpu_objdump, DEBUG from tinygrad.renderer.cstyle import ClangRenderer from tinygrad.runtime.autogen import libc, qcom_dsp if getenv("IOCTL"): import extra.dsp.run # noqa: F401 # pylint: disable=unused-import +from tinygrad.uop.ops import PatternMatcher, UPat + +dsp_pm = PatternMatcher([ + (((UPat.var('x').maximum(0) ^ -1).maximum(-256) ^ -1).cast(dtypes.uchar.vec(128)), + lambda x: UOp(Ops.CUSTOM, dtypes.uchar.vec(128), src=tuple(x.gep(tuple(range(i, i+32))) for i in range(0, 128, 32)), + arg="__builtin_HEXAGON_V6_vpackhub_sat_128B(__builtin_HEXAGON_V6_vpackwh_sat_128B({3}, {2}), __builtin_HEXAGON_V6_vpackwh_sat_128B({1}, {0}))")), + (UPat(Ops.GEP, name="x"), lambda x: UOp(Ops.CUSTOM, x.dtype, x.src+x.src, + "__builtin_shufflevector({0}, {1}, "+','.join([str(y) for y in x.arg])+")") if len(x.arg) > 1 and x.src[0].dtype.count > 1 else None), +]) + +dsp_pm_late = PatternMatcher([ + (UPat.var("x")+UPat(Ops.VECTORIZE,src=UPat.var("y")), lambda x,y: x+UOp(Ops.CUSTOMI,x.dtype,(y,),arg="{0}") if x.op is not Ops.CUSTOMI else None), + (UPat.var("x")*UPat(Ops.VECTORIZE,src=UPat.var("y")), lambda x,y: x*UOp(Ops.CUSTOMI,x.dtype,(y,),arg="{0}") if x.op is not Ops.CUSTOMI else None), + (UPat.var("x")//UPat(Ops.VECTORIZE,src=UPat.var("y")), lambda x,y: x//UOp(Ops.CUSTOMI,x.dtype,(y,),arg="{0}") if x.op is not Ops.CUSTOMI else None), + (UPat(Ops.DEFINE_ACC, src=(UPat(Ops.VECTORIZE, src=UPat(Ops.CONST, arg=0)),), dtype=dtypes.uchar.vec(128), name="d", allow_any_len=True), + lambda d: d.replace(src=(UOp(Ops.CUSTOMI, d.dtype, arg="__builtin_HEXAGON_V6_vd0_128B()"),)+d.src[1:])), +]) + +# NOTE: this just increases readability of the generated code +dsp_string = PatternMatcher([ + (UPat(Ops.CONST, (dtypes.int8, dtypes.uint8), name="x"), lambda ctx,x: str(x.arg)), +]) + class DSPRenderer(ClangRenderer): device = "DSP" - supports_float4 = False + supports_float4 = True buffer_suffix = " restrict __attribute__((align_value(128)))" kernel_prefix = "__attribute__((noinline)) " + pre_matcher = dsp_pm + extra_matcher = dsp_pm_late+ClangRenderer.extra_matcher + string_rewrite = dsp_string+ClangRenderer.string_rewrite type_map = { **ClangRenderer.type_map, dtypes.uint64: "unsigned long long", dtypes.int64: "long long" } - code_for_op = {**ClangRenderer.code_for_op, Ops.SIN: lambda x,dtype: f"__builtin_sin({x})", - Ops.LOG2: lambda x,dtype: f"__builtin_log2l({x})" if dtype == dtypes.float64 else f"__builtin_log2f({x})", - Ops.EXP2: lambda x,dtype: f"__builtin_exp2l({x})" if dtype == dtypes.float64 else f"__builtin_exp2f({x})"} - - def render_kernel(self, function_name:str, kernel:List[str], bufs:List[Tuple[str,Tuple[DType,bool]]], uops:List[UOp], prefix=None) -> str: - ret = super().render_kernel(function_name, kernel, bufs, uops, prefix) - msrc = ['''struct dcvs_v2_req { int type; int _pad; _Bool dcvs_enable; char dcvs_option; _Bool set_latency; int latency; _Bool set_dcvs_params; - short _pad2; char target_corner; char min_corner; char max_corner; int _pad3[3]; };''', 'int HAP_power_set(void*, void*);', - 'typedef union { struct { void *pv; unsigned int len; } buf; struct { int fd; unsigned int offset; } dma; } remote_arg;', - 'void* HAP_mmap(void *addr, int len, int prot, int flags, int fd, long offset);', 'int HAP_munmap(void *addr, int len);', - 'unsigned long long HAP_perf_get_time_us(void);', 'int entry(unsigned long long handle, unsigned int sc, remote_arg* pra) {', + code_for_op = {k:v for k,v in ClangRenderer.code_for_op.items() if k != Ops.SQRT} + + def _render_defines(self, uops) -> list[str]: + return ['''/* DSP boilerplate */ struct dcvs_v2_req { int type; int _pad; _Bool dcvs_enable; char dcvs_option; _Bool set_latency; int latency; + _Bool set_dcvs_params; short _pad2; char target_corner; char min_corner; char max_corner; int _pad3[3];};''','int HAP_power_set(void*, void*);', + 'typedef union { struct { void *pv; unsigned int len; } buf; struct { int fd; unsigned int offset; } dma; } remote_arg;', + 'void* HAP_mmap(void *addr, int len, int prot, int flags, int fd, long offset);', 'int HAP_munmap(void *addr, int len);', + 'unsigned long long HAP_perf_get_time_us(void);'] + super()._render_defines(uops) + + def _render_entry(self, function_name:str, bufs:list[tuple[str,tuple[DType,bool]]]) -> str: + msrc = ['int entry(unsigned long long handle, unsigned int sc, remote_arg* pra) {', 'struct dcvs_v2_req req = {.type=7, .dcvs_enable=0, .set_latency=1, .latency=100, .set_dcvs_params=1, .target_corner = 6 /* TURBO */};', 'HAP_power_set((void*)handle, (void*)&req);'] msrc += ['if ((sc>>24) != 2) return 0;'] @@ -39,7 +63,7 @@ class DSPRenderer(ClangRenderer): msrc += ["*(unsigned long long *)(pra[2].buf.pv) = HAP_perf_get_time_us() - start;"] msrc += [f'HAP_munmap(buf_{i}, sz_or_val_{i});' for i,b in enumerate(bufs) if isinstance(b[1][0], PtrDType)] msrc += ["return 0; }"] - return ret + '\n' + '\n'.join(msrc) + return '\n'.join(msrc) def rpc_sc(method=0, ins=0, outs=0, fds=0): return (method << 24) | (ins << 16) | (outs << 8) | fds def rpc_prep_args(ins=None, outs=None, in_fds=None): @@ -56,7 +80,7 @@ class DSPProgram: def __init__(self, dev:DSPDevice, name:str, lib:bytes): self.dev, self.lib = dev, lib - def __call__(self, *bufs, vals:Tuple[int, ...]=(), wait=False): + def __call__(self, *bufs, vals:tuple[int, ...]=(), wait=False): if len(bufs) >= 16: raise RuntimeError(f"Too many buffers to execute: {len(bufs)}") pra, fds, attrs, _ = rpc_prep_args(ins=[var_vals_mv:=memoryview(bytearray((len(bufs)+len(vals))*4)), off_mv:=memoryview(bytearray(len(bufs)*4))], @@ -67,14 +91,10 @@ class DSPProgram: return timer[0] / 1e6 class DSPBuffer: - def __init__(self, va_addr:int, size:int, share_info:Any, offset:int=0): + def __init__(self, va_addr:int, size:int, share_info, offset:int=0): self.va_addr, self.size, self.share_info, self.offset = va_addr, size, share_info, offset -class DSPAllocator(Allocator): - def __init__(self, dev:DSPDevice): - self.dev = dev - super().__init__() - +class DSPAllocator(Allocator['DSPDevice']): def _alloc(self, size:int, options:BufferSpec): b = qcom_dsp.ION_IOC_ALLOC(self.dev.ion_fd, len=size, align=0x200, heap_id_mask=1< memoryview: return to_mv(src.va_addr, src.size) def _copyin(self, dest:DSPBuffer, src:memoryview): ctypes.memmove(dest.va_addr, from_mv(src), src.nbytes) def _copyout(self, dest:memoryview, src:DSPBuffer): ctypes.memmove(from_mv(dest), src.va_addr, dest.nbytes) def _offset(self, buf, size:int, offset:int): return DSPBuffer(buf.va_addr+offset, size, buf.share_info, buf.offset+offset) -class DSPDevice(Compiled): - def __init__(self, device:str=""): - self.ion_fd = os.open('/dev/ion', os.O_RDONLY) +class ClangCompiler(Compiler): + def __init__(self, cachekey="compile_clang", args:list[str]|None=None, objdump_tool='objdump'): + self.args = ['-shared', '-march=native'] if args is None else args + self.objdump_tool = objdump_tool + super().__init__(cachekey) - # Generate link script to pass into clang. Aligning all used sections to 4k fixes invoke problem. - sections = ['hash', 'text', 'rela.plt', 'got', 'got.plt', 'dynamic', 'dynsym', 'dynstr', 'plt', 'data', 'bss'] - sections_link = '\n'.join([f'.{n} : ALIGN(4096) {{ *(.{n}) }}' for n in sections]) - with tempfile.NamedTemporaryFile(delete=False) as self.link_ld: - self.link_ld.write(f"SECTIONS {{ . = 0x0; {sections_link}\n /DISCARD/ : {{ *(.note .note.* .gnu.hash .comment) }} }}".encode()) - self.link_ld.flush() + def compile(self, src:str) -> bytes: + # TODO: remove file write. sadly clang doesn't like the use of /dev/stdout here + with tempfile.NamedTemporaryFile(delete=True) as output_file: + subprocess.check_output([getenv("CC", 'clang'), *self.args, '-O2', '-Wall', '-Werror', '-x', 'c', '-fPIC', '-ffreestanding', '-nostdlib', + '-', '-o', str(output_file.name)], input=src.encode('utf-8')) + return pathlib.Path(output_file.name).read_bytes() - compiler_args = ["--target=hexagon", "-mcpu=hexagonv65", "-fuse-ld=lld", "-nostdlib", "-mhvx=v65", "-mhvx-length=128b", f"-T{self.link_ld.name}"] - super().__init__(device, DSPAllocator(self), DSPRenderer(), - ClangCompiler("compile_dsp", args=compiler_args, objdump_tool='llvm-objdump'), functools.partial(DSPProgram, self)) + def disassemble(self, lib:bytes): return cpu_objdump(lib, self.objdump_tool) - fastrpc_shell = memoryview(bytearray(pathlib.Path('/dsp/cdsp/fastrpc_shell_3').read_bytes())) - self.shell_buf = self.allocator.alloc(round_up(fastrpc_shell.nbytes, 0x1000), BufferSpec(nolru=True)) - ctypes.memmove(self.shell_buf.va_addr, mv_address(fastrpc_shell), fastrpc_shell.nbytes) +class DSPDevice(Compiled): + def __init__(self, device:str=""): + compiler_args = ["--target=hexagon", "-mcpu=hexagonv65", "-fuse-ld=lld", "-nostdlib", "-mhvx=v65", "-mhvx-length=128b"] + try: + self.ion_fd = os.open('/dev/ion', os.O_RDONLY) + # Generate link script to pass into clang. Aligning all used sections to 4k fixes invoke problem. + sections = ['text', 'rela.plt', 'rela.dyn', 'plt', 'data', 'bss', 'hash', 'dynamic', + 'got', 'got.plt', 'dynsym', 'dynstr', 'symtab', 'shstrtab', 'strtab'] + sections_link = '\n'.join([f'.{n} : ALIGN(4096) {{ *(.{n}) }}' for n in sections]) + with tempfile.NamedTemporaryFile(delete=False) as self.link_ld: + self.link_ld.write(f"SECTIONS {{ . = 0x0; {sections_link}\n /DISCARD/ : {{ *(.note .note.* .gnu.hash .comment) }} }}".encode()) + self.link_ld.flush() - self.init_dsp() - RPCListner(self).start() + from tinygrad.runtime.graph.cpu import CPUGraph + super().__init__(device, DSPAllocator(self), DSPRenderer(), + ClangCompiler("compile_dsp", ["-shared"] + compiler_args + [f"-T{self.link_ld.name}"], 'llvm-objdump'), functools.partial(DSPProgram, self), + functools.partial(CPUGraph, self)) + fastrpc_shell = memoryview(bytearray(pathlib.Path('/dsp/cdsp/fastrpc_shell_3').read_bytes())) + self.shell_buf = self.allocator.alloc(round_up(fastrpc_shell.nbytes, 0x1000), BufferSpec(nolru=True)) + ctypes.memmove(self.shell_buf.va_addr, mv_address(fastrpc_shell), fastrpc_shell.nbytes) + + self.init_dsp() + RPCListener(self).start() + except FileNotFoundError: + super().__init__(device, MallocAllocator, MockDSPRenderer(), ClangCompiler(None, ["-static"] + compiler_args, 'llvm-objdump'), MockDSPProgram) def open_lib(self, lib): self.binded_lib, self.binded_lib_off = lib, 0 @@ -135,7 +175,8 @@ class DSPDevice(Compiled): except (OSError, PermissionError): # DSP might ask for a connection reset or just fail with operation not permitted, try to reset connection. self.init_dsp() - _exec_lib() + try: _exec_lib() + except (OSError, PermissionError) as e: raise RuntimeError(e) def init_dsp(self): if hasattr(self, 'rpc_fd'): @@ -149,7 +190,7 @@ class DSPDevice(Compiled): qcom_dsp.FASTRPC_IOCTL_INIT(self.rpc_fd, flags=0x1, file=self.shell_buf.va_addr, filelen=self.shell_buf.size, filefd=self.shell_buf.share_info.fd) qcom_dsp.FASTRPC_IOCTL_INVOKE(self.rpc_fd, handle=3, sc=rpc_sc(method=3, ins=0, outs=0)) -class RPCListner(threading.Thread): +class RPCListener(threading.Thread): def __init__(self, device:DSPDevice): super().__init__() self.device, self.daemon = device, True @@ -211,3 +252,54 @@ class RPCListner(threading.Thread): st = qcom_dsp.FASTRPC_IOCTL_MMAP(self.device.rpc_fd, fd=-1, flags=in_args[0].cast('I')[2], vaddrin=0, size=in_args[0].cast('Q')[3]) out_args[0].cast('Q')[0:2] = array.array('Q', [0, st.vaddrout]) else: raise RuntimeError(f"Unknown op: {sc=:X}") + +# ***** mock DSP ***** + +mockdsp_boilerplate = '''/* DSP boilerplate */ static long syscall(long r0, long r1, long r2, long r3, long r4, long r5, long r6) { +long retval; __asm__ volatile("r0 = %1; r1 = %2; r2 = %3; r3 = %4; r4 = %5; r5 = %6; r6 = %7; trap0(#1); %0 = r0" : "=r" (retval) + : "r" (r0), "r" (r1), "r" (r2), "r" (r3), "r" (r4), "r" (r5), "r" (r6) : "r0", "r1", "r2", "r3", "r4", "r5", "r6"); return retval; } +static int read(int fd, void* buf, int len) {{ return syscall(fd, (long)buf, len, 0, 0, 0, 63); }} +static int write(int fd, void* buf, int len) {{ return syscall(fd, (long)buf, len, 0, 0, 0, 64); }} +static int exit(int ret) {{ return syscall(ret, 0, 0, 0, 0, 0, 93); }} +static unsigned int inscount(void) {{ unsigned int ret; __asm__ volatile(".word 0x6a15c000; %0 = R0" : "=r" (ret) : : "r0"); return ret; }} +static void *mmap2(void *addr, unsigned int length, int prot, int flags, int fd, unsigned long offset) {{ +return (void*)syscall((long)addr, length, prot, flags, fd, offset, 222); }}''' + +class MockDSPRenderer(DSPRenderer): + def _render_defines(self, uops) -> list[str]: return ClangRenderer._render_defines(self, uops) + def _render_entry(self, function_name:str, bufs:list[tuple[str,tuple[DType,bool]]]) -> str: + # https://gpages.juszkiewicz.com.pl/syscalls-table/syscalls.html + # control register 21 is HEX_REG_QEMU_INSN_CNT, 0x6a15c000 loads it + msrc = [mockdsp_boilerplate, 'void _start(void) {'] + for i,b in enumerate(bufs): + if isinstance(b[1][0], PtrDType): + sz = b[1][0].size*b[1][0].itemsize + # for loop for big reads + msrc.append(f"void *buf{i} = mmap2(0, {sz}, 3, 0x21, -1, 0); for(int rd = 0; rd < {sz}; rd += read(0, buf{i}+rd, {sz}-rd));") + else: + msrc.append(f"unsigned int val{i}; read(0, &val{i}, 4);") + msrc.append("unsigned int st = inscount();") + msrc.append(f"{function_name}({', '.join([(f'(void*)buf{i}' if isinstance(b[1][0], PtrDType) else f'val{i}') for i,b in enumerate(bufs)])});") + msrc.append("unsigned int et = inscount() - st; write(1, &et, sizeof(et));") + for i,b in enumerate(bufs): + if isinstance(b[1][0], PtrDType): msrc.append(f"write(1, buf{i}, {b[1][0].size*b[1][0].itemsize});") + msrc.append('exit(0); }') + return '\n'.join(msrc) + +class MockDSPProgram: + def __init__(self, name:str, lib:bytes): self.lib = lib + def __call__(self, *bufs, vals:tuple[int, ...]=(), wait=False): + with tempfile.NamedTemporaryFile(suffix=".out") as dsp_lib: + dsp_lib.write(self.lib) + dsp_lib.flush() + os.chmod(dsp_lib.name, 0o0777) + # NOTE: this timing includes a docker launch + proc = subprocess.run(["docker", "run", "--rm", "-i", "-v", f"{os.path.abspath(os.path.dirname(dsp_lib.name))}:/work", "-w", "/work", + "qemu-hexagon", "-c", f"qemu-hexagon {'-strace' if DEBUG >= 5 else ''} /work/"+os.path.basename(dsp_lib.name)], + input=b''.join([bytes(x) for x in bufs] + [struct.pack("I", x) for x in vals]), stdout=subprocess.PIPE, check=True) + offset = 4 + for x in bufs: + x[:] = proc.stdout[offset:offset+len(x)] + offset += len(x) + assert offset == len(proc.stdout) + return struct.unpack("I", proc.stdout[0:4])[0] / 1e9 # pretend it's 1 Ghz, but this is an inscount, not a time diff --git a/tinygrad_repo/tinygrad/runtime/ops_gpu.py b/tinygrad_repo/tinygrad/runtime/ops_gpu.py index c35fc4e326..e07c377592 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_gpu.py +++ b/tinygrad_repo/tinygrad/runtime/ops_gpu.py @@ -58,10 +58,7 @@ class CLProgram: return float(end.value-start.value) * OSX_TIMING_RATIO * 1e-9 return None -class CLAllocator(LRUAllocator): - def __init__(self, dev:CLDevice): - self.dev = dev - super().__init__() +class CLAllocator(LRUAllocator['CLDevice']): def _alloc(self, size:int, options:BufferSpec) -> tuple[ctypes._CData, BufferSpec]: if options.image is not None: return (checked(cl.clCreateImage2D(self.dev.context, cl.CL_MEM_READ_WRITE, diff --git a/tinygrad_repo/tinygrad/runtime/ops_hip.py b/tinygrad_repo/tinygrad/runtime/ops_hip.py index 397eeb98f6..d26a91d202 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_hip.py +++ b/tinygrad_repo/tinygrad/runtime/ops_hip.py @@ -1,15 +1,24 @@ -from __future__ import annotations import ctypes, functools from tinygrad.helpers import init_c_var, from_mv, init_c_struct_t, getenv from tinygrad.device import Compiled, LRUAllocator, BufferSpec from tinygrad.runtime.autogen import hip -from tinygrad.runtime.support.compiler_hip import AMDCompiler +from tinygrad.runtime.support.compiler_amd import HIPCompiler from tinygrad.renderer.cstyle import HIPRenderer if getenv("IOCTL"): import extra.hip_gpu_driver.hip_ioctl # noqa: F401 # pylint: disable=unused-import def check(status): if status != 0: raise RuntimeError(f"HIP Error {status}, {ctypes.string_at(hip.hipGetErrorString(status)).decode()}") +class HIPDevice(Compiled): + def __init__(self, device:str=""): + self.device_id = int(device.split(":")[1]) if ":" in device else 0 + self.arch = init_c_var(hip.hipDeviceProp_t(), lambda x: check(hip.hipGetDeviceProperties(x, self.device_id))).gcnArchName.decode() + self.time_event_st, self.time_event_en = [init_c_var(hip.hipEvent_t(), lambda x: hip.hipEventCreate(ctypes.byref(x), 0)) for _ in range(2)] + super().__init__(device, HIPAllocator(self), HIPRenderer(self.arch), HIPCompiler(self.arch), functools.partial(HIPProgram, self)) + def synchronize(self): + check(hip.hipSetDevice(self.device_id)) + check(hip.hipDeviceSynchronize()) + class HIPProgram: def __init__(self, dev:HIPDevice, name:str, lib:bytes): self.dev, self.name, self.lib = dev, name, lib @@ -41,10 +50,7 @@ class HIPProgram: check(hip.hipEventElapsedTime(ctypes.byref(ret := ctypes.c_float()), self.dev.time_event_st, self.dev.time_event_en)) return ret.value * 1e-3 -class HIPAllocator(LRUAllocator): - def __init__(self, dev:HIPDevice): - self.dev = dev - super().__init__() +class HIPAllocator(LRUAllocator[HIPDevice]): def _alloc(self, size:int, options:BufferSpec): check(hip.hipSetDevice(self.dev.device_id)) return init_c_var(hip.hipDeviceptr_t(), lambda x: check(hip.hipMalloc(ctypes.byref(x), size))) @@ -55,13 +61,3 @@ class HIPAllocator(LRUAllocator): def _copyout(self, dest:memoryview, src): self.dev.synchronize() check(hip.hipMemcpy(from_mv(dest), src, len(dest), hip.hipMemcpyDeviceToHost)) - -class HIPDevice(Compiled): - def __init__(self, device:str=""): - self.device_id = int(device.split(":")[1]) if ":" in device else 0 - self.arch = init_c_var(hip.hipDeviceProp_t(), lambda x: check(hip.hipGetDeviceProperties(x, self.device_id))).gcnArchName.decode() - self.time_event_st, self.time_event_en = [init_c_var(hip.hipEvent_t(), lambda x: hip.hipEventCreate(ctypes.byref(x), 0)) for _ in range(2)] - super().__init__(device, HIPAllocator(self), HIPRenderer(), AMDCompiler(self.arch), functools.partial(HIPProgram, self)) - def synchronize(self): - check(hip.hipSetDevice(self.device_id)) - check(hip.hipDeviceSynchronize()) diff --git a/tinygrad_repo/tinygrad/runtime/ops_llvm.py b/tinygrad_repo/tinygrad/runtime/ops_llvm.py index 3976bc43df..1c1cb6ba5c 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_llvm.py +++ b/tinygrad_repo/tinygrad/runtime/ops_llvm.py @@ -1,50 +1,75 @@ -from __future__ import annotations -import ctypes, functools -from tinygrad.device import Compiled, Compiler, MallocAllocator -from tinygrad.helpers import cpu_time_execution, getenv, cpu_objdump +import functools, ctypes, platform +from tinygrad.device import Compiled, Compiler, MallocAllocator, CPUProgram +from tinygrad.helpers import OSX, getenv, capstone_flatdump, DEBUG from tinygrad.renderer.llvmir import LLVMRenderer -import llvmlite.binding as llvm +import tinygrad.runtime.autogen.llvm as llvm +from tinygrad.runtime.support.elf import jit_loader + +def cerr(): return ctypes.pointer(ctypes.pointer(ctypes.c_char())) + +def expect(x, err, ret=None): + if x: raise RuntimeError(llvm.string_cast(err.contents) if not isinstance(err, str) else err) + return ret class LLVMCompiler(Compiler): - def __init__(self, dev:LLVMDevice, opt:bool=False): - self.dev = dev - self.optimizer: llvm.passmanagers.ModulePassManager = llvm.create_module_pass_manager() - self.dev.target_machine.add_analysis_passes(self.optimizer) - if opt: - with llvm.create_pass_manager_builder() as builder: - builder.opt_level = 3; builder.size_level = 0; builder.loop_vectorize = True; builder.slp_vectorize = True # noqa: E702 - builder.populate(self.optimizer) - super().__init__("compile_llvm_opt" if opt else "compile_llvm") + jit = True + target_arch = {'arm64': 'AArch64', 'aarch64': 'AArch64', 'x86_64': 'X86', 'AMD64': 'X86'}[platform.machine()] + def __init__(self, processor:str, feats:str): + for component in ['Target', 'TargetInfo', 'TargetMC', 'AsmParser', 'AsmPrinter']: getattr(llvm, f'LLVMInitialize{self.target_arch}{component}')() - def compile(self, src:str) -> bytes: - mod = llvm.parse_assembly(src) - mod.verify() - self.optimizer.run(mod) - return self.dev.target_machine.emit_object(mod) + triple = {'AArch64': b'aarch64-none-unknown-elf', 'X86': b'x86_64-none-unknown-elf', 'AMDGPU': b'amdgcn-amd-amdhsa'}[self.target_arch] + target = expect(llvm.LLVMGetTargetFromTriple(triple, ctypes.pointer(tgt:=llvm.LLVMTargetRef()), err:=cerr()), err, tgt) + if DEBUG >= 3: print(f"LLVM init for {processor!r} with {feats!r}") + self.target_machine = llvm.LLVMCreateTargetMachine(target, triple, processor.encode(), feats.encode(), + llvm.LLVMCodeGenLevelDefault, llvm.LLVMRelocPIC, llvm.LLVMCodeModelDefault) + + self.pbo = llvm.LLVMCreatePassBuilderOptions() + if (opt:=bool(getenv("LLVMOPT", "1"))): + self.passes = b'default' + llvm.LLVMPassBuilderOptionsSetLoopUnrolling(self.pbo, True) + llvm.LLVMPassBuilderOptionsSetLoopVectorization(self.pbo, True) + llvm.LLVMPassBuilderOptionsSetSLPVectorization(self.pbo, True) + llvm.LLVMPassBuilderOptionsSetVerifyEach(self.pbo, True) + else: + self.passes = b'default' - def disassemble(self, lib:bytes): cpu_objdump(lib) + self.diag_msgs: list[str] = [] + @ctypes.CFUNCTYPE(None, llvm.LLVMDiagnosticInfoRef, ctypes.c_void_p) + def handle_diag(diag_ref, _arg): + severity = llvm.LLVMGetDiagInfoSeverity(diag_ref) + msg = ctypes.string_at(llvm.LLVMGetDiagInfoDescription(diag_ref)).decode() + if severity == llvm.LLVMDSError: + self.diag_msgs.append(msg) + self.handle_diag = handle_diag + llvm.LLVMContextSetDiagnosticHandler(llvm.LLVMGetGlobalContext(), handle_diag, None) + super().__init__(f"compile_llvm_{self.target_arch}{'_jit' if self.jit else ''}{'_opt' if opt else ''}") + + def __del__(self): llvm.LLVMDisposePassBuilderOptions(self.pbo) + + def compile(self, src:str) -> bytes: + self.diag_msgs.clear() + src_buf = llvm.LLVMCreateMemoryBufferWithMemoryRangeCopy(ctypes.create_string_buffer(src_bytes:=src.encode()), len(src_bytes), b'src') + mod = expect(llvm.LLVMParseIRInContext(llvm.LLVMGetGlobalContext(), src_buf, ctypes.pointer(m:=llvm.LLVMModuleRef()), err:=cerr()), err, m) + expect(llvm.LLVMVerifyModule(mod, llvm.LLVMReturnStatusAction, err:=cerr()), err) + expect(llvm.LLVMRunPasses(mod, self.passes, self.target_machine, self.pbo), 'failed to run passes') + if DEBUG >= 7: print(ctypes.string_at(llvm.LLVMPrintModuleToString(mod)).decode()) + obj_buf = expect(llvm.LLVMTargetMachineEmitToMemoryBuffer(self.target_machine, mod, llvm.LLVMObjectFile, err:=cerr(), + ctypes.pointer(buf:=llvm.LLVMMemoryBufferRef())), err, buf) + llvm.LLVMDisposeModule(mod) + obj = ctypes.string_at(llvm.LLVMGetBufferStart(obj_buf), llvm.LLVMGetBufferSize(obj_buf)) + llvm.LLVMDisposeMemoryBuffer(obj_buf) + if self.diag_msgs: raise RuntimeError("llvm diagnostic: " + "\n".join(self.diag_msgs)) + return jit_loader(obj) if self.jit else obj -class LLVMProgram: - def __init__(self, dev:LLVMDevice, name:str, lib:bytes): - self.name, self.lib = name, lib - dev.engine.add_object_file(llvm.object_file.ObjectFileRef.from_data(lib)) - self.fxn = dev.engine.get_function_address(name) - assert self.fxn != 0, "LLVM failed to get function address" + def disassemble(self, lib:bytes): capstone_flatdump(lib) - def __call__(self, *bufs, vals:tuple[int, ...]=(), wait=False): - if not hasattr(self, 'cfunc'): - self.cfunc = ctypes.CFUNCTYPE(ctypes.c_int, *([ctypes.c_void_p]*len(bufs)), *([ctypes.c_int32]*len(vals)))(self.fxn) - return cpu_time_execution(lambda: self.cfunc(*bufs, *vals), enable=wait) +class HostLLVMCompiler(LLVMCompiler): + def __init__(self): + # +reserve-x18 here does the same thing as -ffixed-x18 in ops_cpu.py, see comments there for why it's needed on arm osx + cpu, feats = ctypes.string_at(llvm.LLVMGetHostCPUName()), (b'+reserve-x18,' if OSX else b'') + ctypes.string_at(llvm.LLVMGetHostCPUFeatures()) + super().__init__(cpu.decode(), feats.decode()) class LLVMDevice(Compiled): def __init__(self, device:str): - llvm.initialize() - llvm.initialize_native_target() - llvm.initialize_native_asmprinter() - llvm.initialize_native_asmparser() - # this opt actually can change things. ex: opt=3 means no FMA, opt=2 means FMA - self.target_machine: llvm.targets.TargetMachine = llvm.Target.from_triple(llvm.get_process_triple()).create_target_machine(opt=2) - backing_mod = llvm.parse_assembly(str()) - backing_mod.triple = llvm.get_process_triple() - self.engine: llvm.executionengine.ExecutionEngine = llvm.create_mcjit_compiler(backing_mod, self.target_machine) - super().__init__(device, MallocAllocator, LLVMRenderer(), LLVMCompiler(self, getenv("LLVMOPT")), functools.partial(LLVMProgram, self)) + from tinygrad.runtime.graph.cpu import LLVMGraph + super().__init__(device, MallocAllocator, LLVMRenderer(), HostLLVMCompiler(), CPUProgram, functools.partial(LLVMGraph, self)) diff --git a/tinygrad_repo/tinygrad/runtime/ops_metal.py b/tinygrad_repo/tinygrad/runtime/ops_metal.py index 083f4e98a1..8a41570fcd 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_metal.py +++ b/tinygrad_repo/tinygrad/runtime/ops_metal.py @@ -1,5 +1,4 @@ -from __future__ import annotations -import os, pathlib, struct, ctypes, tempfile, functools, decimal +import os, pathlib, struct, ctypes, tempfile, functools, contextlib, decimal, platform from typing import Any, Union, cast from tinygrad.helpers import prod, to_mv, getenv, round_up, cache_dir, T, init_c_struct_t, PROFILE from tinygrad.device import Compiled, Compiler, CompileError, LRUAllocator, cpu_profile, ProfileDeviceEvent, ProfileRangeEvent @@ -10,10 +9,11 @@ class objc_id(ctypes.c_void_p): # This prevents ctypes from converting response def __eq__(self, other): return self.value == other.value class objc_instance(objc_id): # method with name "new", "alloc" should be freed after use - def __del__(self): msg(self, "release") - -@functools.lru_cache(None) -def sel(name: str): return libobjc.sel_registerName(name.encode()) + def __del__(self): + # CPython doesn't make any guarantees about order in which globals (like `msg` or `libobjc`) are destroyed when the interpreter shuts down + # https://github.com/tinygrad/tinygrad/pull/8949 triggered the unlucky ordering which lead to a bunch of errors at exit + # TODO: Why isn't `sys.is_finalizing` working? + if msg is not None and libobjc is not None: msg("release")(self) class MTLResourceOptions: MTLResourceCPUCacheModeDefaultCache = 0 @@ -27,50 +27,85 @@ REQUEST_TYPE_COMPILE = 13 libobjc = ctypes.CDLL("/usr/lib/libobjc.dylib") libmetal = ctypes.CDLL("/System/Library/Frameworks/Metal.framework/Metal") -compiler = ctypes.CDLL("/System/Library/PrivateFrameworks/MTLCompiler.framework/MTLCompiler") # Must be loaded for default Metal Device: https://developer.apple.com/documentation/metal/1433401-mtlcreatesystemdefaultdevice?language=objc ctypes.CDLL("/System/Library/Frameworks/CoreGraphics.framework/CoreGraphics") libdispatch = ctypes.CDLL("/usr/lib/libSystem.dylib") # libdispatch is part of libSystem on mac libobjc.objc_getClass.restype = objc_id libobjc.sel_registerName.restype = objc_id libmetal.MTLCreateSystemDefaultDevice.restype = objc_instance -compiler.MTLCodeGenServiceCreate.restype = ctypes.c_void_p libdispatch.dispatch_data_create.restype = objc_instance -# Ignore mypy error reporting incompatible default, because typevar default only works on python 3.12 -def msg(ptr: objc_id, selector: str, /, *args: Any, restype: type[T] = objc_id) -> T: # type: ignore [assignment] +@functools.cache +def msg(selector: str, restype: type[T] = objc_id): # type: ignore [assignment] + resname = libobjc.sel_registerName(selector.encode()) sender = libobjc["objc_msgSend"] # Using attribute access returns a new reference so setting restype is safe sender.restype = restype - return sender(ptr, sel(selector), *args) + def _msg(ptr: objc_id, *args: Any) -> T: return sender(ptr, resname, *args) + return _msg -def to_ns_str(s: str): return msg(libobjc.objc_getClass(b"NSString"), "stringWithUTF8String:", s.encode(), restype=objc_instance) -def from_ns_str(s): return bytes(msg(s, "UTF8String", restype=ctypes.c_char_p)).decode() +@functools.cache +def to_ns_str(s: str): return msg("stringWithUTF8String:", objc_instance)(libobjc.objc_getClass(b"NSString"), s.encode()) +def from_ns_str(s): return bytes(msg("UTF8String", ctypes.c_char_p)(s)).decode() def to_struct(*t: int, _type: type = ctypes.c_ulong): return init_c_struct_t(tuple([(f"field{i}", _type) for i in range(len(t))]))(*t) def wait_check(cbuf: Any): - msg(cbuf, "waitUntilCompleted") - error_check(msg(cbuf, "error", restype=objc_instance)) + msg("waitUntilCompleted")(cbuf) + error_check(msg("error", objc_instance)(cbuf)) -def cmdbuf_label(cbuf: objc_id) -> str: return from_ns_str(msg(cbuf, "label", restype=objc_id)) -def cmdbuf_st_time(cbuf: objc_id) -> float: return cast(float, msg(cbuf, "GPUStartTime", restype=ctypes.c_double)) -def cmdbuf_en_time(cbuf: objc_id) -> float: return cast(float, msg(cbuf, "GPUEndTime", restype=ctypes.c_double)) +def cmdbuf_label(cbuf: objc_id) -> str|None: return from_ns_str(label) if (label:=msg("label", objc_id)(cbuf)).value is not None else None +def cmdbuf_st_time(cbuf: objc_id) -> float: return cast(float, msg("GPUStartTime", ctypes.c_double)(cbuf)) +def cmdbuf_en_time(cbuf: objc_id) -> float: return cast(float, msg("GPUEndTime", ctypes.c_double)(cbuf)) def error_check(error: objc_instance, error_constructor: type[Exception] = RuntimeError): if error.value is None: return None - raise error_constructor(from_ns_str(msg(error, "localizedDescription", restype=objc_instance))) + raise error_constructor(from_ns_str(msg("localizedDescription", objc_instance)(error))) + +class MetalDevice(Compiled): + def __init__(self, device:str): + self.sysdevice = libmetal.MTLCreateSystemDefaultDevice() + self.mtl_queue = msg("newCommandQueueWithMaxCommandBufferCount:", objc_instance)(self.sysdevice, 1024) + if self.mtl_queue is None: raise RuntimeError("Cannot allocate a new command queue") + self.mtl_buffers_in_flight: list[Any] = [] + self.timeline_signal = msg("newSharedEvent", objc_instance)(self.sysdevice) + self.timeline_value = 0 + + Compiled.profile_events += [ProfileDeviceEvent(device)] + + from tinygrad.runtime.graph.metal import MetalGraph + # NOTE: GitHub CI macOS runners use paravirtualized metal which is broken with graph. + # This can be reproduced locally with any virtualization software (like utm) that can create macOS VMs with apple's own virtualization framework. + super().__init__(device, MetalAllocator(self), MetalRenderer(), MetalCompiler() if getenv("METAL_DIRECT", 1) else Compiler(), + functools.partial(MetalProgram, self), MetalGraph if 'virtual' not in from_ns_str(msg('name')(self.sysdevice)).lower() else None) + + def synchronize(self): + for cbuf in self.mtl_buffers_in_flight: + wait_check(cbuf) + st, en = decimal.Decimal(cmdbuf_st_time(cbuf)) * 1000000, decimal.Decimal(cmdbuf_en_time(cbuf)) * 1000000 + if PROFILE and (lb:=cmdbuf_label(cbuf)) is not None: + Compiled.profile_events += [ProfileRangeEvent(self.device, lb, st, en, is_copy=lb.startswith("COPY"))] + self.mtl_buffers_in_flight.clear() def metal_src_to_library(device:MetalDevice, src:str) -> objc_instance: - options = msg(libobjc.objc_getClass(b"MTLCompileOptions"), "new", restype=objc_instance) - msg(options, "setFastMathEnabled:", getenv("METAL_FAST_MATH")) - library = msg(device.sysdevice, "newLibraryWithSource:options:error:", to_ns_str(src), options, - ctypes.byref(compileError:=objc_instance()), restype=objc_instance) + options = msg("new", objc_instance)(libobjc.objc_getClass(b"MTLCompileOptions")) + msg("setFastMathEnabled:")(options, getenv("METAL_FAST_MATH")) + library = msg("newLibraryWithSource:options:error:", objc_instance)(device.sysdevice, to_ns_str(src), + options, ctypes.byref(compileError:=objc_instance())) error_check(compileError, CompileError) return library class MetalCompiler(Compiler): + # Opening METAL after LLVM doesn't fail because ctypes.CDLL opens with RTLD_LOCAL but MTLCompiler opens it's own llvm with RTLD_GLOBAL + # This means that MTLCompiler's llvm will create it's own instances of global state because RTLD_LOCAL doesn't export symbols, but if RTLD_GLOBAL + # library is loaded first then RTLD_LOCAL library will just use it's symbols. On linux there is RTLD_DEEPBIND to prevent that, but on macos there + # doesn't seem to be anything we can do. + with contextlib.suppress(FileNotFoundError, ModuleNotFoundError): + import tinygrad.runtime.autogen.llvm # noqa: F401 + support = ctypes.CDLL("/System/Library/PrivateFrameworks/MTLCompiler.framework/MTLCompiler") + support.MTLCodeGenServiceCreate.restype = ctypes.c_void_p + def __init__(self): - self.cgs = ctypes.c_void_p(compiler.MTLCodeGenServiceCreate(b"tinygrad")) + self.cgs = ctypes.c_void_p(MetalCompiler.support.MTLCodeGenServiceCreate(b"tinygrad")) super().__init__("compile_metal_direct") def __reduce__(self): return (MetalCompiler,()) # force pickle to create new instance for each multiprocessing fork def compile(self, src:str) -> bytes: @@ -84,9 +119,14 @@ class MetalCompiler(Compiler): ret = reply[sum(struct.unpack('= 14 else "metal3.0" if macos_major >= 13 else "macos-metal2.0" + # llvm will create modules.timestamp in cache path and cache compilation of metal stdlib (250ms => 8ms compilation time) # note that llvm won't necessarily create anything else here as apple has prebuilt versions of many standard libraries - params = f'-fno-fast-math -std=metal3.1 --driver-mode=metal -x metal -fmodules-cache-path="{cache_dir}"' + params = f'-fno-fast-math -std={metal_version} --driver-mode=metal -x metal -fmodules-cache-path="{cache_dir}" -fno-caret-diagnostics' # source blob has to be padded to multiple of 4 but at least one 'b\x00' should be added, params blob just has to be null terminated src_padded, params_padded = src.encode() + b'\x00'*(round_up(len(src) + 1, 4) - len(src)), params.encode() + b'\x00' request = struct.pack(' cast(int, max_total_threads): - exec_width = msg(self.pipeline_state, "threadExecutionWidth", restype=ctypes.c_ulong) - memory_length = msg(self.pipeline_state, "staticThreadgroupMemoryLength", restype=ctypes.c_ulong) - raise RuntimeError(f"local size {local_size} bigger than {max_total_threads} with exec width {exec_width} memory length {memory_length}") - command_buffer = msg(self.dev.mtl_queue, "commandBuffer", restype=objc_instance) - encoder = msg(command_buffer, "computeCommandEncoder", restype=objc_instance) - msg(encoder, "setComputePipelineState:", self.pipeline_state) - for i,a in enumerate(bufs): msg(encoder, "setBuffer:offset:atIndex:", a.buf, a.offset, i) - for i,a in enumerate(vals, start=len(bufs)): msg(encoder, "setBytes:length:atIndex:", bytes(ctypes.c_int(a)), 4, i) - msg(encoder, "dispatchThreadgroups:threadsPerThreadgroup:", to_struct(*global_size), to_struct(*local_size)) - msg(encoder, "endEncoding") - msg(command_buffer, "setLabel:", to_ns_str(self.name)) - msg(command_buffer, "commit") + if prod(local_size) > self.max_total_threads: + exec_width = msg("threadExecutionWidth", ctypes.c_ulong)(self.pipeline_state) + memory_length = msg("staticThreadgroupMemoryLength", ctypes.c_ulong)(self.pipeline_state) + raise RuntimeError(f"local size {local_size} bigger than {self.max_total_threads} with exec width {exec_width} memory length {memory_length}") + command_buffer = msg("commandBuffer", objc_instance)(self.dev.mtl_queue) + encoder = msg("computeCommandEncoder", objc_instance)(command_buffer) + msg("setComputePipelineState:")(encoder, self.pipeline_state) + for i,a in enumerate(bufs): msg("setBuffer:offset:atIndex:")(encoder, a.buf, a.offset, i) + for i,a in enumerate(vals, start=len(bufs)): msg("setBytes:length:atIndex:")(encoder, bytes(ctypes.c_int(a)), 4, i) + msg("dispatchThreadgroups:threadsPerThreadgroup:")(encoder, to_struct(*global_size), to_struct(*local_size)) + msg("endEncoding")(encoder) + msg("setLabel:")(command_buffer, to_ns_str(self.name)) # TODO: is this always needed? + msg("commit")(command_buffer) self.dev.mtl_buffers_in_flight.append(command_buffer) if wait: wait_check(command_buffer) @@ -148,60 +189,37 @@ class MetalProgram: class MetalBuffer: def __init__(self, buf:Any, size:int, offset=0): self.buf, self.size, self.offset = buf, size, offset -class MetalAllocator(LRUAllocator): - def __init__(self, dev:MetalDevice): - self.dev:MetalDevice = dev - super().__init__() +class MetalAllocator(LRUAllocator[MetalDevice]): def _alloc(self, size:int, options) -> MetalBuffer: + if options.external_ptr: return MetalBuffer(objc_id(options.external_ptr), size) + # Buffer is explicitly released in _free() rather than garbage collected via reference count - ret = msg(self.dev.sysdevice, "newBufferWithLength:options:", ctypes.c_ulong(size), MTLResourceOptions.MTLResourceStorageModeShared, - restype=objc_id) + ret = msg("newBufferWithLength:options:", objc_id)(self.dev.sysdevice, ctypes.c_ulong(size), MTLResourceOptions.MTLResourceStorageModeShared) if ret.value is None: raise MemoryError(f"Metal OOM while allocating {size=}") return MetalBuffer(ret, size) - def _free(self, opaque:MetalBuffer, options): msg(opaque.buf, "release") + def _free(self, opaque:MetalBuffer, options): msg("release")(opaque.buf) def _transfer(self, dest:MetalBuffer, src:MetalBuffer, sz:int, src_dev:MetalDevice, dest_dev:MetalDevice): dest_dev.synchronize() - src_command_buffer = msg(src_dev.mtl_queue, "commandBuffer", restype=objc_instance) - encoder = msg(src_command_buffer, "blitCommandEncoder", restype=objc_instance) - msg(encoder, "copyFromBuffer:sourceOffset:toBuffer:destinationOffset:size:", src.buf, ctypes.c_ulong(src.offset), + src_command_buffer = msg("commandBuffer", objc_instance)(src_dev.mtl_queue) + encoder = msg("blitCommandEncoder", objc_instance)(src_command_buffer) + msg("copyFromBuffer:sourceOffset:toBuffer:destinationOffset:size:")(encoder, src.buf, ctypes.c_ulong(src.offset), dest.buf, ctypes.c_ulong(dest.offset), ctypes.c_ulong(sz)) - msg(encoder, "endEncoding") + msg("endEncoding")(encoder) if src_dev != dest_dev: - msg(src_command_buffer, "encodeSignalEvent:value:", src_dev.timeline_signal, src_dev.timeline_value) - dest_command_buffer = msg(dest_dev.mtl_queue, "commandBuffer", restype=objc_instance) - msg(dest_command_buffer, "encodeWaitForEvent:value:", src_dev.timeline_signal, src_dev.timeline_value) - msg(dest_command_buffer, "commit") + msg("encodeSignalEvent:value:")(src_command_buffer, src_dev.timeline_signal, src_dev.timeline_value) + dest_command_buffer = msg("commandBuffer", objc_instance)(dest_dev.mtl_queue) + msg("encodeWaitForEvent:value:")(dest_command_buffer, src_dev.timeline_signal, src_dev.timeline_value) + msg("commit")(dest_command_buffer) dest_dev.mtl_buffers_in_flight.append(dest_command_buffer) src_dev.timeline_value += 1 - msg(src_command_buffer, "commit") + msg("setLabel:")(src_command_buffer, to_ns_str(f"COPY {src_dev.device} -> {dest_dev.device}")) + msg("commit")(src_command_buffer) src_dev.mtl_buffers_in_flight.append(src_command_buffer) def _cp_mv(self, dst, src, prof_desc): with cpu_profile(prof_desc, self.dev.device, is_copy=True): dst[:] = src def _as_buffer(self, src:MetalBuffer) -> memoryview: self.dev.synchronize() - return to_mv(cast(int, msg(src.buf, "contents", restype=objc_id).value), src.size + src.offset)[src.offset:] + return to_mv(cast(int, msg("contents", objc_id)(src.buf).value), src.size + src.offset)[src.offset:] def _copyin(self, dest:MetalBuffer, src:memoryview): self._cp_mv(self._as_buffer(dest), src, "CPU -> METAL") def _copyout(self, dest:memoryview, src:MetalBuffer): self._cp_mv(dest, self._as_buffer(src), "METAL -> CPU") def _offset(self, buf:MetalBuffer, size:int, offset:int): return MetalBuffer(buf.buf, size, offset) - -class MetalDevice(Compiled): - def __init__(self, device:str): - self.sysdevice = libmetal.MTLCreateSystemDefaultDevice() - self.mtl_queue = msg(self.sysdevice, "newCommandQueueWithMaxCommandBufferCount:", 1024, restype=objc_instance) - if self.mtl_queue is None: raise RuntimeError("Cannot allocate a new command queue") - self.mtl_buffers_in_flight: list[Any] = [] - self.timeline_signal = msg(self.sysdevice, "newSharedEvent", restype=objc_instance) - self.timeline_value = 0 - - Compiled.profile_events += [ProfileDeviceEvent(device)] - - from tinygrad.runtime.graph.metal import MetalGraph - super().__init__(device, MetalAllocator(self), MetalRenderer(), MetalCompiler() if getenv("METAL_DIRECT", 1) else Compiler(), - functools.partial(MetalProgram, self), MetalGraph) - - def synchronize(self): - for cbuf in self.mtl_buffers_in_flight: - wait_check(cbuf) - st, en = decimal.Decimal(cmdbuf_st_time(cbuf)) * 1000000, decimal.Decimal(cmdbuf_en_time(cbuf)) * 1000000 - if PROFILE: Compiled.profile_events += [ProfileRangeEvent(self.device, cmdbuf_label(cbuf), st, en, is_copy=False)] - self.mtl_buffers_in_flight.clear() diff --git a/tinygrad_repo/tinygrad/runtime/ops_npy.py b/tinygrad_repo/tinygrad/runtime/ops_npy.py index d305546b8a..b0e2edf750 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_npy.py +++ b/tinygrad_repo/tinygrad/runtime/ops_npy.py @@ -2,8 +2,9 @@ import numpy as np from tinygrad.helpers import flat_mv from tinygrad.device import Compiled, Allocator -class NpyAllocator(Allocator): - def _copyout(self, dest:memoryview, src:np.ndarray): dest[:] = flat_mv(np.require(src, requirements='C').data) +class NpyAllocator(Allocator['NpyDevice']): + def _as_buffer(self, src:np.ndarray) -> memoryview: return flat_mv(np.require(src, requirements='C').data) + def _copyout(self, dest:memoryview, src:np.ndarray): dest[:] = self._as_buffer(src) class NpyDevice(Compiled): - def __init__(self, device:str): super().__init__(device, NpyAllocator(), None, None, None) + def __init__(self, device:str): super().__init__(device, NpyAllocator(self), None, None, None) diff --git a/tinygrad_repo/tinygrad/runtime/ops_null.py b/tinygrad_repo/tinygrad/runtime/ops_null.py new file mode 100644 index 0000000000..569888d8c5 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/ops_null.py @@ -0,0 +1,26 @@ +from tinygrad.device import Compiled, Compiler, Renderer, Allocator +from tinygrad.uop.ops import Ops +from tinygrad.engine.jit import MultiGraphRunner + +class NullRenderer(Renderer): + device = "NULL" + code_for_op = {k:lambda:None for k in [Ops.EXP2, Ops.LOG2, Ops.SIN, Ops.SQRT]} + has_local = False + def render(self, uops:list) -> str: return "" + +class NullProgram: + def __init__(self, name:str, lib:bytes): pass + def __call__(self, *bufs, global_size:tuple[int,int,int]=(1,1,1), local_size:tuple[int,int,int]=(1,1,1), vals:tuple[int, ...]=(), wait=False): + return 1e-4 + +class NullAllocator(Allocator['NullDevice']): + def _alloc(self, size, options): pass + def _copyin(self, dest, src:memoryview): pass + def _copyout(self, dest:memoryview, src): pass + def _transfer(self, dest, src, sz:int, src_dev, dest_dev): pass + +class NullGraph(MultiGraphRunner): + def __call__(self, input_rawbuffers, var_vals, wait=False) -> float|None: return 1e-3 + +class NullDevice(Compiled): + def __init__(self, device:str): super().__init__(device, NullAllocator(self), NullRenderer(), Compiler(), NullProgram, NullGraph) diff --git a/tinygrad_repo/tinygrad/runtime/ops_nv.py b/tinygrad_repo/tinygrad/runtime/ops_nv.py index d2395e97db..c2d1d09b14 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_nv.py +++ b/tinygrad_repo/tinygrad/runtime/ops_nv.py @@ -1,27 +1,27 @@ from __future__ import annotations -import os, ctypes, contextlib, re, fcntl, functools, mmap, struct, array, sys +import os, ctypes, contextlib, re, functools, mmap, struct, array, sys, weakref assert sys.platform != 'win32' -from typing import Any, cast, Union, Type, Optional +from typing import Any, cast, Union, Type, ClassVar from dataclasses import dataclass from tinygrad.runtime.support.hcq import HCQCompiled, HCQAllocator, HCQBuffer, HWQueue, CLikeArgsState, HCQProgram, HCQSignal, BumpAllocator -from tinygrad.ops import sint -from tinygrad.device import BufferSpec -from tinygrad.helpers import getenv, mv_address, init_c_struct_t, to_mv, round_up, data64, data64_le, DEBUG, prod +from tinygrad.runtime.support.hcq import MMIOInterface, FileIOInterface, MOCKGPU +from tinygrad.uop.ops import sint +from tinygrad.device import BufferSpec, CPUProgram +from tinygrad.helpers import getenv, mv_address, init_c_struct_t, round_up, data64, data64_le, DEBUG, prod, OSX from tinygrad.renderer.ptx import PTXRenderer from tinygrad.renderer.cstyle import NVRenderer from tinygrad.runtime.support.compiler_cuda import CUDACompiler, PTXCompiler, PTX, NVPTXCompiler, NVCompiler -from tinygrad.runtime.autogen import nv_gpu, libc +from tinygrad.runtime.autogen import nv_gpu from tinygrad.runtime.support.elf import elf_loader if getenv("IOCTL"): import extra.nv_gpu_driver.nv_ioctl # noqa: F401 # pylint: disable=unused-import -if MOCKGPU:=getenv("MOCKGPU"): import extra.mockgpu.mockgpu # noqa: F401 # pylint: disable=unused-import def get_error_str(status): return f"{status}: {nv_gpu.nv_status_codes.get(status, 'Unknown error')}" NV_PFAULT_FAULT_TYPE = {dt:name for name,dt in nv_gpu.__dict__.items() if name.startswith("NV_PFAULT_FAULT_TYPE_")} NV_PFAULT_ACCESS_TYPE = {dt:name.split("_")[-1] for name,dt in nv_gpu.__dict__.items() if name.startswith("NV_PFAULT_ACCESS_TYPE_")} -def nv_iowr(fd, nr, args): - ret = fcntl.ioctl(fd, (3 << 30) | (ctypes.sizeof(args) & 0x1FFF) << 16 | (ord('F') & 0xFF) << 8 | (nr & 0xFF), args) +def nv_iowr(fd:FileIOInterface, nr, args): + ret = fd.ioctl((3 << 30) | (ctypes.sizeof(args) & 0x1FFF) << 16 | (ord('F') & 0xFF) << 8 | (nr & 0xFF), args) if ret != 0: raise RuntimeError(f"ioctl returned {ret}") def rm_alloc(fd, clss, root, parant, params): @@ -46,8 +46,8 @@ def make_rmctrl_type(): getattr(nv_gpu, name+"_PARAMS", getattr(nv_gpu, name.replace("_CTRL_CMD_", "_CTRL_DEBUG_")+"_PARAMETERS", None))))}) rmctrl = make_rmctrl_type() -def uvm_ioctl(cmd, sttyp, fd, **kwargs): - ret = fcntl.ioctl(fd, cmd, made:=sttyp(**kwargs)) +def uvm_ioctl(cmd, sttyp, fd:FileIOInterface, **kwargs): + ret = fd.ioctl(cmd, made:=sttyp(**kwargs)) if ret != 0: raise RuntimeError(f"ioctl(uvm) returned {ret}") if made.rmStatus != 0: raise RuntimeError(f"uvm_ioctl returned {get_error_str(made.rmStatus)}") return made @@ -72,11 +72,8 @@ qmd_struct_t = make_qmd_struct_type() assert ctypes.sizeof(qmd_struct_t) == 0x40 * 4 class NVSignal(HCQSignal): - def __init__(self, base_addr:Optional[int]=None, **kwargs): - super().__init__(NVDevice.signals_pool.pop() if base_addr is None else base_addr, **kwargs, timestamp_divider=1000, value_off=0, timestamp_off=8) - - def __del__(self): - if isinstance(self.base_addr, int): NVDevice.signals_pool.append(self.base_addr) + def __init__(self, base_buf:HCQBuffer|None=None, **kwargs): + super().__init__(base_buf, **kwargs, timestamp_divider=1000, dev_t=NVDevice) class NVCommandQueue(HWQueue[NVSignal, 'NVDevice', 'NVProgram', 'NVArgsState']): def __init__(self): @@ -107,7 +104,7 @@ class NVCommandQueue(HWQueue[NVSignal, 'NVDevice', 'NVProgram', 'NVArgsState']): def bind(self, dev:NVDevice): self.binded_device = dev self.hw_page = dev.allocator.alloc(len(self._q) * 4, BufferSpec(cpu_access=True, nolru=True)) - hw_view = to_mv(self.hw_page.va_addr, self.hw_page.size).cast("I") + hw_view = self.hw_page.cpu_view().view(fmt='I') for i, value in enumerate(self._q): hw_view[i] = value # From now on, the queue is on the device for faster submission. @@ -122,6 +119,8 @@ class NVCommandQueue(HWQueue[NVSignal, 'NVDevice', 'NVProgram', 'NVArgsState']): gpfifo.ring[gpfifo.put_value % gpfifo.entries_count] = (cmdq_addr//4 << 2) | (len(self._q) << 42) | (1 << 41) gpfifo.controls.GPPut = (gpfifo.put_value + 1) % gpfifo.entries_count + + if CPUProgram.atomic_lib is not None: CPUProgram.atomic_lib.atomic_thread_fence(__ATOMIC_SEQ_CST:=5) dev.gpu_mmio[0x90 // 4] = gpfifo.token gpfifo.put_value += 1 @@ -134,25 +133,27 @@ class NVComputeQueue(NVCommandQueue): def exec(self, prg:NVProgram, args_state:NVArgsState, global_size:tuple[sint, ...], local_size:tuple[sint, ...]): self.bind_args_state(args_state) - ctypes.memmove(qmd_addr:=(args_state.ptr + round_up(prg.constbufs[0][1], 1 << 8)), ctypes.addressof(prg.qmd), 0x40 * 4) - assert qmd_addr < (1 << 40), f"large qmd addr {qmd_addr:x}" + qmd_buf = args_state.buf.offset(round_up(prg.constbufs[0][1], 1 << 8)) + qmd_buf.cpu_view().view(size=0x40 * 4, fmt='B')[:] = bytes(prg.qmd) + assert qmd_buf.va_addr < (1 << 40), f"large qmd addr {qmd_buf.va_addr:x}" - qmd = qmd_struct_t.from_address(qmd_addr) # Save qmd for later update + qmd = qmd_struct_t.from_address(qmd_buf.va_addr) # Save qmd for later update - self.bind_sints_to_ptr(*global_size, ptr=qmd_addr + nv_gpu.NVC6C0_QMDV03_00_CTA_RASTER_WIDTH[1] // 8, fmt='I') - self.bind_sints_to_ptr(*local_size, ptr=qmd_addr + nv_gpu.NVC6C0_QMDV03_00_CTA_THREAD_DIMENSION0[1] // 8, fmt='H') - qmd.constant_buffer_addr_upper_0, qmd.constant_buffer_addr_lower_0 = data64(args_state.ptr) + self.bind_sints_to_mem(*global_size, mem=qmd_buf.cpu_view(), fmt='I', offset=nv_gpu.NVC6C0_QMDV03_00_CTA_RASTER_WIDTH[1] // 8) + self.bind_sints_to_mem(*local_size, mem=qmd_buf.cpu_view(), fmt='H', offset=nv_gpu.NVC6C0_QMDV03_00_CTA_THREAD_DIMENSION0[1] // 8) + self.bind_sints_to_mem(*local_size, *global_size, mem=args_state.buf.cpu_view(), fmt='I') + qmd.constant_buffer_addr_upper_0, qmd.constant_buffer_addr_lower_0 = data64(args_state.buf.va_addr) if self.active_qmd is None: - self.nvm(1, nv_gpu.NVC6C0_SEND_PCAS_A, qmd_addr >> 8) + self.nvm(1, nv_gpu.NVC6C0_SEND_PCAS_A, qmd_buf.va_addr >> 8) self.nvm(1, nv_gpu.NVC6C0_SEND_SIGNALING_PCAS2_B, 9) else: - self.active_qmd.dependent_qmd0_pointer = qmd_addr >> 8 + self.active_qmd.dependent_qmd0_pointer = qmd_buf.va_addr >> 8 self.active_qmd.dependent_qmd0_action = 1 self.active_qmd.dependent_qmd0_prefetch = 1 self.active_qmd.dependent_qmd0_enable = 1 - self.active_qmd = qmd + self.active_qmd, self.active_qmd_buf = qmd, qmd_buf return self def signal(self, signal:NVSignal, value:sint=0): @@ -160,8 +161,9 @@ class NVComputeQueue(NVCommandQueue): for i in range(2): if getattr(self.active_qmd, f'release{i}_enable') == 0: setattr(self.active_qmd, f'release{i}_enable', 1) - self.bind_sints(signal.value_addr, struct=self.active_qmd, start_field=f'release{i}_address', fmt='Q', mask=0xfffffffff) - self.bind_sints(value, struct=self.active_qmd, start_field=f'release{i}_payload', fmt='Q') + self.bind_sints(signal.value_addr, mem=self.active_qmd_buf.cpu_view(), struct_t=qmd_struct_t, start_field=f'release{i}_address', + fmt='Q', mask=0xfffffffff) + self.bind_sints(value, mem=self.active_qmd_buf.cpu_view(), struct_t=qmd_struct_t, start_field=f'release{i}_payload', fmt='Q') return self self.nvm(0, nv_gpu.NVC56F_SEM_ADDR_LO, *data64_le(signal.value_addr), *data64_le(value), @@ -174,9 +176,10 @@ class NVComputeQueue(NVCommandQueue): class NVCopyQueue(NVCommandQueue): def copy(self, dest:sint, src:sint, copy_size:int): - self.nvm(4, nv_gpu.NVC6B5_OFFSET_IN_UPPER, *data64(src), *data64(dest)) - self.nvm(4, nv_gpu.NVC6B5_LINE_LENGTH_IN, copy_size) - self.nvm(4, nv_gpu.NVC6B5_LAUNCH_DMA, 0x182) # TRANSFER_TYPE_NON_PIPELINED | DST_MEMORY_LAYOUT_PITCH | SRC_MEMORY_LAYOUT_PITCH + for off in range(0, copy_size, step:=(1 << 31)): + self.nvm(4, nv_gpu.NVC6B5_OFFSET_IN_UPPER, *data64(src+off), *data64(dest+off)) + self.nvm(4, nv_gpu.NVC6B5_LINE_LENGTH_IN, min(copy_size-off, step)) + self.nvm(4, nv_gpu.NVC6B5_LAUNCH_DMA, 0x182) # TRANSFER_TYPE_NON_PIPELINED | DST_MEMORY_LAYOUT_PITCH | SRC_MEMORY_LAYOUT_PITCH return self def signal(self, signal:NVSignal, value:sint=0): @@ -187,19 +190,22 @@ class NVCopyQueue(NVCommandQueue): def _submit(self, dev:NVDevice): self._submit_to_gpfifo(dev, dev.dma_gpfifo) class NVArgsState(CLikeArgsState): - def __init__(self, ptr:int, prg:NVProgram, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=()): - if MOCKGPU: prg.constbuffer_0[0:2] = [len(bufs), len(vals)] - super().__init__(ptr, prg, bufs, vals=vals, prefix=prg.constbuffer_0) + def __init__(self, buf:HCQBuffer, prg:NVProgram, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=()): + if MOCKGPU: prg.constbuffer_0[80:82] = [len(bufs), len(vals)] + super().__init__(buf, prg, bufs, vals=vals, prefix=prg.constbuffer_0) class NVProgram(HCQProgram): def __init__(self, dev:NVDevice, name:str, lib:bytes): self.dev, self.name, self.lib = dev, name, lib + # For MOCKGPU, the lib is PTX code, so some values are emulated. + cbuf0_size = 0 if not MOCKGPU else 0x160 + if MOCKGPU: image, sections, relocs = memoryview(bytearray(lib) + b'\x00' * (4 - len(lib)%4)).cast("I"), [], [] # type: ignore else: image, sections, relocs = elf_loader(self.lib, force_section_align=128) # NOTE: Ensure at least 4KB of space after the program to mitigate prefetch memory faults. - self.lib_gpu = self.dev.allocator.alloc(round_up(image.nbytes, 0x1000) + 0x1000, BufferSpec(cpu_access=True)) + self.lib_gpu = self.dev.allocator.alloc(round_up(image.nbytes, 0x1000) + 0x1000, buf_spec:=BufferSpec(cpu_access=True)) self.prog_addr, self.prog_sz, self.regs_usage, self.shmem_usage, self.lcmem_usage = self.lib_gpu.va_addr, image.nbytes, 0, 0x400, 0 self.constbufs: dict[int, tuple[int, int]] = {0: (0, 0x160)} # dict[constbuf index, tuple[va_addr, size]] @@ -208,10 +214,10 @@ class NVProgram(HCQProgram): if sh.name == f".text.{self.name}": self.prog_addr, self.prog_sz, self.regs_usage = self.lib_gpu.va_addr+sh.header.sh_addr, sh.header.sh_size, max(sh.header.sh_info>>24, 16) elif m:=re.match(r'\.nv\.constant(\d+)', sh.name): self.constbufs[int(m.group(1))] = (self.lib_gpu.va_addr+sh.header.sh_addr, sh.header.sh_size) - elif sh.name == ".nv.info": - for off in range(0, sh.header.sh_size, 12): - typ, _, val = struct.unpack_from("III", sh.content, off) - if typ & 0xffff == 0x1204: self.lcmem_usage = val + 0x240 + elif sh.name.startswith(".nv.info"): + for typ, param, data in self._parse_elf_info(sh): + if sh.name == f".nv.info.{name}" and param == 0xa: cbuf0_size = struct.unpack_from("IH", data)[1] # EIATTR_PARAM_CBANK + elif sh.name == ".nv.info" and param == 0x12: self.lcmem_usage = struct.unpack_from("II", data)[1] + 0x240 # EIATTR_MIN_STACK_SIZE # Ensure device has enough local memory to run the program self.dev._ensure_has_local_memory(self.lcmem_usage) @@ -226,7 +232,7 @@ class NVProgram(HCQProgram): ctypes.memmove(self.lib_gpu.va_addr, mv_address(image), image.nbytes) - self.constbuffer_0 = [0] * 88 + self.constbuffer_0 = [0] * (cbuf0_size // 4) self.constbuffer_0[6:12] = [*data64_le(self.dev.shared_mem_window), *data64_le(self.dev.local_mem_window), *data64_le(0xfffdc0)] smem_cfg = min(shmem_conf * 1024 for shmem_conf in [32, 64, 100] if shmem_conf * 1024 >= self.shmem_usage) // 4096 + 1 @@ -245,18 +251,22 @@ class NVProgram(HCQProgram): self.qmd.__setattr__(f'constant_buffer_size_shifted4_{i}', sz) self.qmd.__setattr__(f'constant_buffer_valid_{i}', 1) - # Registers allocation granularity per warp is 256, warp allocaiton granularity is 4. Register file size is 65536. + # Registers allocation granularity per warp is 256, warp allocation granularity is 4. Register file size is 65536. self.max_threads = ((65536 // round_up(max(1, self.regs_usage) * 32, 256)) // 4) * 4 * 32 - # NV's kernargs is constbuffer (size 0x160), then arguments to the kernel follows. Kernargs also appends QMD at the end of the kernel. + # NV's kernargs is constbuffer, then arguments to the kernel follows. Kernargs also appends QMD at the end of the kernel. super().__init__(NVArgsState, self.dev, self.name, kernargs_alloc_size=round_up(self.constbufs[0][1], 1 << 8) + (8 << 8)) + weakref.finalize(self, self._fini, self.dev, self.lib_gpu, buf_spec) - def __del__(self): - if hasattr(self, 'lib_gpu'): self.dev.allocator.free(self.lib_gpu, self.lib_gpu.size, BufferSpec(cpu_access=True)) + def _parse_elf_info(self, sh, start_off=0): + while start_off < sh.header.sh_size: + typ, param, sz = struct.unpack_from("BBH", sh.content, start_off) + yield typ, param, sh.content[start_off+4:start_off+sz+4] if typ == 0x4 else sz + start_off += (sz if typ == 0x4 else 0) + 4 def __call__(self, *bufs, global_size:tuple[int,int,int]=(1,1,1), local_size:tuple[int,int,int]=(1,1,1), vals:tuple[int, ...]=(), wait=False): if prod(local_size) > 1024 or self.max_threads < prod(local_size) or self.lcmem_usage > cast(NVDevice, self.dev).slm_per_thread: - raise RuntimeError("Too many resources requested for launch") + raise RuntimeError(f"Too many resources requested for launch, {prod(local_size)=}, {self.max_threads=}") if any(cur > mx for cur,mx in zip(global_size, [2147483647, 65535, 65535])) or any(cur > mx for cur,mx in zip(local_size, [1024, 1024, 64])): raise RuntimeError(f"Invalid global/local dims {global_size=}, {local_size=}") return super().__call__(*bufs, global_size=global_size, local_size=local_size, vals=vals, wait=wait) @@ -274,7 +284,7 @@ class NVAllocator(HCQAllocator['NVDevice']): @dataclass class GPFifo: - ring: memoryview + ring: MMIOInterface controls: nv_gpu.AmpereAControlGPFifo entries_count: int token: int @@ -282,43 +292,43 @@ class GPFifo: MAP_FIXED, MAP_NORESERVE = 0x10, 0x400 class NVDevice(HCQCompiled[NVSignal]): + devices: ClassVar[list[HCQCompiled]] = [] + signal_pages: ClassVar[list[HCQBuffer]] = [] + signal_pool: ClassVar[list[HCQBuffer]] = [] + root = None - fd_ctl: int = -1 - fd_uvm: int = -1 + fd_ctl: FileIOInterface + fd_uvm: FileIOInterface gpus_info: Union[list, ctypes.Array] = [] - signals_page: Any = None - signals_pool: list[int] = [] # TODO: Need a proper allocator for va addresses # 0x1000000000 - 0x2000000000, reserved for system/cpu mappings # VA space is 48bits. - low_uvm_vaddr_allocator: BumpAllocator = BumpAllocator(size=0x1000000000, start=0x1000000000, wrap=False) - uvm_vaddr_allocator: BumpAllocator = BumpAllocator(size=(1 << 48) - 1, start=0x2000000000, wrap=False) + low_uvm_vaddr_allocator: BumpAllocator = BumpAllocator(size=0x1000000000, base=0x8000000000 if OSX else 0x1000000000, wrap=False) + uvm_vaddr_allocator: BumpAllocator = BumpAllocator(size=(1 << 48) - 1, base=low_uvm_vaddr_allocator.base + low_uvm_vaddr_allocator.size, wrap=False) host_object_enumerator: int = 0x1000 def _new_gpu_fd(self): - fd_dev = os.open(f"/dev/nvidia{NVDevice.gpus_info[self.device_id].minor_number}", os.O_RDWR | os.O_CLOEXEC) - nv_iowr(fd_dev, nv_gpu.NV_ESC_REGISTER_FD, nv_gpu.nv_ioctl_register_fd_t(ctl_fd=self.fd_ctl)) + fd_dev = FileIOInterface(f"/dev/nvidia{NVDevice.gpus_info[self.device_id].minor_number}", os.O_RDWR | os.O_CLOEXEC) + nv_iowr(fd_dev, nv_gpu.NV_ESC_REGISTER_FD, nv_gpu.nv_ioctl_register_fd_t(ctl_fd=self.fd_ctl.fd)) return fd_dev def _gpu_map_to_cpu(self, memory_handle, size, target=None, flags=0, system=False): - fd_dev = self._new_gpu_fd() if not system else os.open("/dev/nvidiactl", os.O_RDWR | os.O_CLOEXEC) - made = nv_gpu.nv_ioctl_nvos33_parameters_with_fd(fd=fd_dev, + fd_dev = self._new_gpu_fd() if not system else FileIOInterface("/dev/nvidiactl", os.O_RDWR | os.O_CLOEXEC) + made = nv_gpu.nv_ioctl_nvos33_parameters_with_fd(fd=fd_dev.fd, params=nv_gpu.NVOS33_PARAMETERS(hClient=self.root, hDevice=self.nvdevice, hMemory=memory_handle, length=size, flags=flags)) nv_iowr(self.fd_ctl, nv_gpu.NV_ESC_RM_MAP_MEMORY, made) if made.params.status != 0: raise RuntimeError(f"_gpu_map_to_cpu returned {get_error_str(made.params.status)}") - res = libc.mmap(target, size, mmap.PROT_READ|mmap.PROT_WRITE, mmap.MAP_SHARED | (MAP_FIXED if target is not None else 0), fd_dev, 0) - os.close(fd_dev) - return res + return fd_dev.mmap(target, size, mmap.PROT_READ|mmap.PROT_WRITE, mmap.MAP_SHARED | (MAP_FIXED if target is not None else 0), 0) def _gpu_alloc(self, size:int, host=False, uncached=False, cpu_access=False, contiguous=False, map_flags=0, tag="") -> HCQBuffer: # Uncached memory is "system". Use huge pages only for gpu memory. - page_size = (4 << 10) if uncached or host else ((2 << 20) if size >= (8 << 20) else (4 << 10)) + page_size = (4 << (12 if OSX else 10)) if uncached or host else ((2 << 20) if size >= (8 << 20) else (4 << (12 if OSX else 10))) size = round_up(size, page_size) va_addr = self._alloc_gpu_vaddr(size, alignment=page_size, force_low=cpu_access) if host: - va_addr = libc.mmap(va_addr, size, mmap.PROT_READ | mmap.PROT_WRITE, MAP_FIXED | mmap.MAP_SHARED | mmap.MAP_ANONYMOUS, -1, 0) + va_addr = FileIOInterface.anon_mmap(va_addr, size, mmap.PROT_READ | mmap.PROT_WRITE, MAP_FIXED | mmap.MAP_SHARED | mmap.MAP_ANONYMOUS, 0) flags = (nv_gpu.NVOS02_FLAGS_PHYSICALITY_NONCONTIGUOUS << 4) | (nv_gpu.NVOS02_FLAGS_COHERENCY_CACHED << 12) \ | (nv_gpu.NVOS02_FLAGS_MAPPING_NO_MAP << 30) @@ -357,16 +367,18 @@ class NVDevice(HCQCompiled[NVSignal]): self._debug_mappings.pop((cast(int, mem.va_addr), mem.size)) uvm.free(self.fd_uvm, base=cast(int, mem.va_addr), length=mem.size) - if mem.meta.has_cpu_mapping: libc.munmap(cast(int, mem.va_addr), mem.size) + if mem.meta.has_cpu_mapping: FileIOInterface.munmap(cast(int, mem.va_addr), mem.size) def _gpu_uvm_map(self, va_base, size, mem_handle, create_range=True, has_cpu_mapping=False, tag="") -> HCQBuffer: if create_range: uvm.create_external_range(self.fd_uvm, base=va_base, length=size) attrs = (nv_gpu.struct_c__SA_UvmGpuMappingAttributes*256)(nv_gpu.struct_c__SA_UvmGpuMappingAttributes(gpuUuid=self.gpu_uuid, gpuMappingType=1)) - # NOTE: va_addr is set to make rawbufs compatable with HCQBuffer protocol. + # NOTE: va_addr is set to make rawbufs compatible with HCQBuffer protocol. self._debug_mappings[(va_base, size)] = tag - return HCQBuffer(va_base, size, meta=uvm.map_external_allocation(self.fd_uvm, base=va_base, length=size, rmCtrlFd=self.fd_ctl, hClient=self.root, - hMemory=mem_handle, gpuAttributesCount=1, perGpuAttributes=attrs, mapped_gpu_ids=[self.gpu_uuid], has_cpu_mapping=has_cpu_mapping)) + return HCQBuffer(va_base, size, meta=uvm.map_external_allocation(self.fd_uvm, base=va_base, length=size, rmCtrlFd=self.fd_ctl.fd, + hClient=self.root, hMemory=mem_handle, gpuAttributesCount=1, perGpuAttributes=attrs, + mapped_gpu_ids=[self.gpu_uuid], has_cpu_mapping=has_cpu_mapping), + view=MMIOInterface(va_base, size, fmt='B') if has_cpu_mapping else None) def _gpu_map(self, mem:HCQBuffer): if self.gpu_uuid in mem.meta.mapped_gpu_ids: return @@ -384,12 +396,12 @@ class NVDevice(HCQCompiled[NVSignal]): def __init__(self, device:str=""): if NVDevice.root is None: - NVDevice.fd_ctl = os.open("/dev/nvidiactl", os.O_RDWR | os.O_CLOEXEC) - NVDevice.fd_uvm = os.open("/dev/nvidia-uvm", os.O_RDWR | os.O_CLOEXEC) - fd_uvm_2 = os.open("/dev/nvidia-uvm", os.O_RDWR | os.O_CLOEXEC) + NVDevice.fd_ctl = FileIOInterface("/dev/nvidiactl", os.O_RDWR | os.O_CLOEXEC) + NVDevice.fd_uvm = FileIOInterface("/dev/nvidia-uvm", os.O_RDWR | os.O_CLOEXEC) + self.fd_uvm_2 = FileIOInterface("/dev/nvidia-uvm", os.O_RDWR | os.O_CLOEXEC) NVDevice.root = rm_alloc(self.fd_ctl, nv_gpu.NV01_ROOT_CLIENT, 0, 0, None).hObjectNew uvm.initialize(self.fd_uvm) - with contextlib.suppress(RuntimeError): uvm.mm_initialize(fd_uvm_2, uvmFd=self.fd_uvm) # this error is okay, CUDA hits it too + with contextlib.suppress(RuntimeError): uvm.mm_initialize(self.fd_uvm_2, uvmFd=self.fd_uvm.fd) # this error is okay, CUDA hits it too nv_iowr(NVDevice.fd_ctl, nv_gpu.NV_ESC_CARD_INFO, gpus_info:=(nv_gpu.nv_ioctl_card_info_t*64)()) visible_devices = [int(x) for x in (getenv('VISIBLE_DEVICES', getenv('CUDA_VISIBLE_DEVICES', ''))).split(',') if x.strip()] @@ -409,7 +421,7 @@ class NVDevice(HCQCompiled[NVSignal]): self.nvdevice = rm_alloc(self.fd_ctl, nv_gpu.NV01_DEVICE_0, self.root, self.root, device_params).hObjectNew self.subdevice = rm_alloc(self.fd_ctl, nv_gpu.NV20_SUBDEVICE_0, self.root, self.nvdevice, None).hObjectNew self.usermode = rm_alloc(self.fd_ctl, nv_gpu.TURING_USERMODE_A, self.root, self.subdevice, None).hObjectNew - self.gpu_mmio = to_mv(self._gpu_map_to_cpu(self.usermode, mmio_sz:=0x10000, flags=2), mmio_sz).cast("I") + self.gpu_mmio = MMIOInterface(self._gpu_map_to_cpu(self.usermode, mmio_sz:=0x10000, flags=2), mmio_sz, fmt='I') self._setup_nvclasses() self._debug_mappings: dict[tuple[int, int], str] = dict() @@ -425,17 +437,12 @@ class NVDevice(HCQCompiled[NVSignal]): self.gpu_uuid = nv_gpu.struct_nv_uuid(uuid=(ctypes.c_ubyte*16)(*[raw_uuid.data[i] for i in range(16)])) uvm.register_gpu(self.fd_uvm, rmCtrlFd=-1, gpu_uuid=self.gpu_uuid) - uvm.register_gpu_vaspace(self.fd_uvm, gpuUuid=self.gpu_uuid, rmCtrlFd=self.fd_ctl, hClient=self.root, hVaSpace=vaspace) + uvm.register_gpu_vaspace(self.fd_uvm, gpuUuid=self.gpu_uuid, rmCtrlFd=self.fd_ctl.fd, hClient=self.root, hVaSpace=vaspace) for dev in cast(list[NVDevice], self.devices): try: uvm.enable_peer_access(self.fd_uvm, gpuUuidA=self.gpu_uuid, gpuUuidB=dev.gpu_uuid) except RuntimeError as e: raise RuntimeError(str(e) + f". Make sure GPUs #{self.gpu_minor} & #{dev.gpu_minor} have P2P enabled between.") from e - if NVDevice.signals_page is None: - NVDevice.signals_page = self._gpu_alloc(16 * 65536, cpu_access=True, uncached=True) - NVDevice.signals_pool = [self.signals_page.va_addr + off for off in range(0, NVDevice.signals_page.size, 16)] - else: self._gpu_map(NVDevice.signals_page) - channel_params = nv_gpu.NV_CHANNEL_GROUP_ALLOCATION_PARAMETERS(engineType=nv_gpu.NV2080_ENGINE_TYPE_GRAPHICS) channel_group = rm_alloc(self.fd_ctl, nv_gpu.KEPLER_CHANNEL_GROUP_A, self.root, self.nvdevice, channel_params).hObjectNew @@ -450,8 +457,8 @@ class NVDevice(HCQCompiled[NVSignal]): rmctrl.gpfifo_schedule(self.fd_ctl, self.root, channel_group, bEnable=1) self.cmdq_page:HCQBuffer = self._gpu_alloc(0x200000, cpu_access=True, tag="cmdq") - self.cmdq_allocator = BumpAllocator(size=self.cmdq_page.size, start=cast(int, self.cmdq_page.va_addr), wrap=True) - self.cmdq: memoryview = to_mv(cast(int, self.cmdq_page.va_addr), 0x200000).cast("I") + self.cmdq_allocator = BumpAllocator(size=self.cmdq_page.size, base=cast(int, self.cmdq_page.va_addr), wrap=True) + self.cmdq = MMIOInterface(cast(int, self.cmdq_page.va_addr), 0x200000, fmt='I') self.num_gpcs, self.num_tpc_per_gpc, self.num_sm_per_tpc, self.max_warps_per_sm, self.sm_version = self._query_gpu_info('num_gpcs', 'num_tpc_per_gpc', 'num_sm_per_tpc', 'max_warps_per_sm', 'sm_version') @@ -481,10 +488,10 @@ class NVDevice(HCQCompiled[NVSignal]): assert ws_token_params.workSubmitToken != -1 channel_base = self._alloc_gpu_vaddr(0x4000000, force_low=True) - uvm.register_channel(self.fd_uvm, gpuUuid=self.gpu_uuid, rmCtrlFd=self.fd_ctl, hClient=self.root, + uvm.register_channel(self.fd_uvm, gpuUuid=self.gpu_uuid, rmCtrlFd=self.fd_ctl.fd, hClient=self.root, hChannel=gpfifo, base=channel_base, length=0x4000000) - return GPFifo(ring=to_mv(gpfifo_area.va_addr + offset, entries * 8).cast("Q"), entries_count=entries, token=ws_token_params.workSubmitToken, + return GPFifo(ring=MMIOInterface(gpfifo_area.va_addr + offset, entries*8, fmt='Q'), entries_count=entries, token=ws_token_params.workSubmitToken, controls=nv_gpu.AmpereAControlGPFifo.from_address(gpfifo_area.va_addr + offset + entries * 8)) def _query_gpu_info(self, *reqs): @@ -509,22 +516,16 @@ class NVDevice(HCQCompiled[NVSignal]): def _ensure_has_local_memory(self, required): if self.slm_per_thread >= required or ((maxlm:=getenv("NV_MAX_LOCAL_MEMORY_PER_THREAD")) > 0 and required >= maxlm): return - if self.shader_local_mem is not None: self.allocator.free(self.shader_local_mem, self.shader_local_mem.size) - self.slm_per_thread, old_slm_per_thread = round_up(required, 32), self.slm_per_thread bytes_per_tpc = round_up(round_up(self.slm_per_thread * 32, 0x200) * self.max_warps_per_sm * self.num_sm_per_tpc, 0x8000) + self.shader_local_mem, ok = self._realloc(self.shader_local_mem, round_up(bytes_per_tpc*self.num_tpc_per_gpc*self.num_gpcs, 0x20000)) - try: self.shader_local_mem = self.allocator.alloc(round_up(bytes_per_tpc * self.num_tpc_per_gpc * self.num_gpcs, 0x20000)) - except MemoryError: - # If can't allocate a new size, reallocator the old buffer. - self.slm_per_thread = old_slm_per_thread - bytes_per_tpc = round_up(round_up(self.slm_per_thread * 32, 0x200) * self.max_warps_per_sm * self.num_sm_per_tpc, 0x8000) - self.shader_local_mem = self.allocator.alloc(round_up(bytes_per_tpc * self.num_tpc_per_gpc * self.num_gpcs, 0x20000)) + # Realloc failed, restore the old value. + if not ok: self.slm_per_thread = old_slm_per_thread cast(NVComputeQueue, NVComputeQueue().wait(self.timeline_signal, self.timeline_value - 1)) \ .setup(local_mem=self.shader_local_mem.va_addr, local_mem_tpc_bytes=bytes_per_tpc) \ - .signal(self.timeline_signal, self.timeline_value).submit(self) - self.timeline_value += 1 + .signal(self.timeline_signal, self.next_timeline()).submit(self) def invalidate_caches(self): rmctrl.fb_flush_gpu_cache(self.fd_ctl, self.root, self.subdevice, @@ -541,7 +542,7 @@ class NVDevice(HCQCompiled[NVSignal]): if sm_errors.mmuFault.valid: mmu_info = rmctrl.debug_read_mmu_fault_info(self.fd_ctl, self.root, self.debugger) for i in range(mmu_info.count): - pfinfo = mmu_info.mmuFaultInfolist[i] + pfinfo = mmu_info.mmuFaultInfoList[i] report += [f"MMU fault: 0x{pfinfo.faultAddress:X} | {NV_PFAULT_FAULT_TYPE[pfinfo.faultType]} | {NV_PFAULT_ACCESS_TYPE[pfinfo.accessType]}"] if DEBUG >= 5: report += ["GPU mappings:\n"+"\n".join(f"\t0x{x:X} - 0x{x+y-1:X} | {self._debug_mappings[(x,y)]}" for x,y in sorted(self._debug_mappings))] diff --git a/tinygrad_repo/tinygrad/runtime/ops_python.py b/tinygrad_repo/tinygrad/runtime/ops_python.py index 38c56e7744..0cdc598507 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_python.py +++ b/tinygrad_repo/tinygrad/runtime/ops_python.py @@ -2,13 +2,12 @@ # a python uops emulator # works to test the tensor cores, and all the uops in general # this is the (living) definition of uops -import sys from typing import Optional, Any, TYPE_CHECKING -import pickle, base64, itertools, time, struct +import pickle, base64, itertools, time, struct, sys from tinygrad.dtype import DType, dtypes, ImageDType, PtrDType, truncate from tinygrad.helpers import all_same, getenv, flatten, get_single_element from tinygrad.device import Compiled, Compiler, Allocator -from tinygrad.ops import exec_alu, Ops, UOp, GroupOp +from tinygrad.uop.ops import exec_alu, Ops, UOp, GroupOp from tinygrad.renderer import Renderer from tinygrad.renderer.cstyle import CUDARenderer, MetalRenderer, AMDRenderer, IntelRenderer, ClangRenderer @@ -18,8 +17,8 @@ def _load(m, i): return m[i] def load(inp, j=0): - if len(inp) == 3: return [_load(m, x+j if x is not None else None) if gate else default for (m,x),default,gate in zip(*inp)] - return [_load(m, x+j if x is not None else None) for m,x in inp[0]] + if len(inp) == 2: return [_load(m, x+j if x is not None else None) if gate else default for (m,x,gate),default in zip(*inp)] + return [_load(m, x+j if x is not None else None) for m,x,_ in inp[0]] def _store(m, i, v): if i < 0 or i >= len(m): raise IndexError(f"store out of bounds, size is {len(m)}, access is {i}, value is {v}") @@ -41,19 +40,19 @@ class PythonProgram: loop_ends: dict[int, int] = {} while i < len(self.uops): uop, dtype, idp, arg = self.uops[i] - void_ops = {Ops.STORE, Ops.ENDRANGE, Ops.BARRIER, Ops.IF, Ops.ENDIF} + void_ops = {Ops.STORE, Ops.ENDRANGE, Ops.BARRIER, Ops.IF, Ops.ENDIF, Ops.SINK} if uop is Ops.DEFINE_ACC: idp = [idp[0]] inp = [ul[v] for v in idp if self.uops[v][0] not in void_ops] dtp = [dl[v] for v in idp if self.uops[v][0] not in void_ops] if getenv("TRACE"): print(i, uop, dtype, arg, inp, dtp) if uop is Ops.STORE: - if len(inp) == 2: inp.append([True] * len(inp[0])) # set the gate to True + assert len(inp) == 2, "expected store is ([(memory, offset, gate)], [value])" if dtp[1].count > 1: for j,val in enumerate(inp[1]): - for (m,o),v,g in zip(inp[0], val, inp[2]): + for (m,o,g),v in zip(inp[0], val): if g: _store(m, o+j, v) else: - for (m,o),v,g in zip(*inp): + for (m,o,g),v in zip(*inp): if g: _store(m, o, v) i += 1 continue @@ -61,16 +60,16 @@ class PythonProgram: loop_ends[idp[0]] = i i = idp[0] continue - if uop in (Ops.BARRIER, Ops.IF, Ops.ENDIF): + if uop in (Ops.BARRIER, Ops.IF, Ops.ENDIF, Ops.SINK): # in the python emulator, the warp is always in sync i += 1 continue assert dtype is not None, f"{uop} is missing a dtype" dl[i] = dtype if uop in {Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL}: - assert dtype.fmt is not None + assert dtype.fmt is not None and isinstance(dtype, PtrDType) if TYPE_CHECKING or sys.version_info < (3, 12): assert dtype.fmt != "e" - buf = memoryview(bytearray(arg[1]*dtype.itemsize)) if uop is Ops.DEFINE_LOCAL else pbufs.pop(0) + buf = memoryview(bytearray(dtype.size*dtype.itemsize)) if uop is Ops.DEFINE_LOCAL else pbufs.pop(0) ul[i] = [buf.cast(dtype.fmt)] * warp_size elif uop is Ops.DEFINE_VAR: ul[i] = [pvals.pop(0)] * warp_size @@ -81,31 +80,32 @@ class PythonProgram: elif uop is Ops.DEFINE_ACC: ul[i] = [[inp[0][0][0]] * warp_size for _ in range(dtype.count)] if dtype.count > 1 else [inp[0][0]] * warp_size elif uop is Ops.INDEX: - ret = [] + ret:list = [] if isinstance(dtp[0], ImageDType): for m,ox,oy in zip(inp[0], inp[1][0], inp[1][1]): if ox < 0 or ox >= dtp[0].shape[1] or oy < 0 or oy >= dtp[0].shape[0]: ret.append((m, None)) else: ret.append((m, ox*4 + oy*dtp[0].shape[1]*4)) else: for m,o in zip(inp[0], inp[1]): ret.append((m,o)) - ul[i] = ret + ul[i] = [(m,o,g) for (m,o),g in zip(ret, inp[2] if len(inp) == 3 else [True]*len(ret))] # set the gate last elif uop is Ops.CAST and isinstance(dtype, PtrDType): ul[i] = inp[0] elif uop is Ops.RANGE: - if i not in ul: ul[i] = [inp[0][0]] * warp_size + if i not in ul: ul[i] = [0] * warp_size else: for j in range(len(ul[i])): ul[i][j] += 1 - if ul[i][0] == inp[1][0]: + if ul[i][0] == inp[0][0]: del ul[i] i = loop_ends[i] + 1 continue elif uop is Ops.VECTORIZE: ul[i] = inp - elif uop in {Ops.CAST, Ops.BITCAST}: + elif uop is Ops.BITCAST: assert dtp[0].fmt and dtype.fmt pack_format, unpack_format = str(warp_size) + dtp[0].fmt, str(warp_size) + dtype.fmt - if uop is Ops.BITCAST: ul[i] = list(struct.unpack(unpack_format, struct.pack(pack_format, *inp[0]))) - else: ul[i] = [truncate.get(dtype, lambda dt: dt)(dtypes.as_const(x, dtype)) for x in inp[0]] + ul[i] = list(struct.unpack(unpack_format, struct.pack(pack_format, *inp[0]))) + elif uop is Ops.CAST: + ul[i] = [truncate.get(dtype, lambda dt: dt)(dtypes.as_const(x, dtype)) for x in inp[0]] elif uop is Ops.LOAD: if dtype.count > 1: ul[i] = [load([inp[i][j] if i != 0 and dtp[i].count > 1 else inp[i] for i in range(len(inp))], j) for j in range(dtype.count)] @@ -137,33 +137,55 @@ class PythonProgram: # (i, j), C, D (2 elements on 32 threads): row major same as A/B def c_map(lane, elem): return (elem + ((lane%2)*2) + ((lane//8)%2)*4, ((lane//2)%4) + (lane//16)*4) ul[i] = wmma_helper(32, 8, 2, 2, 2, a_b_elem, a_b_elem, c_map) + elif arg[4] == "AMD" and arg[5] == 64: + def a_elem(x, k, row, goff): return x[k%4][goff + (k//4)*16 + row] + def b_elem(x, col, k, goff): return a_elem(x, k, col, goff) # pylint: disable=arguments-out-of-order + def c_map(lane, elem): return (lane%16, (lane//16)*4 + elem) + ul[i] = wmma_helper(64, 16, 4, 4, 4, a_elem, b_elem, c_map) + elif arg[4] == "AMD" and len(inp[0]) == 8: # RDNA4 + def a_elem(x, k, row, goff): return x[k - [0, 4, 4, 8][k//4]][goff + row + [0, 16, 0, 16][k//4]] + def b_elem(x, col, k, goff): return a_elem(x, k, col, goff) + def c_map(lane, elem): return (lane%16, (lane//16)*8 + elem) + ul[i] = wmma_helper(32, 16, 8, 8, 8, a_elem, b_elem, c_map) elif arg[4] == "AMD": # A (16 elements on 32 threads): col major, lane 16-32 == lane 0-15 - def a_elem(x, i, j, goff): - assert x[i][goff+j] == x[i][goff+j+16], "warp elements not duplicated properly across lanes" - return x[i][goff+j] + def a_elem(x, k, row, goff): + assert x[k][goff+row] == x[k][goff+row+16], "warp elements not duplicated properly across lanes" + return x[k][goff+row] # B (16 elements on 32 threads): row major, lane 16-32 == lane 0-15 - def b_elem(x, i, j, goff): return a_elem(x, j, i, goff) # pylint: disable=arguments-out-of-order + def b_elem(x, col, k, goff): return a_elem(x, k, col, goff) # pylint: disable=arguments-out-of-order def c_map(lane, elem): return (lane%16, lane//16+elem*2) # (i, j), C, D (8 elements on 32 threads): row major ul[i] = wmma_helper(32, 16, 16, 16, 8, a_elem, b_elem, c_map) elif arg[4] == "CUDA": - # A (8 elements on 32 threads) - def a_elem(x, i, j, goff): return x[(i%2)+(j//8)*2+(i//8)*4][goff+((i//2)%4)+(j%8)*4] - # B (4 elements on 32 threads) - def b_elem(x, i, j, goff): return x[(j%2)+(j//8)*2][goff+(j//2)%4+(i)*4] - # (i, j), C, D (4 elements on 32 threads) - def c_map(lane, elem): return ((elem%2)+(lane%4)*2, (lane//4)+(elem//2)*8) - ul[i] = wmma_helper(32, 16, 8, 4, 4, a_elem, b_elem, c_map) + # (col, row) given (lane, elem) for C & D (4 elements on 32 threads); shared by all tc shapes with M=16 N=8 + def c_map(lane, elem): return (elem%2 + (lane%4)*2, lane//4 + (elem//2)*8) + + if arg[1] == (8,16,16): + def a_elem(x, k, row, goff): return x[k%2 + (row//8)*2 + (k//8)*4][goff + (k//2)%4 + (row%8)*4] + def b_elem(x, col, k, goff): return x[k%2 + (k//8)*2][goff + (k//2)%4 + col*4] + ul[i] = wmma_helper(32, 16, 8, 4, 4, a_elem, b_elem, c_map) + + elif arg[1] == (8,16,8) and arg[2] == dtypes.half: + def a_elem(x, k, row, goff): return x[k%2 + (row//8)*2][goff + k//2 + (row%8)*4] + def b_elem(x, col, k, goff): return x[k%2][goff + k//2 + col*4] + ul[i] = wmma_helper(32, 8, 4, 2, 4, a_elem, b_elem, c_map) + + elif arg[1] == (8,16,8) and arg[2] == dtypes.float: + def a_elem(x, k, row, goff): return x[(k//4)*2 + row//8][goff + k%4 + (row%8)*4] + def b_elem(x, col, k, goff): return x[k//4][goff + k%4 + col*4] + ul[i] = wmma_helper(32, 8, 4, 2, 4, a_elem, b_elem, c_map) + + else: raise NotImplementedError(f"unimplemented tensor core {arg}") elif arg[4] == "INTEL": # A (16 elements on 8 threads) - def a_elem(x, i, j, goff): return x[i%2+j*2][goff+i//2] + def a_elem(x, k, row, goff): return x[k%2+row*2][goff+k//2] # B (16 elements on 8 threads) - def b_elem(x, i, j, goff): return x[j][goff+i] + def b_elem(x, col, k, goff): return x[k][goff+col] # C, D (8 elements on 8 threads) def c_map(lane, elem): return (lane, elem) ul[i] = wmma_helper(8, 16, 16, 16, 8, a_elem, b_elem, c_map) - elif arg[4] == "CLANG": - def elem(x, i, j, _): return x[i+j][0] + elif arg[4] == "CPU": + def elem(x, col, row, _): return x[col+row][0] # k is always 0 def c_map(_, elem): return (elem%16, elem//16) ul[i] = wmma_helper(1, 1, 16, 16, 256, elem, elem, c_map) else: raise NotImplementedError(f"unimplemented tensor core {arg}") @@ -180,21 +202,24 @@ class PythonRenderer(Renderer): def __init__(self): if getenv("EMULATE_METAL"): self.device, self.tensor_cores = "METAL", MetalRenderer.tensor_cores if getenv("EMULATE_AMD"): self.device, self.tensor_cores = "AMD", AMDRenderer.tensor_cores - if getenv("EMULATE_CUDA"): self.device, self.tensor_cores = "CUDA", CUDARenderer.tensor_cores + if getenv("EMULATE_AMD_MFMA"): self.device, self.tensor_cores = "AMD", AMDRenderer.tensor_cores_mfma + if getenv("EMULATE_AMD_RDNA4"): self.device, self.tensor_cores = "AMD", AMDRenderer.tensor_cores_rdna4 + if getenv("EMULATE_CUDA"): self.device, self.tensor_cores = "CUDA", CUDARenderer.tc_sm80 + if getenv("EMULATE_CUDA_SM75"): self.device, self.tensor_cores = "CUDA", CUDARenderer.tc_sm75 if getenv("EMULATE_INTEL"): self.device, self.suffix, self.tensor_cores = "INTEL", "INTEL", IntelRenderer.tensor_cores - if getenv("EMULATE_AMX"): self.device, self.tensor_cores = "CLANG", ClangRenderer.tensor_cores + if getenv("EMULATE_AMX"): self.device, self.tensor_cores = "CPU", ClangRenderer.tensor_cores - def render(self, name:str, uops:list[UOp]) -> str: + def render(self, uops:list[UOp]) -> str: lops = [(u.op, u.dtype, [uops.index(v) for v in u.src], u.arg) for u in uops] return base64.b64encode(pickle.dumps(lops)).decode() class PythonCompiler(Compiler): def compile(self, src:str) -> bytes: return base64.b64decode(src) -class PythonAllocator(Allocator): +class PythonAllocator(Allocator['PythonDevice']): def _alloc(self, size, options): return memoryview(bytearray(size)) def _copyin(self, dest, src:memoryview): dest[:] = src def _copyout(self, dest:memoryview, src): dest[:] = src class PythonDevice(Compiled): - def __init__(self, device:str): super().__init__(device, PythonAllocator(), PythonRenderer(), PythonCompiler(), PythonProgram) + def __init__(self, device:str): super().__init__(device, PythonAllocator(self), PythonRenderer(), PythonCompiler(), PythonProgram) diff --git a/tinygrad_repo/tinygrad/runtime/ops_qcom.py b/tinygrad_repo/tinygrad/runtime/ops_qcom.py index 0b5041f914..08501812dc 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_qcom.py +++ b/tinygrad_repo/tinygrad/runtime/ops_qcom.py @@ -1,11 +1,12 @@ from __future__ import annotations -import os, ctypes, functools, mmap, struct, array, math, sys +import os, ctypes, functools, mmap, struct, array, math, sys, weakref assert sys.platform != 'win32' from types import SimpleNamespace -from typing import Any, cast, Optional +from typing import Any, cast, ClassVar from tinygrad.device import BufferSpec from tinygrad.runtime.support.hcq import HCQBuffer, HWQueue, HCQProgram, HCQCompiled, HCQAllocatorBase, HCQSignal, HCQArgsState, BumpAllocator -from tinygrad.runtime.autogen import kgsl, adreno, libc +from tinygrad.runtime.support.hcq import FileIOInterface, MMIOInterface +from tinygrad.runtime.autogen import kgsl, adreno from tinygrad.runtime.ops_gpu import CLCompiler, CLDevice from tinygrad.renderer.cstyle import QCOMRenderer from tinygrad.helpers import getenv, mv_address, to_mv, round_up, data64_le, prod, fromimport @@ -36,14 +37,11 @@ class QCOMCompiler(CLCompiler): def disassemble(self, lib:bytes): fromimport('extra.disassemblers.adreno', 'disasm')(lib) class QCOMSignal(HCQSignal): - def __init__(self, base_addr:Optional[int]=None, **kwargs): - super().__init__(QCOMDevice.signals_pool.pop() if base_addr is None else base_addr, **kwargs, timestamp_divider=19.2) - - def __del__(self): - if isinstance(self.base_addr, int): QCOMDevice.signals_pool.append(self.base_addr) + def __init__(self, base_buf:HCQBuffer|None=None, **kwargs): + super().__init__(base_buf, **kwargs, timestamp_divider=19.2, dev_t=QCOMDevice) def _sleep(self, time_spent_waiting_ms:int): - # Sleep only for only timeline signals. Do it immidiately to free cpu. + # Sleep only for only timeline signals. Do it immediately to free cpu. if self.timeline_for_device is not None: kgsl.IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID(self.timeline_for_device.fd, context_id=self.timeline_for_device.ctx, timestamp=self.timeline_for_device.last_cmd, timeout=0xffffffff) @@ -134,7 +132,7 @@ class QCOMComputeQueue(HWQueue): self.cmd(adreno.CP_LOAD_STATE6_FRAG, qreg.cp_load_state6_0(state_type=adreno.ST_CONSTANTS, state_src=adreno.SS6_INDIRECT, state_block=adreno.SB6_CS_SHADER, num_unit=1024 // 4), - *data64_le(args_state.ptr)) + *data64_le(args_state.buf.va_addr)) self.cmd(adreno.CP_LOAD_STATE6_FRAG, qreg.cp_load_state6_0(state_type=adreno.ST_SHADER, state_src=adreno.SS6_INDIRECT, state_block=adreno.SB6_CS_SHADER, num_unit=round_up(prg.image_size, 128) // 128), *data64_le(prg.lib_gpu.va_addr)) @@ -147,21 +145,21 @@ class QCOMComputeQueue(HWQueue): if args_state.prg.samp_cnt > 0: self.cmd(adreno.CP_LOAD_STATE6_FRAG, qreg.cp_load_state6_0(state_type=adreno.ST_SHADER, state_src=adreno.SS6_INDIRECT, state_block=adreno.SB6_CS_TEX, num_unit=args_state.prg.samp_cnt), - *data64_le(args_state.ptr + args_state.prg.samp_off)) - self.reg(adreno.REG_A6XX_SP_CS_TEX_SAMP, *data64_le(args_state.ptr + args_state.prg.samp_off)) + *data64_le(args_state.buf.va_addr + args_state.prg.samp_off)) + self.reg(adreno.REG_A6XX_SP_CS_TEX_SAMP, *data64_le(args_state.buf.va_addr + args_state.prg.samp_off)) self.reg(adreno.REG_A6XX_SP_PS_TP_BORDER_COLOR_BASE_ADDR, *data64_le(prg.dev.border_color_buf.va_addr)) if args_state.prg.tex_cnt > 0: self.cmd(adreno.CP_LOAD_STATE6_FRAG, qreg.cp_load_state6_0(state_type=adreno.ST_CONSTANTS, state_src=adreno.SS6_INDIRECT, state_block=adreno.SB6_CS_TEX, num_unit=min(16, args_state.prg.tex_cnt)), - *data64_le(args_state.ptr + args_state.prg.tex_off)) - self.reg(adreno.REG_A6XX_SP_CS_TEX_CONST, *data64_le(args_state.ptr + args_state.prg.tex_off)) + *data64_le(args_state.buf.va_addr + args_state.prg.tex_off)) + self.reg(adreno.REG_A6XX_SP_CS_TEX_CONST, *data64_le(args_state.buf.va_addr + args_state.prg.tex_off)) if args_state.prg.ibo_cnt > 0: self.cmd(adreno.CP_LOAD_STATE6_FRAG, qreg.cp_load_state6_0(state_type=adreno.ST6_IBO, state_src=adreno.SS6_INDIRECT, state_block=adreno.SB6_CS_SHADER, num_unit=args_state.prg.ibo_cnt), - *data64_le(args_state.ptr + args_state.prg.ibo_off)) - self.reg(adreno.REG_A6XX_SP_CS_IBO, *data64_le(args_state.ptr + args_state.prg.ibo_off)) + *data64_le(args_state.buf.va_addr + args_state.prg.ibo_off)) + self.reg(adreno.REG_A6XX_SP_CS_IBO, *data64_le(args_state.buf.va_addr + args_state.prg.ibo_off)) self.reg(adreno.REG_A6XX_SP_CS_CONFIG, qreg.a6xx_sp_cs_config(enabled=True, nsamp=args_state.prg.samp_cnt, ntex=args_state.prg.tex_cnt, nibo=args_state.prg.ibo_cnt)) @@ -170,24 +168,24 @@ class QCOMComputeQueue(HWQueue): return self class QCOMArgsState(HCQArgsState): - def __init__(self, ptr:int, prg:QCOMProgram, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=()): - super().__init__(ptr, prg, bufs, vals=vals) + def __init__(self, buf:HCQBuffer, prg:QCOMProgram, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=()): + super().__init__(buf, prg, bufs, vals=vals) if len(bufs) + len(vals) != len(prg.buf_info): raise RuntimeError(f'incorrect args size given={len(bufs)+len(vals)} != want={len(prg.buf_info)}') - self.buf_info, self.args_info, self.args_view = prg.buf_info[:len(bufs)], prg.buf_info[len(bufs):], to_mv(ptr, prg.kernargs_alloc_size).cast('Q') + self.buf_info, self.args_info = prg.buf_info[:len(bufs)], prg.buf_info[len(bufs):] - ctypes.memset(self.ptr, 0, prg.kernargs_alloc_size) - for cnst_val, cnst_off, cnst_sz in prg.consts_info: to_mv(self.ptr + cnst_off, cnst_sz)[:] = cnst_val.to_bytes(cnst_sz, byteorder='little') + ctypes.memset(cast(int, self.buf.va_addr), 0, prg.kernargs_alloc_size) + for cnst_val,cnst_off,cnst_sz in prg.consts_info: to_mv(self.buf.va_addr + cnst_off, cnst_sz)[:] = cnst_val.to_bytes(cnst_sz, byteorder='little') - if prg.samp_cnt > 0: to_mv(self.ptr + prg.samp_off, len(prg.samplers) * 4).cast('I')[:] = array.array('I', prg.samplers) + if prg.samp_cnt > 0: to_mv(self.buf.va_addr + prg.samp_off, len(prg.samplers) * 4).cast('I')[:] = array.array('I', prg.samplers) for i, b in enumerate(bufs): if prg.buf_info[i].type in {BUFTYPE_TEX, BUFTYPE_IBO}: obj = b.texture_info.desc if prg.buf_info[i].type is BUFTYPE_TEX else b.texture_info.ibo - to_mv(self.ptr + prg.buf_info[i].offset, len(obj) * 4).cast('I')[:] = array.array('I', obj) - self.bind_sints_to_ptr(b.va_addr, ptr=self.ptr + self.buf_info[i].offset + (0 if self.buf_info[i].type is BUFTYPE_BUF else 16), fmt='Q') + to_mv(self.buf.va_addr + prg.buf_info[i].offset, len(obj) * 4).cast('I')[:] = array.array('I', obj) + self.bind_sints_to_buf(b.va_addr, buf=self.buf, fmt='Q', offset=self.buf_info[i].offset+(0 if self.buf_info[i].type is BUFTYPE_BUF else 16)) - for i, v in enumerate(vals): self.bind_sints_to_ptr(v, ptr=self.ptr + self.args_info[i].offset, fmt='I') + for i, v in enumerate(vals): self.bind_sints_to_buf(v, buf=self.buf, fmt='I', offset=self.args_info[i].offset) class QCOMProgram(HCQProgram): def __init__(self, dev: QCOMDevice, name: str, lib: bytes): @@ -195,7 +193,7 @@ class QCOMProgram(HCQProgram): self.name, self.lib = name, lib self._parse_lib() - self.lib_gpu: HCQBuffer = self.dev.allocator.alloc(self.image_size, options=BufferSpec(cpu_access=True, nolru=True)) + self.lib_gpu: HCQBuffer = self.dev.allocator.alloc(self.image_size, buf_spec:=BufferSpec(cpu_access=True, nolru=True)) to_mv(cast(int, self.lib_gpu.va_addr), self.image_size)[:] = self.image self.pvtmem_size_per_item: int = round_up(self.pvtmem, 512) >> 9 @@ -207,6 +205,7 @@ class QCOMProgram(HCQProgram): kernargs_alloc_size = round_up(2048 + (self.tex_cnt + self.ibo_cnt) * 0x40 + self.samp_cnt * 0x10, 0x100) super().__init__(QCOMArgsState, self.dev, self.name, kernargs_alloc_size=kernargs_alloc_size) + weakref.finalize(self, self._fini, self.dev, self.lib_gpu, buf_spec) def __call__(self, *bufs, global_size:tuple[int,int,int]=(1,1,1), local_size:tuple[int,int,int]=(1,1,1), vals:tuple[int, ...]=(), wait=False): if self.max_threads < prod(local_size): raise RuntimeError("Too many resources requested for launch") @@ -264,9 +263,6 @@ class QCOMProgram(HCQProgram): reg_desc_off = _read_lib(0x34) self.fregs, self.hregs = _read_lib(reg_desc_off + 0x14), _read_lib(reg_desc_off + 0x18) - def __del__(self): - if hasattr(self, 'lib_gpu'): self.dev.allocator.free(self.lib_gpu, self.lib_gpu.size, options=BufferSpec(cpu_access=True, nolru=True)) - class QCOMTextureInfo: def __init__(self, pitch:int, real_stride:int, desc:list[int], ibo:list[int]): self.pitch, self.real_stride, self.desc, self.ibo = pitch, real_stride, desc, ibo @@ -319,23 +315,23 @@ class QCOMAllocator(HCQAllocatorBase): self.dev._gpu_free(opaque) class QCOMDevice(HCQCompiled): - signals_page: Any = None - signals_pool: list[int] = [] + devices: ClassVar[list[HCQCompiled]] = [] + signal_pages: ClassVar[list[HCQBuffer]] = [] + signal_pool: ClassVar[list[HCQBuffer]] = [] + gpu_id: int = 0 dummy_addr: int = 0 def __init__(self, device:str=""): - self.fd = os.open('/dev/kgsl-3d0', os.O_RDWR) + self.fd = FileIOInterface('/dev/kgsl-3d0', os.O_RDWR) QCOMDevice.dummy_addr = cast(int, self._gpu_alloc(0x1000).va_addr) - QCOMDevice.signals_page = self._gpu_alloc(16 * 65536, uncached=True) - QCOMDevice.signals_pool = [self.signals_page.va_addr + off for off in range(0, self.signals_page.size, 16)] flags = kgsl.KGSL_CONTEXT_PREAMBLE | kgsl.KGSL_CONTEXT_PWR_CONSTRAINT | kgsl.KGSL_CONTEXT_NO_FAULT_TOLERANCE | kgsl.KGSL_CONTEXT_NO_GMEM_ALLOC \ | kgsl.KGSL_CONTEXT_PRIORITY(8) | kgsl.KGSL_CONTEXT_PREEMPT_STYLE(kgsl.KGSL_CONTEXT_PREEMPT_STYLE_FINEGRAIN) self.ctx = kgsl.IOCTL_KGSL_DRAWCTXT_CREATE(self.fd, flags=flags).drawctxt_id self.cmd_buf = self._gpu_alloc(16 << 20) - self.cmd_buf_allocator = BumpAllocator(size=self.cmd_buf.size, start=cast(int, self.cmd_buf.va_addr), wrap=True) + self.cmd_buf_allocator = BumpAllocator(size=self.cmd_buf.size, base=cast(int, self.cmd_buf.va_addr), wrap=True) self.border_color_buf = self._gpu_alloc(0x1000, fill_zeroes=True) @@ -359,14 +355,14 @@ class QCOMDevice(HCQCompiled): if uncached: flags |= kgsl.KGSL_CACHEMODE(kgsl.KGSL_CACHEMODE_UNCACHED) alloc = kgsl.IOCTL_KGSL_GPUOBJ_ALLOC(self.fd, size=(bosz:=round_up(size, 1< middleware <-> runtime <-> hardware +# with REMOTE tinygrad is frontend <-> middleware <-> RemoteDevice ///HTTP/// remote_server <-> runtime <-> hardware +# this client and server can be on the same machine, same network, or just same internet +# it should be a secure (example: no use of pickle) boundary. HTTP is used for RPC + +from __future__ import annotations +from typing import Callable, Iterator, Optional, Any, cast +from collections import defaultdict +from dataclasses import dataclass, field, replace +import multiprocessing, functools, itertools, asyncio, http, http.client, hashlib, time, os, binascii, struct, ast, contextlib, weakref +from tinygrad.renderer import Renderer, ProgramSpec +from tinygrad.dtype import DTYPES_DICT, dtypes +from tinygrad.uop.ops import UOp, Ops, Variable, sint +from tinygrad.helpers import getenv, DEBUG, fromimport, unwrap, Timing +from tinygrad.engine.jit import GraphRunner, MultiGraphRunner, ExecItem, graph_class +from tinygrad.engine.realize import CompiledRunner, BufferXfer +from tinygrad.device import Compiled, Buffer, Allocator, Compiler, Device, BufferSpec +from tinygrad.runtime.graph.cpu import CPUGraph + +# ***** API ***** + +@dataclass(frozen=True) +class RemoteRequest: session: tuple[str, int]|None = field(default=None, kw_only=True) + +@dataclass(frozen=True) +class SessionFree(RemoteRequest): pass + +@dataclass(frozen=True) +class RemoteProperties: + real_device: str + renderer: tuple[str, str, tuple[Any, ...]] + graph_supported: bool + graph_supports_multi: bool + transfer_supported: bool + offset_supported: bool + +@dataclass(frozen=True) +class GetProperties(RemoteRequest): pass + +@dataclass(frozen=True) +class BufferAlloc(RemoteRequest): buffer_num: int; size: int; options: BufferSpec # noqa: E702 + +@dataclass(frozen=True) +class BufferOffset(RemoteRequest): buffer_num: int; size: int; offset: int; sbuffer_num: int # noqa: E702 + +@dataclass(frozen=True) +class BufferFree(RemoteRequest): buffer_num: int # noqa: E702 + +@dataclass(frozen=True) +class CopyIn(RemoteRequest): buffer_num: int; datahash: str # noqa: E702 + +@dataclass(frozen=True) +class CopyOut(RemoteRequest): buffer_num: int + +@dataclass(frozen=True) +class Transfer(RemoteRequest): buffer_num: int; ssession: tuple[str, int]; sbuffer_num: int # noqa: E702 + +@dataclass(frozen=True) +class ProgramAlloc(RemoteRequest): name: str; datahash: str # noqa: E702 + +@dataclass(frozen=True) +class ProgramFree(RemoteRequest): name: str; datahash: str # noqa: E702 + +@dataclass(frozen=True) +class ProgramExec(RemoteRequest): + name: str; datahash: str; bufs: tuple[int, ...]; vals: tuple[int, ...] # noqa: E702 + global_size: Optional[tuple[int, ...]]; local_size: Optional[tuple[int, ...]]; wait: bool # noqa: E702 + +@dataclass(frozen=True) +class GraphComputeItem: + session: tuple[str, int] + name: str + datahash: str + bufs: tuple[int, ...] + vars: tuple[Variable, ...] + fixedvars: dict[Variable, int] + ins: tuple[int, ...] + outs: tuple[int, ...] + global_size: tuple[sint, ...]|None + local_size: tuple[sint, ...]|None + +@dataclass(frozen=True) +class GraphAlloc(RemoteRequest): + graph_num: int + jit_cache: tuple[GraphComputeItem|Transfer, ...] + bufs: tuple[tuple[tuple[str, int], int], ...] + var_vals: dict[Variable, int] + +@dataclass(frozen=True) +class GraphFree(RemoteRequest): + graph_num: int + +@dataclass(frozen=True) +class GraphExec(RemoteRequest): + graph_num: int + bufs: tuple[tuple[tuple[str, int], int], ...] + var_vals: dict[Variable, int] + wait: bool + +# for safe deserialization +eval_globals = {x.__name__:x for x in [SessionFree, RemoteProperties, GetProperties, BufferAlloc, BufferOffset, BufferFree, CopyIn, CopyOut, Transfer, + ProgramAlloc, ProgramFree, ProgramExec, GraphComputeItem, GraphAlloc, GraphFree, GraphExec, BufferSpec, UOp, + Ops, dtypes]} +attribute_whitelist: dict[Any, set[str]] = {dtypes: {*DTYPES_DICT.keys(), 'imagef', 'imageh'}, Ops: {x.name for x in Ops}} +eval_fxns = {ast.Constant: lambda x: x.value, ast.Tuple: lambda x: tuple(map(safe_eval, x.elts)), ast.List: lambda x: list(map(safe_eval, x.elts)), + ast.Dict: lambda x: {safe_eval(k):safe_eval(v) for k,v in zip(x.keys, x.values)}, + ast.Call: lambda x: safe_eval(x.func)(*[safe_eval(arg) for arg in x.args], **{kwarg.arg: safe_eval(kwarg.value) for kwarg in x.keywords}), + ast.Name: lambda x: eval_globals[x.id], ast.Attribute: lambda x: safe_getattr(safe_eval(x.value), x.attr)} +def safe_getattr(value, attr): + assert attr in attribute_whitelist.get(value, set()), f'getattr({value}, {repr(attr)}) is not whitelisted' + return getattr(value, attr) +def safe_eval(node): return eval_fxns[node.__class__](node) + +class BatchRequest: + def __init__(self): + self._q: list[RemoteRequest] = [] + self._h: dict[str, bytes] = {} + def h(self, d:bytes|memoryview) -> str: + datahash = hashlib.sha256(d).hexdigest() # NOTE: this is very slow, should use blake3 on gpu instead + if datahash not in self._h: + self._h[datahash] = bytes.fromhex(datahash)+struct.pack(" bytes: + self.h(repr(self._q).encode()) + return b''.join(self._h.values()) + def deserialize(self, dat:bytes) -> BatchRequest: + ptr = 0 + while ptr < len(dat): + datahash, datalen = binascii.hexlify(dat[ptr:ptr+0x20]).decode(), struct.unpack(" tuple[http.HTTPStatus, bytes]: + status, ret = http.HTTPStatus.OK, b"" + if path == "/batch" and method == "POST": + # TODO: streaming deserialize? + req = BatchRequest().deserialize(body) + # the cmds are always last (currently in datahash) + for c in req._q: + if DEBUG >= 1: print(c) + session, dev = self.sessions[unwrap(c.session)], Device[f"{self.base_device}:{unwrap(c.session)[1]}"] + match c: + case SessionFree(): del self.sessions[unwrap(c.session)] + case GetProperties(): + cls, args = dev.renderer.__reduce__() + # CPUGraph re-renders kernel from uops specified in CompiledRunner, this is not supported + graph_cls = gt if (gt:=graph_class(Device[self.base_device])) is not CPUGraph else None + rp = RemoteProperties( + real_device=dev.device, renderer=(cls.__module__, cls.__name__, args), + graph_supported=graph_cls is not None, graph_supports_multi=graph_cls is not None and issubclass(graph_cls, MultiGraphRunner), + transfer_supported=hasattr(dev.allocator, '_transfer'), offset_supported=hasattr(dev.allocator, '_offset'), + ) + ret = repr(rp).encode() + case BufferAlloc(): + assert c.buffer_num not in session.buffers, f"buffer {c.buffer_num} already allocated" + session.buffers[c.buffer_num] = Buffer(dev.device, c.size, dtypes.uint8, options=c.options, preallocate=True) + case BufferOffset(): + assert c.buffer_num not in session.buffers, f"buffer {c.buffer_num} already exists" + session.buffers[c.buffer_num] = session.buffers[c.sbuffer_num].view(c.size, dtypes.uint8, c.offset).allocate() + case BufferFree(): del session.buffers[c.buffer_num] + case CopyIn(): session.buffers[c.buffer_num].copyin(memoryview(bytearray(req._h[c.datahash]))) + case CopyOut(): session.buffers[c.buffer_num].copyout(memoryview(ret:=bytearray(session.buffers[c.buffer_num].nbytes))) + case Transfer(): + ssession, sdev = self.sessions[c.ssession], Device[f"{self.base_device}:{unwrap(c.ssession)[1]}"] + dbuf, sbuf = session.buffers[c.buffer_num], ssession.buffers[c.sbuffer_num] + assert dbuf.nbytes == sbuf.nbytes, f"{dbuf.nbytes} != {sbuf.nbytes}" + assert hasattr(dev.allocator, '_transfer'), f"Device {dev.device} doesn't support transfers" + dev.allocator._transfer(dbuf._buf, sbuf._buf, dbuf.nbytes, dest_dev=dev, src_dev=sdev) + case ProgramAlloc(): + lib = dev.compiler.compile_cached(req._h[c.datahash].decode()) + session.programs[(c.name, c.datahash)] = dev.runtime(c.name, lib) + case ProgramFree(): del session.programs[(c.name, c.datahash)] + case ProgramExec(): + bufs = [session.buffers[x]._buf for x in c.bufs] + extra_args = {k:v for k,v in [("global_size", c.global_size), ("local_size", c.local_size)] if v is not None} + r = session.programs[(c.name, c.datahash)](*bufs, vals=c.vals, wait=c.wait, **extra_args) + if r is not None: ret = str(r).encode() + case GraphAlloc(): + graph_fn: Callable = unwrap(dev.graph) + def _parse_ji(gi: GraphComputeItem|Transfer): + match gi: + case GraphComputeItem(): + prg = self.sessions[gi.session].programs[(gi.name, gi.datahash)] + ps = ProgramSpec(gi.name, '', f"{self.base_device}:{gi.session[1]}", UOp(Ops.NOOP), + vars=list(gi.vars), ins=list(gi.ins), outs=list(gi.outs), + global_size=list(cast(tuple[int], gi.global_size)) if gi.global_size is not None else None, + local_size=list(cast(tuple[int], gi.local_size)) if gi.local_size is not None else None) + return ExecItem(CompiledRunner(ps, precompiled=b'', prg=prg), [self.sessions[gi.session].buffers[buf] for buf in gi.bufs], + fixedvars=gi.fixedvars) + case Transfer(): + dbuf, sbuf = self.sessions[unwrap(gi.session)].buffers[gi.buffer_num], self.sessions[gi.ssession].buffers[gi.sbuffer_num] + assert dbuf.nbytes == sbuf.nbytes, f"{dbuf.nbytes} != {sbuf.nbytes}" + return ExecItem(BufferXfer(dbuf.nbytes, dbuf.device, sbuf.device), [dbuf, sbuf]) + assert c.graph_num not in session.graphs, f"graph {c.graph_num} already allocated" + session.graphs[c.graph_num] = graph_fn(list(map(_parse_ji, c.jit_cache)), [self.sessions[s].buffers[i] for s,i in c.bufs], c.var_vals) + case GraphFree(): del session.graphs[c.graph_num] + case GraphExec(): + r = session.graphs[c.graph_num]([self.sessions[s].buffers[i] for s,i in c.bufs], c.var_vals, wait=c.wait) + if r is not None: ret = str(r).encode() + else: status, ret = http.HTTPStatus.NOT_FOUND, b"Not Found" + return status, ret + +def remote_server(port:int): + device = getenv("REMOTEDEV", next(Device.get_available_devices()) if Device.DEFAULT == "REMOTE" else Device.DEFAULT) + async def _inner_async(port:int, device:str): + print(f"start remote server on {port} with device {device}") + await (await asyncio.start_server(RemoteHandler(device), host='', port=port)).serve_forever() + asyncio.run(_inner_async(port, device)) + +# ***** frontend ***** + +class RemoteAllocator(Allocator['RemoteDevice']): + def __init__(self, dev:RemoteDevice): + if dev.properties.offset_supported: self._offset = self._dyn_offset + super().__init__(dev) + # TODO: ideally we shouldn't have to deal with images here + def _alloc(self, size:int, options:BufferSpec) -> int: + self.dev.q(BufferAlloc(buffer_num:=next(self.dev.buffer_num), size, options)) + return buffer_num + # TODO: options should not be here in any Allocator + def _free(self, opaque:int, options): self.dev.q(BufferFree(opaque)) + def _copyin(self, dest:int, src:memoryview): self.dev.q(CopyIn(dest, self.dev.conn.req.h(src))) + def _copyout(self, dest:memoryview, src:int): + resp = self.dev.q(CopyOut(src), wait=True) + assert len(resp) == len(dest), f"buffer length mismatch {len(resp)} != {len(dest)}" + dest[:] = resp + def _transfer(self, dest, src, sz, src_dev, dest_dev): + if dest_dev.properties.transfer_supported and src_dev.conn == dest_dev.conn: + dest_dev.q(Transfer(dest, src_dev.session, src)) + else: + src_dev.allocator._copyout(tmp:=memoryview(bytearray(sz)), src) + dest_dev.allocator._copyin(dest, tmp) + def _dyn_offset(self, opaque:int, size:int, offset:int) -> int: + self.dev.q(BufferOffset(buffer_num:=next(self.dev.buffer_num), size, offset, opaque)) + return buffer_num + +class RemoteProgram: + def __init__(self, dev:RemoteDevice, name:str, lib:bytes): + self.dev, self.name = dev, name + self.datahash = self.dev.conn.req.h(lib) + self.dev.q(ProgramAlloc(self.name, self.datahash)) + super().__init__() + weakref.finalize(self, self._fini, self.dev, self.name, self.datahash) + + @staticmethod + def _fini(dev:RemoteDevice, name:str, datahash:str): dev.q(ProgramFree(name, datahash)) + + def __call__(self, *bufs, global_size=None, local_size=None, vals:tuple[int, ...]=(), wait=False): + ret = self.dev.q(ProgramExec(self.name, self.datahash, bufs, vals, global_size, local_size, wait), wait=wait) + if wait: return float(ret) + +@functools.cache +class RemoteConnection: + def __init__(self, host:str): + if DEBUG >= 1: print(f"remote with host {host}") + while 1: + try: + self.conn = http.client.HTTPConnection(host, timeout=getenv("REMOTE_TIMEOUT", 300.0)) + self.conn.connect() + break + except Exception as e: + print(e) + time.sleep(0.1) + self.req: BatchRequest = BatchRequest() + + def batch_submit(self): + data = self.req.serialize() + with Timing(f"*** send {len(self.req._q):-3d} requests {len(self.req._h):-3d} hashes with len {len(data)/1024:.2f} kB in ", enabled=DEBUG>=3): + self.conn.request("POST", "/batch", data) + response = self.conn.getresponse() + assert response.status == 200, f"POST /batch failed: {response}" + ret = response.read() + self.req = BatchRequest() + return ret + +class RemoteDevice(Compiled): + def __init__(self, device:str): + self.conn: RemoteConnection = RemoteConnection(getenv("HOST", "") or RemoteDevice.local_server()) + + # state for the connection + self.session = (binascii.hexlify(os.urandom(0x10)).decode(), int(device.split(":")[1]) if ":" in device else 0) + self.buffer_num: Iterator[int] = itertools.count(0) + self.graph_num: Iterator[int] = itertools.count(0) + + self.properties: RemoteProperties = safe_eval(ast.parse(self.q(GetProperties(), wait=True), mode="eval").body) + if DEBUG >= 1: print(f"remote has device {self.properties.real_device}") + # TODO: how to we have BEAM be cached on the backend? this should just send a specification of the compute. rethink what goes in Renderer + renderer = self.properties.renderer + if not renderer[0].startswith("tinygrad.renderer.") or not renderer[1].endswith("Renderer"): raise RuntimeError(f"bad renderer {renderer}") + renderer_class = fromimport(renderer[0], renderer[1]) # TODO: is this secure? + if not issubclass(renderer_class, Renderer): raise RuntimeError(f"renderer isn't a Renderer {renderer}") + renderer_instance = renderer_class(*renderer[2]) + renderer_instance.device = device + graph_supported, graph_multi = self.properties.graph_supported, self.properties.graph_supports_multi + graph = fromimport('tinygrad.runtime.graph.remote', f"Remote{'Multi' if graph_multi else ''}Graph") if graph_supported else None + super().__init__(device, RemoteAllocator(self), renderer_instance, Compiler(), functools.partial(RemoteProgram, self), graph) + + def finalize(self): + with contextlib.suppress(ConnectionError, http.client.HTTPException): self.q(SessionFree(), wait=True) + + def q(self, x:RemoteRequest, wait:bool=False): + self.conn.req.q(replace(x, session=self.session)) + if wait: return self.conn.batch_submit() + + @functools.cache + @staticmethod + def local_server(): + multiprocessing.Process(target=remote_server, args=(6667,), name="MainProcess", daemon=True).start() + return "127.0.0.1:6667" + +if __name__ == "__main__": remote_server(getenv("PORT", 6667)) diff --git a/tinygrad_repo/tinygrad/runtime/ops_webgpu.py b/tinygrad_repo/tinygrad/runtime/ops_webgpu.py index df52782180..f7da78e26b 100644 --- a/tinygrad_repo/tinygrad/runtime/ops_webgpu.py +++ b/tinygrad_repo/tinygrad/runtime/ops_webgpu.py @@ -1,63 +1,225 @@ import functools, struct -from tinygrad.device import Compiled, Allocator, Compiler +from tinygrad.device import Compiled, Allocator, Compiler, BufferSpec from tinygrad.renderer.wgsl import WGSLRenderer from tinygrad.helpers import round_up -import wgpu +from tinygrad.runtime.autogen import webgpu +from typing import List, Any, TypeAlias +import ctypes +import os -def create_uniform(wgpu_device, val) -> wgpu.GPUBuffer: - buf = wgpu_device.create_buffer(size=4, usage=wgpu.BufferUsage.UNIFORM | wgpu.BufferUsage.COPY_DST) - wgpu_device.queue.write_buffer(buf, 0, val.to_bytes(4, "little") if isinstance(val, int) else struct.pack(' ctypes.Array: return ctypes.create_string_buffer(_str.encode('utf-8')) + +def from_wgpu_str(string_view:webgpu.struct_WGPUStringView) -> str: return ctypes.string_at(string_view.data, string_view.length).decode("utf-8") + +def to_wgpu_str(_str:str) -> webgpu.struct_WGPUStringView: + return webgpu.WGPUStringView(data=ctypes.cast(ctypes.pointer(to_c_string(_str)), ctypes.POINTER(ctypes.c_char)), length=len(_str)) + +def _wait(future:webgpu.struct_WGPUFuture): + assert webgpu.wgpuInstanceWaitAny(instance, 1, webgpu.WGPUFutureWaitInfo(future=future), 2**64-1) == webgpu.WGPUWaitStatus_Success, "Future failed" + +def write_buffer(device:WGPUDevPtr, buf:WGPUBufPtr, offset:int, src:memoryview|bytearray|bytes): + src = bytearray(src) + webgpu.wgpuQueueWriteBuffer(webgpu.wgpuDeviceGetQueue(device), buf, offset, (ctypes.c_uint8 * len(src)).from_buffer(src), len(src)) + +def _run(async_fun, cb_info_type, cb_type, status_enum, res_idx:int|None, msg_idx:int|None, *params): + result: List[Any] = [] + + def cb(*params): + result[:] = params + if msg_idx: result[msg_idx] = from_wgpu_str(result[msg_idx]) + + cb_info = cb_info_type(nextInChain=None, mode=webgpu.WGPUCallbackMode_WaitAnyOnly, callback=cb_type(cb)) + _wait(async_fun(*params, cb_info)) + + if result[0] != 1: raise RuntimeError(f"[{status_enum[result[0]] if status_enum else 'ERROR'}]{result[msg_idx] if msg_idx else ''}") + return result[res_idx] if res_idx else None + +def copy_buffer_to_buffer(dev:WGPUDevPtr, src:WGPUBufPtr, src_offset:int, dst:WGPUBufPtr, dst_offset:int, size:int): + encoder = webgpu.wgpuDeviceCreateCommandEncoder(dev, webgpu.WGPUCommandEncoderDescriptor()) + webgpu.wgpuCommandEncoderCopyBufferToBuffer(encoder, src, src_offset, dst, dst_offset, size) + cb = webgpu.wgpuCommandEncoderFinish(encoder, webgpu.WGPUCommandBufferDescriptor()) + webgpu.wgpuQueueSubmit(webgpu.wgpuDeviceGetQueue(dev), 1, (webgpu.WGPUCommandBuffer*1)(cb)) + webgpu.wgpuCommandBufferRelease(cb) + webgpu.wgpuCommandEncoderRelease(encoder) + +def read_buffer(dev:WGPUDevPtr, buf:WGPUBufPtr) -> memoryview: + size = webgpu.wgpuBufferGetSize(buf) + tmp_buffer = webgpu.wgpuDeviceCreateBuffer(dev, webgpu.WGPUBufferDescriptor(size=size, + usage=webgpu.WGPUBufferUsage_CopyDst | webgpu.WGPUBufferUsage_MapRead, mappedAtCreation=False)) + copy_buffer_to_buffer(dev, buf, 0, tmp_buffer, 0, size) + _run(webgpu.wgpuBufferMapAsync2, webgpu.WGPUBufferMapCallbackInfo2, webgpu.WGPUBufferMapCallback2, webgpu.WGPUBufferMapAsyncStatus__enumvalues, + None, 0, tmp_buffer, webgpu.WGPUMapMode_Read, 0, size) + void_ptr = ctypes.cast(webgpu.wgpuBufferGetConstMappedRange(tmp_buffer, 0, size), ctypes.c_void_p) + buf_copy = bytearray((ctypes.c_uint8 * size).from_address(void_ptr.value)) + webgpu.wgpuBufferUnmap(tmp_buffer) + webgpu.wgpuBufferDestroy(tmp_buffer) + return memoryview(buf_copy).cast("B") + +def pop_error(device:WGPUDevPtr) -> str: + return _run(webgpu.wgpuDevicePopErrorScopeF, webgpu.WGPUPopErrorScopeCallbackInfo, webgpu.WGPUPopErrorScopeCallback, None, 2, 2, device) + +def create_uniform(wgpu_device:WGPUDevPtr, val:int|float) -> WGPUBufPtr: + buf = webgpu.wgpuDeviceCreateBuffer(wgpu_device, + webgpu.WGPUBufferDescriptor(size=4, usage=webgpu.WGPUBufferUsage_Uniform | webgpu.WGPUBufferUsage_CopyDst)) + write_buffer(wgpu_device, buf, 0, val.to_bytes(4, "little") if isinstance(val, int) else struct.pack(' float|None: wait = wait and self.timestamp_supported - binding_layouts = [{"binding": 0, "visibility": wgpu.ShaderStage.COMPUTE, "buffer": {"type": wgpu.BufferBindingType.uniform }}] - binding_layouts += [{"binding": i+1, "visibility": wgpu.ShaderStage.COMPUTE, - "buffer": {"type": wgpu.BufferBindingType.uniform if i >= len(bufs) else wgpu.BufferBindingType.storage }} for i in range(len(bufs)+len(vals))] # noqa: E501 - bindings = [{"binding": 0, "resource": {"buffer": create_uniform(self.dev, float('inf')), "offset": 0, "size": 4}}] - bindings += [{"binding": i+1, "resource": {"buffer": create_uniform(self.dev, x) if i >= len(bufs) else x, "offset": 0, - "size": 4 if i >= len(bufs) else x.size}} for i,x in enumerate(bufs+vals)] # noqa: E501 - bind_group_layout = self.dev.create_bind_group_layout(entries=binding_layouts) - pipeline_layout = self.dev.create_pipeline_layout(bind_group_layouts=[bind_group_layout]) - bind_group = self.dev.create_bind_group(layout=bind_group_layout, entries=bindings) - compute_pipeline = self.dev.create_compute_pipeline(layout=pipeline_layout,compute={"module": self.prg, "entry_point": self.name},) - command_encoder = self.dev.create_command_encoder() + tmp_bufs = [*bufs] + buf_patch = False + + # WebGPU does not allow using the same buffer for input and output + for i in range(1, len(bufs)): + if ctypes.addressof(bufs[i]) == ctypes.addressof(bufs[0]): + tmp_bufs[0] = webgpu.wgpuDeviceCreateBuffer(self.dev, + webgpu.WGPUBufferDescriptor(size=webgpu.wgpuBufferGetSize(bufs[0]), usage=webgpu.wgpuBufferGetUsage(bufs[0]))) + buf_patch = True + + # Creating bind group layout + binding_layouts = [webgpu.WGPUBindGroupLayoutEntry(binding=0, visibility= webgpu.WGPUShaderStage_Compute, + buffer=webgpu.WGPUBufferBindingLayout(type=webgpu.WGPUBufferBindingType_Uniform))] + binding_layouts += [webgpu.WGPUBindGroupLayoutEntry(binding=i+1, visibility=webgpu.WGPUShaderStage_Compute, + buffer=webgpu.WGPUBufferBindingLayout(type=webgpu.WGPUBufferBindingType_Uniform if i >= len(tmp_bufs) + else webgpu.WGPUBufferBindingType_Storage)) for i in range(len(tmp_bufs)+len(vals))] + + bl_arr_type = webgpu.WGPUBindGroupLayoutEntry * len(binding_layouts) + webgpu.wgpuDevicePushErrorScope(self.dev, webgpu.WGPUErrorFilter_Validation) + bind_group_layouts = [webgpu.wgpuDeviceCreateBindGroupLayout(self.dev, webgpu.WGPUBindGroupLayoutDescriptor( + entryCount=len(binding_layouts), entries=ctypes.cast(bl_arr_type(*binding_layouts), ctypes.POINTER(webgpu.WGPUBindGroupLayoutEntry))))] + + if bg_layout_err := pop_error(self.dev): raise RuntimeError(f"Error creating bind group layout: {bg_layout_err}") + + # Creating pipeline layout + pipeline_layout_desc = webgpu.WGPUPipelineLayoutDescriptor(bindGroupLayoutCount=len(bind_group_layouts), + bindGroupLayouts = (webgpu.WGPUBindGroupLayout * len(bind_group_layouts))(*bind_group_layouts)) + + webgpu.wgpuDevicePushErrorScope(self.dev, webgpu.WGPUErrorFilter_Validation) + pipeline_layout = webgpu.wgpuDeviceCreatePipelineLayout(self.dev, pipeline_layout_desc) + + if pipe_err := pop_error(self.dev): raise RuntimeError(f"Error creating pipeline layout: {pipe_err}") + + # Creating bind group + bindings = [webgpu.WGPUBindGroupEntry(binding=0, buffer=create_uniform(self.dev, float('inf')), offset=0, size=4)] + bindings += [webgpu.WGPUBindGroupEntry(binding=i+1, buffer=create_uniform(self.dev, x) if i >= len(tmp_bufs) else x, offset=0, + size=4 if i >= len(tmp_bufs) else webgpu.wgpuBufferGetSize(x)) for i,x in enumerate(tuple(tmp_bufs)+vals)] + + bg_arr_type = webgpu.WGPUBindGroupEntry * len(bindings) + bind_group_desc = webgpu.WGPUBindGroupDescriptor(layout=bind_group_layouts[0], entryCount=len(bindings), entries=bg_arr_type(*bindings)) + webgpu.wgpuDevicePushErrorScope(self.dev, webgpu.WGPUErrorFilter_Validation) + bind_group = webgpu.wgpuDeviceCreateBindGroup(self.dev, bind_group_desc) + + if bind_err := pop_error(self.dev): raise RuntimeError(f"Error creating bind group: {bind_err}") + + # Creating compute pipeline + compute_desc = webgpu.WGPUComputePipelineDescriptor(layout=pipeline_layout, + compute=webgpu.WGPUComputeState(module=self.prg, entryPoint=to_wgpu_str(self.name))) + pipeline_result = _run(webgpu.wgpuDeviceCreateComputePipelineAsync2, webgpu.WGPUCreateComputePipelineAsyncCallbackInfo2, + webgpu.WGPUCreateComputePipelineAsyncCallback2, webgpu.WGPUCreatePipelineAsyncStatus__enumvalues, 1, None, self.dev, compute_desc) + + command_encoder = webgpu.wgpuDeviceCreateCommandEncoder(self.dev, webgpu.WGPUCommandEncoderDescriptor()) + comp_pass_desc = webgpu.WGPUComputePassDescriptor(nextInChain=None) + if wait: - query_set = self.dev.create_query_set(type=wgpu.QueryType.timestamp, count=2) - query_buf = self.dev.create_buffer(size=16, usage=wgpu.BufferUsage.QUERY_RESOLVE | wgpu.BufferUsage.COPY_SRC) - timestamp_writes = {"query_set": query_set, "beginning_of_pass_write_index": 0, "end_of_pass_write_index": 1} - compute_pass = command_encoder.begin_compute_pass(timestamp_writes=timestamp_writes if wait else None) # pylint: disable=E0606 - compute_pass.set_pipeline(compute_pipeline) - compute_pass.set_bind_group(0, bind_group, [], 0, 999999) # last 2 not used - compute_pass.dispatch_workgroups(*global_size) # x y z - compute_pass.end() + query_set = webgpu.wgpuDeviceCreateQuerySet(self.dev, webgpu.WGPUQuerySetDescriptor(type=webgpu.WGPUQueryType_Timestamp, count=2)) + query_buf = webgpu.wgpuDeviceCreateBuffer(self.dev, + webgpu.WGPUBufferDescriptor(size=16, usage=webgpu.WGPUBufferUsage_QueryResolve | webgpu.WGPUBufferUsage_CopySrc)) + comp_pass_desc.timestampWrites = ctypes.pointer(webgpu.WGPUComputePassTimestampWrites( + querySet=query_set, beginningOfPassWriteIndex=0, endOfPassWriteIndex=1)) + + # Begin compute pass + compute_pass = webgpu.wgpuCommandEncoderBeginComputePass(command_encoder, comp_pass_desc) + webgpu.wgpuComputePassEncoderSetPipeline(compute_pass, pipeline_result) + webgpu.wgpuComputePassEncoderSetBindGroup(compute_pass, 0, bind_group, 0, None) + webgpu.wgpuComputePassEncoderDispatchWorkgroups(compute_pass, *global_size) + webgpu.wgpuComputePassEncoderEnd(compute_pass) + + if wait: webgpu.wgpuCommandEncoderResolveQuerySet(command_encoder, query_set, 0, 2, query_buf, 0) + + cmd_buf = webgpu.wgpuCommandEncoderFinish(command_encoder, webgpu.WGPUCommandBufferDescriptor()) + webgpu.wgpuQueueSubmit(webgpu.wgpuDeviceGetQueue(self.dev), 1, (webgpu.WGPUCommandBuffer*1)(cmd_buf)) + + if buf_patch: + copy_buffer_to_buffer(self.dev, tmp_bufs[0], 0, bufs[0], 0, webgpu.wgpuBufferGetSize(bufs[0])) + webgpu.wgpuBufferDestroy(tmp_bufs[0]) + if wait: - command_encoder.resolve_query_set(query_set=query_set, first_query=0, query_count=2, destination=query_buf, destination_offset=0) - self.dev.queue.submit([command_encoder.finish()]) - return ((timestamps:=self.dev.queue.read_buffer(query_buf).cast("Q").tolist())[1] - timestamps[0]) / 1e9 if wait else None - -# WebGPU buffers have to be 4-byte aligned -class WebGpuAllocator(Allocator): - def __init__(self, dev): self.dev = dev - def _alloc(self, size: int, options): - return self.dev.create_buffer(size=round_up(size, 4), usage=wgpu.BufferUsage.STORAGE | wgpu.BufferUsage.COPY_DST | wgpu.BufferUsage.COPY_SRC) - def _copyin(self, dest, src: memoryview): + time = ((timestamps:=read_buffer(self.dev, query_buf).cast("Q").tolist())[1] - timestamps[0]) / 1e9 + webgpu.wgpuBufferDestroy(query_buf) + webgpu.wgpuQuerySetDestroy(query_set) + return time + return None + +class WebGpuAllocator(Allocator['WGPUDevPtr']): + def _alloc(self, size:int, options:BufferSpec) -> WGPUBufPtr: + # WebGPU buffers have to be 4-byte aligned + return webgpu.wgpuDeviceCreateBuffer(self.dev, webgpu.WGPUBufferDescriptor(size=round_up(size, 4), + usage=webgpu.WGPUBufferUsage_Storage | webgpu.WGPUBufferUsage_CopyDst | webgpu.WGPUBufferUsage_CopySrc)) + def _copyin(self, dest:WGPUBufPtr, src:memoryview): if src.nbytes % 4: padded_src = bytearray(round_up(src.nbytes, 4)) padded_src[:src.nbytes] = src - self.dev.queue.write_buffer(dest, 0, padded_src if src.nbytes % 4 else src) - def _copyout(self, dest: memoryview, src): - buffer_data = self.dev.queue.read_buffer(src, 0) - dest[:] = buffer_data[:dest.nbytes] if src._nbytes > dest.nbytes else buffer_data + write_buffer(self.dev, dest, 0, padded_src if src.nbytes % 4 else src) + def _copyout(self, dest:memoryview, src:WGPUBufPtr): + buffer_data = read_buffer(self.dev, src) + dest[:] = buffer_data[:dest.nbytes] if webgpu.wgpuBufferGetSize(src) > dest.nbytes else buffer_data + def _free(self, opaque:WGPUBufPtr, options:BufferSpec): + webgpu.wgpuBufferDestroy(opaque) class WebGpuDevice(Compiled): def __init__(self, device:str): - adapter = wgpu.gpu.request_adapter_sync(power_preference="high-performance") - timestamp_supported = wgpu.FeatureName.timestamp_query in adapter.features - wgpu_device = adapter.request_device_sync(required_features=[wgpu.FeatureName.timestamp_query] if timestamp_supported else []) - super().__init__(device, WebGpuAllocator(wgpu_device), WGSLRenderer(), Compiler(), - functools.partial(WebGPUProgram, (wgpu_device, timestamp_supported))) + # Requesting an adapter + adapter_res = _run(webgpu.wgpuInstanceRequestAdapterF, webgpu.WGPURequestAdapterCallbackInfo, webgpu.WGPURequestAdapterCallback, + webgpu.WGPURequestAdapterStatus__enumvalues, 1, 2, instance, + + webgpu.WGPURequestAdapterOptions(powerPreference=webgpu.WGPUPowerPreference_HighPerformance, + backendType=backend_types.get(os.getenv("WEBGPU_BACKEND", ""), 0))) + + # Get supported features + supported_features = webgpu.WGPUSupportedFeatures() + webgpu.wgpuAdapterGetFeatures(adapter_res, supported_features) + supported = [supported_features.features[i] for i in range(supported_features.featureCount)] + features = [feat for feat in [webgpu.WGPUFeatureName_TimestampQuery, webgpu.WGPUFeatureName_ShaderF16] if feat in supported] + dev_desc = webgpu.WGPUDeviceDescriptor(requiredFeatureCount=len(features),requiredFeatures=(webgpu.WGPUFeatureName * len(features))(*features)) + + # Limits + supported_limits = webgpu.WGPUSupportedLimits() + webgpu.wgpuAdapterGetLimits(adapter_res, ctypes.cast(ctypes.pointer(supported_limits),ctypes.POINTER(webgpu.struct_WGPUSupportedLimits))) + limits = webgpu.WGPURequiredLimits(limits=supported_limits.limits) + dev_desc.requiredLimits = ctypes.cast(ctypes.pointer(limits),ctypes.POINTER(webgpu.struct_WGPURequiredLimits)) + + # Requesting a device + device_res = _run(webgpu.wgpuAdapterRequestDeviceF, webgpu.WGPURequestDeviceCallbackInfo, webgpu.WGPURequestDeviceCallback, + webgpu.WGPURequestDeviceStatus__enumvalues, 1, 2, adapter_res, dev_desc) + + super().__init__(device, WebGpuAllocator(device_res), WGSLRenderer(), Compiler(), + functools.partial(WebGPUProgram, (device_res, webgpu.WGPUFeatureName_TimestampQuery in supported))) + + def synchronize(self): + _run(webgpu.wgpuQueueOnSubmittedWorkDone2, webgpu.WGPUQueueWorkDoneCallbackInfo2, webgpu.WGPUQueueWorkDoneCallback2, + webgpu.WGPUQueueWorkDoneStatus__enumvalues, None, None, webgpu.wgpuDeviceGetQueue(self.runtime.args[0][0])) diff --git a/tinygrad_repo/tinygrad/runtime/support/allocator.py b/tinygrad_repo/tinygrad/runtime/support/allocator.py new file mode 100644 index 0000000000..12c9757281 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/allocator.py @@ -0,0 +1,97 @@ +import collections, functools +from tinygrad.helpers import round_up + +class TLSFAllocator: + """ + The allocator is based on the Two-Level Segregated Fit (TLSF) algorithm. The allocator maintains 2 level of buckets: + * 1st level is determined by the most significant bit of the size. + * 2nd level splits the covered memory of 1st level into @lv2_cnt entries. + + For each allocation request, the allocator searches for the smallest block that can fit the requested size. + For each deallocation request, the allocator merges the block with its neighbors if they are free. + """ + + def __init__(self, size:int, base:int=0, block_size:int=16, lv2_cnt:int=16): + self.size, self.base, self.block_size, self.l2_cnt = size, base, block_size, lv2_cnt.bit_length() + self.storage:list = [collections.defaultdict(list) for _ in range(size.bit_length() + 1)] + self.lv1_entries:list[int] = [0] * len(self.storage) + + # self.blocks is more like a linked list, where each entry is a contigous block. + self.blocks:dict[int, tuple[int, int|None, int|None, bool]] = {0: (size, None, None, True)} # size, next, prev, is_free + self._insert_block(0, size) + + @functools.cache + def lv1(self, size): return size.bit_length() + + @functools.cache + def lv2(self, size): return (size - (1 << (size.bit_length() - 1))) // (1 << max(0, size.bit_length() - self.l2_cnt)) + + def _insert_block(self, start:int, size:int, prev:int|None=None): + if prev is None: prev = self.blocks[start][2] + self.storage[self.lv1(size)][self.lv2(size)].append(start) + self.lv1_entries[self.lv1(size)] += 1 + self.blocks[start] = (size, start + size, prev, True) + return self + + def _remove_block(self, start:int, size:int, prev:int|None=None): + if prev is None: prev = self.blocks[start][2] + self.storage[self.lv1(size)][self.lv2(size)].remove(start) + self.lv1_entries[self.lv1(size)] -= 1 + self.blocks[start] = (size, start + size, prev, False) + return self + + def _split_block(self, start:int, size:int, new_size:int): + nxt = self.blocks[start][1] + assert self.blocks[start][3], "block must be free" + self._remove_block(start, size)._insert_block(start, new_size)._insert_block(start + new_size, size - new_size, prev=start) + if nxt in self.blocks: self.blocks[nxt] = (self.blocks[nxt][0], self.blocks[nxt][1], start + new_size, self.blocks[nxt][3]) + return self + + def _merge_right(self, start:int): + size, nxt, _, is_free = self.blocks[start] + assert is_free, "block must be free" + + while is_free and nxt in self.blocks: + if (blk:=self.blocks[nxt])[3] is False: break + self._remove_block(start, size)._remove_block(nxt, blk[0])._insert_block(start, size:=size + blk[0]) + assert self.blocks[start][1] == blk[1] + _, nxt, _, _ = self.blocks.pop(nxt) + + if nxt in self.blocks: self.blocks[nxt] = (self.blocks[nxt][0], self.blocks[nxt][1], start, self.blocks[nxt][3]) + + def _merge_block(self, start:int): + # Go left while blocks are free. Then merge all them right. + while (x:=self.blocks[start][2]) is not None and self.blocks[x][3] is True: start = x + self._merge_right(start) + + def alloc(self, req_size:int, align:int=1) -> int: + req_size = max(self.block_size, req_size) # at least block size. + size = max(self.block_size, req_size + align - 1) + + # Round up the allocation size to the next bucket, so any entry there can fit the requested size. + size = round_up(size, (1 << size.bit_length() - self.l2_cnt)) + + # Search for the smallest block that can fit the requested size. Start with the it's bucket and go up until any block is found. + for l1 in range(self.lv1(size), len(self.storage)): + if self.lv1_entries[l1] == 0: continue + for l2 in range(self.lv2(size) if l1 == size.bit_length() else 0, (1 << self.l2_cnt)): + if len(self.storage[l1][l2]) > 0: + nsize = self.blocks[self.storage[l1][l2][0]][0] + assert nsize >= size, "block must be larger" + + # Block start address. + start = self.storage[l1][l2][0] + + # If request contains alignment, split the block into two parts. + if (new_start:=round_up(start, align)) != start: + self._split_block(start, nsize, new_start - start) + start, nsize = new_start, self.blocks[new_start][0] + + # If the block is larger than the requested size, split it into two parts. + if nsize > req_size: self._split_block(start, nsize, req_size) + self._remove_block(start, req_size) # Mark the block as allocated. + return start + self.base + raise MemoryError(f"Can't allocate {req_size} bytes") + + def free(self, start:int): + self._insert_block(start - self.base, self.blocks[start - self.base][0])._merge_block(start - self.base) diff --git a/system/camerad/snapshot/__init__.py b/tinygrad_repo/tinygrad/runtime/support/am/__init__.py similarity index 100% rename from system/camerad/snapshot/__init__.py rename to tinygrad_repo/tinygrad/runtime/support/am/__init__.py diff --git a/tinygrad_repo/tinygrad/runtime/support/am/amdev.py b/tinygrad_repo/tinygrad/runtime/support/am/amdev.py new file mode 100644 index 0000000000..1bbdfbd89a --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/am/amdev.py @@ -0,0 +1,392 @@ +from __future__ import annotations +import ctypes, collections, time, dataclasses, functools, fcntl, os, hashlib +from tinygrad.helpers import mv_address, getenv, round_up, DEBUG, temp, fetch +from tinygrad.runtime.autogen.am import am +from tinygrad.runtime.support.hcq import MMIOInterface +from tinygrad.runtime.support.amd import AMDReg, import_module, import_asic_regs +from tinygrad.runtime.support.allocator import TLSFAllocator +from tinygrad.runtime.support.am.ip import AM_SOC, AM_GMC, AM_IH, AM_PSP, AM_SMU, AM_GFX, AM_SDMA + +AM_DEBUG = getenv("AM_DEBUG", 0) + +@dataclasses.dataclass(frozen=True) +class AMRegister(AMDReg): + adev:AMDev + + def read(self): return self.adev.rreg(self.addr) + def read_bitfields(self) -> dict[str, int]: return self.decode(self.read()) + + def write(self, _am_val:int=0, **kwargs): self.adev.wreg(self.addr, _am_val | self.encode(**kwargs)) + + def update(self, **kwargs): self.write(self.encode(**{**self.read_bitfields(), **kwargs})) + +class AMFirmware: + def __init__(self, adev): + self.adev = adev + def fmt_ver(hwip): return '_'.join(map(str, adev.ip_ver[hwip])) + + # Load SOS firmware + self.sos_fw = {} + + blob, sos_hdr = self.load_fw(f"psp_{fmt_ver(am.MP0_HWIP)}_sos.bin", am.struct_psp_firmware_header_v2_0) + fw_bin = sos_hdr.psp_fw_bin + + for fw_i in range(sos_hdr.psp_fw_bin_count): + fw_bin_desc = am.struct_psp_fw_bin_desc.from_address(ctypes.addressof(fw_bin) + fw_i * ctypes.sizeof(am.struct_psp_fw_bin_desc)) + ucode_start_offset = fw_bin_desc.offset_bytes + sos_hdr.header.ucode_array_offset_bytes + self.sos_fw[fw_bin_desc.fw_type] = blob[ucode_start_offset:ucode_start_offset+fw_bin_desc.size_bytes] + + # Load other fw + self.ucode_start: dict[str, int] = {} + self.descs: list[tuple[list[int], memoryview]] = [] + + blob, hdr = self.load_fw(f"smu_{fmt_ver(am.MP1_HWIP)}.bin", am.struct_smc_firmware_header_v1_0) + self.smu_psp_desc = self.desc(blob, hdr.header.ucode_array_offset_bytes, hdr.header.ucode_size_bytes, am.GFX_FW_TYPE_SMU) + + # SDMA firmware + blob, hdr, hdr_v3 = self.load_fw(f"sdma_{fmt_ver(am.SDMA0_HWIP)}.bin", am.struct_sdma_firmware_header_v2_0, am.struct_sdma_firmware_header_v3_0) + if hdr.header.header_version_major < 3: + self.descs += [self.desc(blob, hdr.ctl_ucode_offset, hdr.ctl_ucode_size_bytes, am.GFX_FW_TYPE_SDMA_UCODE_TH1)] + self.descs += [self.desc(blob, hdr.header.ucode_array_offset_bytes, hdr.ctx_ucode_size_bytes, am.GFX_FW_TYPE_SDMA_UCODE_TH0)] + else: self.descs += [self.desc(blob, hdr_v3.header.ucode_array_offset_bytes, hdr_v3.ucode_size_bytes, am.GFX_FW_TYPE_SDMA_UCODE_TH0)] + + # PFP, ME, MEC firmware + for (fw_name, fw_cnt) in ([('PFP', 1), ('ME', 1)] if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) else []) + [('MEC', 1)]: + blob, hdr = self.load_fw(f"gc_{fmt_ver(am.GC_HWIP)}_{fw_name.lower()}.bin", am.struct_gfx_firmware_header_v2_0) + + # Code part + self.descs += [self.desc(blob, hdr.header.ucode_array_offset_bytes, hdr.ucode_size_bytes, getattr(am, f'GFX_FW_TYPE_RS64_{fw_name}'))] + + # Stack + stack_fws = [getattr(am, f'GFX_FW_TYPE_RS64_{fw_name}_P{fwnum}_STACK') for fwnum in range(fw_cnt)] + self.descs += [self.desc(blob, hdr.data_offset_bytes, hdr.data_size_bytes, *stack_fws)] + self.ucode_start[fw_name] = hdr.ucode_start_addr_lo | (hdr.ucode_start_addr_hi << 32) + + # IMU firmware + blob, hdr = self.load_fw(f"gc_{fmt_ver(am.GC_HWIP)}_imu.bin", am.struct_imu_firmware_header_v1_0) + imu_i_off, imu_i_sz, imu_d_sz = hdr.header.ucode_array_offset_bytes, hdr.imu_iram_ucode_size_bytes, hdr.imu_dram_ucode_size_bytes + self.descs += [self.desc(blob, imu_i_off, imu_i_sz, am.GFX_FW_TYPE_IMU_I), self.desc(blob, imu_i_off + imu_i_sz, imu_d_sz, am.GFX_FW_TYPE_IMU_D)] + + # RLC firmware + blob, hdr0, _hdr1, hdr2, hdr3 = self.load_fw(f"gc_{fmt_ver(am.GC_HWIP)}_rlc.bin", am.struct_rlc_firmware_header_v2_0, + am.struct_rlc_firmware_header_v2_1, am.struct_rlc_firmware_header_v2_2, am.struct_rlc_firmware_header_v2_3) + + for mem,fmem in [('IRAM', 'iram'), ('DRAM_BOOT', 'dram')]: + off, sz = getattr(hdr2, f'rlc_{fmem}_ucode_offset_bytes'), getattr(hdr2, f'rlc_{fmem}_ucode_size_bytes') + self.descs += [self.desc(blob, off, sz, getattr(am, f'GFX_FW_TYPE_RLC_{mem}'))] + + if hdr0.header.header_version_minor == 3: + for mem in ['P', 'V']: + off, sz = getattr(hdr3, f'rlc{mem.lower()}_ucode_offset_bytes'), getattr(hdr3, f'rlc{mem.lower()}_ucode_size_bytes') + self.descs += [self.desc(blob, off, sz, getattr(am, f'GFX_FW_TYPE_RLC_{mem}'))] + + self.descs += [self.desc(blob, hdr0.header.ucode_array_offset_bytes, hdr0.header.ucode_size_bytes, am.GFX_FW_TYPE_RLC_G)] + + def load_fw(self, fname:str, *headers): + fpath = fetch(f"https://gitlab.com/kernel-firmware/linux-firmware/-/raw/45f59212aebd226c7630aff4b58598967c0c8c91/amdgpu/{fname}", subdir="fw") + blob = memoryview(bytearray(fpath.read_bytes())) + if AM_DEBUG >= 1: print(f"am {self.adev.devfmt}: loading firmware {fname}: {hashlib.sha256(blob).hexdigest()}") + return tuple([blob] + [hdr.from_address(mv_address(blob)) for hdr in headers]) + + def desc(self, blob:memoryview, offset:int, size:int, *types:int) -> tuple[list[int], memoryview]: return (list(types), blob[offset:offset+size]) + +@dataclasses.dataclass(frozen=True) +class AMMapping: va_addr:int; size:int; paddrs:list[tuple[int, int]]; uncached:bool=False; system:bool=False; snooped:bool=False # noqa: E702 + +class AMPageTableEntry: + def __init__(self, adev, paddr, lv): self.adev, self.paddr, self.lv, self.entries = adev, paddr, lv, adev.vram.view(paddr, 0x1000, fmt='Q') + + def set_entry(self, entry_id:int, paddr:int, table=False, uncached=False, system=False, snooped=False, frag=0, valid=True): + assert paddr & self.adev.gmc.address_space_mask == paddr, f"Invalid physical address {paddr:#x}" + self.entries[entry_id] = self.adev.gmc.get_pte_flags(self.lv, table, frag, uncached, system, snooped, valid) | (paddr & 0x0000FFFFFFFFF000) + +class AMPageTableTraverseContext: + def __init__(self, adev, pt, vaddr, create_pts=False, free_pts=False, boot=False): + self.adev, self.vaddr, self.create_pts, self.free_pts, self.boot = adev, vaddr - adev.gmc.vm_base, create_pts, free_pts, boot + self.pt_stack:list[tuple[AMPageTableEntry, int, int]] = [(pt, self._pt_pte_idx(pt, vaddr), self._pt_pte_size(pt))] + + def _pt_pte_size(self, pt): return (1 << ((9 * (3-pt.lv)) + 12)) + def _pt_pte_idx(self, pt, va): return (va // self._pt_pte_size(pt)) % 512 + + def level_down(self): + pt, pte_idx, _ = self.pt_stack[-1] + if (entry:=pt.entries[pte_idx]) & am.AMDGPU_PTE_VALID == 0: + assert self.create_pts, "Not allowed to create new page table" + pt.set_entry(pte_idx, self.adev.mm.palloc(0x1000, zero=True, boot=self.boot), table=True, valid=True) + entry = pt.entries[pte_idx] + + assert not self.adev.gmc.is_pte_huge_page(entry), f"Must be table pt={pt.paddr:#x}, {pte_idx=} {entry=:#x}" + child_page_table = AMPageTableEntry(self.adev, entry & 0x0000FFFFFFFFF000, lv=pt.lv+1) + + self.pt_stack.append((child_page_table, self._pt_pte_idx(child_page_table, self.vaddr), self._pt_pte_size(child_page_table))) + return self.pt_stack[-1] + + def _try_free_pt(self) -> bool: + pt, _, _ = self.pt_stack[-1] + if self.free_pts and pt != self.adev.mm.root_page_table and all(pt.entries[i] & am.AMDGPU_PTE_VALID == 0 for i in range(512)): + self.adev.mm.pfree(pt.paddr) + parent_pt, parent_pte_idx, _ = self.pt_stack[-2] + parent_pt.set_entry(parent_pte_idx, 0x0, valid=False) + return True + return False + + def level_up(self): + while self._try_free_pt() or self.pt_stack[-1][1] == 512: + _, pt_cnt, _ = self.pt_stack.pop() + if pt_cnt == 512: self.pt_stack[-1] = (self.pt_stack[-1][0], self.pt_stack[-1][1] + 1, self.pt_stack[-1][2]) + + def next(self, size:int, off=0): + while size > 0: + pt, pte_idx, pte_covers = self.pt_stack[-1] + if self.create_pts: + while pte_covers > size: pt, pte_idx, pte_covers = self.level_down() + else: + while pt.lv!=am.AMDGPU_VM_PTB and not self.adev.gmc.is_pte_huge_page(pt.entries[pte_idx]): pt, pte_idx, pte_covers = self.level_down() + + entries = min(size // pte_covers, 512 - pte_idx) + assert entries > 0, "Invalid entries" + yield off, pt, pte_idx, entries, pte_covers + + size, off, self.vaddr = size - entries * pte_covers, off + entries * pte_covers, self.vaddr + entries * pte_covers + self.pt_stack[-1] = (pt, pte_idx + entries, pte_covers) + self.level_up() + +class AMMemoryManager: + va_allocator = TLSFAllocator(512 * (1 << 30), base=0x7F0000000000) # global for all devices. + + def __init__(self, adev:AMDev, vram_size:int): + self.adev, self.vram_size = adev, vram_size + self.boot_allocator = TLSFAllocator(32 << 20, base=0) # per device + self.pa_allocator = TLSFAllocator(vram_size - (64 << 20), base=self.boot_allocator.size) # per device + self.root_page_table = AMPageTableEntry(self.adev, self.palloc(0x1000, zero=not self.adev.smi_dev, boot=True), lv=am.AMDGPU_VM_PDB1) + + def _frag_size(self, va, sz, must_cover=True): + """ + Calculate the tlb fragment size for a given virtual address and size. + If must_cover is True, the fragment size must cover the size, otherwise the biggest fragment size that fits the size is returned. + Fragment 0 is 4KB, 1 is 8KB and so on. + """ + va_pwr2_div, sz_pwr2_div, sz_pwr2_max = va & -(va) if va > 0 else (1 << 63), sz & -(sz), (1 << (sz.bit_length() - 1)) + return (min(va_pwr2_div, sz_pwr2_div) if must_cover else min(va_pwr2_div, sz_pwr2_max)).bit_length() - 1 - 12 + + def map_range(self, vaddr:int, size:int, paddrs:list[tuple[int, int]], uncached=False, system=False, snooped=False, boot=False) -> AMMapping: + if AM_DEBUG >= 2: print(f"am {self.adev.devfmt}: mapping {vaddr=:#x} ({size=:#x})") + + assert size == sum(p[1] for p in paddrs), f"Size mismatch {size=} {sum(p[1] for p in paddrs)=}" + + ctx = AMPageTableTraverseContext(self.adev, self.root_page_table, vaddr, create_pts=True, boot=boot) + for paddr, psize in paddrs: + for off, pt, pte_idx, pte_cnt, pte_covers in ctx.next(psize): + for pte_off in range(pte_cnt): + assert pt.entries[pte_idx + pte_off] & am.AMDGPU_PTE_VALID == 0, f"PTE already mapped: {pt.entries[pte_idx + pte_off]:#x}" + pt.set_entry(pte_idx + pte_off, paddr + off + pte_off * pte_covers, uncached=uncached, system=system, snooped=snooped, + frag=self._frag_size(ctx.vaddr+off, pte_cnt * pte_covers), valid=True) + + # Invalidate TLB after mappings. + self.adev.gmc.flush_tlb(ip='GC', vmid=0) + self.adev.gmc.flush_tlb(ip='MM', vmid=0) + return AMMapping(vaddr, size, paddrs, uncached=uncached, system=system, snooped=snooped) + + def unmap_range(self, vaddr:int, size:int): + if AM_DEBUG >= 2: print(f"am {self.adev.devfmt}: unmapping {vaddr=:#x} ({size=:#x})") + + ctx = AMPageTableTraverseContext(self.adev, self.root_page_table, vaddr, free_pts=True) + for off, pt, pte_idx, pte_cnt, pte_covers in ctx.next(size): + for pte_id in range(pte_idx, pte_idx + pte_cnt): + assert pt.entries[pte_id] & am.AMDGPU_PTE_VALID == am.AMDGPU_PTE_VALID, f"PTE not mapped: {pt.entries[pte_id]:#x}" + pt.set_entry(pte_id, paddr=0x0, valid=False) + + @staticmethod + def alloc_vaddr(size:int, align=0x1000) -> int: return AMMemoryManager.va_allocator.alloc(size, max((1 << (size.bit_length() - 1)), align)) + + def valloc(self, size:int, align=0x1000, uncached=False, contigous=False) -> AMMapping: + # Alloc physical memory and map it to the virtual address + va = self.alloc_vaddr(size:=round_up(size, 0x1000), align) + + if contigous: paddrs = [(self.palloc(size, zero=True), size)] + else: + # Traverse the PT to find the largest contiguous sizes we need to allocate. Try to allocate the longest segment to reduce TLB pressure. + paddrs = [] + ctx = AMPageTableTraverseContext(self.adev, self.root_page_table, va, create_pts=True) + for off, _, _, seg_cnt, seg_size in ctx.next(size): + rem_len = seg_cnt * seg_size + while rem_len > 0: + # Try to allocate as long segment (power of 2) as possible + cont_seg_sz, paddr = 1 << (self._frag_size(ctx.vaddr+off, rem_len) + 12), None + while cont_seg_sz >= 0x1000: + try: paddr = self.palloc(cont_seg_sz, zero=False) + except MemoryError: cont_seg_sz //= 2 + else: break + + if paddr is not None: paddrs += [(paddr, cont_seg_sz)] + else: + for paddr, _ in paddrs: self.pa_allocator.free(paddr) + raise MemoryError(f"Failed to allocate a contiguous page. (allocation size={size:#x})") + rem_len, off = rem_len - cont_seg_sz, off + cont_seg_sz + + return self.map_range(va, size, paddrs, uncached=uncached) + + def vfree(self, vm:AMMapping): + self.unmap_range(vm.va_addr, vm.size) + self.va_allocator.free(vm.va_addr) + for paddr, _ in vm.paddrs: self.pa_allocator.free(paddr) + + def palloc(self, size:int, align:int=0x1000, zero=True, boot=False) -> int: + assert self.adev.is_booting == boot, "During booting, only boot memory can be allocated" + paddr = (self.boot_allocator if boot else self.pa_allocator).alloc(round_up(size, 0x1000), align) + if zero: self.adev.vram[paddr:paddr+size] = bytes(size) + return paddr + + def pfree(self, paddr:int): self.pa_allocator.free(paddr) + +class AMDev: + def __init__(self, devfmt, vram:MMIOInterface, doorbell:MMIOInterface, mmio:MMIOInterface, dma_regions:list[tuple[int, MMIOInterface]]|None=None): + self.devfmt, self.vram, self.doorbell64, self.mmio, self.dma_regions = devfmt, vram, doorbell, mmio, dma_regions + + os.umask(0) # Set umask to 0 to allow creating files with 0666 permissions + + # Avoid O_CREAT because we don’t want to re-create/replace an existing file (triggers extra perms checks) when opening as non-owner. + if os.path.exists(lock_name:=temp(f"am_{self.devfmt}.lock")): self.lock_fd = os.open(lock_name, os.O_RDWR) + else: self.lock_fd = os.open(lock_name, os.O_RDWR | os.O_CREAT | os.O_CLOEXEC, 0o666) + + try: fcntl.flock(self.lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) + except OSError: raise RuntimeError(f"Failed to open AM device {self.devfmt}. It's already in use.") + + self._run_discovery() + self._build_regs() + + # AM boot Process: + # The GPU being passed can be in one of several states: 1. Not initialized. 2. Initialized by amdgpu. 3. Initialized by AM. + # The 1st and 2nd states require a full GPU setup since their states are unknown. The 2nd state also requires a mode1 reset to + # reinitialize all components. + # + # The 3rd state can be set up partially to optimize boot time. In this case, only the GFX and SDMA IPs need to be initialized. + # To enable this, AM uses a separate boot memory that is guaranteed not to be overwritten. This physical memory is utilized for + # all blocks that are initialized only during the initial AM boot. + # To determine if the GPU is in the third state, AM uses regSCRATCH_REG7 as a flag. + self.is_booting, self.smi_dev = True, False # During boot only boot memory can be allocated. This flag is to validate this. + self.partial_boot = (self.reg("regSCRATCH_REG7").read() == (am_version:=0xA0000004)) and (getenv("AM_RESET", 0) != 1) + + # Memory manager & firmware + self.mm = AMMemoryManager(self, self.vram_size) + self.fw = AMFirmware(self) + + # Initialize IP blocks + self.soc:AM_SOC = AM_SOC(self) + self.gmc:AM_GMC = AM_GMC(self) + self.ih:AM_IH = AM_IH(self) + self.psp:AM_PSP = AM_PSP(self) + self.smu:AM_SMU = AM_SMU(self) + self.gfx:AM_GFX = AM_GFX(self) + self.sdma:AM_SDMA = AM_SDMA(self) + + if self.partial_boot and (self.reg("regGCVM_CONTEXT0_CNTL").read() != 0): + if DEBUG >= 2: print(f"am {self.devfmt}: MEC is active. Issue a full reset.") + self.partial_boot = False + + # Init sw for all IP blocks + for ip in [self.soc, self.gmc, self.ih, self.psp, self.smu, self.gfx, self.sdma]: ip.init_sw() + + # Init hw for IP blocks where it is needed + if not self.partial_boot: + if self.psp.is_sos_alive() and self.smu.is_smu_alive(): self.smu.mode1_reset() + for ip in [self.soc, self.gmc, self.ih, self.psp, self.smu]: + ip.init_hw() + if DEBUG >= 2: print(f"am {self.devfmt}: {ip.__class__.__name__} initialized") + + # Booting done + self.is_booting = False + + # Re-initialize main blocks + for ip in [self.gfx, self.sdma]: + ip.init_hw() + if DEBUG >= 2: print(f"am {self.devfmt}: {ip.__class__.__name__} initialized") + + self.smu.set_clocks(level=-1) # last level, max perf. + for ip in [self.soc, self.gfx]: ip.set_clockgating_state() + self.reg("regSCRATCH_REG7").write(am_version) + if DEBUG >= 2: print(f"am {self.devfmt}: boot done") + + def fini(self): + if DEBUG >= 2: print(f"am {self.devfmt}: Finalizing") + for ip in [self.sdma, self.gfx]: ip.fini_hw() + self.smu.set_clocks(level=0) + self.ih.interrupt_handler() + os.close(self.lock_fd) + + def paddr2mc(self, paddr:int) -> int: return self.gmc.mc_base + paddr + + def reg(self, reg:str) -> AMRegister: return self.__dict__[reg] + + def rreg(self, reg:int) -> int: + val = self.indirect_rreg(reg * 4) if reg > len(self.mmio) else self.mmio[reg] + if AM_DEBUG >= 4 and getattr(self, '_prev_rreg', None) != (reg, val): print(f"am {self.devfmt}: Reading register {reg:#x} with value {val:#x}") + self._prev_rreg = (reg, val) + return val + + def wreg(self, reg:int, val:int): + if AM_DEBUG >= 4: print(f"am {self.devfmt}: Writing register {reg:#x} with value {val:#x}") + if reg > len(self.mmio): self.indirect_wreg(reg * 4, val) + else: self.mmio[reg] = val + + def wreg_pair(self, reg_base:str, lo_suffix:str, hi_suffix:str, val:int): + self.reg(f"{reg_base}{lo_suffix}").write(val & 0xffffffff) + self.reg(f"{reg_base}{hi_suffix}").write(val >> 32) + + def indirect_rreg(self, reg:int) -> int: + self.reg("regBIF_BX_PF0_RSMU_INDEX").write(reg) + return self.reg("regBIF_BX_PF0_RSMU_DATA").read() + + def indirect_wreg(self, reg:int, val:int): + self.reg("regBIF_BX_PF0_RSMU_INDEX").write(reg) + self.reg("regBIF_BX_PF0_RSMU_DATA").write(val) + + def wait_reg(self, reg:AMRegister, value:int, mask=0xffffffff, timeout=10000) -> int: + start_time = int(time.perf_counter() * 1000) + while int(time.perf_counter() * 1000) - start_time < timeout: + if ((rval:=reg.read()) & mask) == value: return rval + raise RuntimeError(f'wait_reg timeout reg=0x{reg.addr:X} mask=0x{mask:X} value=0x{value:X} last_val=0x{rval}') + + def _run_discovery(self): + # NOTE: Fixed register to query memory size without known ip bases to find the discovery table. + # The table is located at the end of VRAM - 64KB and is 10KB in size. + mmRCC_CONFIG_MEMSIZE = 0xde3 + self.vram_size = self.rreg(mmRCC_CONFIG_MEMSIZE) << 20 + tmr_offset, tmr_size = self.vram_size - (64 << 10), (10 << 10) + + self.bhdr = am.struct_binary_header.from_buffer(bytearray(self.vram.view(tmr_offset, tmr_size)[:])) + ihdr = am.struct_ip_discovery_header.from_address(ctypes.addressof(self.bhdr) + self.bhdr.table_list[am.IP_DISCOVERY].offset) + assert ihdr.signature == am.DISCOVERY_TABLE_SIGNATURE and not ihdr.base_addr_64_bit, f"0x{ihdr.signature:X} != 0x{am.DISCOVERY_TABLE_SIGNATURE:X}" + + # Mapping of HW IP to Discovery HW IP + hw_id_map = {am.__dict__[x]: int(y) for x,y in am.hw_id_map} + self.regs_offset:dict[int, dict[int, tuple]] = collections.defaultdict(dict) + self.ip_ver:dict[int, tuple[int, int, int]] = {} + + for num_die in range(ihdr.num_dies): + dhdr = am.struct_die_header.from_address(ctypes.addressof(self.bhdr) + ihdr.die_info[num_die].die_offset) + + ip_offset = ctypes.addressof(self.bhdr) + ctypes.sizeof(dhdr) + ihdr.die_info[num_die].die_offset + for _ in range(dhdr.num_ips): + ip = am.struct_ip_v4.from_address(ip_offset) + ba = (ctypes.c_uint32 * ip.num_base_address).from_address(ip_offset + 8) + for hw_ip in range(1, am.MAX_HWIP): + if hw_ip in hw_id_map and hw_id_map[hw_ip] == ip.hw_id: + self.regs_offset[hw_ip][ip.instance_number] = tuple(list(ba)) + self.ip_ver[hw_ip] = (ip.major, ip.minor, ip.revision) + + ip_offset += 8 + (8 if ihdr.base_addr_64_bit else 4) * ip.num_base_address + + gc_info = am.struct_gc_info_v1_0.from_address(gc_addr:=ctypes.addressof(self.bhdr) + self.bhdr.table_list[am.GC].offset) + self.gc_info = getattr(am, f"struct_gc_info_v{gc_info.header.version_major}_{gc_info.header.version_minor}").from_address(gc_addr) + + def _ip_module(self, prefix:str, hwip, prever_prefix:str=""): return import_module(prefix, self.ip_ver[hwip], prever_prefix) + + def _build_regs(self): + mods = [("mp", am.MP0_HWIP), ("hdp", am.HDP_HWIP), ("gc", am.GC_HWIP), ("mmhub", am.MMHUB_HWIP), ("osssys", am.OSSSYS_HWIP), + ("nbio" if self.ip_ver[am.GC_HWIP] < (12,0,0) else "nbif", am.NBIO_HWIP)] + + for prefix, hwip in mods: + self.__dict__.update(import_asic_regs(prefix, self.ip_ver[hwip], cls=functools.partial(AMRegister, adev=self, bases=self.regs_offset[hwip][0]))) + self.__dict__.update(import_asic_regs('mp', (11, 0), cls=functools.partial(AMRegister, adev=self, bases=self.regs_offset[am.MP1_HWIP][0]))) + diff --git a/tinygrad_repo/tinygrad/runtime/support/am/ip.py b/tinygrad_repo/tinygrad/runtime/support/am/ip.py new file mode 100644 index 0000000000..7412878ae3 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/am/ip.py @@ -0,0 +1,502 @@ +import ctypes, time, contextlib, importlib, functools +from typing import Literal +from tinygrad.runtime.autogen.am import am +from tinygrad.helpers import to_mv, data64, lo32, hi32, DEBUG + +class AM_IP: + def __init__(self, adev): self.adev = adev + def init_sw(self): pass # Prepare sw/allocations for this IP + def init_hw(self): pass # Initialize hw for this IP + def fini_hw(self): pass # Finalize hw for this IP + def set_clockgating_state(self): pass # Set clockgating state for this IP + +class AM_SOC(AM_IP): + def init_sw(self): + self.soc_ver = 24 if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) else 21 + self.module = importlib.import_module(f"tinygrad.runtime.autogen.am.soc{self.soc_ver}") + + def init_hw(self): + self.adev.regRCC_DEV0_EPF2_STRAP2.update(strap_no_soft_reset_dev0_f2=0x0) + self.adev.regRCC_DEV0_EPF0_RCC_DOORBELL_APER_EN.write(0x1) + def set_clockgating_state(self): self.adev.regHDP_MEM_POWER_CTRL.update(atomic_mem_power_ctrl_en=1, atomic_mem_power_ds_en=1) + + def doorbell_enable(self, port, awid=0, awaddr_31_28_value=0, offset=0, size=0): + self.adev.reg(f"{'regGDC_S2A0_S2A' if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) else 'regS2A'}_DOORBELL_ENTRY_{port}_CTRL").update( + **{f"s2a_doorbell_port{port}_enable":1, f"s2a_doorbell_port{port}_awid":awid, f"s2a_doorbell_port{port}_awaddr_31_28_value":awaddr_31_28_value, + f"s2a_doorbell_port{port}_range_offset":offset, f"s2a_doorbell_port{port}_range_size":size}) + +class AM_GMC(AM_IP): + def init_sw(self): + # Memory controller aperture + self.mc_base = (self.adev.regMMMC_VM_FB_LOCATION_BASE.read() & 0xFFFFFF) << 24 + self.mc_end = self.mc_base + self.adev.mm.vram_size - 1 + + # VM aperture + self.vm_base = self.adev.mm.va_allocator.base + self.vm_end = self.vm_base + self.adev.mm.va_allocator.size - 1 + + # GFX11/GFX12 has 44-bit address space + self.address_space_mask = (1 << 44) - 1 + + self.memscratch_paddr = self.adev.mm.palloc(0x1000, zero=not self.adev.partial_boot, boot=True) + self.dummy_page_paddr = self.adev.mm.palloc(0x1000, zero=not self.adev.partial_boot, boot=True) + self.hub_initted = {"MM": False, "GC": False} + + def init_hw(self): self.init_hub("MM") + + def flush_hdp(self): self.adev.wreg(self.adev.reg("regBIF_BX0_REMAP_HDP_MEM_FLUSH_CNTL").read() // 4, 0x0) + def flush_tlb(self, ip:Literal["MM", "GC"], vmid, flush_type=0): + self.flush_hdp() + + # Can't issue TLB invalidation if the hub isn't initialized. + if not self.hub_initted[ip]: return + + if ip == "MM": self.adev.wait_reg(self.adev.regMMVM_INVALIDATE_ENG17_SEM, mask=0x1, value=0x1) + + self.adev.reg(f"reg{ip}VM_INVALIDATE_ENG17_REQ").write(flush_type=flush_type, per_vmid_invalidate_req=(1 << vmid), invalidate_l2_ptes=1, + invalidate_l2_pde0=1, invalidate_l2_pde1=1, invalidate_l2_pde2=1, invalidate_l1_ptes=1, clear_protection_fault_status_addr=0) + + self.adev.wait_reg(self.adev.reg(f"reg{ip}VM_INVALIDATE_ENG17_ACK"), mask=(1 << vmid), value=(1 << vmid)) + + if ip == "MM": + self.adev.regMMVM_INVALIDATE_ENG17_SEM.write(0x0) + self.adev.regMMVM_L2_BANK_SELECT_RESERVED_CID2.update(reserved_cache_private_invalidation=1) + + # Read back the register to ensure the invalidation is complete + self.adev.regMMVM_L2_BANK_SELECT_RESERVED_CID2.read() + + def enable_vm_addressing(self, page_table, ip:Literal["MM", "GC"], vmid): + self.adev.wreg_pair(f"reg{ip}VM_CONTEXT{vmid}_PAGE_TABLE_START_ADDR", "_LO32", "_HI32", self.vm_base >> 12) + self.adev.wreg_pair(f"reg{ip}VM_CONTEXT{vmid}_PAGE_TABLE_END_ADDR", "_LO32", "_HI32", self.vm_end >> 12) + self.adev.wreg_pair(f"reg{ip}VM_CONTEXT{vmid}_PAGE_TABLE_BASE_ADDR", "_LO32", "_HI32", page_table.paddr | 1) + self.adev.reg(f"reg{ip}VM_CONTEXT{vmid}_CNTL").write(0x1800000, pde0_protection_fault_enable_interrupt=1, pde0_protection_fault_enable_default=1, + dummy_page_protection_fault_enable_interrupt=1, dummy_page_protection_fault_enable_default=1, + range_protection_fault_enable_interrupt=1, range_protection_fault_enable_default=1, + valid_protection_fault_enable_interrupt=1, valid_protection_fault_enable_default=1, + read_protection_fault_enable_interrupt=1, read_protection_fault_enable_default=1, + write_protection_fault_enable_interrupt=1, write_protection_fault_enable_default=1, + execute_protection_fault_enable_interrupt=1, execute_protection_fault_enable_default=1, + enable_context=1, page_table_depth=(3 - page_table.lv)) + + def init_hub(self, ip:Literal["MM", "GC"]): + # Init system apertures + self.adev.reg(f"reg{ip}MC_VM_AGP_BASE").write(0) + self.adev.reg(f"reg{ip}MC_VM_AGP_BOT").write(0xffffffffffff >> 24) # disable AGP + self.adev.reg(f"reg{ip}MC_VM_AGP_TOP").write(0) + + self.adev.reg(f"reg{ip}MC_VM_SYSTEM_APERTURE_LOW_ADDR").write(self.mc_base >> 18) + self.adev.reg(f"reg{ip}MC_VM_SYSTEM_APERTURE_HIGH_ADDR").write(self.mc_end >> 18) + self.adev.wreg_pair(f"reg{ip}MC_VM_SYSTEM_APERTURE_DEFAULT_ADDR", "_LSB", "_MSB", self.memscratch_paddr >> 12) + self.adev.wreg_pair(f"reg{ip}VM_L2_PROTECTION_FAULT_DEFAULT_ADDR", "_LO32", "_HI32", self.dummy_page_paddr >> 12) + + self.adev.reg(f"reg{ip}VM_L2_PROTECTION_FAULT_CNTL2").update(active_page_migration_pte_read_retry=1) + + # Init TLB and cache + self.adev.reg(f"reg{ip}MC_VM_MX_L1_TLB_CNTL").update(enable_l1_tlb=1, system_access_mode=3, enable_advanced_driver_model=1, + system_aperture_unmapped_access=0, eco_bits=0, mtype=self.adev.soc.module.MTYPE_UC) + + self.adev.reg(f"reg{ip}VM_L2_CNTL").update(enable_l2_cache=1, enable_l2_fragment_processing=0, enable_default_page_out_to_system_memory=1, + l2_pde0_cache_tag_generation_mode=0, pde_fault_classification=0, context1_identity_access_mode=1, identity_mode_fragment_size=0) + self.adev.reg(f"reg{ip}VM_L2_CNTL2").update(invalidate_all_l1_tlbs=1, invalidate_l2_cache=1) + self.adev.reg(f"reg{ip}VM_L2_CNTL3").write(bank_select=9, l2_cache_bigk_fragment_size=6,l2_cache_4k_associativity=1,l2_cache_bigk_associativity=1) + self.adev.reg(f"reg{ip}VM_L2_CNTL4").write(l2_cache_4k_partition_count=1) + self.adev.reg(f"reg{ip}VM_L2_CNTL5").write(walker_priority_client_id=0x1ff) + + self.enable_vm_addressing(self.adev.mm.root_page_table, ip, vmid=0) + + # Disable identity aperture + self.adev.wreg_pair(f"reg{ip}VM_L2_CONTEXT1_IDENTITY_APERTURE_LOW_ADDR", "_LO32", "_HI32", 0xfffffffff) + self.adev.wreg_pair(f"reg{ip}VM_L2_CONTEXT1_IDENTITY_APERTURE_HIGH_ADDR", "_LO32", "_HI32", 0x0) + self.adev.wreg_pair(f"reg{ip}VM_L2_CONTEXT_IDENTITY_PHYSICAL_OFFSET", "_LO32", "_HI32", 0x0) + + for eng_i in range(18): self.adev.wreg_pair(f"reg{ip}VM_INVALIDATE_ENG{eng_i}_ADDR_RANGE", "_LO32", "_HI32", 0x1fffffffff) + self.hub_initted[ip] = True + + @functools.cache + def get_pte_flags(self, pte_lv, is_table, frag, uncached, system, snooped, valid, extra=0): + extra |= (am.AMDGPU_PTE_SYSTEM * system) | (am.AMDGPU_PTE_SNOOPED * snooped) | (am.AMDGPU_PTE_VALID * valid) | am.AMDGPU_PTE_FRAG(frag) + if not is_table: extra |= (am.AMDGPU_PTE_WRITEABLE | am.AMDGPU_PTE_READABLE | am.AMDGPU_PTE_EXECUTABLE) + if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0): + extra |= am.AMDGPU_PTE_MTYPE_GFX12(0, self.adev.soc.module.MTYPE_UC if uncached else 0) + extra |= (am.AMDGPU_PDE_PTE_GFX12 if not is_table and pte_lv != am.AMDGPU_VM_PTB else (am.AMDGPU_PTE_IS_PTE if not is_table else 0)) + else: + extra |= am.AMDGPU_PTE_MTYPE_NV10(0, self.adev.soc.module.MTYPE_UC if uncached else 0) + extra |= (am.AMDGPU_PDE_PTE if not is_table and pte_lv != am.AMDGPU_VM_PTB else 0) + return extra + def is_pte_huge_page(self, pte): return pte & (am.AMDGPU_PDE_PTE_GFX12 if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) else am.AMDGPU_PDE_PTE) + + def on_interrupt(self): + for ip in ["MM", "GC"]: + st = self.adev.reg(f"reg{ip}VM_L2_PROTECTION_FAULT_STATUS{'_LO32' if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) else ''}").read() + va = (self.adev.reg(f'reg{ip}VM_L2_PROTECTION_FAULT_ADDR_LO32').read() + | (self.adev.reg(f'reg{ip}VM_L2_PROTECTION_FAULT_ADDR_HI32').read()) << 32) << 12 + if st: raise RuntimeError(f"{ip}VM_L2_PROTECTION_FAULT_STATUS: {st:#x} {va:#x}") + +class AM_SMU(AM_IP): + def init_sw(self): + self.smu_mod = self.adev._ip_module("smu", am.MP1_HWIP, prever_prefix='v') + self.driver_table_paddr = self.adev.mm.palloc(0x4000, zero=not self.adev.partial_boot, boot=True) + + def init_hw(self): + self._send_msg(self.smu_mod.PPSMC_MSG_SetDriverDramAddrHigh, hi32(self.adev.paddr2mc(self.driver_table_paddr))) + self._send_msg(self.smu_mod.PPSMC_MSG_SetDriverDramAddrLow, lo32(self.adev.paddr2mc(self.driver_table_paddr))) + self._send_msg(self.smu_mod.PPSMC_MSG_EnableAllSmuFeatures, 0) + + def is_smu_alive(self): + with contextlib.suppress(RuntimeError): self._send_msg(self.smu_mod.PPSMC_MSG_GetSmuVersion, 0, timeout=100) + return self.adev.mmMP1_SMN_C2PMSG_90.read() != 0 + + def mode1_reset(self): + if DEBUG >= 2: print(f"am {self.adev.devfmt}: mode1 reset") + if self.adev.ip_ver[am.MP0_HWIP] >= (14,0,0): self._send_msg(__DEBUGSMC_MSG_Mode1Reset:=2, 0, debug=True) + else: self._send_msg(self.smu_mod.PPSMC_MSG_Mode1Reset, 0) + time.sleep(0.5) # 500ms + + def read_table(self, table_t, cmd): + self._send_msg(self.smu_mod.PPSMC_MSG_TransferTableSmu2Dram, cmd) + return table_t.from_buffer(bytearray(self.adev.vram.view(self.driver_table_paddr, ctypes.sizeof(table_t))[:])) + def read_metrics(self): return self.read_table(self.smu_mod.SmuMetricsExternal_t, self.smu_mod.TABLE_SMU_METRICS) + + def set_clocks(self, level): + if not hasattr(self, 'clcks'): + self.clcks = {} + for clck in [self.smu_mod.PPCLK_GFXCLK, self.smu_mod.PPCLK_UCLK, self.smu_mod.PPCLK_FCLK, self.smu_mod.PPCLK_SOCCLK]: + cnt = self._send_msg(self.smu_mod.PPSMC_MSG_GetDpmFreqByIndex, (clck<<16)|0xff, read_back_arg=True)&0x7fffffff + self.clcks[clck] = [self._send_msg(self.smu_mod.PPSMC_MSG_GetDpmFreqByIndex, (clck<<16)|i, read_back_arg=True)&0x7fffffff for i in range(cnt)] + + for clck, vals in self.clcks.items(): + self._send_msg(self.smu_mod.PPSMC_MSG_SetSoftMinByFreq, clck << 16 | (vals[level])) + self._send_msg(self.smu_mod.PPSMC_MSG_SetSoftMaxByFreq, clck << 16 | (vals[level])) + + def _smu_cmn_send_msg(self, msg, param=0, debug=False): + (self.adev.mmMP1_SMN_C2PMSG_90 if not debug else self.adev.mmMP1_SMN_C2PMSG_54).write(0) # resp reg + (self.adev.mmMP1_SMN_C2PMSG_82 if not debug else self.adev.mmMP1_SMN_C2PMSG_53).write(param) + (self.adev.mmMP1_SMN_C2PMSG_66 if not debug else self.adev.mmMP1_SMN_C2PMSG_75).write(msg) + + def _send_msg(self, msg, param, read_back_arg=False, timeout=10000, debug=False): # 10s + self._smu_cmn_send_msg(msg, param, debug=debug) + self.adev.wait_reg(self.adev.mmMP1_SMN_C2PMSG_90 if not debug else self.adev.mmMP1_SMN_C2PMSG_54, mask=0xFFFFFFFF, value=1, timeout=timeout) + return (self.adev.mmMP1_SMN_C2PMSG_82 if not debug else self.adev.mmMP1_SMN_C2PMSG_53).read() if read_back_arg else None + +class AM_GFX(AM_IP): + def init_hw(self): + # Wait for RLC autoload to complete + while self.adev.regCP_STAT.read() != 0 and self.adev.regRLC_RLCS_BOOTLOAD_STATUS.read_bitfields()['bootload_complete'] != 0: pass + + self._config_gfx_rs64() + self.adev.gmc.init_hub("GC") + + # NOTE: Golden reg for gfx11. No values for this reg provided. The kernel just ors 0x20000000 to this reg. + self.adev.regTCP_CNTL.write(self.adev.regTCP_CNTL.read() | 0x20000000) + + self.adev.regRLC_SRM_CNTL.update(srm_enable=1, auto_incr_addr=1) + + self.adev.soc.doorbell_enable(port=0, awid=0x3, awaddr_31_28_value=0x3) + self.adev.soc.doorbell_enable(port=3, awid=0x6, awaddr_31_28_value=0x3) + + self.adev.regGRBM_CNTL.update(read_timeout=0xff) + for i in range(0, 16): + self._grbm_select(vmid=i) + self.adev.regSH_MEM_CONFIG.write(address_mode=self.adev.soc.module.SH_MEM_ADDRESS_MODE_64, + alignment_mode=self.adev.soc.module.SH_MEM_ALIGNMENT_MODE_UNALIGNED, initial_inst_prefetch=3) + + # Configure apertures: + # LDS: 0x10000000'00000000 - 0x10000001'00000000 (4GB) + # Scratch: 0x20000000'00000000 - 0x20000001'00000000 (4GB) + self.adev.regSH_MEM_BASES.write(shared_base=0x1, private_base=0x2) + self._grbm_select() + + # Configure MEC doorbell range + self.adev.regCP_MEC_DOORBELL_RANGE_LOWER.write(0x0) + self.adev.regCP_MEC_DOORBELL_RANGE_UPPER.write(0x450) + + # Enable MEC + self.adev.regCP_MEC_RS64_CNTL.update(mec_invalidate_icache=0, mec_pipe0_reset=0, mec_pipe0_active=1, mec_halt=0) + + # NOTE: Wait for MEC to be ready. The kernel does udelay here as well. + time.sleep(0.05) + + def fini_hw(self): + self._grbm_select(me=1, pipe=0, queue=0) + self.adev.regCP_HQD_DEQUEUE_REQUEST.write(0x2) # 1 - DRAIN_PIPE; 2 - RESET_WAVES + self.adev.regSPI_COMPUTE_QUEUE_RESET.write(1) + self._grbm_select() + self.adev.regGCVM_CONTEXT0_CNTL.write(0) + + def setup_ring(self, ring_addr:int, ring_size:int, rptr_addr:int, wptr_addr:int, eop_addr:int, eop_size:int, doorbell:int, pipe:int, queue:int): + mqd = self.adev.mm.valloc(0x1000, uncached=True, contigous=True) + + struct_t = getattr(am, f"struct_v{self.adev.ip_ver[am.GC_HWIP][0]}_compute_mqd") + mqd_struct = struct_t(header=0xC0310800, cp_mqd_base_addr_lo=lo32(mqd.va_addr), cp_mqd_base_addr_hi=hi32(mqd.va_addr), + cp_hqd_persistent_state=self.adev.regCP_HQD_PERSISTENT_STATE.encode(preload_size=0x55, preload_req=1), + cp_hqd_pipe_priority=0x2, cp_hqd_queue_priority=0xf, cp_hqd_quantum=0x111, + cp_hqd_pq_base_lo=lo32(ring_addr>>8), cp_hqd_pq_base_hi=hi32(ring_addr>>8), + cp_hqd_pq_rptr_report_addr_lo=lo32(rptr_addr), cp_hqd_pq_rptr_report_addr_hi=hi32(rptr_addr), + cp_hqd_pq_wptr_poll_addr_lo=lo32(wptr_addr), cp_hqd_pq_wptr_poll_addr_hi=hi32(wptr_addr), + cp_hqd_pq_doorbell_control=self.adev.regCP_HQD_PQ_DOORBELL_CONTROL.encode(doorbell_offset=doorbell*2, doorbell_en=1), + cp_hqd_pq_control=self.adev.regCP_HQD_PQ_CONTROL.encode(rptr_block_size=5, unord_dispatch=0, queue_size=(ring_size//4).bit_length()-2), + cp_hqd_ib_control=self.adev.regCP_HQD_IB_CONTROL.encode(min_ib_avail_size=0x3), cp_hqd_hq_status0=0x20004000, + cp_mqd_control=self.adev.regCP_MQD_CONTROL.encode(priv_state=1), cp_hqd_vmid=0, + cp_hqd_eop_base_addr_lo=lo32(eop_addr>>8), cp_hqd_eop_base_addr_hi=hi32(eop_addr>>8), + cp_hqd_eop_control=self.adev.regCP_HQD_EOP_CONTROL.encode(eop_size=(eop_size//4).bit_length()-2)) + + # Copy mqd into memory + self.adev.vram.view(mqd.paddrs[0][0], ctypes.sizeof(mqd_struct))[:] = memoryview(mqd_struct).cast('B') + self.adev.gmc.flush_hdp() + + self._grbm_select(me=1, pipe=pipe, queue=queue) + + mqd_st_mv = to_mv(ctypes.addressof(mqd_struct), ctypes.sizeof(mqd_struct)).cast('I') + for i, reg in enumerate(range(self.adev.regCP_MQD_BASE_ADDR.addr, self.adev.regCP_HQD_PQ_WPTR_HI.addr + 1)): + self.adev.wreg(reg, mqd_st_mv[0x80 + i]) + self.adev.regCP_HQD_ACTIVE.write(0x1) + + self._grbm_select() + + self.adev.reg(f"regCP_ME1_PIPE{pipe}_INT_CNTL").update(time_stamp_int_enable=1, generic0_int_enable=1) + + def set_clockgating_state(self): + if hasattr(self.adev, 'regMM_ATC_L2_MISC_CG'): self.adev.regMM_ATC_L2_MISC_CG.write(enable=1, mem_ls_enable=1) + + self.adev.regRLC_SAFE_MODE.write(message=1, cmd=1) + self.adev.wait_reg(self.adev.regRLC_SAFE_MODE, mask=0x1, value=0x0) + + self.adev.regRLC_CGCG_CGLS_CTRL.update(cgcg_gfx_idle_threshold=0x36, cgcg_en=1, cgls_rep_compansat_delay=0xf, cgls_en=1) + + self.adev.regCP_RB_WPTR_POLL_CNTL.update(poll_frequency=0x100, idle_poll_count=0x90) + self.adev.regCP_INT_CNTL.update(cntx_busy_int_enable=1, cntx_empty_int_enable=1, cmp_busy_int_enable=1, gfx_idle_int_enable=1) + self.adev.regSDMA0_RLC_CGCG_CTRL.update(cgcg_int_enable=1) + self.adev.regSDMA1_RLC_CGCG_CTRL.update(cgcg_int_enable=1) + + self.adev.regRLC_CGTT_MGCG_OVERRIDE.update(perfmon_clock_state=0, gfxip_fgcg_override=0, gfxip_repeater_fgcg_override=0, + grbm_cgtt_sclk_override=0, rlc_cgtt_sclk_override=0, gfxip_mgcg_override=0, gfxip_cgls_override=0, gfxip_cgcg_override=0) + + self.adev.regRLC_SAFE_MODE.write(message=0, cmd=1) + + def _grbm_select(self, me=0, pipe=0, queue=0, vmid=0): self.adev.regGRBM_GFX_CNTL.write(meid=me, pipeid=pipe, vmid=vmid, queueid=queue) + + def _config_gfx_rs64(self): + def _config_helper(eng_name, cntl_reg, eng_reg, pipe_cnt, me=0): + for pipe in range(pipe_cnt): + self._grbm_select(me=me, pipe=pipe) + self.adev.wreg_pair(f"regCP_{eng_reg}_PRGRM_CNTR_START", "", "_HI", self.adev.fw.ucode_start[eng_name] >> 2) + self._grbm_select() + self.adev.reg(f"regCP_{cntl_reg}_CNTL").update(**{f"{eng_name.lower()}_pipe{pipe}_reset": 1 for pipe in range(pipe_cnt)}) + self.adev.reg(f"regCP_{cntl_reg}_CNTL").update(**{f"{eng_name.lower()}_pipe{pipe}_reset": 0 for pipe in range(pipe_cnt)}) + + if self.adev.ip_ver[am.GC_HWIP] >= (12,0,0): + _config_helper(eng_name="PFP", cntl_reg="ME", eng_reg="PFP", pipe_cnt=1) + _config_helper(eng_name="ME", cntl_reg="ME", eng_reg="ME", pipe_cnt=1) + _config_helper(eng_name="MEC", cntl_reg="MEC_RS64", eng_reg="MEC_RS64", pipe_cnt=1, me=1) + +class AM_IH(AM_IP): + def init_sw(self): + self.ring_size = 512 << 10 + def _alloc_ring(size): return (self.adev.mm.palloc(size, zero=False, boot=True), self.adev.mm.palloc(0x1000, zero=False, boot=True)) + self.rings = [(*_alloc_ring(self.ring_size), "", 0), (*_alloc_ring(self.ring_size), "_RING1", 1)] + + def init_hw(self): + for ring_vm, rwptr_vm, suf, ring_id in self.rings: + self.adev.wreg_pair("regIH_RB_BASE", suf, f"_HI{suf}", self.adev.paddr2mc(ring_vm) >> 8) + + self.adev.reg(f"regIH_RB_CNTL{suf}").write(mc_space=4, wptr_overflow_clear=1, rb_size=(self.ring_size//4).bit_length(), + mc_snoop=1, mc_ro=0, mc_vmid=0, **({'wptr_overflow_enable': 1, 'rptr_rearm': 1} if ring_id == 0 else {'rb_full_drain_enable': 1})) + + if ring_id == 0: self.adev.wreg_pair("regIH_RB_WPTR_ADDR", "_LO", "_HI", self.adev.paddr2mc(rwptr_vm)) + + self.adev.reg(f"regIH_RB_WPTR{suf}").write(0) + self.adev.reg(f"regIH_RB_RPTR{suf}").write(0) + + self.adev.reg(f"regIH_DOORBELL_RPTR{suf}").write(offset=(am.AMDGPU_NAVI10_DOORBELL_IH + ring_id) * 2, enable=1) + + self.adev.regIH_STORM_CLIENT_LIST_CNTL.update(client18_is_storm_client=1) + self.adev.regIH_INT_FLOOD_CNTL.update(flood_cntl_enable=1) + self.adev.regIH_MSI_STORM_CTRL.update(delay=3) + + # toggle interrupts + for _, rwptr_vm, suf, ring_id in self.rings: + self.adev.reg(f"regIH_RB_CNTL{suf}").update(rb_enable=1, **({'enable_intr': 1} if ring_id == 0 else {})) + + self.adev.soc.doorbell_enable(port=1, awid=0x0, awaddr_31_28_value=0x0, offset=am.AMDGPU_NAVI10_DOORBELL_IH*2, size=2) + + def interrupt_handler(self): + _, rwptr_vm, suf, _ = self.rings[0] + wptr = self.adev.vram.view(offset=rwptr_vm, size=8, fmt='Q')[0] + + if self.adev.reg(f"regIH_RB_WPTR{suf}").read_bitfields()['rb_overflow']: + self.adev.reg(f"regIH_RB_WPTR{suf}").update(rb_overflow=0) + self.adev.reg(f"regIH_RB_CNTL{suf}").update(wptr_overflow_clear=1) + self.adev.reg(f"regIH_RB_CNTL{suf}").update(wptr_overflow_clear=0) + self.adev.regIH_RB_RPTR.write(wptr % self.ring_size) + +class AM_SDMA(AM_IP): + def init_sw(self): self.sdma_name = "F32" if self.adev.ip_ver[am.SDMA0_HWIP] < (7,0,0) else "MCU" + def init_hw(self): + for pipe in range(2): + self.adev.reg(f"regSDMA{pipe}_WATCHDOG_CNTL").update(queue_hang_count=100) # 10s, 100ms per unit + self.adev.reg(f"regSDMA{pipe}_UTCL1_CNTL").update(resp_mode=3, redo_delay=9) + + # rd=noa, wr=bypass + self.adev.reg(f"regSDMA{pipe}_UTCL1_PAGE").update(rd_l2_policy=0x2, wr_l2_policy=0x3, **({'llc_noalloc':1} if self.sdma_name == "F32" else {})) + self.adev.reg(f"regSDMA{pipe}_{self.sdma_name}_CNTL").update(halt=0, **{f"{'th1_' if self.sdma_name == 'F32' else ''}reset":0}) + self.adev.reg(f"regSDMA{pipe}_CNTL").update(ctxempty_int_enable=1, trap_enable=1) + self.adev.soc.doorbell_enable(port=2, awid=0xe, awaddr_31_28_value=0x3, offset=am.AMDGPU_NAVI10_DOORBELL_sDMA_ENGINE0*2, size=4) + + def fini_hw(self): + self.adev.regSDMA0_QUEUE0_RB_CNTL.update(rb_enable=0) + self.adev.regSDMA0_QUEUE0_IB_CNTL.update(ib_enable=0) + self.adev.regGRBM_SOFT_RESET.write(soft_reset_sdma0=1) + time.sleep(0.01) + self.adev.regGRBM_SOFT_RESET.write(0x0) + + def setup_ring(self, ring_addr:int, ring_size:int, rptr_addr:int, wptr_addr:int, doorbell:int, pipe:int, queue:int): + # Setup the ring + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_MINOR_PTR_UPDATE").write(0x1) + self.adev.wreg_pair(f"regSDMA{pipe}_QUEUE{queue}_RB_RPTR", "", "_HI", 0) + self.adev.wreg_pair(f"regSDMA{pipe}_QUEUE{queue}_RB_WPTR", "", "_HI", 0) + self.adev.wreg_pair(f"regSDMA{pipe}_QUEUE{queue}_RB_BASE", "", "_HI", ring_addr >> 8) + self.adev.wreg_pair(f"regSDMA{pipe}_QUEUE{queue}_RB_RPTR_ADDR", "_LO", "_HI", rptr_addr) + self.adev.wreg_pair(f"regSDMA{pipe}_QUEUE{queue}_RB_WPTR_POLL_ADDR", "_LO", "_HI", wptr_addr) + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_DOORBELL_OFFSET").update(offset=doorbell * 2) + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_DOORBELL").update(enable=1) + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_MINOR_PTR_UPDATE").write(0x0) + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_RB_CNTL").write(rb_vmid=0, rptr_writeback_enable=1, rptr_writeback_timer=4, + **{f'{self.sdma_name.lower()}_wptr_poll_enable':1}, rb_size=(ring_size//4).bit_length()-1, rb_enable=1, rb_priv=1) + self.adev.reg(f"regSDMA{pipe}_QUEUE{queue}_IB_CNTL").update(ib_enable=1) + +class AM_PSP(AM_IP): + def init_sw(self): + self.reg_pref = "regMP0_SMN_C2PMSG" if self.adev.ip_ver[am.MP0_HWIP] < (14,0,0) else "regMPASP_SMN_C2PMSG" + + msg1_region = next((reg for reg in self.adev.dma_regions or [] if reg[1].nbytes >= (512 << 10)), None) + if msg1_region is not None: + self.msg1_addr, self.msg1_view = self.adev.mm.alloc_vaddr(size=msg1_region[1].nbytes, align=am.PSP_1_MEG), msg1_region[1] + self.adev.mm.map_range(self.msg1_addr, msg1_region[1].nbytes, [(msg1_region[0], msg1_region[1].nbytes)], system=True, uncached=True, boot=True) + else: + self.msg1_paddr = self.adev.mm.palloc(am.PSP_1_MEG, align=am.PSP_1_MEG, zero=False, boot=True) + self.msg1_addr, self.msg1_view = self.adev.paddr2mc(self.msg1_paddr), self.adev.vram.view(self.msg1_paddr, am.PSP_1_MEG, 'B') + + self.cmd_paddr = self.adev.mm.palloc(am.PSP_CMD_BUFFER_SIZE, zero=False, boot=True) + self.fence_paddr = self.adev.mm.palloc(am.PSP_FENCE_BUFFER_SIZE, zero=not self.adev.partial_boot, boot=True) + + self.ring_size = 0x10000 + self.ring_paddr = self.adev.mm.palloc(self.ring_size, zero=False, boot=True) + + self.max_tmr_size = 0x1300000 + self.boot_time_tmr = self.adev.ip_ver[am.GC_HWIP] >= (12,0,0) + if not self.boot_time_tmr: + self.tmr_paddr = self.adev.mm.palloc(self.max_tmr_size, align=am.PSP_TMR_ALIGNMENT, zero=False, boot=True) + + def init_hw(self): + spl_key = am.PSP_FW_TYPE_PSP_SPL if self.adev.ip_ver[am.MP0_HWIP] >= (14,0,0) else am.PSP_FW_TYPE_PSP_KDB + sos_components = [(am.PSP_FW_TYPE_PSP_KDB, am.PSP_BL__LOAD_KEY_DATABASE), (spl_key, am.PSP_BL__LOAD_TOS_SPL_TABLE), + (am.PSP_FW_TYPE_PSP_SYS_DRV, am.PSP_BL__LOAD_SYSDRV), (am.PSP_FW_TYPE_PSP_SOC_DRV, am.PSP_BL__LOAD_SOCDRV), + (am.PSP_FW_TYPE_PSP_INTF_DRV, am.PSP_BL__LOAD_INTFDRV), (am.PSP_FW_TYPE_PSP_DBG_DRV, am.PSP_BL__LOAD_DBGDRV), + (am.PSP_FW_TYPE_PSP_RAS_DRV, am.PSP_BL__LOAD_RASDRV), (am.PSP_FW_TYPE_PSP_SOS, am.PSP_BL__LOAD_SOSDRV)] + + if not self.is_sos_alive(): + for fw, compid in sos_components: self._bootloader_load_component(fw, compid) + while not self.is_sos_alive(): time.sleep(0.01) + + self._ring_create() + self._tmr_init() + + # SMU fw should be loaded before TMR. + self._load_ip_fw_cmd(*self.adev.fw.smu_psp_desc) + if not self.boot_time_tmr: self._tmr_load_cmd() + + for psp_desc in self.adev.fw.descs: self._load_ip_fw_cmd(*psp_desc) + self._rlc_autoload_cmd() + + def is_sos_alive(self): return self.adev.reg(f"{self.reg_pref}_81").read() != 0x0 + + def _wait_for_bootloader(self): self.adev.wait_reg(self.adev.reg(f"{self.reg_pref}_35"), mask=0x80000000, value=0x80000000) + + def _prep_msg1(self, data): + assert len(data) <= self.msg1_view.nbytes, f"msg1 buffer is too small {len(data):#x} > {self.msg1_view.nbytes:#x}" + self.msg1_view[:len(data)+4] = bytes(data) + b'\x00' * 4 + self.adev.gmc.flush_hdp() + + def _bootloader_load_component(self, fw, compid): + if fw not in self.adev.fw.sos_fw: return 0 + + self._wait_for_bootloader() + + if DEBUG >= 2: print(f"am {self.adev.devfmt}: loading sos component: {am.psp_fw_type__enumvalues[fw]}") + + self._prep_msg1(self.adev.fw.sos_fw[fw]) + self.adev.reg(f"{self.reg_pref}_36").write(self.msg1_addr >> 20) + self.adev.reg(f"{self.reg_pref}_35").write(compid) + + return self._wait_for_bootloader() if compid != am.PSP_BL__LOAD_SOSDRV else 0 + + def _tmr_init(self): + # Load TOC and calculate TMR size + self._prep_msg1(fwm:=self.adev.fw.sos_fw[am.PSP_FW_TYPE_PSP_TOC]) + self.tmr_size = self._load_toc_cmd(len(fwm)).resp.tmr_size + assert self.tmr_size <= self.max_tmr_size + + def _ring_create(self): + # If the ring is already created, destroy it + if self.adev.reg(f"{self.reg_pref}_71").read() != 0: + self.adev.reg(f"{self.reg_pref}_64").write(am.GFX_CTRL_CMD_ID_DESTROY_RINGS) + + # There might be handshake issue with hardware which needs delay + time.sleep(0.02) + + # Wait until the sOS is ready + self.adev.wait_reg(self.adev.reg(f"{self.reg_pref}_64"), mask=0x80000000, value=0x80000000) + + self.adev.wreg_pair(self.reg_pref, "_69", "_70", self.adev.paddr2mc(self.ring_paddr)) + self.adev.reg(f"{self.reg_pref}_71").write(self.ring_size) + self.adev.reg(f"{self.reg_pref}_64").write(am.PSP_RING_TYPE__KM << 16) + + # There might be handshake issue with hardware which needs delay + time.sleep(0.02) + + self.adev.wait_reg(self.adev.reg(f"{self.reg_pref}_64"), mask=0x8000FFFF, value=0x80000000) + + def _ring_submit(self, cmd): + msg = am.struct_psp_gfx_rb_frame(fence_value=(prev_wptr:=self.adev.reg(f"{self.reg_pref}_67").read()), + cmd_buf_addr_lo=lo32(self.adev.paddr2mc(self.cmd_paddr)), cmd_buf_addr_hi=hi32(self.adev.paddr2mc(self.cmd_paddr)), + fence_addr_lo=lo32(self.adev.paddr2mc(self.fence_paddr)), fence_addr_hi=hi32(self.adev.paddr2mc(self.fence_paddr))) + + self.adev.vram.view(self.cmd_paddr, ctypes.sizeof(cmd))[:] = memoryview(cmd).cast('B') + self.adev.vram.view(self.ring_paddr + prev_wptr * 4, ctypes.sizeof(msg))[:] = memoryview(msg).cast('B') + + # Move the wptr + self.adev.reg(f"{self.reg_pref}_67").write(prev_wptr + ctypes.sizeof(am.struct_psp_gfx_rb_frame) // 4) + + while self.adev.vram.view(self.fence_paddr, 4, 'I')[0] != prev_wptr: pass + time.sleep(0.005) + + resp = type(cmd).from_buffer(bytearray(self.adev.vram.view(self.cmd_paddr, ctypes.sizeof(cmd))[:])) + if resp.resp.status != 0: raise RuntimeError(f"PSP command failed {resp.cmd_id} {resp.resp.status}") + + return resp + + def _load_ip_fw_cmd(self, fw_types, fw_bytes): + self._prep_msg1(fw_bytes) + for fw_type in fw_types: + if DEBUG >= 2: print(f"am {self.adev.devfmt}: loading fw: {am.psp_gfx_fw_type__enumvalues[fw_type]}") + cmd = am.struct_psp_gfx_cmd_resp(cmd_id=am.GFX_CMD_ID_LOAD_IP_FW) + cmd.cmd.cmd_load_ip_fw.fw_phy_addr_hi, cmd.cmd.cmd_load_ip_fw.fw_phy_addr_lo = data64(self.msg1_addr) + cmd.cmd.cmd_load_ip_fw.fw_size = len(fw_bytes) + cmd.cmd.cmd_load_ip_fw.fw_type = fw_type + self._ring_submit(cmd) + + def _tmr_load_cmd(self): + cmd = am.struct_psp_gfx_cmd_resp(cmd_id=am.GFX_CMD_ID_SETUP_TMR) + cmd.cmd.cmd_setup_tmr.buf_phy_addr_hi, cmd.cmd.cmd_setup_tmr.buf_phy_addr_lo = data64(self.adev.paddr2mc(self.tmr_paddr)) + cmd.cmd.cmd_setup_tmr.system_phy_addr_hi, cmd.cmd.cmd_setup_tmr.system_phy_addr_lo = data64(self.tmr_paddr) + cmd.cmd.cmd_setup_tmr.bitfield.virt_phy_addr = 1 + cmd.cmd.cmd_setup_tmr.buf_size = self.tmr_size + return self._ring_submit(cmd) + + def _load_toc_cmd(self, toc_size): + cmd = am.struct_psp_gfx_cmd_resp(cmd_id=am.GFX_CMD_ID_LOAD_TOC) + cmd.cmd.cmd_load_toc.toc_phy_addr_hi, cmd.cmd.cmd_load_toc.toc_phy_addr_lo = data64(self.msg1_addr) + cmd.cmd.cmd_load_toc.toc_size = toc_size + return self._ring_submit(cmd) + + def _rlc_autoload_cmd(self): return self._ring_submit(am.struct_psp_gfx_cmd_resp(cmd_id=am.GFX_CMD_ID_AUTOLOAD_RLC)) diff --git a/tinygrad_repo/tinygrad/runtime/support/amd.py b/tinygrad_repo/tinygrad/runtime/support/amd.py new file mode 100644 index 0000000000..4d72296d7a --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/amd.py @@ -0,0 +1,126 @@ +import functools, importlib, re, urllib +from collections import defaultdict +from dataclasses import dataclass +from tinygrad.helpers import getbits, round_up, fetch +from tinygrad.runtime.autogen import pci +from tinygrad.runtime.support.usb import ASM24Controller + +@dataclass(frozen=True) +class AMDReg: + name:str; offset:int; segment:int; fields:dict[str, tuple[int, int]]; bases:tuple[int, ...] # noqa: E702 + + def encode(self, **kwargs) -> int: return functools.reduce(int.__or__, (value << self.fields[name][0] for name,value in kwargs.items()), 0) + def decode(self, val: int) -> dict: return {name:getbits(val, start, end) for name,(start,end) in self.fields.items()} + + @property + def addr(self): return self.bases[self.segment] + self.offset + +@dataclass(frozen=True) +class AMDIP: + name:str; version:tuple[int, ...]; bases:tuple[int, ...] # noqa: E702 + + @functools.cached_property + def regs(self): return import_asic_regs(self.name, self.version, cls=functools.partial(AMDReg, bases=self.bases)) + + def __getattr__(self, name:str): + if name in self.regs: return self.regs[name] + + # NOTE: gfx10 gc registers always start with mm, no reg prefix + return self.regs[name.replace('reg', 'mm')] + +def fixup_ip_version(ip:str, version:tuple[int, ...]) -> list[tuple[int, ...]]: + # override versions + def _apply_ovrd(ovrd:dict[tuple[int, ...], tuple[int, ...]]) -> tuple[int, ...]: + for ver, ovrd_ver in ovrd.items(): + if version[:len(ver)] == ver: return ovrd_ver + return version + + if ip in ['nbio', 'nbif']: version = _apply_ovrd({(3,3): (2,3,0)}) + elif ip == 'mp': version = _apply_ovrd({(14,0,3): (14,0,2)}) + + return [version, version[:2]+(0,), version[:1]+(0, 0)] + +def import_module(name:str, version:tuple[int, ...], version_prefix:str=""): + for ver in fixup_ip_version(name, version): + try: return importlib.import_module(f"tinygrad.runtime.autogen.am.{name}_{version_prefix}{'_'.join(map(str, ver))}") + except ImportError: pass + raise ImportError(f"Failed to load autogen module for {name.upper()} {'.'.join(map(str, version))}") + +def import_asic_regs(prefix:str, version:tuple[int, ...], cls=AMDReg) -> dict[str, AMDReg]: + def _split_name(name): return name[:(pos:=next((i for i,c in enumerate(name) if c.isupper()), len(name)))], name[pos:] + def _extract_regs(txt): + return {m.group(1): int(m.group(2), 0) for line in txt.splitlines() if (m:=re.match(r'#define\s+(\S+)\s+(0x[\da-fA-F]+|\d+)', line))} + def _download_file(ver, suff) -> str: + dir_prefix = {"osssys": "oss"}.get(prefix, prefix) + fetch_name, file_name = f"{prefix}_{'_'.join(map(str, ver))}_{suff}.h", f"{prefix}_{'_'.join(map(str, version))}_{suff}.h" + url = "https://gitlab.com/linux-kernel/linux-next/-/raw/cf6d949a409e09539477d32dbe7c954e4852e744/drivers/gpu/drm/amd/include/asic_reg" + return fetch(f"{url}/{dir_prefix}/{fetch_name}", name=file_name, subdir="asic_regs").read_text() + + for ver in fixup_ip_version(prefix, version): + try: offs, sh_masks = _extract_regs(_download_file(ver, "offset")), _extract_regs(_download_file(ver, "sh_mask")) + except urllib.error.HTTPError as e: + if e.code == 404: continue + raise + + offsets = {k:v for k,v in offs.items() if _split_name(k)[0] in {'reg', 'mm'} and not k.endswith('_BASE_IDX')} + bases = {k[:-len('_BASE_IDX')]:v for k,v in offs.items() if _split_name(k)[0] in {'reg', 'mm'} and k.endswith('_BASE_IDX')} + + fields: defaultdict[str, dict[str, tuple[int, int]]] = defaultdict(dict) + for field_name, field_mask in sh_masks.items(): + if not ('__' in field_name and field_name.endswith('_MASK')): continue + reg_name, reg_field_name = field_name[:-len('_MASK')].split('__') + fields[reg_name][reg_field_name.lower()] = ((field_mask & -field_mask).bit_length()-1, field_mask.bit_length()-1) + + # NOTE: Some registers like regGFX_IMU_FUSESTRAP in gc_11_0_0 are missing base idx, just skip them + return {reg:cls(name=reg, offset=off, segment=bases[reg], fields=fields[_split_name(reg)[1]]) for reg,off in offsets.items() if reg in bases} + raise ImportError(f"Failed to load ASIC registers for {prefix.upper()} {'.'.join(map(str, version))}") + +def setup_pci_bars(usb:ASM24Controller, gpu_bus:int, mem_base:int, pref_mem_base:int) -> dict[int, tuple[int, int]]: + for bus in range(gpu_bus): + # All 3 values must be written at the same time. + buses = (0 << 0) | ((bus+1) << 8) | ((gpu_bus) << 16) + usb.pcie_cfg_req(pci.PCI_PRIMARY_BUS, bus=bus, dev=0, fn=0, value=buses, size=4) + + usb.pcie_cfg_req(pci.PCI_MEMORY_BASE, bus=bus, dev=0, fn=0, value=(mem_base>>16) & 0xffff, size=2) + usb.pcie_cfg_req(pci.PCI_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0xffff, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_BASE, bus=bus, dev=0, fn=0, value=(pref_mem_base>>16) & 0xffff, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_MEMORY_LIMIT, bus=bus, dev=0, fn=0, value=0xffff, size=2) + usb.pcie_cfg_req(pci.PCI_PREF_BASE_UPPER32, bus=bus, dev=0, fn=0, value=pref_mem_base >> 32, size=4) + usb.pcie_cfg_req(pci.PCI_PREF_LIMIT_UPPER32, bus=bus, dev=0, fn=0, value=0xffffffff, size=4) + + usb.pcie_cfg_req(pci.PCI_COMMAND, bus=bus, dev=0, fn=0, value=pci.PCI_COMMAND_IO | pci.PCI_COMMAND_MEMORY | pci.PCI_COMMAND_MASTER, size=1) + + # resize bar 0 + cap_ptr = 0x100 + while cap_ptr: + if pci.PCI_EXT_CAP_ID(hdr:=usb.pcie_cfg_req(cap_ptr, bus=gpu_bus, dev=0, fn=0, size=4)) == pci.PCI_EXT_CAP_ID_REBAR: + cap = usb.pcie_cfg_req(cap_ptr + 0x04, bus=gpu_bus, dev=0, fn=0, size=4) + new_ctrl = (usb.pcie_cfg_req(cap_ptr + 0x08, bus=gpu_bus, dev=0, fn=0, size=4) & ~0x1F00) | ((int(cap >> 4).bit_length() - 1) << 8) + usb.pcie_cfg_req(cap_ptr + 0x08, bus=gpu_bus, dev=0, fn=0, value=new_ctrl, size=4) + + cap_ptr = pci.PCI_EXT_CAP_NEXT(hdr) + + mem_space_addr, bar_off, bars = [mem_base, pref_mem_base], 0, {} + while bar_off < 24: + cfg = usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off, bus=gpu_bus, dev=0, fn=0, size=4) + bar_mem, bar_64 = bool(cfg & pci.PCI_BASE_ADDRESS_MEM_PREFETCH), cfg & pci.PCI_BASE_ADDRESS_MEM_TYPE_64 + + if (cfg & pci.PCI_BASE_ADDRESS_SPACE) == pci.PCI_BASE_ADDRESS_SPACE_MEMORY: + usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off, bus=gpu_bus, dev=0, fn=0, value=0xffffffff, size=4) + lo = (usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off, bus=gpu_bus, dev=0, fn=0, size=4) & 0xfffffff0) + + if bar_64: usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off + 4, bus=gpu_bus, dev=0, fn=0, value=0xffffffff, size=4) + hi = (usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off + 4, bus=gpu_bus, dev=0, fn=0, size=4) if bar_64 else 0) + + bar_size = ((~(((hi << 32) | lo) & ~0xf)) + 1) & (0xffffffffffffffff if bar_64 else 0xffffffff) + + usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off, bus=gpu_bus, dev=0, fn=0, value=mem_space_addr[bar_mem] & 0xffffffff, size=4) + if bar_64: usb.pcie_cfg_req(pci.PCI_BASE_ADDRESS_0 + bar_off + 4, bus=gpu_bus, dev=0, fn=0, value=mem_space_addr[bar_mem] >> 32, size=4) + + bars[bar_off // 4] = (mem_space_addr[bar_mem], bar_size) + mem_space_addr[bar_mem] += round_up(bar_size, 2 << 20) + + bar_off += 8 if bar_64 else 4 + + usb.pcie_cfg_req(pci.PCI_COMMAND, bus=gpu_bus, dev=0, fn=0, value=pci.PCI_COMMAND_IO | pci.PCI_COMMAND_MEMORY | pci.PCI_COMMAND_MASTER, size=1) + return bars diff --git a/tinygrad_repo/tinygrad/runtime/support/compiler_hip.py b/tinygrad_repo/tinygrad/runtime/support/compiler_amd.py similarity index 64% rename from tinygrad_repo/tinygrad/runtime/support/compiler_hip.py rename to tinygrad_repo/tinygrad/runtime/support/compiler_amd.py index 51c07a74f6..82b95ea642 100644 --- a/tinygrad_repo/tinygrad/runtime/support/compiler_hip.py +++ b/tinygrad_repo/tinygrad/runtime/support/compiler_amd.py @@ -1,6 +1,12 @@ import ctypes, subprocess import tinygrad.runtime.autogen.comgr as comgr from tinygrad.device import Compiler, CompileError +from tinygrad.runtime.ops_llvm import LLVMCompiler +from tinygrad.helpers import OSX, to_char_p_p + +def amdgpu_disassemble(lib:bytes): + asm = subprocess.check_output(["llvm-objdump" if OSX else "/opt/rocm/llvm/bin/llvm-objdump", '-d', '-'], input=lib) + print('\n'.join([x for x in asm.decode('utf-8').split("\n") if 's_code_end' not in x])) def check(status): if status != 0: @@ -14,6 +20,12 @@ def _get_comgr_data(data_set, data_type): check(comgr.amd_comgr_release_data(data_exec)) return bytes(dat) +# amd_comgr_action_info_set_options was deprecated +def set_options(action_info, options:bytes): + # TODO: this type should be correct in the autogen stub + comgr.amd_comgr_action_info_set_option_list.argtypes = [comgr.amd_comgr_action_info_t, ctypes.POINTER(ctypes.POINTER(ctypes.c_char)), comgr.size_t] + return comgr.amd_comgr_action_info_set_option_list(action_info, to_char_p_p(options_list:=options.split(b' ')), len(options_list)) + # AMD_COMGR_SAVE_TEMPS=1 AMD_COMGR_REDIRECT_LOGS=stdout AMD_COMGR_EMIT_VERBOSE_LOGS=1 def compile_hip(prg:str, arch="gfx1100", asm=False) -> bytes: check(comgr.amd_comgr_create_action_info(ctypes.byref(action_info := comgr.amd_comgr_action_info_t()))) @@ -40,15 +52,15 @@ def compile_hip(prg:str, arch="gfx1100", asm=False) -> bytes: check(comgr.amd_comgr_set_data_name(data_src, b"")) check(comgr.amd_comgr_data_set_add(data_set_src, data_src)) # -include hiprtc_runtime.h was removed - check(comgr.amd_comgr_action_info_set_options(action_info, f"-O3 -mcumode --hip-version=6.0.32830 -DHIP_VERSION_MAJOR=6 -DHIP_VERSION_MINOR=0 -DHIP_VERSION_PATCH=32830 -D__HIPCC_RTC__ -std=c++14 -nogpuinc -Wno-gnu-line-marker -Wno-missing-prototypes --offload-arch={arch} -I/opt/rocm/include -Xclang -disable-llvm-passes".encode())) # noqa: E501 + check(set_options(action_info, f"-O3 -mcumode --hip-version=6.0.32830 -DHIP_VERSION_MAJOR=6 -DHIP_VERSION_MINOR=0 -DHIP_VERSION_PATCH=32830 -D__HIPCC_RTC__ -std=c++14 -nogpuinc -Wno-gnu-line-marker -Wno-missing-prototypes --offload-arch={arch} -I/opt/rocm/include -Xclang -disable-llvm-passes".encode())) # noqa: E501 status = comgr.amd_comgr_do_action(comgr.AMD_COMGR_ACTION_COMPILE_SOURCE_WITH_DEVICE_LIBS_TO_BC, action_info, data_set_src, data_set_bc) if status != 0: print(_get_comgr_data(data_set_bc, comgr.AMD_COMGR_DATA_KIND_LOG).decode()) raise RuntimeError("compile failed") - check(comgr.amd_comgr_action_info_set_options(action_info, b"-O3 -mllvm -amdgpu-internalize-symbols")) + check(set_options(action_info, b"-O3 -mllvm -amdgpu-internalize-symbols")) check(comgr.amd_comgr_do_action(comgr.AMD_COMGR_ACTION_CODEGEN_BC_TO_RELOCATABLE, action_info, data_set_bc, data_set_reloc)) - check(comgr.amd_comgr_action_info_set_options(action_info, b"")) + check(set_options(action_info, b"")) check(comgr.amd_comgr_do_action(comgr.AMD_COMGR_ACTION_LINK_RELOCATABLE_TO_EXECUTABLE, action_info, data_set_reloc, data_set_exec)) ret = _get_comgr_data(data_set_exec, comgr.AMD_COMGR_DATA_KIND_EXECUTABLE) check(comgr.amd_comgr_release_data(data_src)) @@ -56,13 +68,25 @@ def compile_hip(prg:str, arch="gfx1100", asm=False) -> bytes: check(comgr.amd_comgr_destroy_action_info(action_info)) return ret -class AMDCompiler(Compiler): +class HIPCompiler(Compiler): def __init__(self, arch:str): self.arch = arch super().__init__(f"compile_hip_{self.arch}") def compile(self, src:str) -> bytes: - try: return compile_hip(src, self.arch) + try: return compile_hip(src, self.arch, src.split('\n', 1)[0].strip() == '.text') except RuntimeError as e: raise CompileError(e) from e - def disassemble(self, lib:bytes): - asm = subprocess.check_output(["/opt/rocm/llvm/bin/llvm-objdump", '-d', '-'], input=lib) - print('\n'.join([x for x in asm.decode('utf-8').split("\n") if 's_code_end' not in x])) + def disassemble(self, lib:bytes): amdgpu_disassemble(lib) + +class AMDLLVMCompiler(LLVMCompiler): + jit = False + target_arch = "AMDGPU" + def __init__(self, arch: str): + self.arch = arch + super().__init__(self.arch, "+cumode") + def __reduce__(self): return (AMDLLVMCompiler, (self.arch,)) + def compile(self, src:str) -> bytes: + try: return super().compile(src) + except RuntimeError as e: + if "undefined value '@llvm.amdgcn." in str(e): raise CompileError(str(e) + "AMD with LLVM backend requires LLVM >= 18") from e + raise CompileError(e) from e + def disassemble(self, lib:bytes): amdgpu_disassemble(lib) diff --git a/tinygrad_repo/tinygrad/runtime/support/compiler_cuda.py b/tinygrad_repo/tinygrad/runtime/support/compiler_cuda.py index e0bc06726c..14cd1a0823 100644 --- a/tinygrad_repo/tinygrad/runtime/support/compiler_cuda.py +++ b/tinygrad_repo/tinygrad/runtime/support/compiler_cuda.py @@ -4,7 +4,7 @@ from tinygrad.helpers import to_char_p_p, colored, init_c_var, getenv import tinygrad.runtime.autogen.nvrtc as nvrtc from tinygrad.device import Compiler, CompileError -PTX = getenv("PTX") # this shouldn't be here, in fact, it shouldn't exist +PTX, CUDA_PATH = getenv("PTX"), getenv("CUDA_PATH", "") # PTX shouldn't be here, in fact, it shouldn't exist def _get_bytes(arg, get_str, get_sz, check) -> bytes: sz = init_c_var(ctypes.c_size_t(), lambda x: check(get_sz(arg, ctypes.byref(x)))) @@ -40,7 +40,8 @@ def cuda_disassemble(lib, arch): class CUDACompiler(Compiler): def __init__(self, arch:str, cache_key:str="cuda"): - self.arch, self.compile_options = arch, [f'--gpu-architecture={arch}', "-I/usr/local/cuda/include", "-I/usr/include", "-I/opt/cuda/include/"] + self.arch, self.compile_options = arch, [f'--gpu-architecture={arch}'] + self.compile_options += [f"-I{CUDA_PATH}/include"] if CUDA_PATH else ["-I/usr/local/cuda/include", "-I/usr/include", "-I/opt/cuda/include"] nvrtc_check(nvrtc.nvrtcVersion((nvrtcMajor := ctypes.c_int()), (nvrtcMinor := ctypes.c_int()))) if (nvrtcMajor.value, nvrtcMinor.value) >= (12, 4): self.compile_options.append("--minimal") super().__init__(f"compile_{cache_key}_{self.arch}") diff --git a/tinygrad_repo/tinygrad/runtime/support/elf.py b/tinygrad_repo/tinygrad/runtime/support/elf.py index 54f1cd844c..26495ca3ea 100644 --- a/tinygrad_repo/tinygrad/runtime/support/elf.py +++ b/tinygrad_repo/tinygrad/runtime/support/elf.py @@ -1,5 +1,6 @@ +import struct, tinygrad.runtime.autogen.libc as libc from dataclasses import dataclass -import tinygrad.runtime.autogen.libc as libc +from tinygrad.helpers import getbits, i2u @dataclass(frozen=True) class ElfSection: name:str; header:libc.Elf64_Shdr; content:bytes # noqa: E702 @@ -31,6 +32,31 @@ def elf_loader(blob:bytes, force_section_align:int=1) -> tuple[memoryview, list[ for sh, trgt_sh_name, c_rels in rel + rela: target_image_off = next(tsh for tsh in sections if tsh.name == trgt_sh_name).header.sh_addr rels = [(r.r_offset, symtab[libc.ELF64_R_SYM(r.r_info)], libc.ELF64_R_TYPE(r.r_info), getattr(r, "r_addend", 0)) for r in c_rels] + for roff, sym, r_type_, r_addend in rels: + if sym.st_shndx == 0: raise RuntimeError(f'Attempting to relocate against an undefined symbol {repr(_strtab(sh_strtab, sym.st_name))}') relocs += [(target_image_off + roff, sections[sym.st_shndx].header.sh_addr + sym.st_value, rtype, raddend) for roff, sym, rtype, raddend in rels] return memoryview(image), sections, relocs + +def relocate(instr: int, ploc: int, tgt: int, r_type: int): + match r_type: + # https://refspecs.linuxfoundation.org/elf/x86_64-abi-0.95.pdf + case libc.R_X86_64_PC32: return i2u(32, tgt-ploc) + # https://github.com/ARM-software/abi-aa/blob/main/aaelf64/aaelf64.rst for definitions of relocations + # https://www.scs.stanford.edu/~zyedidia/arm64/index.html for instruction encodings + case libc.R_AARCH64_ADR_PREL_PG_HI21: + rel_pg = (tgt & ~0xFFF) - (ploc & ~0xFFF) + return instr | (getbits(rel_pg, 12, 13) << 29) | (getbits(rel_pg, 14, 32) << 5) + case libc.R_AARCH64_ADD_ABS_LO12_NC: return instr | (getbits(tgt, 0, 11) << 10) + case libc.R_AARCH64_LDST16_ABS_LO12_NC: return instr | (getbits(tgt, 1, 11) << 10) + case libc.R_AARCH64_LDST32_ABS_LO12_NC: return instr | (getbits(tgt, 2, 11) << 10) + case libc.R_AARCH64_LDST64_ABS_LO12_NC: return instr | (getbits(tgt, 3, 11) << 10) + case libc.R_AARCH64_LDST128_ABS_LO12_NC: return instr | (getbits(tgt, 4, 11) << 10) + raise NotImplementedError(f"Encountered unknown relocation type {r_type}") + +def jit_loader(obj: bytes) -> bytes: + image, _, relocs = elf_loader(obj) + # This is needed because we have an object file, not a .so that has all internal references (like loads of constants from .rodata) resolved. + for ploc,tgt,r_type,r_addend in relocs: + image[ploc:ploc+4] = struct.pack(" MMIOInterface: + return MMIOInterface(self.addr+offset, size or (self.nbytes - offset), fmt=fmt or self.fmt) + +class FileIOInterface: + """ + Hardware Abstraction Layer for HCQ devices. The class provides a unified interface for interacting with hardware devices. + """ + + def __init__(self, path:str="", flags:int=os.O_RDONLY, fd:int|None=None): + self.path:str = path + self.fd:int = fd or os.open(path, flags) + def __del__(self): + if hasattr(self, 'fd'): os.close(self.fd) + def ioctl(self, request, arg): return fcntl.ioctl(self.fd, request, arg) + def mmap(self, start, sz, prot, flags, offset): return libc.mmap(start, sz, prot, flags, self.fd, offset) + def read(self, size=None, binary=False, offset=None): + if offset is not None: self.seek(offset) + with open(self.fd, "rb" if binary else "r", closefd=False) as file: return file.read(size) + def write(self, content, binary=False, offset=None): + if offset is not None: self.seek(offset) + with open(self.fd, "wb" if binary else "w", closefd=False) as file: file.write(content) + def listdir(self): return os.listdir(self.path) + def seek(self, offset): os.lseek(self.fd, offset, os.SEEK_SET) + @staticmethod + def anon_mmap(start, sz, prot, flags, offset): return libc.mmap(start, sz, prot, flags, -1, offset) + @staticmethod + def munmap(buf, sz): return libc.munmap(buf, sz) + @staticmethod + def exists(path): return os.path.exists(path) + @staticmethod + def readlink(path): return os.readlink(path) + @staticmethod + def eventfd(initval, flags=None): return FileIOInterface(fd=os.eventfd(initval, flags)) # type: ignore[attr-defined] + +if MOCKGPU:=getenv("MOCKGPU"): from test.mockgpu.mockgpu import MockFileIOInterface as FileIOInterface # noqa: F401 # pylint: disable=unused-import # **************** for HCQ Compatible Devices **************** SignalType = TypeVar('SignalType', bound='HCQSignal') -DeviceType = TypeVar('DeviceType', bound='HCQCompiled') +HCQDeviceType = TypeVar('HCQDeviceType', bound='HCQCompiled') ProgramType = TypeVar('ProgramType', bound='HCQProgram') ArgsStateType = TypeVar('ArgsStateType', bound='HCQArgsState') QueueType = TypeVar('QueueType', bound='HWQueue') class BumpAllocator: - def __init__(self, size:int, start:int=0, wrap:bool=True): self.size, self.ptr, self.start_off, self.wrap = size, 0, start, wrap + def __init__(self, size:int, base:int=0, wrap:bool=True): self.size, self.ptr, self.base, self.wrap = size, 0, base, wrap def alloc(self, size:int, alignment:int=1) -> int: if round_up(self.ptr, alignment) + size > self.size: if not self.wrap: raise RuntimeError("Out of memory") self.ptr = 0 self.ptr = (res:=round_up(self.ptr, alignment)) + size - return res + self.start_off + return res + self.base -class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): +class HWQueue(Generic[SignalType, HCQDeviceType, ProgramType, ArgsStateType]): """ A base class for hardware command queues in the HCQ (Hardware Command Queue) API. """ def __init__(self): self._q:Any = [] - self.binded_device:Optional[DeviceType] = None + self.binded_device:HCQDeviceType|None = None self.q_sints:list[tuple[int, int]] = [] - self.mv_sints:list[tuple[memoryview, int, int, Optional[int]]] = [] + self.mv_sints:list[tuple[MMIOInterface, int, int, int|None]] = [] self.syms:list[sint] = [] - self._prev_resolved_syms:list[Optional[int]] = [] + self._prev_resolved_syms:list[int|None] = [] def _new_sym(self, sym:sint) -> int: if sym not in self.syms: @@ -51,10 +93,10 @@ class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): """ for v in values: - if isinstance(v, int): self._q.append(v) - else: + if isinstance(v, UOp): self.q_sints.append((len(self._q), self._new_sym(v))) self._q.append(0xbadc0ded) + else: self._q.append(v) # *** common commands *** @@ -116,7 +158,7 @@ class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): # *** submit and bind commands *** - def bind(self, dev:DeviceType): + def bind(self, dev:HCQDeviceType): """ Associates the queue with a specific device for optimized execution. @@ -131,13 +173,13 @@ class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): """ def bind_args_state(self, args_state:ArgsStateType): - for vals, ptr, fmt in args_state.bind_data: self.bind_sints_to_ptr(*vals, ptr=ptr, fmt=fmt) + for vals, mem, fmt in args_state.bind_data: self.bind_sints_to_mem(*vals, mem=mem, fmt=fmt) - def bind_sints(self, *vals:sint, struct:ctypes.Structure, start_field:str, fmt, mask:Optional[int]=None): - self.bind_sints_to_ptr(*vals, ptr=ctypes.addressof(struct) + getattr(type(struct), start_field).offset, fmt=fmt, mask=mask) + def bind_sints(self, *vals:sint, mem:MMIOInterface, struct_t:Type[ctypes.Structure], start_field:str, fmt, mask:int|None=None): + self.bind_sints_to_mem(*vals, mem=mem, fmt=fmt, mask=mask, offset=getattr(struct_t, start_field).offset) - def bind_sints_to_ptr(self, *vals:sint, ptr:int, fmt, mask:Optional[int]=None): - mv = to_mv(ptr, 8*len(vals)).cast(fmt) + def bind_sints_to_mem(self, *vals:sint, mem:MMIOInterface, fmt, mask:int|None=None, offset:int=0): + mv = mem.view(offset=offset, size=len(vals)*8, fmt=fmt) for i, val in enumerate(vals): if isinstance(val, int): mv[i] = val if mask is None else ((mv[i] & ~mask) | val) else: self.mv_sints.append((mv, i, self._new_sym(val), mask)) @@ -153,9 +195,9 @@ class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): if self._prev_resolved_syms[sym_idx] == resolved_syms[sym_idx]: continue mv[off] = resolved_syms[sym_idx] if mask is None else ((mv[off] & ~mask) | resolved_syms[sym_idx]) - self._prev_resolved_syms = cast(list[Optional[int]], resolved_syms) + self._prev_resolved_syms = cast(list[int|None], resolved_syms) - def submit(self, dev:DeviceType, var_vals:Optional[dict[Variable, int]]=None): + def submit(self, dev:HCQDeviceType, var_vals:dict[Variable, int]|None=None): """ Submits the command queue to a specific device for execution. @@ -166,18 +208,23 @@ class HWQueue(Generic[SignalType, DeviceType, ProgramType, ArgsStateType]): if var_vals is not None: self._apply_var_vals(var_vals) self._submit(dev) return self - def _submit(self, dev:DeviceType): raise NotImplementedError("need _submit") + def _submit(self, dev:HCQDeviceType): raise NotImplementedError("need _submit") -class HCQSignal(Generic[DeviceType]): - def __init__(self, base_addr:sint=0, value:int=0, timeline_for_device:Optional[DeviceType]=None, timestamp_divider=1, value_off=0, timestamp_off=8): - self.base_addr, self.value_addr, self.timestamp_addr = base_addr, base_addr+value_off, base_addr+timestamp_off +class HCQSignal(Generic[HCQDeviceType]): + def __init__(self, base_buf:HCQBuffer|None=None, value:int=0, dev_t:Type[HCQDeviceType]|None=None, timeline_for_device:HCQDeviceType|None=None, + timestamp_divider=1, value_off=0, timestamp_off=8): + self.base_buf = cast(HCQBuffer, dev_t._alloc_signal() if dev_t is not None and base_buf is None else base_buf) + self.value_addr, self.timestamp_addr, self.dev_t = self.base_buf.va_addr+value_off, self.base_buf.va_addr+timestamp_off, dev_t self.timestamp_divider:decimal.Decimal = decimal.Decimal(timestamp_divider) - self.timeline_for_device:Optional[DeviceType] = timeline_for_device + self.timeline_for_device:HCQDeviceType|None = timeline_for_device - if isinstance(base_addr, int): - self.value_mv, self.timestamp_mv = to_mv(self.value_addr, 8).cast('Q'), to_mv(self.timestamp_addr, 8).cast('Q') + if isinstance(self.base_buf.va_addr, int): + self.value_mv, self.timestamp_mv = self.base_buf.cpu_view().view(value_off, 8, 'Q'), self.base_buf.cpu_view().view(timestamp_off, 8, 'Q') self.value_mv[0] = value + def __del__(self): + if isinstance(self.base_buf.va_addr, int) and self.dev_t is not None: self.dev_t.signal_pool.append(self.base_buf) + @property def value(self) -> int: return self.value_mv[0] @@ -207,54 +254,57 @@ class HCQSignal(Generic[DeviceType]): Args: value: The value to wait for. - timeout: Maximum time to wait in milliseconds. Defaults to 10s. + timeout: Maximum time to wait in milliseconds. Defaults to 30s. """ start_time = int(time.perf_counter() * 1000) - while self.value < value and (time_spent:=int(time.perf_counter() * 1000) - start_time) < timeout: + while (not_passed:=(prev_value:=self.value) < value) and (time_spent:=int(time.perf_counter() * 1000) - start_time) < timeout: self._sleep(time_spent) - if self.value < value: raise RuntimeError(f"Wait timeout: {timeout} ms! (the signal is not set to {value}, but {self.value})") + if self.value != prev_value: start_time = int(time.perf_counter() * 1000) # progress was made, reset timer + if not_passed and self.value < value: raise RuntimeError(f"Wait timeout: {timeout} ms! (the signal is not set to {value}, but {self.value})") @contextlib.contextmanager -def hcq_profile(dev:HCQCompiled, enabled, desc, queue_type:Optional[Type[HWQueue]]=None, queue:Optional[HWQueue]=None): +def hcq_profile(dev:HCQCompiled, enabled, desc, queue_type:Callable[[], HWQueue]|None=None, queue:HWQueue|None=None): st, en = (dev.signal_t(), dev.signal_t()) if enabled else (None, None) if enabled and queue is not None: queue.timestamp(st) elif enabled: assert queue_type is not None - queue_type().wait(dev.timeline_signal, dev.timeline_value - 1).timestamp(st).signal(dev.timeline_signal, dev.timeline_value).submit(dev) - dev.timeline_value += 1 + queue_type().wait(dev.timeline_signal, dev.timeline_value - 1).timestamp(st).signal(dev.timeline_signal, dev.next_timeline()).submit(dev) try: yield (st, en) finally: if enabled and queue is not None: queue.timestamp(en) elif enabled: assert queue_type is not None - queue_type().wait(dev.timeline_signal, dev.timeline_value - 1).timestamp(en).signal(dev.timeline_signal, dev.timeline_value).submit(dev) - dev.timeline_value += 1 + queue_type().wait(dev.timeline_signal, dev.timeline_value - 1).timestamp(en).signal(dev.timeline_signal, dev.next_timeline()).submit(dev) if enabled and PROFILE: dev.sig_prof_records.append((cast(HCQSignal, st), cast(HCQSignal, en), desc, queue_type is dev.hw_copy_queue_t)) class HCQArgsState(Generic[ProgramType]): - def __init__(self, ptr:int, prg:ProgramType, bufs:tuple[HCQBuffer, ...], vals:tuple[sint, ...]=()): - self.ptr, self.prg = ptr, prg - self.bind_data:list[tuple[tuple[sint, ...], int, str]] = [] + def __init__(self, buf:HCQBuffer, prg:ProgramType, bufs:tuple[HCQBuffer, ...], vals:tuple[sint, ...]=()): + self.buf, self.prg = buf, prg + self.bind_data:list[tuple[tuple[sint, ...], MMIOInterface, str]] = [] - def bind_sints_to_ptr(self, *vals:sint, ptr:int, fmt): self.bind_data.append((vals, ptr, fmt)) + def bind_sints_to_buf(self, *vals:sint, buf:HCQBuffer, fmt, offset=0): self.bind_data.append((vals, buf.cpu_view().view(offset=offset), fmt)) class CLikeArgsState(HCQArgsState[ProgramType]): - def __init__(self, ptr:int, prg:ProgramType, bufs:tuple[HCQBuffer, ...], vals:tuple[sint, ...]=(), prefix:Optional[list[int]]=None): - super().__init__(ptr, prg, bufs, vals=vals) + def __init__(self, buf:HCQBuffer, prg:ProgramType, bufs:tuple[HCQBuffer, ...], vals:tuple[sint, ...]=(), prefix:list[int]|None=None): + super().__init__(buf, prg, bufs, vals=vals) - if prefix is not None: to_mv(self.ptr, len(prefix) * 4).cast('I')[:] = array.array('I', prefix) + if prefix is not None: self.buf.cpu_view().view(size=len(prefix) * 4, fmt='I')[:] = array.array('I', prefix) - self.bind_sints_to_ptr(*[b.va_addr for b in bufs], ptr=self.ptr + len(prefix or []) * 4, fmt='Q') - self.bind_sints_to_ptr(*vals, ptr=self.ptr + len(prefix or []) * 4 + len(bufs) * 8, fmt='I') + self.bind_sints_to_buf(*[b.va_addr for b in bufs], buf=self.buf, fmt='Q', offset=len(prefix or []) * 4) + self.bind_sints_to_buf(*vals, buf=self.buf, fmt='I', offset=len(prefix or []) * 4 + len(bufs) * 8) -class HCQProgram(Generic[DeviceType]): - def __init__(self, args_state_t:Type[HCQArgsState], dev:DeviceType, name:str, kernargs_alloc_size:int): +class HCQProgram(Generic[HCQDeviceType]): + def __init__(self, args_state_t:Type[HCQArgsState], dev:HCQDeviceType, name:str, kernargs_alloc_size:int, lib:bytes|None=None, base:int|None=None): self.args_state_t, self.dev, self.name, self.kernargs_alloc_size = args_state_t, dev, name, kernargs_alloc_size + if PROFILE: Compiled.profile_events += [ProfileProgramEvent(dev.device, name, lib, base)] + + @staticmethod + def _fini(dev, buf, spec): dev.allocator.free(buf, buf.size, spec) - def fill_kernargs(self, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=(), kernargs_ptr:Optional[int]=None) -> HCQArgsState: + def fill_kernargs(self, bufs:tuple[HCQBuffer, ...], vals:tuple[int, ...]=(), kernargs:HCQBuffer|None=None) -> HCQArgsState: """ Fills arguments for the kernel, optionally allocating space from the device if `kernargs_ptr` is not provided. Args: @@ -264,10 +314,11 @@ class HCQProgram(Generic[DeviceType]): Returns: Arguments state with the given buffers and values set for the program. """ - return self.args_state_t(kernargs_ptr or self.dev.kernargs_alloctor.alloc(self.kernargs_alloc_size), self, bufs, vals=vals) + argsbuf = kernargs or self.dev.kernargs_buf.offset(offset=self.dev.kernargs_offset_allocator.alloc(self.kernargs_alloc_size)) + return self.args_state_t(argsbuf, self, bufs, vals=vals) def __call__(self, *bufs:HCQBuffer, global_size:tuple[int,int,int]=(1,1,1), local_size:tuple[int,int,int]=(1,1,1), - vals:tuple[int, ...]=(), wait:bool=False) -> Optional[float]: + vals:tuple[int, ...]=(), wait:bool=False) -> float|None: """ Enqueues the program for execution with the given arguments and dimensions. @@ -288,8 +339,7 @@ class HCQProgram(Generic[DeviceType]): with hcq_profile(self.dev, queue=q, desc=self.name, enabled=wait or PROFILE) as (sig_st, sig_en): q.exec(self, kernargs, global_size, local_size) - q.signal(self.dev.timeline_signal, self.dev.timeline_value).submit(self.dev) - self.dev.timeline_value += 1 + q.signal(self.dev.timeline_signal, self.dev.next_timeline()).submit(self.dev) if wait: self.dev.synchronize() return (float(sig_en.timestamp - sig_st.timestamp) / 1e6) if wait else None @@ -298,25 +348,30 @@ class HCQCompiled(Compiled, Generic[SignalType]): """ A base class for devices compatible with the HCQ (Hardware Command Queue) API. """ - devices: list[HCQCompiled] = [] + devices: ClassVar[list[HCQCompiled]] = [] + signal_pages: ClassVar[list[HCQBuffer]] = [] + signal_pool: ClassVar[list[HCQBuffer]] = [] def __init__(self, device:str, allocator:HCQAllocatorBase, renderer:Renderer, compiler:Compiler, runtime, signal_t:Type[SignalType], - comp_queue_t:Type[HWQueue], copy_queue_t:Optional[Type[HWQueue]]): + comp_queue_t:Callable[[], HWQueue], copy_queue_t:Callable[[], HWQueue]|None, kernargs_size=(16 << 20), sigalloc_size=0x1000): self.device_id:int = int(device.split(":")[1]) if ":" in device else 0 + + from tinygrad.runtime.graph.hcq import HCQGraph + super().__init__(device, allocator, renderer, compiler, runtime, HCQGraph) + + # Map signals if any + for sig_page in self.signal_pages: cast(HCQAllocator, self.allocator).map(sig_page) + self.devices.append(self) + + self.sigalloc_size = sigalloc_size self.signal_t, self.hw_compute_queue_t, self.hw_copy_queue_t = signal_t, comp_queue_t, copy_queue_t self.timeline_value:int = 1 self.timeline_signal:SignalType = self.signal_t(value=0, timeline_for_device=self) self._shadow_timeline_signal:SignalType = self.signal_t(value=0, timeline_for_device=self) self.sig_prof_records:list[tuple[HCQSignal, HCQSignal, str, bool]] = [] - self.raw_prof_records:list[tuple[decimal.Decimal, decimal.Decimal, str, bool, Optional[dict]]] = [] - self.dep_prof_records:list[tuple[decimal.Decimal, decimal.Decimal, HCQCompiled, bool, decimal.Decimal, decimal.Decimal, HCQCompiled, bool]] = [] - from tinygrad.runtime.graph.hcq import HCQGraph - super().__init__(device, allocator, renderer, compiler, runtime, HCQGraph) - - self.kernargs_page:HCQBuffer = self.allocator.alloc(16 << 20, BufferSpec(cpu_access=True)) - self.kernargs_alloctor:BumpAllocator = BumpAllocator(self.kernargs_page.size, start=cast(int, self.kernargs_page.va_addr), wrap=True) - self.devices.append(self) + self.kernargs_buf:HCQBuffer = self.allocator.alloc(kernargs_size, BufferSpec(cpu_access=True)) + self.kernargs_offset_allocator:BumpAllocator = BumpAllocator(self.kernargs_buf.size, wrap=True) def synchronize(self): try: self.timeline_signal.wait(self.timeline_value - 1) @@ -329,10 +384,21 @@ class HCQCompiled(Compiled, Generic[SignalType]): Compiled.profile_events += [ProfileRangeEvent(self.device, name, st.timestamp, en.timestamp, cp) for st,en,name,cp in self.sig_prof_records] self.sig_prof_records = [] + def next_timeline(self): + self.timeline_value += 1 + return self.timeline_value - 1 + + @classmethod + def _alloc_signal(cls) -> HCQBuffer: + if not cls.signal_pool: + cls.signal_pages.append(alc:=cls.devices[0].allocator.alloc(cls.devices[0].sigalloc_size, BufferSpec(host=True,uncached=True,cpu_access=True))) + cls.signal_pool += [alc.offset(offset=off, size=16) for off in range(0, alc.size, 16)] + for dev in cls.devices: cast(HCQAllocator, dev.allocator).map(alc) + return cls.signal_pool.pop() + def _at_profile_finalize(self): - def _sync(d:HCQCompiled, q_t:Type[HWQueue]): - q_t().timestamp(d.timeline_signal).signal(d.timeline_signal, d.timeline_value).submit(d) - d.timeline_value += 1 + def _sync(d:HCQCompiled, q_t:Callable[[], HWQueue]): + q_t().timestamp(d.timeline_signal).signal(d.timeline_signal, d.next_timeline()).submit(d) st = time.perf_counter_ns() d.timeline_signal.wait(d.timeline_value - 1) # average of the two et = time.perf_counter_ns() @@ -348,41 +414,53 @@ class HCQCompiled(Compiled, Generic[SignalType]): self.timeline_signal.value = 0 cast(HCQAllocatorBase, self.allocator).b_timeline = [0] * len(cast(HCQAllocatorBase, self.allocator).b) + def _realloc(self, oldbuf:HCQBuffer|None, new_size:int, options:BufferSpec|None=None) -> tuple[HCQBuffer, bool]: + if oldbuf is not None: self.allocator.free(oldbuf, oldbuf.size, options=options) + try: buf, realloced = self.allocator.alloc(new_size, options=options), True + except MemoryError: buf, realloced = self.allocator.alloc(oldbuf.size if oldbuf is not None else new_size, options=options), False + return buf, realloced + class HCQBuffer: - def __init__(self, va_addr:sint, size:int, texture_info:Any=None, meta:Any=None, _base:Optional[HCQBuffer]=None): - self.va_addr, self.size, self.texture_info, self.meta, self._base = va_addr, size, texture_info, meta, _base + def __init__(self, va_addr:sint, size:int, texture_info:Any=None, meta:Any=None, _base:HCQBuffer|None=None, view:MMIOInterface|None=None): + self.va_addr, self.size, self.texture_info, self.meta, self._base, self.view = va_addr, size, texture_info, meta, _base, view -class HCQAllocatorBase(LRUAllocator, Generic[DeviceType]): + def offset(self, offset:int=0, size:int|None=None) -> HCQBuffer: + return HCQBuffer(self.va_addr+offset, size or (self.size - offset), texture_info=self.texture_info, meta=self.meta, _base=self._base or self, + view=(self.view.view(offset=offset, size=size) if self.view is not None else None)) + + def cpu_view(self) -> MMIOInterface: + assert self.view is not None, "buffer has no cpu_view" + return self.view + +class HCQAllocatorBase(LRUAllocator[HCQDeviceType], Generic[HCQDeviceType]): """ A base allocator class compatible with the HCQ (Hardware Command Queue) API. This class implements basic copy operations following the HCQ API, utilizing both types of `HWQueue`. """ - def __init__(self, dev:DeviceType, batch_size:int=(2 << 20), batch_cnt:int=32): - self.dev:DeviceType = dev - self.b = [self._alloc(batch_size, BufferSpec(host=True)) for _ in range(batch_cnt)] - self.b_timeline, self.b_next = [0] * len(self.b), 0 - super().__init__() + def __init__(self, dev:HCQDeviceType, batch_size:int=(2 << 20), batch_cnt:int=32, copy_bufs=None, max_copyout_size:int|None=None): + super().__init__(dev) + self.b = copy_bufs or [self._alloc(batch_size, BufferSpec(host=True)) for _ in range(batch_cnt)] + self.b_timeline, self.b_next, self.max_copyout_size = [0] * len(self.b), 0, max_copyout_size def map(self, buf:HCQBuffer): pass + def _offset(self, buf, size:int, offset:int) -> HCQBuffer: return buf.offset(offset=offset, size=size) - def _offset(self, buf, size:int, offset:int) -> HCQBuffer: - return HCQBuffer(va_addr=buf.va_addr + offset, size=size, texture_info=buf.texture_info, meta=buf.meta, _base=buf._base or buf) - -class HCQAllocator(HCQAllocatorBase, Generic[DeviceType]): +class HCQAllocator(HCQAllocatorBase, Generic[HCQDeviceType]): def _copyin(self, dest:HCQBuffer, src:memoryview): assert self.dev.hw_copy_queue_t is not None with hcq_profile(self.dev, queue_type=self.dev.hw_copy_queue_t, desc=f"CPU -> {self.dev.device}", enabled=PROFILE): for i in range(0, src.nbytes, self.b[0].size): self.b_next = (self.b_next + 1) % len(self.b) self.dev.timeline_signal.wait(self.b_timeline[self.b_next]) - ctypes.memmove(self.b[self.b_next].va_addr, from_mv(src[i:]), lsize:=min(self.b[self.b_next].size, src.nbytes-i)) + + lsize = min(self.b[self.b_next].size, src.nbytes - i) + self.b[self.b_next].cpu_view().view(size=lsize, fmt='B')[:] = src[i:i+lsize] self.dev.hw_copy_queue_t().wait(self.dev.timeline_signal, self.dev.timeline_value - 1) \ .copy(dest.va_addr+i, self.b[self.b_next].va_addr, lsize) \ - .signal(self.dev.timeline_signal, self.dev.timeline_value).submit(self.dev) - self.b_timeline[self.b_next] = self.dev.timeline_value - self.dev.timeline_value += 1 + .signal(self.dev.timeline_signal, self.dev.next_timeline()).submit(self.dev) + self.b_timeline[self.b_next] = self.dev.timeline_value - 1 def copy_from_disk(self, dest:HCQBuffer, src, size): def _get_temp_buf(): @@ -397,25 +475,22 @@ class HCQAllocator(HCQAllocatorBase, Generic[DeviceType]): for (batch_info, dst_off, src_off, copy_size) in src.device.allocator._copyout_sharded(src, size, _get_temp_buf, seg_len=self.b[0].size): self.dev.hw_copy_queue_t().wait(self.dev.timeline_signal, self.dev.timeline_value - 1) \ .copy(dest.va_addr + dst_off, batch_info[0] + src_off, copy_size) \ - .signal(self.dev.timeline_signal, self.dev.timeline_value).submit(self.dev) - self.b_timeline[batch_info[1]] = self.dev.timeline_value - self.dev.timeline_value += 1 + .signal(self.dev.timeline_signal, self.dev.next_timeline()).submit(self.dev) + self.b_timeline[batch_info[1]] = self.dev.timeline_value - 1 def _copyout(self, dest:memoryview, src:HCQBuffer): self.dev.synchronize() assert self.dev.hw_copy_queue_t is not None with hcq_profile(self.dev, queue_type=self.dev.hw_copy_queue_t, desc=f"{self.dev.device} -> CPU", enabled=PROFILE): - for i in range(0, dest.nbytes, self.b[0].size): + for i in range(0, dest.nbytes, cp_size:=(self.max_copyout_size or self.b[0].size)): self.dev.hw_copy_queue_t().wait(self.dev.timeline_signal, self.dev.timeline_value - 1) \ - .copy(self.b[0].va_addr, src.va_addr+i, lsize:=min(self.b[0].size, dest.nbytes-i)) \ - .signal(self.dev.timeline_signal, self.dev.timeline_value).submit(self.dev) - self.dev.timeline_signal.wait(self.dev.timeline_value) - self.dev.timeline_value += 1 - - ctypes.memmove(from_mv(dest[i:]), self.b[0].va_addr, lsize) + .copy(self.b[0].va_addr, src.va_addr+i, lsize:=min(cp_size, dest.nbytes-i)) \ + .signal(self.dev.timeline_signal, self.dev.next_timeline()).submit(self.dev) + self.dev.timeline_signal.wait(self.dev.timeline_value - 1) + dest[i:i+lsize] = self.b[0].cpu_view().view(size=lsize, fmt='B')[:] - def _transfer(self, dest:HCQBuffer, src:HCQBuffer, sz:int, src_dev:DeviceType, dest_dev:DeviceType): + def _transfer(self, dest:HCQBuffer, src:HCQBuffer, sz:int, src_dev:HCQDeviceType, dest_dev:HCQDeviceType): cast(HCQAllocator, src_dev.allocator).map(dest) assert src_dev.hw_copy_queue_t is not None @@ -423,11 +498,9 @@ class HCQAllocator(HCQAllocatorBase, Generic[DeviceType]): src_dev.hw_copy_queue_t().wait(src_dev.timeline_signal, src_dev.timeline_value - 1) \ .wait(dest_dev.timeline_signal, dest_dev.timeline_value - 1) \ .copy(dest.va_addr, src.va_addr, sz) \ - .signal(src_dev.timeline_signal, src_dev.timeline_value).submit(src_dev) - src_dev.timeline_value += 1 + .signal(src_dev.timeline_signal, src_dev.next_timeline()).submit(src_dev) if src_dev != dest_dev: dest_dev.hw_compute_queue_t().wait(src_dev.timeline_signal, src_dev.timeline_value - 1) \ .wait(dest_dev.timeline_signal, dest_dev.timeline_value - 1) \ - .signal(dest_dev.timeline_signal, dest_dev.timeline_value).submit(dest_dev) - dest_dev.timeline_value += 1 + .signal(dest_dev.timeline_signal, dest_dev.next_timeline()).submit(dest_dev) diff --git a/tinygrad_repo/tinygrad/runtime/support/llvm.py b/tinygrad_repo/tinygrad/runtime/support/llvm.py new file mode 100644 index 0000000000..bb1490e583 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/llvm.py @@ -0,0 +1,25 @@ +import ctypes, ctypes.util, os, sys, subprocess +from tinygrad.helpers import DEBUG, OSX, getenv + +if sys.platform == 'win32': + # Windows llvm distribution doesn't seem to add itself to PATH or anywhere else where it can be easily retrieved from. + # winget also doesn't have something like `brew --prefix llvm` so just hardcode default installation path with an option to override + LLVM_PATH = getenv('LLVM_PATH', 'C:\\Program Files\\LLVM\\bin\\LLVM-C.dll') + if not os.path.exists(LLVM_PATH): + raise FileNotFoundError('LLVM not found, you can install it with `winget install LLVM.LLVM` or point at a custom dll with LLVM_PATH') +elif OSX: + # Will raise FileNotFoundError if brew is not installed + # `brew --prefix` will return even if formula is not installed + if not os.path.exists(brew_prefix:=subprocess.check_output(['brew', '--prefix', 'llvm@19']).decode().strip()): + raise FileNotFoundError('LLVM not found, you can install it with `brew install llvm@19`') + LLVM_PATH: str|None = os.path.join(brew_prefix, 'lib', 'libLLVM.dylib') +else: + LLVM_PATH = ctypes.util.find_library('LLVM') + # use newer LLVM if possible + for ver in reversed(range(14, 19+1)): + if LLVM_PATH is not None: break + LLVM_PATH = ctypes.util.find_library(f'LLVM-{ver}') + if LLVM_PATH is None: + raise FileNotFoundError("No LLVM library found on the system. Install it via your distro's package manager and ensure it's findable as 'LLVM'") + +if DEBUG>=3: print(f'Using LLVM at {repr(LLVM_PATH)}') diff --git a/tinygrad_repo/tinygrad/runtime/support/usb.py b/tinygrad_repo/tinygrad/runtime/support/usb.py new file mode 100644 index 0000000000..72de138627 --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/usb.py @@ -0,0 +1,267 @@ +import ctypes, struct, dataclasses, array, itertools +from typing import Sequence +from tinygrad.runtime.autogen import libusb +from tinygrad.helpers import DEBUG, to_mv, round_up +from tinygrad.runtime.support.hcq import MMIOInterface + +class USB3: + def __init__(self, vendor:int, dev:int, ep_data_in:int, ep_stat_in:int, ep_data_out:int, ep_cmd_out:int, max_streams:int=31): + self.vendor, self.dev = vendor, dev + self.ep_data_in, self.ep_stat_in, self.ep_data_out, self.ep_cmd_out = ep_data_in, ep_stat_in, ep_data_out, ep_cmd_out + self.max_streams = max_streams + self.ctx = ctypes.POINTER(libusb.struct_libusb_context)() + + if libusb.libusb_init(ctypes.byref(self.ctx)): raise RuntimeError("libusb_init failed") + if DEBUG >= 6: libusb.libusb_set_option(self.ctx, libusb.LIBUSB_OPTION_LOG_LEVEL, 4) + + self.handle = libusb.libusb_open_device_with_vid_pid(self.ctx, self.vendor, self.dev) + if not self.handle: raise RuntimeError(f"device {self.vendor:04x}:{self.dev:04x} not found. sudo required?") + + # Detach kernel driver if needed + if libusb.libusb_kernel_driver_active(self.handle, 0): + libusb.libusb_detach_kernel_driver(self.handle, 0) + libusb.libusb_reset_device(self.handle) + + # Set configuration and claim interface + if libusb.libusb_set_configuration(self.handle, 1): raise RuntimeError("set_configuration failed") + if libusb.libusb_claim_interface(self.handle, 0): raise RuntimeError("claim_interface failed. sudo required?") + if libusb.libusb_set_interface_alt_setting(self.handle, 0, 1): raise RuntimeError("alt_setting failed") + + # Clear any stalled endpoints + all_eps = (self.ep_data_out, self.ep_data_in, self.ep_stat_in, self.ep_cmd_out) + for ep in all_eps: libusb.libusb_clear_halt(self.handle, ep) + + # Allocate streams + stream_eps = (ctypes.c_uint8 * 3)(self.ep_data_out, self.ep_data_in, self.ep_stat_in) + if (rc:=libusb.libusb_alloc_streams(self.handle, self.max_streams * len(stream_eps), stream_eps, len(stream_eps))) < 0: + raise RuntimeError(f"alloc_streams failed: {rc}") + + # Base cmd + cmd_template = bytes([0x01, 0x00, 0x00, 0x01, *([0] * 12), 0xE4, 0x24, 0x00, 0xB2, 0x1A, 0x00, 0x00, 0x00, *([0] * 8)]) + + # Init pools + self.tr = {ep: [libusb.libusb_alloc_transfer(0) for _ in range(self.max_streams)] for ep in all_eps} + + self.buf_cmd = [(ctypes.c_uint8 * len(cmd_template))(*cmd_template) for _ in range(self.max_streams)] + self.buf_stat = [(ctypes.c_uint8 * 64)() for _ in range(self.max_streams)] + self.buf_data_in = [(ctypes.c_uint8 * 0x1000)() for _ in range(self.max_streams)] + self.buf_data_out = [(ctypes.c_uint8 * 0x80000)() for _ in range(self.max_streams)] + self.buf_data_out_mvs = [to_mv(ctypes.addressof(self.buf_data_out[i]), 0x80000) for i in range(self.max_streams)] + + def _prep_transfer(self, tr, ep, stream_id, buf, length): + tr.contents.dev_handle, tr.contents.endpoint, tr.contents.length, tr.contents.buffer = self.handle, ep, length, buf + tr.contents.status, tr.contents.flags, tr.contents.timeout, tr.contents.num_iso_packets = 0xff, 0, 1000, 0 + tr.contents.type = (libusb.LIBUSB_TRANSFER_TYPE_BULK_STREAM if stream_id is not None else libusb.LIBUSB_TRANSFER_TYPE_BULK) + if stream_id is not None: libusb.libusb_transfer_set_stream_id(tr, stream_id) + return tr + + def _submit_and_wait(self, cmds): + for tr in cmds: libusb.libusb_submit_transfer(tr) + + running = len(cmds) + while running: + libusb.libusb_handle_events(self.ctx) + running = len(cmds) + for tr in cmds: + if tr.contents.status == libusb.LIBUSB_TRANSFER_COMPLETED: running -= 1 + elif tr.contents.status != 0xFF: raise RuntimeError(f"EP 0x{tr.contents.endpoint:02X} error: {tr.contents.status}") + + def send_batch(self, cdbs:list[bytes], idata:list[int]|None=None, odata:list[bytes|None]|None=None) -> list[bytes|None]: + idata, odata = idata or [0] * len(cdbs), odata or [None] * len(cdbs) + results, tr_window, op_window = [], [], [] + + for idx, (cdb, rlen, send_data) in enumerate(zip(cdbs, idata, odata)): + # allocate slot and stream. stream is 1-based + slot, stream = idx % self.max_streams, (idx % self.max_streams) + 1 + + # build cmd packet + struct.pack_into(">B", self.buf_cmd[slot], 3, stream) + self.buf_cmd[slot][16:16+len(cdb)] = list(cdb) + + # cmd + stat transfers + tr_window.append(self._prep_transfer(self.tr[self.ep_cmd_out][slot], self.ep_cmd_out, None, self.buf_cmd[slot], len(self.buf_cmd[slot]))) + tr_window.append(self._prep_transfer(self.tr[self.ep_stat_in][slot], self.ep_stat_in, stream, self.buf_stat[slot], 64)) + + if rlen: + if rlen > len(self.buf_data_in[slot]): self.buf_data_in[slot] = (ctypes.c_uint8 * round_up(rlen, 0x1000))() + tr_window.append(self._prep_transfer(self.tr[self.ep_data_in][slot], self.ep_data_in, stream, self.buf_data_in[slot], rlen)) + + if send_data is not None: + if len(send_data) > len(self.buf_data_out[slot]): + self.buf_data_out[slot] = (ctypes.c_uint8 * len(send_data))() + self.buf_data_out_mvs[slot] = to_mv(ctypes.addressof(self.buf_data_out[slot]), len(send_data)) + + self.buf_data_out_mvs[slot][:len(send_data)] = bytes(send_data) + tr_window.append(self._prep_transfer(self.tr[self.ep_data_out][slot], self.ep_data_out, stream, self.buf_data_out[slot], len(send_data))) + + op_window.append((idx, slot, rlen)) + if (idx + 1 == len(cdbs)) or len(op_window) >= self.max_streams: + self._submit_and_wait(tr_window) + for idx, slot, rlen in op_window: results.append(bytes(self.buf_data_in[slot][:rlen]) if rlen else None) + tr_window = [] + + return results + +@dataclasses.dataclass(frozen=True) +class WriteOp: addr:int; data:bytes; ignore_cache:bool=True # noqa: E702 + +@dataclasses.dataclass(frozen=True) +class ReadOp: addr:int; size:int # noqa: E702 + +@dataclasses.dataclass(frozen=True) +class ScsiWriteOp: data:bytes; lba:int=0 # noqa: E702 + +class ASM24Controller: + def __init__(self): + self.usb = USB3(0xADD1, 0x0001, 0x81, 0x83, 0x02, 0x04) + self._cache: dict[int, int|None] = {} + self._pci_cacheable: list[tuple[int, int]] = [] + self._pci_cache: dict[int, int|None] = {} + + # Init controller. + self.exec_ops([WriteOp(0x54b, b' '), WriteOp(0x54e, b'\x04'), WriteOp(0x5a8, b'\x02'), WriteOp(0x5f8, b'\x04'), + WriteOp(0x7ec, b'\x01\x00\x00\x00'), WriteOp(0xc422, b'\x02'), WriteOp(0x0, b'\x33')]) + + def exec_ops(self, ops:Sequence[WriteOp|ReadOp|ScsiWriteOp]): + cdbs:list[bytes] = [] + idata:list[int] = [] + odata:list[bytes|None] = [] + + def _add_req(cdb:bytes, i:int, o:bytes|None): + nonlocal cdbs, idata, odata + cdbs, idata, odata = cdbs + [cdb], idata + [i], odata + [o] + + for op in ops: + if isinstance(op, WriteOp): + for off, value in enumerate(op.data): + addr = ((op.addr + off) & 0x1FFFF) | 0x500000 + if not op.ignore_cache and self._cache.get(addr) == value: continue + _add_req(struct.pack('>BBBHB', 0xE5, value, addr >> 16, addr & 0xFFFF, 0), 0, None) + self._cache[addr] = value + elif isinstance(op, ReadOp): + assert op.size <= 0xff + addr = (op.addr & 0x1FFFF) | 0x500000 + _add_req(struct.pack('>BBBHB', 0xE4, op.size, addr >> 16, addr & 0xFFFF, 0), op.size, None) + for i in range(op.size): self._cache[addr + i] = None + elif isinstance(op, ScsiWriteOp): + sectors = round_up(len(op.data), 512) // 512 + _add_req(struct.pack('>BBQIBB', 0x8A, 0, op.lba, sectors, 0, 0), 0, op.data+b'\x00'*((sectors*512)-len(op.data))) + + return self.usb.send_batch(cdbs, idata, odata) + + def write(self, base_addr:int, data:bytes, ignore_cache:bool=True): return self.exec_ops([WriteOp(base_addr, data, ignore_cache)]) + + def scsi_write(self, buf:bytes, lba:int=0): + if len(buf) > 0x4000: buf += b'\x00' * (round_up(len(buf), 0x10000) - len(buf)) + + for i in range(0, len(buf), 0x10000): + self.exec_ops([ScsiWriteOp(buf[i:i+0x10000], lba), WriteOp(0x171, b'\xff\xff\xff', ignore_cache=True)]) + self.exec_ops([WriteOp(0xce6e, b'\x00\x00', ignore_cache=True)]) + + if len(buf) > 0x4000: + for i in range(4): self.exec_ops([WriteOp(0xce40 + i, b'\x00', ignore_cache=True)]) + + def read(self, base_addr:int, length:int, stride:int=0xff) -> bytes: + parts = self.exec_ops([ReadOp(base_addr + off, min(stride, length - off)) for off in range(0, length, stride)]) + return b''.join(p or b'' for p in parts)[:length] + + def _is_pci_cacheable(self, addr:int) -> bool: return any(x <= addr <= x + sz for x, sz in self._pci_cacheable) + def pcie_prep_request(self, fmt_type:int, address:int, value:int|None=None, size:int=4) -> list[WriteOp]: + if fmt_type == 0x60 and size == 4 and self._is_pci_cacheable(address) and self._pci_cache.get(address) == value: return [] + + assert fmt_type >> 8 == 0 and size > 0 and size <= 4, f"Invalid fmt_type {fmt_type} or size {size}" + if DEBUG >= 3: print("pcie_request", hex(fmt_type), hex(address), value, size) + + masked_address, offset = address & 0xFFFFFFFC, address & 0x3 + assert size + offset <= 4 and (value is None or value >> (8 * size) == 0) + self._pci_cache[address] = value if size == 4 and fmt_type == 0x60 else None + + return ([WriteOp(0xB220, struct.pack('>I', value << (8 * offset)), ignore_cache=False)] if value is not None else []) + \ + [WriteOp(0xB218, struct.pack('>I', masked_address), ignore_cache=False), WriteOp(0xB21c, struct.pack('>I', address>>32), ignore_cache=False), + WriteOp(0xB217, bytes([((1 << size) - 1) << offset]), ignore_cache=False), WriteOp(0xB210, bytes([fmt_type]), ignore_cache=False), + WriteOp(0xB254, b"\x0f", ignore_cache=True), WriteOp(0xB296, b"\x04", ignore_cache=True)] + + def pcie_request(self, fmt_type, address, value=None, size=4, cnt=10): + self.exec_ops(self.pcie_prep_request(fmt_type, address, value, size)) + + # Fast path for write requests + if ((fmt_type & 0b11011111) == 0b01000000) or ((fmt_type & 0b10111000) == 0b00110000): return + + while (stat:=self.read(0xB296, 1)[0]) & 2 == 0: + if stat & 1: + self.write(0xB296, bytes([0x01])) + if cnt > 0: return self.pcie_request(fmt_type, address, value, size, cnt=cnt-1) + assert stat == 2, f"stat read 2 was {stat}" + + # Retrieve completion data from Link Status (0xB22A, 0xB22B) + b284 = self.read(0xB284, 1)[0] + completion = struct.unpack('>H', self.read(0xB22A, 2)) + + # Validate completion status based on PCIe request typ + # Completion TLPs for configuration requests always have a byte count of 4. + assert completion[0] & 0xfff == (4 if (fmt_type & 0xbe == 0x04) else size) + + # Extract completion status field + status = (completion[0] >> 13) & 0x7 + + # Handle completion errors or inconsistencies + if status or ((fmt_type & 0xbe == 0x04) and (((value is None) and (not (b284 & 0x01))) or ((value is not None) and (b284 & 0x01)))): + status_map = {0b001: f"Unsupported Request: invalid address/function (target might not be reachable): {address:#x}", + 0b100: "Completer Abort: abort due to internal error", 0b010: "Configuration Request Retry Status: configuration space busy"} + raise RuntimeError(f"TLP status: {status_map.get(status, 'Reserved (0b{:03b})'.format(status))}") + + if value is None: return (struct.unpack('>I', self.read(0xB220, 4))[0] >> (8 * (address & 0x3))) & ((1 << (8 * size)) - 1) + + def pcie_cfg_req(self, byte_addr, bus=1, dev=0, fn=0, value=None, size=4): + assert byte_addr >> 12 == 0 and bus >> 8 == 0 and dev >> 5 == 0 and fn >> 3 == 0, f"Invalid byte_addr {byte_addr}, bus {bus}, dev {dev}, fn {fn}" + + fmt_type = (0x44 if value is not None else 0x4) | int(bus > 0) + address = (bus << 24) | (dev << 19) | (fn << 16) | (byte_addr & 0xfff) + return self.pcie_request(fmt_type, address, value, size) + + def pcie_mem_req(self, address, value=None, size=4): return self.pcie_request(0x60 if value is not None else 0x20, address, value, size) + + def pcie_mem_write(self, address, values, size): + ops = [self.pcie_prep_request(0x60, address + i * size, value, size) for i, value in enumerate(values)] + + # Send in batches of 4 + for i in range(0, len(ops), 4): self.exec_ops(list(itertools.chain.from_iterable(ops[i:i+4]))) + +class USBMMIOInterface(MMIOInterface): + def __init__(self, usb, addr, size, fmt, pcimem=True): + self.usb, self.addr, self.nbytes, self.fmt, self.pcimem, self.el_sz = usb, addr, size, fmt, pcimem, struct.calcsize(fmt) + + def __getitem__(self, index): return self._access_items(index) + def __setitem__(self, index, val): self._access_items(index, val) + + def _access_items(self, index, val=None): + if isinstance(index, slice): return self._acc((index.start or 0) * self.el_sz, ((index.stop or len(self))-(index.start or 0)) * self.el_sz, val) + return self._acc_one(index * self.el_sz, self.el_sz, val) if self.pcimem else self._acc(index * self.el_sz, self.el_sz, val) + + def view(self, offset:int=0, size:int|None=None, fmt=None): + return USBMMIOInterface(self.usb, self.addr+offset, size or (self.nbytes - offset), fmt=fmt or self.fmt, pcimem=self.pcimem) + + def _acc_size(self, sz): return next(x for x in [('I', 4), ('H', 2), ('B', 1)] if sz % x[1] == 0) + + def _acc_one(self, off, sz, val=None): + upper = 0 if sz < 8 else self.usb.pcie_mem_req(self.addr + off + 4, val if val is None else (val >> 32), 4) + lower = self.usb.pcie_mem_req(self.addr + off, val if val is None else val & 0xffffffff, min(sz, 4)) + if val is None: return lower | (upper << 32) + + def _acc(self, off, sz, data=None): + if data is None: # read op + if not self.pcimem: + return int.from_bytes(self.usb.read(self.addr + off, sz), "little") if sz == self.el_sz else self.usb.read(self.addr + off, sz) + + acc, acc_size = self._acc_size(sz) + return bytes(array.array(acc, [self._acc_one(off + i * acc_size, acc_size) for i in range(sz // acc_size)])) + else: # write op + data = struct.pack(self.fmt, data) if isinstance(data, int) else bytes(data) + + if not self.pcimem: + # Fast path for writing into buffer 0xf000 + use_cache = 0xa800 <= self.addr <= 0xb000 + return self.usb.scsi_write(bytes(data)) if self.addr == 0xf000 else self.usb.write(self.addr + off, bytes(data), ignore_cache=not use_cache) + + _, acc_sz = self._acc_size(len(data) * struct.calcsize(self.fmt)) + self.usb.pcie_mem_write(self.addr+off, [int.from_bytes(data[i:i+acc_sz], "little") for i in range(0, len(data), acc_sz)], acc_sz) diff --git a/tinygrad_repo/tinygrad/runtime/support/webgpu.py b/tinygrad_repo/tinygrad/runtime/support/webgpu.py new file mode 100644 index 0000000000..24fb75c71f --- /dev/null +++ b/tinygrad_repo/tinygrad/runtime/support/webgpu.py @@ -0,0 +1,11 @@ +import ctypes, ctypes.util, os, subprocess +from tinygrad.helpers import OSX + +if OSX: + if not os.path.exists(brew_prefix:=subprocess.check_output(['brew', '--prefix', 'dawn']).decode().strip()): + raise FileNotFoundError('dawn library not found. Install it with `brew tap wpmed92/dawn && brew install dawn`') + WEBGPU_PATH: str|None = os.path.join(brew_prefix, 'lib', 'libwebgpu_dawn.dylib') +else: + if (WEBGPU_PATH:=ctypes.util.find_library('webgpu_dawn')) is None: + raise FileNotFoundError("dawn library not found. " + + "Install it with `sudo curl -L https://github.com/wpmed92/pydawn/releases/download/v0.1.6/libwebgpu_dawn.so -o /usr/lib/libwebgpu_dawn.so`") diff --git a/tinygrad_repo/tinygrad/shape/shapetracker.py b/tinygrad_repo/tinygrad/shape/shapetracker.py index d86688fa0f..031fb64e2b 100644 --- a/tinygrad_repo/tinygrad/shape/shapetracker.py +++ b/tinygrad_repo/tinygrad/shape/shapetracker.py @@ -4,39 +4,52 @@ from dataclasses import dataclass import functools from typing import Optional, Callable from tinygrad.helpers import merge_dicts, getenv -from tinygrad.shape.view import View, strides_for_shape +from tinygrad.shape.view import View, strides_for_shape, unravel from tinygrad.dtype import dtypes -from tinygrad.ops import UOp, Ops, graph_rewrite, split_uop, symbolic_flat, Variable, sint, uop_given_valid, simplify_valid - -@functools.lru_cache(None) +from tinygrad.uop.ops import UOp, Ops, graph_rewrite, Variable, sint, sint_to_uop, Context, PatternMatcher, UPat, GroupOp +from tinygrad.codegen.symbolic import split_uop, symbolic_flat, uop_given_valid, simplify_valid + +# If a node overflow, its srcs need to be checked to see if this overflow is the result of an ALU operation, +# or that the node simply inherits the dtype from srcs. Upcast is either `Ops.CAST`+`replace` or just `replace`. +def handle_upcast(u: UOp) -> UOp|None: + dtype = dtypes.int64.vec(u.dtype.count) if u.dtype.count > 1 else dtypes.int64 + # check for overflow, upcast this to int64 + if u.vmax > dtypes.max(dtypes.int) or u.vmin < dtypes.min(dtypes.int): + return u.replace(dtype=dtype, src=tuple([x.cast(dtype) for x in u.src])) + # if any inputs are int64 and this *doesn't* overflow, cast back to int + if any(x.dtype == dtypes.int64 for x in u.src): + return u.replace(dtype=dtype, src=tuple([x.cast(dtype) for x in u.src])).cast(u.dtype) + return None +pm_upcast = PatternMatcher([(UPat(GroupOp.ALU, dtype=dtypes.int, name="u"), handle_upcast),]) + +@functools.cache def views_to_indexed_uops(views: tuple[View, ...], _idxs:Optional[tuple[UOp, ...]]=None) -> tuple[UOp, UOp]: idx, valid = views[-1].to_indexed_uops(_idxs) for view in reversed(views[0:-1]): view = view.minify() - acc, idxs = 1, [] - for d in reversed(view.shape): - idxs.append((idx//acc)%d) - acc *= d - idx, valid = view.to_indexed_uops(idxs[::-1], valid) - return idx, valid - -@functools.lru_cache(None) + idx, valid = view.to_indexed_uops([sint_to_uop(i) for i in unravel(view.shape, idx)], valid) + # symbolic + idx, valid = graph_rewrite(UOp.sink(idx, valid), symbolic_flat, name="indexing sym @ 1").src + # simplify + if (newvalid:=simplify_valid(valid)) is not None: valid = newvalid + if (newidx:=uop_given_valid(valid, idx)) is not None: idx = newidx + # symbolic again, upcast if needed + return graph_rewrite(UOp.sink(idx, valid), symbolic_flat+pm_upcast, name="indexing sym @ 2").src + +@functools.cache def views_to_real_strides(views: tuple[View, ...], ignore_valid=False) -> tuple[Optional[sint], ...]: # NOTE: if a stride is not always valid, it will be None if len(views) == 1 and views[-1].mask is None: return views[-1].strides ret: list[Optional[sint]] = [None] * len(views[-1].shape) - idx, valid = (graph_rewrite(u, symbolic_flat) for u in views_to_indexed_uops(views)) - # TODO: always apply these in to_indexed_uops? - if (newvalid:=simplify_valid(valid)) is not None: valid = newvalid - if (newidx:=uop_given_valid(valid, idx)) is not None: idx = graph_rewrite(newidx, symbolic_flat) + idx, valid = views_to_indexed_uops(views) for c in split_uop(idx, Ops.ADD): if c.op is Ops.RANGE: ret[c.arg] = 1 if c.op is Ops.MUL and c.src[0].op is Ops.RANGE and c.src[1].op is Ops.CONST: ret[c.src[0].arg] = c.src[1].arg if c.op is Ops.MUL and c.src[1].op is Ops.RANGE and c.src[0].op is Ops.CONST: ret[c.src[1].arg] = c.src[0].arg - used_ranges = [x.arg for x in idx.toposort if x.op is Ops.RANGE] + used_ranges = [x.arg for x in idx.toposort() if x.op is Ops.RANGE] ret = [x if i in used_ranges else 0 for i,x in enumerate(ret)] if not ignore_valid: - for masked_axis in [x.arg for x in valid.toposort if x.op is Ops.RANGE]: ret[masked_axis] = None + for masked_axis in [x.arg for x in valid.toposort() if x.op is Ops.RANGE]: ret[masked_axis] = None return tuple(ret) @dataclass(frozen=True, order=True) @@ -56,7 +69,7 @@ class ShapeTracker: return ShapeTracker(tuple(inverted_views)).reshape(out_shape) @staticmethod - def from_shape(shape:tuple[sint, ...]) -> ShapeTracker: return ShapeTracker((View.create(shape),)) + def from_shape(shape:tuple[sint, ...], strides:tuple[sint, ...]|None=None) -> ShapeTracker: return ShapeTracker((View.create(shape, strides),)) @property def contiguous(self) -> bool: return len(self.views) == 1 and self.views[0].contiguous @@ -76,12 +89,13 @@ class ShapeTracker: def to_indexed_uops(self, _idxs:Optional[list[UOp]|tuple[UOp, ...]]=None) -> tuple[UOp, UOp]: return views_to_indexed_uops(self.views, tuple(_idxs) if _idxs is not None else None) + # upper bound on buffer size required to fit this shapetracker def real_size(self) -> int: if 0 in self.shape: return 0 - idx, valid = self.to_indexed_uops() - if not valid.vmax: return 0 + view = (v.shrink(v.mask) if (v:=self.views[0]).mask else v) + idx, _ = views_to_indexed_uops((view,)) assert idx.vmax < 1e12, f"real_size broken for {self}" - return int(idx.vmax+1) + return int(idx.vmax + 1) def vars(self) -> set[Variable]: return set().union(*[v.vars() for v in self.views]) @@ -90,14 +104,18 @@ class ShapeTracker: def unbind(self) -> tuple[ShapeTracker, dict[Variable, int]]: unbound_views, var_vals = zip(*[v.unbind() for v in self.views]) + if all(len(x) == 0 for x in var_vals): return self, {} return ShapeTracker(tuple(unbound_views)), merge_dicts(var_vals) + def substitute(self, dvars:dict[UOp, UOp]): return ShapeTracker(tuple(x.substitute(dvars) for x in self.views)) - def real_strides(self, ignore_valid=False) -> tuple[Optional[sint], ...]: return views_to_real_strides(self.views, ignore_valid) + def real_strides(self, ignore_valid=False) -> tuple[Optional[sint], ...]: + with Context(TRACK_MATCH_STATS=0): return views_to_real_strides(self.views, ignore_valid) def unit_stride_axes(self, ignore_valid=False) -> list[int]: return [i for i,st in enumerate(self.real_strides(ignore_valid)) if st == 1] def axis_is_masked(self, axis:int) -> bool: - _, valid = self.to_indexed_uops() - return axis in [x.arg for x in graph_rewrite(valid, symbolic_flat).toposort if x.op is Ops.RANGE] + with Context(TRACK_MATCH_STATS=0): + _, valid = self.to_indexed_uops() + return axis in [x.arg for x in graph_rewrite(valid, symbolic_flat).toposort() if x.op is Ops.RANGE] def simplify(self) -> ShapeTracker: if len(self.views) >= 2 and (new_view := self.views[-2] + self.views[-1]) is not None: @@ -110,7 +128,7 @@ class ShapeTracker: def shrink(self, arg: tuple[tuple[sint, sint], ...]) -> ShapeTracker: return ShapeTracker(self.views[0:-1] + (self.views[-1].shrink(arg), )) def expand(self, new_shape: tuple[sint, ...]) -> ShapeTracker: return ShapeTracker(self.views[0:-1] + (self.views[-1].expand(new_shape), )) def permute(self, axis: tuple[int, ...]) -> ShapeTracker: return ShapeTracker(self.views[0:-1] + (self.views[-1].permute(axis), )) - def stride(self, mul: tuple[int, ...]) -> ShapeTracker: return ShapeTracker(self.views[0:-1] + (self.views[-1].stride(mul), )) + def flip(self, mul: tuple[int, ...]) -> ShapeTracker: return ShapeTracker(self.views[0:-1] + (self.views[-1].flip(mul), )) def reshape(self, new_shape: tuple[sint, ...]) -> ShapeTracker: if getenv("MERGE_VIEW", 1) and (new_view := self.views[-1].reshape(new_shape)) is not None: return ShapeTracker(self.views[0:-1] + (new_view,)) @@ -119,4 +137,4 @@ class ShapeTracker: def mop(self, op, arg): return mops[op](self, arg) mops: dict[Ops, Callable] = {Ops.RESHAPE: ShapeTracker.reshape, Ops.PERMUTE: ShapeTracker.permute, Ops.EXPAND: ShapeTracker.expand, - Ops.SHRINK: ShapeTracker.shrink, Ops.STRIDE: ShapeTracker.stride, Ops.PAD: ShapeTracker.pad} + Ops.SHRINK: ShapeTracker.shrink, Ops.FLIP: ShapeTracker.flip, Ops.PAD: ShapeTracker.pad} diff --git a/tinygrad_repo/tinygrad/shape/view.py b/tinygrad_repo/tinygrad/shape/view.py index dcc2f821d6..bc7ba0716c 100644 --- a/tinygrad_repo/tinygrad/shape/view.py +++ b/tinygrad_repo/tinygrad/shape/view.py @@ -3,20 +3,20 @@ import functools, operator, itertools from dataclasses import dataclass from typing import Optional, cast, Sequence from tinygrad.dtype import dtypes -from tinygrad.ops import resolve, UOp, Variable, sint, sym_infer, smax, smin, sint_to_uop +from tinygrad.uop.ops import resolve, UOp, Variable, sint, sym_infer, smax, smin, sint_to_uop, Ops from tinygrad.helpers import prod, all_int, argsort, flatten, ceildiv -@functools.lru_cache(maxsize=None) +@functools.cache def canonicalize_strides(shape:tuple[sint, ...], strides:tuple[sint, ...]) -> tuple[sint, ...]: return tuple(0 if s == 1 else st for s, st in zip(shape, strides)) -@functools.lru_cache(maxsize=None) +@functools.cache def strides_for_shape(shape:tuple[sint, ...]) -> tuple[sint, ...]: if not shape: return () strides = tuple(itertools.accumulate(reversed(shape[1:]), operator.mul, initial=1))[::-1] return canonicalize_strides(shape, strides) -@functools.lru_cache(maxsize=None) +@functools.cache def merge_dims(shape:tuple[int, ...], strides:tuple[int, ...], mask:Optional[tuple[tuple[int, int], ...]]=None) -> tuple[tuple[int, int, int], ...]: # merge contiguous sub-parts or zero strided dims # any stride 0, masked from dim=1, or contiguous part is merged into next dim. @@ -38,7 +38,7 @@ def merge_dims(shape:tuple[int, ...], strides:tuple[int, ...], mask:Optional[tup merging = (mask[i][1] - mask[i][0] == 1) if mask is not None else s == 1 return tuple(ret) -@functools.lru_cache(maxsize=None) +@functools.cache def _reshape_mask(_mask:Optional[tuple[tuple[sint, sint], ...]], old_shape:tuple[sint, ...], new_shape:tuple[sint, ...]) \ -> Optional[tuple[tuple[sint, sint], ...]]: """Returns the new mask if reshape is possible, and None if not possible.""" @@ -65,7 +65,7 @@ def _reshape_mask(_mask:Optional[tuple[tuple[sint, sint], ...]], old_shape:tuple else: next_mask = next(r_masks, (0, 1)) # combine if the mask can unfold continuously - if mask != (0, old_dim) and next_mask[1] - next_mask[0] != 1: return None + if mask != (0, old_dim) and l != r and next_mask[1] - next_mask[0] != 1: return None mask, old_dim = (next_mask[0] * old_dim + l, (next_mask[1] - 1) * old_dim + r), old_dim * next(r_shape, 1) return tuple(reversed(new_mask)) @@ -73,11 +73,11 @@ def _reshape_mask(_mask:Optional[tuple[tuple[sint, sint], ...]], old_shape:tuple def unravel(shape:tuple[sint, ...], offset:sint) -> list[sint]: # find the position of offset on each dimension based on shape # similar to unravel_index in numpy/torch - ret = [] - for stride in strides_for_shape(shape): - ret.append(offset // stride if stride != 0 else 0) - offset -= ret[-1] * stride - return ret + acc, idxs = 1, [] + for d in reversed(shape): + idxs.append((offset//acc)%d) + acc *= d + return idxs[::-1] @dataclass(frozen=True) class View: @@ -87,15 +87,9 @@ class View: mask:Optional[tuple[tuple[sint, sint], ...]] contiguous:bool - @functools.cached_property - def t(self): - return tuple(x.tuplize if isinstance(x, UOp) else (x,) \ - for x in self.shape+self.strides+(self.offset,)+(tuple(flatten(self.mask)) if self.mask is not None else tuple())) - def __lt__(self, o:View): return self.t < o.t - def to_indexed_uops(self:View, idxs:Optional[Sequence[UOp]]=None, vexpr:UOp=UOp.const(dtypes.bool, True)) -> tuple[UOp, UOp]: """(idx, valid)""" - if idxs is None: idxs = [UOp.range(dtypes.int, 0, s, i) for i,s in enumerate(self.shape)] + if idxs is None: idxs = [UOp.range(dtypes.int, s, i) for i,s in enumerate(self.shape)] iexpr = sint_to_uop(self.offset) for idx,sh,st,m in zip(idxs, self.shape, self.strides, self.mask if self.mask is not None else itertools.repeat(None)): if resolve(sh != 1) and resolve(st != 0): iexpr = iexpr + idx*st @@ -104,16 +98,16 @@ class View: if resolve(m[1] != sh): vexpr = vexpr * (idx < m[1]) return iexpr, vexpr - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def size(self) -> int: ret = prod([x.vmax if isinstance(x, UOp) else x for x in self.shape]) assert isinstance(ret, int), f"{ret=} is not int" return ret @staticmethod - @functools.lru_cache(maxsize=None) + @functools.cache def create(shape:tuple[sint, ...], strides:Optional[tuple[sint, ...]]=None, offset:sint=0, mask:Optional[tuple[tuple[sint, sint], ...]]=None): - # TODO: this resolve shouldn't be needed + # TODO: resolve shouldn't be needed here if not all(resolve(s >= 0) for s in shape): raise ValueError(f"Trying to create View with negative dimension: {shape=}") strides = canonicalize_strides(shape, strides) if strides else strides_for_shape(shape) # canonicalize 0 in shape @@ -138,23 +132,26 @@ class View: contiguous = offset == 0 and mask is None and strides == strides_for_shape(shape) return View(shape, strides, offset, mask, contiguous) - @functools.lru_cache(None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def vars(self) -> set[Variable]: flatten_mask = tuple(x for m in self.mask for x in m) if self.mask is not None else tuple() return functools.reduce(operator.or_, [x.vars() for x in self.shape+self.strides+(self.offset,)+flatten_mask if isinstance(x, UOp)], set()) - @functools.lru_cache(None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def unbind(self) -> tuple[View, dict[Variable, int]]: - var_unboundvar_val = [(v, v.unbind()) for v in self.vars()] + var_unboundvar_val = [(v, v.unbind()) for v in self.vars() if v.op is Ops.BIND] unbound_vars = {v:uv for v,(uv,_) in var_unboundvar_val} - def substitute(x:sint): return x if isinstance(x, int) else x.substitute(unbound_vars) - new_shape = tuple(map(substitute, self.shape)) - new_strides = tuple(map(substitute, self.strides)) - new_offset = substitute(self.offset) - new_mask = tuple((substitute(x[0]), substitute(x[1])) for x in self.mask) if self.mask is not None else None - return View.create(new_shape, new_strides, new_offset, new_mask), dict(x[1] for x in var_unboundvar_val) - - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + return self.substitute(unbound_vars), dict(x[1] for x in var_unboundvar_val) + + def substitute(self, dvars:dict[UOp, UOp]): + def _substitute(x:sint): return x if isinstance(x, int) else x.substitute(dvars) + new_shape = tuple(map(_substitute, self.shape)) + new_strides = tuple(map(_substitute, self.strides)) + new_offset = _substitute(self.offset) + new_mask = tuple((_substitute(x[0]), _substitute(x[1])) for x in self.mask) if self.mask is not None else None + return View.create(new_shape, new_strides, new_offset, new_mask) + + @functools.cache # pylint: disable=method-cache-max-size-none def __add__(self, vm1:View) -> Optional[View]: vm2 = self if vm2.contiguous: return vm1 @@ -198,19 +195,13 @@ class View: newb, newe, bad = [0] * len(vm1.shape), list(vm1.shape), False for (b, e), o, term, (_, t) in zip(vm2.mask, origin, terms, reversed(extents)): if resolve(b <= t.vmin and t.vmax < e, False): continue - if not all_int([o, b, e]): - bad = True - continue if len(term) != 1: if not term and newe: newe[0] = 0 else: bad = True continue d1, s1 = term[0] - if not all_int([s1, newe[d1]]): - bad = True - continue - newb[d1] = max(newb[d1], ceildiv(b - o if s1 > 0 else e - o - 1, s1)) - newe[d1] = min(newe[d1], (b - o if s1 < 0 else e - o - 1) // s1 + 1) + newb[d1] = smax(newb[d1], ceildiv(b - o if s1 > 0 else e - o - 1, s1)) + newe[d1] = smin(newe[d1], (b - o if s1 < 0 else e - o - 1) // s1 + 1) # If any of vm1 was masked off, try again with that mask in place. if any((b, e) != (0, s) for b, e, s in zip(newb, newe, vm1.shape)): @@ -220,14 +211,14 @@ class View: return View.create(vm1.shape, tuple(strides), sum(o * s for o, s in zip(origin, vm2.strides)) + vm2.offset) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def invert(self, out_shape:tuple[sint, ...]) -> Optional[View]: ret = View.create(self.shape) if self.mask: ret = ret.shrink(self.mask) - ret = ret.stride(tuple(-1 if x < 0 else 1 for x in self.strides)).permute(argsort(tuple(-x if x > 0 else x for x in self.strides))) + ret = ret.flip(tuple(x < 0 for x in self.strides)).permute(argsort(tuple(-x if x > 0 else x for x in self.strides))) return ret if prod(ret.shape) == prod(out_shape) else None # don't support shrink, expand, or stride != (-1, 1) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def minify(self): min_shape = tuple(x[0] for x in merge_dims(self.shape, self.strides, self.mask)) return nv if (nv := self.reshape(min_shape)) else self @@ -241,7 +232,7 @@ class View: mask = tuple([(smax(mx1, mx2), smin(my1, my2)) for (mx1, my1), (mx2, my2) in zip(nmask, mask)]) if mask is not None else nmask return View.create(tuple([y-x for x,y in arg]), self.strides, self.offset+offset, mask) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def pad(self, arg: tuple[tuple[sint, sint], ...]) -> View: assert len(arg) == len(self.shape), f"invalid pad {arg} for {self.shape}" # NOTE: not checking for symbolic arg @@ -252,14 +243,14 @@ class View: return self.__unsafe_resize(zvarg, mask=mask) return self - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def shrink(self, arg: tuple[tuple[sint, sint], ...]) -> View: assert len(arg) == len(self.shape), f"invalid shrink {arg} for {self.shape}" # NOTE: not checking for symbolic arg for s,(b,e) in zip(self.shape,arg): assert not all_int([s,b,e]) or (0<=b<=e<=s), f"invalid shrink {arg} for {self.shape}" return self.__unsafe_resize(arg) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def expand(self, new_shape: tuple[sint, ...]) -> View: if len(new_shape) != len(self.shape): raise ValueError(f"expand arg {new_shape=} must have same number of dimensions as shape {self.shape=}") # NOTE: does not check multiple of symbolic shape @@ -270,28 +261,23 @@ class View: for m,s,ns in zip(self.mask, self.shape, new_shape)]) if self.mask else None return View.create(new_shape, self.strides, self.offset, mask) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none def permute(self, axis: tuple[int, ...]) -> View: assert sorted(axis) == list(range(len(self.shape))), f"invalid permutation {axis} of len {len(self.shape)}" return View.create(tuple(self.shape[a] for a in axis), tuple(self.strides[a] for a in axis), self.offset, tuple(self.mask[a] for a in axis) if self.mask is not None else None) - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none - def stride(self, mul: tuple[int, ...]) -> View: - # except for the negative case, you can build this from the others. invertible in the negative case - assert all(isinstance(x, int) and x != 0 for x in mul), f"invalid stride {mul} for {self.shape}" - strides = tuple([z*m for z,m in zip(self.strides, mul)]) - new_shape = tuple([ceildiv(s, abs(m)) for s,m in zip(self.shape, mul)]) - offset = sum([(s-1)*z for s,z,m in zip(self.shape, self.strides, mul) if m < 0]) - mask = tuple([(ceildiv(mx if m > 0 else s-my, abs(m)), ceildiv(my if m > 0 else s-mx, abs(m))) \ - for (mx,my),s,m in zip(self.mask, self.shape, mul)]) if self.mask is not None else None - return View.create(new_shape, strides, self.offset + offset, mask) - - @functools.lru_cache(maxsize=None) # pylint: disable=method-cache-max-size-none + @functools.cache # pylint: disable=method-cache-max-size-none + def flip(self, arg: tuple[bool, ...]) -> View: + offset = sum((s-1)*z for s,z,f in zip(self.shape, self.strides, arg) if f) + mask = tuple((s-my,s-mx) if f else (mx,my) for (mx,my),s,f in zip(self.mask, self.shape, arg)) if self.mask is not None else None + return View.create(self.shape, tuple(-z if f else z for z,f in zip(self.strides, arg)), self.offset+offset, mask) + + @functools.cache # pylint: disable=method-cache-max-size-none def reshape(self, new_shape: tuple[sint, ...]) -> Optional[View]: if self.shape == new_shape: return self - assert all(x >= 0 for x in new_shape), f"shape can't contain negative numbers {new_shape}" + if not all(x >= 0 for x in new_shape): raise ValueError(f"shape can't contain negative numbers {new_shape}") # check for the same size if (self_all_int := all_int(self.shape)): assert all(isinstance(s, (int, UOp)) for s in new_shape), f"{self.shape=} -> {new_shape=} contains non (int, Variable) dim" diff --git a/tinygrad_repo/tinygrad/tensor.py b/tinygrad_repo/tinygrad/tensor.py index cd1de65127..8f04132289 100644 --- a/tinygrad_repo/tinygrad/tensor.py +++ b/tinygrad_repo/tinygrad/tensor.py @@ -1,58 +1,61 @@ # inspired by https://github.com/karpathy/micrograd/blob/master/micrograd/engine.py from __future__ import annotations -import time, math, itertools, functools, struct, sys, inspect, pathlib, string, dataclasses, hashlib +import time, math, itertools, functools, struct, sys, inspect, pathlib, string, hashlib, weakref, contextvars from contextlib import ContextDecorator -from typing import List, Tuple, Callable, Optional, ClassVar, Type, Union, Sequence, cast, get_args, Literal, TYPE_CHECKING, SupportsIndex +from typing import Callable, ClassVar, Sequence, cast, get_args, Literal, SupportsIndex, ParamSpec, TypeVar, Optional from tinygrad.dtype import DType, DTypeLike, dtypes, ImageDType, ConstType, least_upper_float, least_upper_dtype, sum_acc_dtype, to_dtype, truncate +from tinygrad.dtype import _from_np_dtype, _to_np_dtype from tinygrad.helpers import argfix, make_tuple, flatten, prod, all_int, round_up, merge_dicts, argsort, getenv, all_same, fully_flatten, dedup -from tinygrad.helpers import IMAGE, DEBUG, WINO, _METADATA, Metadata, TRACEMETA, ceildiv, fetch, polyN, unwrap -from tinygrad.multi import MultiLazyBuffer +from tinygrad.helpers import IMAGE, WINO, Metadata, TRACEMETA, ceildiv, fetch, polyN, unwrap, DEBUG from tinygrad.gradient import compute_gradient -from tinygrad.ops import smax, smin, resolve, UOp, Ops, sint, Variable, SimpleMathTrait, identity_element -from tinygrad.device import Device, Buffer, BufferSpec +from tinygrad.uop.ops import smax, smin, resolve, UOp, Ops, sint, Variable, SimpleMathTrait, identity_element, all_metadata +from tinygrad.uop.spec import tensor_uop_spec, type_verify +from tinygrad.device import Device, Buffer from tinygrad.engine.realize import run_schedule from tinygrad.engine.memory import memory_planner from tinygrad.engine.schedule import ScheduleItem, create_schedule_with_vars +from tinygrad.engine.grouper import get_becomes_map -# **** start with two base classes, Tensor and Function **** - -class Function: - def __init__(self, device:Union[str, tuple[str, ...]], *tensors:Tensor, metadata:Optional[Metadata]=None): - self.device = device - self.needs_input_grad = [t.requires_grad for t in tensors] - self.requires_grad = True if any(self.needs_input_grad) else None if None in self.needs_input_grad else False - if self.requires_grad: self.parents = tensors - self.metadata = metadata - - def forward(self, *args, **kwargs): raise NotImplementedError(f"forward not implemented for {type(self)}") - def backward(self, *args, **kwargs): raise RuntimeError(f"backward not implemented for {type(self)}") - - @classmethod - def apply(fxn:Type[Function], *x:Tensor, **kwargs) -> Tensor: - ctx = fxn(x[0].device, *x, metadata=_METADATA.get()) - ret = Tensor.__new__(Tensor) - ret.lazydata, ret.requires_grad, ret.grad = ctx.forward(*[t.lazydata for t in x], **kwargs), ctx.requires_grad, None - ret._ctx = ctx if ctx.requires_grad and not Tensor.no_grad else None # used by autograd engine - return ret +# *** all in scope Tensors are here. this gets relevant UOps *** -import tinygrad.function as F +all_tensors: set[weakref.ref[Tensor]] = set() -def _metaop(op, shape:tuple[sint,...], dtype:DType, device:Union[str, tuple[str, ...]], arg=None, src:tuple[UOp, ...]=()): - if isinstance(device, str): return UOp.metaop(op, shape, dtype, device, arg, src) - return MultiLazyBuffer([UOp.metaop(op, shape, dtype, d, arg, src) for d in device], None) +def _apply_map_to_tensors(applied_map:dict[UOp, UOp], name:str|None=None) -> None: + # get all children of keys in applied_map + all_uops: set[UOp] = set() + search_uops = list(applied_map) + while len(search_uops): + x = search_uops.pop() + if x in all_uops: continue + all_uops.add(x) + search_uops.extend([u for c in x.children if (u:=c()) is not None]) -def _from_np_dtype(npdtype:'np.dtype') -> DType: # type: ignore [name-defined] # noqa: F821 - import numpy as np - return dtypes.fields()[np.dtype(npdtype).name] -def _to_np_dtype(dtype:DType) -> Optional[type]: - import numpy as np - return np.dtype(dtype.fmt).type if dtype.fmt is not None else None + # link the found UOps back to Tensors. exit early if there's no Tensors to realize + # NOTE: this uses all_tensors, but it's fast + fixed_tensors: list[Tensor] = [t for tref in all_tensors if (t:=tref()) is not None and t.lazydata in all_uops] + + if len(fixed_tensors): + # potentially rewrite all the discovered Tensors + sink = UOp.sink(*[t.lazydata for t in fixed_tensors]) + new_sink = sink.substitute(applied_map, name=name) + + # set the relevant lazydata to the realized UOps + for t,s,ns in zip(fixed_tensors, sink.src, new_sink.src): + if s is ns: continue + t.lazydata = ns + +# **** Tensor helper functions **** + +# this tracks the tensor.py METADATA +_METADATA: contextvars.ContextVar[Optional[Metadata]] = contextvars.ContextVar("_METADATA", default=None) + +def _metaop(op, shape:tuple[sint,...], dtype:DType, device:str|tuple[str, ...], arg=None) -> UOp: return UOp.metaop(op, shape, dtype, device, arg) def _fromnp(x: 'np.ndarray') -> UOp: # type: ignore [name-defined] # noqa: F821 - ret = UOp.metaop(Ops.EMPTY, x.shape, _from_np_dtype(x.dtype), "NPY") + ret = UOp.new_buffer("NPY", x.size, _from_np_dtype(x.dtype)) # fake realize ret.buffer.allocate(x) - return ret.buf_uop_view() + return ret.reshape(x.shape) def get_shape(x) -> tuple[int, ...]: # NOTE: str is special because __getitem__ on a str is still a str @@ -60,18 +63,18 @@ def get_shape(x) -> tuple[int, ...]: if not all_same(subs:=[get_shape(xi) for xi in x]): raise ValueError(f"inhomogeneous shape from {x}") return (len(subs),) + (subs[0] if subs else ()) -def _frompy(x:Union[List, Tuple, bytes], dtype:DType) -> UOp: - if isinstance(x, bytes): ret, data = UOp.metaop(Ops.EMPTY, (len(x)//dtype.itemsize,), dtype, "PYTHON"), x +def _frompy(x:list|tuple|bytes, dtype:DType) -> UOp: + if isinstance(x, bytes): ret, data = UOp.new_buffer("PYTHON", len(x)//dtype.itemsize, dtype), x else: - ret = UOp.metaop(Ops.EMPTY, get_shape(x), dtype, "PYTHON") + ret = UOp.new_buffer("PYTHON", prod(shape:=get_shape(x)), dtype).reshape(shape) assert dtype.fmt is not None, f"{dtype=} has None fmt" truncate_function = truncate[dtype] data = struct.pack(f"@{ret.size}{dtype.fmt}", *[truncate_function(xi) for xi in fully_flatten(x)]) # fake realize ret.buffer.allocate(memoryview(data if Device.DEFAULT != "PYTHON" else bytearray(data))) - return ret.buf_uop_view() + return ret -def _get_winograd_matcols(mat, dims:int, shp:tuple[sint, ...], device:Union[str, tuple[str, ...]], dtype:DType) -> list[list[Tensor]]: +def _get_winograd_matcols(mat, dims:int, shp:tuple[sint, ...], device:str|tuple[str, ...], dtype:DType) -> list[list[Tensor]]: return [[Tensor.cat(*[Tensor.full(shp[:dim] + (1,) + shp[dim+1:], float(m[k]), device=device, dtype=dtype) for m in mat], dim=dim) for k in range(len(mat[0]))] for dim in range(dims)] @@ -94,15 +97,17 @@ def _align_left(*shapes:tuple[sint, ...]) -> tuple[tuple[sint, ...], ...]: def _broadcast_shape(*shapes:tuple[sint, ...]) -> tuple[sint, ...]: return tuple(0 if 0 in nth_dim_sizes else smax(nth_dim_sizes) for nth_dim_sizes in zip(*_align_left(*shapes))) -def _masked_setitem(target:Tensor, values:Tensor, mask:Tensor, axes:tuple[int, ...]): - # apply mask to values (already broadcasted) and reduce such that if mask contains repeated indices the last one remains - values = values * mask +def _masked_setitem(target:Tensor, values:Tensor, mask:Tensor, axes:tuple[int, ...]) -> Tensor: + # reduce such that if mask contains repeated indices the last one remains for dim in axes: mask, values = functools.reduce(lambda x,y: (x[0]|y[0], y[0].where(y[1], x[1])), zip(mask.split(1, dim), values.split(1, dim))) # remove extra dims from reduce for dim in reversed(axes): mask, values = mask.squeeze(dim), values.squeeze(dim) - # select from values for each True element in mask else select from self + # select from values for each True element in mask else select from target return mask.where(values, target) +# `(padding_left, padding_right, padding_top, padding_bottom, ...)` -> `(..., (padding_top, padding_bottom), (padding_left, padding_right))` +def _flat_to_grouped(padding:Sequence[sint]) -> tuple[tuple[sint, sint], ...]: return tuple(zip(padding[-2::-2], padding[::-2])) + ReductionStr = Literal["mean", "sum", "none"] class Tensor(SimpleMathTrait): @@ -116,40 +121,35 @@ class Tensor(SimpleMathTrait): np.set_printoptions(precision=4) ``` """ - __slots__ = "lazydata", "requires_grad", "grad", "_ctx" - __deletable__ = ('_ctx',) + __slots__ = "lazydata", "requires_grad", "grad" training: ClassVar[bool] = False no_grad: ClassVar[bool] = False - def __init__(self, data:Union[None, ConstType, bytes, List, Tuple, UOp, MultiLazyBuffer, 'np.ndarray', pathlib.Path], # type: ignore [name-defined] # noqa: F821 - device:Optional[Union[str, tuple, list]]=None, dtype:Optional[DTypeLike]=None, requires_grad:Optional[bool]=None): + def __init__(self, data:ConstType|bytes|list|tuple|UOp|'np.ndarray'|pathlib.Path|None, # type: ignore [name-defined] # noqa: F821 + device:str|tuple|list|None=None, dtype:DTypeLike|None=None, requires_grad:bool|None=None): if dtype is not None: dtype = to_dtype(dtype) if device is None and isinstance(data, pathlib.Path): device = f"DISK:{data.resolve()}" # keep it on the disk if device is None device = tuple(Device.canonicalize(x) for x in device) if isinstance(device, (tuple, list)) else Device.canonicalize(device) # tensors can have gradients if you have called .backward - self.grad: Optional[Tensor] = None + self.grad:Tensor|None = None # NOTE: this can be in three states. False and None: no gradient, True: gradient # None (the default) will be updated to True if it's put in an optimizer - self.requires_grad: Optional[bool] = requires_grad + self.requires_grad:bool|None = requires_grad - # internal variable used for autograd graph construction - self._ctx: Optional[Function] = None - - # create a LazyBuffer from the different types of inputs - if isinstance(data, (UOp, MultiLazyBuffer)): + # create a UOp from the different types of inputs + if isinstance(data, UOp): assert dtype is None or dtype==data.dtype, "dtype doesn't match, and casting isn't supported" - # NOTE: this is here because LazyBuffer = UOp - if isinstance(data, UOp) and data.op is Ops.BIND: data = _metaop(Ops.CONST, tuple(), dtype or data.dtype, device, data) - elif data is None: data = _metaop(Ops.EMPTY, (0,), dtype or dtypes.default_float, device) + if data.op is Ops.BIND: data = _metaop(Ops.BIND, tuple(), dtype or data.dtype, device, data) + elif data is None: data = _metaop(Ops.CONST, (0,), dtype or dtypes.default_float, device, arg=0) elif isinstance(data, get_args(ConstType)): data = _metaop(Ops.CONST, tuple(), dtype or dtypes.from_py(data), device, data) elif isinstance(data, bytes): data = _frompy(data, dtypes.uint8 if dtype is None else dtype) elif isinstance(data, (list, tuple)): if dtype is None: if (d := fully_flatten(data)) and all(isinstance(s, bool) for s in d): dtype = dtypes.bool else: dtype = dtypes.default_int if d and all_int(d) else dtypes.default_float # NOTE: this works because all_int([True, False]) is True - if dtype == dtypes.bfloat16: data = Tensor(_frompy(data, dtypes.float32), device=device).cast(dtypes.bfloat16).lazydata + if dtype in [dtypes.bfloat16, *dtypes.fp8s]: data = Tensor(_frompy(data, dtypes.float32), device=device).cast(dtype).lazydata else: data = _frompy(data, dtype) elif str(type(data)) == "": import numpy as np @@ -158,19 +158,33 @@ class Tensor(SimpleMathTrait): else: data = _fromnp(data.astype(npdtype) if dtype is not None and (npdtype:=_to_np_dtype(dtype)) is not None else data) # type: ignore [name-defined] elif isinstance(data, pathlib.Path): dtype = dtype or dtypes.uint8 - data = _metaop(Ops.EMPTY, (data.stat().st_size // dtype.itemsize,), dtype, f"DISK:{data.resolve()}") + data = UOp.new_buffer(f"DISK:{data.resolve()}", data.stat().st_size // dtype.itemsize, dtype) - # by this point, it has to be a LazyBuffer - if not isinstance(data, (UOp, MultiLazyBuffer)): raise RuntimeError(f"can't create Tensor from {data!r} with type {type(data)}") + # by this point, it has to be a UOp + if not isinstance(data, UOp): raise RuntimeError(f"can't create Tensor from {data!r} with type {type(data)}") # data might be on a different device - if isinstance(device, str): self.lazydata:Union[UOp, MultiLazyBuffer] = data if data.device == device else data.copy_to_device(device) + if isinstance(device, str): self.lazydata:UOp = data if data.device == device else data.copy_to_device(device) # if device is a tuple, we should have/construct a MultiLazyBuffer - elif isinstance(data, UOp): self.lazydata = MultiLazyBuffer.from_sharded(data, device, None, None) + elif isinstance(data, UOp) and isinstance(data.device, str): self.lazydata = Tensor(data).shard(device).lazydata else: assert data.device == device, f"MultiLazyBuffer device mismatch, {data.device} != {device}" self.lazydata = data + # add to all_tensors after construction succeeds + all_tensors.add(weakref.ref(self)) + def __del__(self): all_tensors.discard(weakref.ref(self)) + + def _apply_uop(self, fxn:Callable, *x:Tensor, **kwargs) -> Tensor: + new_uop: UOp = fxn(*[t.lazydata for t in (self,)+x], **kwargs) + if (metadata:=_METADATA.get()) is not None: all_metadata[new_uop] = metadata + needs_input_grad = [t.requires_grad for t in (self,)+x] + return Tensor(new_uop, device=new_uop.device, requires_grad=True if any(needs_input_grad) else None if None in needs_input_grad else False) + + def _apply_broadcasted_uop(self, fxn:Callable, x:Tensor|ConstType, reverse=False) -> Tensor: + lhs,rhs = self._broadcasted(x, reverse) + return lhs._apply_uop(fxn, rhs) + def requires_grad_(self, requires_grad=True) -> Tensor: self.requires_grad = requires_grad return self @@ -186,8 +200,8 @@ class Tensor(SimpleMathTrait): def __exit__(self, exc_type, exc_value, traceback): Tensor.no_grad = self.prev def __repr__(self): - if isinstance(ld:=self.lazydata, MultiLazyBuffer): ld_repr = f"{self.lazydata!r}" - else: ld_repr = f"" + ld = self.lazydata + ld_repr = f"" return f"" # Python has a non moving GC, so this should be okay @@ -200,7 +214,7 @@ class Tensor(SimpleMathTrait): return self.shape[0] @property - def device(self) -> Union[str, tuple[str, ...]]: return self.lazydata.device + def device(self) -> str|tuple[str, ...]: return self.lazydata.device @property def shape(self) -> tuple[sint, ...]: return self.lazydata.shape @@ -210,14 +224,34 @@ class Tensor(SimpleMathTrait): # ***** data handlers **** + def kernelize(self, *lst:Tensor) -> Tensor: + """ + Creates the kernels and buffers needed to realize these Tensor(s). + + NOTE: Kernelize can be called multiple times on a Tensor + """ + big_sink = UOp.sink(*[x.lazydata for x in (self,)+lst]) + + # verify Tensors match the spec + if __debug__: type_verify(list(big_sink.toposort()), tensor_uop_spec) + + becomes_map = get_becomes_map(big_sink) + _apply_map_to_tensors(becomes_map, name="Apply Kernelize Map") + return self + def schedule_with_vars(self, *lst:Tensor) -> tuple[list[ScheduleItem], dict[Variable, int]]: """ Creates the schedule needed to realize these Tensor(s), with Variables. NOTE: A Tensor can only be scheduled once. """ - schedule, var_vals = create_schedule_with_vars(flatten([x.lazydata.lbs for x in (self,)+lst])) - return memory_planner(schedule), var_vals + st = time.perf_counter() + self.kernelize(*lst) + schedule, var_vals, becomes_map = create_schedule_with_vars(UOp.sink(*[x.lazydata for x in (self,)+lst])) + _apply_map_to_tensors(becomes_map, name="Apply Schedule Map") + schedule = memory_planner(schedule) + if DEBUG >= 1 and len(schedule) >= 10: print(f"scheduled {len(schedule)} kernels in {(time.perf_counter()-st)*1000:.2f} ms") + return schedule, var_vals def schedule(self, *lst:Tensor) -> list[ScheduleItem]: """Creates the schedule needed to realize these Tensor(s).""" @@ -230,32 +264,28 @@ class Tensor(SimpleMathTrait): run_schedule(*self.schedule_with_vars(*lst), do_update_stats=do_update_stats) return self - def replace(self, x:Tensor) -> Tensor: + def replace(self, x:Tensor, allow_shape_mismatch=False) -> Tensor: """ Replaces the data of this tensor with the data of another tensor. Only the shape of the tensors must match. """ # used for replacing a Tensor with a new version of it (potentially with a different device and dtype) - assert not x.requires_grad and getattr(self, '_ctx', None) is None - assert self.shape == x.shape, f"replace shape mismatch {self.shape} != {x.shape}" + assert self.shape == x.shape or allow_shape_mismatch, f"replace shape mismatch {self.shape} != {x.shape}" self.lazydata = x.lazydata return self def assign(self, x) -> Tensor: # TODO: this is a hack for writing to DISK. remove with working assign if isinstance(self.device, str) and self.device.startswith("DISK"): - if x.__class__ is not Tensor: x = Tensor(x, device="CLANG", dtype=self.dtype) - self.contiguous().realize().lazydata.base.realized.copyin(x._data()) + if x.__class__ is not Tensor: x = Tensor(x, device="CPU", dtype=self.dtype) + cast(Buffer, self.contiguous().realize().lazydata.base.buffer).ensure_allocated().copyin(x._data()) return self if x.__class__ is not Tensor: x = Tensor(x, device=self.device, dtype=self.dtype) - if DEBUG >= 4: print(f"assign {self.lazydata} <- {x.lazydata}") if self.lazydata is x.lazydata: return self # a self assign is a NOOP # NOTE: we allow cross device assign assert self.shape == x.shape, f"assign shape mismatch {self.shape} != {x.shape}" assert self.device == x.device, f"assign device mismatch {self.device} != {x.device}" assert self.dtype == x.dtype, f"assign dtype mismatch {self.dtype} != {x.dtype}" - assert not isinstance(self.lazydata, MultiLazyBuffer) or self.lazydata.axis == x.lazydata.axis, "axis must match on MultiLazyBuffer" assert not x.requires_grad # self requires_grad is okay? - if not self.lazydata.is_realized: return self.replace(x) self.lazydata = self.lazydata.assign(x.lazydata) return self @@ -265,13 +295,8 @@ class Tensor(SimpleMathTrait): """ return Tensor(self.lazydata.detach(), device=self.device, requires_grad=False) - def _data(self) -> memoryview: - if 0 in self.shape: return memoryview(bytearray(0)) - # NOTE: this realizes on the object from as_buffer being a Python object - cpu = self.cast(self.dtype.base).contiguous().to("CLANG").realize() - buf = cast(Buffer, cast(UOp, cpu.lazydata).base.realized) - if self.device != "CLANG": buf.options = BufferSpec(nolru=True) - return buf.as_buffer(allow_zero_copy=True if self.device != "CLANG" else False) + def _buffer(self) -> Buffer: return cast(Buffer, self.cast(self.dtype.base).contiguous().to("CPU").realize().lazydata.base.buffer) + def _data(self) -> memoryview: return self._buffer().as_buffer() def data(self) -> memoryview: """ @@ -282,10 +307,9 @@ class Tensor(SimpleMathTrait): print(np.frombuffer(t.data(), dtype=np.int32)) ``` """ - assert self.dtype.base.fmt is not None, f"no fmt dtype for {self.dtype.base}" + if 0 in self.shape: return memoryview(bytearray(0)).cast(self.dtype.base.fmt) assert all_int(self.shape), f"no data if shape is symbolic, {self.shape=}" - if TYPE_CHECKING or sys.version_info < (3, 12): assert self.dtype.base.fmt != "e" - return cast(memoryview, self._data().cast(self.dtype.base.fmt) if 0 in self.shape else self._data().cast(self.dtype.base.fmt, self.shape)) + return self._buffer().as_typed_buffer(self.shape) def item(self) -> ConstType: """ @@ -299,16 +323,21 @@ class Tensor(SimpleMathTrait): assert self.numel() == 1, "must have one element for item" return self.data()[(0,) * len(self.shape)] - # TODO: should be Tensor.tolist() -> Union[list[ConstType], ConstType]. The List is Sequence because mypy expects memoryview.tolist() -> list[int] + # TODO: should be Tensor.tolist() -> Union[list[ConstType], ConstType]. The list is Sequence because mypy expects memoryview.tolist() -> list[int] # src: https://github.com/python/mypy/blob/release-1.6/mypy/typeshed/stdlib/builtins.pyi#L803 - def tolist(self) -> Union[Sequence[ConstType], ConstType]: + def tolist(self) -> Sequence[ConstType]|ConstType: """ Returns the value of this tensor as a nested list. + Returns single value for const tensor. ```python exec="true" source="above" session="tensor" result="python" t = Tensor([1, 2, 3, 4]) print(t.tolist()) ``` + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor(5) + print(t.tolist()) + ``` """ return self.data().tolist() @@ -321,22 +350,21 @@ class Tensor(SimpleMathTrait): print(repr(t.numpy())) ``` """ + assert all_int(self.shape), f"no data if shape is symbolic, {self.shape=}" import numpy as np if self.dtype.base == dtypes.bfloat16: return self.float().numpy() - assert _to_np_dtype(self.dtype.base) is not None, f"no np dtype for {self.dtype.base}" - assert all_int(self.shape), f"no data if shape is symbolic, {self.shape=}" - return np.frombuffer(self._data(), dtype=_to_np_dtype(self.dtype.base)).reshape(self.shape) + if 0 in self.shape: return np.empty(self.shape, dtype=_to_np_dtype(self.dtype.base)) + return self._buffer().numpy().reshape(self.shape) def clone(self) -> Tensor: """ - Creates a clone of this tensor allocating a seperate buffer for the data. + Creates a clone of this tensor allocating a separate buffer for the data. """ ret = Tensor(self.lazydata.clone(), self.device, requires_grad=self.requires_grad) if self.grad is not None: ret.grad = self.grad.clone() - if hasattr(self, '_ctx'): ret._ctx = self._ctx return ret - def to(self, device:Optional[Union[str, tuple[str, ...]]]) -> Tensor: + def to(self, device:str|tuple[str, ...]|None) -> Tensor: """ Moves the tensor to the given device. """ @@ -345,68 +373,48 @@ class Tensor(SimpleMathTrait): if not isinstance(device, str): return self.shard(device) ret = Tensor(self.lazydata, device, requires_grad=self.requires_grad) if self.grad is not None: ret.grad = self.grad.to(device) - if hasattr(self, '_ctx'): ret._ctx = self._ctx return ret - def to_(self, device:Optional[Union[str, tuple[str, ...]]]): + def to_(self, device:str|tuple[str, ...]|None) -> Tensor: """ Moves the tensor to the given device in place. """ real = self.to(device) - # TODO: is this assign? - if self.grad is not None and real.grad is not None: self.grad.lazydata = real.grad.lazydata - self.lazydata = real.lazydata + if self.grad is not None and real.grad is not None: self.grad.replace(real.grad) + return self.replace(real) - def shard(self, devices:tuple[str, ...], axis:Optional[int]=None, splits:Optional[tuple[int, ...]]=None) -> Tensor: + def shard(self, devices:tuple[str, ...], axis:int|None=None) -> Tensor: """ - Shards the tensor across the given devices. Optionally specify which axis to shard on, and how to split it across devices. + Shards the tensor across the given devices. Optionally specify which axis to shard on. ```python exec="true" source="above" session="tensor" result="python" - t = Tensor.empty(2, 3) - print(t.shard((t.device, t.device), axis=1, splits=(2, 1)).lazydata) + t = Tensor.empty(2, 4) + print(t.shard((t.device, t.device), axis=1).lazydata) ``` - """ - assert isinstance(self.lazydata, UOp), "can't shard a MultiLazyBuffer" - devices, bounds = tuple(Device.canonicalize(x) for x in devices), None - if axis is not None: - axis = self._resolve_dim(axis) - if splits is None: - if not isinstance(total:=self.shape[axis], int): raise RuntimeError(f"cannot shard symbolic shape {self.shape=}, {axis=}") - sz = ceildiv(total, len(devices)) - splits = tuple([max(0, min(sz, total - sz*i)) for i in range(len(devices))]) - assert sum(splits) == self.shape[axis], "specified splits do not sum up to axis shape" - bounds = tuple(itertools.pairwise(itertools.accumulate(splits, initial=0))) - return Tensor(MultiLazyBuffer.from_sharded(self.lazydata, devices, axis, bounds), device=devices, requires_grad=self.requires_grad) + assert isinstance(self.device, str), "can't shard a MultiLazyBuffer" + devices = tuple(Device.canonicalize(x) for x in devices) + mlb = self.lazydata.shard(devices, self._resolve_dim(axis)) if axis is not None else self.lazydata.copy_to_device(devices) + return Tensor(mlb, device=devices, requires_grad=self.requires_grad) - def shard_(self, devices:tuple[str, ...], axis:Optional[int]=None, splits:Optional[tuple[int, ...]]=None): + def shard_(self, devices:tuple[str, ...], axis:int|None=None) -> Tensor: """ Shards the tensor across the given devices in place. """ - self.lazydata = self.shard(devices, axis, splits).lazydata - return self + return self.replace(self.shard(devices, axis)) @staticmethod def from_uop(y:UOp, **kwargs) -> Tensor: - if y.op is Ops.BIND: return Tensor(y, **kwargs, requires_grad=False) # this is the only UOp allowed in Tensor + if y.op is Ops.BIND: return Tensor(y, **kwargs, requires_grad=False) if y.op is Ops.CONST: return Tensor(y.arg, **kwargs, requires_grad=False) if y.op is Ops.MUL: return Tensor.from_uop(y.src[0]) * Tensor.from_uop(y.src[1]) if y.op is Ops.ADD: return Tensor.from_uop(y.src[0]) + Tensor.from_uop(y.src[1]) - if y.op is Ops.MAX: return Tensor.from_uop(y.src[0]).maximum(Tensor.from_uop(y.src[1])) raise RuntimeError(f"unhandled UOp {y}") # ***** creation entrypoint ***** @staticmethod - def _metaop(op, shape, device:Optional[Union[tuple[str, ...], str]]=None, dtype:Optional[DTypeLike]=None, arg=None, **kwargs): - dtype = to_dtype(dtype) if dtype is not None else dtypes.default_float - if isinstance(device, tuple): - return Tensor(MultiLazyBuffer([UOp.metaop(op, shape, dtype, Device.canonicalize(d), arg) for d in device], None), - device, dtype, **kwargs) - return Tensor(UOp.metaop(op, shape, dtype, Device.canonicalize(device), arg), device, dtype, **kwargs) - - @staticmethod - def empty(*shape, **kwargs): + def empty(*shape, device:str|tuple[str, ...]|None=None, dtype:DTypeLike|None=None, **kwargs) -> Tensor: """ Creates an empty tensor with the given shape. @@ -418,7 +426,11 @@ class Tensor(SimpleMathTrait): print(t.shape) ``` """ - return Tensor._metaop(Ops.EMPTY, argfix(*shape), **kwargs) + dtype, shape = to_dtype(dtype) if dtype is not None else dtypes.default_float, argfix(*shape) + if not isinstance(size:=prod([x.vmax if isinstance(x, UOp) else x for x in shape]), int): raise ValueError(f"size must be int {size}") + # TODO: add test for multidevice tensor + device = tuple(Device.canonicalize(d) for d in device) if isinstance(device, tuple) else Device.canonicalize(device) + return Tensor(UOp.new_buffer(device, size, dtype), device, dtype, **kwargs).reshape(shape) @staticmethod def from_blob(ptr:int, shape:tuple[int, ...], **kwargs) -> Tensor: @@ -429,10 +441,9 @@ class Tensor(SimpleMathTrait): You can pass in `dtype` and `device` keyword arguments to control the data type and device of the tensor. Additionally, all other keyword arguments are passed to the constructor of the tensor. """ - - r = Tensor._metaop(Ops.EMPTY, shape, **kwargs) - r.lazydata.buffer.allocate(external_ptr=ptr) - r.lazydata.buf_uop_view() + r = Tensor.empty(*shape, **kwargs) + assert isinstance(r.device, str) + cast(Buffer, r.lazydata.buffer).allocate(external_ptr=ptr) return r @staticmethod @@ -452,7 +463,7 @@ class Tensor(SimpleMathTrait): _device_seeds: dict[str, Tensor] = {} _device_rng_counters: dict[str, Tensor] = {} @staticmethod - def manual_seed(seed=0): + def manual_seed(seed=0) -> None: """ Sets the seed for random operations. @@ -470,14 +481,14 @@ class Tensor(SimpleMathTrait): Tensor._seed, Tensor._device_seeds, Tensor._device_rng_counters = seed, {}, {} @staticmethod - def _threefry_random_bits(key:Tensor, counts0:Tensor, counts1:Tensor): + def _threefry_random_bits(key:Tensor, counts0:Tensor, counts1:Tensor) -> Tensor: x = (counts1.cast(dtypes.uint64) << 32) | counts0.cast(dtypes.uint64) - x = F.Threefry.apply(x, (key[1]._broadcast_to(x.shape).cast(dtypes.uint64) << 32) | key[0]._broadcast_to(x.shape).cast(dtypes.uint64)) + x = x._apply_uop(UOp.threefry, (key[1]._broadcast_to(x.shape).cast(dtypes.uint64) << 32) | key[0]._broadcast_to(x.shape).cast(dtypes.uint64)) counts0, counts1 = (x & 0xffffffff).cast(dtypes.uint32), ((x >> 32) & 0xffffffff).cast(dtypes.uint32) return counts0.cat(counts1) @staticmethod - def rand(*shape, device:Optional[str]=None, dtype:Optional[DTypeLike]=None, contiguous:bool=True, **kwargs) -> Tensor: + def rand(*shape, device:str|None=None, dtype:DTypeLike|None=None, contiguous:bool=True, **kwargs) -> Tensor: """ Creates a tensor with the given shape, filled with random values from a uniform distribution over the interval `[0, 1)`. @@ -493,15 +504,12 @@ class Tensor(SimpleMathTrait): if not dtypes.is_float(dtype := to_dtype(dtype or dtypes.default_float)): raise ValueError(f"rand only supports float dtypes, got {dtype}") if not all_int(shape:=argfix(*shape)) or not all(s >= 0 for s in shape): raise ValueError(f"invalid input {shape=}") if device is not None and not isinstance(device, str): raise ValueError(f"rand only supports single device, got {device=}") - _device = device = Device.canonicalize(device) + device = Device.canonicalize(device) # if shape has 0, return zero tensor - if (numel := prod(shape)) == 0: return Tensor.zeros(shape, device=_device, dtype=dtype, **kwargs) + if (numel := prod(shape)) == 0: return Tensor.zeros(shape, device=device, dtype=dtype, **kwargs) num = ceildiv(numel * dtype.itemsize, 4) - # when using MOCKGPU and NV generate rand on CLANG - if getenv("MOCKGPU") and device.startswith("NV"): device = "CLANG" - # generate per device seeds and rng counter if we haven't seen this device yet if device not in Tensor._device_seeds: Tensor._device_seeds[device] = Tensor( @@ -524,12 +532,7 @@ class Tensor(SimpleMathTrait): one = Tensor.ones_like(bits, device=bits.device, dtype=dtype).bitcast(uint_dtype) bits = bits.rshift((dtype.itemsize * 8) - nmant).bitwise_or(one) # bitcast back to the original dtype and reshape - out = bits.bitcast(dtype)[:numel].sub(1).reshape(shape) - - # move back to the original device if we were using MOCKGPU - if getenv("MOCKGPU") and _device: out = out.to(_device) - - out.requires_grad = kwargs.get("requires_grad") + out = bits.bitcast(dtype)[:numel].sub(1).reshape(shape).requires_grad_(kwargs.get("requires_grad")) return out.contiguous() if contiguous else out # ***** creation helper functions ***** @@ -617,7 +620,7 @@ class Tensor(SimpleMathTrait): return (Tensor.full((output_len,), step, dtype=dtype, **kwargs)._cumalu(0, Ops.ADD) + (start - step)).cast(dtype) @staticmethod - def linspace(start:Union[int, float], stop:Union[int, float], steps:int, **kwargs) -> Tensor: + def linspace(start:int|float, stop:int|float, steps:int, **kwargs) -> Tensor: """ Returns a 1-D tensor of `steps` evenly spaced values from `start` to `stop`, inclusive. @@ -637,7 +640,7 @@ class Tensor(SimpleMathTrait): return (start + Tensor.arange(steps, **kwargs) * ((stop - start) / (steps - 1))).cast(dtype) @staticmethod - def eye(n:int, m:Optional[int]=None, **kwargs) -> Tensor: + def eye(n:int, m:int|None=None, **kwargs) -> Tensor: """ Returns a 2-D tensor with `n` rows and `m` columns, with ones on the diagonal and zeros elsewhere. @@ -712,18 +715,31 @@ class Tensor(SimpleMathTrait): ``` """ dtype = kwargs.pop("dtype", self.dtype) - if isinstance(self.device, tuple) and isinstance(self.lazydata, MultiLazyBuffer): + if isinstance(self.device, tuple): if kwargs.get("device") is not None: raise RuntimeError("cannot specify `device` on `rand_like` of a multi device tensor") - if self.lazydata.axis is None: return Tensor.rand(*self.shape, dtype=dtype, **kwargs).shard(self.device) - contiguous = kwargs.pop("contiguous", True) - rands = [Tensor.rand(*lb.shape, device=lb.device, dtype=dtype, contiguous=contiguous, **kwargs).lazydata for lb in self.lazydata.lbs] - return Tensor(MultiLazyBuffer(cast(list[UOp], rands), self.lazydata.axis), device=self.device, dtype=dtype, **kwargs) + return Tensor.rand(*self.shape, dtype=dtype, **kwargs).shard(self.device, self.lazydata.axis) return Tensor.rand(*self.shape, device=kwargs.pop("device", self.device), dtype=dtype, **kwargs) # ***** rng hlops ***** + def randn_like(self, dtype:DTypeLike|None=None, requires_grad:bool|None=None, **kwargs) -> Tensor: + """ + Creates a tensor with the same shape and sharding as `self`, filled with random values from a normal distribution with mean 0 and variance 1. + + You can pass in `dtype` and `device` keyword arguments to control the data type and device of the tensor. + Additionally, all other keyword arguments are passed to the constructor of the tensor. + + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor.ones(2, 3) + print(Tensor.randn_like(t).numpy()) + ``` + """ + src = self.stack(self).rand_like(**{**kwargs, "dtype": dtypes.float32}) + # https://en.wikipedia.org/wiki/Box%E2%80%93Muller_transform + return (src[0].mul(2*math.pi).cos().mul((1 - src[1]).log().mul(-2).sqrt()).cast(dtype or self.dtype)).requires_grad_(requires_grad) + @staticmethod - def randn(*shape, dtype:Optional[DTypeLike]=None, requires_grad:Optional[bool]=None, **kwargs) -> Tensor: + def randn(*shape, dtype:DTypeLike|None=None, requires_grad:bool|None=None, **kwargs) -> Tensor: """ Creates a tensor with the given shape, filled with random values from a normal distribution with mean `0` and standard deviation `1`. If `dtype` is not specified, the default type is used. @@ -736,9 +752,7 @@ class Tensor(SimpleMathTrait): print(Tensor.randn(2, 3).numpy()) ``` """ - # https://en.wikipedia.org/wiki/Box%E2%80%93Muller_transform - src = Tensor.rand((2, *argfix(*shape)), **{**kwargs, "dtype": dtypes.float32}) - return (src[0].mul(2*math.pi).cos().mul((1 - src[1]).log().mul(-2).sqrt()).cast(dtype or dtypes.default_float)).requires_grad_(requires_grad) + return Tensor.empty(*shape).randn_like(dtype=dtype, requires_grad=requires_grad) @staticmethod def randint(*shape, low=0, high=10, dtype=dtypes.int32, **kwargs) -> Tensor: @@ -760,7 +774,7 @@ class Tensor(SimpleMathTrait): return Tensor.uniform(*shape, low=low, high=high, dtype=dtype, **kwargs) @staticmethod - def normal(*shape, mean=0.0, std=1.0, requires_grad:Optional[bool]=None, **kwargs) -> Tensor: + def normal(*shape, mean=0.0, std=1.0, requires_grad:bool|None=None, **kwargs) -> Tensor: """ Creates a tensor with the given shape, filled with random values from a normal distribution with the given `mean` and standard deviation `std`. @@ -775,7 +789,7 @@ class Tensor(SimpleMathTrait): return ((std * Tensor.randn(*shape, **kwargs)) + mean).requires_grad_(requires_grad) @staticmethod - def uniform(*shape, low=0.0, high=1.0, dtype:Optional[DTypeLike]=None, requires_grad:Optional[bool]=None, **kwargs) -> Tensor: + def uniform(*shape, low=0.0, high=1.0, dtype:DTypeLike|None=None, requires_grad:bool|None=None, **kwargs) -> Tensor: """ Creates a tensor with the given shape, filled with random values from a uniform distribution over the interval `[low, high)`. @@ -855,6 +869,12 @@ class Tensor(SimpleMathTrait): std = math.sqrt(2.0 / (1 + a ** 2)) / math.sqrt(prod(argfix(*shape)[1:])) return Tensor.normal(*shape, mean=0.0, std=std, **kwargs) + @staticmethod + def randperm(n: int, *, device=None, dtype=dtypes.int32, **kwargs) -> Tensor: + r = Tensor.rand(n, device=device, **kwargs) + _, indices = r.sort() + return indices.cast(dtype) + def multinomial(self:Tensor, num_samples:int = 1, replacement:bool = False) -> Tensor: assert 1 <= self.ndim <= 2 and num_samples > 0, f"{self.ndim=} must be 1 or 2 dim, {num_samples=} must be positive" assert replacement or num_samples == 1, "no replacement only supports num_samples = 1" @@ -866,7 +886,7 @@ class Tensor(SimpleMathTrait): # ***** toposort and backward pass ***** - def gradient(self, *targets:Tensor, gradient:Optional[Tensor]=None) -> list[Tensor]: + def gradient(self, *targets:Tensor, gradient:Tensor|None=None, materialize_grads=False) -> list[Tensor]: """ Compute the gradient of the targets with respect to self. @@ -880,66 +900,45 @@ class Tensor(SimpleMathTrait): print(dy.tolist()) # dz/dy ``` """ - assert isinstance(self.lazydata, UOp), "multi isn't supported yet" - target_uops: list[UOp] = [x.lazydata for x in targets if isinstance(x.lazydata, UOp)] assert gradient is not None or self.shape == tuple(), "when no gradient is provided, backward must be called on a scalar tensor" - grads = compute_gradient(self.lazydata, self.lazydata.const_like(1) if gradient is None else cast(UOp, gradient.lazydata), target_uops) + if gradient is None: gradient = Tensor(1.0, dtype=self.dtype, device=self.device, requires_grad=False) + rets = [] + target_uops = [x.lazydata for x in targets] + grads = compute_gradient(self.lazydata, gradient.lazydata, set(target_uops)) ret = [] for x in target_uops: - if (y:=grads.get(x)) is None: raise RuntimeError(f"{x}\n\nnot found in\n\n{self.lazydata}") - ret.append(Tensor(y, device=x.device)) - return ret + if (y:=grads.get(x)) is None: + if materialize_grads: y = x.const_like(0) + else: raise RuntimeError(f"{x}\n\nnot found in\n\n{self.lazydata}") + ret.append(y) + rets.append(ret) + # create returned Tensors + return [Tensor(u, device=t.device) for t,u in zip(targets, rets[0])] - def _deepwalk(self): - def _walk(node, visited): - visited.add(node) - # if tensor is not leaf, reset grad - if (ctx := getattr(node, "_ctx", None)) is not None and len(ctx.parents) != 0: node.grad = None - if ctx: - for i in node._ctx.parents: - if i not in visited: yield from _walk(i, visited) - yield node - return list(_walk(self, set())) - - def backward(self, gradient:Optional[Tensor]=None, retain_graph:bool=False) -> Tensor: + def backward(self, gradient:Tensor|None=None) -> Tensor: """ Propagates the gradient of a tensor backwards through the computation graph. If the 'gradient' argument is not provided, the tensor must be a scalar, and the gradient is implicitly set to 1.0. - If 'retain_graph' is false, the graph used to compute the grads will be freed. Otherwise, it will be kept. Keeping it can increase memory usage. ```python exec="true" source="above" session="tensor" result="python" t = Tensor([1.0, 2.0, 3.0, 4.0], requires_grad=True) t.sum().backward() print(t.grad.numpy()) ``` """ - toposorted = self._deepwalk() - if gradient is None: - assert self.shape == tuple(), "when no gradient is provided, backward must be called on a scalar tensor" - # fill in the first grad with one. don't use Tensor.ones because we don't need contiguous - # this is "implicit gradient creation" - gradient = Tensor(1.0, dtype=self.dtype, device=self.device, requires_grad=False) - - assert self.shape == gradient.shape, f"grad shape must match tensor shape, {gradient.shape!r} != {self.shape!r}" - self.grad = gradient - for t0 in reversed(toposorted): - if t0.grad is None: raise RuntimeError(f"tensor {t0} has no grad") - token = _METADATA.set(dataclasses.replace(md, backward=True) if (md := t0._ctx.metadata) is not None else None) - grads = t0._ctx.backward(t0.grad.lazydata) - _METADATA.reset(token) - grads = [Tensor(g, device=self.device, requires_grad=False) if g is not None else None - for g in ([grads] if len(t0._ctx.parents) == 1 else grads)] - for t, g in zip(t0._ctx.parents, grads): - if g is not None and t.requires_grad: - assert g.shape == t.shape, f"grad shape must match tensor shape, {g.shape!r} != {t.shape!r}" - t.grad = g if t.grad is None else (t.grad + g) - if not retain_graph: del t0._ctx + all_uops = self.lazydata.toposort() + tensors_need_grad: list[Tensor] = [t for tref in all_tensors if (t:=tref()) is not None and \ + t.lazydata in all_uops and t.requires_grad and not Tensor.no_grad] + # clear contexts + for t,g in zip(tensors_need_grad, self.gradient(*tensors_need_grad, gradient=gradient, materialize_grads=True)): + assert g.shape == t.shape, f"grad shape must match tensor shape, {g.shape!r} != {t.shape!r}" + t.grad = g if t.grad is None else (t.grad + g) return self # ***** movement low level ops ***** - def view(self, *shape) -> Tensor: + def view(self, shape:tuple[sint, ...], *args) -> Tensor: """`.view` is an alias for `.reshape`.""" - return self.reshape(shape) + return self.reshape(argfix(shape, *args)) def reshape(self, shape, *args) -> Tensor: """ @@ -956,7 +955,7 @@ class Tensor(SimpleMathTrait): # resolve -1 if (c := new_shape.count(-1)) > 1: raise RuntimeError(f"only one dimension can be inferred using -1, getting {new_shape}") if c: new_shape = tuple([-prod(self.shape) // prod(new_shape) if s == -1 else s for s in new_shape]) - return F.Reshape.apply(self, shape=new_shape) if new_shape != self.shape else self + return self._apply_uop(UOp.reshape, arg=new_shape) if new_shape != self.shape else self def expand(self, shape, *args) -> Tensor: """ @@ -980,16 +979,16 @@ class Tensor(SimpleMathTrait): `order` can be passed as a tuple or as separate arguments. ```python exec="true" source="above" session="tensor" result="python" - t = Tensor.arange(6).reshape(2, 3) - print(t.numpy()) + t = Tensor.empty(2, 3, 5) + print(t.shape) ``` ```python exec="true" source="above" session="tensor" result="python" - print(t.permute(1, 0).numpy()) + print(t.permute(2, 0, 1).shape) ``` """ order_arg = tuple(self._resolve_dim(x) for x in argfix(order, *args)) if sorted(order_arg) != list(range(self.ndim)): raise RuntimeError(f"order is not a valid permutation, getting {order_arg}") - return F.Permute.apply(self, order=order_arg) + return self._apply_uop(UOp.permute, arg=order_arg) def flip(self, axis, *args) -> Tensor: """ @@ -1009,9 +1008,9 @@ class Tensor(SimpleMathTrait): """ axis_arg = tuple(self._resolve_dim(x) for x in argfix(axis, *args)) if len(axis_arg) != len(dedup(axis_arg)): raise RuntimeError(f"dim can appear at most once, getting {axis_arg}") - return F.Flip.apply(self, axis=axis_arg) + return self._apply_uop(UOp.flip, arg=tuple([i in axis_arg for i in range(len(self.shape))])) - def shrink(self, arg:tuple[Optional[tuple[sint, sint]], ...]) -> Tensor: + def shrink(self, arg:tuple[tuple[sint, sint]|None, ...]) -> Tensor: """ Returns a tensor that shrinks the each axis based on input arg. `arg` must have the same length as `self.ndim`. @@ -1029,21 +1028,22 @@ class Tensor(SimpleMathTrait): ``` """ if (shrink_arg:=[x if x is not None else (0,s) for x,s in zip(arg, self.shape)]) == [(0,s) for s in self.shape]: return self - return F.Shrink.apply(self, arg=tuple(shrink_arg)) + return self._apply_uop(UOp.shrink, arg=tuple(shrink_arg)) - def pad(self, padding:Union[Sequence[sint], Sequence[Optional[tuple[sint, sint]]]], mode:str="constant", value:float=0.0) -> Tensor: + def pad(self, padding:Sequence[sint]|Sequence[tuple[sint, sint]|None], mode:str="constant", value:float=0.0) -> Tensor: """ Returns a tensor with padding applied based on the input `padding`. + `padding` supports two padding structures: - 1. Flat padding: (padding_left, padding_right, padding_top, padding_bottom, ...) - - This structure matches PyTorch's pad. - - `padding` length must be even. + 1. Flat padding: `(padding_left, padding_right, padding_top, padding_bottom, ...)` + - This structure matches PyTorch's pad. + - `padding` length must be even. - 2. Group padding: (..., (padding_top, padding_bottom), (padding_left, padding_right)) - - This structure matches pad for jax, numpy, tensorflow and others. - - For each axis, padding can be `None`, meaning no padding, or a tuple `(start, end)`. - - `padding` must have the same length as `self.ndim`. + 2. Group padding: `(..., (padding_top, padding_bottom), (padding_left, padding_right))` + - This structure matches pad for JAX, NumPy, TensorFlow, and others. + - For each axis, padding can be `None`, meaning no padding, or a tuple `(start, end)`. + - `padding` must have the same length as `self.ndim`. Padding values can be negative, resulting in dimension shrinks that work similarly to Python negative slices. Padding modes is selected with `mode` which supports `constant`, `reflect` and `replicate`. @@ -1063,14 +1063,17 @@ class Tensor(SimpleMathTrait): ``` """ if mode not in {"constant", "reflect", "replicate", "circular"}: raise NotImplementedError(f"{mode=} is not supported") - if (flat:=all(isinstance(p, (int,UOp)) for p in padding)) and len(padding)%2 != 0: raise ValueError("Flat padding must have even number of pads") - # turn flat padding into group padding - pX = ((0,0),)*(self.ndim - len(padding)//2) + tuple(zip(padding[-2::-2], padding[::-2])) if flat else padding + # flat padding + if all(isinstance(p, (int,UOp)) for p in padding): + if len(padding)%2 != 0: raise ValueError("Flat padding must have even number of pads") + pX = _flat_to_grouped(tuple(cast(Sequence[sint], padding)) + (0,0)*(self.ndim - len(padding)//2)) + # group padding + else: pX = tuple((0,0) if p is None else p for p in cast(Sequence[tuple[sint, sint]|None], padding)) if len(pX) != self.ndim: raise ValueError(f"padding length is improper, {padding=} {self.ndim=}") - X, pX = self, cast(tuple[tuple[sint, sint]], tuple((0,0) if p is None else p for p in pX)) - pads = tuple((smax(pB,0), smax(pA,0)) for pB,pA in pX) + X, pads = self, tuple((smax(pB,0), smax(pA,0)) for pB,pA in pX) if mode == "constant": - def _constant(x,px,v): return F.Pad.apply(x, arg=px) if v == 0 else F.Pad.apply(x, arg=px) + F.Pad.apply(Tensor.ones_like(x), arg=px).where(0,v) + def _constant(x:Tensor,px,v) -> Tensor: + return x._apply_uop(UOp.pad, arg=px) if v == 0 else (x._apply_uop(UOp.pad, arg=px)+Tensor.ones_like(x)._apply_uop(UOp.pad, arg=px).where(0,v)) return _constant(X, pX, value) if all(resolve(p >= 0) for p in flatten(pX)) else \ _constant(X.shrink(tuple((-smin(pB,0),smin(pA+s,s)) for (pB,pA),s in zip(pX, X.shape))), pads, value) assert all_int(self.shape), f"does not support symbolic shape {self.shape}" @@ -1092,39 +1095,10 @@ class Tensor(SimpleMathTrait): # ***** movement high level ops ***** - # Supported Indexing Implementations: - # 1. Int indexing (no copy) - # - for all dims where there's int, shrink -> reshape - # - negative indices are taken relative to the end of the sequence, so X[-2] returns the 2nd-to-last element - # - X = Tensor.rand(4,5,9); X[2,-2] shrinks the Tensor to X.shrink(((2, 3), (3, 4), (0, 9))) -> X.shape=(1,1,9) - # - Then we reshape (collapse) the int dim away such that for X: (1,1,9) -> (9,) - # 2. Slice indexing (no copy) - # - for all dims where slice is start:end:stride, shrink -> Optional[flip] -> pad -> reshape -> shrink - # - first shrink the Tensor to X.shrink(((start, end),)) - # - then we apply stride through Optional[flip] -> pad -> reshape -> shrink - # - flip where dim value is negative - # - pad on dims to be multiple of strides, such that reshaping [dim_size_padded] -> [dim_size_padded // stride, stride] is possible - # - shrink [dim_size_padded // stride, stride] -> [dim_size_padded // stride, 1] - # - reshape [dim_size_padded // stride, 1] -> [dim_size_padded // stride] and now you have your stride - # 3. None indexing (no copy) - # - reshape (inject) a dim at the dim where there's None - # 4. Tensor indexing (copy) - # - use Tensor.arange == tensor_index to create masks for dims with Tensors (adds a dim for each mask) - # - combine masks together with mul - # - apply mask to self by mask * self - # - sum reduce away the extra dims added from creating masks - # Tiny Things: - # 1. Supported indices: Union[int, slice, Tensor, None, List, Tuple, Ellipsis] - # - for any list, list[Union[List, Tuple, int]], must have homogeneous shape - # - for any tuple, tuple[Union[List, Tuple, int]], must have homogeneous shape - # 2. Bool indexing is not supported - # 3. Out of bounds Tensor indexing results in 0 - # - e.g: Tensor([1, 2, 3])[Tensor([4, 3, 2])] -> [0, 0, 3] index 4 and 3 are out of bounds - def _getitem(self, indices, v: Optional[Tensor] = None) -> Tensor: + def _getitem(self, indices, v: Tensor|None = None) -> Tensor: # wrap single index into a list if (isinstance(indices, list) and all_int(indices)) or not isinstance(indices, (tuple, list)): indices = [indices] - # turn scalar Tensors into const val for int indexing if possible - x, indices = self, [self._to_const_val(i) if isinstance(i, Tensor) and i.shape == () else i for i in indices] + x, indices = self, list(indices) # filter ellipsis and fill with slice(None) or fill rest of indices with slice(None) if len(ellipsis_idx := [dim for dim, i in enumerate(indices) if i is Ellipsis]) > 1: raise IndexError("indices can only have a single ellipsis") @@ -1141,19 +1115,24 @@ class Tensor(SimpleMathTrait): case list() | tuple() | Tensor(): if not isinstance(index, Tensor): index = Tensor(index, self.device, requires_grad=False) if not dtypes.is_int(index.dtype): raise IndexError(f"index dtype {index.dtype} is not supported") - index = (index.to(self.device) < 0).where(size, 0) + index # treat negative index values + index = (index.to(self.device) < 0).where(index+size, index) # treat negative index values case int() | UOp(): # sint if index >= size or index < -size: raise IndexError(f"{index=} is out of bounds with {size=}") boundary = [index, index+1] if index >= 0 else [index+size, index+size+1] case slice(): if index.step == 0: raise ValueError(f"{index=} cannot have 0 as step") - if not all(isinstance(s,int) or s is None for s in (index.start,index.stop,index.step)): raise TypeError("only int slicing is supported") - # handle int slicing - *boundary, stride = index.indices(cast(SupportsIndex, size)) - if stride * (boundary[1] - boundary[0]) < 0: boundary = [0, 0] - elif stride < 0: boundary = [boundary[1] + 1, boundary[0] + 1] - # update size for slice - size = ceildiv((boundary[1] - boundary[0]), abs(stride)) + if all(isinstance(s, int) or s is None for s in (index.start,index.stop,index.step)): + # handle int slicing + *boundary, stride = index.indices(cast(SupportsIndex, size)) + if stride * (boundary[1] - boundary[0]) < 0: boundary = [0, 0] + elif stride < 0: boundary = [boundary[1] + 1, boundary[0] + 1] + # update size for slice + size = ceildiv((boundary[1] - boundary[0]), abs(stride)) + elif index.step is None and all(isinstance(s,(int,UOp))for s in (index.start,index.stop)) and resolve((index.stop-index.start) > 0, False): + # simple symbolic slice + boundary = [index.start, index.stop] + size = (index.stop - index.start).ssimplify() + else: raise TypeError(f"slice {index=} is not supported") case None: pass # do nothing case _: raise IndexError(f"{type(index).__name__} indexing is not supported") indices_parsed.append({"index":index, "size":size, "boundary":tuple(boundary), "stride":stride}) @@ -1168,13 +1147,13 @@ class Tensor(SimpleMathTrait): if any(abs(st) != 1 for st in strides): strides = tuple(abs(s) for s in strides) # pad shape to multiple of stride - if not all_int(x.shape): raise RuntimeError("symbolic shape not supprted") + if not all_int(x.shape): raise RuntimeError("symbolic shape not supported") x = x.pad(tuple((0, round_up(s, st) - s) for s, st in zip(x.shape, strides))) x = x.reshape(tuple(flatten((s // st, st) for s, st in zip(x.shape, strides)))) x = x.shrink(tuple(flatten(((0, s), (0, 1)) for s in x.shape[::2]))).reshape(x.shape[::2]) # dim injection from None by including None dim size (which is 1) and dim collapse by skipping int dim size - x = x.reshape(tuple(index['size'] for index in indices_parsed if not isinstance(index['index'], int))) + x = x.reshape(tuple(index['size'] for index in indices_parsed if not isinstance(index['index'], (int, UOp)))) # tensor indexing if tops := [(d,i) for d,i in enumerate(i_ for i_ in indices_parsed if not isinstance(i_['index'], int)) if isinstance(i['index'], Tensor)]: @@ -1194,7 +1173,7 @@ class Tensor(SimpleMathTrait): # inject 1's for the extra dims added in create masks reshape_arg = x.shape[:dims[0]] + (1,) * len(big_shape) + x.shape[dims[0]:] # sum reduce the extra dims introduced in create masks - x = (x.reshape(reshape_arg) * mask).sum(sum_axis:=tuple(d + len(big_shape) for d in dims), acc_dtype=x.dtype) + x = (x.reshape(reshape_arg) * mask).sum(sum_axis:=tuple(d + len(big_shape) for d in dims), dtype=x.dtype) # special permute case if dims[0] != 0 and len(dims) != 1 and tuple(dims) != tuple(range(dims[0], dims[-1]+1)): @@ -1211,16 +1190,53 @@ class Tensor(SimpleMathTrait): return x def __getitem__(self, indices) -> Tensor: + """ + Retrieve a sub-tensor using indexing. + + Supported Index Types: `int | slice | Tensor | None | list | tuple | Ellipsis` + + Examples: + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor.arange(12).reshape(3, 4) + print(t.numpy()) + ``` + + - Int Indexing: Select an element or sub-tensor using integers for each dimension. + ```python exec="true" source="above" session="tensor" result="python" + print(t[1, 2].numpy()) + ``` + + - Slice Indexing: Select a range of elements using slice notation (`start:end:stride`). + ```python exec="true" source="above" session="tensor" result="python" + print(t[0:2, ::2].numpy()) + ``` + + - Tensor Indexing: Use another tensor as indices for advanced indexing. Using `tuple` or `list` here also works. + ```python exec="true" source="above" session="tensor" result="python" + print(t[Tensor([2, 0, 1]), Tensor([1, 2, 3])].numpy()) + ``` + + - `None` Indexing: Add a new dimension to the tensor. + ```python exec="true" source="above" session="tensor" result="python" + print(t[:, None].shape) + ``` + + NOTE: Out-of-bounds indexing results in a value of `0`. + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor([1, 2, 3]) + print(t[Tensor([4, 3, 2])].numpy()) + ``` + """ return self._getitem(indices) - def __setitem__(self, indices, v:Union[Tensor, ConstType]) -> None: + def __setitem__(self, indices, v:Tensor|ConstType) -> None: if isinstance(self.device, str) and self.device.startswith("DISK"): - self._getitem(indices).assign(v) + self.realize()._getitem(indices).assign(v) return # NOTE: check that setitem target is valid first - if not all(unwrap(lb.st).contiguous for lb in self.lazydata.lbs): raise RuntimeError("setitem target needs to be contiguous") - if not isinstance(v, (Tensor, float, int, bool)): raise TypeError(f"can't set a {type(v).__name__} to a Tensor") - if not isinstance(v, Tensor): v = Tensor(v, device=self.device, dtype=self.dtype) + if not unwrap(self.lazydata.st).contiguous: raise RuntimeError("setitem target needs to be contiguous") + if isinstance(v, get_args(ConstType)): v = Tensor(v, device=self.device, dtype=self.dtype) + if not isinstance(v, Tensor): raise TypeError(f"can't set a {type(v).__name__} to a Tensor") if self.requires_grad or v.requires_grad: raise NotImplementedError("setitem with requires_grad is not supported") res = self.realize()._getitem(indices, v) @@ -1248,7 +1264,7 @@ class Tensor(SimpleMathTrait): assert all(s >= i for d,(s,i) in enumerate(zip(self.shape, index.shape)) if d != dim), "requires self.shape[d] >= index.shape[d] for all d != dim" index = index.to(self.device) x = self.shrink(tuple((0, i) if d != dim else None for d,i in enumerate(index.shape))).unsqueeze(-1).transpose(-1, dim) - return (x * index.unsqueeze(-1)._one_hot_along_dim(self.shape[dim])).sum(-1, acc_dtype=self.dtype) + return (x * index.unsqueeze(-1)._one_hot_along_dim(self.shape[dim])).sum(-1, dtype=self.dtype) def cat(self:Tensor, *args:Tensor, dim:int=0) -> Tensor: """ @@ -1285,7 +1301,7 @@ class Tensor(SimpleMathTrait): # checks for shapes and number of dimensions delegated to cat return Tensor.cat(*[t.unsqueeze(dim) for t in [self, *args]], dim=dim) - def repeat_interleave(self, repeats:int, dim:Optional[int]=None) -> Tensor: + def repeat_interleave(self, repeats:int, dim:int|None=None) -> Tensor: """ Repeat elements of a tensor. @@ -1323,7 +1339,7 @@ class Tensor(SimpleMathTrait): if not -max(1, total) <= dim <= max(1, total)-1: raise IndexError(f"{dim=} out of range {[-max(1, total), max(1, total)-1]}") return dim + total if dim < 0 else dim - def split(self, sizes:Union[int, list[int]], dim:int=0) -> tuple[Tensor, ...]: + def split(self, sizes:int|Sequence[int], dim:int=0) -> tuple[Tensor, ...]: """ Splits the tensor into chunks along the dimension specified by `dim`. If `sizes` is an integer, it splits into equally sized chunks if possible, otherwise the last chunk will be smaller. @@ -1372,7 +1388,7 @@ class Tensor(SimpleMathTrait): dim = self._resolve_dim(dim) return list(self.split(ceildiv(self.shape[dim], chunks) if self.shape[dim] else [0]*chunks, dim=dim)) - def meshgrid(self:Tensor, *args:Tensor, indexing:Union[Literal["ij"], Literal["xy"]]="ij") -> tuple[Tensor, ...]: + def meshgrid(self:Tensor, *args:Tensor, indexing:Literal["ij", "xy"]="ij") -> tuple[Tensor, ...]: """ Generates coordinate matrices from coordinate vectors. Input tensors can be scalars or 1D tensors. @@ -1399,7 +1415,7 @@ class Tensor(SimpleMathTrait): output_shape = _broadcast_shape(*(t.shape for t in tensors)) return tuple(t._broadcast_to(output_shape) for t in tensors) - def squeeze(self, dim:Optional[int]=None) -> Tensor: + def squeeze(self, dim:int|None=None) -> Tensor: """ Returns a tensor with specified dimensions of input of size 1 removed. If `dim` is not specified, all dimensions with size 1 are removed. @@ -1456,7 +1472,7 @@ class Tensor(SimpleMathTrait): order[dim0], order[dim1] = order[dim1], order[dim0] return self.permute(order) - def flatten(self, start_dim=0, end_dim=-1): + def flatten(self, start_dim=0, end_dim=-1) -> Tensor: """ Flattens the tensor by reshaping it into a one-dimensional tensor. If `start_dim` or `end_dim` are passed, only dimensions starting with `start_dim` and ending with `end_dim` are flattened. @@ -1472,7 +1488,7 @@ class Tensor(SimpleMathTrait): start_dim, end_dim = self._resolve_dim(start_dim), self._resolve_dim(end_dim) return self.reshape(self.shape[:start_dim] + (prod(self.shape[start_dim:end_dim+1]), ) + self.shape[end_dim+1:]) - def unflatten(self, dim:int, sizes:tuple[int,...]): + def unflatten(self, dim:int, sizes:tuple[int,...]) -> Tensor: """ Unflattens dimension `dim` of the tensor into multiple dimensions specified by `sizes`. `Tensor.flatten()` is the inverse of this function. @@ -1489,7 +1505,7 @@ class Tensor(SimpleMathTrait): dim = self._resolve_dim(dim) return self.reshape(self.shape[:dim] + sizes + self.shape[dim+1:]) - def roll(self, shifts:Union[int, tuple[int, ...]], dims:Union[int, tuple[int, ...]]) -> Tensor: + def roll(self, shifts:int|tuple[int, ...], dims:int|tuple[int, ...]) -> Tensor: """ Rolls the tensor along specified dimension(s). The rolling operation is circular, meaning that elements that go beyond the edge are wrapped around to the beginning of the dimension. @@ -1509,22 +1525,83 @@ class Tensor(SimpleMathTrait): rolled[tuple(slice(None) if i != dim else slice(None, -shift) for i in range(rolled.ndim))], dim=dim) return rolled + def rearrange(self, formula:str, **sizes) -> Tensor: + """ + Rearranges input according to formula + + See: https://einops.rocks/api/rearrange/ + + ```python exec="true" source="above" session="tensor" result="python" + x = Tensor([[1, 2], [3, 4]]) + print(Tensor.rearrange(x, "batch channel -> (batch channel)").numpy()) + ``` + """ + def parse_formula(formula: str): + tokens = f" {formula} ".replace("…", "...").replace("(", " ( ").replace(")", " ) ").replace(" ", " ").replace(" 1 ", " ( ) ").split() + lparens, rparens = map(lambda x: [i for i, ch in enumerate(tokens) if ch == x], ("(", ")")) + pairs = list(zip(lparens, rparens)) + assert len(lparens) == len(rparens) and sorted(flatten(pairs)) == flatten(pairs), "bracket mismatch" + return [name for name in tokens if name not in ("(", ")")], [(s - 2*i, e - 1 - 2*i) for i, (s, e) in enumerate(pairs)] + + assert formula.count("->") == 1, 'need exactly one "->" in formula' + + (lhs, unflatten_dims), (rhs, flatten_dims) = map(parse_formula, formula.split("->")) + + for name in sizes: assert name in lhs, f"axis {name} is not used in transform" + assert sorted(lhs) == sorted(rhs) and len(lhs) == len(set(lhs)), f"name mismatch in {formula}" + for name in flatten((lhs, rhs)): assert name == "..." or (name.isidentifier() and "_" not in (name[0], name[-1])), f"invalid axis name {name}" + assert "..." not in flatten([lhs[s:e] for s, e in unflatten_dims]), f"cannot have collapsed ellipsis (...) in lhs of {formula}" + assert lhs.count("...") <= 1, f"too many ellipses in {formula}" + + # resolve ellipsis + if "..." in lhs: ell_len = len(self.shape) - len(lhs) + 1 + sum(e - s - 1 for s, e in unflatten_dims) + lhs, rhs = map(lambda l: l[:(i:=l.index("..."))] + [f"...{j}" for j in range(ell_len)] + l[i + 1:] if "..." in l else l, (lhs, rhs)) + unflatten_dims = [(s + (ell_len - 1 if "...0" in lhs[:s] else 0), e + (ell_len - 1 if "...0" in lhs[:e] else 0)) for s, e in unflatten_dims] + flatten_dims = [(s + (ell_len - 1 if "...0" in rhs[:s] else 0), e + (ell_len - 1 if "...0" in rhs[:e] else 0)) for s, e in flatten_dims] + + # apply movement ops in order unflatten -> permute -> flatten/unsqueeze + t = functools.reduce(lambda x, dims: x.unflatten(dims[0], tuple(sizes.get(lhs[d], -1) for d in range(*dims))), unflatten_dims, self) + for i, name in enumerate(lhs): assert (name not in sizes) or sizes[name] == t.shape[i], f"size provided for dimension {name} incorrect" + t = t.permute([lhs.index(name) for name in rhs]) + return functools.reduce(lambda x, dims: x.flatten(dims[0], dims[1] - 1) if dims[0] Tensor: + def _reduce(self, op:Ops, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: axis = tuple(self._resolve_dim(x) for x in (range(self.ndim) if axis is None else make_tuple(axis, 1))) if self.ndim == 0: axis = () - ret = fxn.apply(self, axis=axis) + ret = self._apply_uop(UOp.r, op=op, axis=axis) return ret if keepdim else ret.reshape(tuple(s for i,s in enumerate(self.shape) if i not in axis)) - def sum(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False, acc_dtype:Optional[DTypeLike]=None): + def sum(self, axis:int|Sequence[int]|None=None, keepdim=False, dtype:DTypeLike|None=None) -> Tensor: """ Returns the sum of the elements of the tensor along the specified axis or axes. You can pass in `axis` and `keepdim` keyword arguments to control the axis along which the maximum is computed and whether the reduced dimensions are retained. - You can pass in `acc_dtype` keyword argument to control the data type of the accumulation. + You can pass in `dtype` keyword argument to control the data type of the accumulation. If not specified, the accumulation data type is chosen based on the input tensor's data type. ```python exec="true" source="above" session="tensor" result="python" @@ -1541,17 +1618,17 @@ class Tensor(SimpleMathTrait): print(t.sum(axis=1).numpy()) ``` """ - ret = self.cast(sum_acc_dtype(self.dtype) if acc_dtype is None else acc_dtype)._reduce(F.Sum, axis, keepdim) - return ret.cast(self.dtype) if acc_dtype is None and self.dtype in (dtypes.float16, dtypes.bfloat16) else ret + ret = self.cast(sum_acc_dtype(self.dtype) if dtype is None else dtype)._reduce(Ops.ADD, axis, keepdim) + return ret.cast(self.dtype) if dtype is None and self.dtype in (dtypes.float16, dtypes.bfloat16) else ret - def prod(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False, acc_dtype:Optional[DTypeLike]=None): + def prod(self, axis:int|Sequence[int]|None=None, keepdim=False, dtype:DTypeLike|None=None) -> Tensor: """ Returns the product of the elements of the tensor along the specified axis or axes. You can pass in `axis` and `keepdim` keyword arguments to control the axis along which the maximum is computed and whether the reduced dimensions are retained. - You can pass in `acc_dtype` keyword argument to control the data type of the accumulation. + You can pass in `dtype` keyword argument to control the data type of the accumulation. If not specified, the accumulation data type is chosen based on the input tensor's data type. ```python exec="true" source="above" session="tensor" result="python" @@ -1568,9 +1645,9 @@ class Tensor(SimpleMathTrait): print(t.prod(axis=1).numpy()) ``` """ - return self.cast(acc_dtype if acc_dtype is not None else self.dtype)._reduce(F.Prod, axis, keepdim) + return self.cast(dtype if dtype is not None else self.dtype)._reduce(Ops.MUL, axis, keepdim) - def max(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False): + def max(self, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: """ Returns the maximum value of the tensor along the specified axis or axes. @@ -1591,11 +1668,11 @@ class Tensor(SimpleMathTrait): print(t.max(axis=1, keepdim=True).numpy()) ``` """ - return self._reduce(F.Max, axis, keepdim) + return self._reduce(Ops.MAX, axis, keepdim) - def _inverse(self): return -self if self.is_floating_point() else ~self if dtypes.is_int(self.dtype) else self.logical_not() + def _inverse(self) -> Tensor: return -self if self.is_floating_point() else ~self if dtypes.is_int(self.dtype) else self.logical_not() - def min(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False): + def min(self, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: """ Returns the minimum value of the tensor along the specified axis or axes. @@ -1618,7 +1695,7 @@ class Tensor(SimpleMathTrait): """ return self._inverse().max(axis=axis, keepdim=keepdim)._inverse() - def any(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False): + def any(self, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: """ Tests if any element evaluates to `True` along the specified axis or axes. @@ -1640,7 +1717,7 @@ class Tensor(SimpleMathTrait): """ return self.bool().max(axis, keepdim) - def all(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False): + def all(self, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: """ Tests if all element evaluates to `True` along the specified axis or axes. @@ -1662,7 +1739,27 @@ class Tensor(SimpleMathTrait): """ return self.logical_not().any(axis, keepdim).logical_not() - def mean(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False): + def isclose(self, other:Tensor, rtol:float=1e-05, atol:float=1e-08, equal_nan=False) -> Tensor: + """ + Returns a new tensor with element-wise comparison of closeness to `other` within a tolerance. + + The `rtol` and `atol` keyword arguments control the relative and absolute tolerance of the comparison. + + By default, two `NaN` values are not close to each other. If `equal_nan` is `True`, two `NaN` values are considered close. + + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([1e-7, 1e-8, 1e-9, float('nan')]).isclose(Tensor([0.0, 0.0, 0.0, float('nan')])).numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([float('nan')]).isclose(Tensor([float('nan')]), equal_nan=True).numpy()) + ``` + """ + is_finite_close = self.isfinite() & other.isfinite() & ((self - other).abs() <= atol + rtol * other.abs()) + is_infinite_close = (self.isinf() | other.isinf()) & (self == other) + is_nan_close = (self.isnan() & other.isnan()) & equal_nan + return is_finite_close | is_infinite_close | is_nan_close + + def mean(self, axis:int|Sequence[int]|None=None, keepdim=False) -> Tensor: """ Returns the mean value of the tensor along the specified axis or axes. @@ -1686,9 +1783,10 @@ class Tensor(SimpleMathTrait): """ output_dtype = self.dtype if dtypes.is_float(self.dtype) else dtypes.float32 numerator = self.cast(sum_acc_dtype(self.dtype)).sum(axis=axis, keepdim=keepdim) - return numerator.div(prod([si for si, so in zip(self.shape, self.sum(axis=axis, keepdim=True).shape) if resolve(si != so)])).cast(output_dtype) + return numerator.div(prod([cast(int, si) for si, so in zip(self.shape, self.sum(axis=axis, keepdim=True).shape) if resolve(si != so)])) \ + .cast(output_dtype) - def var(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False, correction=1): + def var(self, axis:int|Sequence[int]|None=None, keepdim=False, correction=1) -> Tensor: """ Returns the variance of the tensor along the specified axis or axes. @@ -1714,7 +1812,24 @@ class Tensor(SimpleMathTrait): n = prod([si for si, so in zip(self.shape, squares.sum(axis=axis, keepdim=True).shape) if resolve(si != so)]) return squares.sum(axis=axis, keepdim=keepdim).div(smax([0, n-correction])) - def std(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False, correction=1): + def var_mean(self, axis:int|Sequence[int]|None=None, keepdim=False, correction=1) -> tuple[Tensor, Tensor]: + """ + Calculates the variance and mean over the dimensions specified by dim. + Syntactic sugar around `Tensor.var` and `Tensor.mean` to match `torch.var_mean`. + + ```python exec="true" source="above" session="tensor" result="python" + Tensor.manual_seed(42) + t = Tensor.normal(2, 3, mean=2.5, std=0.5) + print(t.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + var, mean = t.var_mean() + print(var.numpy(), mean.numpy()) + ``` + """ + return self.var(axis, keepdim, correction), self.mean(axis, keepdim) + + def std(self, axis:int|Sequence[int]|None=None, keepdim=False, correction=1) -> Tensor: """ Returns the standard deviation of the tensor along the specified axis or axes. @@ -1738,7 +1853,7 @@ class Tensor(SimpleMathTrait): """ return self.var(axis, keepdim, correction).sqrt() - def std_mean(self, axis:Optional[Union[int, Sequence[int]]]=None, keepdim=False, correction=1): + def std_mean(self, axis:int|Sequence[int]|None=None, keepdim=False, correction=1) -> tuple[Tensor, Tensor]: """ Calculates the standard deviation and mean over the dimensions specified by dim. Syntactic sugar around `Tensor.std` and `Tensor.mean` to match `torch.std_mean`. @@ -1755,13 +1870,13 @@ class Tensor(SimpleMathTrait): """ return self.std(axis, keepdim, correction), self.mean(axis, keepdim) - def _softmax(self, axis, dtype:Optional[DTypeLike]=None): - x = self.cast(dtype) if dtype is not None else self - m = x - x.max(axis=axis, keepdim=True).detach() + def _softmax(self, axis, dtype:DTypeLike|None=None) -> tuple[Tensor, Tensor, Tensor]: + m = self - self.max(axis=axis, keepdim=True).detach() + if dtype is not None: m = m.cast(dtype) e = m.exp() return m, e, e.sum(axis=axis, keepdim=True) - def softmax(self, axis=-1, dtype:Optional[DTypeLike]=None): + def softmax(self, axis=-1, dtype:DTypeLike|None=None, _single_kernel=getenv("SINGLE_KERNEL_SOFTMAX")) -> Tensor: """ Applies the softmax function to the tensor along the specified axis. @@ -1781,10 +1896,13 @@ class Tensor(SimpleMathTrait): print(t.softmax(axis=0).numpy()) ``` """ + if _single_kernel: + _, e, ss = self.contiguous()._softmax(axis, dtype) + return e.div(ss).fuse() _, e, ss = self._softmax(axis, dtype) return e.div(ss) - def log_softmax(self, axis=-1, dtype:Optional[DTypeLike]=None): + def log_softmax(self, axis=-1, dtype:DTypeLike|None=None) -> Tensor: """ Applies the log-softmax function to the tensor along the specified axis. @@ -1807,7 +1925,7 @@ class Tensor(SimpleMathTrait): m, _, ss = self._softmax(axis, dtype) return m - ss.log() - def logsumexp(self, axis=None, keepdim=False): + def logsumexp(self, axis=None, keepdim=False) -> Tensor: """ Computes the log-sum-exp of the tensor along the specified axis or axes. @@ -1834,7 +1952,7 @@ class Tensor(SimpleMathTrait): m = self.max(axis=axis, keepdim=True) return (self - m).exp().sum(axis=axis, keepdim=keepdim).log() + m.squeeze(axis) - def logcumsumexp(self, axis=0): + def logcumsumexp(self, axis=0) -> Tensor: """ Computes the log-cumsum-exp of the tensor along the specified axis or axes. @@ -1858,10 +1976,18 @@ class Tensor(SimpleMathTrait): print(t.logcumsumexp(axis=1).numpy()) ``` """ - m = self.max(axis=axis, keepdim=True) - return (self - m).exp().cumsum(axis=axis).log() + m + if self.ndim == 0: return self + axis = self._resolve_dim(axis) + x = self.transpose(axis, -1) + last_dim_size = x.shape[-1] + x_reshaped = x.reshape(-1, last_dim_size) + x_cummax = x_reshaped.cummax(-1).unsqueeze(-1) + x_expand = x_reshaped.unsqueeze(1).expand(*x_reshaped.shape, last_dim_size) + mask = Tensor.ones(last_dim_size, last_dim_size, requires_grad=False, device=self.device).tril().unsqueeze(0) + ret = ((x_expand - x_cummax).exp() * mask).sum(-1).log() + x_cummax.squeeze(-1) + return ret.reshape(*x.shape).transpose(-1, axis) - def argmax(self, axis=None, keepdim=False): + def argmax(self, axis=None, keepdim=False) -> Tensor: """ Returns the indices of the maximum value of the tensor along the specified axis. @@ -1888,7 +2014,7 @@ class Tensor(SimpleMathTrait): idx = m * Tensor.arange(self.shape[axis],0,-1, requires_grad=False, device=self.device).reshape(self.shape[axis], *[1]*(self.ndim-axis-1)) return (self.shape[axis]-idx.max(axis=axis, keepdim=keepdim)).cast(dtypes.int32) - def argmin(self, axis=None, keepdim=False): + def argmin(self, axis=None, keepdim=False) -> Tensor: """ Returns the indices of the minimum value of the tensor along the specified axis. @@ -1911,48 +2037,8 @@ class Tensor(SimpleMathTrait): """ return self._inverse().argmax(axis=axis, keepdim=keepdim) - def rearrange(self, formula: str, **sizes) -> Tensor: - """ - Rearranges input according to formula - - See: https://einops.rocks/api/rearrange/ - - ```python exec="true" source="above" session="tensor" result="python" - x = Tensor([[1, 2], [3, 4]]) - print(Tensor.rearrange(x, "batch channel -> (batch channel)).numpy()) - ``` - """ - def parse_formula(formula: str): - tokens = f" {formula} ".replace("…", "...").replace("(", " ( ").replace(")", " ) ").replace(" ", " ").replace(" 1 ", " ( ) ").split() - lparens, rparens = map(lambda x: [i for i, ch in enumerate(tokens) if ch == x], ("(", ")")) - pairs = list(zip(lparens, rparens)) - assert len(lparens) == len(rparens) and sorted(flatten(pairs)) == flatten(pairs), "bracket mismatch" - return [name for name in tokens if name not in ("(", ")")], [(s - 2*i, e - 1 - 2*i) for i, (s, e) in enumerate(pairs)] - - assert formula.count("->") == 1, 'need exactly one "->" in formula' - - (lhs, unflatten_dims), (rhs, flatten_dims) = map(parse_formula, formula.split("->")) - - for name in sizes: assert name in lhs, f"axis {name} is not used in transform" - assert sorted(lhs) == sorted(rhs) and len(lhs) == len(set(lhs)), f"name mismatch in {formula}" - for name in flatten((lhs, rhs)): assert name == "..." or (name.isidentifier() and "_" not in (name[0], name[-1])), f"invalid axis name {name}" - assert "..." not in flatten([lhs[s:e] for s, e in unflatten_dims]), f"cannot have collapsed ellipsis (...) in lhs of {formula}" - assert lhs.count("...") <= 1, f"too many ellipses in {formula}" - - # resolve ellipsis - if "..." in lhs: ell_len = len(self.shape) - len(lhs) + 1 + sum(e - s - 1 for s, e in unflatten_dims) - lhs, rhs = map(lambda l: l[:(i:=l.index("..."))] + [f"...{j}" for j in range(ell_len)] + l[i + 1:] if "..." in l else l, (lhs, rhs)) - unflatten_dims = [(s + (ell_len - 1 if "...0" in lhs[:s] else 0), e + (ell_len - 1 if "...0" in lhs[:e] else 0)) for s, e in unflatten_dims] - flatten_dims = [(s + (ell_len - 1 if "...0" in rhs[:s] else 0), e + (ell_len - 1 if "...0" in rhs[:e] else 0)) for s, e in flatten_dims] - - # apply movement ops in order unflatten -> permute -> flatten/unsqueeze - t = functools.reduce(lambda x, dims: x.unflatten(dims[0], tuple(sizes.get(lhs[d], -1) for d in range(*dims))), unflatten_dims, self) - for i, name in enumerate(lhs): assert (name not in sizes) or sizes[name] == t.shape[i], f"size provided for dimension {name} incorrect" - t = t.permute([lhs.index(name) for name in rhs]) - return functools.reduce(lambda x, dims: x.flatten(dims[0], dims[1] - 1) if dims[0] Tensor: + def einsum(formula:str, *operands:Tensor|Sequence[Tensor], dtype:DTypeLike|None=None) -> Tensor: """ Sums the product of the elements of the input tensors according to a formula based on the Einstein summation convention. @@ -1994,11 +2080,11 @@ class Tensor(SimpleMathTrait): # sum over all axes that's not in the output, then permute to the output order return functools.reduce(lambda a,b:a*b, xs_) \ - .sum(axis=[axis for axis,(letter,_) in enumerate(letter_val) if letter not in output], acc_dtype=acc_dtype).permute(rhs_order) + .sum(axis=[axis for axis,(letter,_) in enumerate(letter_val) if letter not in output], dtype=dtype).permute(rhs_order) # ***** processing ops ***** - def _pool(self, k_:tuple[sint, ...], stride:Union[tuple[int, ...], int]=1, dilation:Union[tuple[int, ...], int]=1) -> Tensor: + def _pool(self, k_:tuple[sint, ...], stride:int|tuple[int, ...]=1, dilation:int|tuple[int, ...]=1) -> Tensor: assert len(self.shape) >= len(k_), f"can't pool {self.shape} with {k_}" s_, d_ = make_tuple(stride, len(k_)), make_tuple(dilation, len(k_)) assert len(k_) == len(s_) == len(d_), f"stride/dilation mismatch kernel:{k_} stride:{s_} dilation:{d_}" @@ -2007,7 +2093,7 @@ class Tensor(SimpleMathTrait): o_ = [ceildiv(i-d*(k-1), s) for i,d,k,s in zip(i_,d_,k_,s_)] if any(resolve(k > s) for k,s in zip(k_,s_)) or any(d != 1 for d in d_): # input size scaling factor to make sure shrink for stride is possible - f_ = [1 + int(resolve(o*s > i+d)) for o,s,i,d in zip(o_,s_,i_,d_)] + f_ = [1 + int(resolve(o*s > (i - d*(k-1)))) for o,s,i,d,k in zip(o_,s_,i_,d_,k_)] # # repeats such that we don't need padding x = self.repeat([1]*len(noop) + [ceildiv(k*(i*f+d),i) for k,i,d,f in zip(k_,i_,d_,f_)]) # handle dilation @@ -2023,29 +2109,44 @@ class Tensor(SimpleMathTrait): x = x.shrink(tuple(noop + flatten(((0,o), (0,k)) for o,k in zip(o_,k_)))) return x.permute(*range(len(noop)), *[len(noop)+i*2 for i in range(len(i_))], *[len(noop)+i*2+1 for i in range(len(i_))]) - def _padding2d(self, padding:Union[int, Sequence[int]], dims:int) -> Sequence[int]: + def _resolve_pool_pads(self, padding:int|Sequence[int], dims:int) -> Sequence[int]: + if not isinstance(padding, int) and not (len(padding) == 2*dims or len(padding) == dims): + raise ValueError(f"Padding must be an int or a sequence of length {dims} or {2*dims}, but got {padding=} for {self.shape=} with {dims=}.") return [padding]*2*dims if isinstance(padding, int) else (padding if len(padding) == 2*dims else [p for p in padding for _ in range(2)][::-1]) - def _ceil_mode_padding2d(self,k_:tuple[sint, ...], s_:Union[tuple[int, ...], int], d_:Union[tuple[int, ...], int], - p_:Union[tuple[int, ...], int]) -> Sequence[int]: - (d_,s_,p_), i_ = (make_tuple(x, len(k_)) for x in (d_,s_,p_)), self.shape[-len(k_):] + def _apply_ceil_mode(self, pads:Sequence[int], k_:tuple[sint, ...], s_:int|tuple[int, ...], d_:int|tuple[int, ...]) -> list[int]: + (d_,s_), i_ = (make_tuple(x, len(k_)) for x in (d_,s_)), self.shape[-len(k_):] + pads, grouped_pads = list(pads), _flat_to_grouped(pads) # https://arxiv.org/pdf/1603.07285 section 5.1, relationship 15. - o_ = [ceildiv(i+2*p - (d*(k-1)+1), s) + 1 for i,d,k,s,p in zip(i_,d_,k_,s_,p_)] - pads = list(self._padding2d(p_, len(k_))) - # we have to do additional padding before `_pool` so that `o_` in `_pool` is calculated correctly - # `s*(o-1) + (d*(k-1)+1) - (i+2*p)` -> last_sliding_window_start + full_kernel_size - padded_input_shape - # we decrease padding in the case that a sliding window starts in the end padded region, thereby decreasing `o_` in `_pool` - # `smax(s*(o-1) - (p+i-1), 0)` -> last_sliding_window_start - (left_pad + input_size - zero_offset) - for dim,(o,i,s,p,k,d) in enumerate(zip(o_,i_,s_,p_,k_,d_)): pads[-1-dim*2] += s*(o-1) + (d*(k-1)+1) - (i+2*p) - smax(s*(o-1) - (p+i-1), 0) + o_ = [ceildiv(i+pB+pA - (d*(k-1)+1), s) + 1 for i,d,k,s,(pB,pA) in zip(i_,d_,k_,s_,grouped_pads)] + for dim,(o,i,s,k,d,(pB,pA)) in enumerate(zip(o_,i_,s_,k_,d_,grouped_pads)): + # we have to do additional padding before `_pool` so that `o_` in `_pool` is calculated correctly + # `s*(o-1) + (d*(k-1)+1) - (i+pB+pA)` -> last_sliding_window_start + full_kernel_size - padded_input_shape + # we decrease padding in the case that a sliding window starts in the end padded region, thereby decreasing `o_` in `_pool` + # `smax(s*(o-1) - (pB+i-1), 0)` -> last_sliding_window_start - (pad_before + input_size - zero_offset) + pads[-1-dim*2] += s*(o-1) + (d*(k-1)+1) - (i+pB+pA) - smax(s*(o-1) - (pB+i-1), 0) return pads # NOTE: these work for more than 2D - def avg_pool2d(self, kernel_size=(2,2), stride=None, dilation=1, padding=0, ceil_mode=False, count_include_pad=True): + def avg_pool2d(self, kernel_size:tuple[int, ...]=(2,2), stride=None, dilation=1, padding:int|tuple[int, ...]=0, + ceil_mode=False, count_include_pad=True) -> Tensor: """ Applies average pooling over a tensor. - When `ceil_mode` is set to True, output shape will be determined using ceil division. - When `count_include_pad` is set to False, zero padding will not be included in the averaging calculation. + This function supports three different types of `padding` + + 1. `int` (single value): + Applies the same padding value uniformly to all spatial dimensions. + + 2. `tuple[int, ...]` (length = number of spatial dimensions): + Specifies a distinct padding value for each spatial dimension in the form `(padding_height, padding_width, ...)`. + + 3. `tuple[int, ...]` (length = 2 * number of spatial dimensions): + Specifies explicit padding for each side of each spatial dimension in the form + `(padding_left, padding_right, padding_top, padding_bottom, ...)`. + + When `ceil_mode` is set to `True`, output shape will be determined using ceil division. + When `count_include_pad` is set to `False`, zero padding will not be included in the averaging calculation. NOTE: unlike PyTorch, this implementation is not limited to only 2d pooling and instead works for any number of dimensions. @@ -2066,19 +2167,34 @@ class Tensor(SimpleMathTrait): ``` """ axis = tuple(range(-len(k_ := make_tuple(kernel_size, 2)), 0)) - reg_pads, ceil_pads = self._padding2d(padding,len(k_)), self._ceil_mode_padding2d(k_, stride if stride is not None else k_, dilation, padding) def pool(x:Tensor, padding_:Sequence[int]) -> Tensor: return x.pad(padding_)._pool(k_, stride if stride is not None else k_, dilation) + reg_pads = self._resolve_pool_pads(padding, len(k_)) + ceil_pads = self._apply_ceil_mode(reg_pads, k_, stride if stride is not None else k_, dilation) if not count_include_pad: pads = ceil_pads if ceil_mode else reg_pads return pool(self, pads).sum(axis) / pool(self.ones_like(), pads).sum(axis) if not ceil_mode: return pool(self, reg_pads).mean(axis) return pool(self, ceil_pads).sum(axis) / pool(self.pad(reg_pads).ones_like(), tuple(cp-rp for cp,rp in zip(ceil_pads, reg_pads))).sum(axis) - def max_pool2d(self, kernel_size=(2,2), stride=None, dilation=1, padding=0, ceil_mode=False): + def max_pool2d(self, kernel_size:tuple[int, ...]=(2,2), stride=None, dilation=1, padding:int|tuple[int, ...]=0, + ceil_mode=False, return_indices=False) -> Tensor | tuple[Tensor, Tensor]: """ Applies max pooling over a tensor. - When `ceil_mode` is set to True, output shape will be determined using ceil division. + This function supports three different types of `padding` + + 1. `int` (single value): + Applies the same padding value uniformly to all spatial dimensions. + + 2. `tuple[int, ...]` (length = number of spatial dimensions): + Specifies a distinct padding value for each spatial dimension in the form `(padding_height, padding_width, ...)`. + + 3. `tuple[int, ...]` (length = 2 * number of spatial dimensions): + Specifies explicit padding for each side of each spatial dimension in the form + `(padding_left, padding_right, padding_top, padding_bottom, ...)`. + + When `ceil_mode` is set to `True`, output shape will be determined using ceil division. + When `return_indices` is set to `True`, the argmax will be returned along with the max values. NOTE: unlike PyTorch, this implementation is not limited to only 2d pooling and instead works for any number of dimensions. @@ -2095,15 +2211,65 @@ class Tensor(SimpleMathTrait): print(t.max_pool2d(padding=1).numpy()) ``` """ - k_ = make_tuple(kernel_size, 2) - pads = self._ceil_mode_padding2d(k_, stride if stride is not None else k_, dilation, padding) if ceil_mode else self._padding2d(padding, len(k_)) - return self.pad(pads, value=dtypes.min(self.dtype))._pool(k_, stride if stride is not None else k_, dilation).max(tuple(range(-len(k_), 0))) + axis = tuple(range(-len(k_ := make_tuple(kernel_size, 2)), 0)) + pads = self._resolve_pool_pads(padding, len(k_)) + if ceil_mode: pads = self._apply_ceil_mode(pads, k_, stride if stride is not None else k_, dilation) + pooled = self.pad(pads, value=dtypes.min(self.dtype))._pool(k_, stride if stride is not None else k_, dilation) + if not return_indices: return pooled.max(axis) + spatial_sz = math.prod(spatial_shape := self.shape[-len(k_):]) + idx = Tensor.arange(spatial_sz,0,-1, requires_grad=False, device=self.device).reshape(spatial_shape) + m = pooled == pooled.max(axis, keepdim=True) + idx = m * idx.pad(pads, value=dtypes.min(idx.dtype))._pool(k_, stride if stride is not None else k_, dilation) + return pooled.max(axis), spatial_sz - idx.max(axis) + + def max_unpool2d(self, indices:Tensor, kernel_size:tuple[int, ...]=(2,2), stride=None, dilation=1, padding:int|tuple[int, ...]=0, output_size=None): + """ + Performs a partial inverse of `max_pool2d` using the indices from the argmax. + + When `output_size` is provided, the output shape disambiguates to the provided shape. + + NOTE: unlike PyTorch, this implementation is not limited to only 2d pooling and instead works for any number of dimensions. + + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor.arange(1, 17).reshape(1, 1, 4, 4) + print(t.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + output, indices = Tensor.max_pool2d(t, return_indices=True) + print(output.numpy()) + print(indices.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor.max_unpool2d(output, indices).numpy()) + ``` + """ + bs,c,*spatial_shape = self.shape + if output_size is None: + k_,d_,s_ = (make_tuple(x, len(spatial_shape)) for x in (kernel_size, dilation, stride if stride is not None else kernel_size)) + p_ = _flat_to_grouped(self._resolve_pool_pads(padding, len(spatial_shape))) + # https://arxiv.org/pdf/1603.07285 inverse of relationship 15 in section 5.1. + output_size = tuple((i-1)*s - (pB+pA) + (d*(k-1)+1) for i,k,d,s,(pA,pB) in zip(spatial_shape,k_,d_,s_,p_)) + else: output_size = output_size[-len(spatial_shape):] + ret = (indices.reshape(bs,c,1,-1)._one_hot_along_dim(prod(output_size), 2) * self.reshape(bs,c,1,-1)).sum(3) + return ret.reshape(bs,c,*output_size) - def conv2d(self, weight:Tensor, bias:Optional[Tensor]=None, groups=1, stride=1, dilation=1, padding:int|tuple[int, ...]=0, - acc_dtype:Optional[DTypeLike]=None) -> Tensor: + def conv2d(self, weight:Tensor, bias:Tensor|None=None, groups=1, stride=1, dilation=1, padding:int|tuple[int, ...]=0, + dtype:DTypeLike|None=None) -> Tensor: """ Applies a convolution over a tensor with a given `weight` and optional `bias`. + This function supports three different types of `padding` + + 1. `int` (single value): + Applies the same padding value uniformly to all spatial dimensions. + + 2. `tuple[int, ...]` (length = number of spatial dimensions): + Specifies a distinct padding value for each spatial dimension in the form `(padding_height, padding_width, ...)`. + + 3. `tuple[int, ...]` (length = 2 * number of spatial dimensions): + Specifies explicit padding for each side of each spatial dimension in the form + `(padding_left, padding_right, padding_top, padding_bottom, ...)`. + NOTE: unlike PyTorch, this implementation is not limited to only 2d convolutions and instead works for any number of dimensions. See: https://pytorch.org/docs/stable/generated/torch.nn.Conv2d.html @@ -2114,11 +2280,10 @@ class Tensor(SimpleMathTrait): print(t.conv2d(w).numpy()) ``` """ - if IMAGE: return self.image_conv2d(weight, bias, groups, stride, dilation, padding, acc_dtype) + if IMAGE: return self.image_conv2d(weight, bias, groups, stride, dilation, padding, dtype) (bs,cin_), (cout,cin), HW = self.shape[:2], weight.shape[:2], weight.shape[2:] + padding_ = self._resolve_pool_pads(padding, len(HW)) assert groups*cin == cin_ and len(self.shape) == len(weight.shape), f"Input Tensor shape {self.shape} does not match the shape of the weights {weight.shape}. ({groups*cin} vs. {cin_})" # noqa: E501 - if isinstance(padding, (tuple,list)): assert len(padding) == 2*len(HW) or len(padding) == len(HW), f"Expected padding of length {2*len(HW)} or {len(HW)}, but got {len(padding)} for tensor of shape {self.shape}" # noqa: E501 - padding_ = self._padding2d(padding, len(HW)) # conv2d is a pooling op (with padding) x = self.pad(padding_)._pool(HW, stride, dilation) # (bs, groups*cin, oy, ox, H, W) @@ -2128,7 +2293,7 @@ class Tensor(SimpleMathTrait): x = x.reshape(bs, groups, cin, 1, *oyx, *HW).expand(bs, groups, cin, rcout, *oyx, *HW).permute(0,1,3,*[4+i for i in range(len(oyx))],2,*[4+len(oyx)+i for i in range(len(HW))]) # noqa: E501 # conv! broadcasted to (bs, groups, rcout, *oyx, cin, *HW) - ret = (x * weight.reshape(1, groups, rcout, *[1] * len(oyx), cin, *HW)).sum([-1-i for i in range(1+len(oyx))], keepdim=True, acc_dtype=acc_dtype).reshape(bs, cout, *oyx) # noqa: E501 + ret = (x * weight.reshape(1, groups, rcout, *[1] * len(oyx), cin, *HW)).sum([-1-i for i in range(1+len(oyx))], keepdim=True, dtype=dtype).reshape(bs, cout, *oyx) # noqa: E501 return ret if bias is None else ret.add(bias.reshape(1, -1, *[1] * len(HW))) HWI, HWO = (6,) * len(HW), (4,) * len(HW) # F(4x4,3x3) winograd tiles @@ -2136,7 +2301,7 @@ class Tensor(SimpleMathTrait): winograd_Bt = [[4, 0, -5, 0, 1, 0], [0, -4, -4, 1, 1, 0], [0, 4, -4, -1, 1, 0], [0, -2, -1, 2, 1, 0], [0, 2, -1, -2, 1, 0], [0, 4, 0, -5, 0, 1]] winograd_At = [[1, 1, 1, 1, 1, 0], [0, 1, -1, 2, -2, 0], [0, 1, 1, 4, 4, 0], [0, 1, -1, 8, -8, 1]] # applying At in pre-order doubles compile time - # todo: stride == dilation + # TODO: stride == dilation # use padding to round up to 4x4 output tiles # (bs, cin_, tyx, HWI) d = self.pad(sum([[padding_[i*2], padding_[i*2+1] + (-(dim + sum(padding_[i * 2:(i + 1) * 2]) - 2) % 4)] for i, dim in enumerate(self.shape[-len(HW):])], []))._pool(HWI, HWO) # noqa: E501 @@ -2153,7 +2318,7 @@ class Tensor(SimpleMathTrait): dfactors = _apply_winograd_matrix(winograd_Bt, d, len(HW)).reshape(*HWI, bs, groups, 1, cin, *tyx) # matmul; sum across cin: (HWI, bs, groups, rcout, *tyx); then HWI -> HWO: (HWO, bs, groups, rcout, *tyx) - ret = _apply_winograd_matrix(winograd_At, (gfactors * dfactors).sum(axis=-1-len(HW), acc_dtype=acc_dtype), len(HW)) + ret = _apply_winograd_matrix(winograd_At, (gfactors * dfactors).sum(axis=-1-len(HW), dtype=dtype), len(HW)) # interleave tyx and HWO: (bs, groups, rcout, oy, HO, ox, WO) ret = ret.permute([*range(len(HW), len(ret.shape)-len(HW)), *[i+o for i in range(len(HW)) for o in [len(ret.shape)-len(HW),0]]]) @@ -2162,10 +2327,22 @@ class Tensor(SimpleMathTrait): return (ret if bias is None else ret.add(bias.reshape(1, -1, *[1 for _ in range(len(HW))]))).contiguous().contiguous_backward() - def conv_transpose2d(self, weight:Tensor, bias:Optional[Tensor]=None, groups=1, stride=1, dilation=1, padding=0, output_padding=0) -> Tensor: + def conv_transpose2d(self, weight:Tensor, bias:Tensor|None=None, groups=1, stride=1, dilation=1, padding=0, output_padding=0) -> Tensor: """ Applies a transposed convolution over a tensor with a given `weight` and optional `bias`. + This function supports three different types of `padding` + + 1. `int` (single value): + Applies the same padding value uniformly to all spatial dimensions. + + 2. `tuple[int, ...]` (length = number of spatial dimensions): + Specifies a distinct padding value for each spatial dimension in the form `(padding_height, padding_width, ...)`. + + 3. `tuple[int, ...]` (length = 2 * number of spatial dimensions): + Specifies explicit padding for each side of each spatial dimension in the form + `(padding_left, padding_right, padding_top, padding_bottom, ...)`. + NOTE: unlike PyTorch, this implementation is not limited to only 2d transposed convolutions and instead works for any number of dimensions. See: https://pytorch.org/docs/stable/generated/torch.nn.ConvTranspose2d.html @@ -2178,24 +2355,25 @@ class Tensor(SimpleMathTrait): """ x, w = self, weight.unflatten(0, (groups, -1)).transpose(1, 2).flip(*range(3, len(weight.shape)+1)) HW = weight.shape[2:] - stride, dilation, padding, output_padding = [make_tuple(x, len(HW)) for x in (stride, dilation, padding, output_padding)] + padding = _flat_to_grouped(self._resolve_pool_pads(padding, len(HW))) + stride, dilation, output_padding = [make_tuple(x, len(HW)) for x in (stride, dilation, output_padding)] if any(s>1 for s in stride): # handle strides: (k) -> reshape -> (k,1) -> pad -> (k,s) -> reshape -> (k*s) -> shrink (k-(s-1)) x = x.reshape(None, None, *flatten((k,1) for k in x.shape[2:])) x = x.pad((None, None, *flatten((None,(0,s-1)) for s in stride))) x = x.reshape(None, None, *[k*s for k,s in zip(x.shape[2::2], stride)]) x = x.shrink((None, None, *[(0,k-(s-1)) for k,s in zip(x.shape[2:], stride)])) - padding = flatten((((k-1)*d-p,(k-1)*d-p+op) for k,d,p,op in reversed(list(zip(HW, dilation, padding, output_padding))))) + padding = flatten((((k-1)*d-pB,(k-1)*d-pA+op) for k,d,(pB,pA),op in reversed(list(zip(HW, dilation, padding, output_padding))))) return x.conv2d(w.flatten(end_dim=1), groups=groups, bias=bias, dilation=dilation, padding=padding) - def dot(self, w:Tensor, acc_dtype:Optional[DTypeLike]=None) -> Tensor: + def dot(self, w:Tensor, dtype:DTypeLike|None=None) -> Tensor: """ Performs dot product between two tensors. If `w` is 1-D, it's a sum product over the last axis of `self` and `w`. If `w` is N-D with N>=2, it's a sum product over the last axis of `self` and the second-to-last axis of `w`. - You can pass in the optional `acc_dtype` keyword argument to control the data type of the accumulation. + You can pass in the optional `dtype` keyword argument to control the data type of the accumulation. ```python exec="true" source="above" session="tensor" result="python" a = Tensor([1, 2, 3]) @@ -2208,20 +2386,20 @@ class Tensor(SimpleMathTrait): print(a.dot(b).numpy()) ``` """ - if IMAGE: return self.image_dot(w, acc_dtype) + if IMAGE: return self.image_dot(w, dtype) x, dx, dw = self, self.ndim, w.ndim if not (dx > 0 and dw > 0): raise RuntimeError(f"both tensors need to be at least 1D, got {dx}D and {dw}D") if x.shape[-1] != w.shape[axis_w:=-min(w.ndim,2)]: raise RuntimeError(f"cannot dot {x.shape} and {w.shape}") x = x.reshape(*x.shape[0:-1], *[1]*min(dx-1, dw-1, 1), x.shape[-1]) w = w.reshape(*w.shape[0:-2], *[1]*min(dx-1, dw-1, 1), *w.shape[axis_w:]).transpose(-1, axis_w) - return (x*w).sum(-1, acc_dtype=acc_dtype).cast(least_upper_dtype(x.dtype, w.dtype) if acc_dtype is None else acc_dtype) + return (x*w).sum(-1, dtype=dtype).cast(least_upper_dtype(x.dtype, w.dtype) if dtype is None else dtype) - def matmul(self, x:Tensor, reverse=False, acc_dtype:Optional[DTypeLike]=None) -> Tensor: + def matmul(self, x:Tensor, reverse=False, dtype:DTypeLike|None=None) -> Tensor: """ Performs matrix multiplication between two tensors. You can pass in the `reverse` keyword argument to control the order of the matrix multiplication. - You can pass in the optional `acc_dtype` keyword argument to control the data type of the accumulation. + You can pass in the optional `dtype` keyword argument to control the data type of the accumulation. ```python exec="true" source="above" session="tensor" result="python" a = Tensor([[1, 2], [3, 4]]) @@ -2229,26 +2407,26 @@ class Tensor(SimpleMathTrait): print(a.matmul(b).numpy()) ``` """ - return x.dot(self, acc_dtype=acc_dtype) if reverse else self.dot(x, acc_dtype=acc_dtype) + return x.dot(self, dtype=dtype) if reverse else self.dot(x, dtype=dtype) def _cumalu(self, axis:int, op:Ops, _include_initial=False) -> Tensor: - assert self.shape[axis] != 0 and op in (Ops.ADD, Ops.MAX) + assert self.shape[axis] != 0 and op in (Ops.ADD, Ops.MAX, Ops.MUL) pl_sz = self.shape[axis] - int(not _include_initial) pooled = self.transpose(axis,-1).pad((pl_sz, -int(_include_initial)), value=identity_element(op, self.dtype))._pool((self.shape[axis],)) - return (pooled.sum(-1) if op is Ops.ADD else pooled.max(-1)).transpose(axis,-1) + return {Ops.ADD: pooled.sum(-1), Ops.MAX: pooled.max(-1), Ops.MUL: pooled.prod(-1)}[op].transpose(axis, -1) def _split_cumalu(self, axis:int, op:Ops) -> Tensor: axis = self._resolve_dim(axis) if self.ndim == 0 or 0 in self.shape: return self - # TODO: someday the optimizer will find this on it's own + # TODO: someday the optimizer will find this on its own # for now this is a two stage cumsum SPLIT = 256 if not isinstance(s:=self.shape[axis], int) or s <= SPLIT*2: return self._cumalu(axis, op) ret = self.transpose(axis,-1).pad((round_up(s, SPLIT)-s, 0), value=identity_element(op, self.dtype)).unflatten(-1, (-1, SPLIT))._cumalu(-1, op) base = ret[..., -1]._cumalu(-1, op, _include_initial=True) base = base.unsqueeze(-1).expand(*base.shape, ret.shape[-1]) - def fix(x:Tensor): return x.flatten(start_dim=-2)[..., -s:].transpose(axis,-1) - return fix(ret) + fix(base) if op is Ops.ADD else fix(ret).maximum(fix(base)) + def fix(x: Tensor) -> Tensor: return x.flatten(start_dim=-2)[..., -s:].transpose(axis,-1) + return {Ops.ADD: Tensor.__add__, Ops.MAX: Tensor.maximum, Ops.MUL: Tensor.__mul__}[op](fix(ret), fix(base)) def cumsum(self, axis:int=0) -> Tensor: """ @@ -2264,6 +2442,20 @@ class Tensor(SimpleMathTrait): """ return self._split_cumalu(axis, Ops.ADD) + def cumprod(self, axis:int) -> Tensor: + """ + Computes the cumulative product of the elements of the tensor along the specified `axis`. + + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor.arange(1, 7).reshape(2, 3) + print(t.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(t.cumprod(axis=0).numpy()) + ``` + """ + return self._split_cumalu(axis, Ops.MUL) + def cummax(self, axis:int=0) -> Tensor: """ Computes the cumulative max of the tensor along the specified `axis`. @@ -2359,18 +2551,35 @@ class Tensor(SimpleMathTrait): reshape[i] = expand[i] = size[i] if mode == "linear": index = (scale*arr if align_corners else (scale*(arr+0.5))-0.5).clip(0, self.shape[i]-1) - low, high, perc = [y.reshape(reshape).expand(expand) for y in (index.floor(), index.ceil(), index - index.floor())] + low, high, perc = [y.reshape(reshape).expand(expand) for y in (index.floor().int(), index.ceil().int(), index - index.floor())] x = x.gather(i, low).lerp(x.gather(i, high), perc) else: index = (scale*(arr+0.5) if mode=="nearest-exact" else scale*arr).cast(dtypes.int32).reshape(reshape).expand(expand) x = x.gather(i, index) return x.cast(self.dtype) - def scatter(self, dim:int, index:Tensor, src:Union[Tensor, ConstType], reduce:Union[None, Literal['multiply'], Literal['add']]=None) -> Tensor: + def _pre_scatter(self, dim:int, index:Tensor, src:Tensor) -> tuple[Tensor, Tensor]: + index, dim = index.to(self.device), self._resolve_dim(dim) + assert index.ndim == self.ndim == src.ndim, f"self.ndim, index.ndim and src.dim must all equal, {self.ndim=} {index.ndim=} {src.ndim=}" + assert all((d == dim or self_ >= index_) and src_ >= index_ for d,(self_,index_,src_) in enumerate(zip(self.shape, index.shape, src.shape))), \ + f"All dimensions of {index.shape=} should be <= to all dimensions of {src.shape=} and all dimensions except dimension {dim} of {self.shape=}" + if self.dtype != src.dtype: raise RuntimeError(f"expect {self.dtype=} to be equal to {src.dtype=}") + # shrink src to index shape to shrink away the unused values + src = src.shrink(tuple((0,s) for s in index.shape)) + # prepare src and mask for reduce with respect to dim + src = src.unsqueeze(-1).expand(*src.shape, self.shape[dim]).transpose(-1, dim) + mask = index.unsqueeze(-1)._one_hot_along_dim(self.shape[dim]).transpose(-1, dim) + # pad src and mask to self.shape so that reduce can be done with padded values as no-ops + src, mask = (x.pad(tuple((0, self.shape[i] - x.shape[i]) if i != dim else None for i in range(self.ndim)) + (None,)) for x in (src, mask)) + return src, mask + + def scatter(self, dim:int, index:Tensor, src:Tensor|ConstType, reduce:Literal['multiply', 'add']|None=None) -> Tensor: """ Scatters `src` values along an axis specified by `dim`. Apply `add` or `multiply` reduction operation with `reduce`. + NOTE: To use the `reduce` argument with a Tensor `src`, see `Tensor.scatter_reduce`. + ```python exec="true" source="above" session="tensor" result="python" src = Tensor.arange(1, 11).reshape(2, 5) print(src.numpy()) @@ -2391,25 +2600,132 @@ class Tensor(SimpleMathTrait): ``` """ if reduce not in {None, "add", "multiply"}: raise TypeError(f"{reduce=} must be one of None, 'multiply', or 'add'") - index, dim = index.to(self.device), self._resolve_dim(dim) - src = src.cast(self.dtype) if isinstance(src, Tensor) else Tensor(src, device=self.device, dtype=self.dtype)._broadcast_to(index.shape) - assert index.ndim == self.ndim == src.ndim, f"self.ndim, index.ndim and src.dim must all equal, {self.ndim=} {index.ndim=} {src.ndim=}" - assert all((d == dim or self_ >= index_) and src_ >= index_ for d,(self_,index_,src_) in enumerate(zip(self.shape, index.shape, src.shape))), \ - f"All dimensions of {index.shape=} should be <= to all dimensions of {src.shape=} and all dimensions except dimension {dim} of {self.shape=}" - # shrink src to index shape to shrink away the unused values - src = src.shrink(tuple((0,s) for s in index.shape)) - # prepare src and mask for reduce with respect to dim - src = src.unsqueeze(-1).expand(*src.shape, self.shape[dim]).transpose(-1, dim) - mask = index.unsqueeze(-1)._one_hot_along_dim(self.shape[dim]).transpose(-1, dim) - # pad src and mask to self.shape so that reduce can be done with padded values as no-ops - src, mask = (x.pad(tuple((0, self.shape[i] - x.shape[i]) if i != dim else None for i in range(self.ndim)) + (None,)) for x in (src, mask)) - if reduce == "add": return mask.where(src, 0).sum(-1, acc_dtype=self.dtype) + self - if reduce == "multiply": return mask.where(src, 1).prod(-1, acc_dtype=self.dtype) * self + if reduce and isinstance(src, Tensor): raise TypeError("Tensor src is not supported with reduce arg. see scatter_reduce") + if not isinstance(src, Tensor): src = index.full_like(src, device=self.device, dtype=self.dtype) + if reduce == "add": return self.scatter_reduce(dim, index, src, "sum", include_self=True) + if reduce == "multiply": return self.scatter_reduce(dim, index, src, "prod", include_self=True) + src, mask = self._pre_scatter(dim, index, src) return _masked_setitem(self, src, mask, (-1,)) + def scatter_reduce(self, dim:int, index:Tensor, src:Tensor, reduce:Literal["sum", "prod", "mean", "amax", "amin"], + include_self:bool=True) -> Tensor: + """ + Scatters `src` values along an axis specified by `dim`. + Apply `"sum"`, `"prod"`, `"mean"`, `"amax"`, or `"amin"` reduction operations with `reduce`. + + Set `include_self=False` to exclude values in the `self` Tensor from the reduction. + + ```python exec="true" source="above" session="tensor" result="python" + src = Tensor.arange(1, 11).cast(dtypes.float).reshape(2, 5) + print(src.numpy()) + index = Tensor([[0, 0, 0, 0, 0], [0, 0, 0, 0, 0]]) + print(index.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor.ones(1, 5, dtype=src.dtype).scatter_reduce(0, index, src, reduce='sum').numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor.ones(1, 5, dtype=src.dtype).scatter_reduce(0, index, src, reduce='prod').numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor.ones(1, 5, dtype=src.dtype).scatter_reduce(0, index, src, reduce='mean', include_self=False).numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([[-10, 20, 0, 5, 10]], dtype=src.dtype).scatter_reduce(0, index, src, reduce='amax').numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([[-10, 20, 0, 5, 10]], dtype=src.dtype).scatter_reduce(0, index, src, reduce='amin').numpy()) + ``` + """ + src, mask = self._pre_scatter(dim, index, src) + def _inv_mask(a:Tensor|ConstType, b:Tensor|ConstType) -> Tensor: return mask.any(-1).logical_not().where(a, b) + # TODO: should not overwrite dtype here? + if reduce == "sum": return mask.where(src, 0).sum(-1, dtype=self.dtype).add(self if include_self else _inv_mask(self, 0)) + if reduce == "prod": return mask.where(src, 1).prod(-1, dtype=self.dtype).mul(self if include_self else _inv_mask(self, 1)) + if reduce == "amax": return mask.where(src, m := dtypes.min(src.dtype)).max(-1).maximum(self if include_self else _inv_mask(self, m)) + if reduce == "amin": return mask.where(src, m := dtypes.max(src.dtype)).min(-1).minimum(self if include_self else _inv_mask(self, m)) + if reduce == "mean": + count = mask.where(1, 0).sum(-1, dtype=self.dtype).add(1 if include_self else _inv_mask(1, 0)) + return mask.where(src, 0).sum(-1, dtype=self.dtype).add(self if include_self else _inv_mask(self, 0)).div(count) + raise RuntimeError(f"{reduce=} must be one of 'sum', 'prod', 'mean', 'amax', 'amin'") + + def sort(self, dim:int=-1, descending:bool=False) -> tuple[Tensor, Tensor]: + """ + Performs a bitonic sort on the tensor along the specified dimension. + + Order of indices for equivalent elements is always preserved. + + See: https://en.wikipedia.org/wiki/Bitonic_sorter + + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor([[0.1, 0.5, 1.2, 3.4, 2.1], [2.2, 1.9, 0.3, 4.5, 0.8]]) + print(t.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + sorted_values, indices = t.sort(dim=1, descending=True) + print(sorted_values.numpy()) + print(indices.numpy()) + ``` + """ + x, dim = self, self._resolve_dim(dim) + # pad to power of 2 + orig_len = x.shape[dim] + n_stages = math.ceil(math.log2(orig_len)) + fill_value = dtypes.min(x.dtype) if descending else dtypes.max(x.dtype) + pads = tuple((0, 2**n_stages - orig_len) if i == dim else None for i in range(x.ndim)) + x = x.pad(pads, value=fill_value).unflatten(dim, (2,)*n_stages) + # https://en.wikipedia.org/wiki/Bitonic_sorter#/media/File:BitonicSort1.svg + for stage in range(1, n_stages+1): + if stage != n_stages: + # flip so arrows of green boxes point the same way as blue boxes + crossover_dim = dim + n_stages - stage - 1 + blue_box, green_box = x.split(1, crossover_dim) + flip_dims = tuple(-i for i in range(1, stage+1+(self.ndim-dim))) + x = (blue_box.cat(green_box.flip(flip_dims), dim=crossover_dim)).contiguous() + for substage in range(stage-1, -1, -1): + partner_dim = dim + n_stages - substage - 1 + x_top, x_bottom = x.split(1, partner_dim) + x_larger, x_smaller = x_top.maximum(x_bottom), x_top.minimum(x_bottom) + x = (x_larger.cat(x_smaller, dim=partner_dim) if descending else x_smaller.cat(x_larger, dim=partner_dim)).contiguous() + if stage != n_stages: + # flip wires back to undo the crossover + blue_box, flipped_green_box = x.split(1, crossover_dim) + x = blue_box.cat(flipped_green_box.flip(flip_dims), dim=crossover_dim) + x = x.flatten(dim, dim+n_stages-1).shrink(tuple((0, orig_len) if i == dim else None for i in range(x.ndim))) + # compute indices for sorted values + idx = Tensor.arange(orig_len, requires_grad=False, device=self.device).reshape(tuple(orig_len if i == dim else 1 for i in range(x.ndim))) + idx = idx.expand(x.shape) + def compute_counts(t:Tensor): return ((idx.unsqueeze(dim) <= idx.unsqueeze(dim+1)) & (t.unsqueeze(dim) == t.unsqueeze(dim+1))).sum(dim+1) + count_orig, count_sorted = compute_counts(self), compute_counts(x) + cond = (self.unsqueeze(dim+1) == x.unsqueeze(dim)) & (count_orig.unsqueeze(dim+1) == count_sorted.unsqueeze(dim)) + idx = (cond * idx.unsqueeze(dim+1)).sum(dim) + return x, idx + + def topk(self, k:int, dim:int=-1, largest:bool=True, sorted_:bool=True) -> tuple[Tensor, Tensor]: + """ + Computes the top-k elements of the tensor along the specified `dim`. + + Order of indices for equivalent elements is always preserved. + + ```python exec="true" source="above" session="tensor" result="python" + t = Tensor([[0.1, 0.5, 1.2, 3.4, 2.1], [2.2, 1.9, 0.3, 4.5, 0.8]]) + print(t.numpy()) + ``` + ```python exec="true" source="above" session="tensor" result="python" + topk_values, topk_indices = t.topk(2, dim=1) + print(topk_values.numpy()) + print(topk_indices.numpy()) + ``` + """ + if not sorted_: raise NotImplementedError("topk with sorted_=False is not supported") + if k > self.shape[dim:=self._resolve_dim(dim)]: raise ValueError(f"selected index {k=} is out of range") + x, idx = self.sort(dim, descending=largest) + shrink_to_k = tuple((0, k) if i == dim else None for i in range(self.ndim)) + return x.shrink(shrink_to_k), idx.shrink(shrink_to_k) + # ***** unary ops ***** - def logical_not(self): + def logical_not(self) -> Tensor: """ Computes the logical NOT of the tensor element-wise. @@ -2417,8 +2733,9 @@ class Tensor(SimpleMathTrait): print(Tensor([False, True]).logical_not().numpy()) ``` """ - return F.Neq.apply(*self.cast(dtypes.bool)._broadcasted(True)) - def neg(self): + return self.cast(dtypes.bool)._apply_broadcasted_uop(UOp.ne, True) + + def neg(self) -> Tensor: """ Negates the tensor element-wise. @@ -2427,17 +2744,29 @@ class Tensor(SimpleMathTrait): ``` """ return self*-1 if self.dtype != dtypes.bool else self.logical_not() - def contiguous(self): + + def contiguous(self) -> Tensor: """ Returns a contiguous tensor. """ - return F.Contiguous.apply(self) - def contiguous_backward(self): + return self._apply_uop(UOp.contiguous) + + def fuse(self) -> Tensor: + """ + Make this a single kernel back to Ops.CONTIGUOUS on the inputs. + + Useful for single kernel softmax and flash attention. + Careful, this can break codegen or make kernels really slow. + """ + return self._apply_uop(UOp.fuse) + + def contiguous_backward(self) -> Tensor: """ Inserts a contiguous operation in the backward pass. """ - return F.ContiguousBackward.apply(self) - def log(self): + return self._apply_uop(UOp.contiguous_backward) + + def log(self) -> Tensor: """ Computes the natural logarithm element-wise. @@ -2447,8 +2776,9 @@ class Tensor(SimpleMathTrait): print(Tensor([1., 2., 4., 8.]).log().numpy()) ``` """ - return F.Log.apply(self.cast(least_upper_float(self.dtype))) - def log2(self): + return self.log2()*math.log(2) + + def log2(self) -> Tensor: """ Computes the base-2 logarithm element-wise. @@ -2458,8 +2788,9 @@ class Tensor(SimpleMathTrait): print(Tensor([1., 2., 4., 8.]).log2().numpy()) ``` """ - return self.log()/math.log(2) - def exp(self): + return self.cast(least_upper_float(self.dtype))._apply_uop(UOp.log2) + + def exp(self) -> Tensor: """ Computes the exponential function element-wise. @@ -2469,8 +2800,9 @@ class Tensor(SimpleMathTrait): print(Tensor([0., 1., 2., 3.]).exp().numpy()) ``` """ - return F.Exp.apply(self.cast(least_upper_float(self.dtype))) - def exp2(self): + return self.mul(1/math.log(2)).exp2() + + def exp2(self) -> Tensor: """ Computes the base-2 exponential function element-wise. @@ -2480,9 +2812,9 @@ class Tensor(SimpleMathTrait): print(Tensor([0., 1., 2., 3.]).exp2().numpy()) ``` """ - return F.Exp.apply(self*math.log(2)) + return self.cast(least_upper_float(self.dtype))._apply_uop(UOp.exp2) - def relu(self): + def relu(self) -> Tensor: """ Applies the Rectified Linear Unit (ReLU) function element-wise. @@ -2492,9 +2824,9 @@ class Tensor(SimpleMathTrait): print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).relu().numpy()) ``` """ - return F.Relu.apply(self) + return (self>0).where(self, 0) - def sigmoid(self): + def sigmoid(self) -> Tensor: """ Applies the Sigmoid function element-wise. @@ -2506,7 +2838,7 @@ class Tensor(SimpleMathTrait): """ return (1 + (self * (-1/math.log(2))).exp2()).reciprocal() - def hardsigmoid(self, alpha:float=1/6, beta:float=0.5): + def hardsigmoid(self, alpha:float=1/6, beta:float=0.5) -> Tensor: """ Applies the Hardsigmoid function element-wise. NOTE: default `alpha` and `beta` values is taken from torch @@ -2520,7 +2852,7 @@ class Tensor(SimpleMathTrait): """ return (alpha * self + beta).relu() - (alpha * self + beta - 1).relu() - def sqrt(self): + def sqrt(self) -> Tensor: """ Computes the square root of the tensor element-wise. @@ -2528,8 +2860,9 @@ class Tensor(SimpleMathTrait): print(Tensor([1., 2., 3., 4.]).sqrt().numpy()) ``` """ - return F.Sqrt.apply(self.cast(least_upper_float(self.dtype))) - def rsqrt(self): + return self.cast(least_upper_float(self.dtype))._apply_uop(UOp.sqrt) + + def rsqrt(self) -> Tensor: """ Computes the reciprocal of the square root of the tensor element-wise. @@ -2537,8 +2870,9 @@ class Tensor(SimpleMathTrait): print(Tensor([1., 2., 3., 4.]).rsqrt().numpy()) ``` """ - return self.reciprocal().sqrt() - def sin(self): + return self.sqrt().reciprocal() + + def sin(self) -> Tensor: """ Computes the sine of the tensor element-wise. @@ -2546,8 +2880,9 @@ class Tensor(SimpleMathTrait): print(Tensor([0., math.pi/2, math.pi, 3*math.pi/2, 2*math.pi]).sin().numpy()) ``` """ - return F.Sin.apply(self.cast(least_upper_float(self.dtype))) - def cos(self): + return self.cast(least_upper_float(self.dtype))._apply_uop(UOp.sin) + + def cos(self) -> Tensor: """ Computes the cosine of the tensor element-wise. @@ -2556,7 +2891,8 @@ class Tensor(SimpleMathTrait): ``` """ return ((math.pi/2)-self).sin() - def tan(self): + + def tan(self) -> Tensor: """ Computes the tangent of the tensor element-wise. @@ -2566,7 +2902,7 @@ class Tensor(SimpleMathTrait): """ return self.sin() / self.cos() - def asin(self): + def asin(self) -> Tensor: """ Computes the inverse sine (arcsine) of the tensor element-wise. @@ -2579,7 +2915,7 @@ class Tensor(SimpleMathTrait): x = math.pi / 2 - (1.0 - self.abs()).sqrt() * polyN(self.abs(), coefficients) return self.sign() * x - def acos(self): + def acos(self) -> Tensor: """ Computes the inverse cosine (arccosine) of the tensor element-wise. @@ -2589,7 +2925,7 @@ class Tensor(SimpleMathTrait): """ return math.pi / 2 - self.asin() - def atan(self): + def atan(self) -> Tensor: """ Computes the inverse tangent (arctan) of the tensor element-wise. @@ -2610,6 +2946,7 @@ class Tensor(SimpleMathTrait): ``` """ return self.cast(dtypes.int32).cast(self.dtype) + def ceil(self: Tensor) -> Tensor: """ Rounds the tensor element-wise towards positive infinity. @@ -2619,6 +2956,7 @@ class Tensor(SimpleMathTrait): ``` """ return (self > (b := self.trunc())).where(b+1, b) + def floor(self: Tensor) -> Tensor: """ Rounds the tensor element-wise towards negative infinity. @@ -2628,6 +2966,7 @@ class Tensor(SimpleMathTrait): ``` """ return (self < (b := self.trunc())).where(b-1, b) + def round(self: Tensor) -> Tensor: """ Rounds the tensor element-wise with rounding half to even. @@ -2638,7 +2977,7 @@ class Tensor(SimpleMathTrait): """ return ((self > 0) == ((b := self.cast(dtypes.int32) / 2.0).cast(dtypes.int32) == b)).where((self - 0.5).ceil(), (self + 0.5).floor()) - def isinf(self:Tensor, detect_positive:bool=True, detect_negative:bool=True): + def isinf(self:Tensor, detect_positive:bool=True, detect_negative:bool=True) -> Tensor: """ Checks the tensor element-wise to return True where the element is infinity, otherwise returns False @@ -2647,7 +2986,8 @@ class Tensor(SimpleMathTrait): ``` """ return (self == float("inf")) * detect_positive + (self == float("-inf")) * detect_negative - def isnan(self:Tensor): + + def isnan(self:Tensor) -> Tensor: """ Checks the tensor element-wise to return True where the element is NaN, otherwise returns False @@ -2657,7 +2997,17 @@ class Tensor(SimpleMathTrait): """ return self != self - def lerp(self, end: Tensor, weight: Union[Tensor, float]) -> Tensor: + def isfinite(self:Tensor) -> Tensor: + """ + Checks the tensor element-wise to return True where the element is finite, otherwise returns False + + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([1, float('inf'), 2, float('-inf'), float('nan')]).isfinite().numpy()) + ``` + """ + return (self.isinf()|self.isnan()).logical_not() + + def lerp(self, end:Tensor, weight:Tensor|float) -> Tensor: """ Linearly interpolates between `self` and `end` by `weight`. @@ -2670,7 +3020,7 @@ class Tensor(SimpleMathTrait): return (self+(((end - self).cast(dtypes.int8) * w_i + (1<> W_PREC)).cast(dtypes.uint8) return self + (end - self) * weight - def square(self): + def square(self) -> Tensor: """ Squares the tensor element-wise. Equivalent to `self*self`. @@ -2680,7 +3030,8 @@ class Tensor(SimpleMathTrait): ``` """ return self*self - def clamp(self, min_=None, max_=None): + + def clamp(self, min_=None, max_=None) -> Tensor: """ Clips (clamps) the values in the tensor between `min_` and `max_` element-wise. If `min_` is `None`, there is no lower bound. If `max_` is None, there is no upper bound. @@ -2692,12 +3043,14 @@ class Tensor(SimpleMathTrait): if min_ is None and max_ is None: raise RuntimeError("at least one of 'min_' or 'max_' must not be None") ret = self.maximum(min_) if min_ is not None else self return ret.minimum(max_) if max_ is not None else ret - def clip(self, min_=None, max_=None): + + def clip(self, min_=None, max_=None) -> Tensor: """ Alias for `Tensor.clamp`. """ return self.clamp(min_, max_) - def sign(self): + + def sign(self) -> Tensor: """ Returns the sign of the tensor element-wise. @@ -2705,8 +3058,9 @@ class Tensor(SimpleMathTrait): print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).sign().numpy()) ``` """ - return F.Sign.apply(self) - def abs(self): + return self.ne(0).where((self<0).where(self.full_like(-1), self.full_like(1)), self.full_like(0)) + self*0 + + def abs(self) -> Tensor: """ Computes the absolute value of the tensor element-wise. @@ -2715,7 +3069,8 @@ class Tensor(SimpleMathTrait): ``` """ return self * self.sign() - def reciprocal(self): + + def reciprocal(self) -> Tensor: """ Compute `1/x` element-wise. @@ -2723,11 +3078,11 @@ class Tensor(SimpleMathTrait): print(Tensor([1., 2., 3., 4.]).reciprocal().numpy()) ``` """ - return F.Reciprocal.apply(self.cast(least_upper_float(self.dtype))) + return self.cast(least_upper_float(self.dtype))._apply_uop(UOp.reciprocal) # ***** activation functions ***** - def elu(self, alpha=1.0): + def elu(self, alpha=1.0) -> Tensor: """ Applies the Exponential Linear Unit (ELU) function element-wise. @@ -2740,7 +3095,7 @@ class Tensor(SimpleMathTrait): """ return self.relu() - alpha*(1-self.exp()).relu() - def celu(self, alpha=1.0): + def celu(self, alpha=1.0) -> Tensor: """ Applies the Continuously differentiable Exponential Linear Unit (CELU) function element-wise. @@ -2753,7 +3108,7 @@ class Tensor(SimpleMathTrait): """ return self.maximum(0) + (alpha * ((self / alpha).exp() - 1)).minimum(0) - def selu(self, alpha=1.67326, gamma=1.0507): + def selu(self, alpha=1.67326, gamma=1.0507) -> Tensor: """ Applies the Scaled Exponential Linear Unit (SELU) function element-wise. @@ -2766,7 +3121,7 @@ class Tensor(SimpleMathTrait): """ return gamma * (self >= 0).detach().where(self, alpha * (self.exp() - 1)) - def swish(self): + def swish(self) -> Tensor: """ See `.silu()` @@ -2778,7 +3133,7 @@ class Tensor(SimpleMathTrait): """ return self * self.sigmoid() - def silu(self): + def silu(self) -> Tensor: """ Applies the Sigmoid Linear Unit (SiLU) function element-wise. @@ -2791,7 +3146,7 @@ class Tensor(SimpleMathTrait): """ return self.swish() # The SiLU function is also known as the swish function. - def relu6(self): + def relu6(self) -> Tensor: """ Applies the ReLU6 function element-wise. @@ -2804,7 +3159,7 @@ class Tensor(SimpleMathTrait): """ return self.relu() - (self-6).relu() - def hardswish(self): + def hardswish(self) -> Tensor: """ Applies the Hardswish function element-wise. @@ -2817,7 +3172,7 @@ class Tensor(SimpleMathTrait): """ return self * (self+3).relu6() * (1/6) - def tanh(self): + def tanh(self) -> Tensor: """ Applies the Hyperbolic Tangent (tanh) function element-wise. @@ -2829,7 +3184,7 @@ class Tensor(SimpleMathTrait): """ return 2.0 * ((2.0 * self).sigmoid()) - 1.0 - def sinh(self): + def sinh(self) -> Tensor: """ Applies the Hyperbolic Sine (sinh) function element-wise. @@ -2841,7 +3196,7 @@ class Tensor(SimpleMathTrait): """ return (self.exp() - self.neg().exp()) / 2 - def cosh(self): + def cosh(self) -> Tensor: """ Applies the Hyperbolic Cosine (cosh) function element-wise. @@ -2853,7 +3208,7 @@ class Tensor(SimpleMathTrait): """ return (self.exp() + self.neg().exp()) / 2 - def atanh(self): + def atanh(self) -> Tensor: """ Applies the Inverse Hyperbolic Tangent (atanh) function element-wise. @@ -2865,7 +3220,7 @@ class Tensor(SimpleMathTrait): """ return ((1 + self)/(1 - self)).log() / 2 - def asinh(self): + def asinh(self) -> Tensor: """ Applies the Inverse Hyperbolic Sine (asinh) function element-wise. @@ -2877,7 +3232,7 @@ class Tensor(SimpleMathTrait): """ return (self + (self.square() + 1).sqrt()).log() - def acosh(self): + def acosh(self) -> Tensor: """ Applies the Inverse Hyperbolic Cosine (acosh) function element-wise. @@ -2889,7 +3244,7 @@ class Tensor(SimpleMathTrait): """ return (self + (self.square() - 1).sqrt()).log() - def hardtanh(self, min_val=-1, max_val=1): + def hardtanh(self, min_val=-1, max_val=1) -> Tensor: """ Applies the Hardtanh function element-wise. @@ -2901,7 +3256,7 @@ class Tensor(SimpleMathTrait): """ return self.clip(min_val, max_val) - def erf(self): + def erf(self) -> Tensor: """ Applies error function element-wise. @@ -2915,7 +3270,7 @@ class Tensor(SimpleMathTrait): t = 1.0 / (1.0 + 0.3275911 * self.abs()) return self.sign() * (1.0 - t * polyN(t, [1.061405429, -1.453152027, 1.421413741, -0.284496736, 0.254829592]) * (-self.square()).exp()) - def gelu(self): + def gelu(self) -> Tensor: """ Applies the Gaussian Error Linear Unit (GELU) function element-wise. @@ -2928,7 +3283,7 @@ class Tensor(SimpleMathTrait): """ return 0.5 * self * (1 + (math.sqrt(2 / math.pi) * (self + 0.044715 * self ** 3)).tanh()) - def quick_gelu(self): + def quick_gelu(self) -> Tensor: """ Applies the Sigmoid GELU approximation element-wise. @@ -2940,22 +3295,22 @@ class Tensor(SimpleMathTrait): """ return self * (self * 1.702).sigmoid() - def leakyrelu(self, neg_slope=0.01): + def leaky_relu(self, neg_slope=0.01) -> Tensor: """ Applies the Leaky ReLU function element-wise. - Described: https://paperswithcode.com/method/leaky-relu ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).leakyrelu().numpy()) + print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).leaky_relu().numpy()) ``` ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).leakyrelu(neg_slope=0.42).numpy()) + print(Tensor([-3., -2., -1., 0., 1., 2., 3.]).leaky_relu(neg_slope=0.42).numpy()) ``` """ - return self.relu() - (-neg_slope*self).relu() + return (self<0).where(neg_slope*self, self) - def mish(self): + def mish(self) -> Tensor: """ Applies the Mish function element-wise. @@ -2968,7 +3323,7 @@ class Tensor(SimpleMathTrait): """ return self * self.softplus().tanh() - def softplus(self, beta=1): + def softplus(self, beta=1) -> Tensor: """ Applies the Softplus function element-wise. @@ -2980,7 +3335,7 @@ class Tensor(SimpleMathTrait): """ return (1/beta) * (1 + (self*beta).exp()).log() - def softsign(self): + def softsign(self) -> Tensor: """ Applies the Softsign function element-wise. @@ -3001,9 +3356,9 @@ class Tensor(SimpleMathTrait): # for each dimension, check either dim is 1, or it does not change if not all(resolve(s == ns) or resolve(s == 1) for s,ns in zip(shape, new_shape)): raise ValueError(f"cannot broadcast {self.shape} to {new_shape=}") - return F.Expand.apply(self.reshape(shape), shape=new_shape) + return self.reshape(shape)._apply_uop(UOp.expand, arg=new_shape) - def _broadcasted(self, y:Union[Tensor, UOp, ConstType], reverse:bool=False, match_dtype:bool=True) -> tuple[Tensor, Tensor]: + def _broadcasted(self, y:Tensor|ConstType|UOp, reverse:bool=False, match_dtype:bool=True) -> tuple[Tensor, Tensor]: x: Tensor = self if not isinstance(y, Tensor): # make y a Tensor @@ -3022,11 +3377,7 @@ class Tensor(SimpleMathTrait): # broadcast return x._broadcast_to(out_shape:=_broadcast_shape(x.shape, y.shape)), y._broadcast_to(out_shape) - def _to_const_val(self, x:Union[Tensor, ConstType]) -> Union[Tensor, ConstType]: - return x.lazydata.const_arg if isinstance(x, Tensor) and isinstance(x.lazydata, UOp) and x.lazydata.is_unrealized_unmasked_const() \ - and not x.requires_grad and self._broadcasted(x)[0].shape == self.shape else x - - def add(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def add(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Adds `self` and `x`. Equivalent to `self + x`. @@ -3044,9 +3395,9 @@ class Tensor(SimpleMathTrait): print(t.add(Tensor([[2.0], [3.5]])).numpy()) ``` """ - return F.Add.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.add, x, reverse) - def sub(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def sub(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Subtracts `x` from `self`. Equivalent to `self - x`. @@ -3067,7 +3418,7 @@ class Tensor(SimpleMathTrait): a, b = self._broadcasted(x, reverse) return a + (-b) - def mul(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def mul(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Multiplies `self` and `x`. Equivalent to `self * x`. @@ -3085,22 +3436,22 @@ class Tensor(SimpleMathTrait): print(t.mul(Tensor([[-1.0], [2.0]])).numpy()) ``` """ - return F.Mul.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.mul, x, reverse) - def idiv(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def idiv(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Divides `self` by `x`. Equivalent to `self // x`. Supports broadcasting to a common shape, type promotion, and integer inputs. - `idiv` performs integer division. + `idiv` performs integer division (truncate towards zero). ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([1, 4, 10]).idiv(Tensor([2, 3, 4])).numpy()) + print(Tensor([-4, 7, 5, 4, -7, 8]).idiv(Tensor([2, -3, 8, -2, 3, 5])).numpy()) ``` """ - return F.IDiv.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.idiv, x, reverse) - def div(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def div(self, x:Tensor|ConstType, reverse=False, rounding_mode:Literal["trunc", "floor"]|None=None) -> Tensor: """ Divides `self` by `x`. Equivalent to `self / x`. @@ -3120,27 +3471,45 @@ class Tensor(SimpleMathTrait): ``` """ numerator, denominator = self._broadcasted(x, reverse) - return numerator.cast(least_upper_float(numerator.dtype)) * denominator.cast(least_upper_float(denominator.dtype)).reciprocal() + d = numerator.cast(least_upper_float(numerator.dtype)) * denominator.cast(least_upper_float(denominator.dtype)).reciprocal() + output_dtype = numerator.dtype if dtypes.is_int(numerator.dtype) else d.dtype + if rounding_mode == "trunc": return d.trunc().cast(output_dtype) + if rounding_mode == "floor": return d.floor().cast(output_dtype) + if rounding_mode is not None: raise RuntimeError(f"{rounding_mode=} is not supported") + return d + + def mod(self, x:Tensor|ConstType, reverse=False) -> Tensor: + """ + Mod `self` by `x`. + Equivalent to `self % x`. + Supports broadcasting to a common shape, type promotion, and integer inputs. + + ```python exec="true" source="above" session="tensor" result="python" + print(Tensor([-4, 7, 5, 4, -7, 8]).mod(Tensor([2, -3, 8, -2, 3, 5])).numpy()) + ``` + """ + a, b = self._broadcasted(x, reverse) + return a - a.div(b, rounding_mode="floor") * b - def xor(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def bitwise_xor(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Computes bitwise xor of `self` and `x`. Equivalent to `self ^ x`. Supports broadcasting to a common shape, type promotion, and integer, boolean inputs. ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([-1, -2, 3]).xor(Tensor([1, 0, 3])).numpy()) + print(Tensor([-1, -2, 3]).bitwise_xor(Tensor([1, 0, 3])).numpy()) ``` ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([True, True, False, False]).xor(Tensor([True, False, True, False])).numpy()) + print(Tensor([True, True, False, False]).bitwise_xor(Tensor([True, False, True, False])).numpy()) ``` """ if self.dtype != dtypes.bool and not dtypes.is_int(self.dtype): raise RuntimeError(f"{self.dtype} is not supported") - return F.Xor.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.bitwise_xor, x, reverse) - def bitwise_and(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def bitwise_and(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ - Compute the bit-wise AND of `self` and `x`. + Compute the bitwise AND of `self` and `x`. Equivalent to `self & x`. Supports broadcasting to a common shape, type promotion, and integer, boolean inputs. ```python exec="true" source="above" session="tensor" result="python" @@ -3151,11 +3520,11 @@ class Tensor(SimpleMathTrait): ``` """ if self.dtype != dtypes.bool and not dtypes.is_int(self.dtype): raise RuntimeError(f"{self.dtype} is not supported") - return F.BitwiseAnd.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.bitwise_and, x, reverse) - def bitwise_or(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def bitwise_or(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ - Compute the bit-wise OR of `self` and `x`. + Compute the bitwise OR of `self` and `x`. Equivalent to `self | x`. Supports broadcasting to a common shape, type promotion, and integer, boolean inputs. ```python exec="true" source="above" session="tensor" result="python" @@ -3166,11 +3535,11 @@ class Tensor(SimpleMathTrait): ``` """ if self.dtype != dtypes.bool and not dtypes.is_int(self.dtype): raise RuntimeError(f"{self.dtype} is not supported") - return F.BitwiseOr.apply(*self._broadcasted(x, reverse)) + return self._apply_broadcasted_uop(UOp.bitwise_or, x, reverse) def bitwise_not(self) -> Tensor: """ - Compute the bit-wise NOT of `self`. + Compute the bitwise NOT of `self`. Equivalent to `~self`. ```python exec="true" source="above" session="tensor" result="python" print(Tensor([0, 2, 5, 255], dtype="int8").bitwise_not().numpy()) @@ -3182,7 +3551,7 @@ class Tensor(SimpleMathTrait): if self.dtype != dtypes.bool and not dtypes.is_int(self.dtype): raise RuntimeError(f"{self.dtype} is not supported") return self.logical_not() if self.dtype == dtypes.bool else self ^ -1 - def lshift(self, x:int): + def lshift(self, x:int) -> Tensor: """ Computes left arithmetic shift of `self` by `x` bits. `self` must have unsigned dtype. Equivalent to `self << x`. @@ -3194,7 +3563,7 @@ class Tensor(SimpleMathTrait): assert dtypes.is_unsigned(self.dtype) and isinstance(x, int) and x >= 0, f"not supported {self.dtype=} {x=}" return self.mul(2 ** x) - def rshift(self, x:int): + def rshift(self, x:int) -> Tensor: """ Computes right arithmetic shift of `self` by `x` bits. `self` must have unsigned dtype. Equivalent to `self >> x`. @@ -3206,47 +3575,30 @@ class Tensor(SimpleMathTrait): assert dtypes.is_unsigned(self.dtype) and isinstance(x, int) and x >= 0, f"not supported {self.dtype=} {x=}" return self.idiv(2 ** x) - def pow(self, x:Union[Tensor, ConstType], reverse=False) -> Tensor: + def pow(self, x:Tensor|ConstType, reverse=False) -> Tensor: """ Computes power of `self` with `x`. Equivalent to `self ** x`. ```python exec="true" source="above" session="tensor" result="python" - print(Tensor([-1, 2, 3]).pow(2).numpy()) + print(Tensor([-1, 2, 3]).pow(2.0).numpy()) ``` ```python exec="true" source="above" session="tensor" result="python" print(Tensor([-1, 2, 3]).pow(Tensor([-1.5, 0.5, 1.5])).numpy()) ``` ```python exec="true" source="above" session="tensor" result="python" - print((2 ** Tensor([-1, 2, 3])).numpy()) + print((2.0 ** Tensor([-1, 2, 3])).numpy()) ``` """ - x = self._to_const_val(x) - if not isinstance(x, Tensor) and not reverse: - # simple pow identities - if x < 0: return self.reciprocal().pow(-x).cast(self.dtype) - if x == 0: return 1 + self * 0 - # rewrite pow 0.5 to sqrt - if int(x - 0.5) + 0.5 == x: return self.pow(int(x - 0.5)) * self.sqrt() - if int(x) == x: return self.pow(x // 2).square() * (1 if x % 2 == 0 else self) - - # positive const ** self - if not isinstance(x, Tensor) and reverse and x > 0: return self.mul(math.log(x)).exp() - base, exponent = self._broadcasted(x, reverse=reverse) - # start with b ** e = exp(e * log(b)) - ret = base.abs().log().mul(exponent).exp() - # correct sign of negative base with odd exponent (cos has a period of 2pi so we use it here to get the oddness of the exponent) - negative_base = (base < 0).detach().where(1, 0) - # 1 for non-negative base or negative even exponent, -1 for negative odd exponent, don't care about non-integer exponent - correct_sign = 1 + negative_base * ((exponent * math.pi).cos() - 1) - # inject nan for negative base and non-integer exponent - inject_nan = (negative_base * (exponent != exponent.trunc())).detach().where(math.nan, 1) - # apply correct_sign inject_nan, and fix 0 ** 0 = 1 - ret = ((base == 0) * (exponent == 0)).detach().where(1, ret * correct_sign * inject_nan) + # TODO: int pow + if not base.is_floating_point(): raise RuntimeError("base needs to be float") + + # NOTE: pow(int, float) -> int + ret = base._apply_uop(UOp.pow, exponent) return ret.round().cast(self.dtype) if not dtypes.is_float(self.dtype) else ret - def maximum(self, x:Union[Tensor, ConstType]) -> Tensor: + def maximum(self, x:Tensor|ConstType) -> Tensor: """ Computes element-wise maximum of `self` and `x`. @@ -3257,11 +3609,9 @@ class Tensor(SimpleMathTrait): print(Tensor([-1, 2, 3]).maximum(Tensor([-4, -2, 9])).numpy()) ``` """ - # NOTE: the mid-point is for backward, revisit after new gradient API - if self.is_floating_point(): return (self Tensor: + def minimum(self, x:Tensor|ConstType) -> Tensor: """ Computes element-wise minimum of `self` and `x`. @@ -3275,7 +3625,7 @@ class Tensor(SimpleMathTrait): t, x = self._broadcasted(x) return t._inverse().maximum(x._inverse())._inverse() - def where(self:Tensor, x:Union[Tensor, ConstType, sint], y:Union[Tensor, ConstType, sint]): + def where(self:Tensor, x:Tensor|ConstType|sint, y:Tensor|ConstType|sint) -> Tensor: """ Return a tensor of elements selected from either `x` or `y`, depending on `self`. `output_i = x_i if self_i else y_i`. @@ -3297,16 +3647,25 @@ class Tensor(SimpleMathTrait): elif isinstance(y, Tensor): y, x = y._broadcasted(x) cond, x = self._broadcasted(x, match_dtype=False) cond, y = cond._broadcasted(y, match_dtype=False) - return F.Where.apply(cond.cast(dtypes.bool), *x._broadcasted(y)) + return cond.cast(dtypes.bool)._apply_uop(UOp.where, *x._broadcasted(y)) + + def masked_fill(self:Tensor, mask:Tensor, value:Tensor|ConstType) -> Tensor: return mask.where(value, self) - def masked_fill(self:Tensor, mask:Tensor, value:Union[Tensor, ConstType]): return mask.where(value, self) + def copysign(self, other) -> Tensor: + """ + Return a tensor of with the magnitude of `self` and the sign of `other`, elementwise. + """ + # NOTE: torch always return in float, we return based on the broadcasting rule. + other = self._broadcasted(other)[1] + # TODO: remove other*0? + return (other < 0).where(-self.abs(), self.abs()) + other*0 # ***** op wrappers ***** def __invert__(self) -> Tensor: return self.bitwise_not() - def __lshift__(self, x) -> Tensor: return self.lshift(x) - def __rshift__(self, x) -> Tensor: return self.rshift(x) + def __lshift__(self, x:int) -> Tensor: return self.lshift(x) + def __rshift__(self, x:int) -> Tensor: return self.rshift(x) def __pow__(self, x) -> Tensor: return self.pow(x) def __matmul__(self, x) -> Tensor: return self.matmul(x) @@ -3323,19 +3682,19 @@ class Tensor(SimpleMathTrait): def __imatmul__(self, x) -> Tensor: return self.assign(self.matmul(x)) def __iand__(self, x) -> Tensor: return self.assign(self.bitwise_and(x)) def __ior__(self, x) -> Tensor: return self.assign(self.bitwise_or(x)) - def __ixor__(self, x) -> Tensor: return self.assign(self.xor(x)) - def __ilshift__(self, x) -> Tensor: return self.assign(self.lshift(x)) - def __irshift__(self, x) -> Tensor: return self.assign(self.rshift(x)) + def __ixor__(self, x) -> Tensor: return self.assign(self.bitwise_xor(x)) + def __ilshift__(self, x:int) -> Tensor: return self.assign(self.lshift(x)) + def __irshift__(self, x:int) -> Tensor: return self.assign(self.rshift(x)) - def __lt__(self, x) -> Tensor: return F.Less.apply(*self._broadcasted(x, False)) - def __gt__(self, x) -> Tensor: return F.Less.apply(*self._broadcasted(x, True)) - def ne(self, x) -> Tensor: return F.Neq.apply(*self._broadcasted(x)) + def __lt__(self, x) -> Tensor: return self._apply_broadcasted_uop(UOp.__lt__, x, False) + def __gt__(self, x) -> Tensor: return self._apply_broadcasted_uop(UOp.__lt__, x, True) + def ne(self, x) -> Tensor: return self._apply_broadcasted_uop(UOp.ne, x, False) def __eq__(self, x) -> Tensor: return self.eq(x) # type: ignore[override] # ***** functional nn ops ***** - def linear(self, weight:Tensor, bias:Optional[Tensor]=None): + def linear(self, weight:Tensor, bias:Tensor|None=None, dtype:DTypeLike|None=None) -> Tensor: """ Applies a linear transformation to `self` using `weight` and `bias`. @@ -3348,10 +3707,11 @@ class Tensor(SimpleMathTrait): print(t.linear(weight, bias).numpy()) ``` """ + if dtype is not None: return self.cast(dtype).linear(weight.cast(dtype), bias.cast(dtype) if bias is not None else bias) x = self.mul(weight) if len(weight.shape) == 1 else self.dot(weight) return x.add(bias) if bias is not None else x - def sequential(self, ll:list[Callable[[Tensor], Tensor]]): + def sequential(self, ll:list[Callable[[Tensor], Tensor]]) -> Tensor: """ Applies a sequence of functions to `self` chaining the output of each function to the input of the next. @@ -3362,7 +3722,7 @@ class Tensor(SimpleMathTrait): """ return functools.reduce(lambda x,f: f(x), ll, self) - def layernorm(self, axis:Union[int,tuple[int,...]]=-1, eps:float=1e-5) -> Tensor: + def layernorm(self, axis:int|tuple[int,...]=-1, eps:float=1e-5) -> Tensor: """ Applies Layer Normalization over a mini-batch of inputs. @@ -3381,7 +3741,7 @@ class Tensor(SimpleMathTrait): y = (self - self.mean(axis, keepdim=True)) return y.mul((y*y).mean(axis, keepdim=True).add(eps).rsqrt()) - def batchnorm(self, weight:Optional[Tensor], bias:Optional[Tensor], mean:Tensor, invstd:Tensor, axis:Union[int,tuple[int,...]]=1) -> Tensor: + def batchnorm(self, weight:Tensor|None, bias:Tensor|None, mean:Tensor, invstd:Tensor, axis:int|tuple[int, ...]=1) -> Tensor: """ Applies Batch Normalization over a mini-batch of inputs. @@ -3424,7 +3784,8 @@ class Tensor(SimpleMathTrait): return (Tensor.rand_like(self, requires_grad=False, dtype=dtypes.default_float, contiguous=False) >= p).contiguous().where(self, 0) / (1.0 - p) # helper function commonly used for indexing - def _one_hot_along_dim(self:Tensor, num_classes:sint, dim:int=-1): + def _one_hot_along_dim(self:Tensor, num_classes:sint, dim:int=-1) -> Tensor: + if not dtypes.is_int(self.dtype): raise RuntimeError(f"_one_hot_along_dim expects int index tensor, getting {self.dtype}") offset = self.ndim - self._resolve_dim(dim) - 1 return self == Tensor.arange(num_classes, device=self.device, requires_grad=False).reshape((num_classes,) + (1,) * offset) @@ -3439,11 +3800,11 @@ class Tensor(SimpleMathTrait): print(t.one_hot(5).numpy()) ``` """ + if not dtypes.is_int(self.dtype): raise RuntimeError(f"expect integer dtype, getting {self.dtype=}") if num_classes == -1: num_classes = (self.max()+1).item() return self[..., None]._one_hot_along_dim(num_classes).where(1, 0) - def scaled_dot_product_attention(self, key:Tensor, value:Tensor, attn_mask:Optional[Tensor]=None, - dropout_p:float=0.0, is_causal:bool=False) -> Tensor: + def scaled_dot_product_attention(self, key:Tensor, value:Tensor, attn_mask:Tensor|None=None, dropout_p:float=0.0, is_causal:bool=False) -> Tensor: """ Computes scaled dot-product attention. `self` is the query tensor, `key` is the key tensor, and `value` is the value tensor. @@ -3460,10 +3821,15 @@ class Tensor(SimpleMathTrait): """ # NOTE: it also works when `key` and `value` have symbolic shape. assert all_int(self.shape), f"does not support symbolic shape {self.shape}" - if is_causal: attn_mask = Tensor.ones(self.shape[-2], key.shape[-2], requires_grad=False, device=self.device).tril(0).cast(dtypes.bool) - if attn_mask is not None and attn_mask.dtype == dtypes.bool: attn_mask = (attn_mask == 0).where(-float("inf"), 0) - qk = self.matmul(key.transpose(-2,-1), acc_dtype=least_upper_dtype(self.dtype, key.dtype, dtypes.float32)) / math.sqrt(self.shape[-1]) - return ((qk+attn_mask) if attn_mask is not None else qk).softmax(-1).cast(self.dtype).dropout(dropout_p) @ value + qk = self.matmul(key.transpose(-2,-1), dtype=least_upper_dtype(self.dtype, key.dtype, dtypes.float32)) / math.sqrt(self.shape[-1]) + # handle attention mask + if is_causal: + if attn_mask is not None: raise RuntimeError("cannot set attn_mask when is_causal=True") + attn_mask = qk.ones_like(requires_grad=False, device=self.device, dtype=dtypes.bool).tril() + if attn_mask is not None: + if attn_mask.dtype == dtypes.bool: attn_mask = attn_mask.where(0, -float("inf")) + qk = qk + attn_mask + return qk.cast(self.dtype).softmax(-1).dropout(dropout_p) @ value def _do_reduction(self, reduction:ReductionStr="mean") -> Tensor: if reduction not in get_args(ReductionStr): raise ValueError(f"{reduction=} must be one of {get_args(ReductionStr)}") @@ -3548,7 +3914,7 @@ class Tensor(SimpleMathTrait): ret = -self.log_softmax(axis=1).mul(Y).sum(axis=1) return ret._do_reduction(reduction) - def nll_loss(self, Y:Tensor, weight:Optional[Tensor]=None, ignore_index:Optional[int]=None, reduction:ReductionStr="mean") -> Tensor: + def nll_loss(self, Y:Tensor, weight:Tensor|None=None, ignore_index:int|None=None, reduction:ReductionStr="mean") -> Tensor: """ Compute the negative log likelihood loss between log-probabilities and target labels. @@ -3621,8 +3987,8 @@ class Tensor(SimpleMathTrait): def is_floating_point(self) -> bool: """ - Returns `True` if the tensor contains floating point types, i.e. is one of `dtype.float64`, `dtype.float32`, - `dtype.float16`, `dtype.bfloat16`. + Returns `True` if the tensor contains floating point types, i.e. is one of `dtypes.float64`, `dtypes.float32`, + `dtypes.float16`, `dtypes.bfloat16`. ```python exec="true" source="above" session="tensor" result="python" t = Tensor([8, 9], dtype=dtypes.float32) @@ -3631,7 +3997,7 @@ class Tensor(SimpleMathTrait): """ return dtypes.is_float(self.dtype) - def size(self, dim:Optional[int]=None) -> Union[sint, tuple[sint, ...]]: + def size(self, dim:int|None=None) -> sint|tuple[sint, ...]: """ Return the size of the tensor. If `dim` is specified, return the length along dimension `dim`. Otherwise return the shape of the tensor. @@ -3647,10 +4013,10 @@ class Tensor(SimpleMathTrait): # ***** cast ops ***** - def llvm_bf16_cast(self, dtype:DTypeLike): + def llvm_bf16_cast(self, dtype:DTypeLike) -> Tensor: # hack for devices that don't support bfloat16 assert self.dtype == dtypes.bfloat16 - return self.to("LLVM").bitcast(dtypes.uint16).cast(dtypes.uint32).mul(1<<16).bitcast(dtypes.float32).cast(dtype) + return self.to("LLVM").cast(dtype) def cast(self, dtype:DTypeLike) -> Tensor: """ @@ -3671,8 +4037,8 @@ class Tensor(SimpleMathTrait): """ if (dt:=to_dtype(dtype)) in {dtypes.uint8, dtypes.uint16} and dtypes.is_float(self.dtype): # NOTE: values within the int32 range and outside the unsigned dtype range will cause values to wrap around - return F.Cast.apply(F.Cast.apply(self, dtype=dtypes.int32), dtype=dt) - return self if self.dtype == dt else F.Cast.apply(self, dtype=dt) + return self._apply_uop(UOp.cast, dtype=dtypes.int32)._apply_uop(UOp.cast, dtype=dt) + return self if self.dtype == dt else self._apply_uop(UOp.cast, dtype=dt) def bitcast(self, dtype:DTypeLike) -> Tensor: """ @@ -3691,13 +4057,13 @@ class Tensor(SimpleMathTrait): """ if self.requires_grad: raise RuntimeError("can't backprop through bitcast") dt = to_dtype(dtype) - if (not isinstance(self.device, str) or not self.device.startswith("DISK")) and (ns:=dt.itemsize) != (os:=self.dtype.itemsize): - if (self.shape[-1]*os) % ns != 0: raise RuntimeError("unsupported size in bitcast") + if (ns:=dt.itemsize) != (os:=self.dtype.itemsize) and (self.shape[-1]*os) % ns != 0: raise RuntimeError("unsupported size in bitcast") + if (not isinstance(self.device, str) or not self.device.startswith("DISK")) and ns != os: new_uint, old_uint = to_dtype(f"uint{8*ns}"), to_dtype(f"uint{8*os}") tmp = self.bitcast(old_uint) if ns > os: return functools.reduce(Tensor.add, (tmp[..., i::ns//os].cast(new_uint) << 8*i*os for i in range(ns//os))).bitcast(dtype) return Tensor.stack(*(tmp>>8*i*ns for i in range(os//ns)), dim=-1).flatten(-2).cast(new_uint).bitcast(dtype) - return F.Cast.apply(self, dtype=dt, bitcast=True) if self.dtype != dt else self + return self._apply_uop(UOp.bitcast, dtype=dt) if self.dtype != dt else self def float(self) -> Tensor: """ @@ -3761,7 +4127,7 @@ class Tensor(SimpleMathTrait): # *** image Tensor function replacements *** - def image_dot(self, w:Tensor, acc_dtype:Optional[DTypeLike]=None) -> Tensor: + def image_dot(self, w:Tensor, dtype:DTypeLike|None=None) -> Tensor: # NOTE: we use a 1x1 conv2d to do the matmul. mxk @ kxn = (1,k,m,1).conv2d(n,k,1,1) x, dx, dw = self, self.ndim, w.ndim if not (dx > 0 and dw > 0): raise RuntimeError(f"both tensors need to be at least 1D, got {dx}D and {dw}D") @@ -3775,9 +4141,9 @@ class Tensor(SimpleMathTrait): cx = self.transpose(self.ndim-1, self.ndim-2).reshape((bs//groups, groups*cin, -1, 1)) # groups*cout x cin x H, W cw = w.transpose(w.ndim-1, w.ndim-2).reshape((groups*cout, cin, 1, 1)) - return cx.image_conv2d(cw, groups=groups, acc_dtype=acc_dtype).reshape(out_shape_t).transpose(self.ndim-1, self.ndim-2) + return cx.image_conv2d(cw, groups=groups, dtype=dtype).reshape(out_shape_t).transpose(self.ndim-1, self.ndim-2) - def image_conv2d(self, weight:Tensor, bias:Optional[Tensor]=None, groups=1, stride=1, dilation=1, padding=0, acc_dtype=None) -> Tensor: + def image_conv2d(self, weight:Tensor, bias:Tensor|None=None, groups=1, stride=1, dilation=1, padding=0, dtype=None) -> Tensor: base_image_type = dtypes.imageh if getenv("FLOAT16", 0) else dtypes.imagef (bs,_,iy,ix), (cout,cin,H,W) = self.shape, weight.shape @@ -3819,14 +4185,14 @@ class Tensor(SimpleMathTrait): else: w = w.reshape(cout//4, H, rcin_hi, W, rcin_lo, 4).permute(0,1,2,3,5,4) # prepare input - x = x.permute(0,3,4,5,1,2).pad(self._padding2d(padding, 2))._pool((H, W), stride, dilation) # -> (bs, groups, rcin_hi, rcin_lo, oy, ox, H, W) + x = x.permute(0,3,4,5,1,2).pad(self._resolve_pool_pads(padding,2))._pool((H,W), stride, dilation)# -> (bs, groups, rcin_hi, rcin_lo, oy, ox, H, W) x = x.permute(0,4,5,1,2,3,6,7).reshape(bs, (oy := x.shape[4]), (ox := x.shape[5]), *cout_expand[0:2], 1, 1, rcin_hi, rcin_lo, H, W) # prepare weights w = w.permute(0,4,2,5,1,3).reshape((1, 1, 1, *cout_expand, rcin_hi, rcin_lo, H, W)) # the conv! - ret = (x*w).cast(base_image_type((bs*oy, ox*cout//4, 4)) if IMAGE >= 2 else dtypes.float32).sum((-4, -3, -2, -1), acc_dtype=acc_dtype) + ret = (x*w).cast(base_image_type((bs*oy, ox*cout//4, 4)) if IMAGE >= 2 else dtypes.float32).sum((-4, -3, -2, -1), dtype=dtype) # undo hack for non multiples of 4 on C.rcout if added_output_channels != 0: @@ -3837,8 +4203,10 @@ class Tensor(SimpleMathTrait): ret = ret.reshape(bs, oy, ox, cout).permute(0,3,1,2) return ret if bias is None else ret.add(bias.reshape(1, -1, 1, 1)) -def _metadata_wrapper(fn): - def _wrapper(*args, **kwargs): +P = ParamSpec("P") +T = TypeVar("T") +def _metadata_wrapper(fn: Callable[P, T]) -> Callable[P, T]: + def _wrapper(*args: P.args, **kwargs: P.kwargs) -> T: if _METADATA.get() is not None: return fn(*args, **kwargs) if TRACEMETA >= 2: @@ -3871,5 +4239,5 @@ def _metadata_wrapper(fn): if TRACEMETA >= 1: for name, fn in inspect.getmembers(Tensor, inspect.isfunction): - if name in ["__class__", "__init__", "__new__", "__repr__", "backward", "sequential"]: continue + if name in ["__class__", "__init__", "__new__", "__repr__", "backward", "sequential", "gradient"]: continue setattr(Tensor, name, functools.wraps(fn)(_metadata_wrapper(fn))) diff --git a/tinygrad_repo/tinygrad/uop/__init__.py b/tinygrad_repo/tinygrad/uop/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/tinygrad_repo/tinygrad/uop/ops.py b/tinygrad_repo/tinygrad/uop/ops.py new file mode 100644 index 0000000000..dcee9d8f92 --- /dev/null +++ b/tinygrad_repo/tinygrad/uop/ops.py @@ -0,0 +1,1027 @@ +from __future__ import annotations +from typing import Any, Optional, Union, Callable, cast, TYPE_CHECKING, Type, get_args, Sequence +import sys, time, functools, itertools, math, operator, hashlib, os, types, pickle, pathlib, inspect, weakref +from enum import auto, IntEnum, Enum +from dataclasses import dataclass, field +from tinygrad.dtype import ConstType, ImageDType, dtypes, DType, truncate +from tinygrad.helpers import ContextVar, all_int, prod, getenv, all_same, Context, partition, temp, unwrap, T, argfix, Metadata, flatten +from tinygrad.helpers import PICKLE_BUFFERS, dedup, cdiv, cmod +if TYPE_CHECKING: + from tinygrad.shape.shapetracker import ShapeTracker + from tinygrad.device import Buffer, MultiBuffer + +# wrapper around IntEnum that preserves Enum.__str__ and makes auto() unique across all FastEnum subclasses +class FastEnum(IntEnum): + def __str__(self): return Enum.__str__(self) + @staticmethod + def _generate_next_value_(_, __, ___, last_values): return 1 + max([0, *last_values, *[max(c) for c in FastEnum.__subclasses__()]]) + +class SimpleMathTrait: + # required to implement + def alu(self:T, arg:Ops, *src) -> T: raise NotImplementedError + def const_like(self:T, b:ConstLike) -> T: raise NotImplementedError + + # great functions you get! + def ufix(self, x): return self.const_like(x) if not isinstance(x, MathTrait) else x + def _binop(self, op, x, reverse): return self.ufix(x).alu(op, self) if reverse else self.alu(op, self.ufix(x)) + def logical_not(self): return self.ne(True) + def neg(self): + if (dtype:=getattr(self, 'dtype')) is None: raise TypeError(f"MathTraits __neg__ requires a dtype, {self=}") + return self.logical_not() if dtype.scalar() == dtypes.bool else self*(-1) + def add(self, x, reverse=False): return self._binop(Ops.ADD, x, reverse) + def mul(self, x, reverse=False): return self._binop(Ops.MUL, x, reverse) + def bitwise_and(self, x, reverse=False): return self._binop(Ops.AND, x, reverse) + def bitwise_or(self, x, reverse=False): return self._binop(Ops.OR, x, reverse) + def bitwise_xor(self, x, reverse=False): return self._binop(Ops.XOR, x, reverse) + def idiv(self, x, reverse=False): return self._binop(Ops.IDIV, x, reverse) + def mod(self, x, reverse=False): return self._binop(Ops.MOD, x, reverse) + def sub(self, x, reverse=False): return self.ufix(x).alu(Ops.ADD, -self) if reverse else self.alu(Ops.ADD, self.ufix(-x)) + def div(self, x, reverse=False): return (self.ufix(x)*self.alu(Ops.RECIP)) if reverse else (self*self.ufix(x).alu(Ops.RECIP)) + + def __neg__(self): return self.neg() + + def __add__(self, x): return self.add(x) + def __sub__(self, x): return self.sub(x) + def __mul__(self, x): return self.mul(x) + def __truediv__(self, x): return self.div(x) + def __floordiv__(self, x): return self.idiv(x) # TODO: idiv is trunc div, not floordiv + def __mod__(self, x): return self.mod(x) + def __and__(self, x): return self.bitwise_and(x) + def __or__(self, x): return self.bitwise_or(x) + def __xor__(self, x): return self.bitwise_xor(x) + + def __radd__(self, x): return self.add(x, True) + def __rsub__(self, x): return self.sub(x, True) + def __rmul__(self, x): return self.mul(x, True) + def __rtruediv__(self, x): return self.div(x, True) + def __rfloordiv__(self, x): return self.idiv(x, True) + def __rand__(self, x): return self.bitwise_and(x, True) + def __ror__(self, x): return self.bitwise_or(x, True) + def __rxor__(self, x): return self.bitwise_xor(x, True) + def __rmod__(self, x): return self.mod(x, True) + + def __lt__(self, x): return self.alu(Ops.CMPLT, self.ufix(x)) + def __gt__(self, x): return self.ufix(x).alu(Ops.CMPLT, self) + def __ge__(self, x): return (self < x).logical_not() + def __le__(self, x): return (self > x).logical_not() + + def ne(self, x): return self.alu(Ops.CMPNE, self.ufix(x)) + def eq(self, x): return self.ne(x).logical_not() + def __ne__(self, x): return self.ne(x) + # NOTE: __eq__ isn't overridden, and means the same thing as is by default + +class MathTrait(SimpleMathTrait): + # TODO: move to Tensor when new backward is done + def lshift(self, x, reverse=False): return self._binop(Ops.SHL, x, reverse) + def rshift(self, x, reverse=False): return self._binop(Ops.SHR, x, reverse) + def __lshift__(self, x): return self.lshift(x) + def __rshift__(self, x): return self.rshift(x) + def __rlshift__(self, x): return self.lshift(x, True) + def __rrshift__(self, x): return self.rshift(x, True) + + def maximum(self, x): return self.alu(Ops.MAX, self.ufix(x)) + def minimum(self, x): return -(-self).maximum(-x) + def where(self, x, y): + if type(self) is type(x): return self.alu(Ops.WHERE, x, x.ufix(y)) + if type(self) is type(y): return self.alu(Ops.WHERE, y.ufix(x), y) + raise RuntimeError("where needs at least one UOp arg") + def threefry(self, seed): return self.alu(Ops.THREEFRY, seed) + def reciprocal(self): return self.alu(Ops.RECIP) + def sqrt(self): return self.alu(Ops.SQRT) + def sin(self): return self.alu(Ops.SIN) + def log2(self): return self.alu(Ops.LOG2) + def exp2(self): return self.alu(Ops.EXP2) + def pow(self, x): return self.alu(Ops.POW, self.ufix(x)) + +# the order of these Ops controls the order of the toposort +class Ops(FastEnum): + # uops that aren't rendered + SINK = auto(); CONTIGUOUS = auto(); CONTIGUOUS_BACKWARD = auto(); DETACH = auto(); KERNEL = auto(); UNIQUE = auto() # noqa: E702 + + # MetaOps + COPY = auto(); BUFFER_VIEW = auto() # noqa: E702 + + # blocks in linearizer + BLOCK = auto(); BLOCKSTART = auto(); BLOCKEND = auto(); BLOCKFINAL = auto() # noqa: E702 + + # movement ops! + RESHAPE = auto(); PERMUTE = auto(); EXPAND = auto(); PAD = auto(); SHRINK = auto(); FLIP = auto() # noqa: E702 + + # misc ops + UNROLL = auto(); CONTRACT = auto() # noqa: E702 + VIEW = auto(); DEFINE_GLOBAL = auto(); BUFFER = auto() # noqa: E702 + DEFINE_VAR = auto(); DEFINE_LOCAL = auto(); DEFINE_ACC = auto() # noqa: E702 + VALID = auto(); SPECIAL = auto(); NOOP = auto() # noqa: E702 + + # reduce + REDUCE_AXIS = auto(); REDUCE = auto(); ALLREDUCE = auto() # noqa: E702 + + # helper ops + GEP = auto(); VECTORIZE = auto(); CAT = auto(); PTRCAT = auto() # noqa: E702 + + # UnaryOps + CAST = auto(); BITCAST = auto(); EXP2 = auto(); LOG2 = auto(); SIN = auto(); SQRT = auto(); RECIP = auto(); NEG = auto() # noqa: E702 + + # load/store before math + LOAD = auto(); STORE = auto() # noqa: E702 + + # early INDEX + INDEX = auto() + + # math ops + WMMA = auto() + + # BinaryOps + ADD = auto(); MUL = auto(); SHL = auto(); SHR = auto(); IDIV = auto(); MAX = auto(); MOD = auto(); CMPLT = auto(); CMPNE = auto() # noqa: E702 + XOR = auto(); OR = auto(); AND = auto(); THREEFRY = auto(); SUB = auto(); FDIV = auto(); POW = auto() # noqa: E702 + + # TernaryOps + WHERE = auto(); MULACC = auto() # noqa: E702 + + # assignment ops + ASSIGN = auto() + BIND = auto() + + # control flow ops + BARRIER = auto(); RANGE = auto(); IF = auto(); ENDRANGE = auto(); ENDIF = auto() # noqa: E702 + + # consts last! + VCONST = auto(); CONST = auto() # noqa: E702 + + # device + DEVICE = auto() + MULTI = auto() + + # CUSTOMI is inline + CUSTOM = auto(); CUSTOMI = auto() # noqa: E702 + IGNORE = auto(); FUSE = auto() # noqa: E702 + +class GroupOp: + Unary = {Ops.EXP2, Ops.LOG2, Ops.SIN, Ops.SQRT, Ops.RECIP, Ops.NEG} + Binary = {Ops.ADD, Ops.MUL, Ops.IDIV, Ops.MAX, Ops.MOD, Ops.CMPLT, Ops.CMPNE, Ops.XOR, Ops.SHL, Ops.SHR, Ops.OR, Ops.AND, Ops.THREEFRY, + Ops.SUB, Ops.FDIV, Ops.POW} + Ternary = {Ops.WHERE, Ops.MULACC} + ALU = set.union(Unary, Binary, Ternary) + + Irreducible = {Ops.CONST, Ops.DEFINE_VAR, Ops.SPECIAL, Ops.RANGE} + Movement = {Ops.RESHAPE, Ops.EXPAND, Ops.PERMUTE, Ops.PAD, Ops.SHRINK, Ops.FLIP} + + Buffer = {Ops.LOAD, Ops.STORE, Ops.VALID, Ops.CONST, Ops.DEFINE_VAR} + Block = {Ops.BLOCK, Ops.BLOCKEND, Ops.BLOCKSTART} + + # BinaryOps that can be flipped + Commutative = {Ops.ADD, Ops.MUL, Ops.MAX, Ops.CMPNE, Ops.XOR, Ops.AND, Ops.OR} + + # BinaryOps where f(f(a,b),c) = f(a,f(b,c)) + Associative = {Ops.ADD, Ops.MUL, Ops.AND, Ops.OR, Ops.MAX} + + # BinaryOps that satisfy f(x,x)=x see https://en.wikipedia.org/wiki/Idempotence + Idempotent = {Ops.OR, Ops.AND, Ops.MAX} + + # do not preserve f(0) = 0 + UnsafePad = {Ops.RECIP, Ops.LOG2, Ops.EXP2, Ops.IDIV, Ops.POW} + + Meta = {Ops.COPY, Ops.BUFFER_VIEW} + + All = set(Ops) + +# https://en.wikipedia.org/wiki/Identity_element +def identity_element(op:Ops, dt:DType) -> ConstType: return dtypes.as_const({Ops.ADD:0, Ops.MUL:1, Ops.MAX:dtypes.min(dt)}[op], dt) + +def can_pad(root:UOp, edges:dict[UOp, None]) -> bool: + return all(u.op not in GroupOp.UnsafePad for u in root.toposort(gate=lambda x:x not in edges)) + +# With True as the default, this matches the old symbolic behavior +def resolve(x:UOp|bool, default:bool=True): + if isinstance(x, bool): return x + assert x.dtype == dtypes.bool, "UOp in resolve must be bool" + # NOTE: generating the text for the exception is expensive, so we do this + return bool(sx.vmin) if (sx:=x.simplify()).vmin == sx.vmax else default + +# smax/smin are replacements for max/min that preserve symbolic +def _suop(lst, uop_fxn, python_fxn): + uops, nums = partition(lst, lambda x: isinstance(x, UOp)) + return ssimplify(functools.reduce(uop_fxn, uops + ([python_fxn(nums)] if nums else []))) +def smax(*lst): return _suop(argfix(*lst), UOp.maximum, max) +def smin(*lst): return _suop(argfix(*lst), UOp.minimum, min) +def srender(x) -> str: return x.render() if isinstance(x, UOp) else str(x) + +def ssimplify(uop): return uop.ssimplify() if isinstance(uop, UOp) else uop +def sym_infer(uop: Union[UOp, int], var_vals: dict[UOp, int]) -> int: return uop.sym_infer(var_vals) if isinstance(uop, UOp) else uop + +# used for UOp and UPat +def pretty_print(x:Any, rep:Callable, srcfn=lambda x: x.src, cache=None, d=0)->str: + def dfs(x:Any, cache:dict): + for s in srcfn(x) or []: + cache.setdefault(s, [len(cache), 0, False])[1] += 1 + if cache[s][1] == 1: dfs(s, cache) + if cache is None: dfs(x, cache:={}) + if (cx:=cache.setdefault(x, [0,0,False]))[2]: return f"{' '*d} x{cx[0]}" + cx[2], srcs = True, ('None' if srcfn(x) is None else ''.join(f'\n{pretty_print(s, rep, srcfn, cache, d+2)},' for s in srcfn(x))) + return f"{' '*d}{f'x{cx[0]}:=' * (cx[1]>1)}{rep(x)}" % srcs + +class UOpMetaClass(type): + ucache:dict[tuple, weakref.ReferenceType[UOp]] = {} + def __call__(cls, op:Ops, dtype:DType=dtypes.void, src:tuple[UOp,...]=tuple(), arg:Any=None, metadata:Metadata|None=None, _buffer:Buffer|None=None): + if (wret:=UOpMetaClass.ucache.get(key:=(op, dtype, src, arg), None)) is not None and (ret:=wret()) is not None: return ret + UOpMetaClass.ucache[key] = ref = weakref.ref(created:=super().__call__(*key)) + for s in src: s.children.add(ref) + if metadata is not None: all_metadata[created] = metadata + # NOTE: this value is set by pickle when pickling a realized tensor + if _buffer is not None: + assert op is Ops.BUFFER, f"trying to set Buffer {_buffer} for {op}" + buffers[created] = _buffer + return created + +# some uops map to other stuff +buffers:weakref.WeakKeyDictionary[UOp, Buffer] = weakref.WeakKeyDictionary() # this maps BUFFER uops to their device Buffers +all_metadata:weakref.WeakKeyDictionary[UOp, Metadata] = weakref.WeakKeyDictionary() # TODO: should this be here? + +# NOTE: this should be frozen, but frozen is slower +@dataclass(eq=False, slots=True) +class UOp(MathTrait, metaclass=UOpMetaClass): + op:Ops + dtype:DType = dtypes.void + src:tuple[UOp, ...] = tuple() + arg:Any = None + children:set[weakref.ref[UOp]] = field(default_factory=set) + def __del__(self): + if self.op is Ops.BUFFER and (buffer:=buffers.get(self)) is not None: buffer.ref(-1) + if (ref:=UOpMetaClass.ucache.get(k:=(self.op, self.dtype, self.src, self.arg))) is not None: + for s in self.src: s.children.discard(ref) + del UOpMetaClass.ucache[k] + def __reduce__(self): + args = [self.op, self.dtype, self.src, self.arg] + args.append(self.metadata) + if self.op is Ops.BUFFER and self.realized is not None and PICKLE_BUFFERS: args.append(self.realized) + return UOp, tuple(args) + def replace(self, **kwargs) -> UOp: + new_args = (kwargs.pop("op", self.op), kwargs.pop("dtype", self.dtype), kwargs.pop("src", self.src), kwargs.pop("arg", self.arg)) + assert len(kwargs) == 0, f"unused kwargs in replace {list(kwargs)}" + if (self.op, self.dtype, self.src, self.arg) == new_args: return self + return UOp(*new_args) + @functools.cached_property + def key(self) -> bytes: + return hashlib.sha256(str((self.op, self.dtype, self.arg)).encode() + b"".join([s.key for s in self.src])).digest() + def __repr__(self): return pretty_print(self, lambda x: f"{type(self).__name__}({x.op}, {x.dtype}, arg={x.argstr()}, src=(%s))") + def argstr(self): return f'({", ".join(map(str, self.arg))})' if self.op is Ops.REDUCE_AXIS else repr(self.arg) + + @functools.cached_property + def parents(self:UOp) -> dict[UOp, None]: + ret = {s:None for s in self.src} + for s in self.src: ret.update(s.parents) + return ret + @property + def sparents(self:UOp) -> dict[UOp, None]: return {self:None, **self.parents} + + def toposort(self, gate:Callable|None=None) -> dict[UOp, None]: + ret: dict[UOp, None] = {} + stack: list[tuple[UOp, bool]] = [(self, False)] # each stack entry is (node, visited_flag) + while stack: + node, visited = stack.pop() + if node in ret: continue + if not visited: + if gate is None or gate(node): + stack.append((node, True)) # push node back on stack to process after its parents + for parent in reversed(node.src): stack.append((parent, False)) # push parents on the stack + else: ret[node] = None # second time i'm seeing this node, add it to returned toposort + return ret + + # returns map of UOps to their children in the graph rooted by self + def get_children_map(self) -> dict[UOp, dict[UOp, None]]: + ret: dict[UOp, dict[UOp, None]] = {} + for u in self.toposort(): + ret[u] = {} + for s in u.src: ret[s][u] = None + return ret + + @functools.cached_property + def tuplize(self:UOp) -> tuple: + return (self.op.value, self.arg, self.dtype,)+tuple([x.tuplize for x in self.src]) + + # *** uop shape stuff *** + + @functools.cached_property + def st(self) -> ShapeTracker|None: + # VIEW and MovementOps define a new ShapeTracker from the arg + if self.op is Ops.VIEW: return self.arg + if self.op in GroupOp.Movement: return unwrap(self.src[0].st).mop(self.op, self.arg) + # BufferOps and ASSIGN flow ShapeTracker from a direct edge + if self.op in GroupOp.Buffer: return views[0] if (views:=[x.st for x in self.src if x.op is Ops.VIEW]) else None + if self.op is Ops.ASSIGN: return self.src[0].st + + from tinygrad.shape.shapetracker import ShapeTracker + # BUFFER/BUFFER_VIEW and KERNEL only have a size + if self.op in {Ops.BUFFER, Ops.BUFFER_VIEW}: return ShapeTracker.from_shape((self.size,)) + if self.op is Ops.KERNEL: return ShapeTracker.from_shape((self.arg.ast.size,)) + + # otherwise we get the shape from sources + if not (src_sts := [x.st for x in self.src if x.st is not None]): return None + assert all_same([x.shape for x in src_sts]), f"UOp sources must have the same shape {self} {[x.shape for x in src_sts]}" + match self.op: + case Ops.MULTI: shape = tuple(self.src[0].shape[a]*len(self.device) if a == self.axis else s for a,s in enumerate(self.src[0].shape)) + case Ops.BITCAST: + shape = src_sts[0].shape + if self.dtype.itemsize != (input_sz:=self.src[0].dtype.itemsize): shape = shape[:-1]+((shape[-1]*input_sz) // self.dtype.itemsize,) + case Ops.REDUCE_AXIS | Ops.WMMA: shape = src_sts[0].reduce(self.axis_arg) + case _: shape = src_sts[0].shape + return ShapeTracker.from_shape(shape) + + @functools.cached_property + def full_shape(self) -> tuple[sint, ...]: + if self.op is Ops.VIEW: return self.shape + # NOTE: if a parent doesn't have st its full_shape is empty + parent_shapes = [x.full_shape for x in self.src] + return tuple(smax(x) for x in zip(*[x for x in parent_shapes if x != ()])) + @property + def shape(self) -> tuple[sint, ...]: return unwrap(self.st).shape + @property + def size(self) -> int: return self.arg[0] if self.op is Ops.BUFFER_VIEW else self.arg if self.op is Ops.BUFFER else unwrap(self.st).size + + # *** uop evaluation *** + + def simplify(self): + # late import! + from tinygrad.codegen.symbolic import symbolic + with Context(TRACK_MATCH_STATS=0): + return graph_rewrite(self, symbolic) + def ssimplify(self) -> Union[UOp, ConstType]: return ret.arg if (ret:=self.simplify()).op is Ops.CONST else ret + def _eval(self, dtype, expected_type:Type[T]) -> T: + assert self.dtype in dtype, f"eval with wrong dtype {self}" + vmin, vmax = (simple_self:=self.simplify())._min_max + if vmin != vmax: raise ValueError(f"eval failed to be a single number, range is {vmin} to {vmax} in {simple_self.render()}") + assert isinstance(vmin, expected_type), f"vmin is wrong dtype {type(vmin)} != {expected_type}" + return vmin + def __bool__(self): return self._eval((dtypes.bool,), bool) + def __int__(self): return self._eval(dtypes.ints, int) + def __float__(self): return self._eval(dtypes.floats, float) + def substitute(self, dvars:dict[UOp, UOp], name:str|None=None): + dvars = {k:v for k,v in dvars.items() if k is not v} + if len(dvars) == 0: return self + with Context(TRACK_MATCH_STATS=(0 if name is None else TRACK_MATCH_STATS.value)): + return graph_rewrite(self, _substitute, dvars, bottom_up=True, name=name) + + # *** uop syntactic sugar *** + + @property + def st_arg(self) -> ShapeTracker: + assert self.op in GroupOp.Buffer, f"st_arg called on {self.op}" + return unwrap(self.st) + @property + def axis_arg(self) -> tuple[int, ...]: + assert self.op in {Ops.REDUCE_AXIS, Ops.WMMA}, f"axis_arg called on {self.op}" + ret = self.arg[1] if self.op is Ops.REDUCE_AXIS else self.arg[7] + assert isinstance(ret, tuple) and all(isinstance(x, int) for x in ret), f"axis_arg trying to return {ret}" + return ret + def sink(self, *srcs:UOp|None, **kwargs): return UOp(Ops.SINK, dtypes.void, (self,)+tuple([x for x in srcs if x is not None]), **kwargs) + def detach(self): return UOp(Ops.DETACH, self.dtype, (self,)) + def index(self, idx:UOp, valid:UOp|None=None): return UOp(Ops.INDEX, self.dtype, (self,idx,valid) if valid is not None else (self,idx)) + def const_like(self, b:ConstLike): + # constants can optionally have a DEVICE source + if self._device is None: return UOp.const(self.dtype, b) + return UOp.metaop(Ops.CONST, self.shape, self.dtype, self.device, b) + def broadcast(self, count:int): + assert self.dtype.count == 1 + if count == 1: return self + return UOp(Ops.VECTORIZE, self.dtype.vec(count), (self,)*count) + def cast(self, dtype:DType): + if self.dtype == dtype: return self + return UOp(Ops.CAST, dtype, (self,)) + def cast_vec(self, dtype:DType): return UOp(Ops.CAST, dtype.vec(self.dtype.count), (self,)) + def bitcast(self, dtype:DType): return UOp(Ops.BITCAST, dtype, (self,)) + def gep(self, i:Union[tuple[int, ...], int]): + if isinstance(i, tuple) and len(i) == 1: return self.gep(i[0]) + if isinstance(i, int): + # NOTE: these are just shortcuts to not have to create and fold later + if self.op is Ops.VECTORIZE: return self.src[i] + if self.op is Ops.VCONST: return UOp.const(self.dtype.scalar(), self.arg[i]) + if self.op is Ops.CONST: return UOp.const(self.dtype.scalar(), self.arg) + i = (i,) + return UOp(Ops.GEP, self.dtype.scalar().vec(len(i)) if len(i) > 1 else self.dtype.scalar(), (self,), i) + def load(self, *src:UOp, **kwargs): + if 'dtype' not in kwargs: kwargs['dtype'] = self.dtype.base + return UOp(Ops.LOAD, src=(self,)+src, **kwargs) + def store(self, *src:UOp, **kwargs): return UOp(Ops.STORE, dtypes.void, (self,)+src, **kwargs) + def alu(self, arg, *src:UOp): + out_dtype = (self, *src)[-1].dtype + if arg in {Ops.CMPLT, Ops.CMPNE}: out_dtype = dtypes.bool.vec(out_dtype.count) if out_dtype.count > 1 else dtypes.bool + return UOp(arg, out_dtype, (self,)+src) + @staticmethod + def const(dtype:DType, b:ConstLike): + if isinstance(b, UOp): return b.unbind()[0] if b.op is Ops.BIND else b + if isinstance(b, tuple) and all_same(b): b = b[0] # doesn't have to be a VCONST if they are all the same + return UOp(Ops.VCONST if isinstance(b, tuple) else Ops.CONST, dtype, arg=dtypes.as_const(b, dtype)) + def valid(self, st:ShapeTracker): + assert self.op in {Ops.CONST, Ops.DEFINE_VAR} and any(v.mask is not None for v in st.views), f"attempting to create VALID with {self.op} {st}" + from tinygrad.shape.shapetracker import ShapeTracker + # NOTE: only VALID has a masked ShapeTracker, the CONST operands are unmasked + unmasked_st = ShapeTracker.from_shape(()).reshape((1,)*len(st.shape)).expand(st.shape).to_uop() + return UOp(Ops.VALID, dtypes.bool, (st.to_uop(),)).where(self.replace(src=(unmasked_st,)), UOp.const(self.dtype, 0).replace(src=(unmasked_st,))) + @staticmethod + def range(dtype:DType, end:sint, idx:int): return UOp(Ops.RANGE, dtype=dtype, src=(sint_to_uop(end),), arg=idx) + def r(self, op:Ops, axis:tuple[int, ...]): + axis = tuple(sorted([x for x in axis if resolve(self.shape[x] != 1)])) + return self if len(axis) == 0 else UOp(Ops.REDUCE_AXIS, self.dtype, (self,), (op, axis)) + def assign(self, x:UOp): return UOp(Ops.ASSIGN, self.dtype, (self,x)) + def reduce(self, *src:UOp, **kwargs): return UOp(Ops.REDUCE, kwargs.pop('dtype', self.dtype), src=(self,)+src, **kwargs) + def contiguous(self): return self.alu(Ops.CONTIGUOUS) + def contiguous_backward(self): return self.alu(Ops.CONTIGUOUS_BACKWARD) + def fuse(self): return self.alu(Ops.FUSE) + def allreduce(self, op, device:str|tuple[str, ...]|UOp): + assert isinstance(self.device, tuple), f"allreduce must be on tuple {self.device} isn't" + return UOp(Ops.ALLREDUCE, self.dtype, (self, UOp(Ops.DEVICE, arg=device) if not isinstance(device, UOp) else device), op) + + # *** from MultiLazyBuffer *** + + def multi(self, axis:int|None): + assert isinstance(self.device, tuple), f"multi device must be tuple, {self.device} isn't" + assert axis is not None, "multi None is no longer supported" + return UOp(Ops.MULTI, self.dtype, (self,), axis) + + @property + def bounds(self): + if self.axis is None: raise RuntimeError("bounds is not defined when axis is None") + return tuple(itertools.pairwise(itertools.accumulate([self.src[0].shape[self.axis] for _ in self.device], initial=0))) + + @functools.cached_property + def axis(self) -> Optional[int]: + if self.op is Ops.MULTI: return self.arg + # NOTE: they all have to share an axis, we always choose [-1] + if self.op in GroupOp.ALU: return axes[-1] if (axes := dedup([x.axis for x in self.src if x.axis is not None])) else None + if len(self.src) == 0: return None + src_axis = self.src[0].axis + if self.op is Ops.REDUCE_AXIS: return None if src_axis is not None and src_axis in self.arg[1] else src_axis + if self.op is Ops.RESHAPE: + if src_axis is None: return None + arg_acc:list[sint] = list(itertools.accumulate(self.arg, operator.mul, initial=1)) + # new_axis is the last one that preserves prod(prior to new_axis) and must not move items between shards + # TODO: what to do about shrinking to self.shape[self.axis]==1 len(self.real_lbs)==1? + return len(arg_acc) - arg_acc[::-1].index(prod(self.src[0].shape[:src_axis])) - 1 + if self.op is Ops.PERMUTE: return self.arg.index(src_axis) if src_axis is not None else None + return src_axis + + def _unshard(self, axis:int) -> UOp: + bsz, dcount = self.shape[axis], len(self.device) + dnum = UOp.variable("_device_num", 0, dcount-1) + return self.pad(tuple((0,0) if a != axis else (bsz*dnum, bsz*(dcount-1) - bsz*dnum) for a in range(len(self.shape)))) + + def _shard(self, axis:int) -> UOp: + dcount = len(self.device) + dnum = UOp.variable("_device_num", 0, dcount-1) + if self.shape[axis] % dcount != 0: raise RuntimeError(f"multi axis uneven: {self.shape[axis]=} {axis=} {dcount=}") + sz = self.shape[axis] // dcount + return self.shrink(tuple((0,s) if i != axis else (dnum*sz,dnum*sz+sz) for i,s in enumerate(self.shape))) + def shard(self, devices:tuple[str, ...], axis:int) -> UOp: return self.copy_to_device(devices)._shard(axis).multi(axis) + + # *** from LazyBuffer *** + + @staticmethod + def metaop(op:Ops, shape:tuple[sint, ...], dtype:DType, device:str|tuple[str, ...], arg=None) -> UOp: + from tinygrad.shape.shapetracker import ShapeTracker + # Tensor const is CONST(VIEW(DEVICE)) -> RESHAPE -> EXPAND + if op is Ops.CONST: + assert isinstance(arg, get_args(ConstType)), f"trying to create CONST with {arg=}" + return UOp.const(dtype, unwrap(arg)).replace(src=(UOp(Ops.VIEW, dtypes.void, (UOp(Ops.DEVICE, arg=device),), + ShapeTracker.from_shape(())),)).reshape((1,)*len(shape)).expand(shape) + # Tensor variable binding is BIND(VAR(VIEW(DEVICE)), CONST(VIEW(DEVICE))) + assert op is Ops.BIND, f"unknown op {op}" + var, val = arg.unbind() + return var.replace(src=(UOp(Ops.VIEW, dtypes.void, (UOp(Ops.DEVICE, arg=device),), ShapeTracker.from_shape(shape)),)).bind(val) + def copy_to_device(self, device:str|tuple[str, ...]|UOp, arg=None): + return UOp(Ops.COPY, self.dtype, (self, UOp(Ops.DEVICE, arg=device) if not isinstance(device, UOp) else device), arg) + def clone(self) -> UOp: return self.copy_to_device(self.device) + @property + def metadata(self) -> Metadata|None: return all_metadata.get(self, None) + + # *** uop movement ops *** + + @property + def base(self) -> UOp: + if (self.op is Ops.VIEW and len(self.src) != 0) or self.op in GroupOp.Movement: return self.src[0].base + return self + def view(self, new_st:ShapeTracker) -> UOp: return UOp(Ops.VIEW, self.dtype, (self.base,), new_st) + + def _mop(self, op:Ops, arg): + ret = UOp(op, self.dtype, (self,), arg) + if self.st == ret.st: return self # ignore NOOPs, also check ret.st + return ret + + def reshape(self, arg:tuple[sint, ...]): return self._mop(Ops.RESHAPE, arg) + def pad(self, arg:tuple[tuple[sint, sint], ...]): return self._mop(Ops.PAD, arg) + def expand(self, arg:tuple[sint, ...]): return self._mop(Ops.EXPAND, arg) + def permute(self, arg:tuple[sint, ...]): return self._mop(Ops.PERMUTE, arg) + def shrink(self, arg:tuple[tuple[sint, sint], ...]): return self._mop(Ops.SHRINK, arg) + def flip(self, arg:tuple[bool, ...]): return self._mop(Ops.FLIP, arg) + + # *** uop UNIQUE *** + + # TODO: use this in Buffer + unique_num = itertools.count(0) + @staticmethod + def unique(): return UOp(Ops.UNIQUE, arg=next(UOp.unique_num)) + + # *** uop Buffer stuff *** + + @staticmethod + def new_buffer(device:str|tuple[str, ...], size:int, dtype:DType): return UOp(Ops.BUFFER, dtype, (UOp.unique(), UOp(Ops.DEVICE, arg=device)), size) + @property + def device(self) -> str|tuple[str, ...]: return cast(str|tuple[str, ...], unwrap(self._device)) + @functools.cached_property + def _device(self) -> Optional[str|tuple[str, ...]]: + if self.op is Ops.DEVICE: return self.arg + if self.op in {Ops.COPY, Ops.BUFFER, Ops.ALLREDUCE}: return self.src[1].device + return dsrcs[0]._device if len(dsrcs:=[x for x in self.src if x._device is not None]) != 0 else None + @property + def buf_uop(self) -> UOp: + if self.op is Ops.BUFFER: return self + assert self.op is Ops.ASSIGN, f"must be ASSIGN {self.op}" + return self.src[0].base + @property + def buffer(self) -> Buffer|MultiBuffer: + if self is not self.base: + assert unwrap(self.st).contiguous, "VIEW only works here if it's contiguous" + return self.src[0].buffer + assert self.op is Ops.BUFFER, f"must be BUFFER {self.op}" + if (cret:=buffers.get(self)) is not None: return cret + from tinygrad.device import Buffer, MultiBuffer + rdtype = self.dtype if isinstance(self.dtype, ImageDType) else self.dtype.base + if isinstance(self.device, tuple): ret = MultiBuffer(self.device, self.size, rdtype).ref(1) + else: ret = Buffer(self.device, self.size, rdtype).ref(1) + buffers[self] = ret + return ret + @property + def realized(self) -> Optional[Buffer|MultiBuffer]: return self.buffer if self.op is Ops.BUFFER and self.buffer.is_allocated() else None + @property + def is_realized(self) -> bool: + return all(x.base.realized is not None for x in self.base.src) if self.base.op is Ops.MULTI else self.base.realized is not None + + # *** uop Variable stuff *** + + @staticmethod + def variable(name:str, min_val:ConstType, max_val:ConstType, dtype:DType=dtypes.int): + assert not isinstance(min_val, UOp) and not isinstance(max_val, UOp), f"can't create Variable {name} with {min_val}/{max_val}" + return UOp(Ops.DEFINE_VAR, dtype, arg=(name, min_val, max_val)) + @property + def expr(self): + assert self.op is Ops.DEFINE_VAR, f"op is {self.op}, need DEFINE_VAR" + return self.arg[0] + def bind(self, val:int): + assert self.op is Ops.DEFINE_VAR, f"op is {self.op}, need DEFINE_VAR" + assert self.arg[1] <= val and val <= self.arg[2], f"bind {val} not in range [{self.arg[1]}, {self.arg[2]}]" + return UOp(Ops.BIND, self.dtype, (self, self.const_like(val))) + def unbind(self) -> tuple[Variable, int]: + assert self.op is Ops.BIND and self.src[0].op is Ops.DEFINE_VAR and self.src[1].op is Ops.CONST, f"can't unbind {self}" + return self.src[0], self.src[1].arg + @property + def val(self) -> int: return self.unbind()[1] + def vars(self) -> set[UOp]: + bound_vars = set([x for x in self.toposort() if x.op is Ops.BIND and x.src[0].op is Ops.DEFINE_VAR]) + bound_var_base = set(x.src[0] for x in bound_vars) + all_vars = set([x for x in self.toposort() if x.op is Ops.DEFINE_VAR]) + return bound_vars.union(set([x for x in all_vars if x not in bound_var_base])) + def variables(self) -> list[Variable]: + st_vars: list[set[Variable]] = [x.st_arg.vars() for x in self.toposort() if x.op in GroupOp.Buffer] + return sorted(set.union(*st_vars, [x.unbind()[0] if x.op is not Ops.DEFINE_VAR else x for x in self.vars()]), key=lambda v: v.arg) + + # *** uop symbolic stuff *** + + def is_increasing(self:UOp) -> bool: + # is f a monotonically increasing function regards its input + if self.op in GroupOp.Irreducible: return True + if self.op is Ops.ADD: return self.src[0].is_increasing() and self.src[1].is_increasing() + if self.op in (Ops.MUL, Ops.IDIV) and self.src[1].op is Ops.CONST and self.src[1].arg >= 0: return self.src[0].is_increasing() + return False # False if not sure + def const_factor(self) -> int: + """largest known int that divides self""" + # TODO: for negatives it's not the largest + if self.op is Ops.CONST: return self.arg + if self.op is Ops.VCONST: return math.gcd(*self.arg) + if self.op is Ops.ADD: return math.gcd(self.src[0].const_factor(), self.src[1].const_factor()) + if self.op is Ops.MUL: return self.src[0].arg if self.src[0].op is Ops.CONST else self.src[1].arg if self.src[1].op is Ops.CONST else 1 + return 1 + def divides(self, v:int) -> UOp|None: + if v==1: return self + if self.op is Ops.CONST: return self.const_like(self.arg//v) if self.arg%v == 0 else None + if self.op is Ops.VCONST: return self.const_like(tuple(x//v for x in self.arg)) if all(x%v == 0 for x in self.arg) else None + if self.op is Ops.ADD: return d0+d1 if (d0:=self.src[0].divides(v)) is not None and (d1:=self.src[1].divides(v)) is not None else None + if self.op is Ops.MUL: + if (d0:=self.src[0].divides(v)) is not None: return d0 * self.src[1] + if (d1:=self.src[1].divides(v)) is not None: return self.src[0] * d1 + return None # generic None if we aren't sure + @property + def vmin(self) -> ConstType: return self._min_max[0] + @property + def vmax(self) -> ConstType: return self._min_max[1] + @functools.cached_property + def _min_max(self) -> tuple[ConstType, ConstType]: + if self.op in GroupOp.Binary and not dtypes.is_float(self.dtype): + (s0_vmin, s0_vmax), (s1_vmin, s1_vmax) = self.src[0]._min_max, self.src[1]._min_max + if self.op is Ops.ADD: return s0_vmin+s1_vmin, s0_vmax+s1_vmax + if self.op is Ops.SUB: return s0_vmin-s1_vmax, s0_vmax-s1_vmin + if self.op is Ops.AND and s1_vmin == s1_vmax and s0_vmin >= 0 and s1_vmin >= 0: return min(0, s0_vmin), min(s0_vmax, s1_vmax) + if self.op is Ops.MUL: return min(vals:=(s0_vmin*s1_vmin, s0_vmin*s1_vmax, s0_vmax*s1_vmin, s0_vmax*s1_vmax)), max(vals) + # SHL/SHR on consts only + if self.op is Ops.SHL and s1_vmin == s1_vmax and all_int(t:=(s0_vmin, s0_vmax, s1_vmin)): return t[0] << t[2], t[1] << t[2] + if self.op is Ops.SHR and s1_vmin == s1_vmax and all_int(t:=(s0_vmin, s0_vmax, s1_vmin)): return t[0] >> t[2], t[1] >> t[2] + if self.op is Ops.MOD: + if s1_vmin > 0: return (0, s1_vmax-1) if s0_vmin >= 0 else (-(s1_vmax-1), 0) if s0_vmax <= 0 else (-(s1_vmax-1), s1_vmax-1) + if s1_vmax < 0: return (0, -s1_vmax-1) if s0_vmin >= 0 else (-(-s1_vmax-1), 0) if s0_vmax <= 0 else (-(-s1_vmax-1), -s1_vmax-1) + if self.op is Ops.IDIV: + assert isinstance(s0_vmin, int) and isinstance(s0_vmax, int) and isinstance(s1_vmin, int) and isinstance(s1_vmax, int) + if (c:=s1_vmin) == s1_vmax: # s1 is a const + if c > 0: return cdiv(s0_vmin, c), cdiv(s0_vmax, c) + if c < 0: return cdiv(s0_vmax, c), cdiv(s0_vmin, c) + if (s0_vmax <= 0 and s1_vmax < 0): return cdiv(s0_vmax, s1_vmin), cdiv(s0_vmin, s1_vmax) + if (s0_vmin >= 0 and s1_vmin > 0): return cdiv(s0_vmin, s1_vmax), cdiv(s0_vmax, s1_vmin) + if (s0_vmax <= 0 and s1_vmin > 0): return cdiv(s0_vmin, s1_vmin), cdiv(s0_vmax, s1_vmax) + if (s0_vmin >= 0 and s1_vmax < 0): return cdiv(s0_vmax, s1_vmax), cdiv(s0_vmin, s1_vmin) + if self.op is Ops.MAX: return max(s0_vmin, s1_vmin), max(s0_vmax, s1_vmax) + if self.op is Ops.CMPLT: return (s0_vmax str: + ret = graph_rewrite(self.simplify() if simplify else self, renderer if pm is None else pm) + return ret.arg if ret.op is Ops.NOOP else str(ret) + +@dataclass(frozen=True) +class KernelInfo: + name: str = "test" # name of the kernel + local_dims: int = 0 # number of local dimensions (this is remapping RANGE to SPECIAL) + upcasted: int = 0 # count that are upcasted (this is remapping RANGE to UNROLL) + dont_use_locals: bool = False # don't use local indexing + +# ******** ops in python ******** + +def safe_exp2(x): + try: return 2 ** x + except OverflowError: return math.inf + +def safe_pow(x, y): + try: return math.nan if isinstance(p:=pow(x, y), complex) else p + except ZeroDivisionError: return math.inf + except ValueError: return math.inf if x > 0 else -math.inf + +python_alu: dict[Ops, Callable] = { + Ops.LOG2: lambda x: math.log2(x) if x > 0 else -math.inf if x == 0 else math.nan, Ops.EXP2: safe_exp2, + Ops.SQRT: lambda x: math.sqrt(x) if x >= 0 else math.nan, Ops.RECIP: lambda x: 1/x if x != 0 else math.copysign(math.inf, x), + Ops.SIN: lambda x: math.sin(x) if not math.isinf(x) else math.nan, Ops.POW: safe_pow, + Ops.NEG: operator.neg, Ops.ADD: operator.add, Ops.SUB: operator.sub, Ops.MUL: operator.mul, Ops.CMPNE: operator.ne, Ops.CMPLT: operator.lt, + Ops.XOR: operator.xor, Ops.OR: operator.or_, Ops.AND: operator.and_, Ops.SHR: operator.rshift, Ops.SHL: operator.lshift, Ops.MAX: max, + Ops.MOD: cmod, Ops.IDIV: cdiv, Ops.MULACC: lambda x,y,z: (x*y)+z, Ops.WHERE: lambda x,y,z: y if x else z} + +def exec_alu(op:Ops, dtype:DType, operands, truncate_output=True): + if dtype.count > 1: + return tuple([exec_alu(op, dtype.scalar(), [x[i] if isinstance(x, tuple) else x for x in operands]) for i in range(dtype.count)]) + alu = python_alu[op](*operands) + return truncate.get(dtype, lambda x: x)(alu) if truncate_output else alu + +# ***** uop helpers ***** + +def print_uops(uops:list[UOp]): + for i,u in enumerate(uops): + formatted_parents = [(uops.index(x) if x.op is not Ops.CONST else f"{x.arg}") if x in uops else "--" for x in u.src] + print(f"{i:4d} {str(u.op):20s}: {str(u.dtype):30s} " f"{str(formatted_parents):32s} {u.arg}") + +# ***** pattern matcher ***** + +def get_location() -> tuple[str, int]: + frm = sys._getframe(1) + # skip over ops.py (unless there's nothing but ops.py) + while pathlib.Path(frm.f_code.co_filename).name == "ops.py" and frm.f_back is not None and not frm.f_back.f_code.co_filename.startswith(" list[str]: + with open(fn) as f: return f.readlines() + +class UPat(MathTrait): + __slots__ = ("op", "dtype", "arg", "name", "src") + def __init__(self, op:Optional[Union[Ops, tuple[Ops, ...], set[Ops]]]=None, dtype:Optional[Union[DType, tuple[DType, ...]]]=None, + src:Optional[Union[tuple[UPat, ...], list[UPat], UPat]]=None, arg:Any=None, + name:Optional[str]=None, allow_any_len:bool=False, custom_early_reject:Optional[set[Ops]]=None, location=None): + assert op is None or isinstance(op, (Ops, tuple, set)), "op must be Ops or tuple of Ops" + self.op: Optional[tuple[Ops, ...]] = (op,) if isinstance(op, Ops) else (tuple(op) if isinstance(op, set) else op) + self.dtype: Optional[tuple[DType, ...]] = (dtype,) if isinstance(dtype, DType) else dtype + self.arg, self.name, self._in_src, self.custom_early_reject = arg, name, src, custom_early_reject + self.src: Any = None + assert self.name != "ctx", "UPat can't be named ctx" + assert dtype is None or isinstance(dtype, DType) or all(isinstance(x, DType) for x in dtype), f"invalid dtype {dtype}" + + # try all permutations if it's a list + if isinstance(src, list): self.src = list(itertools.permutations(src)) if not all_same(src) else [tuple(src)] + # only one if it's a tuple + elif isinstance(src, tuple): self.src = [src] + # repeat if it's a UPat + elif isinstance(src, UPat): self.src = [itertools.repeat(src)] + + self.strict_length = not (allow_any_len or isinstance(src, UPat) or src is None) + self.required_len: int = 0 if isinstance(src, UPat) or src is None else len(src) + self.location = location or get_location() + + if custom_early_reject is not None: self.early_reject = custom_early_reject + else: + upat_match = [src] if isinstance(src, UPat) else ([] if src is None else self.src[0]) + self.early_reject = {pp.op[0] for pp in upat_match if pp.op is not None and len(pp.op) == 1} + + def __reduce__(self): + return UPat, (self.op, self.dtype, self._in_src, self.arg, self.name, not self.strict_length, self.custom_early_reject, self.location) + def named(self, name:str): return UPat(self.op, self.dtype, self._in_src, self.arg, name, not self.strict_length, self.custom_early_reject) + + @staticmethod + def any(*src): return UPatAny(src=src) + def or_casted(self, name:str|None=None): return UPat.any(self if name is None else self.named(name), UPat(Ops.CAST, name=name, src=(self,))) + + @staticmethod + @functools.cache + def var(name:Optional[str]=None, dtype:Optional[Union[DType, tuple[DType, ...]]]=None): return UPat(dtype=dtype, name=name) + @staticmethod + @functools.cache + def cvar(name:Optional[str]=None, dtype:Optional[DType]=None, vec=True): return UPat((Ops.CONST,Ops.VCONST) if vec else Ops.CONST, dtype, name=name) + @staticmethod + def const(dtype:Optional[Union[DType, tuple[DType, ...]]], b:ConstType): return UPat(Ops.CONST, dtype=dtype, arg=b) + + # copied from UOp + def index(self, idx:UPat, valid:Optional[UPat]=None): return UPat(Ops.INDEX, self.dtype, (self,idx,valid) if valid is not None else (self,idx)) + def view(self, st=None, **kwargs): return UPat(Ops.VIEW, self.dtype, (self,), st, **kwargs) + def cast(self, dtype=None, **kwargs): return UPat(Ops.CAST, dtype, (self,), **kwargs) + def bitcast(self, dtype=None): return UPat(Ops.BITCAST, dtype, (self,)) + def gep(self, i:int|None=None, **kwargs): return UPat(Ops.GEP, None, (self,), (i,) if i is not None else None, **kwargs) + def load(self, *src:UPat, **kwargs): return UPat(Ops.LOAD, src=(self,)+src, **kwargs) + def store(self, *src:UPat, **kwargs): return UPat(Ops.STORE, dtypes.void, (self,)+src, **kwargs) + def assign(self, x:UPat, **kwargs): return UPat(Ops.ASSIGN, self.dtype, (self,x), **kwargs) + def reduce(self, *src:UPat, **kwargs): return UPat(Ops.REDUCE, self.dtype, src=(self,)+src, **kwargs) + def fuse(self): return self.alu(Ops.FUSE) + def or_broadcasted(self, **kwargs): return UPat.any(self, UPat(Ops.VECTORIZE, self.dtype, src=self, **kwargs)) + + def const_like(self, b:ConstLike): return UPat.const(self.dtype, cast(ConstType, b)) + def alu(self, op:Ops, *src:UPat): + asrc = (self,)+src + return UPat(op, dtypes.bool if op in {Ops.CMPLT, Ops.CMPNE} else asrc[-1].dtype, list(asrc) if op in GroupOp.Commutative else asrc) + + def printable(self:UPat) -> str: + try: return lines(self.location[0])[self.location[1]-1].strip() + except FileNotFoundError: return "" + + def __repr__(self): + def rep(x): + form = "UPat(%s, %s, name=%s, dtype=%s, allow_any_len=%s, src=%s)" + return form % (None if x.op is None else ('(%s)'%', '.join(map(str, x.op))), x.arg, repr(x.name), + set(x.dtype) if x.dtype else None, not x.strict_length, "[%s]" if x.src and len(x.src)>1 else ("(%s)" if x.src else "%s")) + return pretty_print(self, rep, srcfn=lambda x:None if x.src is None else [next(x.src[0])] if isinstance(x.src[0], itertools.repeat) else x.src[0]) + + def match(self:UPat, uop:UOp, store:dict[str, UOp]) -> list[dict[str, UOp]]: + if (self.op is not None and uop.op not in self.op) or \ + (self.name is not None and store.setdefault(self.name, uop) is not uop) or \ + (self.dtype is not None and uop.dtype not in self.dtype and uop.dtype.scalar() not in self.dtype) or \ + (self.arg is not None and self.arg != uop.arg) or \ + (len(uop.src) < self.required_len) or \ + (self.strict_length and len(uop.src) != self.required_len): return [] + if self.src is None: return [store] + res: list[dict[str, UOp]] = [] + for vp in self.src: + stores, new_stores = [store.copy()], [] + for uu, vv in zip(uop.src, vp): + for s in stores: new_stores.extend(vv.match(uu, s)) + stores, new_stores = new_stores, [] + res.extend(stores) + return res + +class UPatAny(UPat): + def match(self:UPat, uop:UOp, store:dict[str, UOp]) -> list[dict[str, UOp]]: + matches = [x.match(uop, store.copy()) for x in self.src[0]] + return flatten([x for x in matches if x is not None]) + +def deconstruct_function(fxn:Callable) -> tuple: + new_globals = {k:v for k,v in fxn.__globals__.items() if k in fxn.__code__.co_names} + for co in fxn.__code__.co_consts: + if isinstance(co, types.CodeType): new_globals.update({k:v for k,v in fxn.__globals__.items() if k in co.co_names}) + # NOTE: optional round trip through pickle! + assert fxn.__closure__ is None, "closures are not supported in pattern matchers" + ret = fxn.__code__, new_globals, fxn.__name__, fxn.__defaults__ + return pickle.loads(pickle.dumps(ret)) if getenv("TEST_PICKLE") else ret + +@functools.cache +def upat_interpret(p:UPat, fxn:Callable) -> Callable: + real_fxn = types.FunctionType(*deconstruct_function(fxn)) + if 'ctx' in inspect.signature(real_fxn).parameters: + def universal_match(uop, ctx): + for match in p.match(uop, {}): + if (ret:=real_fxn(ctx=ctx, **match)) is not None: return ret # pylint: disable=not-callable + return None + else: + def universal_match(uop, _): + for match in p.match(uop, {}): + if (ret:=real_fxn(**match)) is not None: return ret # pylint: disable=not-callable + return None + return universal_match + +class PatternMatcher: + def __init__(self, patterns:Sequence[tuple[UPat, Callable|tuple]], compiled=bool(getenv("UPAT_COMPILE", 1))): + if compiled: from tinygrad.uop.upat import upat_compile + # if this comes from a pickle, we reconstruct the lambda functions here + self.patterns:list[tuple[UPat, Callable]] = [(p,types.FunctionType(*fxn) if isinstance(fxn, tuple) else fxn) for p,fxn in patterns] + # NOTE: use of DefaultDict here is very dangerous! all keys will live for the lifetime of the PatternMatcher! + self.pdict: dict[Ops, list[tuple[UPat, Callable, set]]] = {} + # uop is required, arg is optional + for p,fxn in self.patterns: + assert p.op is not None + if compiled and (match:=upat_compile(p, fxn)) is not None: pass # pylint: disable=E0606 + else: match = upat_interpret(p, fxn) + for uop in p.op: self.pdict.setdefault(uop, []).append((p, match, p.early_reject)) + + def __reduce__(self): return PatternMatcher, ([(x,deconstruct_function(fxn) if fxn.__name__ == "" else fxn) for x,fxn in self.patterns],) + + @functools.cache # pylint: disable=method-cache-max-size-none + def __add__(self, more:PatternMatcher): return PatternMatcher(self.patterns+more.patterns) + + def rewrite(self, uop:UOp, ctx=None) -> UOp|None: + ler = {u.op for u in uop.src} + for _,match,early_reject in self.pdict.get(uop.op, []): + if not early_reject.issubset(ler): continue + if (ret:=match(uop, ctx)) is not None: return ret + return None + +# *** tracking pattern matcher *** + +TRACK_MATCH_STATS = ContextVar("TRACK_MATCH_STATS", 2 if getenv("VIZ") else 0) +match_stats:dict[UPat, list[Union[int, float]]] = dict() +@dataclass(frozen=True) +class TrackedGraphRewrite: + loc: tuple[str, int] # location that called graph_rewrite + sink: UOp # the sink input to graph_rewrite + bottom_up: bool + matches: list[tuple[UOp, UOp, UPat]] # before+after of all the matches + name: str|None + depth: int +tracked_keys:list[Any] = [] +tracked_ctxs:list[list[TrackedGraphRewrite]] = [] +_name_cnt:dict[str, int] = {} +def track_rewrites(named=False, name_fxn:Callable|None=None): + def _decorator(func): + def __wrapper(*args, **kwargs): + if TRACK_MATCH_STATS >= 2: + if (count_names:=(named or name_fxn or not args)): _name_cnt[func.__name__] = _name_cnt.get(func.__name__, 0)+1 + tracked_keys.append(f"{func.__name__}_{_name_cnt[func.__name__]}" if count_names else args[0]) + tracked_ctxs.append([]) + ret = func(*args, **kwargs) + if TRACK_MATCH_STATS >= 2 and name_fxn is not None: tracked_keys[-1] = f"{name_fxn(ret)} n{_name_cnt[func.__name__]}" + return ret + return __wrapper + return _decorator + +active_rewrites:list[TrackedGraphRewrite] = [] +def track_matches(func): + def _track_func(*args, **kwargs): + if tracking:=(TRACK_MATCH_STATS >= 2 and tracked_ctxs): + loc = ((frm:=sys._getframe(1)).f_code.co_filename, frm.f_lineno) + depth = len(active_rewrites) + tracked_ctxs[-1].append(ctx:=TrackedGraphRewrite(loc, args[0], kwargs.get("bottom_up", False),[], kwargs.get("name", None), depth)) + active_rewrites.append(ctx) + ret = func(*args, **kwargs) + if tracking: active_rewrites.pop() + return ret + return _track_func + +class TrackedPatternMatcher(PatternMatcher): + def rewrite(self, uop:UOp, ctx=None) -> UOp|None: + ret = None + ler = {u.op for u in uop.src} + for p,match,early_reject in self.pdict.get(uop.op, []): + if p not in match_stats: match_stats[p] = [0,0,0.0,0.0] + st = time.perf_counter() + if not early_reject.issubset(ler): + match_stats[p][2] += time.perf_counter()-st + continue + match_stats[p][1] += 1 + if (ret:=match(uop, ctx)) is not None: + match_stats[p][0] += 1 + match_stats[p][3] += (et:=time.perf_counter()-st) + if TRACK_MATCH_STATS >= 3: print(f"{et*1e6:7.2f} us -- ", p.printable()) + if TRACK_MATCH_STATS >= 2 and isinstance(ret, UOp) and active_rewrites: active_rewrites[-1].matches.append((uop, ret, p)) + return ret + match_stats[p][2] += time.perf_counter()-st + return None + +if TRACK_MATCH_STATS: + PatternMatcher = TrackedPatternMatcher # type: ignore + import atexit + @atexit.register + def print_match_stats(): + if TRACK_MATCH_STATS >= 2: + with open(fn:=temp("rewrites.pkl", append_user=True), "wb") as f: + print(f"rewrote {len(tracked_ctxs)} graphs and matched {sum(len(r.matches) for x in tracked_ctxs for r in x)} times, saved to {fn}") + with Context(PICKLE_BUFFERS=0): pickle.dump((tracked_keys, tracked_ctxs), f) + if getenv("VIZ"): launch_viz("VIZ", temp("rewrites.pkl", append_user=True)) + if getenv("PRINT_MATCH_STATS", 1): + ret = [0,0,0.0,0.0] + for k,v in sorted(list(match_stats.items()), key=lambda x: x[1][2]+x[1][3]): + loc_str = f"{k.location[0].split('/')[-1]}:{k.location[1]}" + if v[1] != 0: print(f"{v[0]:6d} / {v[1]:7d} -- {v[3]*1000.:9.2f} / {(v[2]+v[3])*1000.:9.2f} ms -- {loc_str:20s}", k.printable()) + ret = [x+y for x,y in zip(ret, v)] + print(f"{ret[0]:6d} / {ret[1]:7d} -- {ret[3]*1000.:9.2f} / {(ret[2]+ret[3])*1000.:9.2f} ms -- TOTAL") + +def launch_viz(env_str:str, data:str): + os.environ[env_str] = "0" + os.environ[f"{env_str}_DATA"] = data + if not int(os.getenv("VIZ", "0")) and not int(os.getenv("PROFILE", "0")): + args = ['--kernels', getenv("VIZ_DATA", "")] if getenv("VIZ_DATA", "") else [] + args += ['--profile', getenv("PROFILE_DATA", "")] if getenv("PROFILE_DATA", "") else [] + os.execv(sys.executable, [sys.executable] + [os.path.join(os.path.dirname(__file__), "../", "viz", "serve.py")] + args) + +# *** simple graph rewrite engine *** + +class RewriteContext: + def __init__(self, pm, ctx=None): + self.pm: PatternMatcher = pm + self.ctx = ctx + self.replace: dict[UOp, UOp] = {} + def top_down_rewrite(self, n:UOp) -> UOp: + if (rn := self.replace.get(n)) is not None: return rn + new_src = tuple([self.top_down_rewrite(x) for x in n.src]) + new_n = self.pm.rewrite(n, self.ctx) if new_src == n.src else UOp(n.op, n.dtype, new_src, n.arg) + self.replace[n] = ret = n if new_n is None else self.top_down_rewrite(new_n) + return ret + def bottom_up_rewrite(self, n:UOp) -> UOp: + if (rn := self.replace.get(n)) is not None: return rn + new_n: UOp|None = n + while new_n is not None: last_n, new_n = new_n, self.pm.rewrite(new_n, self.ctx) + new_src = tuple([self.bottom_up_rewrite(x) for x in last_n.src]) + self.replace[n] = ret = last_n if new_src == last_n.src else self.bottom_up_rewrite(UOp(last_n.op, last_n.dtype, new_src, last_n.arg)) + return ret + +@track_matches +def graph_rewrite(sink:UOp, pm:PatternMatcher, ctx=None, bottom_up=False, name=None) -> UOp: + rewrite_ctx = RewriteContext(pm, ctx) + return rewrite_ctx.bottom_up_rewrite(sink) if bottom_up else rewrite_ctx.top_down_rewrite(sink) + +@track_matches +def graph_rewrite_map(sink:UOp, pm:PatternMatcher, ctx=None, bottom_up=False, name=None, input_map:dict[UOp, UOp]|None=None) -> dict[UOp, UOp]: + rewrite_ctx = RewriteContext(pm, ctx) + new_map = {k:(rewrite_ctx.bottom_up_rewrite(k) if bottom_up else rewrite_ctx.top_down_rewrite(k)) for k in list(sink.toposort())[::-1]} + all_metadata.update((v, k.metadata) for k,v in new_map.items() if k.metadata is not None) + if input_map is not None: + for k,v in input_map.items(): new_map[k] = new_map.get(v,v) + return new_map + +def sint_to_uop(x:sint, dtype:DType=dtypes.int) -> UOp: return UOp.const(dtype, x) if isinstance(x, int) else x + +_substitute = PatternMatcher([(UPat(tuple(Ops), name="x"), lambda ctx,x: ctx.get(x,None))]) + +# for debug +syms = { Ops.ADD: "+", Ops.SUB: "-", Ops.IDIV: "//", Ops.MOD: "%", Ops.SHL: "<<", Ops.SHR: ">>", + Ops.MUL: "*", Ops.CMPLT: "<", Ops.CMPNE: "!=", Ops.AND: "&", Ops.OR: "|", Ops.XOR: "^"} +renderer = PatternMatcher([ + (UPat((Ops.DEFINE_VAR, Ops.SPECIAL), name="x"), lambda x: UOp(Ops.NOOP, arg=x.arg[0])), + (UPat(Ops.RANGE, name="x"), lambda x: UOp(Ops.NOOP, arg=f"ridx{x.arg}")), + (UPat((Ops.CONST, Ops.VCONST), name="x"), lambda x: UOp(Ops.NOOP, arg=str(x.arg))), + (UPat(Ops.UNROLL, name="x"), lambda x: UOp(Ops.NOOP, arg=f"UNROLL({x.src[0].arg}, {x.arg})")), + (UPat(Ops.CAST, name="x"), lambda x: UOp(Ops.NOOP, arg=f"({str(x.dtype)[7:]})({x.src[0].arg})")), + (UPat(Ops.LOAD), lambda: UOp(Ops.NOOP, arg="load")), + (UPat(Ops.BIND, src=UPat(Ops.NOOP), name="x"), lambda x: x.src[0]), + #(UPat(Ops.BIND, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"{x.src[0].arg}[={x.src[1].arg}]")), + (UPat(Ops.NEG, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"(-{x.src[0].arg})")), + (UPat(Ops.MAX, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"max({x.src[0].arg}, {x.src[1].arg})")), + (UPat(Ops.MULACC, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[0].arg}*{x.src[1].arg}+{x.src[2].arg})")), + (UPat(Ops.WHERE, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[1].arg} if {x.src[0].arg} else {x.src[2].arg})")), + (UPat(GroupOp.ALU, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"({x.src[0].arg}{syms[x.op]}{x.src[1].arg})")), +]) +renderer_infer = PatternMatcher([ + (UPat(Ops.MOD, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"cmod({x.src[0].arg}, {x.src[1].arg})")), + (UPat(Ops.IDIV, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=f"cdiv({x.src[0].arg}, {x.src[1].arg})")), + *renderer.patterns +]) + +# *** what was symbolic.py *** + +sint = Union[int, UOp] +Variable = UOp + +ConstLike = Union[ConstType, Variable, tuple[ConstType, ...]] diff --git a/tinygrad_repo/tinygrad/uop/spec.py b/tinygrad_repo/tinygrad/uop/spec.py new file mode 100644 index 0000000000..0cf5d58f3f --- /dev/null +++ b/tinygrad_repo/tinygrad/uop/spec.py @@ -0,0 +1,217 @@ +from typing import cast, Callable +from tinygrad.uop.ops import PatternMatcher, UPat, GroupOp, Ops, UOp, print_uops, python_alu, graph_rewrite, resolve +from tinygrad.dtype import DType, ImageDType, dtypes, PtrDType +from tinygrad.helpers import all_same, prod, DEBUG, IGNORE_OOB, Context +try: + import z3 + + # IDIV is truncated division but z3 does floored division; mod by power of two sometimes uses Ops.AND + def z3_cdiv(a,b): return z3.If(a<0, (a+(b-1))/b, a/b) + z3_alu: dict[Ops, Callable] = python_alu | {Ops.MOD: lambda a,b: a-z3_cdiv(a,b)*b, Ops.IDIV: z3_cdiv, Ops.SHR: lambda a,b: a/(2**b.as_long()), + Ops.SHL: lambda a,b: a*(2**b.as_long()), Ops.AND: lambda a,b: a%(b+1) if isinstance(b, z3.ArithRef) else a&b, Ops.WHERE: z3.If} + def create_bounded(name:str, vmin, vmax, solver:z3.Solver) -> z3.ArithRef: + s = z3.Int(name, ctx=solver.ctx) + solver.add(vmin <= s, s <= vmax) + return s + + # ctx is (solver, load_number_dict) + z3_renderer = PatternMatcher([ + # Ops.SPECIAL can have symbolic arg but it wont be in the toposort beacuse its not a src, we need to add it manually + (UPat(Ops.SPECIAL, src=(), name="x"), lambda x: UOp(Ops.SPECIAL, arg=x.arg[0], src=(x.ufix(x.arg[1]),))), + (UPat(Ops.SPECIAL, src=UPat(Ops.NOOP), name="x"), lambda x,ctx: UOp(Ops.NOOP, arg=create_bounded(x.arg, 0, x.src[0].arg-1, ctx[0]))), + (UPat(Ops.DEFINE_VAR, name="x"), lambda x,ctx: UOp(Ops.NOOP, arg=create_bounded(x.arg[0], x.arg[1], x.arg[2], ctx[0]))), + (UPat(Ops.RANGE, name="x"), lambda x,ctx: UOp(Ops.NOOP, arg=create_bounded(f"ridx{x.arg}", 0, x.src[0].arg-1, ctx[0]))), + (UPat(Ops.LOAD, name="x"), lambda x,ctx: UOp(Ops.NOOP, arg=create_bounded(f"load{ctx[1].setdefault(x, len(ctx[1]))}", x.vmin, x.vmax, ctx[0]))), + (UPat(Ops.CONST, name="x"), lambda x,ctx: UOp(Ops.NOOP, arg=(z3.BoolVal if dtypes.is_bool(x.dtype) else z3.IntVal)(x.arg, ctx=ctx[0].ctx))), + (UPat(Ops.CAST, name="x"), lambda x: x.src[0]), + (UPat(GroupOp.ALU, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=z3_alu[x.op](*(s.arg for s in x.src)))), + ]) + + z3_imported = True +except (ImportError, AttributeError): z3_imported = False + +buffer_spec = PatternMatcher([ + (UPat(Ops.UNIQUE, dtypes.void, ()), lambda: True), + (UPat(Ops.DEVICE, dtypes.void, (), name="d"), lambda d: + isinstance(d.arg, str) or (isinstance(d.arg, tuple) and all(isinstance(s, str) for s in d.arg))), + (UPat(Ops.BUFFER, src=(UPat(Ops.UNIQUE), UPat(Ops.DEVICE)), allow_any_len=True, name="buf"), + lambda buf: isinstance(buf.arg, int) and isinstance(buf.dtype, (DType, ImageDType))), + (UPat(Ops.BUFFER_VIEW, src=(UPat(Ops.BUFFER),), name="buf_view"), + lambda buf_view: isinstance(buf_view.arg, tuple) and len(buf_view.arg) == 2 and all(isinstance(arg, (int, UOp)) for arg in buf_view.arg)), +]) + +def validate_kernel(k:UOp): + assert k.arg.ast.op in {Ops.COPY, Ops.BUFFER_VIEW, Ops.SINK}, f"must end with SINK/COPY/BUFFER_VIEW {k.arg}" + if k.arg.ast.op is Ops.SINK: assert all(s.op is Ops.STORE for s in k.arg.ast.src), f"SINK must end with STORE {k.arg.ast}" + return True + +assign_spec = PatternMatcher([ + # KERNEL can attach to an ASSIGN to describe the compute required to realize a BUFFER + (UPat(Ops.KERNEL, src=UPat((Ops.BUFFER, Ops.BUFFER_VIEW, Ops.ASSIGN)), name="k"), validate_kernel), + + # ASSIGN has a target and a value. It can also optionally depend on other assigns + (UPat(Ops.ASSIGN, name="x"), lambda x: len(x.src) >= 2 and all(s.op is Ops.ASSIGN for s in x.src[2:])), +]) + +# *** this is the spec of a Tensor in UOp *** + +tensor_uop_spec = buffer_spec+assign_spec+PatternMatcher([ + (UPat(GroupOp.Movement, name="mv", src=(UPat.var("x"),)), + # naturally correct + lambda mv,x: (isinstance(mv.arg, tuple) and mv.dtype == x.dtype) or + # "make things that can't be images not images" can change the buffer dtype + # this is fine as long as it's a realized buffer and base dtypes match. + ((isinstance(mv.dtype, ImageDType) or isinstance(x.dtype, ImageDType)) and x.dtype.base == mv.dtype.base and x.base.op is Ops.BUFFER)), + (UPat(Ops.VIEW, src=(UPat.var("x"),)), lambda x: x.base.op in {Ops.BUFFER, Ops.BUFFER_VIEW, Ops.ASSIGN, Ops.CONST, Ops.DEVICE}), + + # Tensor variable bindings + (UPat(Ops.BIND, dtypes.int, (UPat(Ops.DEFINE_VAR), UPat.cvar(dtype=dtypes.int)), arg=None), lambda: True), + + # Tensor const has a device and an unmasked ShapeTracker of stride 0 + (UPat(Ops.CONST, src=(UPat(Ops.VIEW, name="st", src=(UPat(Ops.DEVICE),)),)), + lambda st: st.st.views[0].mask is None and len(st.st.views) == 1 and all(s == 0 for s in st.st.views[0].strides)), + + # DETACH and CONTIGUOUS change how we interpret the source UOp + # CONTIGUOUS ensures the source UOp realizes + (UPat((Ops.DETACH, Ops.CONTIGUOUS, Ops.CONTIGUOUS_BACKWARD, Ops.FUSE), name="root", src=(UPat.var("x"),), arg=None), + lambda root,x: root.dtype == x.dtype), + + # COPY/ALLREDUCE/MULTI + (UPat(Ops.COPY, name="copy", src=(UPat.var("x"), UPat(Ops.DEVICE))), lambda copy,x: copy.dtype == x.dtype), + (UPat(Ops.ALLREDUCE, name="red", src=(UPat.var("x"), UPat(Ops.DEVICE))), lambda red,x: red.dtype == x.dtype and isinstance(red.arg, Ops)), + (UPat(Ops.MULTI, name="multi"), lambda multi: all(x.dtype == multi.dtype for x in multi.src) and isinstance(multi.arg, int)), +]) + +# ***** uop type spec ***** + +def validate_index(idx:UOp, mask:UOp|None=None): + if IGNORE_OOB or isinstance(idx.dtype, ImageDType) or (sz := cast(PtrDType, idx.src[0].dtype).size) == -1: return True + # We can use UOp min/max to do a faster check, but it can give false positive since its not an exact bound and doesn't consider the mask + if 0<=idx.src[1].vmin and idx.src[1].vmax + (UPat(Ops.LOAD, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW))), lambda: True), + (UPat(Ops.LOAD, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW), UPat(Ops.STORE))), lambda: True), + + # early STORE has a + (UPat(Ops.STORE, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(Ops.VIEW), UPat())), lambda: True), + + # **** new style load/store **** + + # INDEX is used in new style load/store + # INDEX takes a + (UPat(Ops.INDEX, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat()), name="idx"), validate_index), + (UPat(Ops.INDEX, src=(UPat((Ops.DEFINE_GLOBAL, Ops.DEFINE_LOCAL)), UPat(), UPat(dtype=dtypes.bool, name="mask")), name="idx"), validate_index), + + # LOAD takes a + (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)),)), lambda: True), + (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)), UPat((Ops.IF, Ops.BARRIER)))), lambda: True), + (UPat(Ops.LOAD, src=(UPat((Ops.INDEX, Ops.CAST)), UPat.var("alt")), name="ld"), lambda ld,alt: ld.dtype == alt.dtype), + + # STORE takes a + (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat())), lambda: True), + (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat(), UPat(dtype=dtypes.bool))), lambda: True), + (UPat(Ops.STORE, dtype=dtypes.void, src=(UPat((Ops.INDEX, Ops.CAST)), UPat(), UPat(Ops.IF))), lambda: True), + + # most ALUs have all matching dtypes, except CMPLT, CMPNE, and WHERE + (UPat(Ops.WHERE, name="w", src=(UPat(dtype=dtypes.bool), UPat.var("x"), UPat.var("y"))), lambda w,x,y: w.dtype == x.dtype == y.dtype), + (UPat((Ops.CMPLT, Ops.CMPNE), dtype=dtypes.bool, src=(UPat.var("x"), UPat.var("y"))), lambda x,y: x.dtype.base == y.dtype.base), + # and SHL/SHR, the shift distance can be an int + (UPat((Ops.SHL, Ops.SHR), src=(UPat.var("x"), UPat.var("y")), name="a"), lambda a,x,y: a.dtype == x.dtype and y.dtype in (x.dtype, dtypes.uint)), + (UPat((Ops.IDIV, Ops.MOD), name="x"), lambda x: None if dtypes.is_int(x.dtype) else False), + (UPat(GroupOp.ALU, name="x"), lambda x: all(x.dtype.base == y.dtype.base for y in x.src)), + + (UPat(Ops.ASSIGN, src=(UPat((Ops.DEFINE_ACC, Ops.DEFINE_GLOBAL)), UPat())), lambda: True), + (UPat(Ops.ENDRANGE, dtype=dtypes.void, src=(UPat(Ops.RANGE),)), lambda: True), + + # WMMA has a + (UPat(Ops.WMMA, src=(UPat(), UPat(), UPat()), name="x"), lambda x: isinstance(x.arg, tuple) and len(x.arg) == 8), + (UPat(Ops.CONTRACT, name="x"), lambda x: x.dtype.count == prod(y[1] for y in x.arg)), + (UPat(Ops.UNROLL, name="x"), lambda x: x.src[0].dtype.count == prod(y[1] for y in x.arg)), + + # if has a + (UPat(Ops.IF, dtype=dtypes.void, src=(UPat(),)), lambda: True), + (UPat(Ops.IF, dtype=dtypes.void, src=(UPat(), UPat(Ops.BARRIER))), lambda: True), + (UPat(Ops.ENDIF, dtype=dtypes.void, src=(UPat(Ops.IF),)), lambda: True), + + (UPat(Ops.REDUCE_AXIS, name="x"), lambda x: isinstance(x.arg, tuple) and len(x.arg) >= 2 and x.arg[0] in {Ops.ADD, Ops.MUL, Ops.MAX}), + (UPat(Ops.GEP, src=(UPat.var("src"),), name="gep"), lambda gep,src: gep.dtype == src.dtype.scalar()), + (UPat(Ops.VECTORIZE, name="x"), lambda x: len(x.src)>1 and len(x.src) == x.dtype.count and all(x.dtype == y.dtype.vec(len(x.src)) for y in x.src)), + (UPat((Ops.BITCAST, Ops.CAST), src=(UPat(),), name="x"), lambda x: x.arg is None), + (UPat(Ops.BARRIER, dtypes.void, src=UPat(Ops.STORE, allow_any_len=True)), lambda: True), # NOTE: all pointers must be local + (UPat(Ops.BARRIER, dtypes.void), lambda: True), # BARRIERs can also happen at the end of loops + + # NOTE: for testing, we let sinks be anything + #(UPat(Ops.SINK, src=UPat(Ops.STORE)), lambda: True), + (UPat(Ops.SINK, dtypes.void), lambda: True), + (UPat((Ops.NOOP, Ops.CUSTOMI, Ops.CUSTOM)), lambda: True), + + # PTX LOAD/STORE + (UPat((Ops.LOAD, Ops.STORE), src=(UPat(dtype=dtypes.int64),), allow_any_len=True), lambda: True), +]) + +# *** schedule spec only allows buffers, assigns and kernels in the graph *** + +sched_spec = buffer_spec+assign_spec+PatternMatcher([ + (UPat(GroupOp.All-{Ops.SINK}), lambda: False), +]) + +# *** this is the UOp shape spec *** + +def verify_sink_dims(sink:UOp): + if not all_same([s.shape for s in sink.src]): return False + for dims in zip(*[x.shape for x in sink.toposort() if x.st is not None]): + if len(n_dims:={s for s in dims if resolve(s!=1)}) > 1: + print(f"# INVALID KERNEL DIMS: can only have 1 or n in each dimension: {n_dims}") + return False + +shape_spec = PatternMatcher([ + # shapes must have either 1 or n in each dimension + (UPat(Ops.SINK, src=UPat(Ops.STORE), name="sink"), verify_sink_dims), + # all parent UOps must have the same shape + (UPat(GroupOp.All-{Ops.SINK}, name="root"), lambda root: all_same([x.shape for x in root.src if x.st is not None])), +]) + +# ***** uop helpers ***** + +def type_verify(uops:list[UOp], extra_spec:PatternMatcher|None=None): + check_spec = (extra_spec+spec) if extra_spec is not None else spec + for i,u in enumerate(uops): + with Context(TRACK_MATCH_STATS=0): ret = check_spec.rewrite(u) + if cast(bool|None, ret) is not True: + if DEBUG >= 3: print_uops(uops) + raise RuntimeError(f"UOp verification failed at {i} on {u.op} {u.dtype} {len(u.src)} {[x.op for x in u.src]} {u.arg}") diff --git a/tinygrad_repo/tinygrad/uop/upat.py b/tinygrad_repo/tinygrad/uop/upat.py new file mode 100644 index 0000000000..090de21357 --- /dev/null +++ b/tinygrad_repo/tinygrad/uop/upat.py @@ -0,0 +1,163 @@ +from typing import Any, Callable +import itertools, inspect, functools, types +from tinygrad.helpers import partition, dedup, Context +from tinygrad.uop.ops import UPat, UPatAny, UOp, Ops, PatternMatcher, graph_rewrite, deconstruct_function + +class UPatCompileError(Exception): pass + +# **** UPat compiled **** + +def _get_clause(self:UPat, base:UOp, depth=0) -> UOp: + if isinstance(self, UPatAny): + assert len(self.src) == 1 + return UOp(Ops.AND, src=(UOp(Ops.OR, src=tuple(_get_clause(s, base, depth) for s in self.src[0])),)) + # build the and_clause for acceptance + and_clause:list[UOp] = [] + if self.op is not None: + if len(self.op) > 1: and_clause.append(UOp(Ops.CUSTOM, src=(base, UOp(Ops.BIND, arg=tuple(int(x) for x in self.op))), arg="{0}.op in {1}")) + else: and_clause.append(UOp(Ops.CUSTOM, src=(base,), arg="{0}.op == "+str(self.op[0].value))) + if self.arg is not None: + if isinstance(self.arg, int): and_clause.append(UOp(Ops.CUSTOM, src=(base,), arg="{0}.arg == "+str(int(self.arg)))) + else: and_clause.append(UOp(Ops.CUSTOM, src=(base, UOp(Ops.BIND, arg=self.arg)), arg="{0}.arg == {1}")) + if self.strict_length or self.required_len > 0: + and_clause.append(UOp(Ops.CUSTOM, src=(base,), arg=("len({0}.src)"+(" == " if self.strict_length else " >= ")+str(self.required_len)))) + if self.name is not None: and_clause.append(UOp(Ops.ASSIGN, src=(UOp(Ops.DEFINE_VAR, arg=self.name), base))) + if self.dtype is not None: + if len(self.dtype) > 1: + and_clause.append(UOp(Ops.CUSTOM, src=(base, UOp(Ops.BIND, arg=tuple(self.dtype))), arg="({0}.dtype in {1} or {0}.dtype._scalar in {1})")) + else: and_clause.append(UOp(Ops.CUSTOM, src=(base, UOp(Ops.BIND, arg=self.dtype[0])), arg="({0}.dtype == {1} or {0}.dtype._scalar == {1})")) + if self.src is not None: + # single match + if len(self.src) == 1 and isinstance(self.src[0], tuple): + and_clause += [_get_clause(s, base.gep(i), depth) for i,s in enumerate(self.src[0])] + # repeat match + elif len(self.src) == 1 and isinstance(self.src[0], itertools.repeat): + it = UOp(Ops.NOOP, arg=f"ituop{depth}") + match = _get_clause(next(self.src[0]), it, depth+1) + and_clause.append(UOp(Ops.RANGE, src=(match, it, base), arg="all([{0} for {1} in {2}.src])")) + # multi match (fork) + elif len(self.src) > 1 and all(isinstance(x, tuple) for x in self.src): + fork_cond = [UOp(Ops.AND, src=tuple([_get_clause(s, base.gep(i), depth) for i,s in enumerate(ss)])) for ss in self.src] + and_clause.append(UOp(Ops.OR, src=tuple(fork_cond))) + else: raise RuntimeError("broken") + return UOp(Ops.AND, src=tuple(and_clause)) + +# *** pattern matcher *** + +def do_process_and(a:UOp) -> UOp|None: + found = False + new_src:list[UOp] = [] + or_clause:list[UOp] = [] + + # remove any nested ANDs, extract or clauses + for x in a.src: + if x.op is Ops.AND: + new_src.extend(x.src) + found = True + elif x.op is Ops.OR: or_clause.append(x) + else: new_src.append(x) + + # too big to compile + if len(or_clause) >= 4: raise UPatCompileError("too big to compile") + + # one or clause max + if len(or_clause) > 1: + # need the product of the or clauses + or_clause = [UOp(Ops.OR, src=tuple([UOp(Ops.AND, src=x) for x in itertools.product(*[x.src for x in or_clause])]))] + found = True + + # handle assigns + assigns, new_src = partition(new_src, lambda x: x.op is Ops.ASSIGN) + if len(assigns): + if len(or_clause): + # push assigns to the top if we have an or_clause + assert len(or_clause) == 1 and all(x.op is Ops.AND for x in or_clause[0].src) + or_clause = [UOp(Ops.OR, src=tuple([x.replace(src=x.src+tuple(assigns)) for x in or_clause[0].src]))] + found = True + else: + # check for duplicate assigns + dict_assigns: dict[UOp, UOp] = {} + for a in assigns: + if a.src[0] in dict_assigns: + # duplicate assign is a compare + new_src.append(UOp(Ops.CMPNE, src=(dict_assigns[a.src[0]], a.src[1]))) + found = True + else: + dict_assigns[a.src[0]] = a.src[1] + # put the assigns back + for k,v in dict_assigns.items(): new_src.append(UOp(Ops.ASSIGN, src=(k,v))) + + # reassemble, if there's any deduping to do, do it + if len(dretand:=dedup(new_src+or_clause)) != len(new_src)+len(or_clause): found = True + return UOp(Ops.AND, src=tuple(dretand)) if found else None + +# processor +pm_proc = PatternMatcher([(UPat(Ops.AND, name="a"), do_process_and)], compiled=False) + +# renderer +def wrap(ctx, x) -> UOp: + ctx[ret:=f"a{len(ctx)}"] = x.arg + return UOp(Ops.NOOP, arg=ret) + +pm_renderer = PatternMatcher([ + (UPat(Ops.BIND, name="x"), wrap), + + # CMPNE is actually equal + (UPat(Ops.CMPNE, name="x"), lambda x: UOp(Ops.CUSTOM, src=x.src, arg="{0} is {1}")), + + # RANGE can't have OR inside it + (UPat(Ops.RANGE, src=(UPat(Ops.AND, src=UPat(Ops.NOOP), name="x"), UPat(), UPat()), name="r"), + lambda r,x: r.replace(op=Ops.CUSTOM, src=(UOp(Ops.NOOP, arg="(" + ' and '.join(y.arg for y in x.src) + ")"),)+r.src[1:])), + + (UPat(Ops.CUSTOM, src=UPat(Ops.NOOP), name="x"), lambda x: UOp(Ops.NOOP, arg=x.arg.format(*[y.arg for y in x.src]))), + (UPat(Ops.GEP, src=UPat(Ops.NOOP, name="x"), name="g"), lambda x,g: x.replace(arg=x.arg+f".src[{g.arg[0]}]")) +], compiled=False) + +def _final_render(x:UOp, has_ctx:bool, depth=1) -> list[str]: + assert x.op is Ops.AND + and_pieces, assign_pieces = [], [] + or_pieces: list[str] = [] + for s in x.src: + if s.op is Ops.OR: + assert len(or_pieces) == 0 and len(s.src) >= 1 + for ss in s.src: or_pieces.extend(_final_render(ss, has_ctx, depth+1)) + elif s.op is Ops.ASSIGN: + assert s.src[0].op is Ops.DEFINE_VAR and s.src[1].op is Ops.NOOP + assign_pieces.append(f"{s.src[0].arg}={s.src[1].arg}") + elif s.op is Ops.NOOP: and_pieces.append(s.arg) + else: raise UPatCompileError(f"can't compile this {s}") + # if we have an or, render it + if len(or_pieces): + assert len(assign_pieces) == 0 + and_clause = ' and '.join(and_pieces) + return [f"{' '*depth}if {and_clause if len(and_clause) else 'True'}:"] + or_pieces + # if we don't, this is a final return + assign_clause = ', '.join((["ctx=ctx"] if has_ctx else [])+assign_pieces) + and_clause = ' and '.join(and_pieces + [f"(_ret:=_fxn({assign_clause})) is not None"]) + return [f"{' '*depth}if {and_clause}: return _ret"] + +def _get_code(self:UPat, has_ctx:bool): + ret = _get_clause(self, UOp(Ops.NOOP, arg="uop")) + try: + # TODO: this should be tracked in a "system" rewrite, not untracked or tracked with kernel + with Context(TRACK_MATCH_STATS=0): + ret = graph_rewrite(ret, pm_proc, name="process UPat") + dyn_lookup: dict[str, Any] = {} + out = graph_rewrite(ret, pm_renderer, ctx=dyn_lookup, name="compile UPat") + rendered = _final_render(out, has_ctx) + except UPatCompileError: + #print("FAILED", self, self.location) + return None + return '\n'.join([f"# match for {self.location}", "def compiled_match(uop, ctx):"] + rendered + [" return None"]), dyn_lookup + +@functools.cache +def upat_compile(self:UPat, fxn) -> Callable|None: + real_fxn = types.FunctionType(*deconstruct_function(fxn)) + code = _get_code(self, 'ctx' in inspect.signature(real_fxn).parameters) + if code is None: return None + code_str, dyn_lookup = code + globs = dyn_lookup.copy() + globs["_fxn"] = real_fxn + namespace: dict = {} + exec(code_str, globs, namespace) # pylint: disable=W0122 + return namespace["compiled_match"] diff --git a/tinygrad_repo/tinygrad/viz/README b/tinygrad_repo/tinygrad/viz/README index 4565529c67..ce46d461cf 100644 --- a/tinygrad_repo/tinygrad/viz/README +++ b/tinygrad_repo/tinygrad/viz/README @@ -3,7 +3,7 @@ GRAPH=1 JITGRAPH=1 (this restricts the graph...no need if we can select the schedules) GRAPHUOPS=1 most uses of DEBUG >= 3 -https://tiny-tools-client.vercel.app/ +tiny-tools and a viewer for: SAVE_SCHEDULE=1 diff --git a/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js b/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js deleted file mode 100644 index 23ccb89ff0..0000000000 --- a/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js +++ /dev/null @@ -1,2 +0,0 @@ -!function(e,t){"object"==typeof exports&&"undefined"!=typeof module?module.exports=t():"function"==typeof define&&define.amd?define(t):e.DOMPurify=t()}(this,function(){"use strict";function e(e,t){for(var n=t.length;n--;)"string"==typeof t[n]&&(t[n]=t[n].toLowerCase()),e[t[n]]=!0;return e}function t(e){var t={},n=void 0;for(n in e)Object.prototype.hasOwnProperty.call(e,n)&&(t[n]=e[n]);return t}function n(e){if(Array.isArray(e)){for(var t=0,n=Array(e.length);t0&&void 0!==arguments[0]?arguments[0]:A(),S=function(e){return o(e)};if(S.version="1.0.2",S.removed=[],!x||!x.document||9!==x.document.nodeType)return S.isSupported=!1,S;var k=x.document,w=!1,E=!1,O=x.document,L=x.DocumentFragment,M=x.HTMLTemplateElement,N=x.Node,_=x.NodeFilter,D=x.NamedNodeMap,R=void 0===D?x.NamedNodeMap||x.MozNamedAttrMap:D,C=x.Text,F=x.Comment,z=x.DOMParser,H=x.XMLHttpRequest,I=void 0===H?x.XMLHttpRequest:H,j=x.encodeURI,U=void 0===j?x.encodeURI:j;if("function"==typeof M){var W=O.createElement("template");W.content&&W.content.ownerDocument&&(O=W.content.ownerDocument)}var q=O,G=q.implementation,P=q.createNodeIterator,B=q.getElementsByTagName,X=q.createDocumentFragment,V=k.importNode,Y={};S.isSupported=G&&void 0!==G.createHTMLDocument&&9!==O.documentMode;var K=p,$=f,J=h,Q=g,Z=v,ee=b,te=y,ne=null,oe=e({},[].concat(n(r),n(i),n(a),n(l),n(s))),re=null,ie=e({},[].concat(n(c),n(d),n(u),n(m))),ae=null,le=null,se=!0,ce=!0,de=!1,ue=!1,me=!1,pe=!1,fe=!1,he=!1,ge=!1,ye=!1,ve=!1,be=!0,Te=!0,Ae={},xe=e({},["audio","head","math","script","style","template","svg","video"]),Se=e({},["audio","video","img","source","image"]),ke=e({},["alt","class","for","id","label","name","pattern","placeholder","summary","title","value","style","xmlns"]),we=null,Ee=O.createElement("form"),Oe=function(o){"object"!==(void 0===o?"undefined":T(o))&&(o={}),ne="ALLOWED_TAGS"in o?e({},o.ALLOWED_TAGS):oe,re="ALLOWED_ATTR"in o?e({},o.ALLOWED_ATTR):ie,ae="FORBID_TAGS"in o?e({},o.FORBID_TAGS):{},le="FORBID_ATTR"in o?e({},o.FORBID_ATTR):{},Ae="USE_PROFILES"in o&&o.USE_PROFILES,se=!1!==o.ALLOW_ARIA_ATTR,ce=!1!==o.ALLOW_DATA_ATTR,de=o.ALLOW_UNKNOWN_PROTOCOLS||!1,ue=o.SAFE_FOR_JQUERY||!1,me=o.SAFE_FOR_TEMPLATES||!1,pe=o.WHOLE_DOCUMENT||!1,ge=o.RETURN_DOM||!1,ye=o.RETURN_DOM_FRAGMENT||!1,ve=o.RETURN_DOM_IMPORT||!1,he=o.FORCE_BODY||!1,be=!1!==o.SANITIZE_DOM,Te=!1!==o.KEEP_CONTENT,te=o.ALLOWED_URI_REGEXP||te,me&&(ce=!1),ye&&(ge=!0),Ae&&(ne=e({},[].concat(n(s))),re=[],!0===Ae.html&&(e(ne,r),e(re,c)),!0===Ae.svg&&(e(ne,i),e(re,d),e(re,m)),!0===Ae.svgFilters&&(e(ne,a),e(re,d),e(re,m)),!0===Ae.mathMl&&(e(ne,l),e(re,u),e(re,m))),o.ADD_TAGS&&(ne===oe&&(ne=t(ne)),e(ne,o.ADD_TAGS)),o.ADD_ATTR&&(re===ie&&(re=t(re)),e(re,o.ADD_ATTR)),o.ADD_URI_SAFE_ATTR&&e(ke,o.ADD_URI_SAFE_ATTR),Te&&(ne["#text"]=!0),Object&&"freeze"in Object&&Object.freeze(o),we=o},Le=function(e){S.removed.push({element:e});try{e.parentNode.removeChild(e)}catch(t){e.outerHTML=""}},Me=function(e,t){S.removed.push({attribute:t.getAttributeNode(e),from:t}),t.removeAttribute(e)},Ne=function(e){var t=void 0,n=void 0;if(he&&(e=""+e),E){try{e=U(e)}catch(e){}var o=new I;o.responseType="document",o.open("GET","data:text/html;charset=utf-8,"+e,!1),o.send(null),t=o.response}if(w)try{t=(new z).parseFromString(e,"text/html")}catch(e){}return t&&t.documentElement||((n=(t=G.createHTMLDocument("")).body).parentNode.removeChild(n.parentNode.firstElementChild),n.outerHTML=e),B.call(t,pe?"html":"body")[0]};S.isSupported&&function(){var e=Ne('');e.querySelector("svg")||(E=!0);try{(e=Ne('

')).querySelector("svg img")&&(w=!0)}catch(e){}}();var _e=function(e){return P.call(e.ownerDocument||e,e,_.SHOW_ELEMENT|_.SHOW_COMMENT|_.SHOW_TEXT,function(){return _.FILTER_ACCEPT},!1)},De=function(e){return!(e instanceof C||e instanceof F)&&!("string"==typeof e.nodeName&&"string"==typeof e.textContent&&"function"==typeof e.removeChild&&e.attributes instanceof R&&"function"==typeof e.removeAttribute&&"function"==typeof e.setAttribute)},Re=function(e){return"object"===(void 0===N?"undefined":T(N))?e instanceof N:e&&"object"===(void 0===e?"undefined":T(e))&&"number"==typeof e.nodeType&&"string"==typeof e.nodeName},Ce=function(e,t,n){Y[e]&&Y[e].forEach(function(e){e.call(S,t,n,we)})},Fe=function(e){var t=void 0;if(Ce("beforeSanitizeElements",e,null),De(e))return Le(e),!0;var n=e.nodeName.toLowerCase();if(Ce("uponSanitizeElement",e,{tagName:n,allowedTags:ne}),!ne[n]||ae[n]){if(Te&&!xe[n]&&"function"==typeof e.insertAdjacentHTML)try{e.insertAdjacentHTML("AfterEnd",e.innerHTML)}catch(e){}return Le(e),!0}return!ue||e.firstElementChild||e.content&&e.content.firstElementChild||!/l&&e.setAttribute("id",i.value);else{if("INPUT"===e.nodeName&&"type"===r&&"file"===o&&(re[r]||!le[r]))continue;"id"===n&&e.setAttribute(n,""),Me(n,e)}if(s.keepAttr&&(!be||"id"!==r&&"name"!==r||!(o in O||o in Ee))){if(me&&(o=(o=o.replace(K," ")).replace($," ")),ce&&J.test(r));else if(se&&Q.test(r));else{if(!re[r]||le[r])continue;if(ke[r]);else if(te.test(o.replace(ee,"")));else if("src"!==r&&"xlink:href"!==r||0!==o.indexOf("data:")||!Se[e.nodeName.toLowerCase()]){if(de&&!Z.test(o.replace(ee,"")));else if(o)continue}else;}try{e.setAttribute(n,o),S.removed.pop()}catch(e){}}}Ce("afterSanitizeAttributes",e,null)}},He=function e(t){var n=void 0,o=_e(t);for(Ce("beforeSanitizeShadowDOM",t,null);n=o.nextNode();)Ce("uponSanitizeShadowNode",n,null),Fe(n)||(n.content instanceof L&&e(n.content),ze(n));Ce("afterSanitizeShadowDOM",t,null)};return S.sanitize=function(e,t){var n=void 0,o=void 0,r=void 0,i=void 0,a=void 0;if(e||(e="\x3c!--\x3e"),"string"!=typeof e&&!Re(e)){if("function"!=typeof e.toString)throw new TypeError("toString is not a function");if("string"!=typeof(e=e.toString()))throw new TypeError("dirty is not a string, aborting")}if(!S.isSupported){if("object"===T(x.toStaticHTML)||"function"==typeof x.toStaticHTML){if("string"==typeof e)return x.toStaticHTML(e);if(Re(e))return x.toStaticHTML(e.outerHTML)}return e}if(fe||Oe(t),S.removed=[],e instanceof N)1===(o=(n=Ne("\x3c!--\x3e")).ownerDocument.importNode(e,!0)).nodeType&&"BODY"===o.nodeName?n=o:n.appendChild(o);else{if(!ge&&!pe&&-1===e.indexOf("<"))return e;if(!(n=Ne(e)))return ge?null:""}he&&Le(n.firstChild);for(var l=_e(n);r=l.nextNode();)3===r.nodeType&&r===i||Fe(r)||(r.content instanceof L&&He(r.content),ze(r),i=r);if(ge){if(ye)for(a=X.call(n.ownerDocument);n.firstChild;)a.appendChild(n.firstChild);else a=n;return ve&&(a=V.call(k,a,!0)),a}return pe?n.outerHTML:n.innerHTML},S.setConfig=function(e){Oe(e),fe=!0},S.clearConfig=function(){we=null,fe=!1},S.addHook=function(e,t){"function"==typeof t&&(Y[e]=Y[e]||[],Y[e].push(t))},S.removeHook=function(e){Y[e]&&Y[e].pop()},S.removeHooks=function(e){Y[e]&&(Y[e]=[])},S.removeAllHooks=function(){Y={}},S}var r=["a","abbr","acronym","address","area","article","aside","audio","b","bdi","bdo","big","blink","blockquote","body","br","button","canvas","caption","center","cite","code","col","colgroup","content","data","datalist","dd","decorator","del","details","dfn","dir","div","dl","dt","element","em","fieldset","figcaption","figure","font","footer","form","h1","h2","h3","h4","h5","h6","head","header","hgroup","hr","html","i","img","input","ins","kbd","label","legend","li","main","map","mark","marquee","menu","menuitem","meter","nav","nobr","ol","optgroup","option","output","p","pre","progress","q","rp","rt","ruby","s","samp","section","select","shadow","small","source","spacer","span","strike","strong","style","sub","summary","sup","table","tbody","td","template","textarea","tfoot","th","thead","time","tr","track","tt","u","ul","var","video","wbr"],i=["svg","a","altglyph","altglyphdef","altglyphitem","animatecolor","animatemotion","animatetransform","audio","canvas","circle","clippath","defs","desc","ellipse","filter","font","g","glyph","glyphref","hkern","image","line","lineargradient","marker","mask","metadata","mpath","path","pattern","polygon","polyline","radialgradient","rect","stop","style","switch","symbol","text","textpath","title","tref","tspan","video","view","vkern"],a=["feBlend","feColorMatrix","feComponentTransfer","feComposite","feConvolveMatrix","feDiffuseLighting","feDisplacementMap","feFlood","feFuncA","feFuncB","feFuncG","feFuncR","feGaussianBlur","feMerge","feMergeNode","feMorphology","feOffset","feSpecularLighting","feTile","feTurbulence"],l=["math","menclose","merror","mfenced","mfrac","mglyph","mi","mlabeledtr","mmuliscripts","mn","mo","mover","mpadded","mphantom","mroot","mrow","ms","mpspace","msqrt","mystyle","msub","msup","msubsup","mtable","mtd","mtext","mtr","munder","munderover"],s=["#text"],c=["accept","action","align","alt","autocomplete","background","bgcolor","border","cellpadding","cellspacing","checked","cite","class","clear","color","cols","colspan","coords","crossorigin","datetime","default","dir","disabled","download","enctype","face","for","headers","height","hidden","high","href","hreflang","id","integrity","ismap","label","lang","list","loop","low","max","maxlength","media","method","min","multiple","name","noshade","novalidate","nowrap","open","optimum","pattern","placeholder","poster","preload","pubdate","radiogroup","readonly","rel","required","rev","reversed","role","rows","rowspan","spellcheck","scope","selected","shape","size","sizes","span","srclang","start","src","srcset","step","style","summary","tabindex","title","type","usemap","valign","value","width","xmlns"],d=["accent-height","accumulate","additivive","alignment-baseline","ascent","attributename","attributetype","azimuth","basefrequency","baseline-shift","begin","bias","by","class","clip","clip-path","clip-rule","color","color-interpolation","color-interpolation-filters","color-profile","color-rendering","cx","cy","d","dx","dy","diffuseconstant","direction","display","divisor","dur","edgemode","elevation","end","fill","fill-opacity","fill-rule","filter","flood-color","flood-opacity","font-family","font-size","font-size-adjust","font-stretch","font-style","font-variant","font-weight","fx","fy","g1","g2","glyph-name","glyphref","gradientunits","gradienttransform","height","href","id","image-rendering","in","in2","k","k1","k2","k3","k4","kerning","keypoints","keysplines","keytimes","lang","lengthadjust","letter-spacing","kernelmatrix","kernelunitlength","lighting-color","local","marker-end","marker-mid","marker-start","markerheight","markerunits","markerwidth","maskcontentunits","maskunits","max","mask","media","method","mode","min","name","numoctaves","offset","operator","opacity","order","orient","orientation","origin","overflow","paint-order","path","pathlength","patterncontentunits","patterntransform","patternunits","points","preservealpha","r","rx","ry","radius","refx","refy","repeatcount","repeatdur","restart","result","rotate","scale","seed","shape-rendering","specularconstant","specularexponent","spreadmethod","stddeviation","stitchtiles","stop-color","stop-opacity","stroke-dasharray","stroke-dashoffset","stroke-linecap","stroke-linejoin","stroke-miterlimit","stroke-opacity","stroke","stroke-width","style","surfacescale","tabindex","targetx","targety","transform","text-anchor","text-decoration","text-rendering","textlength","type","u1","u2","unicode","values","viewbox","visibility","vert-adv-y","vert-origin-x","vert-origin-y","width","word-spacing","wrap","writing-mode","xchannelselector","ychannelselector","x","x1","x2","xmlns","y","y1","y2","z","zoomandpan"],u=["accent","accentunder","align","bevelled","close","columnsalign","columnlines","columnspan","denomalign","depth","dir","display","displaystyle","fence","frame","height","href","id","largeop","length","linethickness","lspace","lquote","mathbackground","mathcolor","mathsize","mathvariant","maxsize","minsize","movablelimits","notation","numalign","open","rowalign","rowlines","rowspacing","rowspan","rspace","rquote","scriptlevel","scriptminsize","scriptsizemultiplier","selection","separator","separators","stretchy","subscriptshift","supscriptshift","symmetric","voffset","width","xmlns"],m=["xlink:href","xml:id","xlink:title","xml:space","xmlns:xlink"],p=/\{\{[\s\S]*|[\s\S]*\}\}/gm,f=/<%[\s\S]*|[\s\S]*%>/gm,h=/^data-[\-\w.\u00B7-\uFFFF]/,g=/^aria-[\-\w]+$/,y=/^(?:(?:(?:f|ht)tps?|mailto|tel|callto|cid|xmpp):|[^a-z]|[a-z+.\-]+(?:[^a-z+.\-:]|$))/i,v=/^(?:\w+script|data):/i,b=/[\u0000-\u0020\u00A0\u1680\u180E\u2000-\u2029\u205f\u3000]/g,T="function"==typeof Symbol&&"symbol"==typeof Symbol.iterator?function(e){return typeof e}:function(e){return e&&"function"==typeof Symbol&&e.constructor===Symbol&&e!==Symbol.prototype?"symbol":typeof e},A=function(){return"undefined"==typeof window?null:window};return o()}); -//# sourceMappingURL=purify.min.js.map diff --git a/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js.map b/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js.map deleted file mode 100644 index 0e1eb1588c..0000000000 --- a/tinygrad_repo/tinygrad/viz/assets/cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js.map +++ /dev/null @@ -1 +0,0 @@ -{"version":3,"file":"purify.min.js","sources":["../src/utils.js","../src/purify.js","../src/tags.js","../src/attrs.js","../src/regexp.js"],"sourcesContent":["/* Add properties to a lookup table */\nexport function addToSet(set, array) {\n let l = array.length;\n while (l--) {\n if (typeof array[l] === 'string') {\n array[l] = array[l].toLowerCase();\n }\n set[array[l]] = true;\n }\n return set;\n}\n\n/* Shallow clone an object */\nexport function clone(object) {\n const newObject = {};\n let property;\n for (property in object) {\n if (Object.prototype.hasOwnProperty.call(object, property)) {\n newObject[property] = object[property];\n }\n }\n return newObject;\n}\n","import * as TAGS from './tags';\nimport * as ATTRS from './attrs';\nimport { addToSet, clone } from './utils';\nimport * as EXPRESSIONS from './regexp';\n\nconst getGlobal = () => (typeof window === 'undefined' ? null : window);\n\nfunction createDOMPurify(window = getGlobal()) {\n const DOMPurify = root => createDOMPurify(root);\n\n /**\n * Version label, exposed for easier checks\n * if DOMPurify is up to date or not\n */\n DOMPurify.version = VERSION;\n\n /**\n * Array of elements that DOMPurify removed during sanitation.\n * Empty if nothing was removed.\n */\n DOMPurify.removed = [];\n\n if (!window || !window.document || window.document.nodeType !== 9) {\n // Not running in a browser, provide a factory function\n // so that you can pass your own Window\n DOMPurify.isSupported = false;\n\n return DOMPurify;\n }\n\n const originalDocument = window.document;\n let useDOMParser = false; // See comment below\n let useXHR = false;\n\n let document = window.document;\n const {\n DocumentFragment,\n HTMLTemplateElement,\n Node,\n NodeFilter,\n NamedNodeMap = window.NamedNodeMap || window.MozNamedAttrMap,\n Text,\n Comment,\n DOMParser,\n XMLHttpRequest = window.XMLHttpRequest,\n encodeURI = window.encodeURI,\n } = window;\n\n // As per issue #47, the web-components registry is inherited by a\n // new document created via createHTMLDocument. As per the spec\n // (http://w3c.github.io/webcomponents/spec/custom/#creating-and-passing-registries)\n // a new empty registry is used when creating a template contents owner\n // document, so we use that as our parent document to ensure nothing\n // is inherited.\n if (typeof HTMLTemplateElement === 'function') {\n const template = document.createElement('template');\n if (template.content && template.content.ownerDocument) {\n document = template.content.ownerDocument;\n }\n }\n\n const {\n implementation,\n createNodeIterator,\n getElementsByTagName,\n createDocumentFragment,\n } = document;\n const importNode = originalDocument.importNode;\n\n let hooks = {};\n\n /**\n * Expose whether this browser supports running the full DOMPurify.\n */\n DOMPurify.isSupported =\n implementation &&\n typeof implementation.createHTMLDocument !== 'undefined' &&\n document.documentMode !== 9;\n\n const {\n MUSTACHE_EXPR,\n ERB_EXPR,\n DATA_ATTR,\n ARIA_ATTR,\n IS_SCRIPT_OR_DATA,\n ATTR_WHITESPACE,\n } = EXPRESSIONS;\n\n let IS_ALLOWED_URI = EXPRESSIONS.IS_ALLOWED_URI;\n /**\n * We consider the elements and attributes below to be safe. Ideally\n * don't add any new ones but feel free to remove unwanted ones.\n */\n\n /* allowed element names */\n let ALLOWED_TAGS = null;\n const DEFAULT_ALLOWED_TAGS = addToSet({}, [\n ...TAGS.html,\n ...TAGS.svg,\n ...TAGS.svgFilters,\n ...TAGS.mathMl,\n ...TAGS.text,\n ]);\n\n /* Allowed attribute names */\n let ALLOWED_ATTR = null;\n const DEFAULT_ALLOWED_ATTR = addToSet({}, [\n ...ATTRS.html,\n ...ATTRS.svg,\n ...ATTRS.mathMl,\n ...ATTRS.xml,\n ]);\n\n /* Explicitly forbidden tags (overrides ALLOWED_TAGS/ADD_TAGS) */\n let FORBID_TAGS = null;\n\n /* Explicitly forbidden attributes (overrides ALLOWED_ATTR/ADD_ATTR) */\n let FORBID_ATTR = null;\n\n /* Decide if ARIA attributes are okay */\n let ALLOW_ARIA_ATTR = true;\n\n /* Decide if custom data attributes are okay */\n let ALLOW_DATA_ATTR = true;\n\n /* Decide if unknown protocols are okay */\n let ALLOW_UNKNOWN_PROTOCOLS = false;\n\n /* Output should be safe for jQuery's $() factory? */\n let SAFE_FOR_JQUERY = false;\n\n /* Output should be safe for common template engines.\n * This means, DOMPurify removes data attributes, mustaches and ERB\n */\n let SAFE_FOR_TEMPLATES = false;\n\n /* Decide if document with ... should be returned */\n let WHOLE_DOCUMENT = false;\n\n /* Track whether config is already set on this instance of DOMPurify. */\n let SET_CONFIG = false;\n\n /* Decide if all elements (e.g. style, script) must be children of\n * document.body. By default, browsers might move them to document.head */\n let FORCE_BODY = false;\n\n /* Decide if a DOM `HTMLBodyElement` should be returned, instead of a html string.\n * If `WHOLE_DOCUMENT` is enabled a `HTMLHtmlElement` will be returned instead\n */\n let RETURN_DOM = false;\n\n /* Decide if a DOM `DocumentFragment` should be returned, instead of a html string */\n let RETURN_DOM_FRAGMENT = false;\n\n /* If `RETURN_DOM` or `RETURN_DOM_FRAGMENT` is enabled, decide if the returned DOM\n * `Node` is imported into the current `Document`. If this flag is not enabled the\n * `Node` will belong (its ownerDocument) to a fresh `HTMLDocument`, created by\n * DOMPurify. */\n let RETURN_DOM_IMPORT = false;\n\n /* Output should be free from DOM clobbering attacks? */\n let SANITIZE_DOM = true;\n\n /* Keep element content when removing element? */\n let KEEP_CONTENT = true;\n\n /* Allow usage of profiles like html, svg and mathMl */\n let USE_PROFILES = {};\n\n /* Tags to ignore content of when KEEP_CONTENT is true */\n const FORBID_CONTENTS = addToSet({}, [\n 'audio',\n 'head',\n 'math',\n 'script',\n 'style',\n 'template',\n 'svg',\n 'video',\n ]);\n\n /* Tags that are safe for data: URIs */\n const DATA_URI_TAGS = addToSet({}, [\n 'audio',\n 'video',\n 'img',\n 'source',\n 'image',\n ]);\n\n /* Attributes safe for values like \"javascript:\" */\n const URI_SAFE_ATTRIBUTES = addToSet({}, [\n 'alt',\n 'class',\n 'for',\n 'id',\n 'label',\n 'name',\n 'pattern',\n 'placeholder',\n 'summary',\n 'title',\n 'value',\n 'style',\n 'xmlns',\n ]);\n\n /* Keep a reference to config to pass to hooks */\n let CONFIG = null;\n\n /* Ideally, do not touch anything below this line */\n /* ______________________________________________ */\n\n const formElement = document.createElement('form');\n\n /**\n * _parseConfig\n *\n * @param optional config literal\n */\n // eslint-disable-next-line complexity\n const _parseConfig = function(cfg) {\n /* Shield configuration object from tampering */\n if (typeof cfg !== 'object') {\n cfg = {};\n }\n /* Set configuration parameters */\n ALLOWED_TAGS =\n 'ALLOWED_TAGS' in cfg\n ? addToSet({}, cfg.ALLOWED_TAGS)\n : DEFAULT_ALLOWED_TAGS;\n ALLOWED_ATTR =\n 'ALLOWED_ATTR' in cfg\n ? addToSet({}, cfg.ALLOWED_ATTR)\n : DEFAULT_ALLOWED_ATTR;\n FORBID_TAGS = 'FORBID_TAGS' in cfg ? addToSet({}, cfg.FORBID_TAGS) : {};\n FORBID_ATTR = 'FORBID_ATTR' in cfg ? addToSet({}, cfg.FORBID_ATTR) : {};\n USE_PROFILES = 'USE_PROFILES' in cfg ? cfg.USE_PROFILES : false;\n ALLOW_ARIA_ATTR = cfg.ALLOW_ARIA_ATTR !== false; // Default true\n ALLOW_DATA_ATTR = cfg.ALLOW_DATA_ATTR !== false; // Default true\n ALLOW_UNKNOWN_PROTOCOLS = cfg.ALLOW_UNKNOWN_PROTOCOLS || false; // Default false\n SAFE_FOR_JQUERY = cfg.SAFE_FOR_JQUERY || false; // Default false\n SAFE_FOR_TEMPLATES = cfg.SAFE_FOR_TEMPLATES || false; // Default false\n WHOLE_DOCUMENT = cfg.WHOLE_DOCUMENT || false; // Default false\n RETURN_DOM = cfg.RETURN_DOM || false; // Default false\n RETURN_DOM_FRAGMENT = cfg.RETURN_DOM_FRAGMENT || false; // Default false\n RETURN_DOM_IMPORT = cfg.RETURN_DOM_IMPORT || false; // Default false\n FORCE_BODY = cfg.FORCE_BODY || false; // Default false\n SANITIZE_DOM = cfg.SANITIZE_DOM !== false; // Default true\n KEEP_CONTENT = cfg.KEEP_CONTENT !== false; // Default true\n\n IS_ALLOWED_URI = cfg.ALLOWED_URI_REGEXP || IS_ALLOWED_URI;\n\n if (SAFE_FOR_TEMPLATES) {\n ALLOW_DATA_ATTR = false;\n }\n\n if (RETURN_DOM_FRAGMENT) {\n RETURN_DOM = true;\n }\n\n /* Parse profile info */\n if (USE_PROFILES) {\n ALLOWED_TAGS = addToSet({}, [...TAGS.text]);\n ALLOWED_ATTR = [];\n if (USE_PROFILES.html === true) {\n addToSet(ALLOWED_TAGS, TAGS.html);\n addToSet(ALLOWED_ATTR, ATTRS.html);\n }\n if (USE_PROFILES.svg === true) {\n addToSet(ALLOWED_TAGS, TAGS.svg);\n addToSet(ALLOWED_ATTR, ATTRS.svg);\n addToSet(ALLOWED_ATTR, ATTRS.xml);\n }\n if (USE_PROFILES.svgFilters === true) {\n addToSet(ALLOWED_TAGS, TAGS.svgFilters);\n addToSet(ALLOWED_ATTR, ATTRS.svg);\n addToSet(ALLOWED_ATTR, ATTRS.xml);\n }\n if (USE_PROFILES.mathMl === true) {\n addToSet(ALLOWED_TAGS, TAGS.mathMl);\n addToSet(ALLOWED_ATTR, ATTRS.mathMl);\n addToSet(ALLOWED_ATTR, ATTRS.xml);\n }\n }\n\n /* Merge configuration parameters */\n if (cfg.ADD_TAGS) {\n if (ALLOWED_TAGS === DEFAULT_ALLOWED_TAGS) {\n ALLOWED_TAGS = clone(ALLOWED_TAGS);\n }\n addToSet(ALLOWED_TAGS, cfg.ADD_TAGS);\n }\n if (cfg.ADD_ATTR) {\n if (ALLOWED_ATTR === DEFAULT_ALLOWED_ATTR) {\n ALLOWED_ATTR = clone(ALLOWED_ATTR);\n }\n addToSet(ALLOWED_ATTR, cfg.ADD_ATTR);\n }\n if (cfg.ADD_URI_SAFE_ATTR) {\n addToSet(URI_SAFE_ATTRIBUTES, cfg.ADD_URI_SAFE_ATTR);\n }\n\n /* Add #text in case KEEP_CONTENT is set to true */\n if (KEEP_CONTENT) {\n ALLOWED_TAGS['#text'] = true;\n }\n\n // Prevent further manipulation of configuration.\n // Not available in IE8, Safari 5, etc.\n if (Object && 'freeze' in Object) {\n Object.freeze(cfg);\n }\n\n CONFIG = cfg;\n };\n\n /**\n * _forceRemove\n *\n * @param a DOM node\n */\n const _forceRemove = function(node) {\n DOMPurify.removed.push({ element: node });\n try {\n node.parentNode.removeChild(node);\n } catch (err) {\n node.outerHTML = '';\n }\n };\n\n /**\n * _removeAttribute\n *\n * @param an Attribute name\n * @param a DOM node\n */\n const _removeAttribute = function(name, node) {\n DOMPurify.removed.push({\n attribute: node.getAttributeNode(name),\n from: node,\n });\n node.removeAttribute(name);\n };\n\n /**\n * _initDocument\n *\n * @param a string of dirty markup\n * @return a DOM, filled with the dirty markup\n */\n const _initDocument = function(dirty) {\n /* Create a HTML document */\n let doc;\n let body;\n\n if (FORCE_BODY) {\n dirty = '' + dirty;\n }\n\n /* Use XHR if necessary because Safari 10.1 and newer are buggy */\n if (useXHR) {\n try {\n dirty = encodeURI(dirty);\n } catch (err) {}\n const xhr = new XMLHttpRequest();\n xhr.responseType = 'document';\n xhr.open('GET', 'data:text/html;charset=utf-8,' + dirty, false);\n xhr.send(null);\n doc = xhr.response;\n }\n\n /* Use DOMParser to workaround Firefox bug (see comment below) */\n if (useDOMParser) {\n try {\n doc = new DOMParser().parseFromString(dirty, 'text/html');\n } catch (err) {}\n }\n\n /* Otherwise use createHTMLDocument, because DOMParser is unsafe in\n Safari (see comment below) */\n if (!doc || !doc.documentElement) {\n doc = implementation.createHTMLDocument('');\n body = doc.body;\n body.parentNode.removeChild(body.parentNode.firstElementChild);\n body.outerHTML = dirty;\n }\n\n /* Work on whole document or just its body */\n return getElementsByTagName.call(doc, WHOLE_DOCUMENT ? 'html' : 'body')[0];\n };\n\n // Safari 10.1+ (unfixed as of time of writing) has a catastrophic bug in\n // its implementation of DOMParser such that the following executes the\n // JavaScript:\n //\n // new DOMParser()\n // .parseFromString('', 'text/html');\n //\n // Later, it was also noticed that even more assumed benign and inert ways\n // of creating a document are now insecure thanks to Safari. So we work\n // around that with a feature test and use XHR to create the document in\n // case we really have to. That one seems safe for now.\n //\n // However, Firefox uses a different parser for innerHTML rather than\n // DOMParser (see https://bugzilla.mozilla.org/show_bug.cgi?id=1205631)\n // which means that you *must* use DOMParser, otherwise the output may\n // not be safe if used in a document.write context later.\n //\n // So we feature detect the Firefox bug and use the DOMParser if necessary.\n if (DOMPurify.isSupported) {\n (function() {\n let doc = _initDocument(\n ''\n );\n if (!doc.querySelector('svg')) {\n useXHR = true;\n }\n try {\n doc = _initDocument(\n '

'\n );\n if (doc.querySelector('svg img')) {\n useDOMParser = true;\n }\n } catch (err) {}\n })();\n }\n\n /**\n * _createIterator\n *\n * @param document/fragment to create iterator for\n * @return iterator instance\n */\n const _createIterator = function(root) {\n return createNodeIterator.call(\n root.ownerDocument || root,\n root,\n NodeFilter.SHOW_ELEMENT | NodeFilter.SHOW_COMMENT | NodeFilter.SHOW_TEXT,\n () => {\n return NodeFilter.FILTER_ACCEPT;\n },\n false\n );\n };\n\n /**\n * _isClobbered\n *\n * @param element to check for clobbering attacks\n * @return true if clobbered, false if safe\n */\n const _isClobbered = function(elm) {\n if (elm instanceof Text || elm instanceof Comment) {\n return false;\n }\n if (\n typeof elm.nodeName !== 'string' ||\n typeof elm.textContent !== 'string' ||\n typeof elm.removeChild !== 'function' ||\n !(elm.attributes instanceof NamedNodeMap) ||\n typeof elm.removeAttribute !== 'function' ||\n typeof elm.setAttribute !== 'function'\n ) {\n return true;\n }\n return false;\n };\n\n /**\n * _isNode\n *\n * @param object to check whether it's a DOM node\n * @return true is object is a DOM node\n */\n const _isNode = function(obj) {\n return typeof Node === 'object'\n ? obj instanceof Node\n : obj &&\n typeof obj === 'object' &&\n typeof obj.nodeType === 'number' &&\n typeof obj.nodeName === 'string';\n };\n\n /**\n * _executeHook\n * Execute user configurable hooks\n *\n * @param {String} entryPoint Name of the hook's entry point\n * @param {Node} currentNode\n */\n const _executeHook = function(entryPoint, currentNode, data) {\n if (!hooks[entryPoint]) {\n return;\n }\n\n hooks[entryPoint].forEach(hook => {\n hook.call(DOMPurify, currentNode, data, CONFIG);\n });\n };\n\n /**\n * _sanitizeElements\n *\n * @protect nodeName\n * @protect textContent\n * @protect removeChild\n *\n * @param node to check for permission to exist\n * @return true if node was killed, false if left alive\n */\n const _sanitizeElements = function(currentNode) {\n let content;\n\n /* Execute a hook if present */\n _executeHook('beforeSanitizeElements', currentNode, null);\n\n /* Check if element is clobbered or can clobber */\n if (_isClobbered(currentNode)) {\n _forceRemove(currentNode);\n return true;\n }\n\n /* Now let's check the element's type and name */\n const tagName = currentNode.nodeName.toLowerCase();\n\n /* Execute a hook if present */\n _executeHook('uponSanitizeElement', currentNode, {\n tagName,\n allowedTags: ALLOWED_TAGS,\n });\n\n /* Remove element if anything forbids its presence */\n if (!ALLOWED_TAGS[tagName] || FORBID_TAGS[tagName]) {\n /* Keep content except for black-listed elements */\n if (\n KEEP_CONTENT &&\n !FORBID_CONTENTS[tagName] &&\n typeof currentNode.insertAdjacentHTML === 'function'\n ) {\n try {\n currentNode.insertAdjacentHTML('AfterEnd', currentNode.innerHTML);\n } catch (err) {}\n }\n _forceRemove(currentNode);\n return true;\n }\n\n /* Convert markup to cover jQuery behavior */\n if (\n SAFE_FOR_JQUERY &&\n !currentNode.firstElementChild &&\n (!currentNode.content || !currentNode.content.firstElementChild) &&\n / tag that has an \"id\"\n // attribute at the time.\n if (\n lcName === 'name' &&\n currentNode.nodeName === 'IMG' &&\n attributes.id\n ) {\n idAttr = attributes.id;\n attributes = Array.prototype.slice.apply(attributes);\n _removeAttribute('id', currentNode);\n _removeAttribute(name, currentNode);\n if (attributes.indexOf(idAttr) > l) {\n currentNode.setAttribute('id', idAttr.value);\n }\n } else if (\n // This works around a bug in Safari, where input[type=file]\n // cannot be dynamically set after type has been removed\n currentNode.nodeName === 'INPUT' &&\n lcName === 'type' &&\n value === 'file' &&\n (ALLOWED_ATTR[lcName] || !FORBID_ATTR[lcName])\n ) {\n continue;\n } else {\n // This avoids a crash in Safari v9.0 with double-ids.\n // The trick is to first set the id to be empty and then to\n // remove the attribute\n if (name === 'id') {\n currentNode.setAttribute(name, '');\n }\n _removeAttribute(name, currentNode);\n }\n\n /* Did the hooks approve of the attribute? */\n if (!hookEvent.keepAttr) {\n continue;\n }\n\n /* Make sure attribute cannot clobber */\n if (\n SANITIZE_DOM &&\n (lcName === 'id' || lcName === 'name') &&\n (value in document || value in formElement)\n ) {\n continue;\n }\n\n /* Sanitize attribute content to be template-safe */\n if (SAFE_FOR_TEMPLATES) {\n value = value.replace(MUSTACHE_EXPR, ' ');\n value = value.replace(ERB_EXPR, ' ');\n }\n\n /* Allow valid data-* attributes: At least one character after \"-\"\n (https://html.spec.whatwg.org/multipage/dom.html#embedding-custom-non-visible-data-with-the-data-*-attributes)\n XML-compatible (https://html.spec.whatwg.org/multipage/infrastructure.html#xml-compatible and http://www.w3.org/TR/xml/#d0e804)\n We don't need to check the value; it's always URI safe. */\n if (ALLOW_DATA_ATTR && DATA_ATTR.test(lcName)) {\n // This attribute is safe\n } else if (ALLOW_ARIA_ATTR && ARIA_ATTR.test(lcName)) {\n // This attribute is safe\n /* Otherwise, check the name is permitted */\n } else if (!ALLOWED_ATTR[lcName] || FORBID_ATTR[lcName]) {\n continue;\n\n /* Check value is safe. First, is attr inert? If so, is safe */\n } else if (URI_SAFE_ATTRIBUTES[lcName]) {\n // This attribute is safe\n /* Check no script, data or unknown possibly unsafe URI\n unless we know URI values are safe for that attribute */\n } else if (IS_ALLOWED_URI.test(value.replace(ATTR_WHITESPACE, ''))) {\n // This attribute is safe\n /* Keep image data URIs alive if src/xlink:href is allowed */\n } else if (\n (lcName === 'src' || lcName === 'xlink:href') &&\n value.indexOf('data:') === 0 &&\n DATA_URI_TAGS[currentNode.nodeName.toLowerCase()]\n ) {\n // This attribute is safe\n /* Allow unknown protocols: This provides support for links that\n are handled by protocol handlers which may be unknown ahead of\n time, e.g. fb:, spotify: */\n } else if (\n ALLOW_UNKNOWN_PROTOCOLS &&\n !IS_SCRIPT_OR_DATA.test(value.replace(ATTR_WHITESPACE, ''))\n ) {\n // This attribute is safe\n /* Check for binary attributes */\n // eslint-disable-next-line no-negated-condition\n } else if (!value) {\n // Binary attributes are safe at this point\n /* Anything else, presume unsafe, do not add it back */\n } else {\n continue;\n }\n\n /* Handle invalid data-* attribute set by try-catching it */\n try {\n currentNode.setAttribute(name, value);\n DOMPurify.removed.pop();\n } catch (err) {}\n }\n\n /* Execute a hook if present */\n _executeHook('afterSanitizeAttributes', currentNode, null);\n };\n\n /**\n * _sanitizeShadowDOM\n *\n * @param fragment to iterate over recursively\n * @return void\n */\n const _sanitizeShadowDOM = function(fragment) {\n let shadowNode;\n const shadowIterator = _createIterator(fragment);\n\n /* Execute a hook if present */\n _executeHook('beforeSanitizeShadowDOM', fragment, null);\n\n while ((shadowNode = shadowIterator.nextNode())) {\n /* Execute a hook if present */\n _executeHook('uponSanitizeShadowNode', shadowNode, null);\n\n /* Sanitize tags and elements */\n if (_sanitizeElements(shadowNode)) {\n continue;\n }\n\n /* Deep shadow DOM detected */\n if (shadowNode.content instanceof DocumentFragment) {\n _sanitizeShadowDOM(shadowNode.content);\n }\n\n /* Check attributes, sanitize if necessary */\n _sanitizeAttributes(shadowNode);\n }\n\n /* Execute a hook if present */\n _executeHook('afterSanitizeShadowDOM', fragment, null);\n };\n\n /**\n * Sanitize\n * Public method providing core sanitation functionality\n *\n * @param {String|Node} dirty string or DOM node\n * @param {Object} configuration object\n */\n // eslint-disable-next-line complexity\n DOMPurify.sanitize = function(dirty, cfg) {\n let body;\n let importedNode;\n let currentNode;\n let oldNode;\n let returnNode;\n /* Make sure we have a string to sanitize.\n DO NOT return early, as this will return the wrong type if\n the user has requested a DOM object rather than a string */\n if (!dirty) {\n dirty = '';\n }\n\n /* Stringify, in case dirty is an object */\n if (typeof dirty !== 'string' && !_isNode(dirty)) {\n // eslint-disable-next-line no-negated-condition\n if (typeof dirty.toString !== 'function') {\n throw new TypeError('toString is not a function');\n } else {\n dirty = dirty.toString();\n if (typeof dirty !== 'string') {\n throw new TypeError('dirty is not a string, aborting');\n }\n }\n }\n\n /* Check we can run. Otherwise fall back or ignore */\n if (!DOMPurify.isSupported) {\n if (\n typeof window.toStaticHTML === 'object' ||\n typeof window.toStaticHTML === 'function'\n ) {\n if (typeof dirty === 'string') {\n return window.toStaticHTML(dirty);\n } else if (_isNode(dirty)) {\n return window.toStaticHTML(dirty.outerHTML);\n }\n }\n return dirty;\n }\n\n /* Assign config vars */\n if (!SET_CONFIG) {\n _parseConfig(cfg);\n }\n\n /* Clean up removed elements */\n DOMPurify.removed = [];\n\n if (dirty instanceof Node) {\n /* If dirty is a DOM element, append to an empty document to avoid\n elements being stripped by the parser */\n body = _initDocument('');\n importedNode = body.ownerDocument.importNode(dirty, true);\n if (importedNode.nodeType === 1 && importedNode.nodeName === 'BODY') {\n /* Node is already a body, use as is */\n body = importedNode;\n } else {\n body.appendChild(importedNode);\n }\n } else {\n /* Exit directly if we have nothing to do */\n if (!RETURN_DOM && !WHOLE_DOCUMENT && dirty.indexOf('<') === -1) {\n return dirty;\n }\n\n /* Initialize the document to work on */\n body = _initDocument(dirty);\n\n /* Check we have a DOM node from the data */\n if (!body) {\n return RETURN_DOM ? null : '';\n }\n }\n\n /* Remove first element node (ours) if FORCE_BODY is set */\n if (FORCE_BODY) {\n _forceRemove(body.firstChild);\n }\n\n /* Get node iterator */\n const nodeIterator = _createIterator(body);\n\n /* Now start iterating over the created document */\n while ((currentNode = nodeIterator.nextNode())) {\n /* Fix IE's strange behavior with manipulated textNodes #89 */\n if (currentNode.nodeType === 3 && currentNode === oldNode) {\n continue;\n }\n\n /* Sanitize tags and elements */\n if (_sanitizeElements(currentNode)) {\n continue;\n }\n\n /* Shadow DOM detected, sanitize it */\n if (currentNode.content instanceof DocumentFragment) {\n _sanitizeShadowDOM(currentNode.content);\n }\n\n /* Check attributes, sanitize if necessary */\n _sanitizeAttributes(currentNode);\n\n oldNode = currentNode;\n }\n\n /* Return sanitized string or DOM */\n if (RETURN_DOM) {\n if (RETURN_DOM_FRAGMENT) {\n returnNode = createDocumentFragment.call(body.ownerDocument);\n\n while (body.firstChild) {\n returnNode.appendChild(body.firstChild);\n }\n } else {\n returnNode = body;\n }\n\n if (RETURN_DOM_IMPORT) {\n /* AdoptNode() is not used because internal state is not reset\n (e.g. the past names map of a HTMLFormElement), this is safe\n in theory but we would rather not risk another attack vector.\n The state that is cloned by importNode() is explicitly defined\n by the specs. */\n returnNode = importNode.call(originalDocument, returnNode, true);\n }\n\n return returnNode;\n }\n\n return WHOLE_DOCUMENT ? body.outerHTML : body.innerHTML;\n };\n\n /**\n * Public method to set the configuration once\n * setConfig\n *\n * @param {Object} configuration object\n * @return void\n */\n DOMPurify.setConfig = function(cfg) {\n _parseConfig(cfg);\n SET_CONFIG = true;\n };\n\n /**\n * Public method to remove the configuration\n * clearConfig\n *\n * @return void\n */\n DOMPurify.clearConfig = function() {\n CONFIG = null;\n SET_CONFIG = false;\n };\n\n /**\n * AddHook\n * Public method to add DOMPurify hooks\n *\n * @param {String} entryPoint\n * @param {Function} hookFunction\n */\n DOMPurify.addHook = function(entryPoint, hookFunction) {\n if (typeof hookFunction !== 'function') {\n return;\n }\n hooks[entryPoint] = hooks[entryPoint] || [];\n hooks[entryPoint].push(hookFunction);\n };\n\n /**\n * RemoveHook\n * Public method to remove a DOMPurify hook at a given entryPoint\n * (pops it from the stack of hooks if more are present)\n *\n * @param {String} entryPoint\n * @return void\n */\n DOMPurify.removeHook = function(entryPoint) {\n if (hooks[entryPoint]) {\n hooks[entryPoint].pop();\n }\n };\n\n /**\n * RemoveHooks\n * Public method to remove all DOMPurify hooks at a given entryPoint\n *\n * @param {String} entryPoint\n * @return void\n */\n DOMPurify.removeHooks = function(entryPoint) {\n if (hooks[entryPoint]) {\n hooks[entryPoint] = [];\n }\n };\n\n /**\n * RemoveAllHooks\n * Public method to remove all DOMPurify hooks\n *\n * @return void\n */\n DOMPurify.removeAllHooks = function() {\n hooks = {};\n };\n\n return DOMPurify;\n}\n\nexport default createDOMPurify();\n","export const html = [\n 'a',\n 'abbr',\n 'acronym',\n 'address',\n 'area',\n 'article',\n 'aside',\n 'audio',\n 'b',\n 'bdi',\n 'bdo',\n 'big',\n 'blink',\n 'blockquote',\n 'body',\n 'br',\n 'button',\n 'canvas',\n 'caption',\n 'center',\n 'cite',\n 'code',\n 'col',\n 'colgroup',\n 'content',\n 'data',\n 'datalist',\n 'dd',\n 'decorator',\n 'del',\n 'details',\n 'dfn',\n 'dir',\n 'div',\n 'dl',\n 'dt',\n 'element',\n 'em',\n 'fieldset',\n 'figcaption',\n 'figure',\n 'font',\n 'footer',\n 'form',\n 'h1',\n 'h2',\n 'h3',\n 'h4',\n 'h5',\n 'h6',\n 'head',\n 'header',\n 'hgroup',\n 'hr',\n 'html',\n 'i',\n 'img',\n 'input',\n 'ins',\n 'kbd',\n 'label',\n 'legend',\n 'li',\n 'main',\n 'map',\n 'mark',\n 'marquee',\n 'menu',\n 'menuitem',\n 'meter',\n 'nav',\n 'nobr',\n 'ol',\n 'optgroup',\n 'option',\n 'output',\n 'p',\n 'pre',\n 'progress',\n 'q',\n 'rp',\n 'rt',\n 'ruby',\n 's',\n 'samp',\n 'section',\n 'select',\n 'shadow',\n 'small',\n 'source',\n 'spacer',\n 'span',\n 'strike',\n 'strong',\n 'style',\n 'sub',\n 'summary',\n 'sup',\n 'table',\n 'tbody',\n 'td',\n 'template',\n 'textarea',\n 'tfoot',\n 'th',\n 'thead',\n 'time',\n 'tr',\n 'track',\n 'tt',\n 'u',\n 'ul',\n 'var',\n 'video',\n 'wbr',\n];\n\n// SVG\nexport const svg = [\n 'svg',\n 'a',\n 'altglyph',\n 'altglyphdef',\n 'altglyphitem',\n 'animatecolor',\n 'animatemotion',\n 'animatetransform',\n 'audio',\n 'canvas',\n 'circle',\n 'clippath',\n 'defs',\n 'desc',\n 'ellipse',\n 'filter',\n 'font',\n 'g',\n 'glyph',\n 'glyphref',\n 'hkern',\n 'image',\n 'line',\n 'lineargradient',\n 'marker',\n 'mask',\n 'metadata',\n 'mpath',\n 'path',\n 'pattern',\n 'polygon',\n 'polyline',\n 'radialgradient',\n 'rect',\n 'stop',\n 'style',\n 'switch',\n 'symbol',\n 'text',\n 'textpath',\n 'title',\n 'tref',\n 'tspan',\n 'video',\n 'view',\n 'vkern',\n];\n\nexport const svgFilters = [\n 'feBlend',\n 'feColorMatrix',\n 'feComponentTransfer',\n 'feComposite',\n 'feConvolveMatrix',\n 'feDiffuseLighting',\n 'feDisplacementMap',\n 'feFlood',\n 'feFuncA',\n 'feFuncB',\n 'feFuncG',\n 'feFuncR',\n 'feGaussianBlur',\n 'feMerge',\n 'feMergeNode',\n 'feMorphology',\n 'feOffset',\n 'feSpecularLighting',\n 'feTile',\n 'feTurbulence',\n];\n\nexport const mathMl = [\n 'math',\n 'menclose',\n 'merror',\n 'mfenced',\n 'mfrac',\n 'mglyph',\n 'mi',\n 'mlabeledtr',\n 'mmuliscripts',\n 'mn',\n 'mo',\n 'mover',\n 'mpadded',\n 'mphantom',\n 'mroot',\n 'mrow',\n 'ms',\n 'mpspace',\n 'msqrt',\n 'mystyle',\n 'msub',\n 'msup',\n 'msubsup',\n 'mtable',\n 'mtd',\n 'mtext',\n 'mtr',\n 'munder',\n 'munderover',\n];\n\nexport const text = ['#text'];\n","export const html = [\n 'accept',\n 'action',\n 'align',\n 'alt',\n 'autocomplete',\n 'background',\n 'bgcolor',\n 'border',\n 'cellpadding',\n 'cellspacing',\n 'checked',\n 'cite',\n 'class',\n 'clear',\n 'color',\n 'cols',\n 'colspan',\n 'coords',\n 'crossorigin',\n 'datetime',\n 'default',\n 'dir',\n 'disabled',\n 'download',\n 'enctype',\n 'face',\n 'for',\n 'headers',\n 'height',\n 'hidden',\n 'high',\n 'href',\n 'hreflang',\n 'id',\n 'integrity',\n 'ismap',\n 'label',\n 'lang',\n 'list',\n 'loop',\n 'low',\n 'max',\n 'maxlength',\n 'media',\n 'method',\n 'min',\n 'multiple',\n 'name',\n 'noshade',\n 'novalidate',\n 'nowrap',\n 'open',\n 'optimum',\n 'pattern',\n 'placeholder',\n 'poster',\n 'preload',\n 'pubdate',\n 'radiogroup',\n 'readonly',\n 'rel',\n 'required',\n 'rev',\n 'reversed',\n 'role',\n 'rows',\n 'rowspan',\n 'spellcheck',\n 'scope',\n 'selected',\n 'shape',\n 'size',\n 'sizes',\n 'span',\n 'srclang',\n 'start',\n 'src',\n 'srcset',\n 'step',\n 'style',\n 'summary',\n 'tabindex',\n 'title',\n 'type',\n 'usemap',\n 'valign',\n 'value',\n 'width',\n 'xmlns',\n];\n\nexport const svg = [\n 'accent-height',\n 'accumulate',\n 'additivive',\n 'alignment-baseline',\n 'ascent',\n 'attributename',\n 'attributetype',\n 'azimuth',\n 'basefrequency',\n 'baseline-shift',\n 'begin',\n 'bias',\n 'by',\n 'class',\n 'clip',\n 'clip-path',\n 'clip-rule',\n 'color',\n 'color-interpolation',\n 'color-interpolation-filters',\n 'color-profile',\n 'color-rendering',\n 'cx',\n 'cy',\n 'd',\n 'dx',\n 'dy',\n 'diffuseconstant',\n 'direction',\n 'display',\n 'divisor',\n 'dur',\n 'edgemode',\n 'elevation',\n 'end',\n 'fill',\n 'fill-opacity',\n 'fill-rule',\n 'filter',\n 'flood-color',\n 'flood-opacity',\n 'font-family',\n 'font-size',\n 'font-size-adjust',\n 'font-stretch',\n 'font-style',\n 'font-variant',\n 'font-weight',\n 'fx',\n 'fy',\n 'g1',\n 'g2',\n 'glyph-name',\n 'glyphref',\n 'gradientunits',\n 'gradienttransform',\n 'height',\n 'href',\n 'id',\n 'image-rendering',\n 'in',\n 'in2',\n 'k',\n 'k1',\n 'k2',\n 'k3',\n 'k4',\n 'kerning',\n 'keypoints',\n 'keysplines',\n 'keytimes',\n 'lang',\n 'lengthadjust',\n 'letter-spacing',\n 'kernelmatrix',\n 'kernelunitlength',\n 'lighting-color',\n 'local',\n 'marker-end',\n 'marker-mid',\n 'marker-start',\n 'markerheight',\n 'markerunits',\n 'markerwidth',\n 'maskcontentunits',\n 'maskunits',\n 'max',\n 'mask',\n 'media',\n 'method',\n 'mode',\n 'min',\n 'name',\n 'numoctaves',\n 'offset',\n 'operator',\n 'opacity',\n 'order',\n 'orient',\n 'orientation',\n 'origin',\n 'overflow',\n 'paint-order',\n 'path',\n 'pathlength',\n 'patterncontentunits',\n 'patterntransform',\n 'patternunits',\n 'points',\n 'preservealpha',\n 'r',\n 'rx',\n 'ry',\n 'radius',\n 'refx',\n 'refy',\n 'repeatcount',\n 'repeatdur',\n 'restart',\n 'result',\n 'rotate',\n 'scale',\n 'seed',\n 'shape-rendering',\n 'specularconstant',\n 'specularexponent',\n 'spreadmethod',\n 'stddeviation',\n 'stitchtiles',\n 'stop-color',\n 'stop-opacity',\n 'stroke-dasharray',\n 'stroke-dashoffset',\n 'stroke-linecap',\n 'stroke-linejoin',\n 'stroke-miterlimit',\n 'stroke-opacity',\n 'stroke',\n 'stroke-width',\n 'style',\n 'surfacescale',\n 'tabindex',\n 'targetx',\n 'targety',\n 'transform',\n 'text-anchor',\n 'text-decoration',\n 'text-rendering',\n 'textlength',\n 'type',\n 'u1',\n 'u2',\n 'unicode',\n 'values',\n 'viewbox',\n 'visibility',\n 'vert-adv-y',\n 'vert-origin-x',\n 'vert-origin-y',\n 'width',\n 'word-spacing',\n 'wrap',\n 'writing-mode',\n 'xchannelselector',\n 'ychannelselector',\n 'x',\n 'x1',\n 'x2',\n 'xmlns',\n 'y',\n 'y1',\n 'y2',\n 'z',\n 'zoomandpan',\n];\n\nexport const mathMl = [\n 'accent',\n 'accentunder',\n 'align',\n 'bevelled',\n 'close',\n 'columnsalign',\n 'columnlines',\n 'columnspan',\n 'denomalign',\n 'depth',\n 'dir',\n 'display',\n 'displaystyle',\n 'fence',\n 'frame',\n 'height',\n 'href',\n 'id',\n 'largeop',\n 'length',\n 'linethickness',\n 'lspace',\n 'lquote',\n 'mathbackground',\n 'mathcolor',\n 'mathsize',\n 'mathvariant',\n 'maxsize',\n 'minsize',\n 'movablelimits',\n 'notation',\n 'numalign',\n 'open',\n 'rowalign',\n 'rowlines',\n 'rowspacing',\n 'rowspan',\n 'rspace',\n 'rquote',\n 'scriptlevel',\n 'scriptminsize',\n 'scriptsizemultiplier',\n 'selection',\n 'separator',\n 'separators',\n 'stretchy',\n 'subscriptshift',\n 'supscriptshift',\n 'symmetric',\n 'voffset',\n 'width',\n 'xmlns',\n];\n\nexport const xml = [\n 'xlink:href',\n 'xml:id',\n 'xlink:title',\n 'xml:space',\n 'xmlns:xlink',\n];\n","export const MUSTACHE_EXPR = /\\{\\{[\\s\\S]*|[\\s\\S]*\\}\\}/gm; // Specify template detection regex for SAFE_FOR_TEMPLATES mode\nexport const ERB_EXPR = /<%[\\s\\S]*|[\\s\\S]*%>/gm;\nexport const DATA_ATTR = /^data-[\\-\\w.\\u00B7-\\uFFFF]/; // eslint-disable-line no-useless-escape\nexport const ARIA_ATTR = /^aria-[\\-\\w]+$/; // eslint-disable-line no-useless-escape\nexport const IS_ALLOWED_URI = /^(?:(?:(?:f|ht)tps?|mailto|tel|callto|cid|xmpp):|[^a-z]|[a-z+.\\-]+(?:[^a-z+.\\-:]|$))/i; // eslint-disable-line no-useless-escape\nexport const IS_SCRIPT_OR_DATA = /^(?:\\w+script|data):/i;\nexport const ATTR_WHITESPACE = /[\\u0000-\\u0020\\u00A0\\u1680\\u180E\\u2000-\\u2029\\u205f\\u3000]/g; // This needs to be extensive thanks to Webkit/Blink's behavior\n"],"names":["addToSet","set","array","l","length","toLowerCase","clone","object","newObject","property","Object","prototype","hasOwnProperty","call","createDOMPurify","window","getGlobal","DOMPurify","root","version","VERSION","removed","document","nodeType","isSupported","originalDocument","useDOMParser","useXHR","DocumentFragment","HTMLTemplateElement","Node","NodeFilter","NamedNodeMap","MozNamedAttrMap","Text","Comment","DOMParser","XMLHttpRequest","encodeURI","template","createElement","content","ownerDocument","implementation","createNodeIterator","getElementsByTagName","createDocumentFragment","importNode","hooks","createHTMLDocument","documentMode","MUSTACHE_EXPR","EXPRESSIONS","ERB_EXPR","DATA_ATTR","ARIA_ATTR","IS_SCRIPT_OR_DATA","ATTR_WHITESPACE","IS_ALLOWED_URI","ALLOWED_TAGS","DEFAULT_ALLOWED_TAGS","TAGS","ALLOWED_ATTR","DEFAULT_ALLOWED_ATTR","ATTRS","FORBID_TAGS","FORBID_ATTR","ALLOW_ARIA_ATTR","ALLOW_DATA_ATTR","ALLOW_UNKNOWN_PROTOCOLS","SAFE_FOR_JQUERY","SAFE_FOR_TEMPLATES","WHOLE_DOCUMENT","SET_CONFIG","FORCE_BODY","RETURN_DOM","RETURN_DOM_FRAGMENT","RETURN_DOM_IMPORT","SANITIZE_DOM","KEEP_CONTENT","USE_PROFILES","FORBID_CONTENTS","DATA_URI_TAGS","URI_SAFE_ATTRIBUTES","CONFIG","formElement","_parseConfig","cfg","ALLOWED_URI_REGEXP","html","svg","svgFilters","mathMl","ADD_TAGS","ADD_ATTR","ADD_URI_SAFE_ATTR","freeze","_forceRemove","node","push","element","parentNode","removeChild","err","outerHTML","_removeAttribute","name","getAttributeNode","removeAttribute","_initDocument","dirty","doc","body","xhr","responseType","open","send","response","parseFromString","documentElement","firstElementChild","querySelector","_createIterator","SHOW_ELEMENT","SHOW_COMMENT","SHOW_TEXT","FILTER_ACCEPT","_isClobbered","elm","nodeName","textContent","attributes","setAttribute","_isNode","obj","_executeHook","entryPoint","currentNode","data","forEach","_sanitizeElements","tagName","insertAdjacentHTML","innerHTML","test","cloneNode","replace","_sanitizeAttributes","attr","value","lcName","idAttr","hookEvent","trim","attrName","attrValue","keepAttr","id","Array","slice","apply","indexOf","pop","_sanitizeShadowDOM","fragment","shadowNode","shadowIterator","nextNode","sanitize","importedNode","oldNode","returnNode","toString","TypeError","_typeof","toStaticHTML","appendChild","firstChild","nodeIterator","setConfig","clearConfig","addHook","hookFunction","removeHook","removeHooks","removeAllHooks","text","xml"],"mappings":"qLACA,SAAgBA,EAASC,EAAKC,WACxBC,EAAID,EAAME,OACPD,KACmB,iBAAbD,EAAMC,OACTA,GAAKD,EAAMC,GAAGE,iBAElBH,EAAMC,KAAM,SAEXF,EAIT,SAAgBK,EAAMC,OACdC,KACFC,aACCA,KAAYF,EACXG,OAAOC,UAAUC,eAAeC,KAAKN,EAAQE,OACrCA,GAAYF,EAAOE,WAG1BD,0HCdT,SAASM,QAAgBC,yDAASC,IAC1BC,EAAY,mBAAQH,EAAgBI,SAMhCC,QAAUC,UAMVC,YAELN,IAAWA,EAAOO,UAAyC,IAA7BP,EAAOO,SAASC,kBAGvCC,aAAc,EAEjBP,MAGHQ,EAAmBV,EAAOO,SAC5BI,GAAe,EACfC,GAAS,EAETL,EAAWP,EAAOO,SAEpBM,EAUEb,EAVFa,iBACAC,EASEd,EATFc,oBACAC,EAQEf,EARFe,KACAC,EAOEhB,EAPFgB,aAOEhB,EANFiB,aAAAA,aAAejB,EAAOiB,cAAgBjB,EAAOkB,kBAC7CC,EAKEnB,EALFmB,KACAC,EAIEpB,EAJFoB,QACAC,EAGErB,EAHFqB,YAGErB,EAFFsB,eAAAA,aAAiBtB,EAAOsB,mBAEtBtB,EADFuB,UAAAA,aAAYvB,EAAOuB,eASc,mBAAxBT,EAAoC,KACvCU,EAAWjB,EAASkB,cAAc,YACpCD,EAASE,SAAWF,EAASE,QAAQC,kBAC5BH,EAASE,QAAQC,qBAS5BpB,EAJFqB,IAAAA,eACAC,IAAAA,mBACAC,IAAAA,qBACAC,IAAAA,uBAEIC,EAAatB,EAAiBsB,WAEhCC,OAKMxB,YACRmB,QAC6C,IAAtCA,EAAeM,oBACI,IAA1B3B,EAAS4B,iBAGTC,EAMEC,EALFC,EAKED,EAJFE,EAIEF,EAHFG,EAGEH,EAFFI,EAEEJ,EADFK,GACEL,EAEAM,GAAiBN,EAOjBO,GAAe,KACbC,GAAuB5D,iBACxB6D,KACAA,KACAA,KACAA,KACAA,KAIDC,GAAe,KACbC,GAAuB/D,iBACxBgE,KACAA,KACAA,KACAA,KAIDC,GAAc,KAGdC,GAAc,KAGdC,IAAkB,EAGlBC,IAAkB,EAGlBC,IAA0B,EAG1BC,IAAkB,EAKlBC,IAAqB,EAGrBC,IAAiB,EAGjBC,IAAa,EAIbC,IAAa,EAKbC,IAAa,EAGbC,IAAsB,EAMtBC,IAAoB,EAGpBC,IAAe,EAGfC,IAAe,EAGfC,MAGEC,GAAkBjF,MACtB,QACA,OACA,OACA,SACA,QACA,WACA,MACA,UAIIkF,GAAgBlF,MACpB,QACA,QACA,MACA,SACA,UAIImF,GAAsBnF,MAC1B,MACA,QACA,MACA,KACA,QACA,OACA,UACA,cACA,UACA,QACA,QACA,QACA,UAIEoF,GAAS,KAKPC,GAAc/D,EAASkB,cAAc,QAQrC8C,GAAe,SAASC,GAET,qBAARA,gBAAAA,eAKT,iBAAkBA,EACdvF,KAAauF,EAAI5B,cACjBC,MAEJ,iBAAkB2B,EACdvF,KAAauF,EAAIzB,cACjBC,MACQ,gBAAiBwB,EAAMvF,KAAauF,EAAItB,mBACxC,gBAAiBsB,EAAMvF,KAAauF,EAAIrB,mBACvC,iBAAkBqB,GAAMA,EAAIP,iBACD,IAAxBO,EAAIpB,oBACoB,IAAxBoB,EAAInB,mBACImB,EAAIlB,0BAA2B,KACvCkB,EAAIjB,kBAAmB,KACpBiB,EAAIhB,qBAAsB,KAC9BgB,EAAIf,iBAAkB,KAC1Be,EAAIZ,aAAc,KACTY,EAAIX,sBAAuB,KAC7BW,EAAIV,oBAAqB,KAChCU,EAAIb,aAAc,MACK,IAArBa,EAAIT,iBACiB,IAArBS,EAAIR,gBAEFQ,EAAIC,oBAAsB9B,GAEvCa,SACgB,GAGhBK,SACW,GAIXI,QACahF,iBAAiB6D,YAEN,IAAtBmB,GAAaS,SACN9B,GAAcE,KACdC,GAAcE,KAEA,IAArBgB,GAAaU,QACN/B,GAAcE,KACdC,GAAcE,KACdF,GAAcE,KAEO,IAA5BgB,GAAaW,eACNhC,GAAcE,KACdC,GAAcE,KACdF,GAAcE,KAEG,IAAxBgB,GAAaY,WACNjC,GAAcE,KACdC,GAAcE,KACdF,GAAcE,KAKvBuB,EAAIM,WACFlC,KAAiBC,QACJtD,EAAMqD,OAEdA,GAAc4B,EAAIM,WAEzBN,EAAIO,WACFhC,KAAiBC,QACJzD,EAAMwD,OAEdA,GAAcyB,EAAIO,WAEzBP,EAAIQ,qBACGZ,GAAqBI,EAAIQ,mBAIhChB,QACW,UAAW,GAKtBrE,QAAU,WAAYA,eACjBsF,OAAOT,MAGPA,GAQLU,GAAe,SAASC,KAClB7E,QAAQ8E,MAAOC,QAASF,UAE3BG,WAAWC,YAAYJ,GAC5B,MAAOK,KACFC,UAAY,KAUfC,GAAmB,SAASC,EAAMR,KAC5B7E,QAAQ8E,gBACLD,EAAKS,iBAAiBD,QAC3BR,MAEHU,gBAAgBF,IASjBG,GAAgB,SAASC,OAEzBC,SACAC,YAEAtC,OACM,oBAAsBoC,GAI5BnF,EAAQ,OAEAW,EAAUwE,GAClB,MAAOP,QACHU,EAAM,IAAI5E,IACZ6E,aAAe,aACfC,KAAK,MAAO,gCAAkCL,GAAO,KACrDM,KAAK,QACHH,EAAII,YAIR3F,SAEM,IAAIU,GAAYkF,gBAAgBR,EAAO,aAC7C,MAAOP,WAKNQ,GAAQA,EAAIQ,wBACT5E,EAAeM,mBAAmB,KAC7B+D,MACNX,WAAWC,YAAYU,EAAKX,WAAWmB,qBACvChB,UAAYM,GAIZjE,EAAqBhC,KAAKkG,EAAKvC,GAAiB,OAAS,QAAQ,IAqBtEvD,EAAUO,4BAENuF,EAAMF,GACR,wDAEGE,EAAIU,cAAc,YACZ,UAGHZ,GACJ,qEAEMY,cAAc,gBACL,GAEjB,MAAOlB,YAUPmB,GAAkB,SAASxG,UACxB0B,EAAmB/B,KACxBK,EAAKwB,eAAiBxB,EACtBA,EACAa,EAAW4F,aAAe5F,EAAW6F,aAAe7F,EAAW8F,UAC/D,kBACS9F,EAAW+F,gBAEpB,IAUEC,GAAe,SAASC,WACxBA,aAAe9F,GAAQ8F,aAAe7F,MAIhB,iBAAjB6F,EAAIC,UACgB,iBAApBD,EAAIE,aACgB,mBAApBF,EAAI1B,aACT0B,EAAIG,sBAAsBnG,GACG,mBAAxBgG,EAAIpB,iBACiB,mBAArBoB,EAAII,eAaTC,GAAU,SAASC,SACA,qBAATxG,gBAAAA,IACVwG,aAAexG,EACfwG,GACiB,qBAARA,gBAAAA,KACiB,iBAAjBA,EAAI/G,UACa,iBAAjB+G,EAAIL,UAUbM,GAAe,SAASC,EAAYC,EAAaC,GAChD1F,EAAMwF,MAILA,GAAYG,QAAQ,cACnB9H,KAAKI,EAAWwH,EAAaC,EAAMtD,OActCwD,GAAoB,SAASH,OAC7BhG,eAGS,yBAA0BgG,EAAa,MAGhDV,GAAaU,aACFA,IACN,MAIHI,EAAUJ,EAAYR,SAAS5H,oBAGxB,sBAAuBoI,yBAErB9E,MAIVA,GAAakF,IAAY5E,GAAY4E,GAAU,IAGhD9D,KACCE,GAAgB4D,IACyB,mBAAnCJ,EAAYK,yBAGLA,mBAAmB,WAAYL,EAAYM,WACvD,MAAOxC,cAEEkC,IACN,SAKPnE,IACCmE,EAAYjB,mBACXiB,EAAYhG,SAAYgG,EAAYhG,QAAQ+E,oBAC9C,KAAKwB,KAAKP,EAAYP,iBAEZ7G,QAAQ8E,MAAOC,QAASqC,EAAYQ,gBAClCF,UAAYN,EAAYP,YAAYgB,QAAQ,KAAM,SAI5D3E,IAA+C,IAAzBkE,EAAYlH,mBAE1BkH,EAAYP,aACJgB,QAAQ/F,EAAe,MACvB+F,QAAQ7F,EAAU,KAChCoF,EAAYP,cAAgBzF,MACpBpB,QAAQ8E,MAAOC,QAASqC,EAAYQ,gBAClCf,YAAczF,OAKjB,wBAAyBgG,EAAa,OAE5C,GAeHU,GAAsB,SAASV,OAC/BW,SACA1C,SACA2C,SACAC,SACAC,SACApB,SACAhI,eAES,2BAA4BsI,EAAa,QAEzCA,EAAYN,gBAOnBqB,YACM,aACC,aACD,oBACS1F,UAEjBqE,EAAW/H,OAGRD,KAAK,MACHgI,EAAWhI,KACXiJ,EAAK1C,OACJ0C,EAAKC,MAAMI,SACV/C,EAAKrG,gBAGJqJ,SAAWJ,IACXK,UAAYN,IACZO,UAAW,KACR,wBAAyBnB,EAAae,KAC3CA,EAAUG,UAOL,SAAXL,GACyB,QAAzBb,EAAYR,UACZE,EAAW0B,KAEF1B,EAAW0B,KACPC,MAAMnJ,UAAUoJ,MAAMC,MAAM7B,MACxB,KAAMM,MACN/B,EAAM+B,GACnBN,EAAW8B,QAAQV,GAAUpJ,KACnBiI,aAAa,KAAMmB,EAAOF,WAEnC,CAAA,GAGoB,YAAbpB,UACD,SAAXqB,GACU,SAAVD,IACCvF,GAAawF,KAAYpF,GAAYoF,aAOzB,OAAT5C,KACU0B,aAAa1B,EAAM,OAEhBA,EAAM+B,MAIpBe,EAAUI,YAMb9E,IACY,OAAXwE,GAA8B,SAAXA,KACnBD,KAAS/H,GAAY+H,KAAShE,SAM7Bd,UACM8E,EAAMH,QAAQ/F,EAAe,MACvB+F,QAAQ7F,EAAU,MAO9Be,IAAmBd,EAAU0F,KAAKM,SAE/B,GAAInF,IAAmBZ,EAAUyF,KAAKM,QAGtC,CAAA,IAAKxF,GAAawF,IAAWpF,GAAYoF,YAIzC,GAAInE,GAAoBmE,SAIxB,GAAI5F,GAAesF,KAAKK,EAAMH,QAAQzF,GAAiB,WAGvD,GACO,QAAX6F,GAA+B,eAAXA,GACM,IAA3BD,EAAMY,QAAQ,WACd/E,GAAcuD,EAAYR,SAAS5H,gBAM9B,GACLgE,KACCb,EAAkBwF,KAAKK,EAAMH,QAAQzF,GAAiB,WAKlD,GAAK4F,uBASEjB,aAAa1B,EAAM2C,KACrBhI,QAAQ6I,MAClB,MAAO3D,SAIE,0BAA2BkC,EAAa,QASjD0B,GAAqB,SAArBA,EAA8BC,OAC9BC,SACEC,EAAiB5C,GAAgB0C,UAG1B,0BAA2BA,EAAU,MAE1CC,EAAaC,EAAeC,eAErB,yBAA0BF,EAAY,MAG/CzB,GAAkByB,KAKlBA,EAAW5H,mBAAmBb,KACbyI,EAAW5H,YAIZ4H,OAIT,yBAA0BD,EAAU,gBAWzCI,SAAW,SAAS1D,EAAOvB,OAC/ByB,SACAyD,SACAhC,SACAiC,SACAC,YAIC7D,MACK,eAIW,iBAAVA,IAAuBuB,GAAQvB,GAAQ,IAElB,mBAAnBA,EAAM8D,eACT,IAAIC,UAAU,iCAGC,mBADb/D,EAAM8D,kBAEN,IAAIC,UAAU,uCAMrB5J,EAAUO,YAAa,IAEO,WAA/BsJ,EAAO/J,EAAOgK,eACiB,mBAAxBhK,EAAOgK,aACd,IACqB,iBAAVjE,SACF/F,EAAOgK,aAAajE,GACtB,GAAIuB,GAAQvB,UACV/F,EAAOgK,aAAajE,EAAMN,kBAG9BM,KAIJrC,OACUc,KAILlE,WAENyF,aAAiBhF,EAKW,UAFvB+E,GAAc,gBACDnE,cAAcK,WAAW+D,GAAO,IACnCvF,UAA4C,SAA1BkJ,EAAaxC,WAEvCwC,IAEFO,YAAYP,OAEd,KAEA9F,KAAeH,KAA0C,IAAxBsC,EAAMmD,QAAQ,YAC3CnD,SAIFD,GAAcC,WAIZnC,GAAa,KAAO,GAK3BD,OACWsC,EAAKiE,oBAIdC,EAAexD,GAAgBV,GAG7ByB,EAAcyC,EAAaX,YAEJ,IAAzB9B,EAAYlH,UAAkBkH,IAAgBiC,GAK9C9B,GAAkBH,KAKlBA,EAAYhG,mBAAmBb,MACd6G,EAAYhG,YAIbgG,KAEVA,MAIR9D,GAAY,IACVC,SACW9B,EAAuBjC,KAAKmG,EAAKtE,eAEvCsE,EAAKiE,cACCD,YAAYhE,EAAKiE,mBAGjBjE,SAGXnC,OAMW9B,EAAWlC,KAAKY,EAAkBkJ,GAAY,IAGtDA,SAGFnG,GAAiBwC,EAAKR,UAAYQ,EAAK+B,aAUtCoC,UAAY,SAAS5F,MAChBA,OACA,KASL6F,YAAc,cACb,SACI,KAULC,QAAU,SAAS7C,EAAY8C,GACX,mBAAjBA,MAGL9C,GAAcxF,EAAMwF,SACpBA,GAAYrC,KAAKmF,OAWfC,WAAa,SAAS/C,GAC1BxF,EAAMwF,MACFA,GAAY0B,SAWZsB,YAAc,SAAShD,GAC3BxF,EAAMwF,OACFA,UAUAiD,eAAiB,iBAIpBxK,EC99BF,IAAMwE,GACX,IACA,OACA,UACA,UACA,OACA,UACA,QACA,QACA,IACA,MACA,MACA,MACA,QACA,aACA,OACA,KACA,SACA,SACA,UACA,SACA,OACA,OACA,MACA,WACA,UACA,OACA,WACA,KACA,YACA,MACA,UACA,MACA,MACA,MACA,KACA,KACA,UACA,KACA,WACA,aACA,SACA,OACA,SACA,OACA,KACA,KACA,KACA,KACA,KACA,KACA,OACA,SACA,SACA,KACA,OACA,IACA,MACA,QACA,MACA,MACA,QACA,SACA,KACA,OACA,MACA,OACA,UACA,OACA,WACA,QACA,MACA,OACA,KACA,WACA,SACA,SACA,IACA,MACA,WACA,IACA,KACA,KACA,OACA,IACA,OACA,UACA,SACA,SACA,QACA,SACA,SACA,OACA,SACA,SACA,QACA,MACA,UACA,MACA,QACA,QACA,KACA,WACA,WACA,QACA,KACA,QACA,OACA,KACA,QACA,KACA,IACA,KACA,MACA,QACA,OAIWC,GACX,MACA,IACA,WACA,cACA,eACA,eACA,gBACA,mBACA,QACA,SACA,SACA,WACA,OACA,OACA,UACA,SACA,OACA,IACA,QACA,WACA,QACA,QACA,OACA,iBACA,SACA,OACA,WACA,QACA,OACA,UACA,UACA,WACA,iBACA,OACA,OACA,QACA,SACA,SACA,OACA,WACA,QACA,OACA,QACA,QACA,OACA,SAGWC,GACX,UACA,gBACA,sBACA,cACA,mBACA,oBACA,oBACA,UACA,UACA,UACA,UACA,UACA,iBACA,UACA,cACA,eACA,WACA,qBACA,SACA,gBAGWC,GACX,OACA,WACA,SACA,UACA,QACA,SACA,KACA,aACA,eACA,KACA,KACA,QACA,UACA,WACA,QACA,OACA,KACA,UACA,QACA,UACA,OACA,OACA,UACA,SACA,MACA,QACA,MACA,SACA,cAGW8F,GAAQ,SC/NRjG,GACX,SACA,SACA,QACA,MACA,eACA,aACA,UACA,SACA,cACA,cACA,UACA,OACA,QACA,QACA,QACA,OACA,UACA,SACA,cACA,WACA,UACA,MACA,WACA,WACA,UACA,OACA,MACA,UACA,SACA,SACA,OACA,OACA,WACA,KACA,YACA,QACA,QACA,OACA,OACA,OACA,MACA,MACA,YACA,QACA,SACA,MACA,WACA,OACA,UACA,aACA,SACA,OACA,UACA,UACA,cACA,SACA,UACA,UACA,aACA,WACA,MACA,WACA,MACA,WACA,OACA,OACA,UACA,aACA,QACA,WACA,QACA,OACA,QACA,OACA,UACA,QACA,MACA,SACA,OACA,QACA,UACA,WACA,QACA,OACA,SACA,SACA,QACA,QACA,SAGWC,GACX,gBACA,aACA,aACA,qBACA,SACA,gBACA,gBACA,UACA,gBACA,iBACA,QACA,OACA,KACA,QACA,OACA,YACA,YACA,QACA,sBACA,8BACA,gBACA,kBACA,KACA,KACA,IACA,KACA,KACA,kBACA,YACA,UACA,UACA,MACA,WACA,YACA,MACA,OACA,eACA,YACA,SACA,cACA,gBACA,cACA,YACA,mBACA,eACA,aACA,eACA,cACA,KACA,KACA,KACA,KACA,aACA,WACA,gBACA,oBACA,SACA,OACA,KACA,kBACA,KACA,MACA,IACA,KACA,KACA,KACA,KACA,UACA,YACA,aACA,WACA,OACA,eACA,iBACA,eACA,mBACA,iBACA,QACA,aACA,aACA,eACA,eACA,cACA,cACA,mBACA,YACA,MACA,OACA,QACA,SACA,OACA,MACA,OACA,aACA,SACA,WACA,UACA,QACA,SACA,cACA,SACA,WACA,cACA,OACA,aACA,sBACA,mBACA,eACA,SACA,gBACA,IACA,KACA,KACA,SACA,OACA,OACA,cACA,YACA,UACA,SACA,SACA,QACA,OACA,kBACA,mBACA,mBACA,eACA,eACA,cACA,aACA,eACA,mBACA,oBACA,iBACA,kBACA,oBACA,iBACA,SACA,eACA,QACA,eACA,WACA,UACA,UACA,YACA,cACA,kBACA,iBACA,aACA,OACA,KACA,KACA,UACA,SACA,UACA,aACA,aACA,gBACA,gBACA,QACA,eACA,OACA,eACA,mBACA,mBACA,IACA,KACA,KACA,QACA,IACA,KACA,KACA,IACA,cAGWE,GACX,SACA,cACA,QACA,WACA,QACA,eACA,cACA,aACA,aACA,QACA,MACA,UACA,eACA,QACA,QACA,SACA,OACA,KACA,UACA,SACA,gBACA,SACA,SACA,iBACA,YACA,WACA,cACA,UACA,UACA,gBACA,WACA,WACA,OACA,WACA,WACA,aACA,UACA,SACA,SACA,cACA,gBACA,uBACA,YACA,YACA,aACA,WACA,iBACA,iBACA,YACA,UACA,QACA,SAGW+F,GACX,aACA,SACA,cACA,YACA,eCzUWxI,EAAgB,4BAChBE,EAAW,wBACXC,EAAY,6BACZC,EAAY,iBACZG,EAAiB,wFACjBF,EAAoB,wBACpBC,EAAkB,0QHDzBzC,EAAY,iBAAyB,oBAAXD,OAAyB,KAAOA,eA49BjDD"} \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/viz/assets/d3js.org/d3.v5.min.js b/tinygrad_repo/tinygrad/viz/assets/d3js.org/d3.v5.min.js deleted file mode 100644 index 344d26ccb0..0000000000 --- a/tinygrad_repo/tinygrad/viz/assets/d3js.org/d3.v5.min.js +++ /dev/null @@ -1,2 +0,0 @@ -// https://d3js.org v5.16.0 Copyright 2020 Mike Bostock -!function(t,n){"object"==typeof exports&&"undefined"!=typeof module?n(exports):"function"==typeof define&&define.amd?define(["exports"],n):n((t=t||self).d3=t.d3||{})}(this,function(t){"use strict";function n(t,n){return tn?1:t>=n?0:NaN}function e(t){var e;return 1===t.length&&(e=t,t=function(t,r){return n(e(t),r)}),{left:function(n,e,r,i){for(null==r&&(r=0),null==i&&(i=n.length);r>>1;t(n[o],e)<0?r=o+1:i=o}return r},right:function(n,e,r,i){for(null==r&&(r=0),null==i&&(i=n.length);r>>1;t(n[o],e)>0?i=o:r=o+1}return r}}}var r=e(n),i=r.right,o=r.left;function a(t,n){return[t,n]}function u(t){return null===t?NaN:+t}function c(t,n){var e,r,i=t.length,o=0,a=-1,c=0,f=0;if(null==n)for(;++a1)return f/(o-1)}function f(t,n){var e=c(t,n);return e?Math.sqrt(e):e}function s(t,n){var e,r,i,o=t.length,a=-1;if(null==n){for(;++a=e)for(r=i=e;++ae&&(r=e),i=e)for(r=i=e;++ae&&(r=e),i0)return[t];if((r=n0)for(t=Math.ceil(t/a),n=Math.floor(n/a),o=new Array(i=Math.ceil(n-t+1));++u=0?(o>=y?10:o>=_?5:o>=b?2:1)*Math.pow(10,i):-Math.pow(10,-i)/(o>=y?10:o>=_?5:o>=b?2:1)}function w(t,n,e){var r=Math.abs(n-t)/Math.max(0,e),i=Math.pow(10,Math.floor(Math.log(r)/Math.LN10)),o=r/i;return o>=y?i*=10:o>=_?i*=5:o>=b&&(i*=2),n=1)return+e(t[r-1],r-1,t);var r,i=(r-1)*n,o=Math.floor(i),a=+e(t[o],o,t);return a+(+e(t[o+1],o+1,t)-a)*(i-o)}}function T(t,n){var e,r,i=t.length,o=-1;if(null==n){for(;++o=e)for(r=e;++or&&(r=e)}else for(;++o=e)for(r=e;++or&&(r=e);return r}function A(t){for(var n,e,r,i=t.length,o=-1,a=0;++o=0;)for(n=(r=t[i]).length;--n>=0;)e[--a]=r[n];return e}function S(t,n){var e,r,i=t.length,o=-1;if(null==n){for(;++o=e)for(r=e;++oe&&(r=e)}else for(;++o=e)for(r=e;++oe&&(r=e);return r}function k(t){if(!(i=t.length))return[];for(var n=-1,e=S(t,E),r=new Array(e);++n=0&&(e=t.slice(r+1),t=t.slice(0,r)),t&&!n.hasOwnProperty(t))throw new Error("unknown type: "+t);return{type:t,name:e}})}function X(t,n){for(var e,r=0,i=t.length;r0)for(var e,r,i=new Array(e),o=0;o=0&&"xmlns"!==(n=t.slice(0,e))&&(t=t.slice(e+1)),$.hasOwnProperty(n)?{space:$[n],local:t}:t}function Z(t){var n=W(t);return(n.local?function(t){return function(){return this.ownerDocument.createElementNS(t.space,t.local)}}:function(t){return function(){var n=this.ownerDocument,e=this.namespaceURI;return e===G&&n.documentElement.namespaceURI===G?n.createElement(t):n.createElementNS(e,t)}})(n)}function Q(){}function K(t){return null==t?Q:function(){return this.querySelector(t)}}function J(){return[]}function tt(t){return null==t?J:function(){return this.querySelectorAll(t)}}function nt(t){return function(){return this.matches(t)}}function et(t){return new Array(t.length)}function rt(t,n){this.ownerDocument=t.ownerDocument,this.namespaceURI=t.namespaceURI,this._next=null,this._parent=t,this.__data__=n}rt.prototype={constructor:rt,appendChild:function(t){return this._parent.insertBefore(t,this._next)},insertBefore:function(t,n){return this._parent.insertBefore(t,n)},querySelector:function(t){return this._parent.querySelector(t)},querySelectorAll:function(t){return this._parent.querySelectorAll(t)}};var it="$";function ot(t,n,e,r,i,o){for(var a,u=0,c=n.length,f=o.length;un?1:t>=n?0:NaN}function ct(t){return t.ownerDocument&&t.ownerDocument.defaultView||t.document&&t||t.defaultView}function ft(t,n){return t.style.getPropertyValue(n)||ct(t).getComputedStyle(t,null).getPropertyValue(n)}function st(t){return t.trim().split(/^|\s+/)}function lt(t){return t.classList||new ht(t)}function ht(t){this._node=t,this._names=st(t.getAttribute("class")||"")}function dt(t,n){for(var e=lt(t),r=-1,i=n.length;++r=0&&(this._names.splice(n,1),this._node.setAttribute("class",this._names.join(" ")))},contains:function(t){return this._names.indexOf(t)>=0}};var Mt={};(t.event=null,"undefined"!=typeof document)&&("onmouseenter"in document.documentElement||(Mt={mouseenter:"mouseover",mouseleave:"mouseout"}));function Nt(t,n,e){return t=Tt(t,n,e),function(n){var e=n.relatedTarget;e&&(e===this||8&e.compareDocumentPosition(this))||t.call(this,n)}}function Tt(n,e,r){return function(i){var o=t.event;t.event=i;try{n.call(this,this.__data__,e,r)}finally{t.event=o}}}function At(t){return function(){var n=this.__on;if(n){for(var e,r=0,i=-1,o=n.length;r=m&&(m=b+1);!(_=g[m])&&++m=0;)(r=i[o])&&(a&&4^r.compareDocumentPosition(a)&&a.parentNode.insertBefore(r,a),a=r);return this},sort:function(t){function n(n,e){return n&&e?t(n.__data__,e.__data__):!n-!e}t||(t=ut);for(var e=this._groups,r=e.length,i=new Array(r),o=0;o1?this.each((null==n?function(t){return function(){this.style.removeProperty(t)}}:"function"==typeof n?function(t,n,e){return function(){var r=n.apply(this,arguments);null==r?this.style.removeProperty(t):this.style.setProperty(t,r,e)}}:function(t,n,e){return function(){this.style.setProperty(t,n,e)}})(t,n,null==e?"":e)):ft(this.node(),t)},property:function(t,n){return arguments.length>1?this.each((null==n?function(t){return function(){delete this[t]}}:"function"==typeof n?function(t,n){return function(){var e=n.apply(this,arguments);null==e?delete this[t]:this[t]=e}}:function(t,n){return function(){this[t]=n}})(t,n)):this.node()[t]},classed:function(t,n){var e=st(t+"");if(arguments.length<2){for(var r=lt(this.node()),i=-1,o=e.length;++i=0&&(n=t.slice(e+1),t=t.slice(0,e)),{type:t,name:n}})}(t+""),a=o.length;if(!(arguments.length<2)){for(u=n?St:At,null==e&&(e=!1),r=0;r>8&15|n>>4&240,n>>4&15|240&n,(15&n)<<4|15&n,1):8===e?gn(n>>24&255,n>>16&255,n>>8&255,(255&n)/255):4===e?gn(n>>12&15|n>>8&240,n>>8&15|n>>4&240,n>>4&15|240&n,((15&n)<<4|15&n)/255):null):(n=on.exec(t))?new bn(n[1],n[2],n[3],1):(n=an.exec(t))?new bn(255*n[1]/100,255*n[2]/100,255*n[3]/100,1):(n=un.exec(t))?gn(n[1],n[2],n[3],n[4]):(n=cn.exec(t))?gn(255*n[1]/100,255*n[2]/100,255*n[3]/100,n[4]):(n=fn.exec(t))?Mn(n[1],n[2]/100,n[3]/100,1):(n=sn.exec(t))?Mn(n[1],n[2]/100,n[3]/100,n[4]):ln.hasOwnProperty(t)?vn(ln[t]):"transparent"===t?new bn(NaN,NaN,NaN,0):null}function vn(t){return new bn(t>>16&255,t>>8&255,255&t,1)}function gn(t,n,e,r){return r<=0&&(t=n=e=NaN),new bn(t,n,e,r)}function yn(t){return t instanceof Jt||(t=pn(t)),t?new bn((t=t.rgb()).r,t.g,t.b,t.opacity):new bn}function _n(t,n,e,r){return 1===arguments.length?yn(t):new bn(t,n,e,null==r?1:r)}function bn(t,n,e,r){this.r=+t,this.g=+n,this.b=+e,this.opacity=+r}function mn(){return"#"+wn(this.r)+wn(this.g)+wn(this.b)}function xn(){var t=this.opacity;return(1===(t=isNaN(t)?1:Math.max(0,Math.min(1,t)))?"rgb(":"rgba(")+Math.max(0,Math.min(255,Math.round(this.r)||0))+", "+Math.max(0,Math.min(255,Math.round(this.g)||0))+", "+Math.max(0,Math.min(255,Math.round(this.b)||0))+(1===t?")":", "+t+")")}function wn(t){return((t=Math.max(0,Math.min(255,Math.round(t)||0)))<16?"0":"")+t.toString(16)}function Mn(t,n,e,r){return r<=0?t=n=e=NaN:e<=0||e>=1?t=n=NaN:n<=0&&(t=NaN),new An(t,n,e,r)}function Nn(t){if(t instanceof An)return new An(t.h,t.s,t.l,t.opacity);if(t instanceof Jt||(t=pn(t)),!t)return new An;if(t instanceof An)return t;var n=(t=t.rgb()).r/255,e=t.g/255,r=t.b/255,i=Math.min(n,e,r),o=Math.max(n,e,r),a=NaN,u=o-i,c=(o+i)/2;return u?(a=n===o?(e-r)/u+6*(e0&&c<1?0:a,new An(a,u,c,t.opacity)}function Tn(t,n,e,r){return 1===arguments.length?Nn(t):new An(t,n,e,null==r?1:r)}function An(t,n,e,r){this.h=+t,this.s=+n,this.l=+e,this.opacity=+r}function Sn(t,n,e){return 255*(t<60?n+(e-n)*t/60:t<180?e:t<240?n+(e-n)*(240-t)/60:n)}Qt(Jt,pn,{copy:function(t){return Object.assign(new this.constructor,this,t)},displayable:function(){return this.rgb().displayable()},hex:hn,formatHex:hn,formatHsl:function(){return Nn(this).formatHsl()},formatRgb:dn,toString:dn}),Qt(bn,_n,Kt(Jt,{brighter:function(t){return t=null==t?1/.7:Math.pow(1/.7,t),new bn(this.r*t,this.g*t,this.b*t,this.opacity)},darker:function(t){return t=null==t?.7:Math.pow(.7,t),new bn(this.r*t,this.g*t,this.b*t,this.opacity)},rgb:function(){return this},displayable:function(){return-.5<=this.r&&this.r<255.5&&-.5<=this.g&&this.g<255.5&&-.5<=this.b&&this.b<255.5&&0<=this.opacity&&this.opacity<=1},hex:mn,formatHex:mn,formatRgb:xn,toString:xn})),Qt(An,Tn,Kt(Jt,{brighter:function(t){return t=null==t?1/.7:Math.pow(1/.7,t),new An(this.h,this.s,this.l*t,this.opacity)},darker:function(t){return t=null==t?.7:Math.pow(.7,t),new An(this.h,this.s,this.l*t,this.opacity)},rgb:function(){var t=this.h%360+360*(this.h<0),n=isNaN(t)||isNaN(this.s)?0:this.s,e=this.l,r=e+(e<.5?e:1-e)*n,i=2*e-r;return new bn(Sn(t>=240?t-240:t+120,i,r),Sn(t,i,r),Sn(t<120?t+240:t-120,i,r),this.opacity)},displayable:function(){return(0<=this.s&&this.s<=1||isNaN(this.s))&&0<=this.l&&this.l<=1&&0<=this.opacity&&this.opacity<=1},formatHsl:function(){var t=this.opacity;return(1===(t=isNaN(t)?1:Math.max(0,Math.min(1,t)))?"hsl(":"hsla(")+(this.h||0)+", "+100*(this.s||0)+"%, "+100*(this.l||0)+"%"+(1===t?")":", "+t+")")}}));var kn=Math.PI/180,En=180/Math.PI,Cn=.96422,Pn=1,zn=.82521,Rn=4/29,Dn=6/29,qn=3*Dn*Dn,Ln=Dn*Dn*Dn;function Un(t){if(t instanceof Bn)return new Bn(t.l,t.a,t.b,t.opacity);if(t instanceof Vn)return Gn(t);t instanceof bn||(t=yn(t));var n,e,r=Hn(t.r),i=Hn(t.g),o=Hn(t.b),a=Fn((.2225045*r+.7168786*i+.0606169*o)/Pn);return r===i&&i===o?n=e=a:(n=Fn((.4360747*r+.3850649*i+.1430804*o)/Cn),e=Fn((.0139322*r+.0971045*i+.7141733*o)/zn)),new Bn(116*a-16,500*(n-a),200*(a-e),t.opacity)}function On(t,n,e,r){return 1===arguments.length?Un(t):new Bn(t,n,e,null==r?1:r)}function Bn(t,n,e,r){this.l=+t,this.a=+n,this.b=+e,this.opacity=+r}function Fn(t){return t>Ln?Math.pow(t,1/3):t/qn+Rn}function Yn(t){return t>Dn?t*t*t:qn*(t-Rn)}function In(t){return 255*(t<=.0031308?12.92*t:1.055*Math.pow(t,1/2.4)-.055)}function Hn(t){return(t/=255)<=.04045?t/12.92:Math.pow((t+.055)/1.055,2.4)}function jn(t){if(t instanceof Vn)return new Vn(t.h,t.c,t.l,t.opacity);if(t instanceof Bn||(t=Un(t)),0===t.a&&0===t.b)return new Vn(NaN,0=1?(e=1,n-1):Math.floor(e*n),i=t[r],o=t[r+1],a=r>0?t[r-1]:2*i-o,u=r180||e<-180?e-360*Math.round(e/360):e):ue(isNaN(t)?n:t)}function se(t){return 1==(t=+t)?le:function(n,e){return e-n?function(t,n,e){return t=Math.pow(t,e),n=Math.pow(n,e)-t,e=1/e,function(r){return Math.pow(t+r*n,e)}}(n,e,t):ue(isNaN(n)?e:n)}}function le(t,n){var e=n-t;return e?ce(t,e):ue(isNaN(t)?n:t)}Qt(re,ee,Kt(Jt,{brighter:function(t){return t=null==t?1/.7:Math.pow(1/.7,t),new re(this.h,this.s,this.l*t,this.opacity)},darker:function(t){return t=null==t?.7:Math.pow(.7,t),new re(this.h,this.s,this.l*t,this.opacity)},rgb:function(){var t=isNaN(this.h)?0:(this.h+120)*kn,n=+this.l,e=isNaN(this.s)?0:this.s*n*(1-n),r=Math.cos(t),i=Math.sin(t);return new bn(255*(n+e*($n*r+Wn*i)),255*(n+e*(Zn*r+Qn*i)),255*(n+e*(Kn*r)),this.opacity)}}));var he=function t(n){var e=se(n);function r(t,n){var r=e((t=_n(t)).r,(n=_n(n)).r),i=e(t.g,n.g),o=e(t.b,n.b),a=le(t.opacity,n.opacity);return function(n){return t.r=r(n),t.g=i(n),t.b=o(n),t.opacity=a(n),t+""}}return r.gamma=t,r}(1);function de(t){return function(n){var e,r,i=n.length,o=new Array(i),a=new Array(i),u=new Array(i);for(e=0;eo&&(i=n.slice(o,i),u[a]?u[a]+=i:u[++a]=i),(e=e[0])===(r=r[0])?u[a]?u[a]+=r:u[++a]=r:(u[++a]=null,c.push({i:a,x:me(e,r)})),o=Me.lastIndex;return o180?n+=360:n-t>180&&(t+=360),o.push({i:e.push(i(e)+"rotate(",null,r)-2,x:me(t,n)})):n&&e.push(i(e)+"rotate("+n+r)}(o.rotate,a.rotate,u,c),function(t,n,e,o){t!==n?o.push({i:e.push(i(e)+"skewX(",null,r)-2,x:me(t,n)}):n&&e.push(i(e)+"skewX("+n+r)}(o.skewX,a.skewX,u,c),function(t,n,e,r,o,a){if(t!==e||n!==r){var u=o.push(i(o)+"scale(",null,",",null,")");a.push({i:u-4,x:me(t,e)},{i:u-2,x:me(n,r)})}else 1===e&&1===r||o.push(i(o)+"scale("+e+","+r+")")}(o.scaleX,o.scaleY,a.scaleX,a.scaleY,u,c),o=a=null,function(t){for(var n,e=-1,r=c.length;++e=0&&n._call.call(null,t),n=n._next;--tr}function pr(){or=(ir=ur.now())+ar,tr=nr=0;try{dr()}finally{tr=0,function(){var t,n,e=Ke,r=1/0;for(;e;)e._call?(r>e._time&&(r=e._time),t=e,e=e._next):(n=e._next,e._next=null,e=t?t._next=n:Ke=n);Je=t,gr(r)}(),or=0}}function vr(){var t=ur.now(),n=t-ir;n>rr&&(ar-=n,ir=t)}function gr(t){tr||(nr&&(nr=clearTimeout(nr)),t-or>24?(t<1/0&&(nr=setTimeout(pr,t-ur.now()-ar)),er&&(er=clearInterval(er))):(er||(ir=ur.now(),er=setInterval(vr,rr)),tr=1,cr(pr)))}function yr(t,n,e){var r=new lr;return n=null==n?0:+n,r.restart(function(e){r.stop(),t(e+n)},n,e),r}lr.prototype=hr.prototype={constructor:lr,restart:function(t,n,e){if("function"!=typeof t)throw new TypeError("callback is not a function");e=(null==e?fr():+e)+(null==n?0:+n),this._next||Je===this||(Je?Je._next=this:Ke=this,Je=this),this._call=t,this._time=e,gr()},stop:function(){this._call&&(this._call=null,this._time=1/0,gr())}};var _r=I("start","end","cancel","interrupt"),br=[],mr=0,xr=1,wr=2,Mr=3,Nr=4,Tr=5,Ar=6;function Sr(t,n,e,r,i,o){var a=t.__transition;if(a){if(e in a)return}else t.__transition={};!function(t,n,e){var r,i=t.__transition;function o(c){var f,s,l,h;if(e.state!==xr)return u();for(f in i)if((h=i[f]).name===e.name){if(h.state===Mr)return yr(o);h.state===Nr?(h.state=Ar,h.timer.stop(),h.on.call("interrupt",t,t.__data__,h.index,h.group),delete i[f]):+fmr)throw new Error("too late; already scheduled");return e}function Er(t,n){var e=Cr(t,n);if(e.state>Mr)throw new Error("too late; already running");return e}function Cr(t,n){var e=t.__transition;if(!e||!(e=e[n]))throw new Error("transition not found");return e}function Pr(t,n){var e,r,i,o=t.__transition,a=!0;if(o){for(i in n=null==n?null:n+"",o)(e=o[i]).name===n?(r=e.state>wr&&e.state=0&&(t=t.slice(0,n)),!t||"start"===t})}(n)?kr:Er;return function(){var a=o(this,t),u=a.on;u!==r&&(i=(r=u).copy()).on(n,e),a.on=i}}(e,t,n))},attr:function(t,n){var e=W(t),r="transform"===e?Le:Rr;return this.attrTween(t,"function"==typeof n?(e.local?function(t,n,e){var r,i,o;return function(){var a,u,c=e(this);if(null!=c)return(a=this.getAttributeNS(t.space,t.local))===(u=c+"")?null:a===r&&u===i?o:(i=u,o=n(r=a,c));this.removeAttributeNS(t.space,t.local)}}:function(t,n,e){var r,i,o;return function(){var a,u,c=e(this);if(null!=c)return(a=this.getAttribute(t))===(u=c+"")?null:a===r&&u===i?o:(i=u,o=n(r=a,c));this.removeAttribute(t)}})(e,r,zr(this,"attr."+t,n)):null==n?(e.local?function(t){return function(){this.removeAttributeNS(t.space,t.local)}}:function(t){return function(){this.removeAttribute(t)}})(e):(e.local?function(t,n,e){var r,i,o=e+"";return function(){var a=this.getAttributeNS(t.space,t.local);return a===o?null:a===r?i:i=n(r=a,e)}}:function(t,n,e){var r,i,o=e+"";return function(){var a=this.getAttribute(t);return a===o?null:a===r?i:i=n(r=a,e)}})(e,r,n))},attrTween:function(t,n){var e="attr."+t;if(arguments.length<2)return(e=this.tween(e))&&e._value;if(null==n)return this.tween(e,null);if("function"!=typeof n)throw new Error;var r=W(t);return this.tween(e,(r.local?function(t,n){var e,r;function i(){var i=n.apply(this,arguments);return i!==r&&(e=(r=i)&&function(t,n){return function(e){this.setAttributeNS(t.space,t.local,n.call(this,e))}}(t,i)),e}return i._value=n,i}:function(t,n){var e,r;function i(){var i=n.apply(this,arguments);return i!==r&&(e=(r=i)&&function(t,n){return function(e){this.setAttribute(t,n.call(this,e))}}(t,i)),e}return i._value=n,i})(r,n))},style:function(t,n,e){var r="transform"==(t+="")?qe:Rr;return null==n?this.styleTween(t,function(t,n){var e,r,i;return function(){var o=ft(this,t),a=(this.style.removeProperty(t),ft(this,t));return o===a?null:o===e&&a===r?i:i=n(e=o,r=a)}}(t,r)).on("end.style."+t,qr(t)):"function"==typeof n?this.styleTween(t,function(t,n,e){var r,i,o;return function(){var a=ft(this,t),u=e(this),c=u+"";return null==u&&(this.style.removeProperty(t),c=u=ft(this,t)),a===c?null:a===r&&c===i?o:(i=c,o=n(r=a,u))}}(t,r,zr(this,"style."+t,n))).each(function(t,n){var e,r,i,o,a="style."+n,u="end."+a;return function(){var c=Er(this,t),f=c.on,s=null==c.value[a]?o||(o=qr(n)):void 0;f===e&&i===s||(r=(e=f).copy()).on(u,i=s),c.on=r}}(this._id,t)):this.styleTween(t,function(t,n,e){var r,i,o=e+"";return function(){var a=ft(this,t);return a===o?null:a===r?i:i=n(r=a,e)}}(t,r,n),e).on("end.style."+t,null)},styleTween:function(t,n,e){var r="style."+(t+="");if(arguments.length<2)return(r=this.tween(r))&&r._value;if(null==n)return this.tween(r,null);if("function"!=typeof n)throw new Error;return this.tween(r,function(t,n,e){var r,i;function o(){var o=n.apply(this,arguments);return o!==i&&(r=(i=o)&&function(t,n,e){return function(r){this.style.setProperty(t,n.call(this,r),e)}}(t,o,e)),r}return o._value=n,o}(t,n,null==e?"":e))},text:function(t){return this.tween("text","function"==typeof t?function(t){return function(){var n=t(this);this.textContent=null==n?"":n}}(zr(this,"text",t)):function(t){return function(){this.textContent=t}}(null==t?"":t+""))},textTween:function(t){var n="text";if(arguments.length<1)return(n=this.tween(n))&&n._value;if(null==t)return this.tween(n,null);if("function"!=typeof t)throw new Error;return this.tween(n,function(t){var n,e;function r(){var r=t.apply(this,arguments);return r!==e&&(n=(e=r)&&function(t){return function(n){this.textContent=t.call(this,n)}}(r)),n}return r._value=t,r}(t))},remove:function(){return this.on("end.remove",function(t){return function(){var n=this.parentNode;for(var e in this.__transition)if(+e!==t)return;n&&n.removeChild(this)}}(this._id))},tween:function(t,n){var e=this._id;if(t+="",arguments.length<2){for(var r,i=Cr(this.node(),e).tween,o=0,a=i.length;o0&&(r=o-P),M<0?d=p-z:M>0&&(u=c-z),x=Mi,B.attr("cursor",Pi.selection),I());break;default:return}xi()},!0).on("keyup.brush",function(){switch(t.event.keyCode){case 16:R&&(g=y=R=!1,I());break;case 18:x===Ti&&(w<0?f=h:w>0&&(r=o),M<0?d=p:M>0&&(u=c),x=Ni,I());break;case 32:x===Mi&&(t.event.altKey?(w&&(f=h-P*w,r=o+P*w),M&&(d=p-z*M,u=c+z*M),x=Ti):(w<0?f=h:w>0&&(r=o),M<0?d=p:M>0&&(u=c),x=Ni),B.attr("cursor",Pi[m]),I());break;default:return}xi()},!0),Ht(t.event.view)}mi(),Pr(b),s.call(b),U.start()}function Y(){var t=D(b);!R||g||y||(Math.abs(t[0]-L[0])>Math.abs(t[1]-L[1])?y=!0:g=!0),L=t,v=!0,xi(),I()}function I(){var t;switch(P=L[0]-q[0],z=L[1]-q[1],x){case Mi:case wi:w&&(P=Math.max(S-r,Math.min(E-f,P)),o=r+P,h=f+P),M&&(z=Math.max(k-u,Math.min(C-d,z)),c=u+z,p=d+z);break;case Ni:w<0?(P=Math.max(S-r,Math.min(E-r,P)),o=r+P,h=f):w>0&&(P=Math.max(S-f,Math.min(E-f,P)),o=r,h=f+P),M<0?(z=Math.max(k-u,Math.min(C-u,z)),c=u+z,p=d):M>0&&(z=Math.max(k-d,Math.min(C-d,z)),c=u,p=d+z);break;case Ti:w&&(o=Math.max(S,Math.min(E,r-P*w)),h=Math.max(S,Math.min(E,f+P*w))),M&&(c=Math.max(k,Math.min(C,u-z*M)),p=Math.max(k,Math.min(C,d+z*M)))}h1e-6)if(Math.abs(s*u-c*f)>1e-6&&i){var h=e-o,d=r-a,p=u*u+c*c,v=h*h+d*d,g=Math.sqrt(p),y=Math.sqrt(l),_=i*Math.tan((Qi-Math.acos((p+l-v)/(2*g*y)))/2),b=_/y,m=_/g;Math.abs(b-1)>1e-6&&(this._+="L"+(t+b*f)+","+(n+b*s)),this._+="A"+i+","+i+",0,0,"+ +(s*h>f*d)+","+(this._x1=t+m*u)+","+(this._y1=n+m*c)}else this._+="L"+(this._x1=t)+","+(this._y1=n);else;},arc:function(t,n,e,r,i,o){t=+t,n=+n,o=!!o;var a=(e=+e)*Math.cos(r),u=e*Math.sin(r),c=t+a,f=n+u,s=1^o,l=o?r-i:i-r;if(e<0)throw new Error("negative radius: "+e);null===this._x1?this._+="M"+c+","+f:(Math.abs(this._x1-c)>1e-6||Math.abs(this._y1-f)>1e-6)&&(this._+="L"+c+","+f),e&&(l<0&&(l=l%Ki+Ki),l>Ji?this._+="A"+e+","+e+",0,1,"+s+","+(t-a)+","+(n-u)+"A"+e+","+e+",0,1,"+s+","+(this._x1=c)+","+(this._y1=f):l>1e-6&&(this._+="A"+e+","+e+",0,"+ +(l>=Qi)+","+s+","+(this._x1=t+e*Math.cos(i))+","+(this._y1=n+e*Math.sin(i))))},rect:function(t,n,e,r){this._+="M"+(this._x0=this._x1=+t)+","+(this._y0=this._y1=+n)+"h"+ +e+"v"+ +r+"h"+-e+"Z"},toString:function(){return this._}};function uo(){}function co(t,n){var e=new uo;if(t instanceof uo)t.each(function(t,n){e.set(n,t)});else if(Array.isArray(t)){var r,i=-1,o=t.length;if(null==n)for(;++ir!=d>r&&e<(h-f)*(r-s)/(d-s)+f&&(i=-i)}return i}function wo(t,n,e){var r,i,o,a;return function(t,n,e){return(n[0]-t[0])*(e[1]-t[1])==(e[0]-t[0])*(n[1]-t[1])}(t,n,e)&&(i=t[r=+(t[0]===n[0])],o=e[r],a=n[r],i<=o&&o<=a||a<=o&&o<=i)}function Mo(){}var No=[[],[[[1,1.5],[.5,1]]],[[[1.5,1],[1,1.5]]],[[[1.5,1],[.5,1]]],[[[1,.5],[1.5,1]]],[[[1,1.5],[.5,1]],[[1,.5],[1.5,1]]],[[[1,.5],[1,1.5]]],[[[1,.5],[.5,1]]],[[[.5,1],[1,.5]]],[[[1,1.5],[1,.5]]],[[[.5,1],[1,.5]],[[1.5,1],[1,1.5]]],[[[1.5,1],[1,.5]]],[[[.5,1],[1.5,1]]],[[[1,1.5],[1.5,1]]],[[[.5,1],[1,1.5]]],[]];function To(){var t=1,n=1,e=M,r=u;function i(t){var n=e(t);if(Array.isArray(n))n=n.slice().sort(_o);else{var r=s(t),i=r[0],a=r[1];n=w(i,a,n),n=g(Math.floor(i/n)*n,Math.floor(a/n)*n,n)}return n.map(function(n){return o(t,n)})}function o(e,i){var o=[],u=[];return function(e,r,i){var o,u,c,f,s,l,h=new Array,d=new Array;o=u=-1,f=e[0]>=r,No[f<<1].forEach(p);for(;++o=r,No[c|f<<1].forEach(p);No[f<<0].forEach(p);for(;++u=r,s=e[u*t]>=r,No[f<<1|s<<2].forEach(p);++o=r,l=s,s=e[u*t+o+1]>=r,No[c|f<<1|s<<2|l<<3].forEach(p);No[f|s<<3].forEach(p)}o=-1,s=e[u*t]>=r,No[s<<2].forEach(p);for(;++o=r,No[s<<2|l<<3].forEach(p);function p(t){var n,e,r=[t[0][0]+o,t[0][1]+u],c=[t[1][0]+o,t[1][1]+u],f=a(r),s=a(c);(n=d[f])?(e=h[s])?(delete d[n.end],delete h[e.start],n===e?(n.ring.push(c),i(n.ring)):h[n.start]=d[e.end]={start:n.start,end:e.end,ring:n.ring.concat(e.ring)}):(delete d[n.end],n.ring.push(c),d[n.end=s]=n):(n=h[s])?(e=d[f])?(delete h[n.start],delete d[e.end],n===e?(n.ring.push(c),i(n.ring)):h[e.start]=d[n.end]={start:e.start,end:n.end,ring:e.ring.concat(n.ring)}):(delete h[n.start],n.ring.unshift(r),h[n.start=f]=n):h[f]=d[s]={start:f,end:s,ring:[r,c]}}No[s<<3].forEach(p)}(e,i,function(t){r(t,e,i),function(t){for(var n=0,e=t.length,r=t[e-1][1]*t[0][0]-t[e-1][0]*t[0][1];++n0?o.push([t]):u.push(t)}),u.forEach(function(t){for(var n,e=0,r=o.length;e0&&a0&&u0&&o>0))throw new Error("invalid size");return t=r,n=o,i},i.thresholds=function(t){return arguments.length?(e="function"==typeof t?t:Array.isArray(t)?bo(yo.call(t)):bo(t),i):e},i.smooth=function(t){return arguments.length?(r=t?u:Mo,i):r===u},i}function Ao(t,n,e){for(var r=t.width,i=t.height,o=1+(e<<1),a=0;a=e&&(u>=o&&(c-=t.data[u-o+a*r]),n.data[u-e+a*r]=c/Math.min(u+1,r-1+o-u,o))}function So(t,n,e){for(var r=t.width,i=t.height,o=1+(e<<1),a=0;a=e&&(u>=o&&(c-=t.data[a+(u-o)*r]),n.data[a+(u-e)*r]=c/Math.min(u+1,i-1+o-u,o))}function ko(t){return t[0]}function Eo(t){return t[1]}function Co(){return 1}var Po={},zo={},Ro=34,Do=10,qo=13;function Lo(t){return new Function("d","return {"+t.map(function(t,n){return JSON.stringify(t)+": d["+n+'] || ""'}).join(",")+"}")}function Uo(t){var n=Object.create(null),e=[];return t.forEach(function(t){for(var r in t)r in n||e.push(n[r]=r)}),e}function Oo(t,n){var e=t+"",r=e.length;return r9999?"+"+Oo(t,6):Oo(t,4)}(t.getUTCFullYear())+"-"+Oo(t.getUTCMonth()+1,2)+"-"+Oo(t.getUTCDate(),2)+(i?"T"+Oo(n,2)+":"+Oo(e,2)+":"+Oo(r,2)+"."+Oo(i,3)+"Z":r?"T"+Oo(n,2)+":"+Oo(e,2)+":"+Oo(r,2)+"Z":e||n?"T"+Oo(n,2)+":"+Oo(e,2)+"Z":"")}function Fo(t){var n=new RegExp('["'+t+"\n\r]"),e=t.charCodeAt(0);function r(t,n){var r,i=[],o=t.length,a=0,u=0,c=o<=0,f=!1;function s(){if(c)return zo;if(f)return f=!1,Po;var n,r,i=a;if(t.charCodeAt(i)===Ro){for(;a++=o?c=!0:(r=t.charCodeAt(a++))===Do?f=!0:r===qo&&(f=!0,t.charCodeAt(a)===Do&&++a),t.slice(i+1,n-1).replace(/""/g,'"')}for(;a=(o=(v+y)/2))?v=o:y=o,(s=e>=(a=(g+_)/2))?g=a:_=a,i=d,!(d=d[l=s<<1|f]))return i[l]=p,t;if(u=+t._x.call(null,d.data),c=+t._y.call(null,d.data),n===u&&e===c)return p.next=d,i?i[l]=p:t._root=p,t;do{i=i?i[l]=new Array(4):t._root=new Array(4),(f=n>=(o=(v+y)/2))?v=o:y=o,(s=e>=(a=(g+_)/2))?g=a:_=a}while((l=s<<1|f)==(h=(c>=a)<<1|u>=o));return i[h]=d,i[l]=p,t}function ba(t,n,e,r,i){this.node=t,this.x0=n,this.y0=e,this.x1=r,this.y1=i}function ma(t){return t[0]}function xa(t){return t[1]}function wa(t,n,e){var r=new Ma(null==n?ma:n,null==e?xa:e,NaN,NaN,NaN,NaN);return null==t?r:r.addAll(t)}function Ma(t,n,e,r,i,o){this._x=t,this._y=n,this._x0=e,this._y0=r,this._x1=i,this._y1=o,this._root=void 0}function Na(t){for(var n={data:t.data},e=n;t=t.next;)e=e.next={data:t.data};return n}var Ta=wa.prototype=Ma.prototype;function Aa(t){return t.x+t.vx}function Sa(t){return t.y+t.vy}function ka(t){return t.index}function Ea(t,n){var e=t.get(n);if(!e)throw new Error("missing: "+n);return e}function Ca(t){return t.x}function Pa(t){return t.y}Ta.copy=function(){var t,n,e=new Ma(this._x,this._y,this._x0,this._y0,this._x1,this._y1),r=this._root;if(!r)return e;if(!r.length)return e._root=Na(r),e;for(t=[{source:r,target:e._root=new Array(4)}];r=t.pop();)for(var i=0;i<4;++i)(n=r.source[i])&&(n.length?t.push({source:n,target:r.target[i]=new Array(4)}):r.target[i]=Na(n));return e},Ta.add=function(t){var n=+this._x.call(null,t),e=+this._y.call(null,t);return _a(this.cover(n,e),n,e,t)},Ta.addAll=function(t){var n,e,r,i,o=t.length,a=new Array(o),u=new Array(o),c=1/0,f=1/0,s=-1/0,l=-1/0;for(e=0;es&&(s=r),il&&(l=i));if(c>s||f>l)return this;for(this.cover(c,f).cover(s,l),e=0;et||t>=i||r>n||n>=o;)switch(u=(nh||(o=c.y0)>d||(a=c.x1)=y)<<1|t>=g)&&(c=p[p.length-1],p[p.length-1]=p[p.length-1-f],p[p.length-1-f]=c)}else{var _=t-+this._x.call(null,v.data),b=n-+this._y.call(null,v.data),m=_*_+b*b;if(m=(u=(p+g)/2))?p=u:g=u,(s=a>=(c=(v+y)/2))?v=c:y=c,n=d,!(d=d[l=s<<1|f]))return this;if(!d.length)break;(n[l+1&3]||n[l+2&3]||n[l+3&3])&&(e=n,h=l)}for(;d.data!==t;)if(r=d,!(d=d.next))return this;return(i=d.next)&&delete d.next,r?(i?r.next=i:delete r.next,this):n?(i?n[l]=i:delete n[l],(d=n[0]||n[1]||n[2]||n[3])&&d===(n[3]||n[2]||n[1]||n[0])&&!d.length&&(e?e[h]=d:this._root=d),this):(this._root=i,this)},Ta.removeAll=function(t){for(var n=0,e=t.length;n1?r[0]+r.slice(2):r,+t.slice(e+1)]}function qa(t){return(t=Da(Math.abs(t)))?t[1]:NaN}var La,Ua=/^(?:(.)?([<>=^]))?([+\-( ])?([$#])?(0)?(\d+)?(,)?(\.\d+)?(~)?([a-z%])?$/i;function Oa(t){if(!(n=Ua.exec(t)))throw new Error("invalid format: "+t);var n;return new Ba({fill:n[1],align:n[2],sign:n[3],symbol:n[4],zero:n[5],width:n[6],comma:n[7],precision:n[8]&&n[8].slice(1),trim:n[9],type:n[10]})}function Ba(t){this.fill=void 0===t.fill?" ":t.fill+"",this.align=void 0===t.align?">":t.align+"",this.sign=void 0===t.sign?"-":t.sign+"",this.symbol=void 0===t.symbol?"":t.symbol+"",this.zero=!!t.zero,this.width=void 0===t.width?void 0:+t.width,this.comma=!!t.comma,this.precision=void 0===t.precision?void 0:+t.precision,this.trim=!!t.trim,this.type=void 0===t.type?"":t.type+""}function Fa(t,n){var e=Da(t,n);if(!e)return t+"";var r=e[0],i=e[1];return i<0?"0."+new Array(-i).join("0")+r:r.length>i+1?r.slice(0,i+1)+"."+r.slice(i+1):r+new Array(i-r.length+2).join("0")}Oa.prototype=Ba.prototype,Ba.prototype.toString=function(){return this.fill+this.align+this.sign+this.symbol+(this.zero?"0":"")+(void 0===this.width?"":Math.max(1,0|this.width))+(this.comma?",":"")+(void 0===this.precision?"":"."+Math.max(0,0|this.precision))+(this.trim?"~":"")+this.type};var Ya={"%":function(t,n){return(100*t).toFixed(n)},b:function(t){return Math.round(t).toString(2)},c:function(t){return t+""},d:function(t){return Math.round(t).toString(10)},e:function(t,n){return t.toExponential(n)},f:function(t,n){return t.toFixed(n)},g:function(t,n){return t.toPrecision(n)},o:function(t){return Math.round(t).toString(8)},p:function(t,n){return Fa(100*t,n)},r:Fa,s:function(t,n){var e=Da(t,n);if(!e)return t+"";var r=e[0],i=e[1],o=i-(La=3*Math.max(-8,Math.min(8,Math.floor(i/3))))+1,a=r.length;return o===a?r:o>a?r+new Array(o-a+1).join("0"):o>0?r.slice(0,o)+"."+r.slice(o):"0."+new Array(1-o).join("0")+Da(t,Math.max(0,n+o-1))[0]},X:function(t){return Math.round(t).toString(16).toUpperCase()},x:function(t){return Math.round(t).toString(16)}};function Ia(t){return t}var Ha,ja=Array.prototype.map,Xa=["y","z","a","f","p","n","µ","m","","k","M","G","T","P","E","Z","Y"];function Va(t){var n,e,r=void 0===t.grouping||void 0===t.thousands?Ia:(n=ja.call(t.grouping,Number),e=t.thousands+"",function(t,r){for(var i=t.length,o=[],a=0,u=n[0],c=0;i>0&&u>0&&(c+u+1>r&&(u=Math.max(1,r-c)),o.push(t.substring(i-=u,i+u)),!((c+=u+1)>r));)u=n[a=(a+1)%n.length];return o.reverse().join(e)}),i=void 0===t.currency?"":t.currency[0]+"",o=void 0===t.currency?"":t.currency[1]+"",a=void 0===t.decimal?".":t.decimal+"",u=void 0===t.numerals?Ia:function(t){return function(n){return n.replace(/[0-9]/g,function(n){return t[+n]})}}(ja.call(t.numerals,String)),c=void 0===t.percent?"%":t.percent+"",f=void 0===t.minus?"-":t.minus+"",s=void 0===t.nan?"NaN":t.nan+"";function l(t){var n=(t=Oa(t)).fill,e=t.align,l=t.sign,h=t.symbol,d=t.zero,p=t.width,v=t.comma,g=t.precision,y=t.trim,_=t.type;"n"===_?(v=!0,_="g"):Ya[_]||(void 0===g&&(g=12),y=!0,_="g"),(d||"0"===n&&"="===e)&&(d=!0,n="0",e="=");var b="$"===h?i:"#"===h&&/[boxX]/.test(_)?"0"+_.toLowerCase():"",m="$"===h?o:/[%p]/.test(_)?c:"",x=Ya[_],w=/[defgprs%]/.test(_);function M(t){var i,o,c,h=b,M=m;if("c"===_)M=x(t)+M,t="";else{var N=(t=+t)<0||1/t<0;if(t=isNaN(t)?s:x(Math.abs(t),g),y&&(t=function(t){t:for(var n,e=t.length,r=1,i=-1;r0&&(i=0)}return i>0?t.slice(0,i)+t.slice(n+1):t}(t)),N&&0==+t&&"+"!==l&&(N=!1),h=(N?"("===l?l:f:"-"===l||"("===l?"":l)+h,M=("s"===_?Xa[8+La/3]:"")+M+(N&&"("===l?")":""),w)for(i=-1,o=t.length;++i(c=t.charCodeAt(i))||c>57){M=(46===c?a+t.slice(i+1):t.slice(i))+M,t=t.slice(0,i);break}}v&&!d&&(t=r(t,1/0));var T=h.length+t.length+M.length,A=T>1)+h+t+M+A.slice(T);break;default:t=A+h+t+M}return u(t)}return g=void 0===g?6:/[gprs]/.test(_)?Math.max(1,Math.min(21,g)):Math.max(0,Math.min(20,g)),M.toString=function(){return t+""},M}return{format:l,formatPrefix:function(t,n){var e=l(((t=Oa(t)).type="f",t)),r=3*Math.max(-8,Math.min(8,Math.floor(qa(n)/3))),i=Math.pow(10,-r),o=Xa[8+r/3];return function(t){return e(i*t)+o}}}}function Ga(n){return Ha=Va(n),t.format=Ha.format,t.formatPrefix=Ha.formatPrefix,Ha}function $a(t){return Math.max(0,-qa(Math.abs(t)))}function Wa(t,n){return Math.max(0,3*Math.max(-8,Math.min(8,Math.floor(qa(n)/3)))-qa(Math.abs(t)))}function Za(t,n){return t=Math.abs(t),n=Math.abs(n)-t,Math.max(0,qa(n)-qa(t))+1}function Qa(){return new Ka}function Ka(){this.reset()}Ga({decimal:".",thousands:",",grouping:[3],currency:["$",""],minus:"-"}),Ka.prototype={constructor:Ka,reset:function(){this.s=this.t=0},add:function(t){tu(Ja,t,this.t),tu(this,Ja.s,this.s),this.s?this.t+=Ja.t:this.s=Ja.t},valueOf:function(){return this.s}};var Ja=new Ka;function tu(t,n,e){var r=t.s=n+e,i=r-n,o=r-i;t.t=n-o+(e-i)}var nu=1e-6,eu=1e-12,ru=Math.PI,iu=ru/2,ou=ru/4,au=2*ru,uu=180/ru,cu=ru/180,fu=Math.abs,su=Math.atan,lu=Math.atan2,hu=Math.cos,du=Math.ceil,pu=Math.exp,vu=Math.log,gu=Math.pow,yu=Math.sin,_u=Math.sign||function(t){return t>0?1:t<0?-1:0},bu=Math.sqrt,mu=Math.tan;function xu(t){return t>1?0:t<-1?ru:Math.acos(t)}function wu(t){return t>1?iu:t<-1?-iu:Math.asin(t)}function Mu(t){return(t=yu(t/2))*t}function Nu(){}function Tu(t,n){t&&Su.hasOwnProperty(t.type)&&Su[t.type](t,n)}var Au={Feature:function(t,n){Tu(t.geometry,n)},FeatureCollection:function(t,n){for(var e=t.features,r=-1,i=e.length;++r=0?1:-1,i=r*e,o=hu(n=(n*=cu)/2+ou),a=yu(n),u=qu*a,c=Du*o+u*hu(i),f=u*r*yu(i);Lu.add(lu(f,c)),Ru=t,Du=o,qu=a}function Hu(t){return[lu(t[1],t[0]),wu(t[2])]}function ju(t){var n=t[0],e=t[1],r=hu(e);return[r*hu(n),r*yu(n),yu(e)]}function Xu(t,n){return t[0]*n[0]+t[1]*n[1]+t[2]*n[2]}function Vu(t,n){return[t[1]*n[2]-t[2]*n[1],t[2]*n[0]-t[0]*n[2],t[0]*n[1]-t[1]*n[0]]}function Gu(t,n){t[0]+=n[0],t[1]+=n[1],t[2]+=n[2]}function $u(t,n){return[t[0]*n,t[1]*n,t[2]*n]}function Wu(t){var n=bu(t[0]*t[0]+t[1]*t[1]+t[2]*t[2]);t[0]/=n,t[1]/=n,t[2]/=n}var Zu,Qu,Ku,Ju,tc,nc,ec,rc,ic,oc,ac,uc,cc,fc,sc,lc,hc,dc,pc,vc,gc,yc,_c,bc,mc,xc,wc=Qa(),Mc={point:Nc,lineStart:Ac,lineEnd:Sc,polygonStart:function(){Mc.point=kc,Mc.lineStart=Ec,Mc.lineEnd=Cc,wc.reset(),Ou.polygonStart()},polygonEnd:function(){Ou.polygonEnd(),Mc.point=Nc,Mc.lineStart=Ac,Mc.lineEnd=Sc,Lu<0?(Zu=-(Ku=180),Qu=-(Ju=90)):wc>nu?Ju=90:wc<-nu&&(Qu=-90),oc[0]=Zu,oc[1]=Ku},sphere:function(){Zu=-(Ku=180),Qu=-(Ju=90)}};function Nc(t,n){ic.push(oc=[Zu=t,Ku=t]),nJu&&(Ju=n)}function Tc(t,n){var e=ju([t*cu,n*cu]);if(rc){var r=Vu(rc,e),i=Vu([r[1],-r[0],0],r);Wu(i),i=Hu(i);var o,a=t-tc,u=a>0?1:-1,c=i[0]*uu*u,f=fu(a)>180;f^(u*tcJu&&(Ju=o):f^(u*tc<(c=(c+360)%360-180)&&cJu&&(Ju=n)),f?tPc(Zu,Ku)&&(Ku=t):Pc(t,Ku)>Pc(Zu,Ku)&&(Zu=t):Ku>=Zu?(tKu&&(Ku=t)):t>tc?Pc(Zu,t)>Pc(Zu,Ku)&&(Ku=t):Pc(t,Ku)>Pc(Zu,Ku)&&(Zu=t)}else ic.push(oc=[Zu=t,Ku=t]);nJu&&(Ju=n),rc=e,tc=t}function Ac(){Mc.point=Tc}function Sc(){oc[0]=Zu,oc[1]=Ku,Mc.point=Nc,rc=null}function kc(t,n){if(rc){var e=t-tc;wc.add(fu(e)>180?e+(e>0?360:-360):e)}else nc=t,ec=n;Ou.point(t,n),Tc(t,n)}function Ec(){Ou.lineStart()}function Cc(){kc(nc,ec),Ou.lineEnd(),fu(wc)>nu&&(Zu=-(Ku=180)),oc[0]=Zu,oc[1]=Ku,rc=null}function Pc(t,n){return(n-=t)<0?n+360:n}function zc(t,n){return t[0]-n[0]}function Rc(t,n){return t[0]<=t[1]?t[0]<=n&&n<=t[1]:nru?t+Math.round(-t/au)*au:t,n]}function $c(t,n,e){return(t%=au)?n||e?Vc(Zc(t),Qc(n,e)):Zc(t):n||e?Qc(n,e):Gc}function Wc(t){return function(n,e){return[(n+=t)>ru?n-au:n<-ru?n+au:n,e]}}function Zc(t){var n=Wc(t);return n.invert=Wc(-t),n}function Qc(t,n){var e=hu(t),r=yu(t),i=hu(n),o=yu(n);function a(t,n){var a=hu(n),u=hu(t)*a,c=yu(t)*a,f=yu(n),s=f*e+u*r;return[lu(c*i-s*o,u*e-f*r),wu(s*i+c*o)]}return a.invert=function(t,n){var a=hu(n),u=hu(t)*a,c=yu(t)*a,f=yu(n),s=f*i-c*o;return[lu(c*i+f*o,u*e+s*r),wu(s*e-u*r)]},a}function Kc(t){function n(n){return(n=t(n[0]*cu,n[1]*cu))[0]*=uu,n[1]*=uu,n}return t=$c(t[0]*cu,t[1]*cu,t.length>2?t[2]*cu:0),n.invert=function(n){return(n=t.invert(n[0]*cu,n[1]*cu))[0]*=uu,n[1]*=uu,n},n}function Jc(t,n,e,r,i,o){if(e){var a=hu(n),u=yu(n),c=r*e;null==i?(i=n+r*au,o=n-c/2):(i=tf(a,i),o=tf(a,o),(r>0?io)&&(i+=r*au));for(var f,s=i;r>0?s>o:s1&&n.push(n.pop().concat(n.shift()))},result:function(){var e=n;return n=[],t=null,e}}}function ef(t,n){return fu(t[0]-n[0])=0;--o)i.point((s=f[o])[0],s[1]);else r(h.x,h.p.x,-1,i);h=h.p}f=(h=h.o).z,d=!d}while(!h.v);i.lineEnd()}}}function af(t){if(n=t.length){for(var n,e,r=0,i=t[0];++r=0?1:-1,T=N*M,A=T>ru,S=v*x;if(uf.add(lu(S*N*yu(T),g*w+S*hu(T))),a+=A?M+N*au:M,A^d>=e^b>=e){var k=Vu(ju(h),ju(_));Wu(k);var E=Vu(o,k);Wu(E);var C=(A^M>=0?-1:1)*wu(E[2]);(r>C||r===C&&(k[0]||k[1]))&&(u+=A^M>=0?1:-1)}}return(a<-nu||a0){for(l||(i.polygonStart(),l=!0),i.lineStart(),t=0;t1&&2&c&&h.push(h.pop().concat(h.shift())),a.push(h.filter(lf))}return h}}function lf(t){return t.length>1}function hf(t,n){return((t=t.x)[0]<0?t[1]-iu-nu:iu-t[1])-((n=n.x)[0]<0?n[1]-iu-nu:iu-n[1])}var df=sf(function(){return!0},function(t){var n,e=NaN,r=NaN,i=NaN;return{lineStart:function(){t.lineStart(),n=1},point:function(o,a){var u=o>0?ru:-ru,c=fu(o-e);fu(c-ru)0?iu:-iu),t.point(i,r),t.lineEnd(),t.lineStart(),t.point(u,r),t.point(o,r),n=0):i!==u&&c>=ru&&(fu(e-i)nu?su((yu(n)*(o=hu(r))*yu(e)-yu(r)*(i=hu(n))*yu(t))/(i*o*a)):(n+r)/2}(e,r,o,a),t.point(i,r),t.lineEnd(),t.lineStart(),t.point(u,r),n=0),t.point(e=o,r=a),i=u},lineEnd:function(){t.lineEnd(),e=r=NaN},clean:function(){return 2-n}}},function(t,n,e,r){var i;if(null==t)i=e*iu,r.point(-ru,i),r.point(0,i),r.point(ru,i),r.point(ru,0),r.point(ru,-i),r.point(0,-i),r.point(-ru,-i),r.point(-ru,0),r.point(-ru,i);else if(fu(t[0]-n[0])>nu){var o=t[0]0,i=fu(n)>nu;function o(t,e){return hu(t)*hu(e)>n}function a(t,e,r){var i=[1,0,0],o=Vu(ju(t),ju(e)),a=Xu(o,o),u=o[0],c=a-u*u;if(!c)return!r&&t;var f=n*a/c,s=-n*u/c,l=Vu(i,o),h=$u(i,f);Gu(h,$u(o,s));var d=l,p=Xu(h,d),v=Xu(d,d),g=p*p-v*(Xu(h,h)-1);if(!(g<0)){var y=bu(g),_=$u(d,(-p-y)/v);if(Gu(_,h),_=Hu(_),!r)return _;var b,m=t[0],x=e[0],w=t[1],M=e[1];x0^_[1]<(fu(_[0]-m)ru^(m<=_[0]&&_[0]<=x)){var A=$u(d,(-p+y)/v);return Gu(A,h),[_,Hu(A)]}}}function u(n,e){var i=r?t:ru-t,o=0;return n<-i?o|=1:n>i&&(o|=2),e<-i?o|=4:e>i&&(o|=8),o}return sf(o,function(t){var n,e,c,f,s;return{lineStart:function(){f=c=!1,s=1},point:function(l,h){var d,p=[l,h],v=o(l,h),g=r?v?0:u(l,h):v?u(l+(l<0?ru:-ru),h):0;if(!n&&(f=c=v)&&t.lineStart(),v!==c&&(!(d=a(n,p))||ef(n,d)||ef(p,d))&&(p[0]+=nu,p[1]+=nu,v=o(p[0],p[1])),v!==c)s=0,v?(t.lineStart(),d=a(p,n),t.point(d[0],d[1])):(d=a(n,p),t.point(d[0],d[1]),t.lineEnd()),n=d;else if(i&&n&&r^v){var y;g&e||!(y=a(p,n,!0))||(s=0,r?(t.lineStart(),t.point(y[0][0],y[0][1]),t.point(y[1][0],y[1][1]),t.lineEnd()):(t.point(y[1][0],y[1][1]),t.lineEnd(),t.lineStart(),t.point(y[0][0],y[0][1])))}!v||n&&ef(n,p)||t.point(p[0],p[1]),n=p,c=v,e=g},lineEnd:function(){c&&t.lineEnd(),n=null},clean:function(){return s|(f&&c)<<1}}},function(n,r,i,o){Jc(o,t,e,i,n,r)},r?[0,-t]:[-ru,t-ru])}var vf=1e9,gf=-vf;function yf(t,n,e,r){function i(i,o){return t<=i&&i<=e&&n<=o&&o<=r}function o(i,o,u,f){var s=0,l=0;if(null==i||(s=a(i,u))!==(l=a(o,u))||c(i,o)<0^u>0)do{f.point(0===s||3===s?t:e,s>1?r:n)}while((s=(s+u+4)%4)!==l);else f.point(o[0],o[1])}function a(r,i){return fu(r[0]-t)0?0:3:fu(r[0]-e)0?2:1:fu(r[1]-n)0?1:0:i>0?3:2}function u(t,n){return c(t.x,n.x)}function c(t,n){var e=a(t,1),r=a(n,1);return e!==r?e-r:0===e?n[1]-t[1]:1===e?t[0]-n[0]:2===e?t[1]-n[1]:n[0]-t[0]}return function(a){var c,f,s,l,h,d,p,v,g,y,_,b=a,m=nf(),x={point:w,lineStart:function(){x.point=M,f&&f.push(s=[]);y=!0,g=!1,p=v=NaN},lineEnd:function(){c&&(M(l,h),d&&g&&m.rejoin(),c.push(m.result()));x.point=w,g&&b.lineEnd()},polygonStart:function(){b=m,c=[],f=[],_=!0},polygonEnd:function(){var n=function(){for(var n=0,e=0,i=f.length;er&&(h-o)*(r-a)>(d-a)*(t-o)&&++n:d<=r&&(h-o)*(r-a)<(d-a)*(t-o)&&--n;return n}(),e=_&&n,i=(c=A(c)).length;(e||i)&&(a.polygonStart(),e&&(a.lineStart(),o(null,null,1,a),a.lineEnd()),i&&of(c,u,n,o,a),a.polygonEnd());b=a,c=f=s=null}};function w(t,n){i(t,n)&&b.point(t,n)}function M(o,a){var u=i(o,a);if(f&&s.push([o,a]),y)l=o,h=a,d=u,y=!1,u&&(b.lineStart(),b.point(o,a));else if(u&&g)b.point(o,a);else{var c=[p=Math.max(gf,Math.min(vf,p)),v=Math.max(gf,Math.min(vf,v))],m=[o=Math.max(gf,Math.min(vf,o)),a=Math.max(gf,Math.min(vf,a))];!function(t,n,e,r,i,o){var a,u=t[0],c=t[1],f=0,s=1,l=n[0]-u,h=n[1]-c;if(a=e-u,l||!(a>0)){if(a/=l,l<0){if(a0){if(a>s)return;a>f&&(f=a)}if(a=i-u,l||!(a<0)){if(a/=l,l<0){if(a>s)return;a>f&&(f=a)}else if(l>0){if(a0)){if(a/=h,h<0){if(a0){if(a>s)return;a>f&&(f=a)}if(a=o-c,h||!(a<0)){if(a/=h,h<0){if(a>s)return;a>f&&(f=a)}else if(h>0){if(a0&&(t[0]=u+f*l,t[1]=c+f*h),s<1&&(n[0]=u+s*l,n[1]=c+s*h),!0}}}}}(c,m,t,n,e,r)?u&&(b.lineStart(),b.point(o,a),_=!1):(g||(b.lineStart(),b.point(c[0],c[1])),b.point(m[0],m[1]),u||b.lineEnd(),_=!1)}p=o,v=a,g=u}return x}}var _f,bf,mf,xf=Qa(),wf={sphere:Nu,point:Nu,lineStart:function(){wf.point=Nf,wf.lineEnd=Mf},lineEnd:Nu,polygonStart:Nu,polygonEnd:Nu};function Mf(){wf.point=wf.lineEnd=Nu}function Nf(t,n){_f=t*=cu,bf=yu(n*=cu),mf=hu(n),wf.point=Tf}function Tf(t,n){t*=cu;var e=yu(n*=cu),r=hu(n),i=fu(t-_f),o=hu(i),a=r*yu(i),u=mf*e-bf*r*o,c=bf*e+mf*r*o;xf.add(lu(bu(a*a+u*u),c)),_f=t,bf=e,mf=r}function Af(t){return xf.reset(),Cu(t,wf),+xf}var Sf=[null,null],kf={type:"LineString",coordinates:Sf};function Ef(t,n){return Sf[0]=t,Sf[1]=n,Af(kf)}var Cf={Feature:function(t,n){return zf(t.geometry,n)},FeatureCollection:function(t,n){for(var e=t.features,r=-1,i=e.length;++r0&&(i=Ef(t[o],t[o-1]))>0&&e<=i&&r<=i&&(e+r-i)*(1-Math.pow((e-r)/i,2))nu}).map(c)).concat(g(du(o/d)*d,i,d).filter(function(t){return fu(t%v)>nu}).map(f))}return _.lines=function(){return b().map(function(t){return{type:"LineString",coordinates:t}})},_.outline=function(){return{type:"Polygon",coordinates:[s(r).concat(l(a).slice(1),s(e).reverse().slice(1),l(u).reverse().slice(1))]}},_.extent=function(t){return arguments.length?_.extentMajor(t).extentMinor(t):_.extentMinor()},_.extentMajor=function(t){return arguments.length?(r=+t[0][0],e=+t[1][0],u=+t[0][1],a=+t[1][1],r>e&&(t=r,r=e,e=t),u>a&&(t=u,u=a,a=t),_.precision(y)):[[r,u],[e,a]]},_.extentMinor=function(e){return arguments.length?(n=+e[0][0],t=+e[1][0],o=+e[0][1],i=+e[1][1],n>t&&(e=n,n=t,t=e),o>i&&(e=o,o=i,i=e),_.precision(y)):[[n,o],[t,i]]},_.step=function(t){return arguments.length?_.stepMajor(t).stepMinor(t):_.stepMinor()},_.stepMajor=function(t){return arguments.length?(p=+t[0],v=+t[1],_):[p,v]},_.stepMinor=function(t){return arguments.length?(h=+t[0],d=+t[1],_):[h,d]},_.precision=function(h){return arguments.length?(y=+h,c=Of(o,i,90),f=Bf(n,t,y),s=Of(u,a,90),l=Bf(r,e,y),_):y},_.extentMajor([[-180,-90+nu],[180,90-nu]]).extentMinor([[-180,-80-nu],[180,80+nu]])}function Yf(t){return t}var If,Hf,jf,Xf,Vf=Qa(),Gf=Qa(),$f={point:Nu,lineStart:Nu,lineEnd:Nu,polygonStart:function(){$f.lineStart=Wf,$f.lineEnd=Kf},polygonEnd:function(){$f.lineStart=$f.lineEnd=$f.point=Nu,Vf.add(fu(Gf)),Gf.reset()},result:function(){var t=Vf/2;return Vf.reset(),t}};function Wf(){$f.point=Zf}function Zf(t,n){$f.point=Qf,If=jf=t,Hf=Xf=n}function Qf(t,n){Gf.add(Xf*t-jf*n),jf=t,Xf=n}function Kf(){Qf(If,Hf)}var Jf=1/0,ts=Jf,ns=-Jf,es=ns,rs={point:function(t,n){tns&&(ns=t);nes&&(es=n)},lineStart:Nu,lineEnd:Nu,polygonStart:Nu,polygonEnd:Nu,result:function(){var t=[[Jf,ts],[ns,es]];return ns=es=-(ts=Jf=1/0),t}};var is,os,as,us,cs=0,fs=0,ss=0,ls=0,hs=0,ds=0,ps=0,vs=0,gs=0,ys={point:_s,lineStart:bs,lineEnd:ws,polygonStart:function(){ys.lineStart=Ms,ys.lineEnd=Ns},polygonEnd:function(){ys.point=_s,ys.lineStart=bs,ys.lineEnd=ws},result:function(){var t=gs?[ps/gs,vs/gs]:ds?[ls/ds,hs/ds]:ss?[cs/ss,fs/ss]:[NaN,NaN];return cs=fs=ss=ls=hs=ds=ps=vs=gs=0,t}};function _s(t,n){cs+=t,fs+=n,++ss}function bs(){ys.point=ms}function ms(t,n){ys.point=xs,_s(as=t,us=n)}function xs(t,n){var e=t-as,r=n-us,i=bu(e*e+r*r);ls+=i*(as+t)/2,hs+=i*(us+n)/2,ds+=i,_s(as=t,us=n)}function ws(){ys.point=_s}function Ms(){ys.point=Ts}function Ns(){As(is,os)}function Ts(t,n){ys.point=As,_s(is=as=t,os=us=n)}function As(t,n){var e=t-as,r=n-us,i=bu(e*e+r*r);ls+=i*(as+t)/2,hs+=i*(us+n)/2,ds+=i,ps+=(i=us*t-as*n)*(as+t),vs+=i*(us+n),gs+=3*i,_s(as=t,us=n)}function Ss(t){this._context=t}Ss.prototype={_radius:4.5,pointRadius:function(t){return this._radius=t,this},polygonStart:function(){this._line=0},polygonEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){0===this._line&&this._context.closePath(),this._point=NaN},point:function(t,n){switch(this._point){case 0:this._context.moveTo(t,n),this._point=1;break;case 1:this._context.lineTo(t,n);break;default:this._context.moveTo(t+this._radius,n),this._context.arc(t,n,this._radius,0,au)}},result:Nu};var ks,Es,Cs,Ps,zs,Rs=Qa(),Ds={point:Nu,lineStart:function(){Ds.point=qs},lineEnd:function(){ks&&Ls(Es,Cs),Ds.point=Nu},polygonStart:function(){ks=!0},polygonEnd:function(){ks=null},result:function(){var t=+Rs;return Rs.reset(),t}};function qs(t,n){Ds.point=Ls,Es=Ps=t,Cs=zs=n}function Ls(t,n){Ps-=t,zs-=n,Rs.add(bu(Ps*Ps+zs*zs)),Ps=t,zs=n}function Us(){this._string=[]}function Os(t){return"m0,"+t+"a"+t+","+t+" 0 1,1 0,"+-2*t+"a"+t+","+t+" 0 1,1 0,"+2*t+"z"}function Bs(t){return function(n){var e=new Fs;for(var r in t)e[r]=t[r];return e.stream=n,e}}function Fs(){}function Ys(t,n,e){var r=t.clipExtent&&t.clipExtent();return t.scale(150).translate([0,0]),null!=r&&t.clipExtent(null),Cu(e,t.stream(rs)),n(rs.result()),null!=r&&t.clipExtent(r),t}function Is(t,n,e){return Ys(t,function(e){var r=n[1][0]-n[0][0],i=n[1][1]-n[0][1],o=Math.min(r/(e[1][0]-e[0][0]),i/(e[1][1]-e[0][1])),a=+n[0][0]+(r-o*(e[1][0]+e[0][0]))/2,u=+n[0][1]+(i-o*(e[1][1]+e[0][1]))/2;t.scale(150*o).translate([a,u])},e)}function Hs(t,n,e){return Is(t,[[0,0],n],e)}function js(t,n,e){return Ys(t,function(e){var r=+n,i=r/(e[1][0]-e[0][0]),o=(r-i*(e[1][0]+e[0][0]))/2,a=-i*e[0][1];t.scale(150*i).translate([o,a])},e)}function Xs(t,n,e){return Ys(t,function(e){var r=+n,i=r/(e[1][1]-e[0][1]),o=-i*e[0][0],a=(r-i*(e[1][1]+e[0][1]))/2;t.scale(150*i).translate([o,a])},e)}Us.prototype={_radius:4.5,_circle:Os(4.5),pointRadius:function(t){return(t=+t)!==this._radius&&(this._radius=t,this._circle=null),this},polygonStart:function(){this._line=0},polygonEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){0===this._line&&this._string.push("Z"),this._point=NaN},point:function(t,n){switch(this._point){case 0:this._string.push("M",t,",",n),this._point=1;break;case 1:this._string.push("L",t,",",n);break;default:null==this._circle&&(this._circle=Os(this._radius)),this._string.push("M",t,",",n,this._circle)}},result:function(){if(this._string.length){var t=this._string.join("");return this._string=[],t}return null}},Fs.prototype={constructor:Fs,point:function(t,n){this.stream.point(t,n)},sphere:function(){this.stream.sphere()},lineStart:function(){this.stream.lineStart()},lineEnd:function(){this.stream.lineEnd()},polygonStart:function(){this.stream.polygonStart()},polygonEnd:function(){this.stream.polygonEnd()}};var Vs=16,Gs=hu(30*cu);function $s(t,n){return+n?function(t,n){function e(r,i,o,a,u,c,f,s,l,h,d,p,v,g){var y=f-r,_=s-i,b=y*y+_*_;if(b>4*n&&v--){var m=a+h,x=u+d,w=c+p,M=bu(m*m+x*x+w*w),N=wu(w/=M),T=fu(fu(w)-1)n||fu((y*E+_*C)/b-.5)>.3||a*h+u*d+c*p2?t[2]%360*cu:0,E()):[g*uu,y*uu,_*uu]},S.angle=function(t){return arguments.length?(b=t%360*cu,E()):b*uu},S.reflectX=function(t){return arguments.length?(m=t?-1:1,E()):m<0},S.reflectY=function(t){return arguments.length?(x=t?-1:1,E()):x<0},S.precision=function(t){return arguments.length?(a=$s(u,A=t*t),C()):bu(A)},S.fitExtent=function(t,n){return Is(S,t,n)},S.fitSize=function(t,n){return Hs(S,t,n)},S.fitWidth=function(t,n){return js(S,t,n)},S.fitHeight=function(t,n){return Xs(S,t,n)},function(){return n=t.apply(this,arguments),S.invert=n.invert&&k,E()}}function Js(t){var n=0,e=ru/3,r=Ks(t),i=r(n,e);return i.parallels=function(t){return arguments.length?r(n=t[0]*cu,e=t[1]*cu):[n*uu,e*uu]},i}function tl(t,n){var e=yu(t),r=(e+yu(n))/2;if(fu(r)0?n<-iu+nu&&(n=-iu+nu):n>iu-nu&&(n=iu-nu);var e=i/gu(fl(n),r);return[e*yu(r*t),i-e*hu(r*t)]}return o.invert=function(t,n){var e=i-n,o=_u(r)*bu(t*t+e*e),a=lu(t,fu(e))*_u(e);return e*r<0&&(a-=ru*_u(t)*_u(e)),[a/r,2*su(gu(i/o,1/r))-iu]},o}function ll(t,n){return[t,n]}function hl(t,n){var e=hu(t),r=t===n?yu(t):(e-hu(n))/(n-t),i=e/r+t;if(fu(r)=0;)n+=e[r].value;else n=1;t.value=n}function kl(t,n){var e,r,i,o,a,u=new zl(t),c=+t.value&&(u.value=t.value),f=[u];for(null==n&&(n=El);e=f.pop();)if(c&&(e.value=+e.data.value),(i=n(e.data))&&(a=i.length))for(e.children=new Array(a),o=a-1;o>=0;--o)f.push(r=e.children[o]=new zl(i[o])),r.parent=e,r.depth=e.depth+1;return u.eachBefore(Pl)}function El(t){return t.children}function Cl(t){t.data=t.data.data}function Pl(t){var n=0;do{t.height=n}while((t=t.parent)&&t.height<++n)}function zl(t){this.data=t,this.depth=this.height=0,this.parent=null}_l.invert=function(t,n){for(var e,r=n,i=r*r,o=i*i*i,a=0;a<12&&(o=(i=(r-=e=(r*(dl+pl*i+o*(vl+gl*i))-n)/(dl+3*pl*i+o*(7*vl+9*gl*i)))*r)*i*i,!(fu(e)nu&&--i>0);return[t/(.8707+(o=r*r)*(o*(o*o*o*(.003971-.001529*o)-.013791)-.131979)),r]},xl.invert=il(wu),wl.invert=il(function(t){return 2*su(t)}),Ml.invert=function(t,n){return[-n,2*su(pu(t))-iu]},zl.prototype=kl.prototype={constructor:zl,count:function(){return this.eachAfter(Sl)},each:function(t){var n,e,r,i,o=this,a=[o];do{for(n=a.reverse(),a=[];o=n.pop();)if(t(o),e=o.children)for(r=0,i=e.length;r=0;--e)i.push(n[e]);return this},sum:function(t){return this.eachAfter(function(n){for(var e=+t(n.data)||0,r=n.children,i=r&&r.length;--i>=0;)e+=r[i].value;n.value=e})},sort:function(t){return this.eachBefore(function(n){n.children&&n.children.sort(t)})},path:function(t){for(var n=this,e=function(t,n){if(t===n)return t;var e=t.ancestors(),r=n.ancestors(),i=null;for(t=e.pop(),n=r.pop();t===n;)i=t,t=e.pop(),n=r.pop();return i}(n,t),r=[n];n!==e;)n=n.parent,r.push(n);for(var i=r.length;t!==e;)r.splice(i,0,t),t=t.parent;return r},ancestors:function(){for(var t=this,n=[t];t=t.parent;)n.push(t);return n},descendants:function(){var t=[];return this.each(function(n){t.push(n)}),t},leaves:function(){var t=[];return this.eachBefore(function(n){n.children||t.push(n)}),t},links:function(){var t=this,n=[];return t.each(function(e){e!==t&&n.push({source:e.parent,target:e})}),n},copy:function(){return kl(this).eachBefore(Cl)}};var Rl=Array.prototype.slice;function Dl(t){for(var n,e,r=0,i=(t=function(t){for(var n,e,r=t.length;r;)e=Math.random()*r--|0,n=t[r],t[r]=t[e],t[e]=n;return t}(Rl.call(t))).length,o=[];r0&&e*e>r*r+i*i}function Ol(t,n){for(var e=0;e(a*=a)?(r=(f+a-i)/(2*f),o=Math.sqrt(Math.max(0,a/f-r*r)),e.x=t.x-r*u-o*c,e.y=t.y-r*c+o*u):(r=(f+i-a)/(2*f),o=Math.sqrt(Math.max(0,i/f-r*r)),e.x=n.x+r*u-o*c,e.y=n.y+r*c+o*u)):(e.x=n.x+e.r,e.y=n.y)}function Hl(t,n){var e=t.r+n.r-1e-6,r=n.x-t.x,i=n.y-t.y;return e>0&&e*e>r*r+i*i}function jl(t){var n=t._,e=t.next._,r=n.r+e.r,i=(n.x*e.r+e.x*n.r)/r,o=(n.y*e.r+e.y*n.r)/r;return i*i+o*o}function Xl(t){this._=t,this.next=null,this.previous=null}function Vl(t){if(!(i=t.length))return 0;var n,e,r,i,o,a,u,c,f,s,l;if((n=t[0]).x=0,n.y=0,!(i>1))return n.r;if(e=t[1],n.x=-e.r,e.x=n.r,e.y=0,!(i>2))return n.r+e.r;Il(e,n,r=t[2]),n=new Xl(n),e=new Xl(e),r=new Xl(r),n.next=r.previous=e,e.next=n.previous=r,r.next=e.previous=n;t:for(u=3;uh&&(h=u),g=s*s*v,(d=Math.max(h/g,g/l))>p){s-=u;break}p=d}y.push(a={value:s,dice:c1?n:1)},e}(vh);var _h=function t(n){function e(t,e,r,i,o){if((a=t._squarify)&&a.ratio===n)for(var a,u,c,f,s,l=-1,h=a.length,d=t.value;++l1?n:1)},e}(vh);function bh(t,n,e){return(n[0]-t[0])*(e[1]-t[1])-(n[1]-t[1])*(e[0]-t[0])}function mh(t,n){return t[0]-n[0]||t[1]-n[1]}function xh(t){for(var n=t.length,e=[0,1],r=2,i=2;i1&&bh(t[e[r-2]],t[e[r-1]],t[i])<=0;)--r;e[r++]=i}return e.slice(0,r)}function wh(){return Math.random()}var Mh=function t(n){function e(t,e){return t=null==t?0:+t,e=null==e?1:+e,1===arguments.length?(e=t,t=0):e-=t,function(){return n()*e+t}}return e.source=t,e}(wh),Nh=function t(n){function e(t,e){var r,i;return t=null==t?0:+t,e=null==e?1:+e,function(){var o;if(null!=r)o=r,r=null;else do{r=2*n()-1,o=2*n()-1,i=r*r+o*o}while(!i||i>1);return t+e*o*Math.sqrt(-2*Math.log(i)/i)}}return e.source=t,e}(wh),Th=function t(n){function e(){var t=Nh.source(n).apply(this,arguments);return function(){return Math.exp(t())}}return e.source=t,e}(wh),Ah=function t(n){function e(t){return function(){for(var e=0,r=0;rr&&(n=e,e=r,r=n),function(t){return Math.max(e,Math.min(r,t))}}function Ih(t,n,e){var r=t[0],i=t[1],o=n[0],a=n[1];return i2?Hh:Ih,i=o=null,l}function l(n){return isNaN(n=+n)?e:(i||(i=r(a.map(t),u,c)))(t(f(n)))}return l.invert=function(e){return f(n((o||(o=r(u,a.map(t),me)))(e)))},l.domain=function(t){return arguments.length?(a=zh.call(t,Uh),f===Bh||(f=Yh(a)),s()):a.slice()},l.range=function(t){return arguments.length?(u=Rh.call(t),s()):u.slice()},l.rangeRound=function(t){return u=Rh.call(t),c=Ae,s()},l.clamp=function(t){return arguments.length?(f=t?Yh(a):Bh,l):f!==Bh},l.interpolate=function(t){return arguments.length?(c=t,s()):c},l.unknown=function(t){return arguments.length?(e=t,l):e},function(e,r){return t=e,n=r,s()}}function Vh(t,n){return Xh()(t,n)}function Gh(n,e,r,i){var o,a=w(n,e,r);switch((i=Oa(null==i?",f":i)).type){case"s":var u=Math.max(Math.abs(n),Math.abs(e));return null!=i.precision||isNaN(o=Wa(a,u))||(i.precision=o),t.formatPrefix(i,u);case"":case"e":case"g":case"p":case"r":null!=i.precision||isNaN(o=Za(a,Math.max(Math.abs(n),Math.abs(e))))||(i.precision=o-("e"===i.type));break;case"f":case"%":null!=i.precision||isNaN(o=$a(a))||(i.precision=o-2*("%"===i.type))}return t.format(i)}function $h(t){var n=t.domain;return t.ticks=function(t){var e=n();return m(e[0],e[e.length-1],null==t?10:t)},t.tickFormat=function(t,e){var r=n();return Gh(r[0],r[r.length-1],null==t?10:t,e)},t.nice=function(e){null==e&&(e=10);var r,i=n(),o=0,a=i.length-1,u=i[o],c=i[a];return c0?r=x(u=Math.floor(u/r)*r,c=Math.ceil(c/r)*r,e):r<0&&(r=x(u=Math.ceil(u*r)/r,c=Math.floor(c*r)/r,e)),r>0?(i[o]=Math.floor(u/r)*r,i[a]=Math.ceil(c/r)*r,n(i)):r<0&&(i[o]=Math.ceil(u*r)/r,i[a]=Math.floor(c*r)/r,n(i)),t},t}function Wh(t,n){var e,r=0,i=(t=t.slice()).length-1,o=t[r],a=t[i];return a0){for(;hc)break;v.push(l)}}else for(;h=1;--s)if(!((l=f*s)c)break;v.push(l)}}else v=m(h,d,Math.min(d-h,p)).map(r);return n?v.reverse():v},i.tickFormat=function(n,o){if(null==o&&(o=10===a?".0e":","),"function"!=typeof o&&(o=t.format(o)),n===1/0)return o;null==n&&(n=10);var u=Math.max(1,a*n/i.ticks().length);return function(t){var n=t/r(Math.round(e(t)));return n*a0))return u;do{u.push(a=new Date(+e)),n(e,o),t(e)}while(a=n)for(;t(n),!e(n);)n.setTime(n-1)},function(t,r){if(t>=t)if(r<0)for(;++r<=0;)for(;n(t,-1),!e(t););else for(;--r>=0;)for(;n(t,1),!e(t););})},e&&(i.count=function(n,r){return ld.setTime(+n),hd.setTime(+r),t(ld),t(hd),Math.floor(e(ld,hd))},i.every=function(t){return t=Math.floor(t),isFinite(t)&&t>0?t>1?i.filter(r?function(n){return r(n)%t==0}:function(n){return i.count(0,n)%t==0}):i:null}),i}var pd=dd(function(){},function(t,n){t.setTime(+t+n)},function(t,n){return n-t});pd.every=function(t){return t=Math.floor(t),isFinite(t)&&t>0?t>1?dd(function(n){n.setTime(Math.floor(n/t)*t)},function(n,e){n.setTime(+n+e*t)},function(n,e){return(e-n)/t}):pd:null};var vd=pd.range,gd=6e4,yd=6048e5,_d=dd(function(t){t.setTime(t-t.getMilliseconds())},function(t,n){t.setTime(+t+1e3*n)},function(t,n){return(n-t)/1e3},function(t){return t.getUTCSeconds()}),bd=_d.range,md=dd(function(t){t.setTime(t-t.getMilliseconds()-1e3*t.getSeconds())},function(t,n){t.setTime(+t+n*gd)},function(t,n){return(n-t)/gd},function(t){return t.getMinutes()}),xd=md.range,wd=dd(function(t){t.setTime(t-t.getMilliseconds()-1e3*t.getSeconds()-t.getMinutes()*gd)},function(t,n){t.setTime(+t+36e5*n)},function(t,n){return(n-t)/36e5},function(t){return t.getHours()}),Md=wd.range,Nd=dd(function(t){t.setHours(0,0,0,0)},function(t,n){t.setDate(t.getDate()+n)},function(t,n){return(n-t-(n.getTimezoneOffset()-t.getTimezoneOffset())*gd)/864e5},function(t){return t.getDate()-1}),Td=Nd.range;function Ad(t){return dd(function(n){n.setDate(n.getDate()-(n.getDay()+7-t)%7),n.setHours(0,0,0,0)},function(t,n){t.setDate(t.getDate()+7*n)},function(t,n){return(n-t-(n.getTimezoneOffset()-t.getTimezoneOffset())*gd)/yd})}var Sd=Ad(0),kd=Ad(1),Ed=Ad(2),Cd=Ad(3),Pd=Ad(4),zd=Ad(5),Rd=Ad(6),Dd=Sd.range,qd=kd.range,Ld=Ed.range,Ud=Cd.range,Od=Pd.range,Bd=zd.range,Fd=Rd.range,Yd=dd(function(t){t.setDate(1),t.setHours(0,0,0,0)},function(t,n){t.setMonth(t.getMonth()+n)},function(t,n){return n.getMonth()-t.getMonth()+12*(n.getFullYear()-t.getFullYear())},function(t){return t.getMonth()}),Id=Yd.range,Hd=dd(function(t){t.setMonth(0,1),t.setHours(0,0,0,0)},function(t,n){t.setFullYear(t.getFullYear()+n)},function(t,n){return n.getFullYear()-t.getFullYear()},function(t){return t.getFullYear()});Hd.every=function(t){return isFinite(t=Math.floor(t))&&t>0?dd(function(n){n.setFullYear(Math.floor(n.getFullYear()/t)*t),n.setMonth(0,1),n.setHours(0,0,0,0)},function(n,e){n.setFullYear(n.getFullYear()+e*t)}):null};var jd=Hd.range,Xd=dd(function(t){t.setUTCSeconds(0,0)},function(t,n){t.setTime(+t+n*gd)},function(t,n){return(n-t)/gd},function(t){return t.getUTCMinutes()}),Vd=Xd.range,Gd=dd(function(t){t.setUTCMinutes(0,0,0)},function(t,n){t.setTime(+t+36e5*n)},function(t,n){return(n-t)/36e5},function(t){return t.getUTCHours()}),$d=Gd.range,Wd=dd(function(t){t.setUTCHours(0,0,0,0)},function(t,n){t.setUTCDate(t.getUTCDate()+n)},function(t,n){return(n-t)/864e5},function(t){return t.getUTCDate()-1}),Zd=Wd.range;function Qd(t){return dd(function(n){n.setUTCDate(n.getUTCDate()-(n.getUTCDay()+7-t)%7),n.setUTCHours(0,0,0,0)},function(t,n){t.setUTCDate(t.getUTCDate()+7*n)},function(t,n){return(n-t)/yd})}var Kd=Qd(0),Jd=Qd(1),tp=Qd(2),np=Qd(3),ep=Qd(4),rp=Qd(5),ip=Qd(6),op=Kd.range,ap=Jd.range,up=tp.range,cp=np.range,fp=ep.range,sp=rp.range,lp=ip.range,hp=dd(function(t){t.setUTCDate(1),t.setUTCHours(0,0,0,0)},function(t,n){t.setUTCMonth(t.getUTCMonth()+n)},function(t,n){return n.getUTCMonth()-t.getUTCMonth()+12*(n.getUTCFullYear()-t.getUTCFullYear())},function(t){return t.getUTCMonth()}),dp=hp.range,pp=dd(function(t){t.setUTCMonth(0,1),t.setUTCHours(0,0,0,0)},function(t,n){t.setUTCFullYear(t.getUTCFullYear()+n)},function(t,n){return n.getUTCFullYear()-t.getUTCFullYear()},function(t){return t.getUTCFullYear()});pp.every=function(t){return isFinite(t=Math.floor(t))&&t>0?dd(function(n){n.setUTCFullYear(Math.floor(n.getUTCFullYear()/t)*t),n.setUTCMonth(0,1),n.setUTCHours(0,0,0,0)},function(n,e){n.setUTCFullYear(n.getUTCFullYear()+e*t)}):null};var vp=pp.range;function gp(t){if(0<=t.y&&t.y<100){var n=new Date(-1,t.m,t.d,t.H,t.M,t.S,t.L);return n.setFullYear(t.y),n}return new Date(t.y,t.m,t.d,t.H,t.M,t.S,t.L)}function yp(t){if(0<=t.y&&t.y<100){var n=new Date(Date.UTC(-1,t.m,t.d,t.H,t.M,t.S,t.L));return n.setUTCFullYear(t.y),n}return new Date(Date.UTC(t.y,t.m,t.d,t.H,t.M,t.S,t.L))}function _p(t,n,e){return{y:t,m:n,d:e,H:0,M:0,S:0,L:0}}function bp(t){var n=t.dateTime,e=t.date,r=t.time,i=t.periods,o=t.days,a=t.shortDays,u=t.months,c=t.shortMonths,f=Sp(i),s=kp(i),l=Sp(o),h=kp(o),d=Sp(a),p=kp(a),v=Sp(u),g=kp(u),y=Sp(c),_=kp(c),b={a:function(t){return a[t.getDay()]},A:function(t){return o[t.getDay()]},b:function(t){return c[t.getMonth()]},B:function(t){return u[t.getMonth()]},c:null,d:Wp,e:Wp,f:tv,H:Zp,I:Qp,j:Kp,L:Jp,m:nv,M:ev,p:function(t){return i[+(t.getHours()>=12)]},q:function(t){return 1+~~(t.getMonth()/3)},Q:Cv,s:Pv,S:rv,u:iv,U:ov,V:av,w:uv,W:cv,x:null,X:null,y:fv,Y:sv,Z:lv,"%":Ev},m={a:function(t){return a[t.getUTCDay()]},A:function(t){return o[t.getUTCDay()]},b:function(t){return c[t.getUTCMonth()]},B:function(t){return u[t.getUTCMonth()]},c:null,d:hv,e:hv,f:yv,H:dv,I:pv,j:vv,L:gv,m:_v,M:bv,p:function(t){return i[+(t.getUTCHours()>=12)]},q:function(t){return 1+~~(t.getUTCMonth()/3)},Q:Cv,s:Pv,S:mv,u:xv,U:wv,V:Mv,w:Nv,W:Tv,x:null,X:null,y:Av,Y:Sv,Z:kv,"%":Ev},x={a:function(t,n,e){var r=d.exec(n.slice(e));return r?(t.w=p[r[0].toLowerCase()],e+r[0].length):-1},A:function(t,n,e){var r=l.exec(n.slice(e));return r?(t.w=h[r[0].toLowerCase()],e+r[0].length):-1},b:function(t,n,e){var r=y.exec(n.slice(e));return r?(t.m=_[r[0].toLowerCase()],e+r[0].length):-1},B:function(t,n,e){var r=v.exec(n.slice(e));return r?(t.m=g[r[0].toLowerCase()],e+r[0].length):-1},c:function(t,e,r){return N(t,n,e,r)},d:Bp,e:Bp,f:Xp,H:Yp,I:Yp,j:Fp,L:jp,m:Op,M:Ip,p:function(t,n,e){var r=f.exec(n.slice(e));return r?(t.p=s[r[0].toLowerCase()],e+r[0].length):-1},q:Up,Q:Gp,s:$p,S:Hp,u:Cp,U:Pp,V:zp,w:Ep,W:Rp,x:function(t,n,r){return N(t,e,n,r)},X:function(t,n,e){return N(t,r,n,e)},y:qp,Y:Dp,Z:Lp,"%":Vp};function w(t,n){return function(e){var r,i,o,a=[],u=-1,c=0,f=t.length;for(e instanceof Date||(e=new Date(+e));++u53)return null;"w"in o||(o.w=1),"Z"in o?(i=(r=yp(_p(o.y,0,1))).getUTCDay(),r=i>4||0===i?Jd.ceil(r):Jd(r),r=Wd.offset(r,7*(o.V-1)),o.y=r.getUTCFullYear(),o.m=r.getUTCMonth(),o.d=r.getUTCDate()+(o.w+6)%7):(i=(r=gp(_p(o.y,0,1))).getDay(),r=i>4||0===i?kd.ceil(r):kd(r),r=Nd.offset(r,7*(o.V-1)),o.y=r.getFullYear(),o.m=r.getMonth(),o.d=r.getDate()+(o.w+6)%7)}else("W"in o||"U"in o)&&("w"in o||(o.w="u"in o?o.u%7:"W"in o?1:0),i="Z"in o?yp(_p(o.y,0,1)).getUTCDay():gp(_p(o.y,0,1)).getDay(),o.m=0,o.d="W"in o?(o.w+6)%7+7*o.W-(i+5)%7:o.w+7*o.U-(i+6)%7);return"Z"in o?(o.H+=o.Z/100|0,o.M+=o.Z%100,yp(o)):gp(o)}}function N(t,n,e,r){for(var i,o,a=0,u=n.length,c=e.length;a=c)return-1;if(37===(i=n.charCodeAt(a++))){if(i=n.charAt(a++),!(o=x[i in xp?n.charAt(a++):i])||(r=o(t,e,r))<0)return-1}else if(i!=e.charCodeAt(r++))return-1}return r}return b.x=w(e,b),b.X=w(r,b),b.c=w(n,b),m.x=w(e,m),m.X=w(r,m),m.c=w(n,m),{format:function(t){var n=w(t+="",b);return n.toString=function(){return t},n},parse:function(t){var n=M(t+="",!1);return n.toString=function(){return t},n},utcFormat:function(t){var n=w(t+="",m);return n.toString=function(){return t},n},utcParse:function(t){var n=M(t+="",!0);return n.toString=function(){return t},n}}}var mp,xp={"-":"",_:" ",0:"0"},wp=/^\s*\d+/,Mp=/^%/,Np=/[\\^$*+?|[\]().{}]/g;function Tp(t,n,e){var r=t<0?"-":"",i=(r?-t:t)+"",o=i.length;return r+(o68?1900:2e3),e+r[0].length):-1}function Lp(t,n,e){var r=/^(Z)|([+-]\d\d)(?::?(\d\d))?/.exec(n.slice(e,e+6));return r?(t.Z=r[1]?0:-(r[2]+(r[3]||"00")),e+r[0].length):-1}function Up(t,n,e){var r=wp.exec(n.slice(e,e+1));return r?(t.q=3*r[0]-3,e+r[0].length):-1}function Op(t,n,e){var r=wp.exec(n.slice(e,e+2));return r?(t.m=r[0]-1,e+r[0].length):-1}function Bp(t,n,e){var r=wp.exec(n.slice(e,e+2));return r?(t.d=+r[0],e+r[0].length):-1}function Fp(t,n,e){var r=wp.exec(n.slice(e,e+3));return r?(t.m=0,t.d=+r[0],e+r[0].length):-1}function Yp(t,n,e){var r=wp.exec(n.slice(e,e+2));return r?(t.H=+r[0],e+r[0].length):-1}function Ip(t,n,e){var r=wp.exec(n.slice(e,e+2));return r?(t.M=+r[0],e+r[0].length):-1}function Hp(t,n,e){var r=wp.exec(n.slice(e,e+2));return r?(t.S=+r[0],e+r[0].length):-1}function jp(t,n,e){var r=wp.exec(n.slice(e,e+3));return r?(t.L=+r[0],e+r[0].length):-1}function Xp(t,n,e){var r=wp.exec(n.slice(e,e+6));return r?(t.L=Math.floor(r[0]/1e3),e+r[0].length):-1}function Vp(t,n,e){var r=Mp.exec(n.slice(e,e+1));return r?e+r[0].length:-1}function Gp(t,n,e){var r=wp.exec(n.slice(e));return r?(t.Q=+r[0],e+r[0].length):-1}function $p(t,n,e){var r=wp.exec(n.slice(e));return r?(t.s=+r[0],e+r[0].length):-1}function Wp(t,n){return Tp(t.getDate(),n,2)}function Zp(t,n){return Tp(t.getHours(),n,2)}function Qp(t,n){return Tp(t.getHours()%12||12,n,2)}function Kp(t,n){return Tp(1+Nd.count(Hd(t),t),n,3)}function Jp(t,n){return Tp(t.getMilliseconds(),n,3)}function tv(t,n){return Jp(t,n)+"000"}function nv(t,n){return Tp(t.getMonth()+1,n,2)}function ev(t,n){return Tp(t.getMinutes(),n,2)}function rv(t,n){return Tp(t.getSeconds(),n,2)}function iv(t){var n=t.getDay();return 0===n?7:n}function ov(t,n){return Tp(Sd.count(Hd(t)-1,t),n,2)}function av(t,n){var e=t.getDay();return t=e>=4||0===e?Pd(t):Pd.ceil(t),Tp(Pd.count(Hd(t),t)+(4===Hd(t).getDay()),n,2)}function uv(t){return t.getDay()}function cv(t,n){return Tp(kd.count(Hd(t)-1,t),n,2)}function fv(t,n){return Tp(t.getFullYear()%100,n,2)}function sv(t,n){return Tp(t.getFullYear()%1e4,n,4)}function lv(t){var n=t.getTimezoneOffset();return(n>0?"-":(n*=-1,"+"))+Tp(n/60|0,"0",2)+Tp(n%60,"0",2)}function hv(t,n){return Tp(t.getUTCDate(),n,2)}function dv(t,n){return Tp(t.getUTCHours(),n,2)}function pv(t,n){return Tp(t.getUTCHours()%12||12,n,2)}function vv(t,n){return Tp(1+Wd.count(pp(t),t),n,3)}function gv(t,n){return Tp(t.getUTCMilliseconds(),n,3)}function yv(t,n){return gv(t,n)+"000"}function _v(t,n){return Tp(t.getUTCMonth()+1,n,2)}function bv(t,n){return Tp(t.getUTCMinutes(),n,2)}function mv(t,n){return Tp(t.getUTCSeconds(),n,2)}function xv(t){var n=t.getUTCDay();return 0===n?7:n}function wv(t,n){return Tp(Kd.count(pp(t)-1,t),n,2)}function Mv(t,n){var e=t.getUTCDay();return t=e>=4||0===e?ep(t):ep.ceil(t),Tp(ep.count(pp(t),t)+(4===pp(t).getUTCDay()),n,2)}function Nv(t){return t.getUTCDay()}function Tv(t,n){return Tp(Jd.count(pp(t)-1,t),n,2)}function Av(t,n){return Tp(t.getUTCFullYear()%100,n,2)}function Sv(t,n){return Tp(t.getUTCFullYear()%1e4,n,4)}function kv(){return"+0000"}function Ev(){return"%"}function Cv(t){return+t}function Pv(t){return Math.floor(+t/1e3)}function zv(n){return mp=bp(n),t.timeFormat=mp.format,t.timeParse=mp.parse,t.utcFormat=mp.utcFormat,t.utcParse=mp.utcParse,mp}zv({dateTime:"%x, %X",date:"%-m/%-d/%Y",time:"%-I:%M:%S %p",periods:["AM","PM"],days:["Sunday","Monday","Tuesday","Wednesday","Thursday","Friday","Saturday"],shortDays:["Sun","Mon","Tue","Wed","Thu","Fri","Sat"],months:["January","February","March","April","May","June","July","August","September","October","November","December"],shortMonths:["Jan","Feb","Mar","Apr","May","Jun","Jul","Aug","Sep","Oct","Nov","Dec"]});var Rv=Date.prototype.toISOString?function(t){return t.toISOString()}:t.utcFormat("%Y-%m-%dT%H:%M:%S.%LZ");var Dv=+new Date("2000-01-01T00:00:00.000Z")?function(t){var n=new Date(t);return isNaN(n)?null:n}:t.utcParse("%Y-%m-%dT%H:%M:%S.%LZ"),qv=1e3,Lv=60*qv,Uv=60*Lv,Ov=24*Uv,Bv=7*Ov,Fv=30*Ov,Yv=365*Ov;function Iv(t){return new Date(t)}function Hv(t){return t instanceof Date?+t:+new Date(+t)}function jv(t,n,r,i,o,a,u,c,f){var s=Vh(Bh,Bh),l=s.invert,h=s.domain,d=f(".%L"),p=f(":%S"),v=f("%I:%M"),g=f("%I %p"),y=f("%a %d"),_=f("%b %d"),b=f("%B"),m=f("%Y"),x=[[u,1,qv],[u,5,5*qv],[u,15,15*qv],[u,30,30*qv],[a,1,Lv],[a,5,5*Lv],[a,15,15*Lv],[a,30,30*Lv],[o,1,Uv],[o,3,3*Uv],[o,6,6*Uv],[o,12,12*Uv],[i,1,Ov],[i,2,2*Ov],[r,1,Bv],[n,1,Fv],[n,3,3*Fv],[t,1,Yv]];function M(e){return(u(e)=1?Cy:t<=-1?-Cy:Math.asin(t)}function Ry(t){return t.innerRadius}function Dy(t){return t.outerRadius}function qy(t){return t.startAngle}function Ly(t){return t.endAngle}function Uy(t){return t&&t.padAngle}function Oy(t,n,e,r,i,o,a){var u=t-e,c=n-r,f=(a?o:-o)/Sy(u*u+c*c),s=f*c,l=-f*u,h=t+s,d=n+l,p=e+s,v=r+l,g=(h+p)/2,y=(d+v)/2,_=p-h,b=v-d,m=_*_+b*b,x=i-o,w=h*v-p*d,M=(b<0?-1:1)*Sy(Ny(0,x*x*m-w*w)),N=(w*b-_*M)/m,T=(-w*_-b*M)/m,A=(w*b+_*M)/m,S=(-w*_+b*M)/m,k=N-g,E=T-y,C=A-g,P=S-y;return k*k+E*E>C*C+P*P&&(N=A,T=S),{cx:N,cy:T,x01:-s,y01:-l,x11:N*(i/x-1),y11:T*(i/x-1)}}function By(t){this._context=t}function Fy(t){return new By(t)}function Yy(t){return t[0]}function Iy(t){return t[1]}function Hy(){var t=Yy,n=Iy,e=my(!0),r=null,i=Fy,o=null;function a(a){var u,c,f,s=a.length,l=!1;for(null==r&&(o=i(f=no())),u=0;u<=s;++u)!(u=s;--l)u.point(g[l],y[l]);u.lineEnd(),u.areaEnd()}v&&(g[f]=+t(h,f,c),y[f]=+e(h,f,c),u.point(n?+n(h,f,c):g[f],r?+r(h,f,c):y[f]))}if(d)return u=null,d+""||null}function f(){return Hy().defined(i).curve(a).context(o)}return c.x=function(e){return arguments.length?(t="function"==typeof e?e:my(+e),n=null,c):t},c.x0=function(n){return arguments.length?(t="function"==typeof n?n:my(+n),c):t},c.x1=function(t){return arguments.length?(n=null==t?null:"function"==typeof t?t:my(+t),c):n},c.y=function(t){return arguments.length?(e="function"==typeof t?t:my(+t),r=null,c):e},c.y0=function(t){return arguments.length?(e="function"==typeof t?t:my(+t),c):e},c.y1=function(t){return arguments.length?(r=null==t?null:"function"==typeof t?t:my(+t),c):r},c.lineX0=c.lineY0=function(){return f().x(t).y(e)},c.lineY1=function(){return f().x(t).y(r)},c.lineX1=function(){return f().x(n).y(e)},c.defined=function(t){return arguments.length?(i="function"==typeof t?t:my(!!t),c):i},c.curve=function(t){return arguments.length?(a=t,null!=o&&(u=a(o)),c):a},c.context=function(t){return arguments.length?(null==t?o=u=null:u=a(o=t),c):o},c}function Xy(t,n){return nt?1:n>=t?0:NaN}function Vy(t){return t}By.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;default:this._context.lineTo(t,n)}}};var Gy=Wy(Fy);function $y(t){this._curve=t}function Wy(t){function n(n){return new $y(t(n))}return n._curve=t,n}function Zy(t){var n=t.curve;return t.angle=t.x,delete t.x,t.radius=t.y,delete t.y,t.curve=function(t){return arguments.length?n(Wy(t)):n()._curve},t}function Qy(){return Zy(Hy().curve(Gy))}function Ky(){var t=jy().curve(Gy),n=t.curve,e=t.lineX0,r=t.lineX1,i=t.lineY0,o=t.lineY1;return t.angle=t.x,delete t.x,t.startAngle=t.x0,delete t.x0,t.endAngle=t.x1,delete t.x1,t.radius=t.y,delete t.y,t.innerRadius=t.y0,delete t.y0,t.outerRadius=t.y1,delete t.y1,t.lineStartAngle=function(){return Zy(e())},delete t.lineX0,t.lineEndAngle=function(){return Zy(r())},delete t.lineX1,t.lineInnerRadius=function(){return Zy(i())},delete t.lineY0,t.lineOuterRadius=function(){return Zy(o())},delete t.lineY1,t.curve=function(t){return arguments.length?n(Wy(t)):n()._curve},t}function Jy(t,n){return[(n=+n)*Math.cos(t-=Math.PI/2),n*Math.sin(t)]}$y.prototype={areaStart:function(){this._curve.areaStart()},areaEnd:function(){this._curve.areaEnd()},lineStart:function(){this._curve.lineStart()},lineEnd:function(){this._curve.lineEnd()},point:function(t,n){this._curve.point(n*Math.sin(t),n*-Math.cos(t))}};var t_=Array.prototype.slice;function n_(t){return t.source}function e_(t){return t.target}function r_(t){var n=n_,e=e_,r=Yy,i=Iy,o=null;function a(){var a,u=t_.call(arguments),c=n.apply(this,u),f=e.apply(this,u);if(o||(o=a=no()),t(o,+r.apply(this,(u[0]=c,u)),+i.apply(this,u),+r.apply(this,(u[0]=f,u)),+i.apply(this,u)),a)return o=null,a+""||null}return a.source=function(t){return arguments.length?(n=t,a):n},a.target=function(t){return arguments.length?(e=t,a):e},a.x=function(t){return arguments.length?(r="function"==typeof t?t:my(+t),a):r},a.y=function(t){return arguments.length?(i="function"==typeof t?t:my(+t),a):i},a.context=function(t){return arguments.length?(o=null==t?null:t,a):o},a}function i_(t,n,e,r,i){t.moveTo(n,e),t.bezierCurveTo(n=(n+r)/2,e,n,i,r,i)}function o_(t,n,e,r,i){t.moveTo(n,e),t.bezierCurveTo(n,e=(e+i)/2,r,e,r,i)}function a_(t,n,e,r,i){var o=Jy(n,e),a=Jy(n,e=(e+i)/2),u=Jy(r,e),c=Jy(r,i);t.moveTo(o[0],o[1]),t.bezierCurveTo(a[0],a[1],u[0],u[1],c[0],c[1])}var u_={draw:function(t,n){var e=Math.sqrt(n/Ey);t.moveTo(e,0),t.arc(0,0,e,0,Py)}},c_={draw:function(t,n){var e=Math.sqrt(n/5)/2;t.moveTo(-3*e,-e),t.lineTo(-e,-e),t.lineTo(-e,-3*e),t.lineTo(e,-3*e),t.lineTo(e,-e),t.lineTo(3*e,-e),t.lineTo(3*e,e),t.lineTo(e,e),t.lineTo(e,3*e),t.lineTo(-e,3*e),t.lineTo(-e,e),t.lineTo(-3*e,e),t.closePath()}},f_=Math.sqrt(1/3),s_=2*f_,l_={draw:function(t,n){var e=Math.sqrt(n/s_),r=e*f_;t.moveTo(0,-e),t.lineTo(r,0),t.lineTo(0,e),t.lineTo(-r,0),t.closePath()}},h_=Math.sin(Ey/10)/Math.sin(7*Ey/10),d_=Math.sin(Py/10)*h_,p_=-Math.cos(Py/10)*h_,v_={draw:function(t,n){var e=Math.sqrt(.8908130915292852*n),r=d_*e,i=p_*e;t.moveTo(0,-e),t.lineTo(r,i);for(var o=1;o<5;++o){var a=Py*o/5,u=Math.cos(a),c=Math.sin(a);t.lineTo(c*e,-u*e),t.lineTo(u*r-c*i,c*r+u*i)}t.closePath()}},g_={draw:function(t,n){var e=Math.sqrt(n),r=-e/2;t.rect(r,r,e,e)}},y_=Math.sqrt(3),__={draw:function(t,n){var e=-Math.sqrt(n/(3*y_));t.moveTo(0,2*e),t.lineTo(-y_*e,-e),t.lineTo(y_*e,-e),t.closePath()}},b_=Math.sqrt(3)/2,m_=1/Math.sqrt(12),x_=3*(m_/2+1),w_={draw:function(t,n){var e=Math.sqrt(n/x_),r=e/2,i=e*m_,o=r,a=e*m_+e,u=-o,c=a;t.moveTo(r,i),t.lineTo(o,a),t.lineTo(u,c),t.lineTo(-.5*r-b_*i,b_*r+-.5*i),t.lineTo(-.5*o-b_*a,b_*o+-.5*a),t.lineTo(-.5*u-b_*c,b_*u+-.5*c),t.lineTo(-.5*r+b_*i,-.5*i-b_*r),t.lineTo(-.5*o+b_*a,-.5*a-b_*o),t.lineTo(-.5*u+b_*c,-.5*c-b_*u),t.closePath()}},M_=[u_,c_,l_,g_,v_,__,w_];function N_(){}function T_(t,n,e){t._context.bezierCurveTo((2*t._x0+t._x1)/3,(2*t._y0+t._y1)/3,(t._x0+2*t._x1)/3,(t._y0+2*t._y1)/3,(t._x0+4*t._x1+n)/6,(t._y0+4*t._y1+e)/6)}function A_(t){this._context=t}function S_(t){this._context=t}function k_(t){this._context=t}function E_(t,n){this._basis=new A_(t),this._beta=n}A_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN,this._point=0},lineEnd:function(){switch(this._point){case 3:T_(this,this._x1,this._y1);case 2:this._context.lineTo(this._x1,this._y1)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;break;case 2:this._point=3,this._context.lineTo((5*this._x0+this._x1)/6,(5*this._y0+this._y1)/6);default:T_(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},S_.prototype={areaStart:N_,areaEnd:N_,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._y0=this._y1=this._y2=this._y3=this._y4=NaN,this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x2,this._y2),this._context.closePath();break;case 2:this._context.moveTo((this._x2+2*this._x3)/3,(this._y2+2*this._y3)/3),this._context.lineTo((this._x3+2*this._x2)/3,(this._y3+2*this._y2)/3),this._context.closePath();break;case 3:this.point(this._x2,this._y2),this.point(this._x3,this._y3),this.point(this._x4,this._y4)}},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._x2=t,this._y2=n;break;case 1:this._point=2,this._x3=t,this._y3=n;break;case 2:this._point=3,this._x4=t,this._y4=n,this._context.moveTo((this._x0+4*this._x1+t)/6,(this._y0+4*this._y1+n)/6);break;default:T_(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},k_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN,this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3;var e=(this._x0+4*this._x1+t)/6,r=(this._y0+4*this._y1+n)/6;this._line?this._context.lineTo(e,r):this._context.moveTo(e,r);break;case 3:this._point=4;default:T_(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},E_.prototype={lineStart:function(){this._x=[],this._y=[],this._basis.lineStart()},lineEnd:function(){var t=this._x,n=this._y,e=t.length-1;if(e>0)for(var r,i=t[0],o=n[0],a=t[e]-i,u=n[e]-o,c=-1;++c<=e;)r=c/e,this._basis.point(this._beta*t[c]+(1-this._beta)*(i+r*a),this._beta*n[c]+(1-this._beta)*(o+r*u));this._x=this._y=null,this._basis.lineEnd()},point:function(t,n){this._x.push(+t),this._y.push(+n)}};var C_=function t(n){function e(t){return 1===n?new A_(t):new E_(t,n)}return e.beta=function(n){return t(+n)},e}(.85);function P_(t,n,e){t._context.bezierCurveTo(t._x1+t._k*(t._x2-t._x0),t._y1+t._k*(t._y2-t._y0),t._x2+t._k*(t._x1-n),t._y2+t._k*(t._y1-e),t._x2,t._y2)}function z_(t,n){this._context=t,this._k=(1-n)/6}z_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:P_(this,this._x1,this._y1)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2,this._x1=t,this._y1=n;break;case 2:this._point=3;default:P_(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var R_=function t(n){function e(t){return new z_(t,n)}return e.tension=function(n){return t(+n)},e}(0);function D_(t,n){this._context=t,this._k=(1-n)/6}D_.prototype={areaStart:N_,areaEnd:N_,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN,this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x3,this._y3),this._context.closePath();break;case 2:this._context.lineTo(this._x3,this._y3),this._context.closePath();break;case 3:this.point(this._x3,this._y3),this.point(this._x4,this._y4),this.point(this._x5,this._y5)}},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._x3=t,this._y3=n;break;case 1:this._point=2,this._context.moveTo(this._x4=t,this._y4=n);break;case 2:this._point=3,this._x5=t,this._y5=n;break;default:P_(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var q_=function t(n){function e(t){return new D_(t,n)}return e.tension=function(n){return t(+n)},e}(0);function L_(t,n){this._context=t,this._k=(1-n)/6}L_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3,this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;default:P_(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var U_=function t(n){function e(t){return new L_(t,n)}return e.tension=function(n){return t(+n)},e}(0);function O_(t,n,e){var r=t._x1,i=t._y1,o=t._x2,a=t._y2;if(t._l01_a>ky){var u=2*t._l01_2a+3*t._l01_a*t._l12_a+t._l12_2a,c=3*t._l01_a*(t._l01_a+t._l12_a);r=(r*u-t._x0*t._l12_2a+t._x2*t._l01_2a)/c,i=(i*u-t._y0*t._l12_2a+t._y2*t._l01_2a)/c}if(t._l23_a>ky){var f=2*t._l23_2a+3*t._l23_a*t._l12_a+t._l12_2a,s=3*t._l23_a*(t._l23_a+t._l12_a);o=(o*f+t._x1*t._l23_2a-n*t._l12_2a)/s,a=(a*f+t._y1*t._l23_2a-e*t._l12_2a)/s}t._context.bezierCurveTo(r,i,o,a,t._x2,t._y2)}function B_(t,n){this._context=t,this._alpha=n}B_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:this.point(this._x2,this._y2)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;break;case 2:this._point=3;default:O_(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var F_=function t(n){function e(t){return n?new B_(t,n):new z_(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function Y_(t,n){this._context=t,this._alpha=n}Y_.prototype={areaStart:N_,areaEnd:N_,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x3,this._y3),this._context.closePath();break;case 2:this._context.lineTo(this._x3,this._y3),this._context.closePath();break;case 3:this.point(this._x3,this._y3),this.point(this._x4,this._y4),this.point(this._x5,this._y5)}},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1,this._x3=t,this._y3=n;break;case 1:this._point=2,this._context.moveTo(this._x4=t,this._y4=n);break;case 2:this._point=3,this._x5=t,this._y5=n;break;default:O_(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var I_=function t(n){function e(t){return n?new Y_(t,n):new D_(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function H_(t,n){this._context=t,this._alpha=n}H_.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3,this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;default:O_(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var j_=function t(n){function e(t){return n?new H_(t,n):new L_(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function X_(t){this._context=t}function V_(t){return t<0?-1:1}function G_(t,n,e){var r=t._x1-t._x0,i=n-t._x1,o=(t._y1-t._y0)/(r||i<0&&-0),a=(e-t._y1)/(i||r<0&&-0),u=(o*i+a*r)/(r+i);return(V_(o)+V_(a))*Math.min(Math.abs(o),Math.abs(a),.5*Math.abs(u))||0}function $_(t,n){var e=t._x1-t._x0;return e?(3*(t._y1-t._y0)/e-n)/2:n}function W_(t,n,e){var r=t._x0,i=t._y0,o=t._x1,a=t._y1,u=(o-r)/3;t._context.bezierCurveTo(r+u,i+u*n,o-u,a-u*e,o,a)}function Z_(t){this._context=t}function Q_(t){this._context=new K_(t)}function K_(t){this._context=t}function J_(t){this._context=t}function tb(t){var n,e,r=t.length-1,i=new Array(r),o=new Array(r),a=new Array(r);for(i[0]=0,o[0]=2,a[0]=t[0]+2*t[1],n=1;n=0;--n)i[n]=(a[n]-i[n+1])/o[n];for(o[r-1]=(t[r]+i[r-1])/2,n=0;n1)for(var e,r,i,o=1,a=t[n[0]],u=a.length;o=0;)e[n]=n;return e}function ib(t,n){return t[n]}function ob(t){var n=t.map(ab);return rb(t).sort(function(t,e){return n[t]-n[e]})}function ab(t){for(var n,e=-1,r=0,i=t.length,o=-1/0;++eo&&(o=n,r=e);return r}function ub(t){var n=t.map(cb);return rb(t).sort(function(t,e){return n[t]-n[e]})}function cb(t){for(var n,e=0,r=-1,i=t.length;++r0)){if(o/=h,h<0){if(o0){if(o>l)return;o>s&&(s=o)}if(o=r-c,h||!(o<0)){if(o/=h,h<0){if(o>l)return;o>s&&(s=o)}else if(h>0){if(o0)){if(o/=d,d<0){if(o0){if(o>l)return;o>s&&(s=o)}if(o=i-f,d||!(o<0)){if(o/=d,d<0){if(o>l)return;o>s&&(s=o)}else if(d>0){if(o0||l<1)||(s>0&&(t[0]=[c+s*h,f+s*d]),l<1&&(t[1]=[c+l*h,f+l*d]),!0)}}}}}function xb(t,n,e,r,i){var o=t[1];if(o)return!0;var a,u,c=t[0],f=t.left,s=t.right,l=f[0],h=f[1],d=s[0],p=s[1],v=(l+d)/2,g=(h+p)/2;if(p===h){if(v=r)return;if(l>d){if(c){if(c[1]>=i)return}else c=[v,e];o=[v,i]}else{if(c){if(c[1]1)if(l>d){if(c){if(c[1]>=i)return}else c=[(e-u)/a,e];o=[(i-u)/a,i]}else{if(c){if(c[1]=r)return}else c=[n,a*n+u];o=[r,a*r+u]}else{if(c){if(c[0]=0&&(this._t=1-this._t,this._line=1-this._line)},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;default:if(this._t<=0)this._context.lineTo(this._x,n),this._context.lineTo(t,n);else{var e=this._x*(1-this._t)+t*this._t;this._context.lineTo(e,this._y),this._context.lineTo(e,n)}}this._x=t,this._y=n}},hb.prototype={constructor:hb,insert:function(t,n){var e,r,i;if(t){if(n.P=t,n.N=t.N,t.N&&(t.N.P=n),t.N=n,t.R){for(t=t.R;t.L;)t=t.L;t.L=n}else t.R=n;e=t}else this._?(t=gb(this._),n.P=null,n.N=t,t.P=t.L=n,e=t):(n.P=n.N=null,this._=n,e=null);for(n.L=n.R=null,n.U=e,n.C=!0,t=n;e&&e.C;)e===(r=e.U).L?(i=r.R)&&i.C?(e.C=i.C=!1,r.C=!0,t=r):(t===e.R&&(pb(this,e),e=(t=e).U),e.C=!1,r.C=!0,vb(this,r)):(i=r.L)&&i.C?(e.C=i.C=!1,r.C=!0,t=r):(t===e.L&&(vb(this,e),e=(t=e).U),e.C=!1,r.C=!0,pb(this,r)),e=t.U;this._.C=!1},remove:function(t){t.N&&(t.N.P=t.P),t.P&&(t.P.N=t.N),t.N=t.P=null;var n,e,r,i=t.U,o=t.L,a=t.R;if(e=o?a?gb(a):o:a,i?i.L===t?i.L=e:i.R=e:this._=e,o&&a?(r=e.C,e.C=t.C,e.L=o,o.U=e,e!==a?(i=e.U,e.U=t.U,t=e.R,i.L=t,e.R=a,a.U=e):(e.U=i,i=e,t=e.R)):(r=t.C,t=e),t&&(t.U=i),!r)if(t&&t.C)t.C=!1;else{do{if(t===this._)break;if(t===i.L){if((n=i.R).C&&(n.C=!1,i.C=!0,pb(this,i),n=i.R),n.L&&n.L.C||n.R&&n.R.C){n.R&&n.R.C||(n.L.C=!1,n.C=!0,vb(this,n),n=i.R),n.C=i.C,i.C=n.R.C=!1,pb(this,i),t=this._;break}}else if((n=i.L).C&&(n.C=!1,i.C=!0,vb(this,i),n=i.L),n.L&&n.L.C||n.R&&n.R.C){n.L&&n.L.C||(n.R.C=!1,n.C=!0,pb(this,n),n=i.L),n.C=i.C,i.C=n.L.C=!1,vb(this,i),t=this._;break}n.C=!0,t=i,i=i.U}while(!t.C);t&&(t.C=!1)}}};var Tb,Ab=[];function Sb(){db(this),this.x=this.y=this.arc=this.site=this.cy=null}function kb(t){var n=t.P,e=t.N;if(n&&e){var r=n.site,i=t.site,o=e.site;if(r!==o){var a=i[0],u=i[1],c=r[0]-a,f=r[1]-u,s=o[0]-a,l=o[1]-u,h=2*(c*l-f*s);if(!(h>=-Hb)){var d=c*c+f*f,p=s*s+l*l,v=(l*d-f*p)/h,g=(c*p-s*d)/h,y=Ab.pop()||new Sb;y.arc=t,y.site=i,y.x=v+a,y.y=(y.cy=g+u)+Math.sqrt(v*v+g*g),t.circle=y;for(var _=null,b=Fb._;b;)if(y.yIb)u=u.L;else{if(!((i=o-Ub(u,a))>Ib)){r>-Ib?(n=u.P,e=u):i>-Ib?(n=u,e=u.N):n=e=u;break}if(!u.R){n=u;break}u=u.R}!function(t){Bb[t.index]={site:t,halfedges:[]}}(t);var c=zb(t);if(Ob.insert(n,c),n||e){if(n===e)return Eb(n),e=zb(n.site),Ob.insert(c,e),c.edge=e.edge=yb(n.site,c.site),kb(n),void kb(e);if(e){Eb(n),Eb(e);var f=n.site,s=f[0],l=f[1],h=t[0]-s,d=t[1]-l,p=e.site,v=p[0]-s,g=p[1]-l,y=2*(h*g-d*v),_=h*h+d*d,b=v*v+g*g,m=[(g*_-d*b)/y+s,(h*b-v*_)/y+l];bb(e.edge,f,p,m),c.edge=yb(f,t,null,m),e.edge=yb(t,p,null,m),kb(n),kb(e)}else c.edge=yb(n.site,c.site)}}function Lb(t,n){var e=t.site,r=e[0],i=e[1],o=i-n;if(!o)return r;var a=t.P;if(!a)return-1/0;var u=(e=a.site)[0],c=e[1],f=c-n;if(!f)return u;var s=u-r,l=1/o-1/f,h=s/f;return l?(-h+Math.sqrt(h*h-2*l*(s*s/(-2*f)-c+f/2+i-o/2)))/l+r:(r+u)/2}function Ub(t,n){var e=t.N;if(e)return Lb(e,n);var r=t.site;return r[1]===n?r[0]:1/0}var Ob,Bb,Fb,Yb,Ib=1e-6,Hb=1e-12;function jb(t,n,e){return(t[0]-e[0])*(n[1]-t[1])-(t[0]-n[0])*(e[1]-t[1])}function Xb(t,n){return n[1]-t[1]||n[0]-t[0]}function Vb(t,n){var e,r,i,o=t.sort(Xb).pop();for(Yb=[],Bb=new Array(t.length),Ob=new hb,Fb=new hb;;)if(i=Tb,o&&(!i||o[1]Ib||Math.abs(i[0][1]-i[1][1])>Ib)||delete Yb[o]}(a,u,c,f),function(t,n,e,r){var i,o,a,u,c,f,s,l,h,d,p,v,g=Bb.length,y=!0;for(i=0;iIb||Math.abs(v-h)>Ib)&&(c.splice(u,0,Yb.push(_b(a,d,Math.abs(p-t)Ib?[t,Math.abs(l-t)Ib?[Math.abs(h-r)Ib?[e,Math.abs(l-e)Ib?[Math.abs(h-n)=u)return null;var c=t-i.site[0],f=n-i.site[1],s=c*c+f*f;do{i=o.cells[r=a],a=null,i.halfedges.forEach(function(e){var r=o.edges[e],u=r.left;if(u!==i.site&&u||(u=r.right)){var c=t-u[0],f=n-u[1],l=c*c+f*f;lr?(r+i)/2:Math.min(0,r)||Math.max(0,i),a>o?(o+a)/2:Math.min(0,o)||Math.max(0,a))}Qb.prototype=Wb.prototype,t.FormatSpecifier=Ba,t.active=function(t,n){var e,r,i=t.__transition;if(i)for(r in n=null==n?null:n+"",i)if((e=i[r]).state>xr&&e.name===n)return new Ur([[t]],yi,n,+r);return null},t.arc=function(){var t=Ry,n=Dy,e=my(0),r=null,i=qy,o=Ly,a=Uy,u=null;function c(){var c,f,s=+t.apply(this,arguments),l=+n.apply(this,arguments),h=i.apply(this,arguments)-Cy,d=o.apply(this,arguments)-Cy,p=xy(d-h),v=d>h;if(u||(u=c=no()),lky)if(p>Py-ky)u.moveTo(l*My(h),l*Ay(h)),u.arc(0,0,l,h,d,!v),s>ky&&(u.moveTo(s*My(d),s*Ay(d)),u.arc(0,0,s,d,h,v));else{var g,y,_=h,b=d,m=h,x=d,w=p,M=p,N=a.apply(this,arguments)/2,T=N>ky&&(r?+r.apply(this,arguments):Sy(s*s+l*l)),A=Ty(xy(l-s)/2,+e.apply(this,arguments)),S=A,k=A;if(T>ky){var E=zy(T/s*Ay(N)),C=zy(T/l*Ay(N));(w-=2*E)>ky?(m+=E*=v?1:-1,x-=E):(w=0,m=x=(h+d)/2),(M-=2*C)>ky?(_+=C*=v?1:-1,b-=C):(M=0,_=b=(h+d)/2)}var P=l*My(_),z=l*Ay(_),R=s*My(x),D=s*Ay(x);if(A>ky){var q,L=l*My(b),U=l*Ay(b),O=s*My(m),B=s*Ay(m);if(p1?0:t<-1?Ey:Math.acos(t)}((F*I+Y*H)/(Sy(F*F+Y*Y)*Sy(I*I+H*H)))/2),X=Sy(q[0]*q[0]+q[1]*q[1]);S=Ty(A,(s-X)/(j-1)),k=Ty(A,(l-X)/(j+1))}}M>ky?k>ky?(g=Oy(O,B,P,z,l,k,v),y=Oy(L,U,R,D,l,k,v),u.moveTo(g.cx+g.x01,g.cy+g.y01),kky&&w>ky?S>ky?(g=Oy(R,D,L,U,s,-S,v),y=Oy(P,z,O,B,s,-S,v),u.lineTo(g.cx+g.x01,g.cy+g.y01),S>a,f=i+2*u>>a,s=bo(20);function l(r){var i=new Float32Array(c*f),l=new Float32Array(c*f);r.forEach(function(r,o,s){var l=+t(r,o,s)+u>>a,h=+n(r,o,s)+u>>a,d=+e(r,o,s);l>=0&&l=0&&h>a),So({width:c,height:f,data:l},{width:c,height:f,data:i},o>>a),Ao({width:c,height:f,data:i},{width:c,height:f,data:l},o>>a),So({width:c,height:f,data:l},{width:c,height:f,data:i},o>>a),Ao({width:c,height:f,data:i},{width:c,height:f,data:l},o>>a),So({width:c,height:f,data:l},{width:c,height:f,data:i},o>>a);var d=s(i);if(!Array.isArray(d)){var p=T(i);d=w(0,p,d),(d=g(0,Math.floor(p/d)*d,d)).shift()}return To().thresholds(d).size([c,f])(i).map(h)}function h(t){return t.value*=Math.pow(2,-2*a),t.coordinates.forEach(d),t}function d(t){t.forEach(p)}function p(t){t.forEach(v)}function v(t){t[0]=t[0]*Math.pow(2,a)-u,t[1]=t[1]*Math.pow(2,a)-u}function y(){return c=r+2*(u=3*o)>>a,f=i+2*u>>a,l}return l.x=function(n){return arguments.length?(t="function"==typeof n?n:bo(+n),l):t},l.y=function(t){return arguments.length?(n="function"==typeof t?t:bo(+t),l):n},l.weight=function(t){return arguments.length?(e="function"==typeof t?t:bo(+t),l):e},l.size=function(t){if(!arguments.length)return[r,i];var n=Math.ceil(t[0]),e=Math.ceil(t[1]);if(!(n>=0||n>=0))throw new Error("invalid size");return r=n,i=e,y()},l.cellSize=function(t){if(!arguments.length)return 1<=1))throw new Error("invalid cell size");return a=Math.floor(Math.log(t)/Math.LN2),y()},l.thresholds=function(t){return arguments.length?(s="function"==typeof t?t:Array.isArray(t)?bo(yo.call(t)):bo(t),l):s},l.bandwidth=function(t){if(!arguments.length)return Math.sqrt(o*(o+1));if(!((t=+t)>=0))throw new Error("invalid bandwidth");return o=Math.round((Math.sqrt(4*t*t+1)-1)/2),y()},l},t.contours=To,t.create=function(t){return Rt(Z(t).call(document.documentElement))},t.creator=Z,t.cross=function(t,n,e){var r,i,o,u,c=t.length,f=n.length,s=new Array(c*f);for(null==e&&(e=a),r=o=0;rt?1:n>=t?0:NaN},t.deviation=f,t.dispatch=I,t.drag=function(){var n,e,r,i,o=Gt,a=$t,u=Wt,c=Zt,f={},s=I("start","drag","end"),l=0,h=0;function d(t){t.on("mousedown.drag",p).filter(c).on("touchstart.drag",y).on("touchmove.drag",_).on("touchend.drag touchcancel.drag",b).style("touch-action","none").style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}function p(){if(!i&&o.apply(this,arguments)){var u=m("mouse",a.apply(this,arguments),Bt,this,arguments);u&&(Rt(t.event.view).on("mousemove.drag",v,!0).on("mouseup.drag",g,!0),Ht(t.event.view),Yt(),r=!1,n=t.event.clientX,e=t.event.clientY,u("start"))}}function v(){if(It(),!r){var i=t.event.clientX-n,o=t.event.clientY-e;r=i*i+o*o>h}f.mouse("drag")}function g(){Rt(t.event.view).on("mousemove.drag mouseup.drag",null),jt(t.event.view,r),It(),f.mouse("end")}function y(){if(o.apply(this,arguments)){var n,e,r=t.event.changedTouches,i=a.apply(this,arguments),u=r.length;for(n=0;nc+d||if+d||ou.index){var p=c-a.x-a.vx,v=f-a.y-a.vy,g=p*p+v*v;gt.r&&(t.r=t[n].r)}function u(){if(n){var r,i,o=n.length;for(e=new Array(o),r=0;r=a)){(t.data!==n||t.next)&&(0===s&&(d+=(s=ya())*s),0===l&&(d+=(l=ya())*l),d1?(null==e?u.remove(t):u.set(t,d(e)),n):u.get(t)},find:function(n,e,r){var i,o,a,u,c,f=0,s=t.length;for(null==r?r=1/0:r*=r,f=0;f1?(f.on(t,e),n):f.on(t)}}},t.forceX=function(t){var n,e,r,i=ga(.1);function o(t){for(var i,o=0,a=n.length;o=.12&&i<.234&&r>=-.425&&r<-.214?u:i>=.166&&i<.234&&r>=-.214&&r<-.115?c:a).invert(t)},s.stream=function(e){return t&&n===e?t:(r=[a.stream(n=e),u.stream(e),c.stream(e)],i=r.length,t={point:function(t,n){for(var e=-1;++ePc(r[0],r[1])&&(r[1]=i[1]),Pc(i[0],r[1])>Pc(r[0],r[1])&&(r[0]=i[0])):o.push(r=i);for(a=-1/0,n=0,r=o[e=o.length-1];n<=e;r=i,++n)i=o[n],(u=Pc(r[1],i[0]))>a&&(a=u,Zu=i[0],Ku=r[1])}return ic=oc=null,Zu===1/0||Qu===1/0?[[NaN,NaN],[NaN,NaN]]:[[Zu,Qu],[Ku,Ju]]},t.geoCentroid=function(t){ac=uc=cc=fc=sc=lc=hc=dc=pc=vc=gc=0,Cu(t,Dc);var n=pc,e=vc,r=gc,i=n*n+e*e+r*r;return i2?t[2]+90:90]):[(t=e())[0],t[1],t[2]-90]},e([0,0,90]).scale(159.155)},t.geoTransverseMercatorRaw=Ml,t.gray=function(t,n){return new Bn(t,0,0,null==n?1:n)},t.hcl=Xn,t.hierarchy=kl,t.histogram=function(){var t=v,n=s,e=M;function r(r){var o,a,u=r.length,c=new Array(u);for(o=0;ol;)h.pop(),--d;var p,v=new Array(d+1);for(o=0;o<=d;++o)(p=v[o]=[]).x0=o>0?h[o-1]:s,p.x1=o1)&&(t-=Math.floor(t));var n=Math.abs(t-.5);return ly.h=360*t-100,ly.s=1.5-1.5*n,ly.l=.8-.9*n,ly+""},t.interpolateRdBu=yg,t.interpolateRdGy=bg,t.interpolateRdPu=Yg,t.interpolateRdYlBu=xg,t.interpolateRdYlGn=Mg,t.interpolateReds=oy,t.interpolateRgb=he,t.interpolateRgbBasis=pe,t.interpolateRgbBasisClosed=ve,t.interpolateRound=Ae,t.interpolateSinebow=function(t){var n;return t=(.5-t)*Math.PI,hy.r=255*(n=Math.sin(t))*n,hy.g=255*(n=Math.sin(t+dy))*n,hy.b=255*(n=Math.sin(t+py))*n,hy+""},t.interpolateSpectral=Tg,t.interpolateString=Ne,t.interpolateTransformCss=qe,t.interpolateTransformSvg=Le,t.interpolateTurbo=function(t){return t=Math.max(0,Math.min(1,t)),"rgb("+Math.max(0,Math.min(255,Math.round(34.61+t*(1172.33-t*(10793.56-t*(33300.12-t*(38394.49-14825.05*t)))))))+", "+Math.max(0,Math.min(255,Math.round(23.31+t*(557.33+t*(1225.33-t*(3574.96-t*(1073.77+707.56*t)))))))+", "+Math.max(0,Math.min(255,Math.round(27.2+t*(3211.1-t*(15327.97-t*(27814-t*(22569.18-6838.66*t)))))))+")"},t.interpolateViridis=gy,t.interpolateWarm=fy,t.interpolateYlGn=Xg,t.interpolateYlGnBu=Hg,t.interpolateYlOrBr=Gg,t.interpolateYlOrRd=Wg,t.interpolateZoom=Ie,t.interrupt=Pr,t.interval=function(t,n,e){var r=new lr,i=n;return null==n?(r.restart(t,n,e),r):(n=+n,e=null==e?fr():+e,r.restart(function o(a){a+=i,r.restart(o,i+=n,e),t(a)},n,e),r)},t.isoFormat=Rv,t.isoParse=Dv,t.json=function(t,n){return fetch(t,n).then(la)},t.keys=function(t){var n=[];for(var e in t)n.push(e);return n},t.lab=On,t.lch=function(t,n,e,r){return 1===arguments.length?jn(t):new Vn(e,n,t,null==r?1:r)},t.line=Hy,t.lineRadial=Qy,t.linkHorizontal=function(){return r_(i_)},t.linkRadial=function(){var t=r_(a_);return t.angle=t.x,delete t.x,t.radius=t.y,delete t.y,t},t.linkVertical=function(){return r_(o_)},t.local=qt,t.map=co,t.matcher=nt,t.max=T,t.mean=function(t,n){var e,r=t.length,i=r,o=-1,a=0;if(null==n)for(;++o=r.length)return null!=t&&e.sort(t),null!=n?n(e):e;for(var c,f,s,l=-1,h=e.length,d=r[i++],p=co(),v=a();++lr.length)return e;var a,u=i[o-1];return null!=n&&o>=r.length?a=e.entries():(a=[],e.each(function(n,e){a.push({key:e,values:t(n,o)})})),null!=u?a.sort(function(t,n){return u(t.key,n.key)}):a}(o(t,0,lo,ho),0)},key:function(t){return r.push(t),e},sortKeys:function(t){return i[r.length-1]=t,e},sortValues:function(n){return t=n,e},rollup:function(t){return n=t,e}}},t.now=fr,t.pack=function(){var t=null,n=1,e=1,r=Wl;function i(i){return i.x=n/2,i.y=e/2,t?i.eachBefore(Kl(t)).eachAfter(Jl(r,.5)).eachBefore(th(1)):i.eachBefore(Kl(Ql)).eachAfter(Jl(Wl,1)).eachAfter(Jl(r,i.r/Math.min(n,e))).eachBefore(th(Math.min(n,e)/(2*i.r))),i}return i.radius=function(n){return arguments.length?(t=Gl(n),i):t},i.size=function(t){return arguments.length?(n=+t[0],e=+t[1],i):[n,e]},i.padding=function(t){return arguments.length?(r="function"==typeof t?t:Zl(+t),i):r},i},t.packEnclose=Dl,t.packSiblings=function(t){return Vl(t),t},t.pairs=function(t,n){null==n&&(n=a);for(var e=0,r=t.length-1,i=t[0],o=new Array(r<0?0:r);e0&&(d+=l);for(null!=n?p.sort(function(t,e){return n(v[t],v[e])}):null!=e&&p.sort(function(t,n){return e(a[t],a[n])}),u=0,f=d?(y-h*b)/d:0;u0?l*f:0)+b,v[c]={data:a[c],index:u,value:l,startAngle:g,endAngle:s,padAngle:_};return v}return a.value=function(n){return arguments.length?(t="function"==typeof n?n:my(+n),a):t},a.sortValues=function(t){return arguments.length?(n=t,e=null,a):n},a.sort=function(t){return arguments.length?(e=t,n=null,a):e},a.startAngle=function(t){return arguments.length?(r="function"==typeof t?t:my(+t),a):r},a.endAngle=function(t){return arguments.length?(i="function"==typeof t?t:my(+t),a):i},a.padAngle=function(t){return arguments.length?(o="function"==typeof t?t:my(+t),a):o},a},t.piecewise=function(t,n){for(var e=0,r=n.length-1,i=n[0],o=new Array(r<0?0:r);eu!=f>u&&a<(c-e)*(u-r)/(f-r)+e&&(s=!s),c=e,f=r;return s},t.polygonHull=function(t){if((e=t.length)<3)return null;var n,e,r=new Array(e),i=new Array(e);for(n=0;n=0;--n)f.push(t[r[o[n]][2]]);for(n=+u;n0?a[n-1]:r[0],n=o?[a[o-1],r]:[a[n-1],a[n]]},c.unknown=function(t){return arguments.length?(n=t,c):c},c.thresholds=function(){return a.slice()},c.copy=function(){return t().domain([e,r]).range(u).unknown(n)},Eh.apply($h(c),arguments)},t.scaleSequential=function t(){var n=$h(Xv()(Bh));return n.copy=function(){return Vv(n,t())},Ch.apply(n,arguments)},t.scaleSequentialLog=function t(){var n=ed(Xv()).domain([1,10]);return n.copy=function(){return Vv(n,t()).base(n.base())},Ch.apply(n,arguments)},t.scaleSequentialPow=Gv,t.scaleSequentialQuantile=function t(){var e=[],r=Bh;function o(t){if(!isNaN(t=+t))return r((i(e,t)-1)/(e.length-1))}return o.domain=function(t){if(!arguments.length)return e.slice();e=[];for(var r,i=0,a=t.length;i0)for(var e,r,i,o,a,u,c=0,f=t[n[0]].length;c0?(r[0]=o,r[1]=o+=i):i<0?(r[1]=a,r[0]=a+=i):(r[0]=0,r[1]=i)},t.stackOffsetExpand=function(t,n){if((r=t.length)>0){for(var e,r,i,o=0,a=t[0].length;o0){for(var e,r=0,i=t[n[0]],o=i.length;r0&&(r=(e=t[n[0]]).length)>0){for(var e,r,i,o=0,a=1;a0)throw new Error("cycle");return o}return e.id=function(n){return arguments.length?(t=$l(n),e):t},e.parentId=function(t){return arguments.length?(n=$l(t),e):n},e},t.style=ft,t.sum=function(t,n){var e,r=t.length,i=-1,o=0;if(null==n)for(;++i=0;--i)u.push(e=n.children[i]=new dh(r[i],i)),e.parent=n;return(a.parent=new dh(null,0)).children=[a],a}(i);if(c.eachAfter(o),c.parent.m=-c.z,c.eachBefore(a),r)i.eachBefore(u);else{var f=i,s=i,l=i;i.eachBefore(function(t){t.xs.x&&(s=t),t.depth>l.depth&&(l=t)});var h=f===s?1:t(f,s)/2,d=h-f.x,p=n/(s.x+h+d),v=e/(l.depth||1);i.eachBefore(function(t){t.x=(t.x+d)*p,t.y=t.depth*v})}return i}function o(n){var e=n.children,r=n.parent.children,i=n.i?r[n.i-1]:null;if(e){!function(t){for(var n,e=0,r=0,i=t.children,o=i.length;--o>=0;)(n=i[o]).z+=e,n.m+=e,e+=n.s+(r+=n.c)}(n);var o=(e[0].z+e[e.length-1].z)/2;i?(n.z=i.z+t(n._,i._),n.m=n.z-o):n.z=o}else i&&(n.z=i.z+t(n._,i._));n.parent.A=function(n,e,r){if(e){for(var i,o=n,a=n,u=e,c=o.parent.children[0],f=o.m,s=a.m,l=u.m,h=c.m;u=sh(u),o=fh(o),u&&o;)c=fh(c),(a=sh(a)).a=n,(i=u.z+l-o.z-f+t(u._,o._))>0&&(lh(hh(u,n,r),n,i),f+=i,s+=i),l+=u.m,f+=o.m,h+=c.m,s+=a.m;u&&!sh(a)&&(a.t=u,a.m+=l-s),o&&!fh(c)&&(c.t=o,c.m+=f-h,r=n)}return r}(n,i,n.parent.A||r[0])}function a(t){t._.x=t.z+t.parent.m,t.m+=t.parent.m}function u(t){t.x*=n,t.y=t.depth*e}return i.separation=function(n){return arguments.length?(t=n,i):t},i.size=function(t){return arguments.length?(r=!1,n=+t[0],e=+t[1],i):r?null:[n,e]},i.nodeSize=function(t){return arguments.length?(r=!0,n=+t[0],e=+t[1],i):r?[n,e]:null},i},t.treemap=function(){var t=yh,n=!1,e=1,r=1,i=[0],o=Wl,a=Wl,u=Wl,c=Wl,f=Wl;function s(t){return t.x0=t.y0=0,t.x1=e,t.y1=r,t.eachBefore(l),i=[0],n&&t.eachBefore(nh),t}function l(n){var e=i[n.depth],r=n.x0+e,s=n.y0+e,l=n.x1-e,h=n.y1-e;l=e-1){var s=u[n];return s.x0=i,s.y0=o,s.x1=a,void(s.y1=c)}for(var l=f[n],h=r/2+l,d=n+1,p=e-1;d>>1;f[v]c-o){var _=(i*y+a*g)/r;t(n,d,g,i,o,_,c),t(d,e,y,_,o,a,c)}else{var b=(o*y+c*g)/r;t(n,d,g,i,o,a,b),t(d,e,y,i,b,a,c)}}(0,c,t.value,n,e,r,i)},t.treemapDice=eh,t.treemapResquarify=_h,t.treemapSlice=ph,t.treemapSliceDice=function(t,n,e,r,i){(1&t.depth?ph:eh)(t,n,e,r,i)},t.treemapSquarify=yh,t.tsv=sa,t.tsvFormat=Ko,t.tsvFormatBody=Jo,t.tsvFormatRow=na,t.tsvFormatRows=ta,t.tsvFormatValue=ea,t.tsvParse=Zo,t.tsvParseRows=Qo,t.utcDay=Wd,t.utcDays=Zd,t.utcFriday=rp,t.utcFridays=sp,t.utcHour=Gd,t.utcHours=$d,t.utcMillisecond=pd,t.utcMilliseconds=vd,t.utcMinute=Xd,t.utcMinutes=Vd,t.utcMonday=Jd,t.utcMondays=ap,t.utcMonth=hp,t.utcMonths=dp,t.utcSaturday=ip,t.utcSaturdays=lp,t.utcSecond=_d,t.utcSeconds=bd,t.utcSunday=Kd,t.utcSundays=op,t.utcThursday=ep,t.utcThursdays=fp,t.utcTuesday=tp,t.utcTuesdays=up,t.utcWednesday=np,t.utcWednesdays=cp,t.utcWeek=Kd,t.utcWeeks=op,t.utcYear=pp,t.utcYears=vp,t.values=function(t){var n=[];for(var e in t)n.push(t[e]);return n},t.variance=c,t.version="5.16.0",t.voronoi=function(){var t=sb,n=lb,e=null;function r(r){return new Vb(r.map(function(e,i){var o=[Math.round(t(e,i,r)/Ib)*Ib,Math.round(n(e,i,r)/Ib)*Ib];return o.index=i,o.data=e,o}),e)}return r.polygons=function(t){return r(t).polygons()},r.links=function(t){return r(t).links()},r.triangles=function(t){return r(t).triangles()},r.x=function(n){return arguments.length?(t="function"==typeof n?n:fb(+n),r):t},r.y=function(t){return arguments.length?(n="function"==typeof t?t:fb(+t),r):n},r.extent=function(t){return arguments.length?(e=null==t?null:[[+t[0][0],+t[0][1]],[+t[1][0],+t[1][1]]],r):e&&[[e[0][0],e[0][1]],[e[1][0],e[1][1]]]},r.size=function(t){return arguments.length?(e=null==t?null:[[0,0],[+t[0],+t[1]]],r):e&&[e[1][0]-e[0][0],e[1][1]-e[0][1]]},r},t.window=ct,t.xml=da,t.zip=function(){return k(arguments)},t.zoom=function(){var n,e,r=tm,i=nm,o=om,a=rm,u=im,c=[0,1/0],f=[[-1/0,-1/0],[1/0,1/0]],s=250,l=Ie,h=I("start","zoom","end"),d=500,p=150,v=0;function g(t){t.property("__zoom",em).on("wheel.zoom",M).on("mousedown.zoom",N).on("dblclick.zoom",T).filter(u).on("touchstart.zoom",A).on("touchmove.zoom",S).on("touchend.zoom touchcancel.zoom",k).style("touch-action","none").style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}function y(t,n){return(n=Math.max(c[0],Math.min(c[1],n)))===t.k?t:new Wb(n,t.x,t.y)}function _(t,n,e){var r=n[0]-e[0]*t.k,i=n[1]-e[1]*t.k;return r===t.x&&i===t.y?t:new Wb(t.k,r,i)}function b(t){return[(+t[0][0]+ +t[1][0])/2,(+t[0][1]+ +t[1][1])/2]}function m(t,n,e){t.on("start.zoom",function(){x(this,arguments).start()}).on("interrupt.zoom end.zoom",function(){x(this,arguments).end()}).tween("zoom",function(){var t=this,r=arguments,o=x(t,r),a=i.apply(t,r),u=null==e?b(a):"function"==typeof e?e.apply(t,r):e,c=Math.max(a[1][0]-a[0][0],a[1][1]-a[0][1]),f=t.__zoom,s="function"==typeof n?n.apply(t,r):n,h=l(f.invert(u).concat(c/f.k),s.invert(u).concat(c/s.k));return function(t){if(1===t)t=s;else{var n=h(t),e=c/n[2];t=new Wb(e,u[0]-n[0]*e,u[1]-n[1]*e)}o.zoom(null,t)}})}function x(t,n,e){return!e&&t.__zooming||new w(t,n)}function w(t,n){this.that=t,this.args=n,this.active=0,this.extent=i.apply(t,n),this.taps=0}function M(){if(r.apply(this,arguments)){var t=x(this,arguments),n=this.__zoom,e=Math.max(c[0],Math.min(c[1],n.k*Math.pow(2,a.apply(this,arguments)))),i=Bt(this);if(t.wheel)t.mouse[0][0]===i[0]&&t.mouse[0][1]===i[1]||(t.mouse[1]=n.invert(t.mouse[0]=i)),clearTimeout(t.wheel);else{if(n.k===e)return;t.mouse=[i,n.invert(i)],Pr(this),t.start()}Jb(),t.wheel=setTimeout(function(){t.wheel=null,t.end()},p),t.zoom("mouse",o(_(y(n,e),t.mouse[0],t.mouse[1]),t.extent,f))}}function N(){if(!e&&r.apply(this,arguments)){var n=x(this,arguments,!0),i=Rt(t.event.view).on("mousemove.zoom",function(){if(Jb(),!n.moved){var e=t.event.clientX-u,r=t.event.clientY-c;n.moved=e*e+r*r>v}n.zoom("mouse",o(_(n.that.__zoom,n.mouse[0]=Bt(n.that),n.mouse[1]),n.extent,f))},!0).on("mouseup.zoom",function(){i.on("mousemove.zoom mouseup.zoom",null),jt(t.event.view,n.moved),Jb(),n.end()},!0),a=Bt(this),u=t.event.clientX,c=t.event.clientY;Ht(t.event.view),Kb(),n.mouse=[a,this.__zoom.invert(a)],Pr(this),n.start()}}function T(){if(r.apply(this,arguments)){var n=this.__zoom,e=Bt(this),a=n.invert(e),u=n.k*(t.event.shiftKey?.5:2),c=o(_(y(n,u),e,a),i.apply(this,arguments),f);Jb(),s>0?Rt(this).transition().duration(s).call(m,c,e):Rt(this).call(g.transform,c)}}function A(){if(r.apply(this,arguments)){var e,i,o,a,u=t.event.touches,c=u.length,f=x(this,arguments,t.event.changedTouches.length===c);for(Kb(),i=0;in?1:t>=n?0:NaN}function e(t,n){return null==t||null==n?NaN:nt?1:n>=t?0:NaN}function r(t){let r,o,a;function u(t,n,e=0,i=t.length){if(e>>1;o(t[r],n)<0?e=r+1:i=r}while(en(t(e),r),a=(n,e)=>t(n)-e):(r=t===n||t===e?t:i,o=t,a=t),{left:u,center:function(t,n,e=0,r=t.length){const i=u(t,n,e,r-1);return i>e&&a(t[i-1],n)>-a(t[i],n)?i-1:i},right:function(t,n,e=0,i=t.length){if(e>>1;o(t[r],n)<=0?e=r+1:i=r}while(e{n(t,e,(r<<=2)+0,(i<<=2)+0,o<<=2),n(t,e,r+1,i+1,o),n(t,e,r+2,i+2,o),n(t,e,r+3,i+3,o)}}));function d(t){return function(n,e,r=e){if(!((e=+e)>=0))throw new RangeError("invalid rx");if(!((r=+r)>=0))throw new RangeError("invalid ry");let{data:i,width:o,height:a}=n;if(!((o=Math.floor(o))>=0))throw new RangeError("invalid width");if(!((a=Math.floor(void 0!==a?a:i.length/o))>=0))throw new RangeError("invalid height");if(!o||!a||!e&&!r)return n;const u=e&&t(e),c=r&&t(r),f=i.slice();return u&&c?(p(u,f,i,o,a),p(u,i,f,o,a),p(u,f,i,o,a),g(c,i,f,o,a),g(c,f,i,o,a),g(c,i,f,o,a)):u?(p(u,i,f,o,a),p(u,f,i,o,a),p(u,i,f,o,a)):c&&(g(c,i,f,o,a),g(c,f,i,o,a),g(c,i,f,o,a)),n}}function p(t,n,e,r,i){for(let o=0,a=r*i;o{if(!((o-=a)>=i))return;let u=t*r[i];const c=a*t;for(let t=i,n=i+c;t{if(!((a-=u)>=o))return;let c=n*i[o];const f=u*n,s=f+u;for(let t=o,n=o+f;t=n&&++e;else{let r=-1;for(let i of t)null!=(i=n(i,++r,t))&&(i=+i)>=i&&++e}return e}function _(t){return 0|t.length}function b(t){return!(t>0)}function m(t){return"object"!=typeof t||"length"in t?t:Array.from(t)}function x(t,n){let e,r=0,i=0,o=0;if(void 0===n)for(let n of t)null!=n&&(n=+n)>=n&&(e=n-i,i+=e/++r,o+=e*(n-i));else{let a=-1;for(let u of t)null!=(u=n(u,++a,t))&&(u=+u)>=u&&(e=u-i,i+=e/++r,o+=e*(u-i))}if(r>1)return o/(r-1)}function w(t,n){const e=x(t,n);return e?Math.sqrt(e):e}function M(t,n){let e,r;if(void 0===n)for(const n of t)null!=n&&(void 0===e?n>=n&&(e=r=n):(e>n&&(e=n),r=o&&(e=r=o):(e>o&&(e=o),r0){for(o=t[--i];i>0&&(n=o,e=t[--i],o=n+e,r=e-(o-n),!r););i>0&&(r<0&&t[i-1]<0||r>0&&t[i-1]>0)&&(e=2*r,n=o+e,e==n-o&&(o=n))}return o}}class InternMap extends Map{constructor(t,n=N){if(super(),Object.defineProperties(this,{_intern:{value:new Map},_key:{value:n}}),null!=t)for(const[n,e]of t)this.set(n,e)}get(t){return super.get(A(this,t))}has(t){return super.has(A(this,t))}set(t,n){return super.set(S(this,t),n)}delete(t){return super.delete(E(this,t))}}class InternSet extends Set{constructor(t,n=N){if(super(),Object.defineProperties(this,{_intern:{value:new Map},_key:{value:n}}),null!=t)for(const n of t)this.add(n)}has(t){return super.has(A(this,t))}add(t){return super.add(S(this,t))}delete(t){return super.delete(E(this,t))}}function A({_intern:t,_key:n},e){const r=n(e);return t.has(r)?t.get(r):e}function S({_intern:t,_key:n},e){const r=n(e);return t.has(r)?t.get(r):(t.set(r,e),e)}function E({_intern:t,_key:n},e){const r=n(e);return t.has(r)&&(e=t.get(r),t.delete(r)),e}function N(t){return null!==t&&"object"==typeof t?t.valueOf():t}function k(t){return t}function C(t,...n){return F(t,k,k,n)}function P(t,...n){return F(t,Array.from,k,n)}function z(t,n){for(let e=1,r=n.length;et.pop().map((([n,e])=>[...t,n,e]))));return t}function $(t,n,...e){return F(t,k,n,e)}function D(t,n,...e){return F(t,Array.from,n,e)}function R(t){if(1!==t.length)throw new Error("duplicate key");return t[0]}function F(t,n,e,r){return function t(i,o){if(o>=r.length)return e(i);const a=new InternMap,u=r[o++];let c=-1;for(const t of i){const n=u(t,++c,i),e=a.get(n);e?e.push(t):a.set(n,[t])}for(const[n,e]of a)a.set(n,t(e,o));return n(a)}(t,0)}function q(t,n){return Array.from(n,(n=>t[n]))}function U(t,...n){if("function"!=typeof t[Symbol.iterator])throw new TypeError("values is not iterable");t=Array.from(t);let[e]=n;if(e&&2!==e.length||n.length>1){const r=Uint32Array.from(t,((t,n)=>n));return n.length>1?(n=n.map((n=>t.map(n))),r.sort(((t,e)=>{for(const r of n){const n=O(r[t],r[e]);if(n)return n}}))):(e=t.map(e),r.sort(((t,n)=>O(e[t],e[n])))),q(t,r)}return t.sort(I(e))}function I(t=n){if(t===n)return O;if("function"!=typeof t)throw new TypeError("compare is not a function");return(n,e)=>{const r=t(n,e);return r||0===r?r:(0===t(e,e))-(0===t(n,n))}}function O(t,n){return(null==t||!(t>=t))-(null==n||!(n>=n))||(tn?1:0)}var B=Array.prototype.slice;function Y(t){return()=>t}const L=Math.sqrt(50),j=Math.sqrt(10),H=Math.sqrt(2);function X(t,n,e){const r=(n-t)/Math.max(0,e),i=Math.floor(Math.log10(r)),o=r/Math.pow(10,i),a=o>=L?10:o>=j?5:o>=H?2:1;let u,c,f;return i<0?(f=Math.pow(10,-i)/a,u=Math.round(t*f),c=Math.round(n*f),u/fn&&--c,f=-f):(f=Math.pow(10,i)*a,u=Math.round(t/f),c=Math.round(n/f),u*fn&&--c),c0))return[];if((t=+t)===(n=+n))return[t];const r=n=i))return[];const u=o-i+1,c=new Array(u);if(r)if(a<0)for(let t=0;t0?(t=Math.floor(t/i)*i,n=Math.ceil(n/i)*i):i<0&&(t=Math.ceil(t*i)/i,n=Math.floor(n*i)/i),r=i}}function K(t){return Math.max(1,Math.ceil(Math.log(v(t))/Math.LN2)+1)}function Q(){var t=k,n=M,e=K;function r(r){Array.isArray(r)||(r=Array.from(r));var i,o,a,u=r.length,c=new Array(u);for(i=0;i=h)if(t>=h&&n===M){const t=V(l,h,e);isFinite(t)&&(t>0?h=(Math.floor(h/t)+1)*t:t<0&&(h=(Math.ceil(h*-t)+1)/-t))}else d.pop()}for(var p=d.length,g=0,y=p;d[g]<=l;)++g;for(;d[y-1]>h;)--y;(g||y0?d[i-1]:l,v.x1=i0)for(i=0;i=n)&&(e=n);else{let r=-1;for(let i of t)null!=(i=n(i,++r,t))&&(e=i)&&(e=i)}return e}function tt(t,n){let e,r=-1,i=-1;if(void 0===n)for(const n of t)++i,null!=n&&(e=n)&&(e=n,r=i);else for(let o of t)null!=(o=n(o,++i,t))&&(e=o)&&(e=o,r=i);return r}function nt(t,n){let e;if(void 0===n)for(const n of t)null!=n&&(e>n||void 0===e&&n>=n)&&(e=n);else{let r=-1;for(let i of t)null!=(i=n(i,++r,t))&&(e>i||void 0===e&&i>=i)&&(e=i)}return e}function et(t,n){let e,r=-1,i=-1;if(void 0===n)for(const n of t)++i,null!=n&&(e>n||void 0===e&&n>=n)&&(e=n,r=i);else for(let o of t)null!=(o=n(o,++i,t))&&(e>o||void 0===e&&o>=o)&&(e=o,r=i);return r}function rt(t,n,e=0,r=1/0,i){if(n=Math.floor(n),e=Math.floor(Math.max(0,e)),r=Math.floor(Math.min(t.length-1,r)),!(e<=n&&n<=r))return t;for(i=void 0===i?O:I(i);r>e;){if(r-e>600){const o=r-e+1,a=n-e+1,u=Math.log(o),c=.5*Math.exp(2*u/3),f=.5*Math.sqrt(u*c*(o-c)/o)*(a-o/2<0?-1:1);rt(t,n,Math.max(e,Math.floor(n-a*c/o+f)),Math.min(r,Math.floor(n+(o-a)*c/o+f)),i)}const o=t[n];let a=e,u=r;for(it(t,e,n),i(t[r],o)>0&&it(t,e,r);a0;)--u}0===i(t[e],o)?it(t,e,u):(++u,it(t,u,r)),u<=n&&(e=u+1),n<=u&&(r=u-1)}return t}function it(t,n,e){const r=t[n];t[n]=t[e],t[e]=r}function ot(t,e=n){let r,i=!1;if(1===e.length){let o;for(const a of t){const t=e(a);(i?n(t,o)>0:0===n(t,t))&&(r=a,o=t,i=!0)}}else for(const n of t)(i?e(n,r)>0:0===e(n,n))&&(r=n,i=!0);return r}function at(t,n,e){if(t=Float64Array.from(function*(t,n){if(void 0===n)for(let n of t)null!=n&&(n=+n)>=n&&(yield n);else{let e=-1;for(let r of t)null!=(r=n(r,++e,t))&&(r=+r)>=r&&(yield r)}}(t,e)),(r=t.length)&&!isNaN(n=+n)){if(n<=0||r<2)return nt(t);if(n>=1)return J(t);var r,i=(r-1)*n,o=Math.floor(i),a=J(rt(t,o).subarray(0,o+1));return a+(nt(t.subarray(o+1))-a)*(i-o)}}function ut(t,n,e=o){if((r=t.length)&&!isNaN(n=+n)){if(n<=0||r<2)return+e(t[0],0,t);if(n>=1)return+e(t[r-1],r-1,t);var r,i=(r-1)*n,a=Math.floor(i),u=+e(t[a],a,t);return u+(+e(t[a+1],a+1,t)-u)*(i-a)}}function ct(t,n,e=o){if(!isNaN(n=+n)){if(r=Float64Array.from(t,((n,r)=>o(e(t[r],r,t)))),n<=0)return et(r);if(n>=1)return tt(r);var r,i=Uint32Array.from(t,((t,n)=>n)),a=r.length-1,u=Math.floor(a*n);return rt(i,u,0,a,((t,n)=>O(r[t],r[n]))),(u=ot(i.subarray(0,u+1),(t=>r[t])))>=0?u:-1}}function ft(t){return Array.from(function*(t){for(const n of t)yield*n}(t))}function st(t,n){return[t,n]}function lt(t,n,e){t=+t,n=+n,e=(i=arguments.length)<2?(n=t,t=0,1):i<3?1:+e;for(var r=-1,i=0|Math.max(0,Math.ceil((n-t)/e)),o=new Array(i);++r+t(n)}function kt(t,n){return n=Math.max(0,t.bandwidth()-2*n)/2,t.round()&&(n=Math.round(n)),e=>+t(e)+n}function Ct(){return!this.__axis}function Pt(t,n){var e=[],r=null,i=null,o=6,a=6,u=3,c="undefined"!=typeof window&&window.devicePixelRatio>1?0:.5,f=t===xt||t===Tt?-1:1,s=t===Tt||t===wt?"x":"y",l=t===xt||t===Mt?St:Et;function h(h){var d=null==r?n.ticks?n.ticks.apply(n,e):n.domain():r,p=null==i?n.tickFormat?n.tickFormat.apply(n,e):mt:i,g=Math.max(o,0)+u,y=n.range(),v=+y[0]+c,_=+y[y.length-1]+c,b=(n.bandwidth?kt:Nt)(n.copy(),c),m=h.selection?h.selection():h,x=m.selectAll(".domain").data([null]),w=m.selectAll(".tick").data(d,n).order(),M=w.exit(),T=w.enter().append("g").attr("class","tick"),A=w.select("line"),S=w.select("text");x=x.merge(x.enter().insert("path",".tick").attr("class","domain").attr("stroke","currentColor")),w=w.merge(T),A=A.merge(T.append("line").attr("stroke","currentColor").attr(s+"2",f*o)),S=S.merge(T.append("text").attr("fill","currentColor").attr(s,f*g).attr("dy",t===xt?"0em":t===Mt?"0.71em":"0.32em")),h!==m&&(x=x.transition(h),w=w.transition(h),A=A.transition(h),S=S.transition(h),M=M.transition(h).attr("opacity",At).attr("transform",(function(t){return isFinite(t=b(t))?l(t+c):this.getAttribute("transform")})),T.attr("opacity",At).attr("transform",(function(t){var n=this.parentNode.__axis;return l((n&&isFinite(n=n(t))?n:b(t))+c)}))),M.remove(),x.attr("d",t===Tt||t===wt?a?"M"+f*a+","+v+"H"+c+"V"+_+"H"+f*a:"M"+c+","+v+"V"+_:a?"M"+v+","+f*a+"V"+c+"H"+_+"V"+f*a:"M"+v+","+c+"H"+_),w.attr("opacity",1).attr("transform",(function(t){return l(b(t)+c)})),A.attr(s+"2",f*o),S.attr(s,f*g).text(p),m.filter(Ct).attr("fill","none").attr("font-size",10).attr("font-family","sans-serif").attr("text-anchor",t===wt?"start":t===Tt?"end":"middle"),m.each((function(){this.__axis=b}))}return h.scale=function(t){return arguments.length?(n=t,h):n},h.ticks=function(){return e=Array.from(arguments),h},h.tickArguments=function(t){return arguments.length?(e=null==t?[]:Array.from(t),h):e.slice()},h.tickValues=function(t){return arguments.length?(r=null==t?null:Array.from(t),h):r&&r.slice()},h.tickFormat=function(t){return arguments.length?(i=t,h):i},h.tickSize=function(t){return arguments.length?(o=a=+t,h):o},h.tickSizeInner=function(t){return arguments.length?(o=+t,h):o},h.tickSizeOuter=function(t){return arguments.length?(a=+t,h):a},h.tickPadding=function(t){return arguments.length?(u=+t,h):u},h.offset=function(t){return arguments.length?(c=+t,h):c},h}var zt={value:()=>{}};function $t(){for(var t,n=0,e=arguments.length,r={};n=0&&(n=t.slice(e+1),t=t.slice(0,e)),t&&!r.hasOwnProperty(t))throw new Error("unknown type: "+t);return{type:t,name:n}}))),a=-1,u=o.length;if(!(arguments.length<2)){if(null!=n&&"function"!=typeof n)throw new Error("invalid callback: "+n);for(;++a0)for(var e,r,i=new Array(e),o=0;o=0&&"xmlns"!==(n=t.slice(0,e))&&(t=t.slice(e+1)),Ut.hasOwnProperty(n)?{space:Ut[n],local:t}:t}function Ot(t){return function(){var n=this.ownerDocument,e=this.namespaceURI;return e===qt&&n.documentElement.namespaceURI===qt?n.createElement(t):n.createElementNS(e,t)}}function Bt(t){return function(){return this.ownerDocument.createElementNS(t.space,t.local)}}function Yt(t){var n=It(t);return(n.local?Bt:Ot)(n)}function Lt(){}function jt(t){return null==t?Lt:function(){return this.querySelector(t)}}function Ht(t){return null==t?[]:Array.isArray(t)?t:Array.from(t)}function Xt(){return[]}function Gt(t){return null==t?Xt:function(){return this.querySelectorAll(t)}}function Vt(t){return function(){return this.matches(t)}}function Wt(t){return function(n){return n.matches(t)}}var Zt=Array.prototype.find;function Kt(){return this.firstElementChild}var Qt=Array.prototype.filter;function Jt(){return Array.from(this.children)}function tn(t){return new Array(t.length)}function nn(t,n){this.ownerDocument=t.ownerDocument,this.namespaceURI=t.namespaceURI,this._next=null,this._parent=t,this.__data__=n}function en(t,n,e,r,i,o){for(var a,u=0,c=n.length,f=o.length;un?1:t>=n?0:NaN}function cn(t){return function(){this.removeAttribute(t)}}function fn(t){return function(){this.removeAttributeNS(t.space,t.local)}}function sn(t,n){return function(){this.setAttribute(t,n)}}function ln(t,n){return function(){this.setAttributeNS(t.space,t.local,n)}}function hn(t,n){return function(){var e=n.apply(this,arguments);null==e?this.removeAttribute(t):this.setAttribute(t,e)}}function dn(t,n){return function(){var e=n.apply(this,arguments);null==e?this.removeAttributeNS(t.space,t.local):this.setAttributeNS(t.space,t.local,e)}}function pn(t){return t.ownerDocument&&t.ownerDocument.defaultView||t.document&&t||t.defaultView}function gn(t){return function(){this.style.removeProperty(t)}}function yn(t,n,e){return function(){this.style.setProperty(t,n,e)}}function vn(t,n,e){return function(){var r=n.apply(this,arguments);null==r?this.style.removeProperty(t):this.style.setProperty(t,r,e)}}function _n(t,n){return t.style.getPropertyValue(n)||pn(t).getComputedStyle(t,null).getPropertyValue(n)}function bn(t){return function(){delete this[t]}}function mn(t,n){return function(){this[t]=n}}function xn(t,n){return function(){var e=n.apply(this,arguments);null==e?delete this[t]:this[t]=e}}function wn(t){return t.trim().split(/^|\s+/)}function Mn(t){return t.classList||new Tn(t)}function Tn(t){this._node=t,this._names=wn(t.getAttribute("class")||"")}function An(t,n){for(var e=Mn(t),r=-1,i=n.length;++r=0&&(this._names.splice(n,1),this._node.setAttribute("class",this._names.join(" ")))},contains:function(t){return this._names.indexOf(t)>=0}};var Gn=[null];function Vn(t,n){this._groups=t,this._parents=n}function Wn(){return new Vn([[document.documentElement]],Gn)}function Zn(t){return"string"==typeof t?new Vn([[document.querySelector(t)]],[document.documentElement]):new Vn([[t]],Gn)}Vn.prototype=Wn.prototype={constructor:Vn,select:function(t){"function"!=typeof t&&(t=jt(t));for(var n=this._groups,e=n.length,r=new Array(e),i=0;i=m&&(m=b+1);!(_=y[m])&&++m=0;)(r=i[o])&&(a&&4^r.compareDocumentPosition(a)&&a.parentNode.insertBefore(r,a),a=r);return this},sort:function(t){function n(n,e){return n&&e?t(n.__data__,e.__data__):!n-!e}t||(t=un);for(var e=this._groups,r=e.length,i=new Array(r),o=0;o1?this.each((null==n?gn:"function"==typeof n?vn:yn)(t,n,null==e?"":e)):_n(this.node(),t)},property:function(t,n){return arguments.length>1?this.each((null==n?bn:"function"==typeof n?xn:mn)(t,n)):this.node()[t]},classed:function(t,n){var e=wn(t+"");if(arguments.length<2){for(var r=Mn(this.node()),i=-1,o=e.length;++i=0&&(n=t.slice(e+1),t=t.slice(0,e)),{type:t,name:n}}))}(t+""),a=o.length;if(!(arguments.length<2)){for(u=n?Ln:Yn,r=0;r()=>t;function fe(t,{sourceEvent:n,subject:e,target:r,identifier:i,active:o,x:a,y:u,dx:c,dy:f,dispatch:s}){Object.defineProperties(this,{type:{value:t,enumerable:!0,configurable:!0},sourceEvent:{value:n,enumerable:!0,configurable:!0},subject:{value:e,enumerable:!0,configurable:!0},target:{value:r,enumerable:!0,configurable:!0},identifier:{value:i,enumerable:!0,configurable:!0},active:{value:o,enumerable:!0,configurable:!0},x:{value:a,enumerable:!0,configurable:!0},y:{value:u,enumerable:!0,configurable:!0},dx:{value:c,enumerable:!0,configurable:!0},dy:{value:f,enumerable:!0,configurable:!0},_:{value:s}})}function se(t){return!t.ctrlKey&&!t.button}function le(){return this.parentNode}function he(t,n){return null==n?{x:t.x,y:t.y}:n}function de(){return navigator.maxTouchPoints||"ontouchstart"in this}function pe(t,n,e){t.prototype=n.prototype=e,e.constructor=t}function ge(t,n){var e=Object.create(t.prototype);for(var r in n)e[r]=n[r];return e}function ye(){}fe.prototype.on=function(){var t=this._.on.apply(this._,arguments);return t===this._?this:t};var ve=.7,_e=1/ve,be="\\s*([+-]?\\d+)\\s*",me="\\s*([+-]?(?:\\d*\\.)?\\d+(?:[eE][+-]?\\d+)?)\\s*",xe="\\s*([+-]?(?:\\d*\\.)?\\d+(?:[eE][+-]?\\d+)?)%\\s*",we=/^#([0-9a-f]{3,8})$/,Me=new RegExp(`^rgb\\(${be},${be},${be}\\)$`),Te=new RegExp(`^rgb\\(${xe},${xe},${xe}\\)$`),Ae=new RegExp(`^rgba\\(${be},${be},${be},${me}\\)$`),Se=new RegExp(`^rgba\\(${xe},${xe},${xe},${me}\\)$`),Ee=new RegExp(`^hsl\\(${me},${xe},${xe}\\)$`),Ne=new RegExp(`^hsla\\(${me},${xe},${xe},${me}\\)$`),ke={aliceblue:15792383,antiquewhite:16444375,aqua:65535,aquamarine:8388564,azure:15794175,beige:16119260,bisque:16770244,black:0,blanchedalmond:16772045,blue:255,blueviolet:9055202,brown:10824234,burlywood:14596231,cadetblue:6266528,chartreuse:8388352,chocolate:13789470,coral:16744272,cornflowerblue:6591981,cornsilk:16775388,crimson:14423100,cyan:65535,darkblue:139,darkcyan:35723,darkgoldenrod:12092939,darkgray:11119017,darkgreen:25600,darkgrey:11119017,darkkhaki:12433259,darkmagenta:9109643,darkolivegreen:5597999,darkorange:16747520,darkorchid:10040012,darkred:9109504,darksalmon:15308410,darkseagreen:9419919,darkslateblue:4734347,darkslategray:3100495,darkslategrey:3100495,darkturquoise:52945,darkviolet:9699539,deeppink:16716947,deepskyblue:49151,dimgray:6908265,dimgrey:6908265,dodgerblue:2003199,firebrick:11674146,floralwhite:16775920,forestgreen:2263842,fuchsia:16711935,gainsboro:14474460,ghostwhite:16316671,gold:16766720,goldenrod:14329120,gray:8421504,green:32768,greenyellow:11403055,grey:8421504,honeydew:15794160,hotpink:16738740,indianred:13458524,indigo:4915330,ivory:16777200,khaki:15787660,lavender:15132410,lavenderblush:16773365,lawngreen:8190976,lemonchiffon:16775885,lightblue:11393254,lightcoral:15761536,lightcyan:14745599,lightgoldenrodyellow:16448210,lightgray:13882323,lightgreen:9498256,lightgrey:13882323,lightpink:16758465,lightsalmon:16752762,lightseagreen:2142890,lightskyblue:8900346,lightslategray:7833753,lightslategrey:7833753,lightsteelblue:11584734,lightyellow:16777184,lime:65280,limegreen:3329330,linen:16445670,magenta:16711935,maroon:8388608,mediumaquamarine:6737322,mediumblue:205,mediumorchid:12211667,mediumpurple:9662683,mediumseagreen:3978097,mediumslateblue:8087790,mediumspringgreen:64154,mediumturquoise:4772300,mediumvioletred:13047173,midnightblue:1644912,mintcream:16121850,mistyrose:16770273,moccasin:16770229,navajowhite:16768685,navy:128,oldlace:16643558,olive:8421376,olivedrab:7048739,orange:16753920,orangered:16729344,orchid:14315734,palegoldenrod:15657130,palegreen:10025880,paleturquoise:11529966,palevioletred:14381203,papayawhip:16773077,peachpuff:16767673,peru:13468991,pink:16761035,plum:14524637,powderblue:11591910,purple:8388736,rebeccapurple:6697881,red:16711680,rosybrown:12357519,royalblue:4286945,saddlebrown:9127187,salmon:16416882,sandybrown:16032864,seagreen:3050327,seashell:16774638,sienna:10506797,silver:12632256,skyblue:8900331,slateblue:6970061,slategray:7372944,slategrey:7372944,snow:16775930,springgreen:65407,steelblue:4620980,tan:13808780,teal:32896,thistle:14204888,tomato:16737095,turquoise:4251856,violet:15631086,wheat:16113331,white:16777215,whitesmoke:16119285,yellow:16776960,yellowgreen:10145074};function Ce(){return this.rgb().formatHex()}function Pe(){return this.rgb().formatRgb()}function ze(t){var n,e;return t=(t+"").trim().toLowerCase(),(n=we.exec(t))?(e=n[1].length,n=parseInt(n[1],16),6===e?$e(n):3===e?new qe(n>>8&15|n>>4&240,n>>4&15|240&n,(15&n)<<4|15&n,1):8===e?De(n>>24&255,n>>16&255,n>>8&255,(255&n)/255):4===e?De(n>>12&15|n>>8&240,n>>8&15|n>>4&240,n>>4&15|240&n,((15&n)<<4|15&n)/255):null):(n=Me.exec(t))?new qe(n[1],n[2],n[3],1):(n=Te.exec(t))?new qe(255*n[1]/100,255*n[2]/100,255*n[3]/100,1):(n=Ae.exec(t))?De(n[1],n[2],n[3],n[4]):(n=Se.exec(t))?De(255*n[1]/100,255*n[2]/100,255*n[3]/100,n[4]):(n=Ee.exec(t))?Le(n[1],n[2]/100,n[3]/100,1):(n=Ne.exec(t))?Le(n[1],n[2]/100,n[3]/100,n[4]):ke.hasOwnProperty(t)?$e(ke[t]):"transparent"===t?new qe(NaN,NaN,NaN,0):null}function $e(t){return new qe(t>>16&255,t>>8&255,255&t,1)}function De(t,n,e,r){return r<=0&&(t=n=e=NaN),new qe(t,n,e,r)}function Re(t){return t instanceof ye||(t=ze(t)),t?new qe((t=t.rgb()).r,t.g,t.b,t.opacity):new qe}function Fe(t,n,e,r){return 1===arguments.length?Re(t):new qe(t,n,e,null==r?1:r)}function qe(t,n,e,r){this.r=+t,this.g=+n,this.b=+e,this.opacity=+r}function Ue(){return`#${Ye(this.r)}${Ye(this.g)}${Ye(this.b)}`}function Ie(){const t=Oe(this.opacity);return`${1===t?"rgb(":"rgba("}${Be(this.r)}, ${Be(this.g)}, ${Be(this.b)}${1===t?")":`, ${t})`}`}function Oe(t){return isNaN(t)?1:Math.max(0,Math.min(1,t))}function Be(t){return Math.max(0,Math.min(255,Math.round(t)||0))}function Ye(t){return((t=Be(t))<16?"0":"")+t.toString(16)}function Le(t,n,e,r){return r<=0?t=n=e=NaN:e<=0||e>=1?t=n=NaN:n<=0&&(t=NaN),new Xe(t,n,e,r)}function je(t){if(t instanceof Xe)return new Xe(t.h,t.s,t.l,t.opacity);if(t instanceof ye||(t=ze(t)),!t)return new Xe;if(t instanceof Xe)return t;var n=(t=t.rgb()).r/255,e=t.g/255,r=t.b/255,i=Math.min(n,e,r),o=Math.max(n,e,r),a=NaN,u=o-i,c=(o+i)/2;return u?(a=n===o?(e-r)/u+6*(e0&&c<1?0:a,new Xe(a,u,c,t.opacity)}function He(t,n,e,r){return 1===arguments.length?je(t):new Xe(t,n,e,null==r?1:r)}function Xe(t,n,e,r){this.h=+t,this.s=+n,this.l=+e,this.opacity=+r}function Ge(t){return(t=(t||0)%360)<0?t+360:t}function Ve(t){return Math.max(0,Math.min(1,t||0))}function We(t,n,e){return 255*(t<60?n+(e-n)*t/60:t<180?e:t<240?n+(e-n)*(240-t)/60:n)}pe(ye,ze,{copy(t){return Object.assign(new this.constructor,this,t)},displayable(){return this.rgb().displayable()},hex:Ce,formatHex:Ce,formatHex8:function(){return this.rgb().formatHex8()},formatHsl:function(){return je(this).formatHsl()},formatRgb:Pe,toString:Pe}),pe(qe,Fe,ge(ye,{brighter(t){return t=null==t?_e:Math.pow(_e,t),new qe(this.r*t,this.g*t,this.b*t,this.opacity)},darker(t){return t=null==t?ve:Math.pow(ve,t),new qe(this.r*t,this.g*t,this.b*t,this.opacity)},rgb(){return this},clamp(){return new qe(Be(this.r),Be(this.g),Be(this.b),Oe(this.opacity))},displayable(){return-.5<=this.r&&this.r<255.5&&-.5<=this.g&&this.g<255.5&&-.5<=this.b&&this.b<255.5&&0<=this.opacity&&this.opacity<=1},hex:Ue,formatHex:Ue,formatHex8:function(){return`#${Ye(this.r)}${Ye(this.g)}${Ye(this.b)}${Ye(255*(isNaN(this.opacity)?1:this.opacity))}`},formatRgb:Ie,toString:Ie})),pe(Xe,He,ge(ye,{brighter(t){return t=null==t?_e:Math.pow(_e,t),new Xe(this.h,this.s,this.l*t,this.opacity)},darker(t){return t=null==t?ve:Math.pow(ve,t),new Xe(this.h,this.s,this.l*t,this.opacity)},rgb(){var t=this.h%360+360*(this.h<0),n=isNaN(t)||isNaN(this.s)?0:this.s,e=this.l,r=e+(e<.5?e:1-e)*n,i=2*e-r;return new qe(We(t>=240?t-240:t+120,i,r),We(t,i,r),We(t<120?t+240:t-120,i,r),this.opacity)},clamp(){return new Xe(Ge(this.h),Ve(this.s),Ve(this.l),Oe(this.opacity))},displayable(){return(0<=this.s&&this.s<=1||isNaN(this.s))&&0<=this.l&&this.l<=1&&0<=this.opacity&&this.opacity<=1},formatHsl(){const t=Oe(this.opacity);return`${1===t?"hsl(":"hsla("}${Ge(this.h)}, ${100*Ve(this.s)}%, ${100*Ve(this.l)}%${1===t?")":`, ${t})`}`}}));const Ze=Math.PI/180,Ke=180/Math.PI,Qe=.96422,Je=1,tr=.82521,nr=4/29,er=6/29,rr=3*er*er,ir=er*er*er;function or(t){if(t instanceof ur)return new ur(t.l,t.a,t.b,t.opacity);if(t instanceof pr)return gr(t);t instanceof qe||(t=Re(t));var n,e,r=lr(t.r),i=lr(t.g),o=lr(t.b),a=cr((.2225045*r+.7168786*i+.0606169*o)/Je);return r===i&&i===o?n=e=a:(n=cr((.4360747*r+.3850649*i+.1430804*o)/Qe),e=cr((.0139322*r+.0971045*i+.7141733*o)/tr)),new ur(116*a-16,500*(n-a),200*(a-e),t.opacity)}function ar(t,n,e,r){return 1===arguments.length?or(t):new ur(t,n,e,null==r?1:r)}function ur(t,n,e,r){this.l=+t,this.a=+n,this.b=+e,this.opacity=+r}function cr(t){return t>ir?Math.pow(t,1/3):t/rr+nr}function fr(t){return t>er?t*t*t:rr*(t-nr)}function sr(t){return 255*(t<=.0031308?12.92*t:1.055*Math.pow(t,1/2.4)-.055)}function lr(t){return(t/=255)<=.04045?t/12.92:Math.pow((t+.055)/1.055,2.4)}function hr(t){if(t instanceof pr)return new pr(t.h,t.c,t.l,t.opacity);if(t instanceof ur||(t=or(t)),0===t.a&&0===t.b)return new pr(NaN,0=1?(e=1,n-1):Math.floor(e*n),i=t[r],o=t[r+1],a=r>0?t[r-1]:2*i-o,u=r()=>t;function Cr(t,n){return function(e){return t+e*n}}function Pr(t,n){var e=n-t;return e?Cr(t,e>180||e<-180?e-360*Math.round(e/360):e):kr(isNaN(t)?n:t)}function zr(t){return 1==(t=+t)?$r:function(n,e){return e-n?function(t,n,e){return t=Math.pow(t,e),n=Math.pow(n,e)-t,e=1/e,function(r){return Math.pow(t+r*n,e)}}(n,e,t):kr(isNaN(n)?e:n)}}function $r(t,n){var e=n-t;return e?Cr(t,e):kr(isNaN(t)?n:t)}var Dr=function t(n){var e=zr(n);function r(t,n){var r=e((t=Fe(t)).r,(n=Fe(n)).r),i=e(t.g,n.g),o=e(t.b,n.b),a=$r(t.opacity,n.opacity);return function(n){return t.r=r(n),t.g=i(n),t.b=o(n),t.opacity=a(n),t+""}}return r.gamma=t,r}(1);function Rr(t){return function(n){var e,r,i=n.length,o=new Array(i),a=new Array(i),u=new Array(i);for(e=0;eo&&(i=n.slice(o,i),u[a]?u[a]+=i:u[++a]=i),(e=e[0])===(r=r[0])?u[a]?u[a]+=r:u[++a]=r:(u[++a]=null,c.push({i:a,x:Yr(e,r)})),o=Hr.lastIndex;return o180?n+=360:n-t>180&&(t+=360),o.push({i:e.push(i(e)+"rotate(",null,r)-2,x:Yr(t,n)})):n&&e.push(i(e)+"rotate("+n+r)}(o.rotate,a.rotate,u,c),function(t,n,e,o){t!==n?o.push({i:e.push(i(e)+"skewX(",null,r)-2,x:Yr(t,n)}):n&&e.push(i(e)+"skewX("+n+r)}(o.skewX,a.skewX,u,c),function(t,n,e,r,o,a){if(t!==e||n!==r){var u=o.push(i(o)+"scale(",null,",",null,")");a.push({i:u-4,x:Yr(t,e)},{i:u-2,x:Yr(n,r)})}else 1===e&&1===r||o.push(i(o)+"scale("+e+","+r+")")}(o.scaleX,o.scaleY,a.scaleX,a.scaleY,u,c),o=a=null,function(t){for(var n,e=-1,r=c.length;++e=0&&n._call.call(void 0,t),n=n._next;--yi}function Ci(){xi=(mi=Mi.now())+wi,yi=vi=0;try{ki()}finally{yi=0,function(){var t,n,e=pi,r=1/0;for(;e;)e._call?(r>e._time&&(r=e._time),t=e,e=e._next):(n=e._next,e._next=null,e=t?t._next=n:pi=n);gi=t,zi(r)}(),xi=0}}function Pi(){var t=Mi.now(),n=t-mi;n>bi&&(wi-=n,mi=t)}function zi(t){yi||(vi&&(vi=clearTimeout(vi)),t-xi>24?(t<1/0&&(vi=setTimeout(Ci,t-Mi.now()-wi)),_i&&(_i=clearInterval(_i))):(_i||(mi=Mi.now(),_i=setInterval(Pi,bi)),yi=1,Ti(Ci)))}function $i(t,n,e){var r=new Ei;return n=null==n?0:+n,r.restart((e=>{r.stop(),t(e+n)}),n,e),r}Ei.prototype=Ni.prototype={constructor:Ei,restart:function(t,n,e){if("function"!=typeof t)throw new TypeError("callback is not a function");e=(null==e?Ai():+e)+(null==n?0:+n),this._next||gi===this||(gi?gi._next=this:pi=this,gi=this),this._call=t,this._time=e,zi()},stop:function(){this._call&&(this._call=null,this._time=1/0,zi())}};var Di=$t("start","end","cancel","interrupt"),Ri=[],Fi=0,qi=1,Ui=2,Ii=3,Oi=4,Bi=5,Yi=6;function Li(t,n,e,r,i,o){var a=t.__transition;if(a){if(e in a)return}else t.__transition={};!function(t,n,e){var r,i=t.__transition;function o(t){e.state=qi,e.timer.restart(a,e.delay,e.time),e.delay<=t&&a(t-e.delay)}function a(o){var f,s,l,h;if(e.state!==qi)return c();for(f in i)if((h=i[f]).name===e.name){if(h.state===Ii)return $i(a);h.state===Oi?(h.state=Yi,h.timer.stop(),h.on.call("interrupt",t,t.__data__,h.index,h.group),delete i[f]):+fFi)throw new Error("too late; already scheduled");return e}function Hi(t,n){var e=Xi(t,n);if(e.state>Ii)throw new Error("too late; already running");return e}function Xi(t,n){var e=t.__transition;if(!e||!(e=e[n]))throw new Error("transition not found");return e}function Gi(t,n){var e,r,i,o=t.__transition,a=!0;if(o){for(i in n=null==n?null:n+"",o)(e=o[i]).name===n?(r=e.state>Ui&&e.state=0&&(t=t.slice(0,n)),!t||"start"===t}))}(n)?ji:Hi;return function(){var a=o(this,t),u=a.on;u!==r&&(i=(r=u).copy()).on(n,e),a.on=i}}(e,t,n))},attr:function(t,n){var e=It(t),r="transform"===e?ni:Ki;return this.attrTween(t,"function"==typeof n?(e.local?ro:eo)(e,r,Zi(this,"attr."+t,n)):null==n?(e.local?Ji:Qi)(e):(e.local?no:to)(e,r,n))},attrTween:function(t,n){var e="attr."+t;if(arguments.length<2)return(e=this.tween(e))&&e._value;if(null==n)return this.tween(e,null);if("function"!=typeof n)throw new Error;var r=It(t);return this.tween(e,(r.local?io:oo)(r,n))},style:function(t,n,e){var r="transform"==(t+="")?ti:Ki;return null==n?this.styleTween(t,function(t,n){var e,r,i;return function(){var o=_n(this,t),a=(this.style.removeProperty(t),_n(this,t));return o===a?null:o===e&&a===r?i:i=n(e=o,r=a)}}(t,r)).on("end.style."+t,lo(t)):"function"==typeof n?this.styleTween(t,function(t,n,e){var r,i,o;return function(){var a=_n(this,t),u=e(this),c=u+"";return null==u&&(this.style.removeProperty(t),c=u=_n(this,t)),a===c?null:a===r&&c===i?o:(i=c,o=n(r=a,u))}}(t,r,Zi(this,"style."+t,n))).each(function(t,n){var e,r,i,o,a="style."+n,u="end."+a;return function(){var c=Hi(this,t),f=c.on,s=null==c.value[a]?o||(o=lo(n)):void 0;f===e&&i===s||(r=(e=f).copy()).on(u,i=s),c.on=r}}(this._id,t)):this.styleTween(t,function(t,n,e){var r,i,o=e+"";return function(){var a=_n(this,t);return a===o?null:a===r?i:i=n(r=a,e)}}(t,r,n),e).on("end.style."+t,null)},styleTween:function(t,n,e){var r="style."+(t+="");if(arguments.length<2)return(r=this.tween(r))&&r._value;if(null==n)return this.tween(r,null);if("function"!=typeof n)throw new Error;return this.tween(r,function(t,n,e){var r,i;function o(){var o=n.apply(this,arguments);return o!==i&&(r=(i=o)&&function(t,n,e){return function(r){this.style.setProperty(t,n.call(this,r),e)}}(t,o,e)),r}return o._value=n,o}(t,n,null==e?"":e))},text:function(t){return this.tween("text","function"==typeof t?function(t){return function(){var n=t(this);this.textContent=null==n?"":n}}(Zi(this,"text",t)):function(t){return function(){this.textContent=t}}(null==t?"":t+""))},textTween:function(t){var n="text";if(arguments.length<1)return(n=this.tween(n))&&n._value;if(null==t)return this.tween(n,null);if("function"!=typeof t)throw new Error;return this.tween(n,function(t){var n,e;function r(){var r=t.apply(this,arguments);return r!==e&&(n=(e=r)&&function(t){return function(n){this.textContent=t.call(this,n)}}(r)),n}return r._value=t,r}(t))},remove:function(){return this.on("end.remove",function(t){return function(){var n=this.parentNode;for(var e in this.__transition)if(+e!==t)return;n&&n.removeChild(this)}}(this._id))},tween:function(t,n){var e=this._id;if(t+="",arguments.length<2){for(var r,i=Xi(this.node(),e).tween,o=0,a=i.length;o()=>t;function Qo(t,{sourceEvent:n,target:e,selection:r,mode:i,dispatch:o}){Object.defineProperties(this,{type:{value:t,enumerable:!0,configurable:!0},sourceEvent:{value:n,enumerable:!0,configurable:!0},target:{value:e,enumerable:!0,configurable:!0},selection:{value:r,enumerable:!0,configurable:!0},mode:{value:i,enumerable:!0,configurable:!0},_:{value:o}})}function Jo(t){t.preventDefault(),t.stopImmediatePropagation()}var ta={name:"drag"},na={name:"space"},ea={name:"handle"},ra={name:"center"};const{abs:ia,max:oa,min:aa}=Math;function ua(t){return[+t[0],+t[1]]}function ca(t){return[ua(t[0]),ua(t[1])]}var fa={name:"x",handles:["w","e"].map(va),input:function(t,n){return null==t?null:[[+t[0],n[0][1]],[+t[1],n[1][1]]]},output:function(t){return t&&[t[0][0],t[1][0]]}},sa={name:"y",handles:["n","s"].map(va),input:function(t,n){return null==t?null:[[n[0][0],+t[0]],[n[1][0],+t[1]]]},output:function(t){return t&&[t[0][1],t[1][1]]}},la={name:"xy",handles:["n","w","e","s","nw","ne","sw","se"].map(va),input:function(t){return null==t?null:ca(t)},output:function(t){return t}},ha={overlay:"crosshair",selection:"move",n:"ns-resize",e:"ew-resize",s:"ns-resize",w:"ew-resize",nw:"nwse-resize",ne:"nesw-resize",se:"nwse-resize",sw:"nesw-resize"},da={e:"w",w:"e",nw:"ne",ne:"nw",se:"sw",sw:"se"},pa={n:"s",s:"n",nw:"sw",ne:"se",se:"ne",sw:"nw"},ga={overlay:1,selection:1,n:null,e:1,s:null,w:-1,nw:-1,ne:1,se:1,sw:-1},ya={overlay:1,selection:1,n:-1,e:null,s:1,w:null,nw:-1,ne:-1,se:1,sw:1};function va(t){return{type:t}}function _a(t){return!t.ctrlKey&&!t.button}function ba(){var t=this.ownerSVGElement||this;return t.hasAttribute("viewBox")?[[(t=t.viewBox.baseVal).x,t.y],[t.x+t.width,t.y+t.height]]:[[0,0],[t.width.baseVal.value,t.height.baseVal.value]]}function ma(){return navigator.maxTouchPoints||"ontouchstart"in this}function xa(t){for(;!t.__brush;)if(!(t=t.parentNode))return;return t.__brush}function wa(t){var n,e=ba,r=_a,i=ma,o=!0,a=$t("start","brush","end"),u=6;function c(n){var e=n.property("__brush",g).selectAll(".overlay").data([va("overlay")]);e.enter().append("rect").attr("class","overlay").attr("pointer-events","all").attr("cursor",ha.overlay).merge(e).each((function(){var t=xa(this).extent;Zn(this).attr("x",t[0][0]).attr("y",t[0][1]).attr("width",t[1][0]-t[0][0]).attr("height",t[1][1]-t[0][1])})),n.selectAll(".selection").data([va("selection")]).enter().append("rect").attr("class","selection").attr("cursor",ha.selection).attr("fill","#777").attr("fill-opacity",.3).attr("stroke","#fff").attr("shape-rendering","crispEdges");var r=n.selectAll(".handle").data(t.handles,(function(t){return t.type}));r.exit().remove(),r.enter().append("rect").attr("class",(function(t){return"handle handle--"+t.type})).attr("cursor",(function(t){return ha[t.type]})),n.each(f).attr("fill","none").attr("pointer-events","all").on("mousedown.brush",h).filter(i).on("touchstart.brush",h).on("touchmove.brush",d).on("touchend.brush touchcancel.brush",p).style("touch-action","none").style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}function f(){var t=Zn(this),n=xa(this).selection;n?(t.selectAll(".selection").style("display",null).attr("x",n[0][0]).attr("y",n[0][1]).attr("width",n[1][0]-n[0][0]).attr("height",n[1][1]-n[0][1]),t.selectAll(".handle").style("display",null).attr("x",(function(t){return"e"===t.type[t.type.length-1]?n[1][0]-u/2:n[0][0]-u/2})).attr("y",(function(t){return"s"===t.type[0]?n[1][1]-u/2:n[0][1]-u/2})).attr("width",(function(t){return"n"===t.type||"s"===t.type?n[1][0]-n[0][0]+u:u})).attr("height",(function(t){return"e"===t.type||"w"===t.type?n[1][1]-n[0][1]+u:u}))):t.selectAll(".selection,.handle").style("display","none").attr("x",null).attr("y",null).attr("width",null).attr("height",null)}function s(t,n,e){var r=t.__brush.emitter;return!r||e&&r.clean?new l(t,n,e):r}function l(t,n,e){this.that=t,this.args=n,this.state=t.__brush,this.active=0,this.clean=e}function h(e){if((!n||e.touches)&&r.apply(this,arguments)){var i,a,u,c,l,h,d,p,g,y,v,_=this,b=e.target.__data__.type,m="selection"===(o&&e.metaKey?b="overlay":b)?ta:o&&e.altKey?ra:ea,x=t===sa?null:ga[b],w=t===fa?null:ya[b],M=xa(_),T=M.extent,A=M.selection,S=T[0][0],E=T[0][1],N=T[1][0],k=T[1][1],C=0,P=0,z=x&&w&&o&&e.shiftKey,$=Array.from(e.touches||[e],(t=>{const n=t.identifier;return(t=ne(t,_)).point0=t.slice(),t.identifier=n,t}));Gi(_);var D=s(_,arguments,!0).beforestart();if("overlay"===b){A&&(g=!0);const n=[$[0],$[1]||$[0]];M.selection=A=[[i=t===sa?S:aa(n[0][0],n[1][0]),u=t===fa?E:aa(n[0][1],n[1][1])],[l=t===sa?N:oa(n[0][0],n[1][0]),d=t===fa?k:oa(n[0][1],n[1][1])]],$.length>1&&I(e)}else i=A[0][0],u=A[0][1],l=A[1][0],d=A[1][1];a=i,c=u,h=l,p=d;var R=Zn(_).attr("pointer-events","none"),F=R.selectAll(".overlay").attr("cursor",ha[b]);if(e.touches)D.moved=U,D.ended=O;else{var q=Zn(e.view).on("mousemove.brush",U,!0).on("mouseup.brush",O,!0);o&&q.on("keydown.brush",(function(t){switch(t.keyCode){case 16:z=x&&w;break;case 18:m===ea&&(x&&(l=h-C*x,i=a+C*x),w&&(d=p-P*w,u=c+P*w),m=ra,I(t));break;case 32:m!==ea&&m!==ra||(x<0?l=h-C:x>0&&(i=a-C),w<0?d=p-P:w>0&&(u=c-P),m=na,F.attr("cursor",ha.selection),I(t));break;default:return}Jo(t)}),!0).on("keyup.brush",(function(t){switch(t.keyCode){case 16:z&&(y=v=z=!1,I(t));break;case 18:m===ra&&(x<0?l=h:x>0&&(i=a),w<0?d=p:w>0&&(u=c),m=ea,I(t));break;case 32:m===na&&(t.altKey?(x&&(l=h-C*x,i=a+C*x),w&&(d=p-P*w,u=c+P*w),m=ra):(x<0?l=h:x>0&&(i=a),w<0?d=p:w>0&&(u=c),m=ea),F.attr("cursor",ha[b]),I(t));break;default:return}Jo(t)}),!0),ae(e.view)}f.call(_),D.start(e,m.name)}function U(t){for(const n of t.changedTouches||[t])for(const t of $)t.identifier===n.identifier&&(t.cur=ne(n,_));if(z&&!y&&!v&&1===$.length){const t=$[0];ia(t.cur[0]-t[0])>ia(t.cur[1]-t[1])?v=!0:y=!0}for(const t of $)t.cur&&(t[0]=t.cur[0],t[1]=t.cur[1]);g=!0,Jo(t),I(t)}function I(t){const n=$[0],e=n.point0;var r;switch(C=n[0]-e[0],P=n[1]-e[1],m){case na:case ta:x&&(C=oa(S-i,aa(N-l,C)),a=i+C,h=l+C),w&&(P=oa(E-u,aa(k-d,P)),c=u+P,p=d+P);break;case ea:$[1]?(x&&(a=oa(S,aa(N,$[0][0])),h=oa(S,aa(N,$[1][0])),x=1),w&&(c=oa(E,aa(k,$[0][1])),p=oa(E,aa(k,$[1][1])),w=1)):(x<0?(C=oa(S-i,aa(N-i,C)),a=i+C,h=l):x>0&&(C=oa(S-l,aa(N-l,C)),a=i,h=l+C),w<0?(P=oa(E-u,aa(k-u,P)),c=u+P,p=d):w>0&&(P=oa(E-d,aa(k-d,P)),c=u,p=d+P));break;case ra:x&&(a=oa(S,aa(N,i-C*x)),h=oa(S,aa(N,l+C*x))),w&&(c=oa(E,aa(k,u-P*w)),p=oa(E,aa(k,d+P*w)))}ht+e))}function za(t,n){var e=0,r=null,i=null,o=null;function a(a){var u,c=a.length,f=new Array(c),s=Pa(0,c),l=new Array(c*c),h=new Array(c),d=0;a=Float64Array.from({length:c*c},n?(t,n)=>a[n%c][n/c|0]:(t,n)=>a[n/c|0][n%c]);for(let n=0;nr(f[t],f[n])));for(const e of s){const r=n;if(t){const t=Pa(1+~c,c).filter((t=>t<0?a[~t*c+e]:a[e*c+t]));i&&t.sort(((t,n)=>i(t<0?-a[~t*c+e]:a[e*c+t],n<0?-a[~n*c+e]:a[e*c+n])));for(const r of t)if(r<0){(l[~r*c+e]||(l[~r*c+e]={source:null,target:null})).target={index:e,startAngle:n,endAngle:n+=a[~r*c+e]*d,value:a[~r*c+e]}}else{(l[e*c+r]||(l[e*c+r]={source:null,target:null})).source={index:e,startAngle:n,endAngle:n+=a[e*c+r]*d,value:a[e*c+r]}}h[e]={index:e,startAngle:r,endAngle:n,value:f[e]}}else{const t=Pa(0,c).filter((t=>a[e*c+t]||a[t*c+e]));i&&t.sort(((t,n)=>i(a[e*c+t],a[e*c+n])));for(const r of t){let t;if(e=0))throw new Error(`invalid digits: ${t}`);if(n>15)return qa;const e=10**n;return function(t){this._+=t[0];for(let n=1,r=t.length;nRa)if(Math.abs(s*u-c*f)>Ra&&i){let h=e-o,d=r-a,p=u*u+c*c,g=h*h+d*d,y=Math.sqrt(p),v=Math.sqrt(l),_=i*Math.tan(($a-Math.acos((p+l-g)/(2*y*v)))/2),b=_/v,m=_/y;Math.abs(b-1)>Ra&&this._append`L${t+b*f},${n+b*s}`,this._append`A${i},${i},0,0,${+(s*h>f*d)},${this._x1=t+m*u},${this._y1=n+m*c}`}else this._append`L${this._x1=t},${this._y1=n}`;else;}arc(t,n,e,r,i,o){if(t=+t,n=+n,o=!!o,(e=+e)<0)throw new Error(`negative radius: ${e}`);let a=e*Math.cos(r),u=e*Math.sin(r),c=t+a,f=n+u,s=1^o,l=o?r-i:i-r;null===this._x1?this._append`M${c},${f}`:(Math.abs(this._x1-c)>Ra||Math.abs(this._y1-f)>Ra)&&this._append`L${c},${f}`,e&&(l<0&&(l=l%Da+Da),l>Fa?this._append`A${e},${e},0,1,${s},${t-a},${n-u}A${e},${e},0,1,${s},${this._x1=c},${this._y1=f}`:l>Ra&&this._append`A${e},${e},0,${+(l>=$a)},${s},${this._x1=t+e*Math.cos(i)},${this._y1=n+e*Math.sin(i)}`)}rect(t,n,e,r){this._append`M${this._x0=this._x1=+t},${this._y0=this._y1=+n}h${e=+e}v${+r}h${-e}Z`}toString(){return this._}};function Ia(){return new Ua}Ia.prototype=Ua.prototype;var Oa=Array.prototype.slice;function Ba(t){return function(){return t}}function Ya(t){return t.source}function La(t){return t.target}function ja(t){return t.radius}function Ha(t){return t.startAngle}function Xa(t){return t.endAngle}function Ga(){return 0}function Va(){return 10}function Wa(t){var n=Ya,e=La,r=ja,i=ja,o=Ha,a=Xa,u=Ga,c=null;function f(){var f,s=n.apply(this,arguments),l=e.apply(this,arguments),h=u.apply(this,arguments)/2,d=Oa.call(arguments),p=+r.apply(this,(d[0]=s,d)),g=o.apply(this,d)-Ea,y=a.apply(this,d)-Ea,v=+i.apply(this,(d[0]=l,d)),_=o.apply(this,d)-Ea,b=a.apply(this,d)-Ea;if(c||(c=f=Ia()),h>Ca&&(Ma(y-g)>2*h+Ca?y>g?(g+=h,y-=h):(g-=h,y+=h):g=y=(g+y)/2,Ma(b-_)>2*h+Ca?b>_?(_+=h,b-=h):(_-=h,b+=h):_=b=(_+b)/2),c.moveTo(p*Ta(g),p*Aa(g)),c.arc(0,0,p,g,y),g!==_||y!==b)if(t){var m=v-+t.apply(this,arguments),x=(_+b)/2;c.quadraticCurveTo(0,0,m*Ta(_),m*Aa(_)),c.lineTo(v*Ta(x),v*Aa(x)),c.lineTo(m*Ta(b),m*Aa(b))}else c.quadraticCurveTo(0,0,v*Ta(_),v*Aa(_)),c.arc(0,0,v,_,b);if(c.quadraticCurveTo(0,0,p*Ta(g),p*Aa(g)),c.closePath(),f)return c=null,f+""||null}return t&&(f.headRadius=function(n){return arguments.length?(t="function"==typeof n?n:Ba(+n),f):t}),f.radius=function(t){return arguments.length?(r=i="function"==typeof t?t:Ba(+t),f):r},f.sourceRadius=function(t){return arguments.length?(r="function"==typeof t?t:Ba(+t),f):r},f.targetRadius=function(t){return arguments.length?(i="function"==typeof t?t:Ba(+t),f):i},f.startAngle=function(t){return arguments.length?(o="function"==typeof t?t:Ba(+t),f):o},f.endAngle=function(t){return arguments.length?(a="function"==typeof t?t:Ba(+t),f):a},f.padAngle=function(t){return arguments.length?(u="function"==typeof t?t:Ba(+t),f):u},f.source=function(t){return arguments.length?(n=t,f):n},f.target=function(t){return arguments.length?(e=t,f):e},f.context=function(t){return arguments.length?(c=null==t?null:t,f):c},f}var Za=Array.prototype.slice;function Ka(t,n){return t-n}var Qa=t=>()=>t;function Ja(t,n){for(var e,r=-1,i=n.length;++rr!=d>r&&e<(h-f)*(r-s)/(d-s)+f&&(i=-i)}return i}function nu(t,n,e){var r,i,o,a;return function(t,n,e){return(n[0]-t[0])*(e[1]-t[1])==(e[0]-t[0])*(n[1]-t[1])}(t,n,e)&&(i=t[r=+(t[0]===n[0])],o=e[r],a=n[r],i<=o&&o<=a||a<=o&&o<=i)}function eu(){}var ru=[[],[[[1,1.5],[.5,1]]],[[[1.5,1],[1,1.5]]],[[[1.5,1],[.5,1]]],[[[1,.5],[1.5,1]]],[[[1,1.5],[.5,1]],[[1,.5],[1.5,1]]],[[[1,.5],[1,1.5]]],[[[1,.5],[.5,1]]],[[[.5,1],[1,.5]]],[[[1,1.5],[1,.5]]],[[[.5,1],[1,.5]],[[1.5,1],[1,1.5]]],[[[1.5,1],[1,.5]]],[[[.5,1],[1.5,1]]],[[[1,1.5],[1.5,1]]],[[[.5,1],[1,1.5]]],[]];function iu(){var t=1,n=1,e=K,r=u;function i(t){var n=e(t);if(Array.isArray(n))n=n.slice().sort(Ka);else{const e=M(t,ou);for(n=G(...Z(e[0],e[1],n),n);n[n.length-1]>=e[1];)n.pop();for(;n[1]o(t,n)))}function o(e,i){const o=null==i?NaN:+i;if(isNaN(o))throw new Error(`invalid value: ${i}`);var u=[],c=[];return function(e,r,i){var o,u,c,f,s,l,h=new Array,d=new Array;o=u=-1,f=au(e[0],r),ru[f<<1].forEach(p);for(;++o=r,ru[s<<2].forEach(p);for(;++o0?u.push([t]):c.push(t)})),c.forEach((function(t){for(var n,e=0,r=u.length;e0&&o0&&a=0&&o>=0))throw new Error("invalid size");return t=r,n=o,i},i.thresholds=function(t){return arguments.length?(e="function"==typeof t?t:Array.isArray(t)?Qa(Za.call(t)):Qa(t),i):e},i.smooth=function(t){return arguments.length?(r=t?u:eu,i):r===u},i}function ou(t){return isFinite(t)?t:NaN}function au(t,n){return null!=t&&+t>=n}function uu(t){return null==t||isNaN(t=+t)?-1/0:t}function cu(t,n,e,r){const i=r-n,o=e-n,a=isFinite(i)||isFinite(o)?i/o:Math.sign(i)/Math.sign(o);return isNaN(a)?t:t+a-.5}function fu(t){return t[0]}function su(t){return t[1]}function lu(){return 1}const hu=134217729,du=33306690738754706e-32;function pu(t,n,e,r,i){let o,a,u,c,f=n[0],s=r[0],l=0,h=0;s>f==s>-f?(o=f,f=n[++l]):(o=s,s=r[++h]);let d=0;if(lf==s>-f?(a=f+o,u=o-(a-f),f=n[++l]):(a=s+o,u=o-(a-s),s=r[++h]),o=a,0!==u&&(i[d++]=u);lf==s>-f?(a=o+f,c=a-o,u=o-(a-c)+(f-c),f=n[++l]):(a=o+s,c=a-o,u=o-(a-c)+(s-c),s=r[++h]),o=a,0!==u&&(i[d++]=u);for(;l=33306690738754716e-32*f?c:-function(t,n,e,r,i,o,a){let u,c,f,s,l,h,d,p,g,y,v,_,b,m,x,w,M,T;const A=t-i,S=e-i,E=n-o,N=r-o;m=A*N,h=hu*A,d=h-(h-A),p=A-d,h=hu*N,g=h-(h-N),y=N-g,x=p*y-(m-d*g-p*g-d*y),w=E*S,h=hu*E,d=h-(h-E),p=E-d,h=hu*S,g=h-(h-S),y=S-g,M=p*y-(w-d*g-p*g-d*y),v=x-M,l=x-v,_u[0]=x-(v+l)+(l-M),_=m+v,l=_-m,b=m-(_-l)+(v-l),v=b-w,l=b-v,_u[1]=b-(v+l)+(l-w),T=_+v,l=T-_,_u[2]=_-(T-l)+(v-l),_u[3]=T;let k=function(t,n){let e=n[0];for(let r=1;r=C||-k>=C)return k;if(l=t-A,u=t-(A+l)+(l-i),l=e-S,f=e-(S+l)+(l-i),l=n-E,c=n-(E+l)+(l-o),l=r-N,s=r-(N+l)+(l-o),0===u&&0===c&&0===f&&0===s)return k;if(C=vu*a+du*Math.abs(k),k+=A*s+N*u-(E*f+S*c),k>=C||-k>=C)return k;m=u*N,h=hu*u,d=h-(h-u),p=u-d,h=hu*N,g=h-(h-N),y=N-g,x=p*y-(m-d*g-p*g-d*y),w=c*S,h=hu*c,d=h-(h-c),p=c-d,h=hu*S,g=h-(h-S),y=S-g,M=p*y-(w-d*g-p*g-d*y),v=x-M,l=x-v,wu[0]=x-(v+l)+(l-M),_=m+v,l=_-m,b=m-(_-l)+(v-l),v=b-w,l=b-v,wu[1]=b-(v+l)+(l-w),T=_+v,l=T-_,wu[2]=_-(T-l)+(v-l),wu[3]=T;const P=pu(4,_u,4,wu,bu);m=A*s,h=hu*A,d=h-(h-A),p=A-d,h=hu*s,g=h-(h-s),y=s-g,x=p*y-(m-d*g-p*g-d*y),w=E*f,h=hu*E,d=h-(h-E),p=E-d,h=hu*f,g=h-(h-f),y=f-g,M=p*y-(w-d*g-p*g-d*y),v=x-M,l=x-v,wu[0]=x-(v+l)+(l-M),_=m+v,l=_-m,b=m-(_-l)+(v-l),v=b-w,l=b-v,wu[1]=b-(v+l)+(l-w),T=_+v,l=T-_,wu[2]=_-(T-l)+(v-l),wu[3]=T;const z=pu(P,bu,4,wu,mu);m=u*s,h=hu*u,d=h-(h-u),p=u-d,h=hu*s,g=h-(h-s),y=s-g,x=p*y-(m-d*g-p*g-d*y),w=c*f,h=hu*c,d=h-(h-c),p=c-d,h=hu*f,g=h-(h-f),y=f-g,M=p*y-(w-d*g-p*g-d*y),v=x-M,l=x-v,wu[0]=x-(v+l)+(l-M),_=m+v,l=_-m,b=m-(_-l)+(v-l),v=b-w,l=b-v,wu[1]=b-(v+l)+(l-w),T=_+v,l=T-_,wu[2]=_-(T-l)+(v-l),wu[3]=T;const $=pu(z,mu,4,wu,xu);return xu[$-1]}(t,n,e,r,i,o,f)}const Tu=Math.pow(2,-52),Au=new Uint32Array(512);class Su{static from(t,n=zu,e=$u){const r=t.length,i=new Float64Array(2*r);for(let o=0;o>1;if(n>0&&"number"!=typeof t[0])throw new Error("Expected coords to contain numbers.");this.coords=t;const e=Math.max(2*n-5,0);this._triangles=new Uint32Array(3*e),this._halfedges=new Int32Array(3*e),this._hashSize=Math.ceil(Math.sqrt(n)),this._hullPrev=new Uint32Array(n),this._hullNext=new Uint32Array(n),this._hullTri=new Uint32Array(n),this._hullHash=new Int32Array(this._hashSize),this._ids=new Uint32Array(n),this._dists=new Float64Array(n),this.update()}update(){const{coords:t,_hullPrev:n,_hullNext:e,_hullTri:r,_hullHash:i}=this,o=t.length>>1;let a=1/0,u=1/0,c=-1/0,f=-1/0;for(let n=0;nc&&(c=e),r>f&&(f=r),this._ids[n]=n}const s=(a+c)/2,l=(u+f)/2;let h,d,p;for(let n=0,e=1/0;n0&&(d=n,e=r)}let v=t[2*d],_=t[2*d+1],b=1/0;for(let n=0;nr&&(n[e++]=i,r=o)}return this.hull=n.subarray(0,e),this.triangles=new Uint32Array(0),void(this.halfedges=new Uint32Array(0))}if(Mu(g,y,v,_,m,x)<0){const t=d,n=v,e=_;d=p,v=m,_=x,p=t,m=n,x=e}const w=function(t,n,e,r,i,o){const a=e-t,u=r-n,c=i-t,f=o-n,s=a*a+u*u,l=c*c+f*f,h=.5/(a*f-u*c),d=t+(f*s-u*l)*h,p=n+(a*l-c*s)*h;return{x:d,y:p}}(g,y,v,_,m,x);this._cx=w.x,this._cy=w.y;for(let n=0;n0&&Math.abs(f-o)<=Tu&&Math.abs(s-a)<=Tu)continue;if(o=f,a=s,c===h||c===d||c===p)continue;let l=0;for(let t=0,n=this._hashKey(f,s);t=0;)if(y=g,y===l){y=-1;break}if(-1===y)continue;let v=this._addTriangle(y,c,e[y],-1,-1,r[y]);r[c]=this._legalize(v+2),r[y]=v,M++;let _=e[y];for(;g=e[_],Mu(f,s,t[2*_],t[2*_+1],t[2*g],t[2*g+1])<0;)v=this._addTriangle(_,c,g,r[c],-1,r[_]),r[c]=this._legalize(v+2),e[_]=_,M--,_=g;if(y===l)for(;g=n[y],Mu(f,s,t[2*g],t[2*g+1],t[2*y],t[2*y+1])<0;)v=this._addTriangle(g,c,y,-1,r[y],r[g]),this._legalize(v+2),r[g]=v,e[y]=y,M--,y=g;this._hullStart=n[c]=y,e[y]=n[_]=c,e[c]=_,i[this._hashKey(f,s)]=c,i[this._hashKey(t[2*y],t[2*y+1])]=y}this.hull=new Uint32Array(M);for(let t=0,n=this._hullStart;t0?3-e:1+e)/4}(t-this._cx,n-this._cy)*this._hashSize)%this._hashSize}_legalize(t){const{_triangles:n,_halfedges:e,coords:r}=this;let i=0,o=0;for(;;){const a=e[t],u=t-t%3;if(o=u+(t+2)%3,-1===a){if(0===i)break;t=Au[--i];continue}const c=a-a%3,f=u+(t+1)%3,s=c+(a+2)%3,l=n[o],h=n[t],d=n[f],p=n[s];if(Nu(r[2*l],r[2*l+1],r[2*h],r[2*h+1],r[2*d],r[2*d+1],r[2*p],r[2*p+1])){n[t]=p,n[a]=l;const r=e[s];if(-1===r){let n=this._hullStart;do{if(this._hullTri[n]===s){this._hullTri[n]=t;break}n=this._hullPrev[n]}while(n!==this._hullStart)}this._link(t,r),this._link(a,e[o]),this._link(o,s);const u=c+(a+1)%3;i=e&&n[t[a]]>o;)t[a+1]=t[a--];t[a+1]=r}else{let i=e+1,o=r;Pu(t,e+r>>1,i),n[t[e]]>n[t[r]]&&Pu(t,e,r),n[t[i]]>n[t[r]]&&Pu(t,i,r),n[t[e]]>n[t[i]]&&Pu(t,e,i);const a=t[i],u=n[a];for(;;){do{i++}while(n[t[i]]u);if(o=o-e?(Cu(t,n,i,r),Cu(t,n,e,o-1)):(Cu(t,n,e,o-1),Cu(t,n,i,r))}}function Pu(t,n,e){const r=t[n];t[n]=t[e],t[e]=r}function zu(t){return t[0]}function $u(t){return t[1]}const Du=1e-6;class Ru{constructor(){this._x0=this._y0=this._x1=this._y1=null,this._=""}moveTo(t,n){this._+=`M${this._x0=this._x1=+t},${this._y0=this._y1=+n}`}closePath(){null!==this._x1&&(this._x1=this._x0,this._y1=this._y0,this._+="Z")}lineTo(t,n){this._+=`L${this._x1=+t},${this._y1=+n}`}arc(t,n,e){const r=(t=+t)+(e=+e),i=n=+n;if(e<0)throw new Error("negative radius");null===this._x1?this._+=`M${r},${i}`:(Math.abs(this._x1-r)>Du||Math.abs(this._y1-i)>Du)&&(this._+="L"+r+","+i),e&&(this._+=`A${e},${e},0,1,1,${t-e},${n}A${e},${e},0,1,1,${this._x1=r},${this._y1=i}`)}rect(t,n,e,r){this._+=`M${this._x0=this._x1=+t},${this._y0=this._y1=+n}h${+e}v${+r}h${-e}Z`}value(){return this._||null}}class Fu{constructor(){this._=[]}moveTo(t,n){this._.push([t,n])}closePath(){this._.push(this._[0].slice())}lineTo(t,n){this._.push([t,n])}value(){return this._.length?this._:null}}class qu{constructor(t,[n,e,r,i]=[0,0,960,500]){if(!((r=+r)>=(n=+n)&&(i=+i)>=(e=+e)))throw new Error("invalid bounds");this.delaunay=t,this._circumcenters=new Float64Array(2*t.points.length),this.vectors=new Float64Array(2*t.points.length),this.xmax=r,this.xmin=n,this.ymax=i,this.ymin=e,this._init()}update(){return this.delaunay.update(),this._init(),this}_init(){const{delaunay:{points:t,hull:n,triangles:e},vectors:r}=this;let i,o;const a=this.circumcenters=this._circumcenters.subarray(0,e.length/3*2);for(let r,u,c=0,f=0,s=e.length;c1;)i-=2;for(let t=2;t0){if(n>=this.ymax)return null;(i=(this.ymax-n)/r)0){if(t>=this.xmax)return null;(i=(this.xmax-t)/e)this.xmax?2:0)|(nthis.ymax?8:0)}_simplify(t){if(t&&t.length>4){for(let n=0;n2&&function(t){const{triangles:n,coords:e}=t;for(let t=0;t1e-10)return!1}return!0}(t)){this.collinear=Int32Array.from({length:n.length/2},((t,n)=>n)).sort(((t,e)=>n[2*t]-n[2*e]||n[2*t+1]-n[2*e+1]));const t=this.collinear[0],e=this.collinear[this.collinear.length-1],r=[n[2*t],n[2*t+1],n[2*e],n[2*e+1]],i=1e-8*Math.hypot(r[3]-r[1],r[2]-r[0]);for(let t=0,e=n.length/2;t0&&(this.triangles=new Int32Array(3).fill(-1),this.halfedges=new Int32Array(3).fill(-1),this.triangles[0]=r[0],o[r[0]]=1,2===r.length&&(o[r[1]]=0,this.triangles[1]=r[1],this.triangles[2]=r[1]))}voronoi(t){return new qu(this,t)}*neighbors(t){const{inedges:n,hull:e,_hullIndex:r,halfedges:i,triangles:o,collinear:a}=this;if(a){const n=a.indexOf(t);return n>0&&(yield a[n-1]),void(n=0&&i!==e&&i!==r;)e=i;return i}_step(t,n,e){const{inedges:r,hull:i,_hullIndex:o,halfedges:a,triangles:u,points:c}=this;if(-1===r[t]||!c.length)return(t+1)%(c.length>>1);let f=t,s=Iu(n-c[2*t],2)+Iu(e-c[2*t+1],2);const l=r[t];let h=l;do{let r=u[h];const l=Iu(n-c[2*r],2)+Iu(e-c[2*r+1],2);if(l9999?"+"+Ku(n,6):Ku(n,4))+"-"+Ku(t.getUTCMonth()+1,2)+"-"+Ku(t.getUTCDate(),2)+(o?"T"+Ku(e,2)+":"+Ku(r,2)+":"+Ku(i,2)+"."+Ku(o,3)+"Z":i?"T"+Ku(e,2)+":"+Ku(r,2)+":"+Ku(i,2)+"Z":r||e?"T"+Ku(e,2)+":"+Ku(r,2)+"Z":"")}function Ju(t){var n=new RegExp('["'+t+"\n\r]"),e=t.charCodeAt(0);function r(t,n){var r,i=[],o=t.length,a=0,u=0,c=o<=0,f=!1;function s(){if(c)return Hu;if(f)return f=!1,ju;var n,r,i=a;if(t.charCodeAt(i)===Xu){for(;a++=o?c=!0:(r=t.charCodeAt(a++))===Gu?f=!0:r===Vu&&(f=!0,t.charCodeAt(a)===Gu&&++a),t.slice(i+1,n-1).replace(/""/g,'"')}for(;amc(n,e).then((n=>(new DOMParser).parseFromString(n,t)))}var Sc=Ac("application/xml"),Ec=Ac("text/html"),Nc=Ac("image/svg+xml");function kc(t,n,e,r){if(isNaN(n)||isNaN(e))return t;var i,o,a,u,c,f,s,l,h,d=t._root,p={data:r},g=t._x0,y=t._y0,v=t._x1,_=t._y1;if(!d)return t._root=p,t;for(;d.length;)if((f=n>=(o=(g+v)/2))?g=o:v=o,(s=e>=(a=(y+_)/2))?y=a:_=a,i=d,!(d=d[l=s<<1|f]))return i[l]=p,t;if(u=+t._x.call(null,d.data),c=+t._y.call(null,d.data),n===u&&e===c)return p.next=d,i?i[l]=p:t._root=p,t;do{i=i?i[l]=new Array(4):t._root=new Array(4),(f=n>=(o=(g+v)/2))?g=o:v=o,(s=e>=(a=(y+_)/2))?y=a:_=a}while((l=s<<1|f)==(h=(c>=a)<<1|u>=o));return i[h]=d,i[l]=p,t}function Cc(t,n,e,r,i){this.node=t,this.x0=n,this.y0=e,this.x1=r,this.y1=i}function Pc(t){return t[0]}function zc(t){return t[1]}function $c(t,n,e){var r=new Dc(null==n?Pc:n,null==e?zc:e,NaN,NaN,NaN,NaN);return null==t?r:r.addAll(t)}function Dc(t,n,e,r,i,o){this._x=t,this._y=n,this._x0=e,this._y0=r,this._x1=i,this._y1=o,this._root=void 0}function Rc(t){for(var n={data:t.data},e=n;t=t.next;)e=e.next={data:t.data};return n}var Fc=$c.prototype=Dc.prototype;function qc(t){return function(){return t}}function Uc(t){return 1e-6*(t()-.5)}function Ic(t){return t.x+t.vx}function Oc(t){return t.y+t.vy}function Bc(t){return t.index}function Yc(t,n){var e=t.get(n);if(!e)throw new Error("node not found: "+n);return e}Fc.copy=function(){var t,n,e=new Dc(this._x,this._y,this._x0,this._y0,this._x1,this._y1),r=this._root;if(!r)return e;if(!r.length)return e._root=Rc(r),e;for(t=[{source:r,target:e._root=new Array(4)}];r=t.pop();)for(var i=0;i<4;++i)(n=r.source[i])&&(n.length?t.push({source:n,target:r.target[i]=new Array(4)}):r.target[i]=Rc(n));return e},Fc.add=function(t){const n=+this._x.call(null,t),e=+this._y.call(null,t);return kc(this.cover(n,e),n,e,t)},Fc.addAll=function(t){var n,e,r,i,o=t.length,a=new Array(o),u=new Array(o),c=1/0,f=1/0,s=-1/0,l=-1/0;for(e=0;es&&(s=r),il&&(l=i));if(c>s||f>l)return this;for(this.cover(c,f).cover(s,l),e=0;et||t>=i||r>n||n>=o;)switch(u=(nh||(o=c.y0)>d||(a=c.x1)=v)<<1|t>=y)&&(c=p[p.length-1],p[p.length-1]=p[p.length-1-f],p[p.length-1-f]=c)}else{var _=t-+this._x.call(null,g.data),b=n-+this._y.call(null,g.data),m=_*_+b*b;if(m=(u=(p+y)/2))?p=u:y=u,(s=a>=(c=(g+v)/2))?g=c:v=c,n=d,!(d=d[l=s<<1|f]))return this;if(!d.length)break;(n[l+1&3]||n[l+2&3]||n[l+3&3])&&(e=n,h=l)}for(;d.data!==t;)if(r=d,!(d=d.next))return this;return(i=d.next)&&delete d.next,r?(i?r.next=i:delete r.next,this):n?(i?n[l]=i:delete n[l],(d=n[0]||n[1]||n[2]||n[3])&&d===(n[3]||n[2]||n[1]||n[0])&&!d.length&&(e?e[h]=d:this._root=d),this):(this._root=i,this)},Fc.removeAll=function(t){for(var n=0,e=t.length;n1?r[0]+r.slice(2):r,+t.slice(e+1)]}function Zc(t){return(t=Wc(Math.abs(t)))?t[1]:NaN}var Kc,Qc=/^(?:(.)?([<>=^]))?([+\-( ])?([$#])?(0)?(\d+)?(,)?(\.\d+)?(~)?([a-z%])?$/i;function Jc(t){if(!(n=Qc.exec(t)))throw new Error("invalid format: "+t);var n;return new tf({fill:n[1],align:n[2],sign:n[3],symbol:n[4],zero:n[5],width:n[6],comma:n[7],precision:n[8]&&n[8].slice(1),trim:n[9],type:n[10]})}function tf(t){this.fill=void 0===t.fill?" ":t.fill+"",this.align=void 0===t.align?">":t.align+"",this.sign=void 0===t.sign?"-":t.sign+"",this.symbol=void 0===t.symbol?"":t.symbol+"",this.zero=!!t.zero,this.width=void 0===t.width?void 0:+t.width,this.comma=!!t.comma,this.precision=void 0===t.precision?void 0:+t.precision,this.trim=!!t.trim,this.type=void 0===t.type?"":t.type+""}function nf(t,n){var e=Wc(t,n);if(!e)return t+"";var r=e[0],i=e[1];return i<0?"0."+new Array(-i).join("0")+r:r.length>i+1?r.slice(0,i+1)+"."+r.slice(i+1):r+new Array(i-r.length+2).join("0")}Jc.prototype=tf.prototype,tf.prototype.toString=function(){return this.fill+this.align+this.sign+this.symbol+(this.zero?"0":"")+(void 0===this.width?"":Math.max(1,0|this.width))+(this.comma?",":"")+(void 0===this.precision?"":"."+Math.max(0,0|this.precision))+(this.trim?"~":"")+this.type};var ef={"%":(t,n)=>(100*t).toFixed(n),b:t=>Math.round(t).toString(2),c:t=>t+"",d:function(t){return Math.abs(t=Math.round(t))>=1e21?t.toLocaleString("en").replace(/,/g,""):t.toString(10)},e:(t,n)=>t.toExponential(n),f:(t,n)=>t.toFixed(n),g:(t,n)=>t.toPrecision(n),o:t=>Math.round(t).toString(8),p:(t,n)=>nf(100*t,n),r:nf,s:function(t,n){var e=Wc(t,n);if(!e)return t+"";var r=e[0],i=e[1],o=i-(Kc=3*Math.max(-8,Math.min(8,Math.floor(i/3))))+1,a=r.length;return o===a?r:o>a?r+new Array(o-a+1).join("0"):o>0?r.slice(0,o)+"."+r.slice(o):"0."+new Array(1-o).join("0")+Wc(t,Math.max(0,n+o-1))[0]},X:t=>Math.round(t).toString(16).toUpperCase(),x:t=>Math.round(t).toString(16)};function rf(t){return t}var of,af=Array.prototype.map,uf=["y","z","a","f","p","n","µ","m","","k","M","G","T","P","E","Z","Y"];function cf(t){var n,e,r=void 0===t.grouping||void 0===t.thousands?rf:(n=af.call(t.grouping,Number),e=t.thousands+"",function(t,r){for(var i=t.length,o=[],a=0,u=n[0],c=0;i>0&&u>0&&(c+u+1>r&&(u=Math.max(1,r-c)),o.push(t.substring(i-=u,i+u)),!((c+=u+1)>r));)u=n[a=(a+1)%n.length];return o.reverse().join(e)}),i=void 0===t.currency?"":t.currency[0]+"",o=void 0===t.currency?"":t.currency[1]+"",a=void 0===t.decimal?".":t.decimal+"",u=void 0===t.numerals?rf:function(t){return function(n){return n.replace(/[0-9]/g,(function(n){return t[+n]}))}}(af.call(t.numerals,String)),c=void 0===t.percent?"%":t.percent+"",f=void 0===t.minus?"−":t.minus+"",s=void 0===t.nan?"NaN":t.nan+"";function l(t){var n=(t=Jc(t)).fill,e=t.align,l=t.sign,h=t.symbol,d=t.zero,p=t.width,g=t.comma,y=t.precision,v=t.trim,_=t.type;"n"===_?(g=!0,_="g"):ef[_]||(void 0===y&&(y=12),v=!0,_="g"),(d||"0"===n&&"="===e)&&(d=!0,n="0",e="=");var b="$"===h?i:"#"===h&&/[boxX]/.test(_)?"0"+_.toLowerCase():"",m="$"===h?o:/[%p]/.test(_)?c:"",x=ef[_],w=/[defgprs%]/.test(_);function M(t){var i,o,c,h=b,M=m;if("c"===_)M=x(t)+M,t="";else{var T=(t=+t)<0||1/t<0;if(t=isNaN(t)?s:x(Math.abs(t),y),v&&(t=function(t){t:for(var n,e=t.length,r=1,i=-1;r0&&(i=0)}return i>0?t.slice(0,i)+t.slice(n+1):t}(t)),T&&0==+t&&"+"!==l&&(T=!1),h=(T?"("===l?l:f:"-"===l||"("===l?"":l)+h,M=("s"===_?uf[8+Kc/3]:"")+M+(T&&"("===l?")":""),w)for(i=-1,o=t.length;++i(c=t.charCodeAt(i))||c>57){M=(46===c?a+t.slice(i+1):t.slice(i))+M,t=t.slice(0,i);break}}g&&!d&&(t=r(t,1/0));var A=h.length+t.length+M.length,S=A>1)+h+t+M+S.slice(A);break;default:t=S+h+t+M}return u(t)}return y=void 0===y?6:/[gprs]/.test(_)?Math.max(1,Math.min(21,y)):Math.max(0,Math.min(20,y)),M.toString=function(){return t+""},M}return{format:l,formatPrefix:function(t,n){var e=l(((t=Jc(t)).type="f",t)),r=3*Math.max(-8,Math.min(8,Math.floor(Zc(n)/3))),i=Math.pow(10,-r),o=uf[8+r/3];return function(t){return e(i*t)+o}}}}function ff(n){return of=cf(n),t.format=of.format,t.formatPrefix=of.formatPrefix,of}function sf(t){return Math.max(0,-Zc(Math.abs(t)))}function lf(t,n){return Math.max(0,3*Math.max(-8,Math.min(8,Math.floor(Zc(n)/3)))-Zc(Math.abs(t)))}function hf(t,n){return t=Math.abs(t),n=Math.abs(n)-t,Math.max(0,Zc(n)-Zc(t))+1}t.format=void 0,t.formatPrefix=void 0,ff({thousands:",",grouping:[3],currency:["$",""]});var df=1e-6,pf=1e-12,gf=Math.PI,yf=gf/2,vf=gf/4,_f=2*gf,bf=180/gf,mf=gf/180,xf=Math.abs,wf=Math.atan,Mf=Math.atan2,Tf=Math.cos,Af=Math.ceil,Sf=Math.exp,Ef=Math.hypot,Nf=Math.log,kf=Math.pow,Cf=Math.sin,Pf=Math.sign||function(t){return t>0?1:t<0?-1:0},zf=Math.sqrt,$f=Math.tan;function Df(t){return t>1?0:t<-1?gf:Math.acos(t)}function Rf(t){return t>1?yf:t<-1?-yf:Math.asin(t)}function Ff(t){return(t=Cf(t/2))*t}function qf(){}function Uf(t,n){t&&Of.hasOwnProperty(t.type)&&Of[t.type](t,n)}var If={Feature:function(t,n){Uf(t.geometry,n)},FeatureCollection:function(t,n){for(var e=t.features,r=-1,i=e.length;++r=0?1:-1,i=r*e,o=Tf(n=(n*=mf)/2+vf),a=Cf(n),u=Vf*a,c=Gf*o+u*Tf(i),f=u*r*Cf(i);as.add(Mf(f,c)),Xf=t,Gf=o,Vf=a}function ds(t){return[Mf(t[1],t[0]),Rf(t[2])]}function ps(t){var n=t[0],e=t[1],r=Tf(e);return[r*Tf(n),r*Cf(n),Cf(e)]}function gs(t,n){return t[0]*n[0]+t[1]*n[1]+t[2]*n[2]}function ys(t,n){return[t[1]*n[2]-t[2]*n[1],t[2]*n[0]-t[0]*n[2],t[0]*n[1]-t[1]*n[0]]}function vs(t,n){t[0]+=n[0],t[1]+=n[1],t[2]+=n[2]}function _s(t,n){return[t[0]*n,t[1]*n,t[2]*n]}function bs(t){var n=zf(t[0]*t[0]+t[1]*t[1]+t[2]*t[2]);t[0]/=n,t[1]/=n,t[2]/=n}var ms,xs,ws,Ms,Ts,As,Ss,Es,Ns,ks,Cs,Ps,zs,$s,Ds,Rs,Fs={point:qs,lineStart:Is,lineEnd:Os,polygonStart:function(){Fs.point=Bs,Fs.lineStart=Ys,Fs.lineEnd=Ls,rs=new T,cs.polygonStart()},polygonEnd:function(){cs.polygonEnd(),Fs.point=qs,Fs.lineStart=Is,Fs.lineEnd=Os,as<0?(Wf=-(Kf=180),Zf=-(Qf=90)):rs>df?Qf=90:rs<-df&&(Zf=-90),os[0]=Wf,os[1]=Kf},sphere:function(){Wf=-(Kf=180),Zf=-(Qf=90)}};function qs(t,n){is.push(os=[Wf=t,Kf=t]),nQf&&(Qf=n)}function Us(t,n){var e=ps([t*mf,n*mf]);if(es){var r=ys(es,e),i=ys([r[1],-r[0],0],r);bs(i),i=ds(i);var o,a=t-Jf,u=a>0?1:-1,c=i[0]*bf*u,f=xf(a)>180;f^(u*JfQf&&(Qf=o):f^(u*Jf<(c=(c+360)%360-180)&&cQf&&(Qf=n)),f?tjs(Wf,Kf)&&(Kf=t):js(t,Kf)>js(Wf,Kf)&&(Wf=t):Kf>=Wf?(tKf&&(Kf=t)):t>Jf?js(Wf,t)>js(Wf,Kf)&&(Kf=t):js(t,Kf)>js(Wf,Kf)&&(Wf=t)}else is.push(os=[Wf=t,Kf=t]);nQf&&(Qf=n),es=e,Jf=t}function Is(){Fs.point=Us}function Os(){os[0]=Wf,os[1]=Kf,Fs.point=qs,es=null}function Bs(t,n){if(es){var e=t-Jf;rs.add(xf(e)>180?e+(e>0?360:-360):e)}else ts=t,ns=n;cs.point(t,n),Us(t,n)}function Ys(){cs.lineStart()}function Ls(){Bs(ts,ns),cs.lineEnd(),xf(rs)>df&&(Wf=-(Kf=180)),os[0]=Wf,os[1]=Kf,es=null}function js(t,n){return(n-=t)<0?n+360:n}function Hs(t,n){return t[0]-n[0]}function Xs(t,n){return t[0]<=t[1]?t[0]<=n&&n<=t[1]:ngf&&(t-=Math.round(t/_f)*_f),[t,n]}function ul(t,n,e){return(t%=_f)?n||e?ol(fl(t),sl(n,e)):fl(t):n||e?sl(n,e):al}function cl(t){return function(n,e){return xf(n+=t)>gf&&(n-=Math.round(n/_f)*_f),[n,e]}}function fl(t){var n=cl(t);return n.invert=cl(-t),n}function sl(t,n){var e=Tf(t),r=Cf(t),i=Tf(n),o=Cf(n);function a(t,n){var a=Tf(n),u=Tf(t)*a,c=Cf(t)*a,f=Cf(n),s=f*e+u*r;return[Mf(c*i-s*o,u*e-f*r),Rf(s*i+c*o)]}return a.invert=function(t,n){var a=Tf(n),u=Tf(t)*a,c=Cf(t)*a,f=Cf(n),s=f*i-c*o;return[Mf(c*i+f*o,u*e+s*r),Rf(s*e-u*r)]},a}function ll(t){function n(n){return(n=t(n[0]*mf,n[1]*mf))[0]*=bf,n[1]*=bf,n}return t=ul(t[0]*mf,t[1]*mf,t.length>2?t[2]*mf:0),n.invert=function(n){return(n=t.invert(n[0]*mf,n[1]*mf))[0]*=bf,n[1]*=bf,n},n}function hl(t,n,e,r,i,o){if(e){var a=Tf(n),u=Cf(n),c=r*e;null==i?(i=n+r*_f,o=n-c/2):(i=dl(a,i),o=dl(a,o),(r>0?io)&&(i+=r*_f));for(var f,s=i;r>0?s>o:s1&&n.push(n.pop().concat(n.shift()))},result:function(){var e=n;return n=[],t=null,e}}}function gl(t,n){return xf(t[0]-n[0])=0;--o)i.point((s=f[o])[0],s[1]);else r(h.x,h.p.x,-1,i);h=h.p}f=(h=h.o).z,d=!d}while(!h.v);i.lineEnd()}}}function _l(t){if(n=t.length){for(var n,e,r=0,i=t[0];++r=0?1:-1,E=S*A,N=E>gf,k=y*w;if(c.add(Mf(k*S*Cf(E),v*M+k*Tf(E))),a+=N?A+S*_f:A,N^p>=e^m>=e){var C=ys(ps(d),ps(b));bs(C);var P=ys(o,C);bs(P);var z=(N^A>=0?-1:1)*Rf(P[2]);(r>z||r===z&&(C[0]||C[1]))&&(u+=N^A>=0?1:-1)}}return(a<-df||a0){for(l||(i.polygonStart(),l=!0),i.lineStart(),t=0;t1&&2&c&&h.push(h.pop().concat(h.shift())),a.push(h.filter(wl))}return h}}function wl(t){return t.length>1}function Ml(t,n){return((t=t.x)[0]<0?t[1]-yf-df:yf-t[1])-((n=n.x)[0]<0?n[1]-yf-df:yf-n[1])}al.invert=al;var Tl=xl((function(){return!0}),(function(t){var n,e=NaN,r=NaN,i=NaN;return{lineStart:function(){t.lineStart(),n=1},point:function(o,a){var u=o>0?gf:-gf,c=xf(o-e);xf(c-gf)0?yf:-yf),t.point(i,r),t.lineEnd(),t.lineStart(),t.point(u,r),t.point(o,r),n=0):i!==u&&c>=gf&&(xf(e-i)df?wf((Cf(n)*(o=Tf(r))*Cf(e)-Cf(r)*(i=Tf(n))*Cf(t))/(i*o*a)):(n+r)/2}(e,r,o,a),t.point(i,r),t.lineEnd(),t.lineStart(),t.point(u,r),n=0),t.point(e=o,r=a),i=u},lineEnd:function(){t.lineEnd(),e=r=NaN},clean:function(){return 2-n}}}),(function(t,n,e,r){var i;if(null==t)i=e*yf,r.point(-gf,i),r.point(0,i),r.point(gf,i),r.point(gf,0),r.point(gf,-i),r.point(0,-i),r.point(-gf,-i),r.point(-gf,0),r.point(-gf,i);else if(xf(t[0]-n[0])>df){var o=t[0]0,i=xf(n)>df;function o(t,e){return Tf(t)*Tf(e)>n}function a(t,e,r){var i=[1,0,0],o=ys(ps(t),ps(e)),a=gs(o,o),u=o[0],c=a-u*u;if(!c)return!r&&t;var f=n*a/c,s=-n*u/c,l=ys(i,o),h=_s(i,f);vs(h,_s(o,s));var d=l,p=gs(h,d),g=gs(d,d),y=p*p-g*(gs(h,h)-1);if(!(y<0)){var v=zf(y),_=_s(d,(-p-v)/g);if(vs(_,h),_=ds(_),!r)return _;var b,m=t[0],x=e[0],w=t[1],M=e[1];x0^_[1]<(xf(_[0]-m)gf^(m<=_[0]&&_[0]<=x)){var S=_s(d,(-p+v)/g);return vs(S,h),[_,ds(S)]}}}function u(n,e){var i=r?t:gf-t,o=0;return n<-i?o|=1:n>i&&(o|=2),e<-i?o|=4:e>i&&(o|=8),o}return xl(o,(function(t){var n,e,c,f,s;return{lineStart:function(){f=c=!1,s=1},point:function(l,h){var d,p=[l,h],g=o(l,h),y=r?g?0:u(l,h):g?u(l+(l<0?gf:-gf),h):0;if(!n&&(f=c=g)&&t.lineStart(),g!==c&&(!(d=a(n,p))||gl(n,d)||gl(p,d))&&(p[2]=1),g!==c)s=0,g?(t.lineStart(),d=a(p,n),t.point(d[0],d[1])):(d=a(n,p),t.point(d[0],d[1],2),t.lineEnd()),n=d;else if(i&&n&&r^g){var v;y&e||!(v=a(p,n,!0))||(s=0,r?(t.lineStart(),t.point(v[0][0],v[0][1]),t.point(v[1][0],v[1][1]),t.lineEnd()):(t.point(v[1][0],v[1][1]),t.lineEnd(),t.lineStart(),t.point(v[0][0],v[0][1],3)))}!g||n&&gl(n,p)||t.point(p[0],p[1]),n=p,c=g,e=y},lineEnd:function(){c&&t.lineEnd(),n=null},clean:function(){return s|(f&&c)<<1}}}),(function(n,r,i,o){hl(o,t,e,i,n,r)}),r?[0,-t]:[-gf,t-gf])}var Sl,El,Nl,kl,Cl=1e9,Pl=-Cl;function zl(t,n,e,r){function i(i,o){return t<=i&&i<=e&&n<=o&&o<=r}function o(i,o,u,f){var s=0,l=0;if(null==i||(s=a(i,u))!==(l=a(o,u))||c(i,o)<0^u>0)do{f.point(0===s||3===s?t:e,s>1?r:n)}while((s=(s+u+4)%4)!==l);else f.point(o[0],o[1])}function a(r,i){return xf(r[0]-t)0?0:3:xf(r[0]-e)0?2:1:xf(r[1]-n)0?1:0:i>0?3:2}function u(t,n){return c(t.x,n.x)}function c(t,n){var e=a(t,1),r=a(n,1);return e!==r?e-r:0===e?n[1]-t[1]:1===e?t[0]-n[0]:2===e?t[1]-n[1]:n[0]-t[0]}return function(a){var c,f,s,l,h,d,p,g,y,v,_,b=a,m=pl(),x={point:w,lineStart:function(){x.point=M,f&&f.push(s=[]);v=!0,y=!1,p=g=NaN},lineEnd:function(){c&&(M(l,h),d&&y&&m.rejoin(),c.push(m.result()));x.point=w,y&&b.lineEnd()},polygonStart:function(){b=m,c=[],f=[],_=!0},polygonEnd:function(){var n=function(){for(var n=0,e=0,i=f.length;er&&(h-o)*(r-a)>(d-a)*(t-o)&&++n:d<=r&&(h-o)*(r-a)<(d-a)*(t-o)&&--n;return n}(),e=_&&n,i=(c=ft(c)).length;(e||i)&&(a.polygonStart(),e&&(a.lineStart(),o(null,null,1,a),a.lineEnd()),i&&vl(c,u,n,o,a),a.polygonEnd());b=a,c=f=s=null}};function w(t,n){i(t,n)&&b.point(t,n)}function M(o,a){var u=i(o,a);if(f&&s.push([o,a]),v)l=o,h=a,d=u,v=!1,u&&(b.lineStart(),b.point(o,a));else if(u&&y)b.point(o,a);else{var c=[p=Math.max(Pl,Math.min(Cl,p)),g=Math.max(Pl,Math.min(Cl,g))],m=[o=Math.max(Pl,Math.min(Cl,o)),a=Math.max(Pl,Math.min(Cl,a))];!function(t,n,e,r,i,o){var a,u=t[0],c=t[1],f=0,s=1,l=n[0]-u,h=n[1]-c;if(a=e-u,l||!(a>0)){if(a/=l,l<0){if(a0){if(a>s)return;a>f&&(f=a)}if(a=i-u,l||!(a<0)){if(a/=l,l<0){if(a>s)return;a>f&&(f=a)}else if(l>0){if(a0)){if(a/=h,h<0){if(a0){if(a>s)return;a>f&&(f=a)}if(a=o-c,h||!(a<0)){if(a/=h,h<0){if(a>s)return;a>f&&(f=a)}else if(h>0){if(a0&&(t[0]=u+f*l,t[1]=c+f*h),s<1&&(n[0]=u+s*l,n[1]=c+s*h),!0}}}}}(c,m,t,n,e,r)?u&&(b.lineStart(),b.point(o,a),_=!1):(y||(b.lineStart(),b.point(c[0],c[1])),b.point(m[0],m[1]),u||b.lineEnd(),_=!1)}p=o,g=a,y=u}return x}}var $l={sphere:qf,point:qf,lineStart:function(){$l.point=Rl,$l.lineEnd=Dl},lineEnd:qf,polygonStart:qf,polygonEnd:qf};function Dl(){$l.point=$l.lineEnd=qf}function Rl(t,n){El=t*=mf,Nl=Cf(n*=mf),kl=Tf(n),$l.point=Fl}function Fl(t,n){t*=mf;var e=Cf(n*=mf),r=Tf(n),i=xf(t-El),o=Tf(i),a=r*Cf(i),u=kl*e-Nl*r*o,c=Nl*e+kl*r*o;Sl.add(Mf(zf(a*a+u*u),c)),El=t,Nl=e,kl=r}function ql(t){return Sl=new T,Lf(t,$l),+Sl}var Ul=[null,null],Il={type:"LineString",coordinates:Ul};function Ol(t,n){return Ul[0]=t,Ul[1]=n,ql(Il)}var Bl={Feature:function(t,n){return Ll(t.geometry,n)},FeatureCollection:function(t,n){for(var e=t.features,r=-1,i=e.length;++r0&&(i=Ol(t[o],t[o-1]))>0&&e<=i&&r<=i&&(e+r-i)*(1-Math.pow((e-r)/i,2))df})).map(c)).concat(lt(Af(o/d)*d,i,d).filter((function(t){return xf(t%g)>df})).map(f))}return v.lines=function(){return _().map((function(t){return{type:"LineString",coordinates:t}}))},v.outline=function(){return{type:"Polygon",coordinates:[s(r).concat(l(a).slice(1),s(e).reverse().slice(1),l(u).reverse().slice(1))]}},v.extent=function(t){return arguments.length?v.extentMajor(t).extentMinor(t):v.extentMinor()},v.extentMajor=function(t){return arguments.length?(r=+t[0][0],e=+t[1][0],u=+t[0][1],a=+t[1][1],r>e&&(t=r,r=e,e=t),u>a&&(t=u,u=a,a=t),v.precision(y)):[[r,u],[e,a]]},v.extentMinor=function(e){return arguments.length?(n=+e[0][0],t=+e[1][0],o=+e[0][1],i=+e[1][1],n>t&&(e=n,n=t,t=e),o>i&&(e=o,o=i,i=e),v.precision(y)):[[n,o],[t,i]]},v.step=function(t){return arguments.length?v.stepMajor(t).stepMinor(t):v.stepMinor()},v.stepMajor=function(t){return arguments.length?(p=+t[0],g=+t[1],v):[p,g]},v.stepMinor=function(t){return arguments.length?(h=+t[0],d=+t[1],v):[h,d]},v.precision=function(h){return arguments.length?(y=+h,c=Wl(o,i,90),f=Zl(n,t,y),s=Wl(u,a,90),l=Zl(r,e,y),v):y},v.extentMajor([[-180,-90+df],[180,90-df]]).extentMinor([[-180,-80-df],[180,80+df]])}var Ql,Jl,th,nh,eh=t=>t,rh=new T,ih=new T,oh={point:qf,lineStart:qf,lineEnd:qf,polygonStart:function(){oh.lineStart=ah,oh.lineEnd=fh},polygonEnd:function(){oh.lineStart=oh.lineEnd=oh.point=qf,rh.add(xf(ih)),ih=new T},result:function(){var t=rh/2;return rh=new T,t}};function ah(){oh.point=uh}function uh(t,n){oh.point=ch,Ql=th=t,Jl=nh=n}function ch(t,n){ih.add(nh*t-th*n),th=t,nh=n}function fh(){ch(Ql,Jl)}var sh=oh,lh=1/0,hh=lh,dh=-lh,ph=dh,gh={point:function(t,n){tdh&&(dh=t);nph&&(ph=n)},lineStart:qf,lineEnd:qf,polygonStart:qf,polygonEnd:qf,result:function(){var t=[[lh,hh],[dh,ph]];return dh=ph=-(hh=lh=1/0),t}};var yh,vh,_h,bh,mh=gh,xh=0,wh=0,Mh=0,Th=0,Ah=0,Sh=0,Eh=0,Nh=0,kh=0,Ch={point:Ph,lineStart:zh,lineEnd:Rh,polygonStart:function(){Ch.lineStart=Fh,Ch.lineEnd=qh},polygonEnd:function(){Ch.point=Ph,Ch.lineStart=zh,Ch.lineEnd=Rh},result:function(){var t=kh?[Eh/kh,Nh/kh]:Sh?[Th/Sh,Ah/Sh]:Mh?[xh/Mh,wh/Mh]:[NaN,NaN];return xh=wh=Mh=Th=Ah=Sh=Eh=Nh=kh=0,t}};function Ph(t,n){xh+=t,wh+=n,++Mh}function zh(){Ch.point=$h}function $h(t,n){Ch.point=Dh,Ph(_h=t,bh=n)}function Dh(t,n){var e=t-_h,r=n-bh,i=zf(e*e+r*r);Th+=i*(_h+t)/2,Ah+=i*(bh+n)/2,Sh+=i,Ph(_h=t,bh=n)}function Rh(){Ch.point=Ph}function Fh(){Ch.point=Uh}function qh(){Ih(yh,vh)}function Uh(t,n){Ch.point=Ih,Ph(yh=_h=t,vh=bh=n)}function Ih(t,n){var e=t-_h,r=n-bh,i=zf(e*e+r*r);Th+=i*(_h+t)/2,Ah+=i*(bh+n)/2,Sh+=i,Eh+=(i=bh*t-_h*n)*(_h+t),Nh+=i*(bh+n),kh+=3*i,Ph(_h=t,bh=n)}var Oh=Ch;function Bh(t){this._context=t}Bh.prototype={_radius:4.5,pointRadius:function(t){return this._radius=t,this},polygonStart:function(){this._line=0},polygonEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){0===this._line&&this._context.closePath(),this._point=NaN},point:function(t,n){switch(this._point){case 0:this._context.moveTo(t,n),this._point=1;break;case 1:this._context.lineTo(t,n);break;default:this._context.moveTo(t+this._radius,n),this._context.arc(t,n,this._radius,0,_f)}},result:qf};var Yh,Lh,jh,Hh,Xh,Gh=new T,Vh={point:qf,lineStart:function(){Vh.point=Wh},lineEnd:function(){Yh&&Zh(Lh,jh),Vh.point=qf},polygonStart:function(){Yh=!0},polygonEnd:function(){Yh=null},result:function(){var t=+Gh;return Gh=new T,t}};function Wh(t,n){Vh.point=Zh,Lh=Hh=t,jh=Xh=n}function Zh(t,n){Hh-=t,Xh-=n,Gh.add(zf(Hh*Hh+Xh*Xh)),Hh=t,Xh=n}var Kh=Vh;let Qh,Jh,td,nd;class ed{constructor(t){this._append=null==t?rd:function(t){const n=Math.floor(t);if(!(n>=0))throw new RangeError(`invalid digits: ${t}`);if(n>15)return rd;if(n!==Qh){const t=10**n;Qh=n,Jh=function(n){let e=1;this._+=n[0];for(const r=n.length;e4*n&&g--){var m=a+h,x=u+d,w=c+p,M=zf(m*m+x*x+w*w),T=Rf(w/=M),A=xf(xf(w)-1)n||xf((v*k+_*C)/b-.5)>.3||a*h+u*d+c*p2?t[2]%360*mf:0,k()):[y*bf,v*bf,_*bf]},E.angle=function(t){return arguments.length?(b=t%360*mf,k()):b*bf},E.reflectX=function(t){return arguments.length?(m=t?-1:1,k()):m<0},E.reflectY=function(t){return arguments.length?(x=t?-1:1,k()):x<0},E.precision=function(t){return arguments.length?(a=dd(u,S=t*t),C()):zf(S)},E.fitExtent=function(t,n){return ud(E,t,n)},E.fitSize=function(t,n){return cd(E,t,n)},E.fitWidth=function(t,n){return fd(E,t,n)},E.fitHeight=function(t,n){return sd(E,t,n)},function(){return n=t.apply(this,arguments),E.invert=n.invert&&N,k()}}function _d(t){var n=0,e=gf/3,r=vd(t),i=r(n,e);return i.parallels=function(t){return arguments.length?r(n=t[0]*mf,e=t[1]*mf):[n*bf,e*bf]},i}function bd(t,n){var e=Cf(t),r=(e+Cf(n))/2;if(xf(r)0?n<-yf+df&&(n=-yf+df):n>yf-df&&(n=yf-df);var e=i/kf(Nd(n),r);return[e*Cf(r*t),i-e*Tf(r*t)]}return o.invert=function(t,n){var e=i-n,o=Pf(r)*zf(t*t+e*e),a=Mf(t,xf(e))*Pf(e);return e*r<0&&(a-=gf*Pf(t)*Pf(e)),[a/r,2*wf(kf(i/o,1/r))-yf]},o}function Cd(t,n){return[t,n]}function Pd(t,n){var e=Tf(t),r=t===n?Cf(t):(e-Tf(n))/(n-t),i=e/r+t;if(xf(r)=0;)n+=e[r].value;else n=1;t.value=n}function Gd(t,n){t instanceof Map?(t=[void 0,t],void 0===n&&(n=Wd)):void 0===n&&(n=Vd);for(var e,r,i,o,a,u=new Qd(t),c=[u];e=c.pop();)if((i=n(e.data))&&(a=(i=Array.from(i)).length))for(e.children=i,o=a-1;o>=0;--o)c.push(r=i[o]=new Qd(i[o])),r.parent=e,r.depth=e.depth+1;return u.eachBefore(Kd)}function Vd(t){return t.children}function Wd(t){return Array.isArray(t)?t[1]:null}function Zd(t){void 0!==t.data.value&&(t.value=t.data.value),t.data=t.data.data}function Kd(t){var n=0;do{t.height=n}while((t=t.parent)&&t.height<++n)}function Qd(t){this.data=t,this.depth=this.height=0,this.parent=null}function Jd(t){return null==t?null:tp(t)}function tp(t){if("function"!=typeof t)throw new Error;return t}function np(){return 0}function ep(t){return function(){return t}}qd.invert=function(t,n){for(var e,r=n,i=r*r,o=i*i*i,a=0;a<12&&(o=(i=(r-=e=(r*(zd+$d*i+o*(Dd+Rd*i))-n)/(zd+3*$d*i+o*(7*Dd+9*Rd*i)))*r)*i*i,!(xf(e)df&&--i>0);return[t/(.8707+(o=r*r)*(o*(o*o*o*(.003971-.001529*o)-.013791)-.131979)),r]},Od.invert=Md(Rf),Bd.invert=Md((function(t){return 2*wf(t)})),Yd.invert=function(t,n){return[-n,2*wf(Sf(t))-yf]},Qd.prototype=Gd.prototype={constructor:Qd,count:function(){return this.eachAfter(Xd)},each:function(t,n){let e=-1;for(const r of this)t.call(n,r,++e,this);return this},eachAfter:function(t,n){for(var e,r,i,o=this,a=[o],u=[],c=-1;o=a.pop();)if(u.push(o),e=o.children)for(r=0,i=e.length;r=0;--r)o.push(e[r]);return this},find:function(t,n){let e=-1;for(const r of this)if(t.call(n,r,++e,this))return r},sum:function(t){return this.eachAfter((function(n){for(var e=+t(n.data)||0,r=n.children,i=r&&r.length;--i>=0;)e+=r[i].value;n.value=e}))},sort:function(t){return this.eachBefore((function(n){n.children&&n.children.sort(t)}))},path:function(t){for(var n=this,e=function(t,n){if(t===n)return t;var e=t.ancestors(),r=n.ancestors(),i=null;t=e.pop(),n=r.pop();for(;t===n;)i=t,t=e.pop(),n=r.pop();return i}(n,t),r=[n];n!==e;)n=n.parent,r.push(n);for(var i=r.length;t!==e;)r.splice(i,0,t),t=t.parent;return r},ancestors:function(){for(var t=this,n=[t];t=t.parent;)n.push(t);return n},descendants:function(){return Array.from(this)},leaves:function(){var t=[];return this.eachBefore((function(n){n.children||t.push(n)})),t},links:function(){var t=this,n=[];return t.each((function(e){e!==t&&n.push({source:e.parent,target:e})})),n},copy:function(){return Gd(this).eachBefore(Zd)},[Symbol.iterator]:function*(){var t,n,e,r,i=this,o=[i];do{for(t=o.reverse(),o=[];i=t.pop();)if(yield i,n=i.children)for(e=0,r=n.length;e(t=(rp*t+ip)%op)/op}function up(t,n){for(var e,r,i=0,o=(t=function(t,n){let e,r,i=t.length;for(;i;)r=n()*i--|0,e=t[i],t[i]=t[r],t[r]=e;return t}(Array.from(t),n)).length,a=[];i0&&e*e>r*r+i*i}function lp(t,n){for(var e=0;e1e-6?(E+Math.sqrt(E*E-4*S*N))/(2*S):N/E);return{x:r+w+M*k,y:i+T+A*k,r:k}}function gp(t,n,e){var r,i,o,a,u=t.x-n.x,c=t.y-n.y,f=u*u+c*c;f?(i=n.r+e.r,i*=i,a=t.r+e.r,i>(a*=a)?(r=(f+a-i)/(2*f),o=Math.sqrt(Math.max(0,a/f-r*r)),e.x=t.x-r*u-o*c,e.y=t.y-r*c+o*u):(r=(f+i-a)/(2*f),o=Math.sqrt(Math.max(0,i/f-r*r)),e.x=n.x+r*u-o*c,e.y=n.y+r*c+o*u)):(e.x=n.x+e.r,e.y=n.y)}function yp(t,n){var e=t.r+n.r-1e-6,r=n.x-t.x,i=n.y-t.y;return e>0&&e*e>r*r+i*i}function vp(t){var n=t._,e=t.next._,r=n.r+e.r,i=(n.x*e.r+e.x*n.r)/r,o=(n.y*e.r+e.y*n.r)/r;return i*i+o*o}function _p(t){this._=t,this.next=null,this.previous=null}function bp(t,n){if(!(o=(t=function(t){return"object"==typeof t&&"length"in t?t:Array.from(t)}(t)).length))return 0;var e,r,i,o,a,u,c,f,s,l,h;if((e=t[0]).x=0,e.y=0,!(o>1))return e.r;if(r=t[1],e.x=-r.r,r.x=e.r,r.y=0,!(o>2))return e.r+r.r;gp(r,e,i=t[2]),e=new _p(e),r=new _p(r),i=new _p(i),e.next=i.previous=r,r.next=e.previous=i,i.next=r.previous=e;t:for(c=3;c1&&!zp(t,n););return t.slice(0,n)}function zp(t,n){if("/"===t[n]){let e=0;for(;n>0&&"\\"===t[--n];)++e;if(!(1&e))return!0}return!1}function $p(t,n){return t.parent===n.parent?1:2}function Dp(t){var n=t.children;return n?n[0]:t.t}function Rp(t){var n=t.children;return n?n[n.length-1]:t.t}function Fp(t,n,e){var r=e/(n.i-t.i);n.c-=r,n.s+=e,t.c+=r,n.z+=e,n.m+=e}function qp(t,n,e){return t.a.parent===n.parent?t.a:e}function Up(t,n){this._=t,this.parent=null,this.children=null,this.A=null,this.a=this,this.z=0,this.m=0,this.c=0,this.s=0,this.t=null,this.i=n}function Ip(t,n,e,r,i){for(var o,a=t.children,u=-1,c=a.length,f=t.value&&(i-e)/t.value;++uh&&(h=u),y=s*s*g,(d=Math.max(h/y,y/l))>p){s-=u;break}p=d}v.push(a={value:s,dice:c1?n:1)},e}(Op);var Lp=function t(n){function e(t,e,r,i,o){if((a=t._squarify)&&a.ratio===n)for(var a,u,c,f,s,l=-1,h=a.length,d=t.value;++l1?n:1)},e}(Op);function jp(t,n,e){return(n[0]-t[0])*(e[1]-t[1])-(n[1]-t[1])*(e[0]-t[0])}function Hp(t,n){return t[0]-n[0]||t[1]-n[1]}function Xp(t){const n=t.length,e=[0,1];let r,i=2;for(r=2;r1&&jp(t[e[i-2]],t[e[i-1]],t[r])<=0;)--i;e[i++]=r}return e.slice(0,i)}var Gp=Math.random,Vp=function t(n){function e(t,e){return t=null==t?0:+t,e=null==e?1:+e,1===arguments.length?(e=t,t=0):e-=t,function(){return n()*e+t}}return e.source=t,e}(Gp),Wp=function t(n){function e(t,e){return arguments.length<2&&(e=t,t=0),t=Math.floor(t),e=Math.floor(e)-t,function(){return Math.floor(n()*e+t)}}return e.source=t,e}(Gp),Zp=function t(n){function e(t,e){var r,i;return t=null==t?0:+t,e=null==e?1:+e,function(){var o;if(null!=r)o=r,r=null;else do{r=2*n()-1,o=2*n()-1,i=r*r+o*o}while(!i||i>1);return t+e*o*Math.sqrt(-2*Math.log(i)/i)}}return e.source=t,e}(Gp),Kp=function t(n){var e=Zp.source(n);function r(){var t=e.apply(this,arguments);return function(){return Math.exp(t())}}return r.source=t,r}(Gp),Qp=function t(n){function e(t){return(t=+t)<=0?()=>0:function(){for(var e=0,r=t;r>1;--r)e+=n();return e+r*n()}}return e.source=t,e}(Gp),Jp=function t(n){var e=Qp.source(n);function r(t){if(0==(t=+t))return n;var r=e(t);return function(){return r()/t}}return r.source=t,r}(Gp),tg=function t(n){function e(t){return function(){return-Math.log1p(-n())/t}}return e.source=t,e}(Gp),ng=function t(n){function e(t){if((t=+t)<0)throw new RangeError("invalid alpha");return t=1/-t,function(){return Math.pow(1-n(),t)}}return e.source=t,e}(Gp),eg=function t(n){function e(t){if((t=+t)<0||t>1)throw new RangeError("invalid p");return function(){return Math.floor(n()+t)}}return e.source=t,e}(Gp),rg=function t(n){function e(t){if((t=+t)<0||t>1)throw new RangeError("invalid p");return 0===t?()=>1/0:1===t?()=>1:(t=Math.log1p(-t),function(){return 1+Math.floor(Math.log1p(-n())/t)})}return e.source=t,e}(Gp),ig=function t(n){var e=Zp.source(n)();function r(t,r){if((t=+t)<0)throw new RangeError("invalid k");if(0===t)return()=>0;if(r=null==r?1:+r,1===t)return()=>-Math.log1p(-n())*r;var i=(t<1?t+1:t)-1/3,o=1/(3*Math.sqrt(i)),a=t<1?()=>Math.pow(n(),1/t):()=>1;return function(){do{do{var t=e(),u=1+o*t}while(u<=0);u*=u*u;var c=1-n()}while(c>=1-.0331*t*t*t*t&&Math.log(c)>=.5*t*t+i*(1-u+Math.log(u)));return i*u*a()*r}}return r.source=t,r}(Gp),og=function t(n){var e=ig.source(n);function r(t,n){var r=e(t),i=e(n);return function(){var t=r();return 0===t?0:t/(t+i())}}return r.source=t,r}(Gp),ag=function t(n){var e=rg.source(n),r=og.source(n);function i(t,n){return t=+t,(n=+n)>=1?()=>t:n<=0?()=>0:function(){for(var i=0,o=t,a=n;o*a>16&&o*(1-a)>16;){var u=Math.floor((o+1)*a),c=r(u,o-u+1)();c<=a?(i+=u,o-=u,a=(a-c)/(1-c)):(o=u-1,a/=c)}for(var f=a<.5,s=e(f?a:1-a),l=s(),h=0;l<=o;++h)l+=s();return i+(f?h:o-h)}}return i.source=t,i}(Gp),ug=function t(n){function e(t,e,r){var i;return 0==(t=+t)?i=t=>-Math.log(t):(t=1/t,i=n=>Math.pow(n,t)),e=null==e?0:+e,r=null==r?1:+r,function(){return e+r*i(-Math.log1p(-n()))}}return e.source=t,e}(Gp),cg=function t(n){function e(t,e){return t=null==t?0:+t,e=null==e?1:+e,function(){return t+e*Math.tan(Math.PI*n())}}return e.source=t,e}(Gp),fg=function t(n){function e(t,e){return t=null==t?0:+t,e=null==e?1:+e,function(){var r=n();return t+e*Math.log(r/(1-r))}}return e.source=t,e}(Gp),sg=function t(n){var e=ig.source(n),r=ag.source(n);function i(t){return function(){for(var i=0,o=t;o>16;){var a=Math.floor(.875*o),u=e(a)();if(u>o)return i+r(a-1,o/u)();i+=a,o-=u}for(var c=-Math.log1p(-n()),f=0;c<=o;++f)c-=Math.log1p(-n());return i+f}}return i.source=t,i}(Gp);const lg=1/4294967296;function hg(t,n){switch(arguments.length){case 0:break;case 1:this.range(t);break;default:this.range(n).domain(t)}return this}function dg(t,n){switch(arguments.length){case 0:break;case 1:"function"==typeof t?this.interpolator(t):this.range(t);break;default:this.domain(t),"function"==typeof n?this.interpolator(n):this.range(n)}return this}const pg=Symbol("implicit");function gg(){var t=new InternMap,n=[],e=[],r=pg;function i(i){let o=t.get(i);if(void 0===o){if(r!==pg)return r;t.set(i,o=n.push(i)-1)}return e[o%e.length]}return i.domain=function(e){if(!arguments.length)return n.slice();n=[],t=new InternMap;for(const r of e)t.has(r)||t.set(r,n.push(r)-1);return i},i.range=function(t){return arguments.length?(e=Array.from(t),i):e.slice()},i.unknown=function(t){return arguments.length?(r=t,i):r},i.copy=function(){return gg(n,e).unknown(r)},hg.apply(i,arguments),i}function yg(){var t,n,e=gg().unknown(void 0),r=e.domain,i=e.range,o=0,a=1,u=!1,c=0,f=0,s=.5;function l(){var e=r().length,l=an&&(e=t,t=n,n=e),function(e){return Math.max(t,Math.min(n,e))}}(a[0],a[t-1])),r=t>2?Mg:wg,i=o=null,l}function l(n){return null==n||isNaN(n=+n)?e:(i||(i=r(a.map(t),u,c)))(t(f(n)))}return l.invert=function(e){return f(n((o||(o=r(u,a.map(t),Yr)))(e)))},l.domain=function(t){return arguments.length?(a=Array.from(t,_g),s()):a.slice()},l.range=function(t){return arguments.length?(u=Array.from(t),s()):u.slice()},l.rangeRound=function(t){return u=Array.from(t),c=Vr,s()},l.clamp=function(t){return arguments.length?(f=!!t||mg,s()):f!==mg},l.interpolate=function(t){return arguments.length?(c=t,s()):c},l.unknown=function(t){return arguments.length?(e=t,l):e},function(e,r){return t=e,n=r,s()}}function Sg(){return Ag()(mg,mg)}function Eg(n,e,r,i){var o,a=W(n,e,r);switch((i=Jc(null==i?",f":i)).type){case"s":var u=Math.max(Math.abs(n),Math.abs(e));return null!=i.precision||isNaN(o=lf(a,u))||(i.precision=o),t.formatPrefix(i,u);case"":case"e":case"g":case"p":case"r":null!=i.precision||isNaN(o=hf(a,Math.max(Math.abs(n),Math.abs(e))))||(i.precision=o-("e"===i.type));break;case"f":case"%":null!=i.precision||isNaN(o=sf(a))||(i.precision=o-2*("%"===i.type))}return t.format(i)}function Ng(t){var n=t.domain;return t.ticks=function(t){var e=n();return G(e[0],e[e.length-1],null==t?10:t)},t.tickFormat=function(t,e){var r=n();return Eg(r[0],r[r.length-1],null==t?10:t,e)},t.nice=function(e){null==e&&(e=10);var r,i,o=n(),a=0,u=o.length-1,c=o[a],f=o[u],s=10;for(f0;){if((i=V(c,f,e))===r)return o[a]=c,o[u]=f,n(o);if(i>0)c=Math.floor(c/i)*i,f=Math.ceil(f/i)*i;else{if(!(i<0))break;c=Math.ceil(c*i)/i,f=Math.floor(f*i)/i}r=i}return t},t}function kg(t,n){var e,r=0,i=(t=t.slice()).length-1,o=t[r],a=t[i];return a-t(-n,e)}function Fg(n){const e=n(Cg,Pg),r=e.domain;let i,o,a=10;function u(){return i=function(t){return t===Math.E?Math.log:10===t&&Math.log10||2===t&&Math.log2||(t=Math.log(t),n=>Math.log(n)/t)}(a),o=function(t){return 10===t?Dg:t===Math.E?Math.exp:n=>Math.pow(t,n)}(a),r()[0]<0?(i=Rg(i),o=Rg(o),n(zg,$g)):n(Cg,Pg),e}return e.base=function(t){return arguments.length?(a=+t,u()):a},e.domain=function(t){return arguments.length?(r(t),u()):r()},e.ticks=t=>{const n=r();let e=n[0],u=n[n.length-1];const c=u0){for(;l<=h;++l)for(f=1;fu)break;p.push(s)}}else for(;l<=h;++l)for(f=a-1;f>=1;--f)if(s=l>0?f/o(-l):f*o(l),!(su)break;p.push(s)}2*p.length{if(null==n&&(n=10),null==r&&(r=10===a?"s":","),"function"!=typeof r&&(a%1||null!=(r=Jc(r)).precision||(r.trim=!0),r=t.format(r)),n===1/0)return r;const u=Math.max(1,a*n/e.ticks().length);return t=>{let n=t/o(Math.round(i(t)));return n*ar(kg(r(),{floor:t=>o(Math.floor(i(t))),ceil:t=>o(Math.ceil(i(t)))})),e}function qg(t){return function(n){return Math.sign(n)*Math.log1p(Math.abs(n/t))}}function Ug(t){return function(n){return Math.sign(n)*Math.expm1(Math.abs(n))*t}}function Ig(t){var n=1,e=t(qg(n),Ug(n));return e.constant=function(e){return arguments.length?t(qg(n=+e),Ug(n)):n},Ng(e)}function Og(t){return function(n){return n<0?-Math.pow(-n,t):Math.pow(n,t)}}function Bg(t){return t<0?-Math.sqrt(-t):Math.sqrt(t)}function Yg(t){return t<0?-t*t:t*t}function Lg(t){var n=t(mg,mg),e=1;return n.exponent=function(n){return arguments.length?1===(e=+n)?t(mg,mg):.5===e?t(Bg,Yg):t(Og(e),Og(1/e)):e},Ng(n)}function jg(){var t=Lg(Ag());return t.copy=function(){return Tg(t,jg()).exponent(t.exponent())},hg.apply(t,arguments),t}function Hg(t){return Math.sign(t)*t*t}const Xg=new Date,Gg=new Date;function Vg(t,n,e,r){function i(n){return t(n=0===arguments.length?new Date:new Date(+n)),n}return i.floor=n=>(t(n=new Date(+n)),n),i.ceil=e=>(t(e=new Date(e-1)),n(e,1),t(e),e),i.round=t=>{const n=i(t),e=i.ceil(t);return t-n(n(t=new Date(+t),null==e?1:Math.floor(e)),t),i.range=(e,r,o)=>{const a=[];if(e=i.ceil(e),o=null==o?1:Math.floor(o),!(e0))return a;let u;do{a.push(u=new Date(+e)),n(e,o),t(e)}while(uVg((n=>{if(n>=n)for(;t(n),!e(n);)n.setTime(n-1)}),((t,r)=>{if(t>=t)if(r<0)for(;++r<=0;)for(;n(t,-1),!e(t););else for(;--r>=0;)for(;n(t,1),!e(t););})),e&&(i.count=(n,r)=>(Xg.setTime(+n),Gg.setTime(+r),t(Xg),t(Gg),Math.floor(e(Xg,Gg))),i.every=t=>(t=Math.floor(t),isFinite(t)&&t>0?t>1?i.filter(r?n=>r(n)%t==0:n=>i.count(0,n)%t==0):i:null)),i}const Wg=Vg((()=>{}),((t,n)=>{t.setTime(+t+n)}),((t,n)=>n-t));Wg.every=t=>(t=Math.floor(t),isFinite(t)&&t>0?t>1?Vg((n=>{n.setTime(Math.floor(n/t)*t)}),((n,e)=>{n.setTime(+n+e*t)}),((n,e)=>(e-n)/t)):Wg:null);const Zg=Wg.range,Kg=1e3,Qg=6e4,Jg=36e5,ty=864e5,ny=6048e5,ey=2592e6,ry=31536e6,iy=Vg((t=>{t.setTime(t-t.getMilliseconds())}),((t,n)=>{t.setTime(+t+n*Kg)}),((t,n)=>(n-t)/Kg),(t=>t.getUTCSeconds())),oy=iy.range,ay=Vg((t=>{t.setTime(t-t.getMilliseconds()-t.getSeconds()*Kg)}),((t,n)=>{t.setTime(+t+n*Qg)}),((t,n)=>(n-t)/Qg),(t=>t.getMinutes())),uy=ay.range,cy=Vg((t=>{t.setUTCSeconds(0,0)}),((t,n)=>{t.setTime(+t+n*Qg)}),((t,n)=>(n-t)/Qg),(t=>t.getUTCMinutes())),fy=cy.range,sy=Vg((t=>{t.setTime(t-t.getMilliseconds()-t.getSeconds()*Kg-t.getMinutes()*Qg)}),((t,n)=>{t.setTime(+t+n*Jg)}),((t,n)=>(n-t)/Jg),(t=>t.getHours())),ly=sy.range,hy=Vg((t=>{t.setUTCMinutes(0,0,0)}),((t,n)=>{t.setTime(+t+n*Jg)}),((t,n)=>(n-t)/Jg),(t=>t.getUTCHours())),dy=hy.range,py=Vg((t=>t.setHours(0,0,0,0)),((t,n)=>t.setDate(t.getDate()+n)),((t,n)=>(n-t-(n.getTimezoneOffset()-t.getTimezoneOffset())*Qg)/ty),(t=>t.getDate()-1)),gy=py.range,yy=Vg((t=>{t.setUTCHours(0,0,0,0)}),((t,n)=>{t.setUTCDate(t.getUTCDate()+n)}),((t,n)=>(n-t)/ty),(t=>t.getUTCDate()-1)),vy=yy.range,_y=Vg((t=>{t.setUTCHours(0,0,0,0)}),((t,n)=>{t.setUTCDate(t.getUTCDate()+n)}),((t,n)=>(n-t)/ty),(t=>Math.floor(t/ty))),by=_y.range;function my(t){return Vg((n=>{n.setDate(n.getDate()-(n.getDay()+7-t)%7),n.setHours(0,0,0,0)}),((t,n)=>{t.setDate(t.getDate()+7*n)}),((t,n)=>(n-t-(n.getTimezoneOffset()-t.getTimezoneOffset())*Qg)/ny))}const xy=my(0),wy=my(1),My=my(2),Ty=my(3),Ay=my(4),Sy=my(5),Ey=my(6),Ny=xy.range,ky=wy.range,Cy=My.range,Py=Ty.range,zy=Ay.range,$y=Sy.range,Dy=Ey.range;function Ry(t){return Vg((n=>{n.setUTCDate(n.getUTCDate()-(n.getUTCDay()+7-t)%7),n.setUTCHours(0,0,0,0)}),((t,n)=>{t.setUTCDate(t.getUTCDate()+7*n)}),((t,n)=>(n-t)/ny))}const Fy=Ry(0),qy=Ry(1),Uy=Ry(2),Iy=Ry(3),Oy=Ry(4),By=Ry(5),Yy=Ry(6),Ly=Fy.range,jy=qy.range,Hy=Uy.range,Xy=Iy.range,Gy=Oy.range,Vy=By.range,Wy=Yy.range,Zy=Vg((t=>{t.setDate(1),t.setHours(0,0,0,0)}),((t,n)=>{t.setMonth(t.getMonth()+n)}),((t,n)=>n.getMonth()-t.getMonth()+12*(n.getFullYear()-t.getFullYear())),(t=>t.getMonth())),Ky=Zy.range,Qy=Vg((t=>{t.setUTCDate(1),t.setUTCHours(0,0,0,0)}),((t,n)=>{t.setUTCMonth(t.getUTCMonth()+n)}),((t,n)=>n.getUTCMonth()-t.getUTCMonth()+12*(n.getUTCFullYear()-t.getUTCFullYear())),(t=>t.getUTCMonth())),Jy=Qy.range,tv=Vg((t=>{t.setMonth(0,1),t.setHours(0,0,0,0)}),((t,n)=>{t.setFullYear(t.getFullYear()+n)}),((t,n)=>n.getFullYear()-t.getFullYear()),(t=>t.getFullYear()));tv.every=t=>isFinite(t=Math.floor(t))&&t>0?Vg((n=>{n.setFullYear(Math.floor(n.getFullYear()/t)*t),n.setMonth(0,1),n.setHours(0,0,0,0)}),((n,e)=>{n.setFullYear(n.getFullYear()+e*t)})):null;const nv=tv.range,ev=Vg((t=>{t.setUTCMonth(0,1),t.setUTCHours(0,0,0,0)}),((t,n)=>{t.setUTCFullYear(t.getUTCFullYear()+n)}),((t,n)=>n.getUTCFullYear()-t.getUTCFullYear()),(t=>t.getUTCFullYear()));ev.every=t=>isFinite(t=Math.floor(t))&&t>0?Vg((n=>{n.setUTCFullYear(Math.floor(n.getUTCFullYear()/t)*t),n.setUTCMonth(0,1),n.setUTCHours(0,0,0,0)}),((n,e)=>{n.setUTCFullYear(n.getUTCFullYear()+e*t)})):null;const rv=ev.range;function iv(t,n,e,i,o,a){const u=[[iy,1,Kg],[iy,5,5e3],[iy,15,15e3],[iy,30,3e4],[a,1,Qg],[a,5,3e5],[a,15,9e5],[a,30,18e5],[o,1,Jg],[o,3,108e5],[o,6,216e5],[o,12,432e5],[i,1,ty],[i,2,1728e5],[e,1,ny],[n,1,ey],[n,3,7776e6],[t,1,ry]];function c(n,e,i){const o=Math.abs(e-n)/i,a=r((([,,t])=>t)).right(u,o);if(a===u.length)return t.every(W(n/ry,e/ry,i));if(0===a)return Wg.every(Math.max(W(n,e,i),1));const[c,f]=u[o/u[a-1][2]=12)]},q:function(t){return 1+~~(t.getMonth()/3)},Q:k_,s:C_,S:Zv,u:Kv,U:Qv,V:t_,w:n_,W:e_,x:null,X:null,y:r_,Y:o_,Z:u_,"%":N_},m={a:function(t){return a[t.getUTCDay()]},A:function(t){return o[t.getUTCDay()]},b:function(t){return c[t.getUTCMonth()]},B:function(t){return u[t.getUTCMonth()]},c:null,d:c_,e:c_,f:d_,g:T_,G:S_,H:f_,I:s_,j:l_,L:h_,m:p_,M:g_,p:function(t){return i[+(t.getUTCHours()>=12)]},q:function(t){return 1+~~(t.getUTCMonth()/3)},Q:k_,s:C_,S:y_,u:v_,U:__,V:m_,w:x_,W:w_,x:null,X:null,y:M_,Y:A_,Z:E_,"%":N_},x={a:function(t,n,e){var r=d.exec(n.slice(e));return r?(t.w=p.get(r[0].toLowerCase()),e+r[0].length):-1},A:function(t,n,e){var r=l.exec(n.slice(e));return r?(t.w=h.get(r[0].toLowerCase()),e+r[0].length):-1},b:function(t,n,e){var r=v.exec(n.slice(e));return r?(t.m=_.get(r[0].toLowerCase()),e+r[0].length):-1},B:function(t,n,e){var r=g.exec(n.slice(e));return r?(t.m=y.get(r[0].toLowerCase()),e+r[0].length):-1},c:function(t,e,r){return T(t,n,e,r)},d:zv,e:zv,f:Uv,g:Nv,G:Ev,H:Dv,I:Dv,j:$v,L:qv,m:Pv,M:Rv,p:function(t,n,e){var r=f.exec(n.slice(e));return r?(t.p=s.get(r[0].toLowerCase()),e+r[0].length):-1},q:Cv,Q:Ov,s:Bv,S:Fv,u:Mv,U:Tv,V:Av,w:wv,W:Sv,x:function(t,n,r){return T(t,e,n,r)},X:function(t,n,e){return T(t,r,n,e)},y:Nv,Y:Ev,Z:kv,"%":Iv};function w(t,n){return function(e){var r,i,o,a=[],u=-1,c=0,f=t.length;for(e instanceof Date||(e=new Date(+e));++u53)return null;"w"in o||(o.w=1),"Z"in o?(i=(r=sv(lv(o.y,0,1))).getUTCDay(),r=i>4||0===i?qy.ceil(r):qy(r),r=yy.offset(r,7*(o.V-1)),o.y=r.getUTCFullYear(),o.m=r.getUTCMonth(),o.d=r.getUTCDate()+(o.w+6)%7):(i=(r=fv(lv(o.y,0,1))).getDay(),r=i>4||0===i?wy.ceil(r):wy(r),r=py.offset(r,7*(o.V-1)),o.y=r.getFullYear(),o.m=r.getMonth(),o.d=r.getDate()+(o.w+6)%7)}else("W"in o||"U"in o)&&("w"in o||(o.w="u"in o?o.u%7:"W"in o?1:0),i="Z"in o?sv(lv(o.y,0,1)).getUTCDay():fv(lv(o.y,0,1)).getDay(),o.m=0,o.d="W"in o?(o.w+6)%7+7*o.W-(i+5)%7:o.w+7*o.U-(i+6)%7);return"Z"in o?(o.H+=o.Z/100|0,o.M+=o.Z%100,sv(o)):fv(o)}}function T(t,n,e,r){for(var i,o,a=0,u=n.length,c=e.length;a=c)return-1;if(37===(i=n.charCodeAt(a++))){if(i=n.charAt(a++),!(o=x[i in pv?n.charAt(a++):i])||(r=o(t,e,r))<0)return-1}else if(i!=e.charCodeAt(r++))return-1}return r}return b.x=w(e,b),b.X=w(r,b),b.c=w(n,b),m.x=w(e,m),m.X=w(r,m),m.c=w(n,m),{format:function(t){var n=w(t+="",b);return n.toString=function(){return t},n},parse:function(t){var n=M(t+="",!1);return n.toString=function(){return t},n},utcFormat:function(t){var n=w(t+="",m);return n.toString=function(){return t},n},utcParse:function(t){var n=M(t+="",!0);return n.toString=function(){return t},n}}}var dv,pv={"-":"",_:" ",0:"0"},gv=/^\s*\d+/,yv=/^%/,vv=/[\\^$*+?|[\]().{}]/g;function _v(t,n,e){var r=t<0?"-":"",i=(r?-t:t)+"",o=i.length;return r+(o[t.toLowerCase(),n])))}function wv(t,n,e){var r=gv.exec(n.slice(e,e+1));return r?(t.w=+r[0],e+r[0].length):-1}function Mv(t,n,e){var r=gv.exec(n.slice(e,e+1));return r?(t.u=+r[0],e+r[0].length):-1}function Tv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.U=+r[0],e+r[0].length):-1}function Av(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.V=+r[0],e+r[0].length):-1}function Sv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.W=+r[0],e+r[0].length):-1}function Ev(t,n,e){var r=gv.exec(n.slice(e,e+4));return r?(t.y=+r[0],e+r[0].length):-1}function Nv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.y=+r[0]+(+r[0]>68?1900:2e3),e+r[0].length):-1}function kv(t,n,e){var r=/^(Z)|([+-]\d\d)(?::?(\d\d))?/.exec(n.slice(e,e+6));return r?(t.Z=r[1]?0:-(r[2]+(r[3]||"00")),e+r[0].length):-1}function Cv(t,n,e){var r=gv.exec(n.slice(e,e+1));return r?(t.q=3*r[0]-3,e+r[0].length):-1}function Pv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.m=r[0]-1,e+r[0].length):-1}function zv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.d=+r[0],e+r[0].length):-1}function $v(t,n,e){var r=gv.exec(n.slice(e,e+3));return r?(t.m=0,t.d=+r[0],e+r[0].length):-1}function Dv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.H=+r[0],e+r[0].length):-1}function Rv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.M=+r[0],e+r[0].length):-1}function Fv(t,n,e){var r=gv.exec(n.slice(e,e+2));return r?(t.S=+r[0],e+r[0].length):-1}function qv(t,n,e){var r=gv.exec(n.slice(e,e+3));return r?(t.L=+r[0],e+r[0].length):-1}function Uv(t,n,e){var r=gv.exec(n.slice(e,e+6));return r?(t.L=Math.floor(r[0]/1e3),e+r[0].length):-1}function Iv(t,n,e){var r=yv.exec(n.slice(e,e+1));return r?e+r[0].length:-1}function Ov(t,n,e){var r=gv.exec(n.slice(e));return r?(t.Q=+r[0],e+r[0].length):-1}function Bv(t,n,e){var r=gv.exec(n.slice(e));return r?(t.s=+r[0],e+r[0].length):-1}function Yv(t,n){return _v(t.getDate(),n,2)}function Lv(t,n){return _v(t.getHours(),n,2)}function jv(t,n){return _v(t.getHours()%12||12,n,2)}function Hv(t,n){return _v(1+py.count(tv(t),t),n,3)}function Xv(t,n){return _v(t.getMilliseconds(),n,3)}function Gv(t,n){return Xv(t,n)+"000"}function Vv(t,n){return _v(t.getMonth()+1,n,2)}function Wv(t,n){return _v(t.getMinutes(),n,2)}function Zv(t,n){return _v(t.getSeconds(),n,2)}function Kv(t){var n=t.getDay();return 0===n?7:n}function Qv(t,n){return _v(xy.count(tv(t)-1,t),n,2)}function Jv(t){var n=t.getDay();return n>=4||0===n?Ay(t):Ay.ceil(t)}function t_(t,n){return t=Jv(t),_v(Ay.count(tv(t),t)+(4===tv(t).getDay()),n,2)}function n_(t){return t.getDay()}function e_(t,n){return _v(wy.count(tv(t)-1,t),n,2)}function r_(t,n){return _v(t.getFullYear()%100,n,2)}function i_(t,n){return _v((t=Jv(t)).getFullYear()%100,n,2)}function o_(t,n){return _v(t.getFullYear()%1e4,n,4)}function a_(t,n){var e=t.getDay();return _v((t=e>=4||0===e?Ay(t):Ay.ceil(t)).getFullYear()%1e4,n,4)}function u_(t){var n=t.getTimezoneOffset();return(n>0?"-":(n*=-1,"+"))+_v(n/60|0,"0",2)+_v(n%60,"0",2)}function c_(t,n){return _v(t.getUTCDate(),n,2)}function f_(t,n){return _v(t.getUTCHours(),n,2)}function s_(t,n){return _v(t.getUTCHours()%12||12,n,2)}function l_(t,n){return _v(1+yy.count(ev(t),t),n,3)}function h_(t,n){return _v(t.getUTCMilliseconds(),n,3)}function d_(t,n){return h_(t,n)+"000"}function p_(t,n){return _v(t.getUTCMonth()+1,n,2)}function g_(t,n){return _v(t.getUTCMinutes(),n,2)}function y_(t,n){return _v(t.getUTCSeconds(),n,2)}function v_(t){var n=t.getUTCDay();return 0===n?7:n}function __(t,n){return _v(Fy.count(ev(t)-1,t),n,2)}function b_(t){var n=t.getUTCDay();return n>=4||0===n?Oy(t):Oy.ceil(t)}function m_(t,n){return t=b_(t),_v(Oy.count(ev(t),t)+(4===ev(t).getUTCDay()),n,2)}function x_(t){return t.getUTCDay()}function w_(t,n){return _v(qy.count(ev(t)-1,t),n,2)}function M_(t,n){return _v(t.getUTCFullYear()%100,n,2)}function T_(t,n){return _v((t=b_(t)).getUTCFullYear()%100,n,2)}function A_(t,n){return _v(t.getUTCFullYear()%1e4,n,4)}function S_(t,n){var e=t.getUTCDay();return _v((t=e>=4||0===e?Oy(t):Oy.ceil(t)).getUTCFullYear()%1e4,n,4)}function E_(){return"+0000"}function N_(){return"%"}function k_(t){return+t}function C_(t){return Math.floor(+t/1e3)}function P_(n){return dv=hv(n),t.timeFormat=dv.format,t.timeParse=dv.parse,t.utcFormat=dv.utcFormat,t.utcParse=dv.utcParse,dv}t.timeFormat=void 0,t.timeParse=void 0,t.utcFormat=void 0,t.utcParse=void 0,P_({dateTime:"%x, %X",date:"%-m/%-d/%Y",time:"%-I:%M:%S %p",periods:["AM","PM"],days:["Sunday","Monday","Tuesday","Wednesday","Thursday","Friday","Saturday"],shortDays:["Sun","Mon","Tue","Wed","Thu","Fri","Sat"],months:["January","February","March","April","May","June","July","August","September","October","November","December"],shortMonths:["Jan","Feb","Mar","Apr","May","Jun","Jul","Aug","Sep","Oct","Nov","Dec"]});var z_="%Y-%m-%dT%H:%M:%S.%LZ";var $_=Date.prototype.toISOString?function(t){return t.toISOString()}:t.utcFormat(z_),D_=$_;var R_=+new Date("2000-01-01T00:00:00.000Z")?function(t){var n=new Date(t);return isNaN(n)?null:n}:t.utcParse(z_),F_=R_;function q_(t){return new Date(t)}function U_(t){return t instanceof Date?+t:+new Date(+t)}function I_(t,n,e,r,i,o,a,u,c,f){var s=Sg(),l=s.invert,h=s.domain,d=f(".%L"),p=f(":%S"),g=f("%I:%M"),y=f("%I %p"),v=f("%a %d"),_=f("%b %d"),b=f("%B"),m=f("%Y");function x(t){return(c(t)Fr(t[t.length-1]),ib=new Array(3).concat("d8b365f5f5f55ab4ac","a6611adfc27d80cdc1018571","a6611adfc27df5f5f580cdc1018571","8c510ad8b365f6e8c3c7eae55ab4ac01665e","8c510ad8b365f6e8c3f5f5f5c7eae55ab4ac01665e","8c510abf812ddfc27df6e8c3c7eae580cdc135978f01665e","8c510abf812ddfc27df6e8c3f5f5f5c7eae580cdc135978f01665e","5430058c510abf812ddfc27df6e8c3c7eae580cdc135978f01665e003c30","5430058c510abf812ddfc27df6e8c3f5f5f5c7eae580cdc135978f01665e003c30").map(H_),ob=rb(ib),ab=new Array(3).concat("af8dc3f7f7f77fbf7b","7b3294c2a5cfa6dba0008837","7b3294c2a5cff7f7f7a6dba0008837","762a83af8dc3e7d4e8d9f0d37fbf7b1b7837","762a83af8dc3e7d4e8f7f7f7d9f0d37fbf7b1b7837","762a839970abc2a5cfe7d4e8d9f0d3a6dba05aae611b7837","762a839970abc2a5cfe7d4e8f7f7f7d9f0d3a6dba05aae611b7837","40004b762a839970abc2a5cfe7d4e8d9f0d3a6dba05aae611b783700441b","40004b762a839970abc2a5cfe7d4e8f7f7f7d9f0d3a6dba05aae611b783700441b").map(H_),ub=rb(ab),cb=new Array(3).concat("e9a3c9f7f7f7a1d76a","d01c8bf1b6dab8e1864dac26","d01c8bf1b6daf7f7f7b8e1864dac26","c51b7de9a3c9fde0efe6f5d0a1d76a4d9221","c51b7de9a3c9fde0eff7f7f7e6f5d0a1d76a4d9221","c51b7dde77aef1b6dafde0efe6f5d0b8e1867fbc414d9221","c51b7dde77aef1b6dafde0eff7f7f7e6f5d0b8e1867fbc414d9221","8e0152c51b7dde77aef1b6dafde0efe6f5d0b8e1867fbc414d9221276419","8e0152c51b7dde77aef1b6dafde0eff7f7f7e6f5d0b8e1867fbc414d9221276419").map(H_),fb=rb(cb),sb=new Array(3).concat("998ec3f7f7f7f1a340","5e3c99b2abd2fdb863e66101","5e3c99b2abd2f7f7f7fdb863e66101","542788998ec3d8daebfee0b6f1a340b35806","542788998ec3d8daebf7f7f7fee0b6f1a340b35806","5427888073acb2abd2d8daebfee0b6fdb863e08214b35806","5427888073acb2abd2d8daebf7f7f7fee0b6fdb863e08214b35806","2d004b5427888073acb2abd2d8daebfee0b6fdb863e08214b358067f3b08","2d004b5427888073acb2abd2d8daebf7f7f7fee0b6fdb863e08214b358067f3b08").map(H_),lb=rb(sb),hb=new Array(3).concat("ef8a62f7f7f767a9cf","ca0020f4a58292c5de0571b0","ca0020f4a582f7f7f792c5de0571b0","b2182bef8a62fddbc7d1e5f067a9cf2166ac","b2182bef8a62fddbc7f7f7f7d1e5f067a9cf2166ac","b2182bd6604df4a582fddbc7d1e5f092c5de4393c32166ac","b2182bd6604df4a582fddbc7f7f7f7d1e5f092c5de4393c32166ac","67001fb2182bd6604df4a582fddbc7d1e5f092c5de4393c32166ac053061","67001fb2182bd6604df4a582fddbc7f7f7f7d1e5f092c5de4393c32166ac053061").map(H_),db=rb(hb),pb=new Array(3).concat("ef8a62ffffff999999","ca0020f4a582bababa404040","ca0020f4a582ffffffbababa404040","b2182bef8a62fddbc7e0e0e09999994d4d4d","b2182bef8a62fddbc7ffffffe0e0e09999994d4d4d","b2182bd6604df4a582fddbc7e0e0e0bababa8787874d4d4d","b2182bd6604df4a582fddbc7ffffffe0e0e0bababa8787874d4d4d","67001fb2182bd6604df4a582fddbc7e0e0e0bababa8787874d4d4d1a1a1a","67001fb2182bd6604df4a582fddbc7ffffffe0e0e0bababa8787874d4d4d1a1a1a").map(H_),gb=rb(pb),yb=new Array(3).concat("fc8d59ffffbf91bfdb","d7191cfdae61abd9e92c7bb6","d7191cfdae61ffffbfabd9e92c7bb6","d73027fc8d59fee090e0f3f891bfdb4575b4","d73027fc8d59fee090ffffbfe0f3f891bfdb4575b4","d73027f46d43fdae61fee090e0f3f8abd9e974add14575b4","d73027f46d43fdae61fee090ffffbfe0f3f8abd9e974add14575b4","a50026d73027f46d43fdae61fee090e0f3f8abd9e974add14575b4313695","a50026d73027f46d43fdae61fee090ffffbfe0f3f8abd9e974add14575b4313695").map(H_),vb=rb(yb),_b=new Array(3).concat("fc8d59ffffbf91cf60","d7191cfdae61a6d96a1a9641","d7191cfdae61ffffbfa6d96a1a9641","d73027fc8d59fee08bd9ef8b91cf601a9850","d73027fc8d59fee08bffffbfd9ef8b91cf601a9850","d73027f46d43fdae61fee08bd9ef8ba6d96a66bd631a9850","d73027f46d43fdae61fee08bffffbfd9ef8ba6d96a66bd631a9850","a50026d73027f46d43fdae61fee08bd9ef8ba6d96a66bd631a9850006837","a50026d73027f46d43fdae61fee08bffffbfd9ef8ba6d96a66bd631a9850006837").map(H_),bb=rb(_b),mb=new Array(3).concat("fc8d59ffffbf99d594","d7191cfdae61abdda42b83ba","d7191cfdae61ffffbfabdda42b83ba","d53e4ffc8d59fee08be6f59899d5943288bd","d53e4ffc8d59fee08bffffbfe6f59899d5943288bd","d53e4ff46d43fdae61fee08be6f598abdda466c2a53288bd","d53e4ff46d43fdae61fee08bffffbfe6f598abdda466c2a53288bd","9e0142d53e4ff46d43fdae61fee08be6f598abdda466c2a53288bd5e4fa2","9e0142d53e4ff46d43fdae61fee08bffffbfe6f598abdda466c2a53288bd5e4fa2").map(H_),xb=rb(mb),wb=new Array(3).concat("e5f5f999d8c92ca25f","edf8fbb2e2e266c2a4238b45","edf8fbb2e2e266c2a42ca25f006d2c","edf8fbccece699d8c966c2a42ca25f006d2c","edf8fbccece699d8c966c2a441ae76238b45005824","f7fcfde5f5f9ccece699d8c966c2a441ae76238b45005824","f7fcfde5f5f9ccece699d8c966c2a441ae76238b45006d2c00441b").map(H_),Mb=rb(wb),Tb=new Array(3).concat("e0ecf49ebcda8856a7","edf8fbb3cde38c96c688419d","edf8fbb3cde38c96c68856a7810f7c","edf8fbbfd3e69ebcda8c96c68856a7810f7c","edf8fbbfd3e69ebcda8c96c68c6bb188419d6e016b","f7fcfde0ecf4bfd3e69ebcda8c96c68c6bb188419d6e016b","f7fcfde0ecf4bfd3e69ebcda8c96c68c6bb188419d810f7c4d004b").map(H_),Ab=rb(Tb),Sb=new Array(3).concat("e0f3dba8ddb543a2ca","f0f9e8bae4bc7bccc42b8cbe","f0f9e8bae4bc7bccc443a2ca0868ac","f0f9e8ccebc5a8ddb57bccc443a2ca0868ac","f0f9e8ccebc5a8ddb57bccc44eb3d32b8cbe08589e","f7fcf0e0f3dbccebc5a8ddb57bccc44eb3d32b8cbe08589e","f7fcf0e0f3dbccebc5a8ddb57bccc44eb3d32b8cbe0868ac084081").map(H_),Eb=rb(Sb),Nb=new Array(3).concat("fee8c8fdbb84e34a33","fef0d9fdcc8afc8d59d7301f","fef0d9fdcc8afc8d59e34a33b30000","fef0d9fdd49efdbb84fc8d59e34a33b30000","fef0d9fdd49efdbb84fc8d59ef6548d7301f990000","fff7ecfee8c8fdd49efdbb84fc8d59ef6548d7301f990000","fff7ecfee8c8fdd49efdbb84fc8d59ef6548d7301fb300007f0000").map(H_),kb=rb(Nb),Cb=new Array(3).concat("ece2f0a6bddb1c9099","f6eff7bdc9e167a9cf02818a","f6eff7bdc9e167a9cf1c9099016c59","f6eff7d0d1e6a6bddb67a9cf1c9099016c59","f6eff7d0d1e6a6bddb67a9cf3690c002818a016450","fff7fbece2f0d0d1e6a6bddb67a9cf3690c002818a016450","fff7fbece2f0d0d1e6a6bddb67a9cf3690c002818a016c59014636").map(H_),Pb=rb(Cb),zb=new Array(3).concat("ece7f2a6bddb2b8cbe","f1eef6bdc9e174a9cf0570b0","f1eef6bdc9e174a9cf2b8cbe045a8d","f1eef6d0d1e6a6bddb74a9cf2b8cbe045a8d","f1eef6d0d1e6a6bddb74a9cf3690c00570b0034e7b","fff7fbece7f2d0d1e6a6bddb74a9cf3690c00570b0034e7b","fff7fbece7f2d0d1e6a6bddb74a9cf3690c00570b0045a8d023858").map(H_),$b=rb(zb),Db=new Array(3).concat("e7e1efc994c7dd1c77","f1eef6d7b5d8df65b0ce1256","f1eef6d7b5d8df65b0dd1c77980043","f1eef6d4b9dac994c7df65b0dd1c77980043","f1eef6d4b9dac994c7df65b0e7298ace125691003f","f7f4f9e7e1efd4b9dac994c7df65b0e7298ace125691003f","f7f4f9e7e1efd4b9dac994c7df65b0e7298ace125698004367001f").map(H_),Rb=rb(Db),Fb=new Array(3).concat("fde0ddfa9fb5c51b8a","feebe2fbb4b9f768a1ae017e","feebe2fbb4b9f768a1c51b8a7a0177","feebe2fcc5c0fa9fb5f768a1c51b8a7a0177","feebe2fcc5c0fa9fb5f768a1dd3497ae017e7a0177","fff7f3fde0ddfcc5c0fa9fb5f768a1dd3497ae017e7a0177","fff7f3fde0ddfcc5c0fa9fb5f768a1dd3497ae017e7a017749006a").map(H_),qb=rb(Fb),Ub=new Array(3).concat("edf8b17fcdbb2c7fb8","ffffcca1dab441b6c4225ea8","ffffcca1dab441b6c42c7fb8253494","ffffccc7e9b47fcdbb41b6c42c7fb8253494","ffffccc7e9b47fcdbb41b6c41d91c0225ea80c2c84","ffffd9edf8b1c7e9b47fcdbb41b6c41d91c0225ea80c2c84","ffffd9edf8b1c7e9b47fcdbb41b6c41d91c0225ea8253494081d58").map(H_),Ib=rb(Ub),Ob=new Array(3).concat("f7fcb9addd8e31a354","ffffccc2e69978c679238443","ffffccc2e69978c67931a354006837","ffffccd9f0a3addd8e78c67931a354006837","ffffccd9f0a3addd8e78c67941ab5d238443005a32","ffffe5f7fcb9d9f0a3addd8e78c67941ab5d238443005a32","ffffe5f7fcb9d9f0a3addd8e78c67941ab5d238443006837004529").map(H_),Bb=rb(Ob),Yb=new Array(3).concat("fff7bcfec44fd95f0e","ffffd4fed98efe9929cc4c02","ffffd4fed98efe9929d95f0e993404","ffffd4fee391fec44ffe9929d95f0e993404","ffffd4fee391fec44ffe9929ec7014cc4c028c2d04","ffffe5fff7bcfee391fec44ffe9929ec7014cc4c028c2d04","ffffe5fff7bcfee391fec44ffe9929ec7014cc4c02993404662506").map(H_),Lb=rb(Yb),jb=new Array(3).concat("ffeda0feb24cf03b20","ffffb2fecc5cfd8d3ce31a1c","ffffb2fecc5cfd8d3cf03b20bd0026","ffffb2fed976feb24cfd8d3cf03b20bd0026","ffffb2fed976feb24cfd8d3cfc4e2ae31a1cb10026","ffffccffeda0fed976feb24cfd8d3cfc4e2ae31a1cb10026","ffffccffeda0fed976feb24cfd8d3cfc4e2ae31a1cbd0026800026").map(H_),Hb=rb(jb),Xb=new Array(3).concat("deebf79ecae13182bd","eff3ffbdd7e76baed62171b5","eff3ffbdd7e76baed63182bd08519c","eff3ffc6dbef9ecae16baed63182bd08519c","eff3ffc6dbef9ecae16baed64292c62171b5084594","f7fbffdeebf7c6dbef9ecae16baed64292c62171b5084594","f7fbffdeebf7c6dbef9ecae16baed64292c62171b508519c08306b").map(H_),Gb=rb(Xb),Vb=new Array(3).concat("e5f5e0a1d99b31a354","edf8e9bae4b374c476238b45","edf8e9bae4b374c47631a354006d2c","edf8e9c7e9c0a1d99b74c47631a354006d2c","edf8e9c7e9c0a1d99b74c47641ab5d238b45005a32","f7fcf5e5f5e0c7e9c0a1d99b74c47641ab5d238b45005a32","f7fcf5e5f5e0c7e9c0a1d99b74c47641ab5d238b45006d2c00441b").map(H_),Wb=rb(Vb),Zb=new Array(3).concat("f0f0f0bdbdbd636363","f7f7f7cccccc969696525252","f7f7f7cccccc969696636363252525","f7f7f7d9d9d9bdbdbd969696636363252525","f7f7f7d9d9d9bdbdbd969696737373525252252525","fffffff0f0f0d9d9d9bdbdbd969696737373525252252525","fffffff0f0f0d9d9d9bdbdbd969696737373525252252525000000").map(H_),Kb=rb(Zb),Qb=new Array(3).concat("efedf5bcbddc756bb1","f2f0f7cbc9e29e9ac86a51a3","f2f0f7cbc9e29e9ac8756bb154278f","f2f0f7dadaebbcbddc9e9ac8756bb154278f","f2f0f7dadaebbcbddc9e9ac8807dba6a51a34a1486","fcfbfdefedf5dadaebbcbddc9e9ac8807dba6a51a34a1486","fcfbfdefedf5dadaebbcbddc9e9ac8807dba6a51a354278f3f007d").map(H_),Jb=rb(Qb),tm=new Array(3).concat("fee0d2fc9272de2d26","fee5d9fcae91fb6a4acb181d","fee5d9fcae91fb6a4ade2d26a50f15","fee5d9fcbba1fc9272fb6a4ade2d26a50f15","fee5d9fcbba1fc9272fb6a4aef3b2ccb181d99000d","fff5f0fee0d2fcbba1fc9272fb6a4aef3b2ccb181d99000d","fff5f0fee0d2fcbba1fc9272fb6a4aef3b2ccb181da50f1567000d").map(H_),nm=rb(tm),em=new Array(3).concat("fee6cefdae6be6550d","feeddefdbe85fd8d3cd94701","feeddefdbe85fd8d3ce6550da63603","feeddefdd0a2fdae6bfd8d3ce6550da63603","feeddefdd0a2fdae6bfd8d3cf16913d948018c2d04","fff5ebfee6cefdd0a2fdae6bfd8d3cf16913d948018c2d04","fff5ebfee6cefdd0a2fdae6bfd8d3cf16913d94801a636037f2704").map(H_),rm=rb(em);var im=hi(Tr(300,.5,0),Tr(-240,.5,1)),om=hi(Tr(-100,.75,.35),Tr(80,1.5,.8)),am=hi(Tr(260,.75,.35),Tr(80,1.5,.8)),um=Tr();var cm=Fe(),fm=Math.PI/3,sm=2*Math.PI/3;function lm(t){var n=t.length;return function(e){return t[Math.max(0,Math.min(n-1,Math.floor(e*n)))]}}var hm=lm(H_("44015444025645045745055946075a46085c460a5d460b5e470d60470e6147106347116447136548146748166848176948186a481a6c481b6d481c6e481d6f481f70482071482173482374482475482576482677482878482979472a7a472c7a472d7b472e7c472f7d46307e46327e46337f463480453581453781453882443983443a83443b84433d84433e85423f854240864241864142874144874045884046883f47883f48893e49893e4a893e4c8a3d4d8a3d4e8a3c4f8a3c508b3b518b3b528b3a538b3a548c39558c39568c38588c38598c375a8c375b8d365c8d365d8d355e8d355f8d34608d34618d33628d33638d32648e32658e31668e31678e31688e30698e306a8e2f6b8e2f6c8e2e6d8e2e6e8e2e6f8e2d708e2d718e2c718e2c728e2c738e2b748e2b758e2a768e2a778e2a788e29798e297a8e297b8e287c8e287d8e277e8e277f8e27808e26818e26828e26828e25838e25848e25858e24868e24878e23888e23898e238a8d228b8d228c8d228d8d218e8d218f8d21908d21918c20928c20928c20938c1f948c1f958b1f968b1f978b1f988b1f998a1f9a8a1e9b8a1e9c891e9d891f9e891f9f881fa0881fa1881fa1871fa28720a38620a48621a58521a68522a78522a88423a98324aa8325ab8225ac8226ad8127ad8128ae8029af7f2ab07f2cb17e2db27d2eb37c2fb47c31b57b32b67a34b67935b77937b87838b9773aba763bbb753dbc743fbc7340bd7242be7144bf7046c06f48c16e4ac16d4cc26c4ec36b50c46a52c56954c56856c66758c7655ac8645cc8635ec96260ca6063cb5f65cb5e67cc5c69cd5b6ccd5a6ece5870cf5773d05675d05477d1537ad1517cd2507fd34e81d34d84d44b86d54989d5488bd6468ed64590d74393d74195d84098d83e9bd93c9dd93ba0da39a2da37a5db36a8db34aadc32addc30b0dd2fb2dd2db5de2bb8de29bade28bddf26c0df25c2df23c5e021c8e020cae11fcde11dd0e11cd2e21bd5e21ad8e219dae319dde318dfe318e2e418e5e419e7e419eae51aece51befe51cf1e51df4e61ef6e620f8e621fbe723fde725")),dm=lm(H_("00000401000501010601010802010902020b02020d03030f03031204041405041606051806051a07061c08071e0907200a08220b09240c09260d0a290e0b2b100b2d110c2f120d31130d34140e36150e38160f3b180f3d19103f1a10421c10441d11471e114920114b21114e22115024125325125527125829115a2a115c2c115f2d11612f116331116533106734106936106b38106c390f6e3b0f703d0f713f0f72400f74420f75440f764510774710784910784a10794c117a4e117b4f127b51127c52137c54137d56147d57157e59157e5a167e5c167f5d177f5f187f601880621980641a80651a80671b80681c816a1c816b1d816d1d816e1e81701f81721f817320817521817621817822817922827b23827c23827e24828025828125818326818426818627818827818928818b29818c29818e2a81902a81912b81932b80942c80962c80982d80992d809b2e7f9c2e7f9e2f7fa02f7fa1307ea3307ea5317ea6317da8327daa337dab337cad347cae347bb0357bb2357bb3367ab5367ab73779b83779ba3878bc3978bd3977bf3a77c03a76c23b75c43c75c53c74c73d73c83e73ca3e72cc3f71cd4071cf4070d0416fd2426fd3436ed5446dd6456cd8456cd9466bdb476adc4869de4968df4a68e04c67e24d66e34e65e44f64e55064e75263e85362e95462ea5661eb5760ec5860ed5a5fee5b5eef5d5ef05f5ef1605df2625df2645cf3655cf4675cf4695cf56b5cf66c5cf66e5cf7705cf7725cf8745cf8765cf9785df9795df97b5dfa7d5efa7f5efa815ffb835ffb8560fb8761fc8961fc8a62fc8c63fc8e64fc9065fd9266fd9467fd9668fd9869fd9a6afd9b6bfe9d6cfe9f6dfea16efea36ffea571fea772fea973feaa74feac76feae77feb078feb27afeb47bfeb67cfeb77efeb97ffebb81febd82febf84fec185fec287fec488fec68afec88cfeca8dfecc8ffecd90fecf92fed194fed395fed597fed799fed89afdda9cfddc9efddea0fde0a1fde2a3fde3a5fde5a7fde7a9fde9aafdebacfcecaefceeb0fcf0b2fcf2b4fcf4b6fcf6b8fcf7b9fcf9bbfcfbbdfcfdbf")),pm=lm(H_("00000401000501010601010802010a02020c02020e03021004031204031405041706041907051b08051d09061f0a07220b07240c08260d08290e092b10092d110a30120a32140b34150b37160b39180c3c190c3e1b0c411c0c431e0c451f0c48210c4a230c4c240c4f260c51280b53290b552b0b572d0b592f0a5b310a5c320a5e340a5f3609613809623909633b09643d09653e0966400a67420a68440a68450a69470b6a490b6a4a0c6b4c0c6b4d0d6c4f0d6c510e6c520e6d540f6d550f6d57106e59106e5a116e5c126e5d126e5f136e61136e62146e64156e65156e67166e69166e6a176e6c186e6d186e6f196e71196e721a6e741a6e751b6e771c6d781c6d7a1d6d7c1d6d7d1e6d7f1e6c801f6c82206c84206b85216b87216b88226a8a226a8c23698d23698f24699025689225689326679526679727669827669a28659b29649d29649f2a63a02a63a22b62a32c61a52c60a62d60a82e5fa92e5eab2f5ead305dae305cb0315bb1325ab3325ab43359b63458b73557b93556ba3655bc3754bd3853bf3952c03a51c13a50c33b4fc43c4ec63d4dc73e4cc83f4bca404acb4149cc4248ce4347cf4446d04545d24644d34743d44842d54a41d74b3fd84c3ed94d3dda4e3cdb503bdd513ade5238df5337e05536e15635e25734e35933e45a31e55c30e65d2fe75e2ee8602de9612bea632aeb6429eb6628ec6726ed6925ee6a24ef6c23ef6e21f06f20f1711ff1731df2741cf3761bf37819f47918f57b17f57d15f67e14f68013f78212f78410f8850ff8870ef8890cf98b0bf98c0af98e09fa9008fa9207fa9407fb9606fb9706fb9906fb9b06fb9d07fc9f07fca108fca309fca50afca60cfca80dfcaa0ffcac11fcae12fcb014fcb216fcb418fbb61afbb81dfbba1ffbbc21fbbe23fac026fac228fac42afac62df9c72ff9c932f9cb35f8cd37f8cf3af7d13df7d340f6d543f6d746f5d949f5db4cf4dd4ff4df53f4e156f3e35af3e55df2e661f2e865f2ea69f1ec6df1ed71f1ef75f1f179f2f27df2f482f3f586f3f68af4f88ef5f992f6fa96f8fb9af9fc9dfafda1fcffa4")),gm=lm(H_("0d088710078813078916078a19068c1b068d1d068e20068f2206902406912605912805922a05932c05942e05952f059631059733059735049837049938049a3a049a3c049b3e049c3f049c41049d43039e44039e46039f48039f4903a04b03a14c02a14e02a25002a25102a35302a35502a45601a45801a45901a55b01a55c01a65e01a66001a66100a76300a76400a76600a76700a86900a86a00a86c00a86e00a86f00a87100a87201a87401a87501a87701a87801a87a02a87b02a87d03a87e03a88004a88104a78305a78405a78606a68707a68808a68a09a58b0aa58d0ba58e0ca48f0da4910ea3920fa39410a29511a19613a19814a099159f9a169f9c179e9d189d9e199da01a9ca11b9ba21d9aa31e9aa51f99a62098a72197a82296aa2395ab2494ac2694ad2793ae2892b02991b12a90b22b8fb32c8eb42e8db52f8cb6308bb7318ab83289ba3388bb3488bc3587bd3786be3885bf3984c03a83c13b82c23c81c33d80c43e7fc5407ec6417dc7427cc8437bc9447aca457acb4679cc4778cc4977cd4a76ce4b75cf4c74d04d73d14e72d24f71d35171d45270d5536fd5546ed6556dd7566cd8576bd9586ada5a6ada5b69db5c68dc5d67dd5e66de5f65de6164df6263e06363e16462e26561e26660e3685fe4695ee56a5de56b5de66c5ce76e5be76f5ae87059e97158e97257ea7457eb7556eb7655ec7754ed7953ed7a52ee7b51ef7c51ef7e50f07f4ff0804ef1814df1834cf2844bf3854bf3874af48849f48948f58b47f58c46f68d45f68f44f79044f79143f79342f89441f89540f9973ff9983ef99a3efa9b3dfa9c3cfa9e3bfb9f3afba139fba238fca338fca537fca636fca835fca934fdab33fdac33fdae32fdaf31fdb130fdb22ffdb42ffdb52efeb72dfeb82cfeba2cfebb2bfebd2afebe2afec029fdc229fdc328fdc527fdc627fdc827fdca26fdcb26fccd25fcce25fcd025fcd225fbd324fbd524fbd724fad824fada24f9dc24f9dd25f8df25f8e125f7e225f7e425f6e626f6e826f5e926f5eb27f4ed27f3ee27f3f027f2f227f1f426f1f525f0f724f0f921"));function ym(t){return function(){return t}}const vm=Math.abs,_m=Math.atan2,bm=Math.cos,mm=Math.max,xm=Math.min,wm=Math.sin,Mm=Math.sqrt,Tm=1e-12,Am=Math.PI,Sm=Am/2,Em=2*Am;function Nm(t){return t>=1?Sm:t<=-1?-Sm:Math.asin(t)}function km(t){let n=3;return t.digits=function(e){if(!arguments.length)return n;if(null==e)n=null;else{const t=Math.floor(e);if(!(t>=0))throw new RangeError(`invalid digits: ${e}`);n=t}return t},()=>new Ua(n)}function Cm(t){return t.innerRadius}function Pm(t){return t.outerRadius}function zm(t){return t.startAngle}function $m(t){return t.endAngle}function Dm(t){return t&&t.padAngle}function Rm(t,n,e,r,i,o,a){var u=t-e,c=n-r,f=(a?o:-o)/Mm(u*u+c*c),s=f*c,l=-f*u,h=t+s,d=n+l,p=e+s,g=r+l,y=(h+p)/2,v=(d+g)/2,_=p-h,b=g-d,m=_*_+b*b,x=i-o,w=h*g-p*d,M=(b<0?-1:1)*Mm(mm(0,x*x*m-w*w)),T=(w*b-_*M)/m,A=(-w*_-b*M)/m,S=(w*b+_*M)/m,E=(-w*_+b*M)/m,N=T-y,k=A-v,C=S-y,P=E-v;return N*N+k*k>C*C+P*P&&(T=S,A=E),{cx:T,cy:A,x01:-s,y01:-l,x11:T*(i/x-1),y11:A*(i/x-1)}}var Fm=Array.prototype.slice;function qm(t){return"object"==typeof t&&"length"in t?t:Array.from(t)}function Um(t){this._context=t}function Im(t){return new Um(t)}function Om(t){return t[0]}function Bm(t){return t[1]}function Ym(t,n){var e=ym(!0),r=null,i=Im,o=null,a=km(u);function u(u){var c,f,s,l=(u=qm(u)).length,h=!1;for(null==r&&(o=i(s=a())),c=0;c<=l;++c)!(c=l;--h)u.point(v[h],_[h]);u.lineEnd(),u.areaEnd()}y&&(v[s]=+t(d,s,f),_[s]=+n(d,s,f),u.point(r?+r(d,s,f):v[s],e?+e(d,s,f):_[s]))}if(p)return u=null,p+""||null}function s(){return Ym().defined(i).curve(a).context(o)}return t="function"==typeof t?t:void 0===t?Om:ym(+t),n="function"==typeof n?n:ym(void 0===n?0:+n),e="function"==typeof e?e:void 0===e?Bm:ym(+e),f.x=function(n){return arguments.length?(t="function"==typeof n?n:ym(+n),r=null,f):t},f.x0=function(n){return arguments.length?(t="function"==typeof n?n:ym(+n),f):t},f.x1=function(t){return arguments.length?(r=null==t?null:"function"==typeof t?t:ym(+t),f):r},f.y=function(t){return arguments.length?(n="function"==typeof t?t:ym(+t),e=null,f):n},f.y0=function(t){return arguments.length?(n="function"==typeof t?t:ym(+t),f):n},f.y1=function(t){return arguments.length?(e=null==t?null:"function"==typeof t?t:ym(+t),f):e},f.lineX0=f.lineY0=function(){return s().x(t).y(n)},f.lineY1=function(){return s().x(t).y(e)},f.lineX1=function(){return s().x(r).y(n)},f.defined=function(t){return arguments.length?(i="function"==typeof t?t:ym(!!t),f):i},f.curve=function(t){return arguments.length?(a=t,null!=o&&(u=a(o)),f):a},f.context=function(t){return arguments.length?(null==t?o=u=null:u=a(o=t),f):o},f}function jm(t,n){return nt?1:n>=t?0:NaN}function Hm(t){return t}Um.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;default:this._context.lineTo(t,n)}}};var Xm=Vm(Im);function Gm(t){this._curve=t}function Vm(t){function n(n){return new Gm(t(n))}return n._curve=t,n}function Wm(t){var n=t.curve;return t.angle=t.x,delete t.x,t.radius=t.y,delete t.y,t.curve=function(t){return arguments.length?n(Vm(t)):n()._curve},t}function Zm(){return Wm(Ym().curve(Xm))}function Km(){var t=Lm().curve(Xm),n=t.curve,e=t.lineX0,r=t.lineX1,i=t.lineY0,o=t.lineY1;return t.angle=t.x,delete t.x,t.startAngle=t.x0,delete t.x0,t.endAngle=t.x1,delete t.x1,t.radius=t.y,delete t.y,t.innerRadius=t.y0,delete t.y0,t.outerRadius=t.y1,delete t.y1,t.lineStartAngle=function(){return Wm(e())},delete t.lineX0,t.lineEndAngle=function(){return Wm(r())},delete t.lineX1,t.lineInnerRadius=function(){return Wm(i())},delete t.lineY0,t.lineOuterRadius=function(){return Wm(o())},delete t.lineY1,t.curve=function(t){return arguments.length?n(Vm(t)):n()._curve},t}function Qm(t,n){return[(n=+n)*Math.cos(t-=Math.PI/2),n*Math.sin(t)]}Gm.prototype={areaStart:function(){this._curve.areaStart()},areaEnd:function(){this._curve.areaEnd()},lineStart:function(){this._curve.lineStart()},lineEnd:function(){this._curve.lineEnd()},point:function(t,n){this._curve.point(n*Math.sin(t),n*-Math.cos(t))}};class Jm{constructor(t,n){this._context=t,this._x=n}areaStart(){this._line=0}areaEnd(){this._line=NaN}lineStart(){this._point=0}lineEnd(){(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line}point(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;default:this._x?this._context.bezierCurveTo(this._x0=(this._x0+t)/2,this._y0,this._x0,n,t,n):this._context.bezierCurveTo(this._x0,this._y0=(this._y0+n)/2,t,this._y0,t,n)}this._x0=t,this._y0=n}}class tx{constructor(t){this._context=t}lineStart(){this._point=0}lineEnd(){}point(t,n){if(t=+t,n=+n,0===this._point)this._point=1;else{const e=Qm(this._x0,this._y0),r=Qm(this._x0,this._y0=(this._y0+n)/2),i=Qm(t,this._y0),o=Qm(t,n);this._context.moveTo(...e),this._context.bezierCurveTo(...r,...i,...o)}this._x0=t,this._y0=n}}function nx(t){return new Jm(t,!0)}function ex(t){return new Jm(t,!1)}function rx(t){return new tx(t)}function ix(t){return t.source}function ox(t){return t.target}function ax(t){let n=ix,e=ox,r=Om,i=Bm,o=null,a=null,u=km(c);function c(){let c;const f=Fm.call(arguments),s=n.apply(this,f),l=e.apply(this,f);if(null==o&&(a=t(c=u())),a.lineStart(),f[0]=s,a.point(+r.apply(this,f),+i.apply(this,f)),f[0]=l,a.point(+r.apply(this,f),+i.apply(this,f)),a.lineEnd(),c)return a=null,c+""||null}return c.source=function(t){return arguments.length?(n=t,c):n},c.target=function(t){return arguments.length?(e=t,c):e},c.x=function(t){return arguments.length?(r="function"==typeof t?t:ym(+t),c):r},c.y=function(t){return arguments.length?(i="function"==typeof t?t:ym(+t),c):i},c.context=function(n){return arguments.length?(null==n?o=a=null:a=t(o=n),c):o},c}const ux=Mm(3);var cx={draw(t,n){const e=.59436*Mm(n+xm(n/28,.75)),r=e/2,i=r*ux;t.moveTo(0,e),t.lineTo(0,-e),t.moveTo(-i,-r),t.lineTo(i,r),t.moveTo(-i,r),t.lineTo(i,-r)}},fx={draw(t,n){const e=Mm(n/Am);t.moveTo(e,0),t.arc(0,0,e,0,Em)}},sx={draw(t,n){const e=Mm(n/5)/2;t.moveTo(-3*e,-e),t.lineTo(-e,-e),t.lineTo(-e,-3*e),t.lineTo(e,-3*e),t.lineTo(e,-e),t.lineTo(3*e,-e),t.lineTo(3*e,e),t.lineTo(e,e),t.lineTo(e,3*e),t.lineTo(-e,3*e),t.lineTo(-e,e),t.lineTo(-3*e,e),t.closePath()}};const lx=Mm(1/3),hx=2*lx;var dx={draw(t,n){const e=Mm(n/hx),r=e*lx;t.moveTo(0,-e),t.lineTo(r,0),t.lineTo(0,e),t.lineTo(-r,0),t.closePath()}},px={draw(t,n){const e=.62625*Mm(n);t.moveTo(0,-e),t.lineTo(e,0),t.lineTo(0,e),t.lineTo(-e,0),t.closePath()}},gx={draw(t,n){const e=.87559*Mm(n-xm(n/7,2));t.moveTo(-e,0),t.lineTo(e,0),t.moveTo(0,e),t.lineTo(0,-e)}},yx={draw(t,n){const e=Mm(n),r=-e/2;t.rect(r,r,e,e)}},vx={draw(t,n){const e=.4431*Mm(n);t.moveTo(e,e),t.lineTo(e,-e),t.lineTo(-e,-e),t.lineTo(-e,e),t.closePath()}};const _x=wm(Am/10)/wm(7*Am/10),bx=wm(Em/10)*_x,mx=-bm(Em/10)*_x;var xx={draw(t,n){const e=Mm(.8908130915292852*n),r=bx*e,i=mx*e;t.moveTo(0,-e),t.lineTo(r,i);for(let n=1;n<5;++n){const o=Em*n/5,a=bm(o),u=wm(o);t.lineTo(u*e,-a*e),t.lineTo(a*r-u*i,u*r+a*i)}t.closePath()}};const wx=Mm(3);var Mx={draw(t,n){const e=-Mm(n/(3*wx));t.moveTo(0,2*e),t.lineTo(-wx*e,-e),t.lineTo(wx*e,-e),t.closePath()}};const Tx=Mm(3);var Ax={draw(t,n){const e=.6824*Mm(n),r=e/2,i=e*Tx/2;t.moveTo(0,-e),t.lineTo(i,r),t.lineTo(-i,r),t.closePath()}};const Sx=-.5,Ex=Mm(3)/2,Nx=1/Mm(12),kx=3*(Nx/2+1);var Cx={draw(t,n){const e=Mm(n/kx),r=e/2,i=e*Nx,o=r,a=e*Nx+e,u=-o,c=a;t.moveTo(r,i),t.lineTo(o,a),t.lineTo(u,c),t.lineTo(Sx*r-Ex*i,Ex*r+Sx*i),t.lineTo(Sx*o-Ex*a,Ex*o+Sx*a),t.lineTo(Sx*u-Ex*c,Ex*u+Sx*c),t.lineTo(Sx*r+Ex*i,Sx*i-Ex*r),t.lineTo(Sx*o+Ex*a,Sx*a-Ex*o),t.lineTo(Sx*u+Ex*c,Sx*c-Ex*u),t.closePath()}},Px={draw(t,n){const e=.6189*Mm(n-xm(n/6,1.7));t.moveTo(-e,-e),t.lineTo(e,e),t.moveTo(-e,e),t.lineTo(e,-e)}};const zx=[fx,sx,dx,yx,xx,Mx,Cx],$x=[fx,gx,Px,Ax,cx,vx,px];function Dx(){}function Rx(t,n,e){t._context.bezierCurveTo((2*t._x0+t._x1)/3,(2*t._y0+t._y1)/3,(t._x0+2*t._x1)/3,(t._y0+2*t._y1)/3,(t._x0+4*t._x1+n)/6,(t._y0+4*t._y1+e)/6)}function Fx(t){this._context=t}function qx(t){this._context=t}function Ux(t){this._context=t}function Ix(t,n){this._basis=new Fx(t),this._beta=n}Fx.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN,this._point=0},lineEnd:function(){switch(this._point){case 3:Rx(this,this._x1,this._y1);case 2:this._context.lineTo(this._x1,this._y1)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;break;case 2:this._point=3,this._context.lineTo((5*this._x0+this._x1)/6,(5*this._y0+this._y1)/6);default:Rx(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},qx.prototype={areaStart:Dx,areaEnd:Dx,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._y0=this._y1=this._y2=this._y3=this._y4=NaN,this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x2,this._y2),this._context.closePath();break;case 2:this._context.moveTo((this._x2+2*this._x3)/3,(this._y2+2*this._y3)/3),this._context.lineTo((this._x3+2*this._x2)/3,(this._y3+2*this._y2)/3),this._context.closePath();break;case 3:this.point(this._x2,this._y2),this.point(this._x3,this._y3),this.point(this._x4,this._y4)}},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._x2=t,this._y2=n;break;case 1:this._point=2,this._x3=t,this._y3=n;break;case 2:this._point=3,this._x4=t,this._y4=n,this._context.moveTo((this._x0+4*this._x1+t)/6,(this._y0+4*this._y1+n)/6);break;default:Rx(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},Ux.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN,this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3;var e=(this._x0+4*this._x1+t)/6,r=(this._y0+4*this._y1+n)/6;this._line?this._context.lineTo(e,r):this._context.moveTo(e,r);break;case 3:this._point=4;default:Rx(this,t,n)}this._x0=this._x1,this._x1=t,this._y0=this._y1,this._y1=n}},Ix.prototype={lineStart:function(){this._x=[],this._y=[],this._basis.lineStart()},lineEnd:function(){var t=this._x,n=this._y,e=t.length-1;if(e>0)for(var r,i=t[0],o=n[0],a=t[e]-i,u=n[e]-o,c=-1;++c<=e;)r=c/e,this._basis.point(this._beta*t[c]+(1-this._beta)*(i+r*a),this._beta*n[c]+(1-this._beta)*(o+r*u));this._x=this._y=null,this._basis.lineEnd()},point:function(t,n){this._x.push(+t),this._y.push(+n)}};var Ox=function t(n){function e(t){return 1===n?new Fx(t):new Ix(t,n)}return e.beta=function(n){return t(+n)},e}(.85);function Bx(t,n,e){t._context.bezierCurveTo(t._x1+t._k*(t._x2-t._x0),t._y1+t._k*(t._y2-t._y0),t._x2+t._k*(t._x1-n),t._y2+t._k*(t._y1-e),t._x2,t._y2)}function Yx(t,n){this._context=t,this._k=(1-n)/6}Yx.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:Bx(this,this._x1,this._y1)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2,this._x1=t,this._y1=n;break;case 2:this._point=3;default:Bx(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var Lx=function t(n){function e(t){return new Yx(t,n)}return e.tension=function(n){return t(+n)},e}(0);function jx(t,n){this._context=t,this._k=(1-n)/6}jx.prototype={areaStart:Dx,areaEnd:Dx,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN,this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x3,this._y3),this._context.closePath();break;case 2:this._context.lineTo(this._x3,this._y3),this._context.closePath();break;case 3:this.point(this._x3,this._y3),this.point(this._x4,this._y4),this.point(this._x5,this._y5)}},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._x3=t,this._y3=n;break;case 1:this._point=2,this._context.moveTo(this._x4=t,this._y4=n);break;case 2:this._point=3,this._x5=t,this._y5=n;break;default:Bx(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var Hx=function t(n){function e(t){return new jx(t,n)}return e.tension=function(n){return t(+n)},e}(0);function Xx(t,n){this._context=t,this._k=(1-n)/6}Xx.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3,this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;default:Bx(this,t,n)}this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var Gx=function t(n){function e(t){return new Xx(t,n)}return e.tension=function(n){return t(+n)},e}(0);function Vx(t,n,e){var r=t._x1,i=t._y1,o=t._x2,a=t._y2;if(t._l01_a>Tm){var u=2*t._l01_2a+3*t._l01_a*t._l12_a+t._l12_2a,c=3*t._l01_a*(t._l01_a+t._l12_a);r=(r*u-t._x0*t._l12_2a+t._x2*t._l01_2a)/c,i=(i*u-t._y0*t._l12_2a+t._y2*t._l01_2a)/c}if(t._l23_a>Tm){var f=2*t._l23_2a+3*t._l23_a*t._l12_a+t._l12_2a,s=3*t._l23_a*(t._l23_a+t._l12_a);o=(o*f+t._x1*t._l23_2a-n*t._l12_2a)/s,a=(a*f+t._y1*t._l23_2a-e*t._l12_2a)/s}t._context.bezierCurveTo(r,i,o,a,t._x2,t._y2)}function Wx(t,n){this._context=t,this._alpha=n}Wx.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:this.point(this._x2,this._y2)}(this._line||0!==this._line&&1===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;break;case 2:this._point=3;default:Vx(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var Zx=function t(n){function e(t){return n?new Wx(t,n):new Yx(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function Kx(t,n){this._context=t,this._alpha=n}Kx.prototype={areaStart:Dx,areaEnd:Dx,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 1:this._context.moveTo(this._x3,this._y3),this._context.closePath();break;case 2:this._context.lineTo(this._x3,this._y3),this._context.closePath();break;case 3:this.point(this._x3,this._y3),this.point(this._x4,this._y4),this.point(this._x5,this._y5)}},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1,this._x3=t,this._y3=n;break;case 1:this._point=2,this._context.moveTo(this._x4=t,this._y4=n);break;case 2:this._point=3,this._x5=t,this._y5=n;break;default:Vx(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var Qx=function t(n){function e(t){return n?new Kx(t,n):new jx(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function Jx(t,n){this._context=t,this._alpha=n}Jx.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN,this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){(this._line||0!==this._line&&3===this._point)&&this._context.closePath(),this._line=1-this._line},point:function(t,n){if(t=+t,n=+n,this._point){var e=this._x2-t,r=this._y2-n;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(e*e+r*r,this._alpha))}switch(this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3,this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;default:Vx(this,t,n)}this._l01_a=this._l12_a,this._l12_a=this._l23_a,this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a,this._x0=this._x1,this._x1=this._x2,this._x2=t,this._y0=this._y1,this._y1=this._y2,this._y2=n}};var tw=function t(n){function e(t){return n?new Jx(t,n):new Xx(t,0)}return e.alpha=function(n){return t(+n)},e}(.5);function nw(t){this._context=t}function ew(t){return t<0?-1:1}function rw(t,n,e){var r=t._x1-t._x0,i=n-t._x1,o=(t._y1-t._y0)/(r||i<0&&-0),a=(e-t._y1)/(i||r<0&&-0),u=(o*i+a*r)/(r+i);return(ew(o)+ew(a))*Math.min(Math.abs(o),Math.abs(a),.5*Math.abs(u))||0}function iw(t,n){var e=t._x1-t._x0;return e?(3*(t._y1-t._y0)/e-n)/2:n}function ow(t,n,e){var r=t._x0,i=t._y0,o=t._x1,a=t._y1,u=(o-r)/3;t._context.bezierCurveTo(r+u,i+u*n,o-u,a-u*e,o,a)}function aw(t){this._context=t}function uw(t){this._context=new cw(t)}function cw(t){this._context=t}function fw(t){this._context=t}function sw(t){var n,e,r=t.length-1,i=new Array(r),o=new Array(r),a=new Array(r);for(i[0]=0,o[0]=2,a[0]=t[0]+2*t[1],n=1;n=0;--n)i[n]=(a[n]-i[n+1])/o[n];for(o[r-1]=(t[r]+i[r-1])/2,n=0;n1)for(var e,r,i,o=1,a=t[n[0]],u=a.length;o=0;)e[n]=n;return e}function pw(t,n){return t[n]}function gw(t){const n=[];return n.key=t,n}function yw(t){var n=t.map(vw);return dw(t).sort((function(t,e){return n[t]-n[e]}))}function vw(t){for(var n,e=-1,r=0,i=t.length,o=-1/0;++eo&&(o=n,r=e);return r}function _w(t){var n=t.map(bw);return dw(t).sort((function(t,e){return n[t]-n[e]}))}function bw(t){for(var n,e=0,r=-1,i=t.length;++r=0&&(this._t=1-this._t,this._line=1-this._line)},point:function(t,n){switch(t=+t,n=+n,this._point){case 0:this._point=1,this._line?this._context.lineTo(t,n):this._context.moveTo(t,n);break;case 1:this._point=2;default:if(this._t<=0)this._context.lineTo(this._x,n),this._context.lineTo(t,n);else{var e=this._x*(1-this._t)+t*this._t;this._context.lineTo(e,this._y),this._context.lineTo(e,n)}}this._x=t,this._y=n}};var mw=t=>()=>t;function xw(t,{sourceEvent:n,target:e,transform:r,dispatch:i}){Object.defineProperties(this,{type:{value:t,enumerable:!0,configurable:!0},sourceEvent:{value:n,enumerable:!0,configurable:!0},target:{value:e,enumerable:!0,configurable:!0},transform:{value:r,enumerable:!0,configurable:!0},_:{value:i}})}function ww(t,n,e){this.k=t,this.x=n,this.y=e}ww.prototype={constructor:ww,scale:function(t){return 1===t?this:new ww(this.k*t,this.x,this.y)},translate:function(t,n){return 0===t&0===n?this:new ww(this.k,this.x+this.k*t,this.y+this.k*n)},apply:function(t){return[t[0]*this.k+this.x,t[1]*this.k+this.y]},applyX:function(t){return t*this.k+this.x},applyY:function(t){return t*this.k+this.y},invert:function(t){return[(t[0]-this.x)/this.k,(t[1]-this.y)/this.k]},invertX:function(t){return(t-this.x)/this.k},invertY:function(t){return(t-this.y)/this.k},rescaleX:function(t){return t.copy().domain(t.range().map(this.invertX,this).map(t.invert,t))},rescaleY:function(t){return t.copy().domain(t.range().map(this.invertY,this).map(t.invert,t))},toString:function(){return"translate("+this.x+","+this.y+") scale("+this.k+")"}};var Mw=new ww(1,0,0);function Tw(t){for(;!t.__zoom;)if(!(t=t.parentNode))return Mw;return t.__zoom}function Aw(t){t.stopImmediatePropagation()}function Sw(t){t.preventDefault(),t.stopImmediatePropagation()}function Ew(t){return!(t.ctrlKey&&"wheel"!==t.type||t.button)}function Nw(){var t=this;return t instanceof SVGElement?(t=t.ownerSVGElement||t).hasAttribute("viewBox")?[[(t=t.viewBox.baseVal).x,t.y],[t.x+t.width,t.y+t.height]]:[[0,0],[t.width.baseVal.value,t.height.baseVal.value]]:[[0,0],[t.clientWidth,t.clientHeight]]}function kw(){return this.__zoom||Mw}function Cw(t){return-t.deltaY*(1===t.deltaMode?.05:t.deltaMode?1:.002)*(t.ctrlKey?10:1)}function Pw(){return navigator.maxTouchPoints||"ontouchstart"in this}function zw(t,n,e){var r=t.invertX(n[0][0])-e[0][0],i=t.invertX(n[1][0])-e[1][0],o=t.invertY(n[0][1])-e[0][1],a=t.invertY(n[1][1])-e[1][1];return t.translate(i>r?(r+i)/2:Math.min(0,r)||Math.max(0,i),a>o?(o+a)/2:Math.min(0,o)||Math.max(0,a))}Tw.prototype=ww.prototype,t.Adder=T,t.Delaunay=Lu,t.FormatSpecifier=tf,t.InternMap=InternMap,t.InternSet=InternSet,t.Node=Qd,t.Path=Ua,t.Voronoi=qu,t.ZoomTransform=ww,t.active=function(t,n){var e,r,i=t.__transition;if(i)for(r in n=null==n?null:n+"",i)if((e=i[r]).state>qi&&e.name===n)return new po([[t]],Zo,n,+r);return null},t.arc=function(){var t=Cm,n=Pm,e=ym(0),r=null,i=zm,o=$m,a=Dm,u=null,c=km(f);function f(){var f,s,l=+t.apply(this,arguments),h=+n.apply(this,arguments),d=i.apply(this,arguments)-Sm,p=o.apply(this,arguments)-Sm,g=vm(p-d),y=p>d;if(u||(u=f=c()),hTm)if(g>Em-Tm)u.moveTo(h*bm(d),h*wm(d)),u.arc(0,0,h,d,p,!y),l>Tm&&(u.moveTo(l*bm(p),l*wm(p)),u.arc(0,0,l,p,d,y));else{var v,_,b=d,m=p,x=d,w=p,M=g,T=g,A=a.apply(this,arguments)/2,S=A>Tm&&(r?+r.apply(this,arguments):Mm(l*l+h*h)),E=xm(vm(h-l)/2,+e.apply(this,arguments)),N=E,k=E;if(S>Tm){var C=Nm(S/l*wm(A)),P=Nm(S/h*wm(A));(M-=2*C)>Tm?(x+=C*=y?1:-1,w-=C):(M=0,x=w=(d+p)/2),(T-=2*P)>Tm?(b+=P*=y?1:-1,m-=P):(T=0,b=m=(d+p)/2)}var z=h*bm(b),$=h*wm(b),D=l*bm(w),R=l*wm(w);if(E>Tm){var F,q=h*bm(m),U=h*wm(m),I=l*bm(x),O=l*wm(x);if(g1?0:t<-1?Am:Math.acos(t)}((B*L+Y*j)/(Mm(B*B+Y*Y)*Mm(L*L+j*j)))/2),X=Mm(F[0]*F[0]+F[1]*F[1]);N=xm(E,(l-X)/(H-1)),k=xm(E,(h-X)/(H+1))}else N=k=0}T>Tm?k>Tm?(v=Rm(I,O,z,$,h,k,y),_=Rm(q,U,D,R,h,k,y),u.moveTo(v.cx+v.x01,v.cy+v.y01),kTm&&M>Tm?N>Tm?(v=Rm(D,R,q,U,l,-N,y),_=Rm(z,$,I,O,l,-N,y),u.lineTo(v.cx+v.x01,v.cy+v.y01),N=0))throw new RangeError("invalid r");let e=t.length;if(!((e=Math.floor(e))>=0))throw new RangeError("invalid length");if(!e||!n)return t;const r=y(n),i=t.slice();return r(t,i,0,e,1),r(i,t,0,e,1),r(t,i,0,e,1),t},t.blur2=l,t.blurImage=h,t.brush=function(){return wa(la)},t.brushSelection=function(t){var n=t.__brush;return n?n.dim.output(n.selection):null},t.brushX=function(){return wa(fa)},t.brushY=function(){return wa(sa)},t.buffer=function(t,n){return fetch(t,n).then(_c)},t.chord=function(){return za(!1,!1)},t.chordDirected=function(){return za(!0,!1)},t.chordTranspose=function(){return za(!1,!0)},t.cluster=function(){var t=Ld,n=1,e=1,r=!1;function i(i){var o,a=0;i.eachAfter((function(n){var e=n.children;e?(n.x=function(t){return t.reduce(jd,0)/t.length}(e),n.y=function(t){return 1+t.reduce(Hd,0)}(e)):(n.x=o?a+=t(n,o):0,n.y=0,o=n)}));var u=function(t){for(var n;n=t.children;)t=n[0];return t}(i),c=function(t){for(var n;n=t.children;)t=n[n.length-1];return t}(i),f=u.x-t(u,c)/2,s=c.x+t(c,u)/2;return i.eachAfter(r?function(t){t.x=(t.x-i.x)*n,t.y=(i.y-t.y)*e}:function(t){t.x=(t.x-f)/(s-f)*n,t.y=(1-(i.y?t.y/i.y:1))*e})}return i.separation=function(n){return arguments.length?(t=n,i):t},i.size=function(t){return arguments.length?(r=!1,n=+t[0],e=+t[1],i):r?null:[n,e]},i.nodeSize=function(t){return arguments.length?(r=!0,n=+t[0],e=+t[1],i):r?[n,e]:null},i},t.color=ze,t.contourDensity=function(){var t=fu,n=su,e=lu,r=960,i=500,o=20,a=2,u=3*o,c=r+2*u>>a,f=i+2*u>>a,s=Qa(20);function h(r){var i=new Float32Array(c*f),s=Math.pow(2,-a),h=-1;for(const o of r){var d=(t(o,++h,r)+u)*s,p=(n(o,h,r)+u)*s,g=+e(o,h,r);if(g&&d>=0&&d=0&&pt*r)))(n).map(((t,n)=>(t.value=+e[n],p(t))))}function p(t){return t.coordinates.forEach(g),t}function g(t){t.forEach(y)}function y(t){t.forEach(v)}function v(t){t[0]=t[0]*Math.pow(2,a)-u,t[1]=t[1]*Math.pow(2,a)-u}function _(){return c=r+2*(u=3*o)>>a,f=i+2*u>>a,d}return d.contours=function(t){var n=h(t),e=iu().size([c,f]),r=Math.pow(2,2*a),i=t=>{t=+t;var i=p(e.contour(n,t*r));return i.value=t,i};return Object.defineProperty(i,"max",{get:()=>J(n)/r}),i},d.x=function(n){return arguments.length?(t="function"==typeof n?n:Qa(+n),d):t},d.y=function(t){return arguments.length?(n="function"==typeof t?t:Qa(+t),d):n},d.weight=function(t){return arguments.length?(e="function"==typeof t?t:Qa(+t),d):e},d.size=function(t){if(!arguments.length)return[r,i];var n=+t[0],e=+t[1];if(!(n>=0&&e>=0))throw new Error("invalid size");return r=n,i=e,_()},d.cellSize=function(t){if(!arguments.length)return 1<=1))throw new Error("invalid cell size");return a=Math.floor(Math.log(t)/Math.LN2),_()},d.thresholds=function(t){return arguments.length?(s="function"==typeof t?t:Array.isArray(t)?Qa(Za.call(t)):Qa(t),d):s},d.bandwidth=function(t){if(!arguments.length)return Math.sqrt(o*(o+1));if(!((t=+t)>=0))throw new Error("invalid bandwidth");return o=(Math.sqrt(4*t*t+1)-1)/2,_()},d},t.contours=iu,t.count=v,t.create=function(t){return Zn(Yt(t).call(document.documentElement))},t.creator=Yt,t.cross=function(...t){const n="function"==typeof t[t.length-1]&&function(t){return n=>t(...n)}(t.pop()),e=(t=t.map(m)).map(_),r=t.length-1,i=new Array(r+1).fill(0),o=[];if(r<0||e.some(b))return o;for(;;){o.push(i.map(((n,e)=>t[e][n])));let a=r;for(;++i[a]===e[a];){if(0===a)return n?o.map(n):o;i[a--]=0}}},t.csv=wc,t.csvFormat=rc,t.csvFormatBody=ic,t.csvFormatRow=ac,t.csvFormatRows=oc,t.csvFormatValue=uc,t.csvParse=nc,t.csvParseRows=ec,t.cubehelix=Tr,t.cumsum=function(t,n){var e=0,r=0;return Float64Array.from(t,void 0===n?t=>e+=+t||0:i=>e+=+n(i,r++,t)||0)},t.curveBasis=function(t){return new Fx(t)},t.curveBasisClosed=function(t){return new qx(t)},t.curveBasisOpen=function(t){return new Ux(t)},t.curveBumpX=nx,t.curveBumpY=ex,t.curveBundle=Ox,t.curveCardinal=Lx,t.curveCardinalClosed=Hx,t.curveCardinalOpen=Gx,t.curveCatmullRom=Zx,t.curveCatmullRomClosed=Qx,t.curveCatmullRomOpen=tw,t.curveLinear=Im,t.curveLinearClosed=function(t){return new nw(t)},t.curveMonotoneX=function(t){return new aw(t)},t.curveMonotoneY=function(t){return new uw(t)},t.curveNatural=function(t){return new fw(t)},t.curveStep=function(t){return new lw(t,.5)},t.curveStepAfter=function(t){return new lw(t,1)},t.curveStepBefore=function(t){return new lw(t,0)},t.descending=e,t.deviation=w,t.difference=function(t,...n){t=new InternSet(t);for(const e of n)for(const n of e)t.delete(n);return t},t.disjoint=function(t,n){const e=n[Symbol.iterator](),r=new InternSet;for(const n of t){if(r.has(n))return!1;let t,i;for(;({value:t,done:i}=e.next())&&!i;){if(Object.is(n,t))return!1;r.add(t)}}return!0},t.dispatch=$t,t.drag=function(){var t,n,e,r,i=se,o=le,a=he,u=de,c={},f=$t("start","drag","end"),s=0,l=0;function h(t){t.on("mousedown.drag",d).filter(u).on("touchstart.drag",y).on("touchmove.drag",v,ee).on("touchend.drag touchcancel.drag",_).style("touch-action","none").style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}function d(a,u){if(!r&&i.call(this,a,u)){var c=b(this,o.call(this,a,u),a,u,"mouse");c&&(Zn(a.view).on("mousemove.drag",p,re).on("mouseup.drag",g,re),ae(a.view),ie(a),e=!1,t=a.clientX,n=a.clientY,c("start",a))}}function p(r){if(oe(r),!e){var i=r.clientX-t,o=r.clientY-n;e=i*i+o*o>l}c.mouse("drag",r)}function g(t){Zn(t.view).on("mousemove.drag mouseup.drag",null),ue(t.view,e),oe(t),c.mouse("end",t)}function y(t,n){if(i.call(this,t,n)){var e,r,a=t.changedTouches,u=o.call(this,t,n),c=a.length;for(e=0;e+t,t.easePoly=wo,t.easePolyIn=mo,t.easePolyInOut=wo,t.easePolyOut=xo,t.easeQuad=_o,t.easeQuadIn=function(t){return t*t},t.easeQuadInOut=_o,t.easeQuadOut=function(t){return t*(2-t)},t.easeSin=Ao,t.easeSinIn=function(t){return 1==+t?1:1-Math.cos(t*To)},t.easeSinInOut=Ao,t.easeSinOut=function(t){return Math.sin(t*To)},t.every=function(t,n){if("function"!=typeof n)throw new TypeError("test is not a function");let e=-1;for(const r of t)if(!n(r,++e,t))return!1;return!0},t.extent=M,t.fcumsum=function(t,n){const e=new T;let r=-1;return Float64Array.from(t,void 0===n?t=>e.add(+t||0):i=>e.add(+n(i,++r,t)||0))},t.filter=function(t,n){if("function"!=typeof n)throw new TypeError("test is not a function");const e=[];let r=-1;for(const i of t)n(i,++r,t)&&e.push(i);return e},t.flatGroup=function(t,...n){return z(P(t,...n),n)},t.flatRollup=function(t,n,...e){return z(D(t,n,...e),e)},t.forceCenter=function(t,n){var e,r=1;function i(){var i,o,a=e.length,u=0,c=0;for(i=0;if+p||os+p||ac.index){var g=f-u.x-u.vx,y=s-u.y-u.vy,v=g*g+y*y;vt.r&&(t.r=t[n].r)}function c(){if(n){var r,i,o=n.length;for(e=new Array(o),r=0;r[u(t,n,r),t])));for(a=0,i=new Array(f);a=u)){(t.data!==n||t.next)&&(0===l&&(p+=(l=Uc(e))*l),0===h&&(p+=(h=Uc(e))*h),p(t=(Lc*t+jc)%Hc)/Hc}();function l(){h(),f.call("tick",n),e1?(null==e?u.delete(t):u.set(t,p(e)),n):u.get(t)},find:function(n,e,r){var i,o,a,u,c,f=0,s=t.length;for(null==r?r=1/0:r*=r,f=0;f1?(f.on(t,e),n):f.on(t)}}},t.forceX=function(t){var n,e,r,i=qc(.1);function o(t){for(var i,o=0,a=n.length;o=.12&&i<.234&&r>=-.425&&r<-.214?u:i>=.166&&i<.234&&r>=-.214&&r<-.115?c:a).invert(t)},s.stream=function(e){return t&&n===e?t:(r=[a.stream(n=e),u.stream(e),c.stream(e)],i=r.length,t={point:function(t,n){for(var e=-1;++ejs(r[0],r[1])&&(r[1]=i[1]),js(i[0],r[1])>js(r[0],r[1])&&(r[0]=i[0])):o.push(r=i);for(a=-1/0,n=0,r=o[e=o.length-1];n<=e;r=i,++n)i=o[n],(u=js(r[1],i[0]))>a&&(a=u,Wf=i[0],Kf=r[1])}return is=os=null,Wf===1/0||Zf===1/0?[[NaN,NaN],[NaN,NaN]]:[[Wf,Zf],[Kf,Qf]]},t.geoCentroid=function(t){ms=xs=ws=Ms=Ts=As=Ss=Es=0,Ns=new T,ks=new T,Cs=new T,Lf(t,Gs);var n=+Ns,e=+ks,r=+Cs,i=Ef(n,e,r);return i=0))throw new RangeError(`invalid digits: ${t}`);i=n}return null===n&&(r=new ed(i)),a},a.projection(t).digits(i).context(n)},t.geoProjection=yd,t.geoProjectionMutator=vd,t.geoRotation=ll,t.geoStereographic=function(){return yd(Bd).scale(250).clipAngle(142)},t.geoStereographicRaw=Bd,t.geoStream=Lf,t.geoTransform=function(t){return{stream:id(t)}},t.geoTransverseMercator=function(){var t=Ed(Yd),n=t.center,e=t.rotate;return t.center=function(t){return arguments.length?n([-t[1],t[0]]):[(t=n())[1],-t[0]]},t.rotate=function(t){return arguments.length?e([t[0],t[1],t.length>2?t[2]+90:90]):[(t=e())[0],t[1],t[2]-90]},e([0,0,90]).scale(159.155)},t.geoTransverseMercatorRaw=Yd,t.gray=function(t,n){return new ur(t,0,0,null==n?1:n)},t.greatest=ot,t.greatestIndex=function(t,e=n){if(1===e.length)return tt(t,e);let r,i=-1,o=-1;for(const n of t)++o,(i<0?0===e(n,n):e(n,r)>0)&&(r=n,i=o);return i},t.group=C,t.groupSort=function(t,e,r){return(2!==e.length?U($(t,e,r),(([t,e],[r,i])=>n(e,i)||n(t,r))):U(C(t,r),(([t,r],[i,o])=>e(r,o)||n(t,i)))).map((([t])=>t))},t.groups=P,t.hcl=dr,t.hierarchy=Gd,t.histogram=Q,t.hsl=He,t.html=Ec,t.image=function(t,n){return new Promise((function(e,r){var i=new Image;for(var o in n)i[o]=n[o];i.onerror=r,i.onload=function(){e(i)},i.src=t}))},t.index=function(t,...n){return F(t,k,R,n)},t.indexes=function(t,...n){return F(t,Array.from,R,n)},t.interpolate=Gr,t.interpolateArray=function(t,n){return(Ir(n)?Ur:Or)(t,n)},t.interpolateBasis=Er,t.interpolateBasisClosed=Nr,t.interpolateBlues=Gb,t.interpolateBrBG=ob,t.interpolateBuGn=Mb,t.interpolateBuPu=Ab,t.interpolateCividis=function(t){return t=Math.max(0,Math.min(1,t)),"rgb("+Math.max(0,Math.min(255,Math.round(-4.54-t*(35.34-t*(2381.73-t*(6402.7-t*(7024.72-2710.57*t)))))))+", "+Math.max(0,Math.min(255,Math.round(32.49+t*(170.73+t*(52.82-t*(131.46-t*(176.58-67.37*t)))))))+", "+Math.max(0,Math.min(255,Math.round(81.24+t*(442.36-t*(2482.43-t*(6167.24-t*(6614.94-2475.67*t)))))))+")"},t.interpolateCool=am,t.interpolateCubehelix=li,t.interpolateCubehelixDefault=im,t.interpolateCubehelixLong=hi,t.interpolateDate=Br,t.interpolateDiscrete=function(t){var n=t.length;return function(e){return t[Math.max(0,Math.min(n-1,Math.floor(e*n)))]}},t.interpolateGnBu=Eb,t.interpolateGreens=Wb,t.interpolateGreys=Kb,t.interpolateHcl=ci,t.interpolateHclLong=fi,t.interpolateHsl=oi,t.interpolateHslLong=ai,t.interpolateHue=function(t,n){var e=Pr(+t,+n);return function(t){var n=e(t);return n-360*Math.floor(n/360)}},t.interpolateInferno=pm,t.interpolateLab=function(t,n){var e=$r((t=ar(t)).l,(n=ar(n)).l),r=$r(t.a,n.a),i=$r(t.b,n.b),o=$r(t.opacity,n.opacity);return function(n){return t.l=e(n),t.a=r(n),t.b=i(n),t.opacity=o(n),t+""}},t.interpolateMagma=dm,t.interpolateNumber=Yr,t.interpolateNumberArray=Ur,t.interpolateObject=Lr,t.interpolateOrRd=kb,t.interpolateOranges=rm,t.interpolatePRGn=ub,t.interpolatePiYG=fb,t.interpolatePlasma=gm,t.interpolatePuBu=$b,t.interpolatePuBuGn=Pb,t.interpolatePuOr=lb,t.interpolatePuRd=Rb,t.interpolatePurples=Jb,t.interpolateRainbow=function(t){(t<0||t>1)&&(t-=Math.floor(t));var n=Math.abs(t-.5);return um.h=360*t-100,um.s=1.5-1.5*n,um.l=.8-.9*n,um+""},t.interpolateRdBu=db,t.interpolateRdGy=gb,t.interpolateRdPu=qb,t.interpolateRdYlBu=vb,t.interpolateRdYlGn=bb,t.interpolateReds=nm,t.interpolateRgb=Dr,t.interpolateRgbBasis=Fr,t.interpolateRgbBasisClosed=qr,t.interpolateRound=Vr,t.interpolateSinebow=function(t){var n;return t=(.5-t)*Math.PI,cm.r=255*(n=Math.sin(t))*n,cm.g=255*(n=Math.sin(t+fm))*n,cm.b=255*(n=Math.sin(t+sm))*n,cm+""},t.interpolateSpectral=xb,t.interpolateString=Xr,t.interpolateTransformCss=ti,t.interpolateTransformSvg=ni,t.interpolateTurbo=function(t){return t=Math.max(0,Math.min(1,t)),"rgb("+Math.max(0,Math.min(255,Math.round(34.61+t*(1172.33-t*(10793.56-t*(33300.12-t*(38394.49-14825.05*t)))))))+", "+Math.max(0,Math.min(255,Math.round(23.31+t*(557.33+t*(1225.33-t*(3574.96-t*(1073.77+707.56*t)))))))+", "+Math.max(0,Math.min(255,Math.round(27.2+t*(3211.1-t*(15327.97-t*(27814-t*(22569.18-6838.66*t)))))))+")"},t.interpolateViridis=hm,t.interpolateWarm=om,t.interpolateYlGn=Bb,t.interpolateYlGnBu=Ib,t.interpolateYlOrBr=Lb,t.interpolateYlOrRd=Hb,t.interpolateZoom=ri,t.interrupt=Gi,t.intersection=function(t,...n){t=new InternSet(t),n=n.map(vt);t:for(const e of t)for(const r of n)if(!r.has(e)){t.delete(e);continue t}return t},t.interval=function(t,n,e){var r=new Ei,i=n;return null==n?(r.restart(t,n,e),r):(r._restart=r.restart,r.restart=function(t,n,e){n=+n,e=null==e?Ai():+e,r._restart((function o(a){a+=i,r._restart(o,i+=n,e),t(a)}),n,e)},r.restart(t,n,e),r)},t.isoFormat=D_,t.isoParse=F_,t.json=function(t,n){return fetch(t,n).then(Tc)},t.lab=ar,t.lch=function(t,n,e,r){return 1===arguments.length?hr(t):new pr(e,n,t,null==r?1:r)},t.least=function(t,e=n){let r,i=!1;if(1===e.length){let o;for(const a of t){const t=e(a);(i?n(t,o)<0:0===n(t,t))&&(r=a,o=t,i=!0)}}else for(const n of t)(i?e(n,r)<0:0===e(n,n))&&(r=n,i=!0);return r},t.leastIndex=ht,t.line=Ym,t.lineRadial=Zm,t.link=ax,t.linkHorizontal=function(){return ax(nx)},t.linkRadial=function(){const t=ax(rx);return t.angle=t.x,delete t.x,t.radius=t.y,delete t.y,t},t.linkVertical=function(){return ax(ex)},t.local=Qn,t.map=function(t,n){if("function"!=typeof t[Symbol.iterator])throw new TypeError("values is not iterable");if("function"!=typeof n)throw new TypeError("mapper is not a function");return Array.from(t,((e,r)=>n(e,r,t)))},t.matcher=Vt,t.max=J,t.maxIndex=tt,t.mean=function(t,n){let e=0,r=0;if(void 0===n)for(let n of t)null!=n&&(n=+n)>=n&&(++e,r+=n);else{let i=-1;for(let o of t)null!=(o=n(o,++i,t))&&(o=+o)>=o&&(++e,r+=o)}if(e)return r/e},t.median=function(t,n){return at(t,.5,n)},t.medianIndex=function(t,n){return ct(t,.5,n)},t.merge=ft,t.min=nt,t.minIndex=et,t.mode=function(t,n){const e=new InternMap;if(void 0===n)for(let n of t)null!=n&&n>=n&&e.set(n,(e.get(n)||0)+1);else{let r=-1;for(let i of t)null!=(i=n(i,++r,t))&&i>=i&&e.set(i,(e.get(i)||0)+1)}let r,i=0;for(const[t,n]of e)n>i&&(i=n,r=t);return r},t.namespace=It,t.namespaces=Ut,t.nice=Z,t.now=Ai,t.pack=function(){var t=null,n=1,e=1,r=np;function i(i){const o=ap();return i.x=n/2,i.y=e/2,t?i.eachBefore(xp(t)).eachAfter(wp(r,.5,o)).eachBefore(Mp(1)):i.eachBefore(xp(mp)).eachAfter(wp(np,1,o)).eachAfter(wp(r,i.r/Math.min(n,e),o)).eachBefore(Mp(Math.min(n,e)/(2*i.r))),i}return i.radius=function(n){return arguments.length?(t=Jd(n),i):t},i.size=function(t){return arguments.length?(n=+t[0],e=+t[1],i):[n,e]},i.padding=function(t){return arguments.length?(r="function"==typeof t?t:ep(+t),i):r},i},t.packEnclose=function(t){return up(t,ap())},t.packSiblings=function(t){return bp(t,ap()),t},t.pairs=function(t,n=st){const e=[];let r,i=!1;for(const o of t)i&&e.push(n(r,o)),r=o,i=!0;return e},t.partition=function(){var t=1,n=1,e=0,r=!1;function i(i){var o=i.height+1;return i.x0=i.y0=e,i.x1=t,i.y1=n/o,i.eachBefore(function(t,n){return function(r){r.children&&Ap(r,r.x0,t*(r.depth+1)/n,r.x1,t*(r.depth+2)/n);var i=r.x0,o=r.y0,a=r.x1-e,u=r.y1-e;a0&&(d+=l);for(null!=n?p.sort((function(t,e){return n(g[t],g[e])})):null!=e&&p.sort((function(t,n){return e(a[t],a[n])})),u=0,f=d?(v-h*b)/d:0;u0?l*f:0)+b,g[c]={data:a[c],index:u,value:l,startAngle:y,endAngle:s,padAngle:_};return g}return a.value=function(n){return arguments.length?(t="function"==typeof n?n:ym(+n),a):t},a.sortValues=function(t){return arguments.length?(n=t,e=null,a):n},a.sort=function(t){return arguments.length?(e=t,n=null,a):e},a.startAngle=function(t){return arguments.length?(r="function"==typeof t?t:ym(+t),a):r},a.endAngle=function(t){return arguments.length?(i="function"==typeof t?t:ym(+t),a):i},a.padAngle=function(t){return arguments.length?(o="function"==typeof t?t:ym(+t),a):o},a},t.piecewise=di,t.pointRadial=Qm,t.pointer=ne,t.pointers=function(t,n){return t.target&&(t=te(t),void 0===n&&(n=t.currentTarget),t=t.touches||[t]),Array.from(t,(t=>ne(t,n)))},t.polygonArea=function(t){for(var n,e=-1,r=t.length,i=t[r-1],o=0;++eu!=f>u&&a<(c-e)*(u-r)/(f-r)+e&&(s=!s),c=e,f=r;return s},t.polygonHull=function(t){if((e=t.length)<3)return null;var n,e,r=new Array(e),i=new Array(e);for(n=0;n=0;--n)f.push(t[r[o[n]][2]]);for(n=+u;n(n=1664525*n+1013904223|0,lg*(n>>>0))},t.randomLogNormal=Kp,t.randomLogistic=fg,t.randomNormal=Zp,t.randomPareto=ng,t.randomPoisson=sg,t.randomUniform=Vp,t.randomWeibull=ug,t.range=lt,t.rank=function(t,e=n){if("function"!=typeof t[Symbol.iterator])throw new TypeError("values is not iterable");let r=Array.from(t);const i=new Float64Array(r.length);2!==e.length&&(r=r.map(e),e=n);const o=(t,n)=>e(r[t],r[n]);let a,u;return(t=Uint32Array.from(r,((t,n)=>n))).sort(e===n?(t,n)=>O(r[t],r[n]):I(o)),t.forEach(((t,n)=>{const e=o(t,void 0===a?t:a);e>=0?((void 0===a||e>0)&&(a=t,u=n),i[t]=u):i[t]=NaN})),i},t.reduce=function(t,n,e){if("function"!=typeof n)throw new TypeError("reducer is not a function");const r=t[Symbol.iterator]();let i,o,a=-1;if(arguments.length<3){if(({done:i,value:e}=r.next()),i)return;++a}for(;({done:i,value:o}=r.next()),!i;)e=n(e,o,++a,t);return e},t.reverse=function(t){if("function"!=typeof t[Symbol.iterator])throw new TypeError("values is not iterable");return Array.from(t).reverse()},t.rgb=Fe,t.ribbon=function(){return Wa()},t.ribbonArrow=function(){return Wa(Va)},t.rollup=$,t.rollups=D,t.scaleBand=yg,t.scaleDiverging=function t(){var n=Ng(L_()(mg));return n.copy=function(){return B_(n,t())},dg.apply(n,arguments)},t.scaleDivergingLog=function t(){var n=Fg(L_()).domain([.1,1,10]);return n.copy=function(){return B_(n,t()).base(n.base())},dg.apply(n,arguments)},t.scaleDivergingPow=j_,t.scaleDivergingSqrt=function(){return j_.apply(null,arguments).exponent(.5)},t.scaleDivergingSymlog=function t(){var n=Ig(L_());return n.copy=function(){return B_(n,t()).constant(n.constant())},dg.apply(n,arguments)},t.scaleIdentity=function t(n){var e;function r(t){return null==t||isNaN(t=+t)?e:t}return r.invert=r,r.domain=r.range=function(t){return arguments.length?(n=Array.from(t,_g),r):n.slice()},r.unknown=function(t){return arguments.length?(e=t,r):e},r.copy=function(){return t(n).unknown(e)},n=arguments.length?Array.from(n,_g):[0,1],Ng(r)},t.scaleImplicit=pg,t.scaleLinear=function t(){var n=Sg();return n.copy=function(){return Tg(n,t())},hg.apply(n,arguments),Ng(n)},t.scaleLog=function t(){const n=Fg(Ag()).domain([1,10]);return n.copy=()=>Tg(n,t()).base(n.base()),hg.apply(n,arguments),n},t.scaleOrdinal=gg,t.scalePoint=function(){return vg(yg.apply(null,arguments).paddingInner(1))},t.scalePow=jg,t.scaleQuantile=function t(){var e,r=[],i=[],o=[];function a(){var t=0,n=Math.max(1,i.length);for(o=new Array(n-1);++t0?o[n-1]:r[0],n=i?[o[i-1],r]:[o[n-1],o[n]]},u.unknown=function(t){return arguments.length?(n=t,u):u},u.thresholds=function(){return o.slice()},u.copy=function(){return t().domain([e,r]).range(a).unknown(n)},hg.apply(Ng(u),arguments)},t.scaleRadial=function t(){var n,e=Sg(),r=[0,1],i=!1;function o(t){var r=function(t){return Math.sign(t)*Math.sqrt(Math.abs(t))}(e(t));return isNaN(r)?n:i?Math.round(r):r}return o.invert=function(t){return e.invert(Hg(t))},o.domain=function(t){return arguments.length?(e.domain(t),o):e.domain()},o.range=function(t){return arguments.length?(e.range((r=Array.from(t,_g)).map(Hg)),o):r.slice()},o.rangeRound=function(t){return o.range(t).round(!0)},o.round=function(t){return arguments.length?(i=!!t,o):i},o.clamp=function(t){return arguments.length?(e.clamp(t),o):e.clamp()},o.unknown=function(t){return arguments.length?(n=t,o):n},o.copy=function(){return t(e.domain(),r).round(i).clamp(e.clamp()).unknown(n)},hg.apply(o,arguments),Ng(o)},t.scaleSequential=function t(){var n=Ng(O_()(mg));return n.copy=function(){return B_(n,t())},dg.apply(n,arguments)},t.scaleSequentialLog=function t(){var n=Fg(O_()).domain([1,10]);return n.copy=function(){return B_(n,t()).base(n.base())},dg.apply(n,arguments)},t.scaleSequentialPow=Y_,t.scaleSequentialQuantile=function t(){var e=[],r=mg;function i(t){if(null!=t&&!isNaN(t=+t))return r((s(e,t,1)-1)/(e.length-1))}return i.domain=function(t){if(!arguments.length)return e.slice();e=[];for(let n of t)null==n||isNaN(n=+n)||e.push(n);return e.sort(n),i},i.interpolator=function(t){return arguments.length?(r=t,i):r},i.range=function(){return e.map(((t,n)=>r(n/(e.length-1))))},i.quantiles=function(t){return Array.from({length:t+1},((n,r)=>at(e,r/t)))},i.copy=function(){return t(r).domain(e)},dg.apply(i,arguments)},t.scaleSequentialSqrt=function(){return Y_.apply(null,arguments).exponent(.5)},t.scaleSequentialSymlog=function t(){var n=Ig(O_());return n.copy=function(){return B_(n,t()).constant(n.constant())},dg.apply(n,arguments)},t.scaleSqrt=function(){return jg.apply(null,arguments).exponent(.5)},t.scaleSymlog=function t(){var n=Ig(Ag());return n.copy=function(){return Tg(n,t()).constant(n.constant())},hg.apply(n,arguments)},t.scaleThreshold=function t(){var n,e=[.5],r=[0,1],i=1;function o(t){return null!=t&&t<=t?r[s(e,t,0,i)]:n}return o.domain=function(t){return arguments.length?(e=Array.from(t),i=Math.min(e.length,r.length-1),o):e.slice()},o.range=function(t){return arguments.length?(r=Array.from(t),i=Math.min(e.length,r.length-1),o):r.slice()},o.invertExtent=function(t){var n=r.indexOf(t);return[e[n-1],e[n]]},o.unknown=function(t){return arguments.length?(n=t,o):n},o.copy=function(){return t().domain(e).range(r).unknown(n)},hg.apply(o,arguments)},t.scaleTime=function(){return hg.apply(I_(uv,cv,tv,Zy,xy,py,sy,ay,iy,t.timeFormat).domain([new Date(2e3,0,1),new Date(2e3,0,2)]),arguments)},t.scaleUtc=function(){return hg.apply(I_(ov,av,ev,Qy,Fy,yy,hy,cy,iy,t.utcFormat).domain([Date.UTC(2e3,0,1),Date.UTC(2e3,0,2)]),arguments)},t.scan=function(t,n){const e=ht(t,n);return e<0?void 0:e},t.schemeAccent=G_,t.schemeBlues=Xb,t.schemeBrBG=ib,t.schemeBuGn=wb,t.schemeBuPu=Tb,t.schemeCategory10=X_,t.schemeDark2=V_,t.schemeGnBu=Sb,t.schemeGreens=Vb,t.schemeGreys=Zb,t.schemeObservable10=W_,t.schemeOrRd=Nb,t.schemeOranges=em,t.schemePRGn=ab,t.schemePaired=Z_,t.schemePastel1=K_,t.schemePastel2=Q_,t.schemePiYG=cb,t.schemePuBu=zb,t.schemePuBuGn=Cb,t.schemePuOr=sb,t.schemePuRd=Db,t.schemePurples=Qb,t.schemeRdBu=hb,t.schemeRdGy=pb,t.schemeRdPu=Fb,t.schemeRdYlBu=yb,t.schemeRdYlGn=_b,t.schemeReds=tm,t.schemeSet1=J_,t.schemeSet2=tb,t.schemeSet3=nb,t.schemeSpectral=mb,t.schemeTableau10=eb,t.schemeYlGn=Ob,t.schemeYlGnBu=Ub,t.schemeYlOrBr=Yb,t.schemeYlOrRd=jb,t.select=Zn,t.selectAll=function(t){return"string"==typeof t?new Vn([document.querySelectorAll(t)],[document.documentElement]):new Vn([Ht(t)],Gn)},t.selection=Wn,t.selector=jt,t.selectorAll=Gt,t.shuffle=dt,t.shuffler=pt,t.some=function(t,n){if("function"!=typeof n)throw new TypeError("test is not a function");let e=-1;for(const r of t)if(n(r,++e,t))return!0;return!1},t.sort=U,t.stack=function(){var t=ym([]),n=dw,e=hw,r=pw;function i(i){var o,a,u=Array.from(t.apply(this,arguments),gw),c=u.length,f=-1;for(const t of i)for(o=0,++f;o0)for(var e,r,i,o,a,u,c=0,f=t[n[0]].length;c0?(r[0]=o,r[1]=o+=i):i<0?(r[1]=a,r[0]=a+=i):(r[0]=0,r[1]=i)},t.stackOffsetExpand=function(t,n){if((r=t.length)>0){for(var e,r,i,o=0,a=t[0].length;o0){for(var e,r=0,i=t[n[0]],o=i.length;r0&&(r=(e=t[n[0]]).length)>0){for(var e,r,i,o=0,a=1;afunction(t){t=`${t}`;let n=t.length;zp(t,n-1)&&!zp(t,n-2)&&(t=t.slice(0,-1));return"/"===t[0]?t:`/${t}`}(t(n,e,r)))),e=n.map(Pp),i=new Set(n).add("");for(const t of e)i.has(t)||(i.add(t),n.push(t),e.push(Pp(t)),h.push(Np));d=(t,e)=>n[e],p=(t,n)=>e[n]}for(a=0,i=h.length;a=0&&(f=h[t]).data===Np;--t)f.data=null}if(u.parent=Sp,u.eachBefore((function(t){t.depth=t.parent.depth+1,--i})).eachBefore(Kd),u.parent=null,i>0)throw new Error("cycle");return u}return r.id=function(t){return arguments.length?(n=Jd(t),r):n},r.parentId=function(t){return arguments.length?(e=Jd(t),r):e},r.path=function(n){return arguments.length?(t=Jd(n),r):t},r},t.style=_n,t.subset=function(t,n){return _t(n,t)},t.sum=function(t,n){let e=0;if(void 0===n)for(let n of t)(n=+n)&&(e+=n);else{let r=-1;for(let i of t)(i=+n(i,++r,t))&&(e+=i)}return e},t.superset=_t,t.svg=Nc,t.symbol=function(t,n){let e=null,r=km(i);function i(){let i;if(e||(e=i=r()),t.apply(this,arguments).draw(e,+n.apply(this,arguments)),i)return e=null,i+""||null}return t="function"==typeof t?t:ym(t||fx),n="function"==typeof n?n:ym(void 0===n?64:+n),i.type=function(n){return arguments.length?(t="function"==typeof n?n:ym(n),i):t},i.size=function(t){return arguments.length?(n="function"==typeof t?t:ym(+t),i):n},i.context=function(t){return arguments.length?(e=null==t?null:t,i):e},i},t.symbolAsterisk=cx,t.symbolCircle=fx,t.symbolCross=sx,t.symbolDiamond=dx,t.symbolDiamond2=px,t.symbolPlus=gx,t.symbolSquare=yx,t.symbolSquare2=vx,t.symbolStar=xx,t.symbolTimes=Px,t.symbolTriangle=Mx,t.symbolTriangle2=Ax,t.symbolWye=Cx,t.symbolX=Px,t.symbols=zx,t.symbolsFill=zx,t.symbolsStroke=$x,t.text=mc,t.thresholdFreedmanDiaconis=function(t,n,e){const r=v(t),i=at(t,.75)-at(t,.25);return r&&i?Math.ceil((e-n)/(2*i*Math.pow(r,-1/3))):1},t.thresholdScott=function(t,n,e){const r=v(t),i=w(t);return r&&i?Math.ceil((e-n)*Math.cbrt(r)/(3.49*i)):1},t.thresholdSturges=K,t.tickFormat=Eg,t.tickIncrement=V,t.tickStep=W,t.ticks=G,t.timeDay=py,t.timeDays=gy,t.timeFormatDefaultLocale=P_,t.timeFormatLocale=hv,t.timeFriday=Sy,t.timeFridays=$y,t.timeHour=sy,t.timeHours=ly,t.timeInterval=Vg,t.timeMillisecond=Wg,t.timeMilliseconds=Zg,t.timeMinute=ay,t.timeMinutes=uy,t.timeMonday=wy,t.timeMondays=ky,t.timeMonth=Zy,t.timeMonths=Ky,t.timeSaturday=Ey,t.timeSaturdays=Dy,t.timeSecond=iy,t.timeSeconds=oy,t.timeSunday=xy,t.timeSundays=Ny,t.timeThursday=Ay,t.timeThursdays=zy,t.timeTickInterval=cv,t.timeTicks=uv,t.timeTuesday=My,t.timeTuesdays=Cy,t.timeWednesday=Ty,t.timeWednesdays=Py,t.timeWeek=xy,t.timeWeeks=Ny,t.timeYear=tv,t.timeYears=nv,t.timeout=$i,t.timer=Ni,t.timerFlush=ki,t.transition=go,t.transpose=gt,t.tree=function(){var t=$p,n=1,e=1,r=null;function i(i){var c=function(t){for(var n,e,r,i,o,a=new Up(t,0),u=[a];n=u.pop();)if(r=n._.children)for(n.children=new Array(o=r.length),i=o-1;i>=0;--i)u.push(e=n.children[i]=new Up(r[i],i)),e.parent=n;return(a.parent=new Up(null,0)).children=[a],a}(i);if(c.eachAfter(o),c.parent.m=-c.z,c.eachBefore(a),r)i.eachBefore(u);else{var f=i,s=i,l=i;i.eachBefore((function(t){t.xs.x&&(s=t),t.depth>l.depth&&(l=t)}));var h=f===s?1:t(f,s)/2,d=h-f.x,p=n/(s.x+h+d),g=e/(l.depth||1);i.eachBefore((function(t){t.x=(t.x+d)*p,t.y=t.depth*g}))}return i}function o(n){var e=n.children,r=n.parent.children,i=n.i?r[n.i-1]:null;if(e){!function(t){for(var n,e=0,r=0,i=t.children,o=i.length;--o>=0;)(n=i[o]).z+=e,n.m+=e,e+=n.s+(r+=n.c)}(n);var o=(e[0].z+e[e.length-1].z)/2;i?(n.z=i.z+t(n._,i._),n.m=n.z-o):n.z=o}else i&&(n.z=i.z+t(n._,i._));n.parent.A=function(n,e,r){if(e){for(var i,o=n,a=n,u=e,c=o.parent.children[0],f=o.m,s=a.m,l=u.m,h=c.m;u=Rp(u),o=Dp(o),u&&o;)c=Dp(c),(a=Rp(a)).a=n,(i=u.z+l-o.z-f+t(u._,o._))>0&&(Fp(qp(u,n,r),n,i),f+=i,s+=i),l+=u.m,f+=o.m,h+=c.m,s+=a.m;u&&!Rp(a)&&(a.t=u,a.m+=l-s),o&&!Dp(c)&&(c.t=o,c.m+=f-h,r=n)}return r}(n,i,n.parent.A||r[0])}function a(t){t._.x=t.z+t.parent.m,t.m+=t.parent.m}function u(t){t.x*=n,t.y=t.depth*e}return i.separation=function(n){return arguments.length?(t=n,i):t},i.size=function(t){return arguments.length?(r=!1,n=+t[0],e=+t[1],i):r?null:[n,e]},i.nodeSize=function(t){return arguments.length?(r=!0,n=+t[0],e=+t[1],i):r?[n,e]:null},i},t.treemap=function(){var t=Yp,n=!1,e=1,r=1,i=[0],o=np,a=np,u=np,c=np,f=np;function s(t){return t.x0=t.y0=0,t.x1=e,t.y1=r,t.eachBefore(l),i=[0],n&&t.eachBefore(Tp),t}function l(n){var e=i[n.depth],r=n.x0+e,s=n.y0+e,l=n.x1-e,h=n.y1-e;l=e-1){var s=u[n];return s.x0=i,s.y0=o,s.x1=a,void(s.y1=c)}var l=f[n],h=r/2+l,d=n+1,p=e-1;for(;d>>1;f[g]c-o){var _=r?(i*v+a*y)/r:a;t(n,d,y,i,o,_,c),t(d,e,v,_,o,a,c)}else{var b=r?(o*v+c*y)/r:c;t(n,d,y,i,o,a,b),t(d,e,v,i,b,a,c)}}(0,c,t.value,n,e,r,i)},t.treemapDice=Ap,t.treemapResquarify=Lp,t.treemapSlice=Ip,t.treemapSliceDice=function(t,n,e,r,i){(1&t.depth?Ip:Ap)(t,n,e,r,i)},t.treemapSquarify=Yp,t.tsv=Mc,t.tsvFormat=lc,t.tsvFormatBody=hc,t.tsvFormatRow=pc,t.tsvFormatRows=dc,t.tsvFormatValue=gc,t.tsvParse=fc,t.tsvParseRows=sc,t.union=function(...t){const n=new InternSet;for(const e of t)for(const t of e)n.add(t);return n},t.unixDay=_y,t.unixDays=by,t.utcDay=yy,t.utcDays=vy,t.utcFriday=By,t.utcFridays=Vy,t.utcHour=hy,t.utcHours=dy,t.utcMillisecond=Wg,t.utcMilliseconds=Zg,t.utcMinute=cy,t.utcMinutes=fy,t.utcMonday=qy,t.utcMondays=jy,t.utcMonth=Qy,t.utcMonths=Jy,t.utcSaturday=Yy,t.utcSaturdays=Wy,t.utcSecond=iy,t.utcSeconds=oy,t.utcSunday=Fy,t.utcSundays=Ly,t.utcThursday=Oy,t.utcThursdays=Gy,t.utcTickInterval=av,t.utcTicks=ov,t.utcTuesday=Uy,t.utcTuesdays=Hy,t.utcWednesday=Iy,t.utcWednesdays=Xy,t.utcWeek=Fy,t.utcWeeks=Ly,t.utcYear=ev,t.utcYears=rv,t.variance=x,t.version="7.9.0",t.window=pn,t.xml=Sc,t.zip=function(){return gt(arguments)},t.zoom=function(){var t,n,e,r=Ew,i=Nw,o=zw,a=Cw,u=Pw,c=[0,1/0],f=[[-1/0,-1/0],[1/0,1/0]],s=250,l=ri,h=$t("start","zoom","end"),d=500,p=150,g=0,y=10;function v(t){t.property("__zoom",kw).on("wheel.zoom",T,{passive:!1}).on("mousedown.zoom",A).on("dblclick.zoom",S).filter(u).on("touchstart.zoom",E).on("touchmove.zoom",N).on("touchend.zoom touchcancel.zoom",k).style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}function _(t,n){return(n=Math.max(c[0],Math.min(c[1],n)))===t.k?t:new ww(n,t.x,t.y)}function b(t,n,e){var r=n[0]-e[0]*t.k,i=n[1]-e[1]*t.k;return r===t.x&&i===t.y?t:new ww(t.k,r,i)}function m(t){return[(+t[0][0]+ +t[1][0])/2,(+t[0][1]+ +t[1][1])/2]}function x(t,n,e,r){t.on("start.zoom",(function(){w(this,arguments).event(r).start()})).on("interrupt.zoom end.zoom",(function(){w(this,arguments).event(r).end()})).tween("zoom",(function(){var t=this,o=arguments,a=w(t,o).event(r),u=i.apply(t,o),c=null==e?m(u):"function"==typeof e?e.apply(t,o):e,f=Math.max(u[1][0]-u[0][0],u[1][1]-u[0][1]),s=t.__zoom,h="function"==typeof n?n.apply(t,o):n,d=l(s.invert(c).concat(f/s.k),h.invert(c).concat(f/h.k));return function(t){if(1===t)t=h;else{var n=d(t),e=f/n[2];t=new ww(e,c[0]-n[0]*e,c[1]-n[1]*e)}a.zoom(null,t)}}))}function w(t,n,e){return!e&&t.__zooming||new M(t,n)}function M(t,n){this.that=t,this.args=n,this.active=0,this.sourceEvent=null,this.extent=i.apply(t,n),this.taps=0}function T(t,...n){if(r.apply(this,arguments)){var e=w(this,n).event(t),i=this.__zoom,u=Math.max(c[0],Math.min(c[1],i.k*Math.pow(2,a.apply(this,arguments)))),s=ne(t);if(e.wheel)e.mouse[0][0]===s[0]&&e.mouse[0][1]===s[1]||(e.mouse[1]=i.invert(e.mouse[0]=s)),clearTimeout(e.wheel);else{if(i.k===u)return;e.mouse=[s,i.invert(s)],Gi(this),e.start()}Sw(t),e.wheel=setTimeout((function(){e.wheel=null,e.end()}),p),e.zoom("mouse",o(b(_(i,u),e.mouse[0],e.mouse[1]),e.extent,f))}}function A(t,...n){if(!e&&r.apply(this,arguments)){var i=t.currentTarget,a=w(this,n,!0).event(t),u=Zn(t.view).on("mousemove.zoom",(function(t){if(Sw(t),!a.moved){var n=t.clientX-s,e=t.clientY-l;a.moved=n*n+e*e>g}a.event(t).zoom("mouse",o(b(a.that.__zoom,a.mouse[0]=ne(t,i),a.mouse[1]),a.extent,f))}),!0).on("mouseup.zoom",(function(t){u.on("mousemove.zoom mouseup.zoom",null),ue(t.view,a.moved),Sw(t),a.event(t).end()}),!0),c=ne(t,i),s=t.clientX,l=t.clientY;ae(t.view),Aw(t),a.mouse=[c,this.__zoom.invert(c)],Gi(this),a.start()}}function S(t,...n){if(r.apply(this,arguments)){var e=this.__zoom,a=ne(t.changedTouches?t.changedTouches[0]:t,this),u=e.invert(a),c=e.k*(t.shiftKey?.5:2),l=o(b(_(e,c),a,u),i.apply(this,n),f);Sw(t),s>0?Zn(this).transition().duration(s).call(x,l,a,t):Zn(this).call(v.transform,l,a,t)}}function E(e,...i){if(r.apply(this,arguments)){var o,a,u,c,f=e.touches,s=f.length,l=w(this,i,e.changedTouches.length===s).event(e);for(Aw(e),a=0;a0}},{}],14:[function(require,module,exports){module.exports=intersectNode;function intersectNode(node,point){return node.intersect(point)}},{}],15:[function(require,module,exports){ -/* eslint "no-console": off */ -var intersectLine=require("./intersect-line");module.exports=intersectPolygon; -/* - * Returns the point ({x, y}) at which the point argument intersects with the - * node argument assuming that it has the shape specified by polygon. - */function intersectPolygon(node,polyPoints,point){var x1=node.x;var y1=node.y;var intersections=[];var minX=Number.POSITIVE_INFINITY;var minY=Number.POSITIVE_INFINITY;polyPoints.forEach(function(entry){minX=Math.min(minX,entry.x);minY=Math.min(minY,entry.y)});var left=x1-node.width/2-minX;var top=y1-node.height/2-minY;for(var i=0;i1){ -// More intersections, find the one nearest to edge end point -intersections.sort(function(p,q){var pdx=p.x-point.x;var pdy=p.y-point.y;var distp=Math.sqrt(pdx*pdx+pdy*pdy);var qdx=q.x-point.x;var qdy=q.y-point.y;var distq=Math.sqrt(qdx*qdx+qdy*qdy);return distpMath.abs(dx)*h){ -// Intersection is top or bottom of rect. -if(dy<0){h=-h}sx=dy===0?0:h*dx/dy;sy=h}else{ -// Intersection is left or right of rect. -if(dx<0){w=-w}sx=w;sy=dx===0?0:w*dy/dx}return{x:x+sx,y:y+sy}}},{}],17:[function(require,module,exports){var util=require("../util");module.exports=addHtmlLabel;function addHtmlLabel(root,node){var fo=root.append("foreignObject").attr("width","100000");var div=fo.append("xhtml:div");div.attr("xmlns","http://www.w3.org/1999/xhtml");var label=node.label;switch(typeof label){case"function":div.insert(label);break;case"object": -// Currently we assume this is a DOM object. -div.insert(function(){return label});break;default:div.html(label)}util.applyStyle(div,node.labelStyle);div.style("display","inline-block"); -// Fix for firefox -div.style("white-space","nowrap");var client=div.node().getBoundingClientRect();fo.attr("width",client.width).attr("height",client.height);return fo}},{"../util":27}],18:[function(require,module,exports){var addTextLabel=require("./add-text-label");var addHtmlLabel=require("./add-html-label");var addSVGLabel=require("./add-svg-label");module.exports=addLabel;function addLabel(root,node,location){var label=node.label;var labelSvg=root.append("g"); -// Allow the label to be a string, a function that returns a DOM element, or -// a DOM element itself. -if(node.labelType==="svg"){addSVGLabel(labelSvg,node)}else if(typeof label!=="string"||node.labelType==="html"){addHtmlLabel(labelSvg,node)}else{addTextLabel(labelSvg,node)}var labelBBox=labelSvg.node().getBBox();var y;switch(location){case"top":y=-node.height/2;break;case"bottom":y=node.height/2-labelBBox.height;break;default:y=-labelBBox.height/2}labelSvg.attr("transform","translate("+-labelBBox.width/2+","+y+")");return labelSvg}},{"./add-html-label":17,"./add-svg-label":19,"./add-text-label":20}],19:[function(require,module,exports){var util=require("../util");module.exports=addSVGLabel;function addSVGLabel(root,node){var domNode=root;domNode.node().appendChild(node.label);util.applyStyle(domNode,node.labelStyle);return domNode}},{"../util":27}],20:[function(require,module,exports){var util=require("../util");module.exports=addTextLabel; -/* - * Attaches a text label to the specified root. Handles escape sequences. - */function addTextLabel(root,node){var domNode=root.append("text");var lines=processEscapeSequences(node.label).split("\n");for(var i=0;ib?1:a>=b?0:NaN}function bisector(compare){if(compare.length===1)compare=ascendingComparator(compare);return{left:function(a,x,lo,hi){if(lo==null)lo=0;if(hi==null)hi=a.length;while(lo>>1;if(compare(a[mid],x)<0)lo=mid+1;else hi=mid}return lo},right:function(a,x,lo,hi){if(lo==null)lo=0;if(hi==null)hi=a.length;while(lo>>1;if(compare(a[mid],x)>0)hi=mid;else lo=mid+1}return lo}}}function ascendingComparator(f){return function(d,x){return ascending(f(d),x)}}var ascendingBisect=bisector(ascending);var bisectRight=ascendingBisect.right;var bisectLeft=ascendingBisect.left;function pairs(array,f){if(f==null)f=pair;var i=0,n=array.length-1,p=array[0],pairs=new Array(n<0?0:n);while(ia?1:b>=a?0:NaN}function number(x){return x===null?NaN:+x}function variance(values,valueof){var n=values.length,m=0,i=-1,mean=0,value,delta,sum=0;if(valueof==null){while(++i1)return sum/(m-1)}function deviation(array,f){var v=variance(array,f);return v?Math.sqrt(v):v}function extent(values,valueof){var n=values.length,i=-1,value,min,max;if(valueof==null){while(++i=value){min=max=value;while(++ivalue)min=value;if(max=value){min=max=value;while(++ivalue)min=value;if(max0)return[start];if(reverse=stop0){start=Math.ceil(start/step);stop=Math.floor(stop/step);ticks=new Array(n=Math.ceil(stop-start+1));while(++i=0?(error>=e10?10:error>=e5?5:error>=e2?2:1)*Math.pow(10,power):-Math.pow(10,-power)/(error>=e10?10:error>=e5?5:error>=e2?2:1)}function tickStep(start,stop,count){var step0=Math.abs(stop-start)/Math.max(0,count),step1=Math.pow(10,Math.floor(Math.log(step0)/Math.LN10)),error=step0/step1;if(error>=e10)step1*=10;else if(error>=e5)step1*=5;else if(error>=e2)step1*=2;return stopx1)tz.pop(),--m;var bins=new Array(m+1),bin; -// Initialize bins. -for(i=0;i<=m;++i){bin=bins[i]=[];bin.x0=i>0?tz[i-1]:x0;bin.x1=i=1)return+valueof(values[n-1],n-1,values);var n,i=(n-1)*p,i0=Math.floor(i),value0=+valueof(values[i0],i0,values),value1=+valueof(values[i0+1],i0+1,values);return value0+(value1-value0)*(i-i0)}function freedmanDiaconis(values,min,max){values=map.call(values,number).sort(ascending);return Math.ceil((max-min)/(2*(quantile(values,.75)-quantile(values,.25))*Math.pow(values.length,-1/3)))}function scott(values,min,max){return Math.ceil((max-min)/(3.5*deviation(values)*Math.pow(values.length,-1/3)))}function max(values,valueof){var n=values.length,i=-1,value,max;if(valueof==null){while(++i=value){max=value;while(++imax){max=value}}}}}else{while(++i=value){max=value;while(++imax){max=value}}}}}return max}function mean(values,valueof){var n=values.length,m=n,i=-1,value,sum=0;if(valueof==null){while(++i=0){array=arrays[n];m=array.length;while(--m>=0){merged[--j]=array[m]}}return merged}function min(values,valueof){var n=values.length,i=-1,value,min;if(valueof==null){while(++i=value){min=value;while(++ivalue){min=value}}}}}else{while(++i=value){min=value;while(++ivalue){min=value}}}}}return min}function permute(array,indexes){var i=indexes.length,permutes=new Array(i);while(i--)permutes[i]=array[indexes[i]];return permutes}function scan(values,compare){if(!(n=values.length))return;var n,i=0,j=0,xi,xj=values[j];if(compare==null)compare=ascending;while(++iMath.abs(point1[1]-point[1]))lockY=true;else lockX=true}point=point1;moving=true;noevent();move()}function move(){var t;dx=point[0]-point0[0];dy=point[1]-point0[1];switch(mode){case MODE_SPACE:case MODE_DRAG:{if(signX)dx=Math.max(W-w0,Math.min(E-e0,dx)),w1=w0+dx,e1=e0+dx;if(signY)dy=Math.max(N-n0,Math.min(S-s0,dy)),n1=n0+dy,s1=s0+dy;break}case MODE_HANDLE:{if(signX<0)dx=Math.max(W-w0,Math.min(E-w0,dx)),w1=w0+dx,e1=e0;else if(signX>0)dx=Math.max(W-e0,Math.min(E-e0,dx)),w1=w0,e1=e0+dx;if(signY<0)dy=Math.max(N-n0,Math.min(S-n0,dy)),n1=n0+dy,s1=s0;else if(signY>0)dy=Math.max(N-s0,Math.min(S-s0,dy)),n1=n0,s1=s0+dy;break}case MODE_CENTER:{if(signX)w1=Math.max(W,Math.min(E,w0-dx*signX)),e1=Math.max(W,Math.min(E,e0+dx*signX));if(signY)n1=Math.max(N,Math.min(S,n0-dy*signY)),s1=Math.max(N,Math.min(S,s0+dy*signY));break}}if(e10)w0=w1-dx;if(signY<0)s0=s1-dy;else if(signY>0)n0=n1-dy;mode=MODE_SPACE;overlay.attr("cursor",cursors.selection);move()}break}default:return}noevent()}function keyupped(){switch(d3Selection.event.keyCode){case 16:{// SHIFT -if(shifting){lockX=lockY=shifting=false;move()}break}case 18:{// ALT -if(mode===MODE_CENTER){if(signX<0)e0=e1;else if(signX>0)w0=w1;if(signY<0)s0=s1;else if(signY>0)n0=n1;mode=MODE_HANDLE;move()}break}case 32:{// SPACE -if(mode===MODE_SPACE){if(d3Selection.event.altKey){if(signX)e0=e1-dx*signX,w0=w1+dx*signX;if(signY)s0=s1-dy*signY,n0=n1+dy*signY;mode=MODE_CENTER}else{if(signX<0)e0=e1;else if(signX>0)w0=w1;if(signY<0)s0=s1;else if(signY>0)n0=n1;mode=MODE_HANDLE}overlay.attr("cursor",cursors[type]);move()}break}default:return}noevent()}}function touchmoved(){emitter(this,arguments).moved()}function touchended(){emitter(this,arguments).ended()}function initialize(){var state=this.__brush||{selection:null};state.extent=number2(extent.apply(this,arguments));state.dim=dim;return state}brush.extent=function(_){return arguments.length?(extent=typeof _==="function"?_:constant(number2(_)),brush):extent};brush.filter=function(_){return arguments.length?(filter=typeof _==="function"?_:constant(!!_),brush):filter};brush.touchable=function(_){return arguments.length?(touchable=typeof _==="function"?_:constant(!!_),brush):touchable};brush.handleSize=function(_){return arguments.length?(handleSize=+_,brush):handleSize};brush.keyModifiers=function(_){return arguments.length?(keys=!!_,brush):keys};brush.on=function(){var value=listeners.on.apply(listeners,arguments);return value===listeners?brush:value};return brush}exports.brush=brush;exports.brushSelection=brushSelection;exports.brushX=brushX;exports.brushY=brushY;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-dispatch":36,"d3-drag":37,"d3-interpolate":45,"d3-selection":52,"d3-transition":57}],32:[function(require,module,exports){ -// https://d3js.org/d3-chord/ v1.0.6 Copyright 2018 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports,require("d3-array"),require("d3-path")):typeof define==="function"&&define.amd?define(["exports","d3-array","d3-path"],factory):factory(global.d3=global.d3||{},global.d3,global.d3)})(this,function(exports,d3Array,d3Path){"use strict";var cos=Math.cos;var sin=Math.sin;var pi=Math.PI;var halfPi=pi/2;var tau=pi*2;var max=Math.max;function compareValue(compare){return function(a,b){return compare(a.source.value+a.target.value,b.source.value+b.target.value)}}function chord(){var padAngle=0,sortGroups=null,sortSubgroups=null,sortChords=null;function chord(matrix){var n=matrix.length,groupSums=[],groupIndex=d3Array.range(n),subgroupIndex=[],chords=[],groups=chords.groups=new Array(n),subgroups=new Array(n*n),k,x,x0,dx,i,j; -// Compute the sum. -k=0,i=-1;while(++i=keys.length){if(sortValues!=null)array.sort(sortValues);return rollup!=null?rollup(array):array}var i=-1,n=array.length,key=keys[depth++],keyValue,value,valuesByKey=map(),values,result=createResult();while(++ikeys.length)return map$$1;var array,sortKey=sortKeys[depth-1];if(rollup!=null&&depth>=keys.length)array=map$$1.entries();else array=[],map$$1.each(function(v,k){array.push({key:k,values:entries(v,depth)})});return sortKey!=null?array.sort(function(a,b){return sortKey(a.key,b.key)}):array}return nest={object:function(array){return apply(array,0,createObject,setObject)},map:function(array){return apply(array,0,createMap,setMap)},entries:function(array){return entries(apply(array,0,createMap,setMap),0)},key:function(d){keys.push(d);return nest},sortKeys:function(order){sortKeys[keys.length-1]=order;return nest},sortValues:function(order){sortValues=order;return nest},rollup:function(f){rollup=f;return nest}}}function createObject(){return{}}function setObject(object,key,value){object[key]=value}function createMap(){return map()}function setMap(map$$1,key,value){map$$1.set(key,value)}function Set(){}var proto=map.prototype;Set.prototype=set.prototype={constructor:Set,has:proto.has,add:function(value){value+="";this[prefix+value]=value;return this},remove:proto.remove,clear:proto.clear,values:proto.keys,size:proto.size,empty:proto.empty,each:proto.each};function set(object,f){var set=new Set; -// Copy constructor. -if(object instanceof Set)object.each(function(value){set.add(value)}); -// Otherwise, assume it’s an array. -else if(object){var i=-1,n=object.length;if(f==null)while(++i>8&15|m>>4&240,m>>4&15|m&240,(m&15)<<4|m&15,1):l===8?new Rgb(m>>24&255,m>>16&255,m>>8&255,(m&255)/255):l===4?new Rgb(m>>12&15|m>>8&240,m>>8&15|m>>4&240,m>>4&15|m&240,((m&15)<<4|m&15)/255):null):// invalid hex -(m=reRgbInteger.exec(format))?new Rgb(m[1],m[2],m[3],1):(m=reRgbPercent.exec(format))?new Rgb(m[1]*255/100,m[2]*255/100,m[3]*255/100,1):(m=reRgbaInteger.exec(format))?rgba(m[1],m[2],m[3],m[4]):(m=reRgbaPercent.exec(format))?rgba(m[1]*255/100,m[2]*255/100,m[3]*255/100,m[4]):(m=reHslPercent.exec(format))?hsla(m[1],m[2]/100,m[3]/100,1):(m=reHslaPercent.exec(format))?hsla(m[1],m[2]/100,m[3]/100,m[4]):named.hasOwnProperty(format)?rgbn(named[format]):format==="transparent"?new Rgb(NaN,NaN,NaN,0):null}function rgbn(n){return new Rgb(n>>16&255,n>>8&255,n&255,1)}function rgba(r,g,b,a){if(a<=0)r=g=b=NaN;return new Rgb(r,g,b,a)}function rgbConvert(o){if(!(o instanceof Color))o=color(o);if(!o)return new Rgb;o=o.rgb();return new Rgb(o.r,o.g,o.b,o.opacity)}function rgb(r,g,b,opacity){return arguments.length===1?rgbConvert(r):new Rgb(r,g,b,opacity==null?1:opacity)}function Rgb(r,g,b,opacity){this.r=+r;this.g=+g;this.b=+b;this.opacity=+opacity}define(Rgb,rgb,extend(Color,{brighter:function(k){k=k==null?brighter:Math.pow(brighter,k);return new Rgb(this.r*k,this.g*k,this.b*k,this.opacity)},darker:function(k){k=k==null?darker:Math.pow(darker,k);return new Rgb(this.r*k,this.g*k,this.b*k,this.opacity)},rgb:function(){return this},displayable:function(){return-.5<=this.r&&this.r<255.5&&(-.5<=this.g&&this.g<255.5)&&(-.5<=this.b&&this.b<255.5)&&(0<=this.opacity&&this.opacity<=1)},hex:rgb_formatHex,// Deprecated! Use color.formatHex. -formatHex:rgb_formatHex,formatRgb:rgb_formatRgb,toString:rgb_formatRgb}));function rgb_formatHex(){return"#"+hex(this.r)+hex(this.g)+hex(this.b)}function rgb_formatRgb(){var a=this.opacity;a=isNaN(a)?1:Math.max(0,Math.min(1,a));return(a===1?"rgb(":"rgba(")+Math.max(0,Math.min(255,Math.round(this.r)||0))+", "+Math.max(0,Math.min(255,Math.round(this.g)||0))+", "+Math.max(0,Math.min(255,Math.round(this.b)||0))+(a===1?")":", "+a+")")}function hex(value){value=Math.max(0,Math.min(255,Math.round(value)||0));return(value<16?"0":"")+value.toString(16)}function hsla(h,s,l,a){if(a<=0)h=s=l=NaN;else if(l<=0||l>=1)h=s=NaN;else if(s<=0)h=NaN;return new Hsl(h,s,l,a)}function hslConvert(o){if(o instanceof Hsl)return new Hsl(o.h,o.s,o.l,o.opacity);if(!(o instanceof Color))o=color(o);if(!o)return new Hsl;if(o instanceof Hsl)return o;o=o.rgb();var r=o.r/255,g=o.g/255,b=o.b/255,min=Math.min(r,g,b),max=Math.max(r,g,b),h=NaN,s=max-min,l=(max+min)/2;if(s){if(r===max)h=(g-b)/s+(g0&&l<1?0:h}return new Hsl(h,s,l,o.opacity)}function hsl(h,s,l,opacity){return arguments.length===1?hslConvert(h):new Hsl(h,s,l,opacity==null?1:opacity)}function Hsl(h,s,l,opacity){this.h=+h;this.s=+s;this.l=+l;this.opacity=+opacity}define(Hsl,hsl,extend(Color,{brighter:function(k){k=k==null?brighter:Math.pow(brighter,k);return new Hsl(this.h,this.s,this.l*k,this.opacity)},darker:function(k){k=k==null?darker:Math.pow(darker,k);return new Hsl(this.h,this.s,this.l*k,this.opacity)},rgb:function(){var h=this.h%360+(this.h<0)*360,s=isNaN(h)||isNaN(this.s)?0:this.s,l=this.l,m2=l+(l<.5?l:1-l)*s,m1=2*l-m2;return new Rgb(hsl2rgb(h>=240?h-240:h+120,m1,m2),hsl2rgb(h,m1,m2),hsl2rgb(h<120?h+240:h-120,m1,m2),this.opacity)},displayable:function(){return(0<=this.s&&this.s<=1||isNaN(this.s))&&(0<=this.l&&this.l<=1)&&(0<=this.opacity&&this.opacity<=1)},formatHsl:function(){var a=this.opacity;a=isNaN(a)?1:Math.max(0,Math.min(1,a));return(a===1?"hsl(":"hsla(")+(this.h||0)+", "+(this.s||0)*100+"%, "+(this.l||0)*100+"%"+(a===1?")":", "+a+")")}})); -/* From FvD 13.37, CSS Color Module Level 3 */function hsl2rgb(h,m1,m2){return(h<60?m1+(m2-m1)*h/60:h<180?m2:h<240?m1+(m2-m1)*(240-h)/60:m1)*255}var deg2rad=Math.PI/180;var rad2deg=180/Math.PI; -// https://observablehq.com/@mbostock/lab-and-rgb -var K=18,Xn=.96422,Yn=1,Zn=.82521,t0=4/29,t1=6/29,t2=3*t1*t1,t3=t1*t1*t1;function labConvert(o){if(o instanceof Lab)return new Lab(o.l,o.a,o.b,o.opacity);if(o instanceof Hcl)return hcl2lab(o);if(!(o instanceof Rgb))o=rgbConvert(o);var r=rgb2lrgb(o.r),g=rgb2lrgb(o.g),b=rgb2lrgb(o.b),y=xyz2lab((.2225045*r+.7168786*g+.0606169*b)/Yn),x,z;if(r===g&&g===b)x=z=y;else{x=xyz2lab((.4360747*r+.3850649*g+.1430804*b)/Xn);z=xyz2lab((.0139322*r+.0971045*g+.7141733*b)/Zn)}return new Lab(116*y-16,500*(x-y),200*(y-z),o.opacity)}function gray(l,opacity){return new Lab(l,0,0,opacity==null?1:opacity)}function lab(l,a,b,opacity){return arguments.length===1?labConvert(l):new Lab(l,a,b,opacity==null?1:opacity)}function Lab(l,a,b,opacity){this.l=+l;this.a=+a;this.b=+b;this.opacity=+opacity}define(Lab,lab,extend(Color,{brighter:function(k){return new Lab(this.l+K*(k==null?1:k),this.a,this.b,this.opacity)},darker:function(k){return new Lab(this.l-K*(k==null?1:k),this.a,this.b,this.opacity)},rgb:function(){var y=(this.l+16)/116,x=isNaN(this.a)?y:y+this.a/500,z=isNaN(this.b)?y:y-this.b/200;x=Xn*lab2xyz(x);y=Yn*lab2xyz(y);z=Zn*lab2xyz(z);return new Rgb(lrgb2rgb(3.1338561*x-1.6168667*y-.4906146*z),lrgb2rgb(-.9787684*x+1.9161415*y+.033454*z),lrgb2rgb(.0719453*x-.2289914*y+1.4052427*z),this.opacity)}}));function xyz2lab(t){return t>t3?Math.pow(t,1/3):t/t2+t0}function lab2xyz(t){return t>t1?t*t*t:t2*(t-t0)}function lrgb2rgb(x){return 255*(x<=.0031308?12.92*x:1.055*Math.pow(x,1/2.4)-.055)}function rgb2lrgb(x){return(x/=255)<=.04045?x/12.92:Math.pow((x+.055)/1.055,2.4)}function hclConvert(o){if(o instanceof Hcl)return new Hcl(o.h,o.c,o.l,o.opacity);if(!(o instanceof Lab))o=labConvert(o);if(o.a===0&&o.b===0)return new Hcl(NaN,0y!==yj>y&&x<(xj-xi)*(y-yi)/(yj-yi)+xi)contains=-contains}return contains}function segmentContains(a,b,c){var i;return collinear(a,b,c)&&within(a[i=+(a[0]===b[0])],c[i],b[i])}function collinear(a,b,c){return(b[0]-a[0])*(c[1]-a[1])===(c[0]-a[0])*(b[1]-a[1])}function within(p,q,r){return p<=q&&q<=r||r<=q&&q<=p}function noop(){}var cases=[[],[[[1,1.5],[.5,1]]],[[[1.5,1],[1,1.5]]],[[[1.5,1],[.5,1]]],[[[1,.5],[1.5,1]]],[[[1,1.5],[.5,1]],[[1,.5],[1.5,1]]],[[[1,.5],[1,1.5]]],[[[1,.5],[.5,1]]],[[[.5,1],[1,.5]]],[[[1,1.5],[1,.5]]],[[[.5,1],[1,.5]],[[1.5,1],[1,1.5]]],[[[1.5,1],[1,.5]]],[[[.5,1],[1.5,1]]],[[[1,1.5],[1.5,1]]],[[[.5,1],[1,1.5]]],[]];function contours(){var dx=1,dy=1,threshold=d3Array.thresholdSturges,smooth=smoothLinear;function contours(values){var tz=threshold(values); -// Convert number of thresholds into uniform thresholds. -if(!Array.isArray(tz)){var domain=d3Array.extent(values),start=domain[0],stop=domain[1];tz=d3Array.tickStep(start,stop,tz);tz=d3Array.range(Math.floor(start/tz)*tz,Math.floor(stop/tz)*tz,tz)}else{tz=tz.slice().sort(ascending)}return tz.map(function(value){return contour(values,value)})} -// Accumulate, smooth contour rings, assign holes to exterior rings. -// Based on https://github.com/mbostock/shapefile/blob/v0.6.2/shp/polygon.js -function contour(values,value){var polygons=[],holes=[];isorings(values,value,function(ring){smooth(ring,values,value);if(area(ring)>0)polygons.push([ring]);else holes.push(ring)});holes.forEach(function(hole){for(var i=0,n=polygons.length,polygon;i=value;cases[t1<<1].forEach(stitch);while(++x=value;cases[t0|t1<<1].forEach(stitch)}cases[t1<<0].forEach(stitch); -// General case for the intermediate rows. -while(++y=value;t2=values[y*dx]>=value;cases[t1<<1|t2<<2].forEach(stitch);while(++x=value;t3=t2,t2=values[y*dx+x+1]>=value;cases[t0|t1<<1|t2<<2|t3<<3].forEach(stitch)}cases[t1|t2<<3].forEach(stitch)} -// Special case for the last row (y = dy - 1, t0 = t1 = 0). -x=-1;t2=values[y*dx]>=value;cases[t2<<2].forEach(stitch);while(++x=value;cases[t2<<2|t3<<3].forEach(stitch)}cases[t2<<3].forEach(stitch);function stitch(line){var start=[line[0][0]+x,line[0][1]+y],end=[line[1][0]+x,line[1][1]+y],startIndex=index(start),endIndex=index(end),f,g;if(f=fragmentByEnd[startIndex]){if(g=fragmentByStart[endIndex]){delete fragmentByEnd[f.end];delete fragmentByStart[g.start];if(f===g){f.ring.push(end);callback(f.ring)}else{fragmentByStart[f.start]=fragmentByEnd[g.end]={start:f.start,end:g.end,ring:f.ring.concat(g.ring)}}}else{delete fragmentByEnd[f.end];f.ring.push(end);fragmentByEnd[f.end=endIndex]=f}}else if(f=fragmentByStart[endIndex]){if(g=fragmentByEnd[startIndex]){delete fragmentByStart[f.start];delete fragmentByEnd[g.end];if(f===g){f.ring.push(end);callback(f.ring)}else{fragmentByStart[g.start]=fragmentByEnd[f.end]={start:g.start,end:f.end,ring:g.ring.concat(f.ring)}}}else{delete fragmentByStart[f.start];f.ring.unshift(start);fragmentByStart[f.start=startIndex]=f}}else{fragmentByStart[startIndex]=fragmentByEnd[endIndex]={start:startIndex,end:endIndex,ring:[start,end]}}}}function index(point){return point[0]*2+point[1]*(dx+1)*4}function smoothLinear(ring,values,value){ring.forEach(function(point){var x=point[0],y=point[1],xt=x|0,yt=y|0,v0,v1=values[yt*dx+xt];if(x>0&&x0&&y0)||!(_1>0))throw new Error("invalid size");return dx=_0,dy=_1,contours};contours.thresholds=function(_){return arguments.length?(threshold=typeof _==="function"?_:Array.isArray(_)?constant(slice.call(_)):constant(_),contours):threshold};contours.smooth=function(_){return arguments.length?(smooth=_?smoothLinear:noop,contours):smooth===smoothLinear};return contours} -// TODO Optimize edge cases. -// TODO Optimize index calculation. -// TODO Optimize arguments. -function blurX(source,target,r){var n=source.width,m=source.height,w=(r<<1)+1;for(var j=0;j=r){if(i>=w){sr-=source.data[i-w+j*n]}target.data[i-r+j*n]=sr/Math.min(i+1,n-1+w-i,w)}}}} -// TODO Optimize edge cases. -// TODO Optimize index calculation. -// TODO Optimize arguments. -function blurY(source,target,r){var n=source.width,m=source.height,w=(r<<1)+1;for(var i=0;i=r){if(j>=w){sr-=source.data[i+(j-w)*n]}target.data[i+(j-r)*n]=sr/Math.min(j+1,m-1+w-j,w)}}}}function defaultX(d){return d[0]}function defaultY(d){return d[1]}function defaultWeight(){return 1}function density(){var x=defaultX,y=defaultY,weight=defaultWeight,dx=960,dy=500,r=20,// blur radius -k=2,// log2(grid cell size) -o=r*3,// grid offset, to pad for blur -n=dx+o*2>>k,// grid width -m=dy+o*2>>k,// grid height -threshold=constant(20);function density(data){var values0=new Float32Array(n*m),values1=new Float32Array(n*m);data.forEach(function(d,i,data){var xi=+x(d,i,data)+o>>k,yi=+y(d,i,data)+o>>k,wi=+weight(d,i,data);if(xi>=0&&xi=0&&yi>k);blurY({width:n,height:m,data:values1},{width:n,height:m,data:values0},r>>k);blurX({width:n,height:m,data:values0},{width:n,height:m,data:values1},r>>k);blurY({width:n,height:m,data:values1},{width:n,height:m,data:values0},r>>k);blurX({width:n,height:m,data:values0},{width:n,height:m,data:values1},r>>k);blurY({width:n,height:m,data:values1},{width:n,height:m,data:values0},r>>k);var tz=threshold(values0); -// Convert number of thresholds into uniform thresholds. -if(!Array.isArray(tz)){var stop=d3Array.max(values0);tz=d3Array.tickStep(0,stop,tz);tz=d3Array.range(0,Math.floor(stop/tz)*tz,tz);tz.shift()}return contours().thresholds(tz).size([n,m])(values0).map(transform)}function transform(geometry){geometry.value*=Math.pow(2,-2*k);// Density in points per square pixel. -geometry.coordinates.forEach(transformPolygon);return geometry}function transformPolygon(coordinates){coordinates.forEach(transformRing)}function transformRing(coordinates){coordinates.forEach(transformPoint)} -// TODO Optimize. -function transformPoint(coordinates){coordinates[0]=coordinates[0]*Math.pow(2,k)-o;coordinates[1]=coordinates[1]*Math.pow(2,k)-o}function resize(){o=r*3;n=dx+o*2>>k;m=dy+o*2>>k;return density}density.x=function(_){return arguments.length?(x=typeof _==="function"?_:constant(+_),density):x};density.y=function(_){return arguments.length?(y=typeof _==="function"?_:constant(+_),density):y};density.weight=function(_){return arguments.length?(weight=typeof _==="function"?_:constant(+_),density):weight};density.size=function(_){if(!arguments.length)return[dx,dy];var _0=Math.ceil(_[0]),_1=Math.ceil(_[1]);if(!(_0>=0)&&!(_0>=0))throw new Error("invalid size");return dx=_0,dy=_1,resize()};density.cellSize=function(_){if(!arguments.length)return 1<=1))throw new Error("invalid cell size");return k=Math.floor(Math.log(_)/Math.LN2),resize()};density.thresholds=function(_){return arguments.length?(threshold=typeof _==="function"?_:Array.isArray(_)?constant(slice.call(_)):constant(_),density):threshold};density.bandwidth=function(_){if(!arguments.length)return Math.sqrt(r*(r+1));if(!((_=+_)>=0))throw new Error("invalid bandwidth");return r=Math.round((Math.sqrt(4*_*_+1)-1)/2),resize()};return density}exports.contours=contours;exports.contourDensity=density;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-array":29}],36:[function(require,module,exports){ -// https://d3js.org/d3-dispatch/ v1.0.6 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):(global=global||self,factory(global.d3=global.d3||{}))})(this,function(exports){"use strict";var noop={value:function(){}};function dispatch(){for(var i=0,n=arguments.length,_={},t;i=0)name=t.slice(i+1),t=t.slice(0,i);if(t&&!types.hasOwnProperty(t))throw new Error("unknown type: "+t);return{type:t,name:name}})}Dispatch.prototype=dispatch.prototype={constructor:Dispatch,on:function(typename,callback){var _=this._,T=parseTypenames(typename+"",_),t,i=-1,n=T.length; -// If no callback was specified, return the callback of the given type and name. -if(arguments.length<2){while(++i0)for(var args=new Array(n),i=0,n,t;iclickDistance2}gestures.mouse("drag")}function mouseupped(){d3Selection.select(d3Selection.event.view).on("mousemove.drag mouseup.drag",null);yesdrag(d3Selection.event.view,mousemoving);noevent();gestures.mouse("end")}function touchstarted(){if(!filter.apply(this,arguments))return;var touches=d3Selection.event.changedTouches,c=container.apply(this,arguments),n=touches.length,i,gesture;for(i=0;i9999?"+"+pad(year,6):pad(year,4)}function formatDate(date){var hours=date.getUTCHours(),minutes=date.getUTCMinutes(),seconds=date.getUTCSeconds(),milliseconds=date.getUTCMilliseconds();return isNaN(date)?"Invalid Date":formatYear(date.getUTCFullYear())+"-"+pad(date.getUTCMonth()+1,2)+"-"+pad(date.getUTCDate(),2)+(milliseconds?"T"+pad(hours,2)+":"+pad(minutes,2)+":"+pad(seconds,2)+"."+pad(milliseconds,3)+"Z":seconds?"T"+pad(hours,2)+":"+pad(minutes,2)+":"+pad(seconds,2)+"Z":minutes||hours?"T"+pad(hours,2)+":"+pad(minutes,2)+"Z":"")}function dsv(delimiter){var reFormat=new RegExp('["'+delimiter+"\n\r]"),DELIMITER=delimiter.charCodeAt(0);function parse(text,f){var convert,columns,rows=parseRows(text,function(row,i){if(convert)return convert(row,i-1);columns=row,convert=f?customConverter(row,f):objectConverter(row)});rows.columns=columns||[];return rows}function parseRows(text,f){var rows=[],// output rows -N=text.length,I=0,// current character index -n=0,// current line number -t,// current token -eof=N<=0,// current token followed by EOF? -eol=false;// current token followed by EOL? -// Strip the trailing newline. -if(text.charCodeAt(N-1)===NEWLINE)--N;if(text.charCodeAt(N-1)===RETURN)--N;function token(){if(eof)return EOF;if(eol)return eol=false,EOL; -// Unescape quotes. -var i,j=I,c;if(text.charCodeAt(j)===QUOTE){while(I++=N)eof=true;else if((c=text.charCodeAt(I++))===NEWLINE)eol=true;else if(c===RETURN){eol=true;if(text.charCodeAt(I)===NEWLINE)++I}return text.slice(j+1,i-1).replace(/""/g,'"')} -// Find next delimiter or newline. -while(Inode.index){var x=xi-data.x-data.vx,y=yi-data.y-data.vy,l=x*x+y*y;if(lxi+r||x1yi+r||y1quad.r){quad.r=quad[i].r}}}function initialize(){if(!nodes)return;var i,n=nodes.length,node;radii=new Array(n);for(i=0;i1?(_==null?forces.remove(name):forces.set(name,initializeForce(_)),simulation):forces.get(name)},find:function(x,y,radius){var i=0,n=nodes.length,dx,dy,d2,node,closest;if(radius==null)radius=Infinity;else radius*=radius;for(i=0;i1?(event.on(name,_),simulation):event.on(name)}}}function manyBody(){var nodes,node,alpha,strength=constant(-30),strengths,distanceMin2=1,distanceMax2=Infinity,theta2=.81;function force(_){var i,n=nodes.length,tree=d3Quadtree.quadtree(nodes,x$1,y$1).visitAfter(accumulate);for(alpha=_,i=0;i=distanceMax2)return; -// Limit forces for very close nodes; randomize direction if coincident. -if(quad.data!==node||quad.next){if(x===0)x=jiggle(),l+=x*x;if(y===0)y=jiggle(),l+=y*y;if(l1?coefficient[0]+coefficient.slice(2):coefficient,+x.slice(i+1)]}function exponent(x){return x=formatDecimal(Math.abs(x)),x?x[1]:NaN}function formatGroup(grouping,thousands){return function(value,width){var i=value.length,t=[],j=0,g=grouping[0],length=0;while(i>0&&g>0){if(length+g+1>width)g=Math.max(1,width-length);t.push(value.substring(i-=g,i+g));if((length+=g+1)>width)break;g=grouping[j=(j+1)%grouping.length]}return t.reverse().join(thousands)}}function formatNumerals(numerals){return function(value){return value.replace(/[0-9]/g,function(i){return numerals[+i]})}} -// [[fill]align][sign][symbol][0][width][,][.precision][~][type] -var re=/^(?:(.)?([<>=^]))?([+\-( ])?([$#])?(0)?(\d+)?(,)?(\.\d+)?(~)?([a-z%])?$/i;function formatSpecifier(specifier){if(!(match=re.exec(specifier)))throw new Error("invalid format: "+specifier);var match;return new FormatSpecifier({fill:match[1],align:match[2],sign:match[3],symbol:match[4],zero:match[5],width:match[6],comma:match[7],precision:match[8]&&match[8].slice(1),trim:match[9],type:match[10]})}formatSpecifier.prototype=FormatSpecifier.prototype;// instanceof -function FormatSpecifier(specifier){this.fill=specifier.fill===undefined?" ":specifier.fill+"";this.align=specifier.align===undefined?">":specifier.align+"";this.sign=specifier.sign===undefined?"-":specifier.sign+"";this.symbol=specifier.symbol===undefined?"":specifier.symbol+"";this.zero=!!specifier.zero;this.width=specifier.width===undefined?undefined:+specifier.width;this.comma=!!specifier.comma;this.precision=specifier.precision===undefined?undefined:+specifier.precision;this.trim=!!specifier.trim;this.type=specifier.type===undefined?"":specifier.type+""}FormatSpecifier.prototype.toString=function(){return this.fill+this.align+this.sign+this.symbol+(this.zero?"0":"")+(this.width===undefined?"":Math.max(1,this.width|0))+(this.comma?",":"")+(this.precision===undefined?"":"."+Math.max(0,this.precision|0))+(this.trim?"~":"")+this.type}; -// Trims insignificant zeros, e.g., replaces 1.2000k with 1.2k. -function formatTrim(s){out:for(var n=s.length,i=1,i0=-1,i1;i0){if(!+s[i])break out;i0=0}break}}return i0>0?s.slice(0,i0)+s.slice(i1+1):s}var prefixExponent;function formatPrefixAuto(x,p){var d=formatDecimal(x,p);if(!d)return x+"";var coefficient=d[0],exponent=d[1],i=exponent-(prefixExponent=Math.max(-8,Math.min(8,Math.floor(exponent/3)))*3)+1,n=coefficient.length;return i===n?coefficient:i>n?coefficient+new Array(i-n+1).join("0"):i>0?coefficient.slice(0,i)+"."+coefficient.slice(i):"0."+new Array(1-i).join("0")+formatDecimal(x,Math.max(0,p+i-1))[0];// less than 1y! -}function formatRounded(x,p){var d=formatDecimal(x,p);if(!d)return x+"";var coefficient=d[0],exponent=d[1];return exponent<0?"0."+new Array(-exponent).join("0")+coefficient:coefficient.length>exponent+1?coefficient.slice(0,exponent+1)+"."+coefficient.slice(exponent+1):coefficient+new Array(exponent-coefficient.length+2).join("0")}var formatTypes={"%":function(x,p){return(x*100).toFixed(p)},b:function(x){return Math.round(x).toString(2)},c:function(x){return x+""},d:function(x){return Math.round(x).toString(10)},e:function(x,p){return x.toExponential(p)},f:function(x,p){return x.toFixed(p)},g:function(x,p){return x.toPrecision(p)},o:function(x){return Math.round(x).toString(8)},p:function(x,p){return formatRounded(x*100,p)},r:formatRounded,s:formatPrefixAuto,X:function(x){return Math.round(x).toString(16).toUpperCase()},x:function(x){return Math.round(x).toString(16)}};function identity(x){return x}var map=Array.prototype.map,prefixes=["y","z","a","f","p","n","µ","m","","k","M","G","T","P","E","Z","Y"];function formatLocale(locale){var group=locale.grouping===undefined||locale.thousands===undefined?identity:formatGroup(map.call(locale.grouping,Number),locale.thousands+""),currencyPrefix=locale.currency===undefined?"":locale.currency[0]+"",currencySuffix=locale.currency===undefined?"":locale.currency[1]+"",decimal=locale.decimal===undefined?".":locale.decimal+"",numerals=locale.numerals===undefined?identity:formatNumerals(map.call(locale.numerals,String)),percent=locale.percent===undefined?"%":locale.percent+"",minus=locale.minus===undefined?"-":locale.minus+"",nan=locale.nan===undefined?"NaN":locale.nan+"";function newFormat(specifier){specifier=formatSpecifier(specifier);var fill=specifier.fill,align=specifier.align,sign=specifier.sign,symbol=specifier.symbol,zero=specifier.zero,width=specifier.width,comma=specifier.comma,precision=specifier.precision,trim=specifier.trim,type=specifier.type; -// The "n" type is an alias for ",g". -if(type==="n")comma=true,type="g"; -// The "" type, and any invalid type, is an alias for ".12~g". -else if(!formatTypes[type])precision===undefined&&(precision=12),trim=true,type="g"; -// If zero fill is specified, padding goes after sign and before digits. -if(zero||fill==="0"&&align==="=")zero=true,fill="0",align="="; -// Compute the prefix and suffix. -// For SI-prefix, the suffix is lazily computed. -var prefix=symbol==="$"?currencyPrefix:symbol==="#"&&/[boxX]/.test(type)?"0"+type.toLowerCase():"",suffix=symbol==="$"?currencySuffix:/[%p]/.test(type)?percent:""; -// What format function should we use? -// Is this an integer type? -// Can this type generate exponential notation? -var formatType=formatTypes[type],maybeSuffix=/[defgprs%]/.test(type); -// Set the default precision if not specified, -// or clamp the specified precision to the supported range. -// For significant precision, it must be in [1, 21]. -// For fixed precision, it must be in [0, 20]. -precision=precision===undefined?6:/[gprs]/.test(type)?Math.max(1,Math.min(21,precision)):Math.max(0,Math.min(20,precision));function format(value){var valuePrefix=prefix,valueSuffix=suffix,i,n,c;if(type==="c"){valueSuffix=formatType(value)+valueSuffix;value=""}else{value=+value; -// Perform the initial formatting. -var valueNegative=value<0;value=isNaN(value)?nan:formatType(Math.abs(value),precision); -// Trim insignificant zeros. -if(trim)value=formatTrim(value); -// If a negative value rounds to zero during formatting, treat as positive. -if(valueNegative&&+value===0)valueNegative=false; -// Compute the prefix and suffix. -valuePrefix=(valueNegative?sign==="("?sign:minus:sign==="-"||sign==="("?"":sign)+valuePrefix;valueSuffix=(type==="s"?prefixes[8+prefixExponent/3]:"")+valueSuffix+(valueNegative&&sign==="("?")":""); -// Break the formatted value into the integer “value” part that can be -// grouped, and fractional or exponential “suffix” part that is not. -if(maybeSuffix){i=-1,n=value.length;while(++ic||c>57){valueSuffix=(c===46?decimal+value.slice(i+1):value.slice(i))+valueSuffix;value=value.slice(0,i);break}}}} -// If the fill character is not "0", grouping is applied before padding. -if(comma&&!zero)value=group(value,Infinity); -// Compute the padding. -var length=valuePrefix.length+value.length+valueSuffix.length,padding=length>1)+valuePrefix+value+valueSuffix+padding.slice(length);break;default:value=padding+valuePrefix+value+valueSuffix;break}return numerals(value)}format.toString=function(){return specifier+""};return format}function formatPrefix(specifier,value){var f=newFormat((specifier=formatSpecifier(specifier),specifier.type="f",specifier)),e=Math.max(-8,Math.min(8,Math.floor(exponent(value)/3)))*3,k=Math.pow(10,-e),prefix=prefixes[8+e/3];return function(value){return f(k*value)+prefix}}return{format:newFormat,formatPrefix:formatPrefix}}var locale;defaultLocale({decimal:".",thousands:",",grouping:[3],currency:["$",""],minus:"-"});function defaultLocale(definition){locale=formatLocale(definition);exports.format=locale.format;exports.formatPrefix=locale.formatPrefix;return locale}function precisionFixed(step){return Math.max(0,-exponent(Math.abs(step)))}function precisionPrefix(step,value){return Math.max(0,Math.max(-8,Math.min(8,Math.floor(exponent(value)/3)))*3-exponent(Math.abs(step)))}function precisionRound(step,max){step=Math.abs(step),max=Math.abs(max)-step;return Math.max(0,exponent(max)-exponent(step))+1}exports.FormatSpecifier=FormatSpecifier;exports.formatDefaultLocale=defaultLocale;exports.formatLocale=formatLocale;exports.formatSpecifier=formatSpecifier;exports.precisionFixed=precisionFixed;exports.precisionPrefix=precisionPrefix;exports.precisionRound=precisionRound;Object.defineProperty(exports,"__esModule",{value:true})})},{}],43:[function(require,module,exports){ -// https://d3js.org/d3-geo/ v1.11.9 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports,require("d3-array")):typeof define==="function"&&define.amd?define(["exports","d3-array"],factory):(global=global||self,factory(global.d3=global.d3||{},global.d3))})(this,function(exports,d3Array){"use strict"; -// Adds floating point numbers with twice the normal precision. -// Reference: J. R. Shewchuk, Adaptive Precision Floating-Point Arithmetic and -// Fast Robust Geometric Predicates, Discrete & Computational Geometry 18(3) -// 305–363 (1997). -// Code adapted from GeographicLib by Charles F. F. Karney, -// http://geographiclib.sourceforge.net/ -function adder(){return new Adder}function Adder(){this.reset()}Adder.prototype={constructor:Adder,reset:function(){this.s=// rounded value -this.t=0;// exact error -},add:function(y){add(temp,y,this.t);add(this,temp.s,this.s);if(this.s)this.t+=temp.t;else this.s=temp.t},valueOf:function(){return this.s}};var temp=new Adder;function add(adder,a,b){var x=adder.s=a+b,bv=x-a,av=x-bv;adder.t=a-av+(b-bv)}var epsilon=1e-6;var epsilon2=1e-12;var pi=Math.PI;var halfPi=pi/2;var quarterPi=pi/4;var tau=pi*2;var degrees=180/pi;var radians=pi/180;var abs=Math.abs;var atan=Math.atan;var atan2=Math.atan2;var cos=Math.cos;var ceil=Math.ceil;var exp=Math.exp;var log=Math.log;var pow=Math.pow;var sin=Math.sin;var sign=Math.sign||function(x){return x>0?1:x<0?-1:0};var sqrt=Math.sqrt;var tan=Math.tan;function acos(x){return x>1?0:x<-1?pi:Math.acos(x)}function asin(x){return x>1?halfPi:x<-1?-halfPi:Math.asin(x)}function haversin(x){return(x=sin(x/2))*x}function noop(){}function streamGeometry(geometry,stream){if(geometry&&streamGeometryType.hasOwnProperty(geometry.type)){streamGeometryType[geometry.type](geometry,stream)}}var streamObjectType={Feature:function(object,stream){streamGeometry(object.geometry,stream)},FeatureCollection:function(object,stream){var features=object.features,i=-1,n=features.length;while(++i=0?1:-1,adLambda=sdLambda*dLambda,cosPhi=cos(phi),sinPhi=sin(phi),k=sinPhi0*sinPhi,u=cosPhi0*cosPhi+k*cos(adLambda),v=k*sdLambda*sin(adLambda);areaRingSum.add(atan2(v,u)); -// Advance the previous points. -lambda0=lambda,cosPhi0=cosPhi,sinPhi0=sinPhi}function area(object){areaSum.reset();geoStream(object,areaStream);return areaSum*2}function spherical(cartesian){return[atan2(cartesian[1],cartesian[0]),asin(cartesian[2])]}function cartesian(spherical){var lambda=spherical[0],phi=spherical[1],cosPhi=cos(phi);return[cosPhi*cos(lambda),cosPhi*sin(lambda),sin(phi)]}function cartesianDot(a,b){return a[0]*b[0]+a[1]*b[1]+a[2]*b[2]}function cartesianCross(a,b){return[a[1]*b[2]-a[2]*b[1],a[2]*b[0]-a[0]*b[2],a[0]*b[1]-a[1]*b[0]]} -// TODO return a -function cartesianAddInPlace(a,b){a[0]+=b[0],a[1]+=b[1],a[2]+=b[2]}function cartesianScale(vector,k){return[vector[0]*k,vector[1]*k,vector[2]*k]} -// TODO return d -function cartesianNormalizeInPlace(d){var l=sqrt(d[0]*d[0]+d[1]*d[1]+d[2]*d[2]);d[0]/=l,d[1]/=l,d[2]/=l}var lambda0$1,phi0,lambda1,phi1,// bounds -lambda2,// previous lambda-coordinate -lambda00$1,phi00$1,// first point -p0,// previous 3D point -deltaSum=adder(),ranges,range;var boundsStream={point:boundsPoint,lineStart:boundsLineStart,lineEnd:boundsLineEnd,polygonStart:function(){boundsStream.point=boundsRingPoint;boundsStream.lineStart=boundsRingStart;boundsStream.lineEnd=boundsRingEnd;deltaSum.reset();areaStream.polygonStart()},polygonEnd:function(){areaStream.polygonEnd();boundsStream.point=boundsPoint;boundsStream.lineStart=boundsLineStart;boundsStream.lineEnd=boundsLineEnd;if(areaRingSum<0)lambda0$1=-(lambda1=180),phi0=-(phi1=90);else if(deltaSum>epsilon)phi1=90;else if(deltaSum<-epsilon)phi0=-90;range[0]=lambda0$1,range[1]=lambda1},sphere:function(){lambda0$1=-(lambda1=180),phi0=-(phi1=90)}};function boundsPoint(lambda,phi){ranges.push(range=[lambda0$1=lambda,lambda1=lambda]);if(phiphi1)phi1=phi}function linePoint(lambda,phi){var p=cartesian([lambda*radians,phi*radians]);if(p0){var normal=cartesianCross(p0,p),equatorial=[normal[1],-normal[0],0],inflection=cartesianCross(equatorial,normal);cartesianNormalizeInPlace(inflection);inflection=spherical(inflection);var delta=lambda-lambda2,sign=delta>0?1:-1,lambdai=inflection[0]*degrees*sign,phii,antimeridian=abs(delta)>180;if(antimeridian^(sign*lambda2phi1)phi1=phii}else if(lambdai=(lambdai+360)%360-180,antimeridian^(sign*lambda2phi1)phi1=phi}if(antimeridian){if(lambdaangle(lambda0$1,lambda1))lambda1=lambda}else{if(angle(lambda,lambda1)>angle(lambda0$1,lambda1))lambda0$1=lambda}}else{if(lambda1>=lambda0$1){if(lambdalambda1)lambda1=lambda}else{if(lambda>lambda2){if(angle(lambda0$1,lambda)>angle(lambda0$1,lambda1))lambda1=lambda}else{if(angle(lambda,lambda1)>angle(lambda0$1,lambda1))lambda0$1=lambda}}}}else{ranges.push(range=[lambda0$1=lambda,lambda1=lambda])}if(phiphi1)phi1=phi;p0=p,lambda2=lambda}function boundsLineStart(){boundsStream.point=linePoint}function boundsLineEnd(){range[0]=lambda0$1,range[1]=lambda1;boundsStream.point=boundsPoint;p0=null}function boundsRingPoint(lambda,phi){if(p0){var delta=lambda-lambda2;deltaSum.add(abs(delta)>180?delta+(delta>0?360:-360):delta)}else{lambda00$1=lambda,phi00$1=phi}areaStream.point(lambda,phi);linePoint(lambda,phi)}function boundsRingStart(){areaStream.lineStart()}function boundsRingEnd(){boundsRingPoint(lambda00$1,phi00$1);areaStream.lineEnd();if(abs(deltaSum)>epsilon)lambda0$1=-(lambda1=180);range[0]=lambda0$1,range[1]=lambda1;p0=null} -// Finds the left-right distance between two longitudes. -// This is almost the same as (lambda1 - lambda0 + 360°) % 360°, except that we want -// the distance between ±180° to be 360°. -function angle(lambda0,lambda1){return(lambda1-=lambda0)<0?lambda1+360:lambda1}function rangeCompare(a,b){return a[0]-b[0]}function rangeContains(range,x){return range[0]<=range[1]?range[0]<=x&&x<=range[1]:xangle(a[0],a[1]))a[1]=b[1];if(angle(b[0],a[1])>angle(a[0],a[1]))a[0]=b[0]}else{merged.push(a=b)}} -// Finally, find the largest gap between the merged ranges. -// The final bounding box will be the inverse of this gap. -for(deltaMax=-Infinity,n=merged.length-1,i=0,a=merged[n];i<=n;a=b,++i){b=merged[i];if((delta=angle(a[1],b[0]))>deltaMax)deltaMax=delta,lambda0$1=b[0],lambda1=a[1]}}ranges=range=null;return lambda0$1===Infinity||phi0===Infinity?[[NaN,NaN],[NaN,NaN]]:[[lambda0$1,phi0],[lambda1,phi1]]}var W0,W1,X0,Y0,Z0,X1,Y1,Z1,X2,Y2,Z2,lambda00$2,phi00$2,// first point -x0,y0,z0;// previous point -var centroidStream={sphere:noop,point:centroidPoint,lineStart:centroidLineStart,lineEnd:centroidLineEnd,polygonStart:function(){centroidStream.lineStart=centroidRingStart;centroidStream.lineEnd=centroidRingEnd},polygonEnd:function(){centroidStream.lineStart=centroidLineStart;centroidStream.lineEnd=centroidLineEnd}}; -// Arithmetic mean of Cartesian vectors. -function centroidPoint(lambda,phi){lambda*=radians,phi*=radians;var cosPhi=cos(phi);centroidPointCartesian(cosPhi*cos(lambda),cosPhi*sin(lambda),sin(phi))}function centroidPointCartesian(x,y,z){++W0;X0+=(x-X0)/W0;Y0+=(y-Y0)/W0;Z0+=(z-Z0)/W0}function centroidLineStart(){centroidStream.point=centroidLinePointFirst}function centroidLinePointFirst(lambda,phi){lambda*=radians,phi*=radians;var cosPhi=cos(phi);x0=cosPhi*cos(lambda);y0=cosPhi*sin(lambda);z0=sin(phi);centroidStream.point=centroidLinePoint;centroidPointCartesian(x0,y0,z0)}function centroidLinePoint(lambda,phi){lambda*=radians,phi*=radians;var cosPhi=cos(phi),x=cosPhi*cos(lambda),y=cosPhi*sin(lambda),z=sin(phi),w=atan2(sqrt((w=y0*z-z0*y)*w+(w=z0*x-x0*z)*w+(w=x0*y-y0*x)*w),x0*x+y0*y+z0*z);W1+=w;X1+=w*(x0+(x0=x));Y1+=w*(y0+(y0=y));Z1+=w*(z0+(z0=z));centroidPointCartesian(x0,y0,z0)}function centroidLineEnd(){centroidStream.point=centroidPoint} -// See J. E. Brock, The Inertia Tensor for a Spherical Triangle, -// J. Applied Mechanics 42, 239 (1975). -function centroidRingStart(){centroidStream.point=centroidRingPointFirst}function centroidRingEnd(){centroidRingPoint(lambda00$2,phi00$2);centroidStream.point=centroidPoint}function centroidRingPointFirst(lambda,phi){lambda00$2=lambda,phi00$2=phi;lambda*=radians,phi*=radians;centroidStream.point=centroidRingPoint;var cosPhi=cos(phi);x0=cosPhi*cos(lambda);y0=cosPhi*sin(lambda);z0=sin(phi);centroidPointCartesian(x0,y0,z0)}function centroidRingPoint(lambda,phi){lambda*=radians,phi*=radians;var cosPhi=cos(phi),x=cosPhi*cos(lambda),y=cosPhi*sin(lambda),z=sin(phi),cx=y0*z-z0*y,cy=z0*x-x0*z,cz=x0*y-y0*x,m=sqrt(cx*cx+cy*cy+cz*cz),w=asin(m),// line weight = angle -v=m&&-w/m;// area weight multiplier -X2+=v*cx;Y2+=v*cy;Z2+=v*cz;W1+=w;X1+=w*(x0+(x0=x));Y1+=w*(y0+(y0=y));Z1+=w*(z0+(z0=z));centroidPointCartesian(x0,y0,z0)}function centroid(object){W0=W1=X0=Y0=Z0=X1=Y1=Z1=X2=Y2=Z2=0;geoStream(object,centroidStream);var x=X2,y=Y2,z=Z2,m=x*x+y*y+z*z; -// If the area-weighted ccentroid is undefined, fall back to length-weighted ccentroid. -if(mpi?lambda+Math.round(-lambda/tau)*tau:lambda,phi]}rotationIdentity.invert=rotationIdentity;function rotateRadians(deltaLambda,deltaPhi,deltaGamma){return(deltaLambda%=tau)?deltaPhi||deltaGamma?compose(rotationLambda(deltaLambda),rotationPhiGamma(deltaPhi,deltaGamma)):rotationLambda(deltaLambda):deltaPhi||deltaGamma?rotationPhiGamma(deltaPhi,deltaGamma):rotationIdentity}function forwardRotationLambda(deltaLambda){return function(lambda,phi){return lambda+=deltaLambda,[lambda>pi?lambda-tau:lambda<-pi?lambda+tau:lambda,phi]}}function rotationLambda(deltaLambda){var rotation=forwardRotationLambda(deltaLambda);rotation.invert=forwardRotationLambda(-deltaLambda);return rotation}function rotationPhiGamma(deltaPhi,deltaGamma){var cosDeltaPhi=cos(deltaPhi),sinDeltaPhi=sin(deltaPhi),cosDeltaGamma=cos(deltaGamma),sinDeltaGamma=sin(deltaGamma);function rotation(lambda,phi){var cosPhi=cos(phi),x=cos(lambda)*cosPhi,y=sin(lambda)*cosPhi,z=sin(phi),k=z*cosDeltaPhi+x*sinDeltaPhi;return[atan2(y*cosDeltaGamma-k*sinDeltaGamma,x*cosDeltaPhi-z*sinDeltaPhi),asin(k*cosDeltaGamma+y*sinDeltaGamma)]}rotation.invert=function(lambda,phi){var cosPhi=cos(phi),x=cos(lambda)*cosPhi,y=sin(lambda)*cosPhi,z=sin(phi),k=z*cosDeltaGamma-y*sinDeltaGamma;return[atan2(y*cosDeltaGamma+z*sinDeltaGamma,x*cosDeltaPhi+k*sinDeltaPhi),asin(k*cosDeltaPhi-x*sinDeltaPhi)]};return rotation}function rotation(rotate){rotate=rotateRadians(rotate[0]*radians,rotate[1]*radians,rotate.length>2?rotate[2]*radians:0);function forward(coordinates){coordinates=rotate(coordinates[0]*radians,coordinates[1]*radians);return coordinates[0]*=degrees,coordinates[1]*=degrees,coordinates}forward.invert=function(coordinates){coordinates=rotate.invert(coordinates[0]*radians,coordinates[1]*radians);return coordinates[0]*=degrees,coordinates[1]*=degrees,coordinates};return forward} -// Generates a circle centered at [0°, 0°], with a given radius and precision. -function circleStream(stream,radius,delta,direction,t0,t1){if(!delta)return;var cosRadius=cos(radius),sinRadius=sin(radius),step=direction*delta;if(t0==null){t0=radius+direction*tau;t1=radius-step/2}else{t0=circleRadius(cosRadius,t0);t1=circleRadius(cosRadius,t1);if(direction>0?t0t1)t0+=direction*tau}for(var point,t=t0;direction>0?t>t1:t1)lines.push(lines.pop().concat(lines.shift()))},result:function(){var result=lines;lines=[];line=null;return result}}}function pointEqual(a,b){return abs(a[0]-b[0])=0;--i)stream.point((point=points[i])[0],point[1])}else{interpolate(current.x,current.p.x,-1,stream)}current=current.p}current=current.o;points=current.z;isSubject=!isSubject}while(!current.v);stream.lineEnd()}}function link(array){if(!(n=array.length))return;var n,i=0,a=array[0],b;while(++i=0?1:-1,absDelta=sign*delta,antimeridian=absDelta>pi,k=sinPhi0*sinPhi1;sum.add(atan2(k*sign*sin(absDelta),cosPhi0*cosPhi1+k*cos(absDelta)));angle+=antimeridian?delta+sign*tau:delta; -// Are the longitudes either side of the point’s meridian (lambda), -// and are the latitudes smaller than the parallel (phi)? -if(antimeridian^lambda0>=lambda^lambda1>=lambda){var arc=cartesianCross(cartesian(point0),cartesian(point1));cartesianNormalizeInPlace(arc);var intersection=cartesianCross(normal,arc);cartesianNormalizeInPlace(intersection);var phiArc=(antimeridian^delta>=0?-1:1)*asin(intersection[2]);if(phi>phiArc||phi===phiArc&&(arc[0]||arc[1])){winding+=antimeridian^delta>=0?1:-1}}}} -// First, determine whether the South pole is inside or outside: -// -// It is inside if: -// * the polygon winds around it in a clockwise direction. -// * the polygon does not (cumulatively) wind around it, but has a negative -// (counter-clockwise) area. -// -// Second, count the (signed) number of times a segment crosses a lambda -// from the point to the South pole. If it is zero, then the point is the -// same side as the South pole. -return(angle<-epsilon||angle0){if(!polygonStarted)sink.polygonStart(),polygonStarted=true;sink.lineStart();for(i=0;i1&&clean&2)ringSegments.push(ringSegments.pop().concat(ringSegments.shift()));segments.push(ringSegments.filter(validSegment))}return clip}}function validSegment(segment){return segment.length>1} -// Intersections are sorted along the clip edge. For both antimeridian cutting -// and circle clipping, the same comparison is used. -function compareIntersection(a,b){return((a=a.x)[0]<0?a[1]-halfPi-epsilon:halfPi-a[1])-((b=b.x)[0]<0?b[1]-halfPi-epsilon:halfPi-b[1])}var clipAntimeridian=clip(function(){return true},clipAntimeridianLine,clipAntimeridianInterpolate,[-pi,-halfPi]); -// Takes a line and cuts into visible segments. Return values: 0 - there were -// intersections or the line was empty; 1 - no intersections; 2 - there were -// intersections, and the first and last segments should be rejoined. -function clipAntimeridianLine(stream){var lambda0=NaN,phi0=NaN,sign0=NaN,clean;// no intersections -return{lineStart:function(){stream.lineStart();clean=1},point:function(lambda1,phi1){var sign1=lambda1>0?pi:-pi,delta=abs(lambda1-lambda0);if(abs(delta-pi)0?halfPi:-halfPi);stream.point(sign0,phi0);stream.lineEnd();stream.lineStart();stream.point(sign1,phi0);stream.point(lambda1,phi0);clean=0}else if(sign0!==sign1&&delta>=pi){// line crosses antimeridian -if(abs(lambda0-sign0)epsilon?atan((sin(phi0)*(cosPhi1=cos(phi1))*sin(lambda1)-sin(phi1)*(cosPhi0=cos(phi0))*sin(lambda0))/(cosPhi0*cosPhi1*sinLambda0Lambda1)):(phi0+phi1)/2}function clipAntimeridianInterpolate(from,to,direction,stream){var phi;if(from==null){phi=direction*halfPi;stream.point(-pi,phi);stream.point(0,phi);stream.point(pi,phi);stream.point(pi,0);stream.point(pi,-phi);stream.point(0,-phi);stream.point(-pi,-phi);stream.point(-pi,0);stream.point(-pi,phi)}else if(abs(from[0]-to[0])>epsilon){var lambda=from[0]0,notHemisphere=abs(cr)>epsilon;// TODO optimise for this common case -function interpolate(from,to,direction,stream){circleStream(stream,radius,delta,direction,from,to)}function visible(lambda,phi){return cos(lambda)*cos(phi)>cr} -// Takes a line and cuts into visible segments. Return values used for polygon -// clipping: 0 - there were intersections or the line was empty; 1 - no -// intersections 2 - there were intersections, and the first and last segments -// should be rejoined. -function clipLine(stream){var point0,// previous point -c0,// code for previous point -v0,// visibility of previous point -v00,// visibility of first point -clean;// no intersections -return{lineStart:function(){v00=v0=false;clean=1},point:function(lambda,phi){var point1=[lambda,phi],point2,v=visible(lambda,phi),c=smallRadius?v?0:code(lambda,phi):v?code(lambda+(lambda<0?pi:-pi),phi):0;if(!point0&&(v00=v0=v))stream.lineStart(); -// Handle degeneracies. -// TODO ignore if not clipping polygons. -if(v!==v0){point2=intersect(point0,point1);if(!point2||pointEqual(point0,point2)||pointEqual(point1,point2)){point1[0]+=epsilon;point1[1]+=epsilon;v=visible(point1[0],point1[1])}}if(v!==v0){clean=0;if(v){ -// outside going in -stream.lineStart();point2=intersect(point1,point0);stream.point(point2[0],point2[1])}else{ -// inside going out -point2=intersect(point0,point1);stream.point(point2[0],point2[1]);stream.lineEnd()}point0=point2}else if(notHemisphere&&point0&&smallRadius^v){var t; -// If the codes for two points are different, or are both zero, -// and there this segment intersects with the small circle. -if(!(c&c0)&&(t=intersect(point1,point0,true))){clean=0;if(smallRadius){stream.lineStart();stream.point(t[0][0],t[0][1]);stream.point(t[1][0],t[1][1]);stream.lineEnd()}else{stream.point(t[1][0],t[1][1]);stream.lineEnd();stream.lineStart();stream.point(t[0][0],t[0][1])}}}if(v&&(!point0||!pointEqual(point0,point1))){stream.point(point1[0],point1[1])}point0=point1,v0=v,c0=c},lineEnd:function(){if(v0)stream.lineEnd();point0=null}, -// Rejoin first and last segments if there were intersections and the first -// and last points were visible. -clean:function(){return clean|(v00&&v0)<<1}}} -// Intersects the great circle between a and b with the clip circle. -function intersect(a,b,two){var pa=cartesian(a),pb=cartesian(b); -// We have two planes, n1.p = d1 and n2.p = d2. -// Find intersection line p(t) = c1 n1 + c2 n2 + t (n1 ⨯ n2). -var n1=[1,0,0],// normal -n2=cartesianCross(pa,pb),n2n2=cartesianDot(n2,n2),n1n2=n2[0],// cartesianDot(n1, n2), -determinant=n2n2-n1n2*n1n2; -// Two polar points. -if(!determinant)return!two&&a;var c1=cr*n2n2/determinant,c2=-cr*n1n2/determinant,n1xn2=cartesianCross(n1,n2),A=cartesianScale(n1,c1),B=cartesianScale(n2,c2);cartesianAddInPlace(A,B); -// Solve |p(t)|^2 = 1. -var u=n1xn2,w=cartesianDot(A,u),uu=cartesianDot(u,u),t2=w*w-uu*(cartesianDot(A,A)-1);if(t2<0)return;var t=sqrt(t2),q=cartesianScale(u,(-w-t)/uu);cartesianAddInPlace(q,A);q=spherical(q);if(!two)return q; -// Two intersection points. -var lambda0=a[0],lambda1=b[0],phi0=a[1],phi1=b[1],z;if(lambda10^q[1]<(abs(q[0]-lambda0)pi^(lambda0<=q[0]&&q[0]<=lambda1)){var q1=cartesianScale(u,(-w+t)/uu);cartesianAddInPlace(q1,A);return[q,spherical(q1)]}} -// Generates a 4-bit vector representing the location of a point relative to -// the small circle's bounding box. -function code(lambda,phi){var r=smallRadius?radius:pi-radius,code=0;if(lambda<-r)code|=1;// left -else if(lambda>r)code|=2;// right -if(phi<-r)code|=4;// below -else if(phi>r)code|=8;// above -return code}return clip(visible,clipLine,interpolate,smallRadius?[0,-radius]:[-pi,radius-pi])}function clipLine(a,b,x0,y0,x1,y1){var ax=a[0],ay=a[1],bx=b[0],by=b[1],t0=0,t1=1,dx=bx-ax,dy=by-ay,r;r=x0-ax;if(!dx&&r>0)return;r/=dx;if(dx<0){if(r0){if(r>t1)return;if(r>t0)t0=r}r=x1-ax;if(!dx&&r<0)return;r/=dx;if(dx<0){if(r>t1)return;if(r>t0)t0=r}else if(dx>0){if(r0)return;r/=dy;if(dy<0){if(r0){if(r>t1)return;if(r>t0)t0=r}r=y1-ay;if(!dy&&r<0)return;r/=dy;if(dy<0){if(r>t1)return;if(r>t0)t0=r}else if(dy>0){if(r0)a[0]=ax+t0*dx,a[1]=ay+t0*dy;if(t1<1)b[0]=ax+t1*dx,b[1]=ay+t1*dy;return true}var clipMax=1e9,clipMin=-clipMax; -// TODO Use d3-polygon’s polygonContains here for the ring check? -// TODO Eliminate duplicate buffering in clipBuffer and polygon.push? -function clipRectangle(x0,y0,x1,y1){function visible(x,y){return x0<=x&&x<=x1&&y0<=y&&y<=y1}function interpolate(from,to,direction,stream){var a=0,a1=0;if(from==null||(a=corner(from,direction))!==(a1=corner(to,direction))||comparePoint(from,to)<0^direction>0){do{stream.point(a===0||a===3?x0:x1,a>1?y1:y0)}while((a=(a+direction+4)%4)!==a1)}else{stream.point(to[0],to[1])}}function corner(p,direction){return abs(p[0]-x0)0?0:3:abs(p[0]-x1)0?2:1:abs(p[1]-y0)0?1:0:direction>0?3:2;// abs(p[1] - y1) < epsilon -}function compareIntersection(a,b){return comparePoint(a.x,b.x)}function comparePoint(a,b){var ca=corner(a,1),cb=corner(b,1);return ca!==cb?ca-cb:ca===0?b[1]-a[1]:ca===1?a[0]-b[0]:ca===2?a[1]-b[1]:b[0]-a[0]}return function(stream){var activeStream=stream,bufferStream=clipBuffer(),segments,polygon,ring,x__,y__,v__,// first point -x_,y_,v_,// previous point -first,clean;var clipStream={point:point,lineStart:lineStart,lineEnd:lineEnd,polygonStart:polygonStart,polygonEnd:polygonEnd};function point(x,y){if(visible(x,y))activeStream.point(x,y)}function polygonInside(){var winding=0;for(var i=0,n=polygon.length;iy1&&(b0-a0)*(y1-a1)>(b1-a1)*(x0-a0))++winding}else{if(b1<=y1&&(b0-a0)*(y1-a1)<(b1-a1)*(x0-a0))--winding}}}return winding} -// Buffer geometry within a polygon and then clip it en masse. -function polygonStart(){activeStream=bufferStream,segments=[],polygon=[],clean=true}function polygonEnd(){var startInside=polygonInside(),cleanInside=clean&&startInside,visible=(segments=d3Array.merge(segments)).length;if(cleanInside||visible){stream.polygonStart();if(cleanInside){stream.lineStart();interpolate(null,null,1,stream);stream.lineEnd()}if(visible){clipRejoin(segments,compareIntersection,startInside,interpolate,stream)}stream.polygonEnd()}activeStream=stream,segments=polygon=ring=null}function lineStart(){clipStream.point=linePoint;if(polygon)polygon.push(ring=[]);first=true;v_=false;x_=y_=NaN} -// TODO rather than special-case polygons, simply handle them separately. -// Ideally, coincident intersection points should be jittered to avoid -// clipping issues. -function lineEnd(){if(segments){linePoint(x__,y__);if(v__&&v_)bufferStream.rejoin();segments.push(bufferStream.result())}clipStream.point=point;if(v_)activeStream.lineEnd()}function linePoint(x,y){var v=visible(x,y);if(polygon)ring.push([x,y]);if(first){x__=x,y__=y,v__=v;first=false;if(v){activeStream.lineStart();activeStream.point(x,y)}}else{if(v&&v_)activeStream.point(x,y);else{var a=[x_=Math.max(clipMin,Math.min(clipMax,x_)),y_=Math.max(clipMin,Math.min(clipMax,y_))],b=[x=Math.max(clipMin,Math.min(clipMax,x)),y=Math.max(clipMin,Math.min(clipMax,y))];if(clipLine(a,b,x0,y0,x1,y1)){if(!v_){activeStream.lineStart();activeStream.point(a[0],a[1])}activeStream.point(b[0],b[1]);if(!v)activeStream.lineEnd();clean=false}else if(v){activeStream.lineStart();activeStream.point(x,y);clean=false}}}x_=x,y_=y,v_=v}return clipStream}}function extent(){var x0=0,y0=0,x1=960,y1=500,cache,cacheStream,clip;return clip={stream:function(stream){return cache&&cacheStream===stream?cache:cache=clipRectangle(x0,y0,x1,y1)(cacheStream=stream)},extent:function(_){return arguments.length?(x0=+_[0][0],y0=+_[0][1],x1=+_[1][0],y1=+_[1][1],cache=cacheStream=null,clip):[[x0,y0],[x1,y1]]}}}var lengthSum=adder(),lambda0$2,sinPhi0$1,cosPhi0$1;var lengthStream={sphere:noop,point:noop,lineStart:lengthLineStart,lineEnd:noop,polygonStart:noop,polygonEnd:noop};function lengthLineStart(){lengthStream.point=lengthPointFirst;lengthStream.lineEnd=lengthLineEnd}function lengthLineEnd(){lengthStream.point=lengthStream.lineEnd=noop}function lengthPointFirst(lambda,phi){lambda*=radians,phi*=radians;lambda0$2=lambda,sinPhi0$1=sin(phi),cosPhi0$1=cos(phi);lengthStream.point=lengthPoint}function lengthPoint(lambda,phi){lambda*=radians,phi*=radians;var sinPhi=sin(phi),cosPhi=cos(phi),delta=abs(lambda-lambda0$2),cosDelta=cos(delta),sinDelta=sin(delta),x=cosPhi*sinDelta,y=cosPhi0$1*sinPhi-sinPhi0$1*cosPhi*cosDelta,z=sinPhi0$1*sinPhi+cosPhi0$1*cosPhi*cosDelta;lengthSum.add(atan2(sqrt(x*x+y*y),z));lambda0$2=lambda,sinPhi0$1=sinPhi,cosPhi0$1=cosPhi}function length(object){lengthSum.reset();geoStream(object,lengthStream);return+lengthSum}var coordinates=[null,null],object={type:"LineString",coordinates:coordinates};function distance(a,b){coordinates[0]=a;coordinates[1]=b;return length(object)}var containsObjectType={Feature:function(object,point){return containsGeometry(object.geometry,point)},FeatureCollection:function(object,point){var features=object.features,i=-1,n=features.length;while(++i0){ab=distance(coordinates[i],coordinates[i-1]);if(ab>0&&ao<=ab&&bo<=ab&&(ao+bo-ab)*(1-Math.pow((ao-bo)/ab,2))epsilon}).map(x)).concat(d3Array.range(ceil(y0/dy)*dy,y1,dy).filter(function(y){return abs(y%DY)>epsilon}).map(y))}graticule.lines=function(){return lines().map(function(coordinates){return{type:"LineString",coordinates:coordinates}})};graticule.outline=function(){return{type:"Polygon",coordinates:[X(X0).concat(Y(Y1).slice(1),X(X1).reverse().slice(1),Y(Y0).reverse().slice(1))]}};graticule.extent=function(_){if(!arguments.length)return graticule.extentMinor();return graticule.extentMajor(_).extentMinor(_)};graticule.extentMajor=function(_){if(!arguments.length)return[[X0,Y0],[X1,Y1]];X0=+_[0][0],X1=+_[1][0];Y0=+_[0][1],Y1=+_[1][1];if(X0>X1)_=X0,X0=X1,X1=_;if(Y0>Y1)_=Y0,Y0=Y1,Y1=_;return graticule.precision(precision)};graticule.extentMinor=function(_){if(!arguments.length)return[[x0,y0],[x1,y1]];x0=+_[0][0],x1=+_[1][0];y0=+_[0][1],y1=+_[1][1];if(x0>x1)_=x0,x0=x1,x1=_;if(y0>y1)_=y0,y0=y1,y1=_;return graticule.precision(precision)};graticule.step=function(_){if(!arguments.length)return graticule.stepMinor();return graticule.stepMajor(_).stepMinor(_)};graticule.stepMajor=function(_){if(!arguments.length)return[DX,DY];DX=+_[0],DY=+_[1];return graticule};graticule.stepMinor=function(_){if(!arguments.length)return[dx,dy];dx=+_[0],dy=+_[1];return graticule};graticule.precision=function(_){if(!arguments.length)return precision;precision=+_;x=graticuleX(y0,y1,90);y=graticuleY(x0,x1,precision);X=graticuleX(Y0,Y1,90);Y=graticuleY(X0,X1,precision);return graticule};return graticule.extentMajor([[-180,-90+epsilon],[180,90-epsilon]]).extentMinor([[-180,-80-epsilon],[180,80+epsilon]])}function graticule10(){return graticule()()}function interpolate(a,b){var x0=a[0]*radians,y0=a[1]*radians,x1=b[0]*radians,y1=b[1]*radians,cy0=cos(y0),sy0=sin(y0),cy1=cos(y1),sy1=sin(y1),kx0=cy0*cos(x0),ky0=cy0*sin(x0),kx1=cy1*cos(x1),ky1=cy1*sin(x1),d=2*asin(sqrt(haversin(y1-y0)+cy0*cy1*haversin(x1-x0))),k=sin(d);var interpolate=d?function(t){var B=sin(t*=d)/k,A=sin(d-t)/k,x=A*kx0+B*kx1,y=A*ky0+B*ky1,z=A*sy0+B*sy1;return[atan2(y,x)*degrees,atan2(z,sqrt(x*x+y*y))*degrees]}:function(){return[x0*degrees,y0*degrees]};interpolate.distance=d;return interpolate}function identity(x){return x}var areaSum$1=adder(),areaRingSum$1=adder(),x00,y00,x0$1,y0$1;var areaStream$1={point:noop,lineStart:noop,lineEnd:noop,polygonStart:function(){areaStream$1.lineStart=areaRingStart$1;areaStream$1.lineEnd=areaRingEnd$1},polygonEnd:function(){areaStream$1.lineStart=areaStream$1.lineEnd=areaStream$1.point=noop;areaSum$1.add(abs(areaRingSum$1));areaRingSum$1.reset()},result:function(){var area=areaSum$1/2;areaSum$1.reset();return area}};function areaRingStart$1(){areaStream$1.point=areaPointFirst$1}function areaPointFirst$1(x,y){areaStream$1.point=areaPoint$1;x00=x0$1=x,y00=y0$1=y}function areaPoint$1(x,y){areaRingSum$1.add(y0$1*x-x0$1*y);x0$1=x,y0$1=y}function areaRingEnd$1(){areaPoint$1(x00,y00)}var x0$2=Infinity,y0$2=x0$2,x1=-x0$2,y1=x1;var boundsStream$1={point:boundsPoint$1,lineStart:noop,lineEnd:noop,polygonStart:noop,polygonEnd:noop,result:function(){var bounds=[[x0$2,y0$2],[x1,y1]];x1=y1=-(y0$2=x0$2=Infinity);return bounds}};function boundsPoint$1(x,y){if(xx1)x1=x;if(yy1)y1=y} -// TODO Enforce positive area for exterior, negative area for interior? -var X0$1=0,Y0$1=0,Z0$1=0,X1$1=0,Y1$1=0,Z1$1=0,X2$1=0,Y2$1=0,Z2$1=0,x00$1,y00$1,x0$3,y0$3;var centroidStream$1={point:centroidPoint$1,lineStart:centroidLineStart$1,lineEnd:centroidLineEnd$1,polygonStart:function(){centroidStream$1.lineStart=centroidRingStart$1;centroidStream$1.lineEnd=centroidRingEnd$1},polygonEnd:function(){centroidStream$1.point=centroidPoint$1;centroidStream$1.lineStart=centroidLineStart$1;centroidStream$1.lineEnd=centroidLineEnd$1},result:function(){var centroid=Z2$1?[X2$1/Z2$1,Y2$1/Z2$1]:Z1$1?[X1$1/Z1$1,Y1$1/Z1$1]:Z0$1?[X0$1/Z0$1,Y0$1/Z0$1]:[NaN,NaN];X0$1=Y0$1=Z0$1=X1$1=Y1$1=Z1$1=X2$1=Y2$1=Z2$1=0;return centroid}};function centroidPoint$1(x,y){X0$1+=x;Y0$1+=y;++Z0$1}function centroidLineStart$1(){centroidStream$1.point=centroidPointFirstLine}function centroidPointFirstLine(x,y){centroidStream$1.point=centroidPointLine;centroidPoint$1(x0$3=x,y0$3=y)}function centroidPointLine(x,y){var dx=x-x0$3,dy=y-y0$3,z=sqrt(dx*dx+dy*dy);X1$1+=z*(x0$3+x)/2;Y1$1+=z*(y0$3+y)/2;Z1$1+=z;centroidPoint$1(x0$3=x,y0$3=y)}function centroidLineEnd$1(){centroidStream$1.point=centroidPoint$1}function centroidRingStart$1(){centroidStream$1.point=centroidPointFirstRing}function centroidRingEnd$1(){centroidPointRing(x00$1,y00$1)}function centroidPointFirstRing(x,y){centroidStream$1.point=centroidPointRing;centroidPoint$1(x00$1=x0$3=x,y00$1=y0$3=y)}function centroidPointRing(x,y){var dx=x-x0$3,dy=y-y0$3,z=sqrt(dx*dx+dy*dy);X1$1+=z*(x0$3+x)/2;Y1$1+=z*(y0$3+y)/2;Z1$1+=z;z=y0$3*x-x0$3*y;X2$1+=z*(x0$3+x);Y2$1+=z*(y0$3+y);Z2$1+=z*3;centroidPoint$1(x0$3=x,y0$3=y)}function PathContext(context){this._context=context}PathContext.prototype={_radius:4.5,pointRadius:function(_){return this._radius=_,this},polygonStart:function(){this._line=0},polygonEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){if(this._line===0)this._context.closePath();this._point=NaN},point:function(x,y){switch(this._point){case 0:{this._context.moveTo(x,y);this._point=1;break}case 1:{this._context.lineTo(x,y);break}default:{this._context.moveTo(x+this._radius,y);this._context.arc(x,y,this._radius,0,tau);break}}},result:noop};var lengthSum$1=adder(),lengthRing,x00$2,y00$2,x0$4,y0$4;var lengthStream$1={point:noop,lineStart:function(){lengthStream$1.point=lengthPointFirst$1},lineEnd:function(){if(lengthRing)lengthPoint$1(x00$2,y00$2);lengthStream$1.point=noop},polygonStart:function(){lengthRing=true},polygonEnd:function(){lengthRing=null},result:function(){var length=+lengthSum$1;lengthSum$1.reset();return length}};function lengthPointFirst$1(x,y){lengthStream$1.point=lengthPoint$1;x00$2=x0$4=x,y00$2=y0$4=y}function lengthPoint$1(x,y){x0$4-=x,y0$4-=y;lengthSum$1.add(sqrt(x0$4*x0$4+y0$4*y0$4));x0$4=x,y0$4=y}function PathString(){this._string=[]}PathString.prototype={_radius:4.5,_circle:circle$1(4.5),pointRadius:function(_){if((_=+_)!==this._radius)this._radius=_,this._circle=null;return this},polygonStart:function(){this._line=0},polygonEnd:function(){this._line=NaN},lineStart:function(){this._point=0},lineEnd:function(){if(this._line===0)this._string.push("Z");this._point=NaN},point:function(x,y){switch(this._point){case 0:{this._string.push("M",x,",",y);this._point=1;break}case 1:{this._string.push("L",x,",",y);break}default:{if(this._circle==null)this._circle=circle$1(this._radius);this._string.push("M",x,",",y,this._circle);break}}},result:function(){if(this._string.length){var result=this._string.join("");this._string=[];return result}else{return null}}};function circle$1(radius){return"m0,"+radius+"a"+radius+","+radius+" 0 1,1 0,"+-2*radius+"a"+radius+","+radius+" 0 1,1 0,"+2*radius+"z"}function index(projection,context){var pointRadius=4.5,projectionStream,contextStream;function path(object){if(object){if(typeof pointRadius==="function")contextStream.pointRadius(+pointRadius.apply(this,arguments));geoStream(object,projectionStream(contextStream))}return contextStream.result()}path.area=function(object){geoStream(object,projectionStream(areaStream$1));return areaStream$1.result()};path.measure=function(object){geoStream(object,projectionStream(lengthStream$1));return lengthStream$1.result()};path.bounds=function(object){geoStream(object,projectionStream(boundsStream$1));return boundsStream$1.result()};path.centroid=function(object){geoStream(object,projectionStream(centroidStream$1));return centroidStream$1.result()};path.projection=function(_){return arguments.length?(projectionStream=_==null?(projection=null,identity):(projection=_).stream,path):projection};path.context=function(_){if(!arguments.length)return context;contextStream=_==null?(context=null,new PathString):new PathContext(context=_);if(typeof pointRadius!=="function")contextStream.pointRadius(pointRadius);return path};path.pointRadius=function(_){if(!arguments.length)return pointRadius;pointRadius=typeof _==="function"?_:(contextStream.pointRadius(+_),+_);return path};return path.projection(projection).context(context)}function transform(methods){return{stream:transformer(methods)}}function transformer(methods){return function(stream){var s=new TransformStream;for(var key in methods)s[key]=methods[key];s.stream=stream;return s}}function TransformStream(){}TransformStream.prototype={constructor:TransformStream,point:function(x,y){this.stream.point(x,y)},sphere:function(){this.stream.sphere()},lineStart:function(){this.stream.lineStart()},lineEnd:function(){this.stream.lineEnd()},polygonStart:function(){this.stream.polygonStart()},polygonEnd:function(){this.stream.polygonEnd()}};function fit(projection,fitBounds,object){var clip=projection.clipExtent&&projection.clipExtent();projection.scale(150).translate([0,0]);if(clip!=null)projection.clipExtent(null);geoStream(object,projection.stream(boundsStream$1));fitBounds(boundsStream$1.result());if(clip!=null)projection.clipExtent(clip);return projection}function fitExtent(projection,extent,object){return fit(projection,function(b){var w=extent[1][0]-extent[0][0],h=extent[1][1]-extent[0][1],k=Math.min(w/(b[1][0]-b[0][0]),h/(b[1][1]-b[0][1])),x=+extent[0][0]+(w-k*(b[1][0]+b[0][0]))/2,y=+extent[0][1]+(h-k*(b[1][1]+b[0][1]))/2;projection.scale(150*k).translate([x,y])},object)}function fitSize(projection,size,object){return fitExtent(projection,[[0,0],size],object)}function fitWidth(projection,width,object){return fit(projection,function(b){var w=+width,k=w/(b[1][0]-b[0][0]),x=(w-k*(b[1][0]+b[0][0]))/2,y=-k*b[0][1];projection.scale(150*k).translate([x,y])},object)}function fitHeight(projection,height,object){return fit(projection,function(b){var h=+height,k=h/(b[1][1]-b[0][1]),x=-k*b[0][0],y=(h-k*(b[1][1]+b[0][1]))/2;projection.scale(150*k).translate([x,y])},object)}var maxDepth=16,// maximum depth of subdivision -cosMinDistance=cos(30*radians);// cos(minimum angular distance) -function resample(project,delta2){return+delta2?resample$1(project,delta2):resampleNone(project)}function resampleNone(project){return transformer({point:function(x,y){x=project(x,y);this.stream.point(x[0],x[1])}})}function resample$1(project,delta2){function resampleLineTo(x0,y0,lambda0,a0,b0,c0,x1,y1,lambda1,a1,b1,c1,depth,stream){var dx=x1-x0,dy=y1-y0,d2=dx*dx+dy*dy;if(d2>4*delta2&&depth--){var a=a0+a1,b=b0+b1,c=c0+c1,m=sqrt(a*a+b*b+c*c),phi2=asin(c/=m),lambda2=abs(abs(c)-1)delta2||abs((dx*dx2+dy*dy2)/d2-.5)>.3||a0*a1+b0*b1+c0*c12?_[2]%360*radians:0,recenter()):[deltaLambda*degrees,deltaPhi*degrees,deltaGamma*degrees]};projection.angle=function(_){return arguments.length?(alpha=_%360*radians,recenter()):alpha*degrees};projection.precision=function(_){return arguments.length?(projectResample=resample(projectTransform,delta2=_*_),reset()):sqrt(delta2)};projection.fitExtent=function(extent,object){return fitExtent(projection,extent,object)};projection.fitSize=function(size,object){return fitSize(projection,size,object)};projection.fitWidth=function(width,object){return fitWidth(projection,width,object)};projection.fitHeight=function(height,object){return fitHeight(projection,height,object)};function recenter(){var center=scaleTranslateRotate(k,0,0,alpha).apply(null,project(lambda,phi)),transform=(alpha?scaleTranslateRotate:scaleTranslate)(k,x-center[0],y-center[1],alpha);rotate=rotateRadians(deltaLambda,deltaPhi,deltaGamma);projectTransform=compose(project,transform);projectRotateTransform=compose(rotate,projectTransform);projectResample=resample(projectTransform,delta2);return reset()}function reset(){cache=cacheStream=null;return projection}return function(){project=projectAt.apply(this,arguments);projection.invert=project.invert&&invert;return recenter()}}function conicProjection(projectAt){var phi0=0,phi1=pi/3,m=projectionMutator(projectAt),p=m(phi0,phi1);p.parallels=function(_){return arguments.length?m(phi0=_[0]*radians,phi1=_[1]*radians):[phi0*degrees,phi1*degrees]};return p}function cylindricalEqualAreaRaw(phi0){var cosPhi0=cos(phi0);function forward(lambda,phi){return[lambda*cosPhi0,sin(phi)/cosPhi0]}forward.invert=function(x,y){return[x/cosPhi0,asin(y*cosPhi0)]};return forward}function conicEqualAreaRaw(y0,y1){var sy0=sin(y0),n=(sy0+sin(y1))/2; -// Are the parallels symmetrical around the Equator? -if(abs(n)=.12&&y<.234&&x>=-.425&&x<-.214?alaska:y>=.166&&y<.234&&x>=-.214&&x<-.115?hawaii:lower48).invert(coordinates)};albersUsa.stream=function(stream){return cache&&cacheStream===stream?cache:cache=multiplex([lower48.stream(cacheStream=stream),alaska.stream(stream),hawaii.stream(stream)])};albersUsa.precision=function(_){if(!arguments.length)return lower48.precision();lower48.precision(_),alaska.precision(_),hawaii.precision(_);return reset()};albersUsa.scale=function(_){if(!arguments.length)return lower48.scale();lower48.scale(_),alaska.scale(_*.35),hawaii.scale(_);return albersUsa.translate(lower48.translate())};albersUsa.translate=function(_){if(!arguments.length)return lower48.translate();var k=lower48.scale(),x=+_[0],y=+_[1];lower48Point=lower48.translate(_).clipExtent([[x-.455*k,y-.238*k],[x+.455*k,y+.238*k]]).stream(pointStream);alaskaPoint=alaska.translate([x-.307*k,y+.201*k]).clipExtent([[x-.425*k+epsilon,y+.12*k+epsilon],[x-.214*k-epsilon,y+.234*k-epsilon]]).stream(pointStream);hawaiiPoint=hawaii.translate([x-.205*k,y+.212*k]).clipExtent([[x-.214*k+epsilon,y+.166*k+epsilon],[x-.115*k-epsilon,y+.234*k-epsilon]]).stream(pointStream);return reset()};albersUsa.fitExtent=function(extent,object){return fitExtent(albersUsa,extent,object)};albersUsa.fitSize=function(size,object){return fitSize(albersUsa,size,object)};albersUsa.fitWidth=function(width,object){return fitWidth(albersUsa,width,object)};albersUsa.fitHeight=function(height,object){return fitHeight(albersUsa,height,object)};function reset(){cache=cacheStream=null;return albersUsa}return albersUsa.scale(1070)}function azimuthalRaw(scale){return function(x,y){var cx=cos(x),cy=cos(y),k=scale(cx*cy);return[k*cy*sin(x),k*sin(y)]}}function azimuthalInvert(angle){return function(x,y){var z=sqrt(x*x+y*y),c=angle(z),sc=sin(c),cc=cos(c);return[atan2(x*sc,z*cc),asin(z&&y*sc/z)]}}var azimuthalEqualAreaRaw=azimuthalRaw(function(cxcy){return sqrt(2/(1+cxcy))});azimuthalEqualAreaRaw.invert=azimuthalInvert(function(z){return 2*asin(z/2)});function azimuthalEqualArea(){return projection(azimuthalEqualAreaRaw).scale(124.75).clipAngle(180-.001)}var azimuthalEquidistantRaw=azimuthalRaw(function(c){return(c=acos(c))&&c/sin(c)});azimuthalEquidistantRaw.invert=azimuthalInvert(function(z){return z});function azimuthalEquidistant(){return projection(azimuthalEquidistantRaw).scale(79.4188).clipAngle(180-.001)}function mercatorRaw(lambda,phi){return[lambda,log(tan((halfPi+phi)/2))]}mercatorRaw.invert=function(x,y){return[x,2*atan(exp(y))-halfPi]};function mercator(){return mercatorProjection(mercatorRaw).scale(961/tau)}function mercatorProjection(project){var m=projection(project),center=m.center,scale=m.scale,translate=m.translate,clipExtent=m.clipExtent,x0=null,y0,x1,y1;// clip extent -m.scale=function(_){return arguments.length?(scale(_),reclip()):scale()};m.translate=function(_){return arguments.length?(translate(_),reclip()):translate()};m.center=function(_){return arguments.length?(center(_),reclip()):center()};m.clipExtent=function(_){return arguments.length?(_==null?x0=y0=x1=y1=null:(x0=+_[0][0],y0=+_[0][1],x1=+_[1][0],y1=+_[1][1]),reclip()):x0==null?null:[[x0,y0],[x1,y1]]};function reclip(){var k=pi*scale(),t=m(rotation(m.rotate()).invert([0,0]));return clipExtent(x0==null?[[t[0]-k,t[1]-k],[t[0]+k,t[1]+k]]:project===mercatorRaw?[[Math.max(t[0]-k,x0),y0],[Math.min(t[0]+k,x1),y1]]:[[x0,Math.max(t[1]-k,y0)],[x1,Math.min(t[1]+k,y1)]])}return reclip()}function tany(y){return tan((halfPi+y)/2)}function conicConformalRaw(y0,y1){var cy0=cos(y0),n=y0===y1?sin(y0):log(cy0/cos(y1))/log(tany(y1)/tany(y0)),f=cy0*pow(tany(y0),n)/n;if(!n)return mercatorRaw;function project(x,y){if(f>0){if(y<-halfPi+epsilon)y=-halfPi+epsilon}else{if(y>halfPi-epsilon)y=halfPi-epsilon}var r=f/pow(tany(y),n);return[r*sin(n*x),f-r*cos(n*x)]}project.invert=function(x,y){var fy=f-y,r=sign(n)*sqrt(x*x+fy*fy);return[atan2(x,abs(fy))/n*sign(fy),2*atan(pow(f/r,1/n))-halfPi]};return project}function conicConformal(){return conicProjection(conicConformalRaw).scale(109.5).parallels([30,30])}function equirectangularRaw(lambda,phi){return[lambda,phi]}equirectangularRaw.invert=equirectangularRaw;function equirectangular(){return projection(equirectangularRaw).scale(152.63)}function conicEquidistantRaw(y0,y1){var cy0=cos(y0),n=y0===y1?sin(y0):(cy0-cos(y1))/(y1-y0),g=cy0/n+y0;if(abs(n)epsilon&&--i>0);return[x/(.8707+(phi2=phi*phi)*(-.131979+phi2*(-.013791+phi2*phi2*phi2*(.003971-.001529*phi2)))),phi]};function naturalEarth1(){return projection(naturalEarth1Raw).scale(175.295)}function orthographicRaw(x,y){return[cos(y)*sin(x),sin(y)]}orthographicRaw.invert=azimuthalInvert(asin);function orthographic(){return projection(orthographicRaw).scale(249.5).clipAngle(90+epsilon)}function stereographicRaw(x,y){var cy=cos(y),k=1+cos(x)*cy;return[cy*sin(x)/k,sin(y)/k]}stereographicRaw.invert=azimuthalInvert(function(z){return 2*atan(z)});function stereographic(){return projection(stereographicRaw).scale(250).clipAngle(142)}function transverseMercatorRaw(lambda,phi){return[log(tan((halfPi+phi)/2)),-lambda]}transverseMercatorRaw.invert=function(x,y){return[-y,2*atan(exp(x))-halfPi]};function transverseMercator(){var m=mercatorProjection(transverseMercatorRaw),center=m.center,rotate=m.rotate;m.center=function(_){return arguments.length?center([-_[1],_[0]]):(_=center(),[_[1],-_[0]])};m.rotate=function(_){return arguments.length?rotate([_[0],_[1],_.length>2?_[2]+90:90]):(_=rotate(),[_[0],_[1],_[2]-90])};return rotate([0,0,90]).scale(159.155)}exports.geoAlbers=albers;exports.geoAlbersUsa=albersUsa;exports.geoArea=area;exports.geoAzimuthalEqualArea=azimuthalEqualArea;exports.geoAzimuthalEqualAreaRaw=azimuthalEqualAreaRaw;exports.geoAzimuthalEquidistant=azimuthalEquidistant;exports.geoAzimuthalEquidistantRaw=azimuthalEquidistantRaw;exports.geoBounds=bounds;exports.geoCentroid=centroid;exports.geoCircle=circle;exports.geoClipAntimeridian=clipAntimeridian;exports.geoClipCircle=clipCircle;exports.geoClipExtent=extent;exports.geoClipRectangle=clipRectangle;exports.geoConicConformal=conicConformal;exports.geoConicConformalRaw=conicConformalRaw;exports.geoConicEqualArea=conicEqualArea;exports.geoConicEqualAreaRaw=conicEqualAreaRaw;exports.geoConicEquidistant=conicEquidistant;exports.geoConicEquidistantRaw=conicEquidistantRaw;exports.geoContains=contains;exports.geoDistance=distance;exports.geoEqualEarth=equalEarth;exports.geoEqualEarthRaw=equalEarthRaw;exports.geoEquirectangular=equirectangular;exports.geoEquirectangularRaw=equirectangularRaw;exports.geoGnomonic=gnomonic;exports.geoGnomonicRaw=gnomonicRaw;exports.geoGraticule=graticule;exports.geoGraticule10=graticule10;exports.geoIdentity=identity$1;exports.geoInterpolate=interpolate;exports.geoLength=length;exports.geoMercator=mercator;exports.geoMercatorRaw=mercatorRaw;exports.geoNaturalEarth1=naturalEarth1;exports.geoNaturalEarth1Raw=naturalEarth1Raw;exports.geoOrthographic=orthographic;exports.geoOrthographicRaw=orthographicRaw;exports.geoPath=index;exports.geoProjection=projection;exports.geoProjectionMutator=projectionMutator;exports.geoRotation=rotation;exports.geoStereographic=stereographic;exports.geoStereographicRaw=stereographicRaw;exports.geoStream=geoStream;exports.geoTransform=transform;exports.geoTransverseMercator=transverseMercator;exports.geoTransverseMercatorRaw=transverseMercatorRaw;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-array":29}],44:[function(require,module,exports){ -// https://d3js.org/d3-hierarchy/ v1.1.9 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):(global=global||self,factory(global.d3=global.d3||{}))})(this,function(exports){"use strict";function defaultSeparation(a,b){return a.parent===b.parent?1:2}function meanX(children){return children.reduce(meanXReduce,0)/children.length}function meanXReduce(x,c){return x+c.x}function maxY(children){return 1+children.reduce(maxYReduce,0)}function maxYReduce(y,c){return Math.max(y,c.y)}function leafLeft(node){var children;while(children=node.children)node=children[0];return node}function leafRight(node){var children;while(children=node.children)node=children[children.length-1];return node}function cluster(){var separation=defaultSeparation,dx=1,dy=1,nodeSize=false;function cluster(root){var previousNode,x=0; -// First walk, computing the initial x & y values. -root.eachAfter(function(node){var children=node.children;if(children){node.x=meanX(children);node.y=maxY(children)}else{node.x=previousNode?x+=separation(node,previousNode):0;node.y=0;previousNode=node}});var left=leafLeft(root),right=leafRight(root),x0=left.x-separation(left,right)/2,x1=right.x+separation(right,left)/2; -// Second walk, normalizing x & y to the desired size. -return root.eachAfter(nodeSize?function(node){node.x=(node.x-root.x)*dx;node.y=(root.y-node.y)*dy}:function(node){node.x=(node.x-x0)/(x1-x0)*dx;node.y=(1-(root.y?node.y/root.y:1))*dy})}cluster.separation=function(x){return arguments.length?(separation=x,cluster):separation};cluster.size=function(x){return arguments.length?(nodeSize=false,dx=+x[0],dy=+x[1],cluster):nodeSize?null:[dx,dy]};cluster.nodeSize=function(x){return arguments.length?(nodeSize=true,dx=+x[0],dy=+x[1],cluster):nodeSize?[dx,dy]:null};return cluster}function count(node){var sum=0,children=node.children,i=children&&children.length;if(!i)sum=1;else while(--i>=0)sum+=children[i].value;node.value=sum}function node_count(){return this.eachAfter(count)}function node_each(callback){var node=this,current,next=[node],children,i,n;do{current=next.reverse(),next=[];while(node=current.pop()){callback(node),children=node.children;if(children)for(i=0,n=children.length;i=0;--i){nodes.push(children[i])}}return this}function node_eachAfter(callback){var node=this,nodes=[node],next=[],children,i,n;while(node=nodes.pop()){next.push(node),children=node.children;if(children)for(i=0,n=children.length;i=0)sum+=children[i].value;node.value=sum})}function node_sort(compare){return this.eachBefore(function(node){if(node.children){node.children.sort(compare)}})}function node_path(end){var start=this,ancestor=leastCommonAncestor(start,end),nodes=[start];while(start!==ancestor){start=start.parent;nodes.push(start)}var k=nodes.length;while(end!==ancestor){nodes.splice(k,0,end);end=end.parent}return nodes}function leastCommonAncestor(a,b){if(a===b)return a;var aNodes=a.ancestors(),bNodes=b.ancestors(),c=null;a=aNodes.pop();b=bNodes.pop();while(a===b){c=a;a=aNodes.pop();b=bNodes.pop()}return c}function node_ancestors(){var node=this,nodes=[node];while(node=node.parent){nodes.push(node)}return nodes}function node_descendants(){var nodes=[];this.each(function(node){nodes.push(node)});return nodes}function node_leaves(){var leaves=[];this.eachBefore(function(node){if(!node.children){leaves.push(node)}});return leaves}function node_links(){var root=this,links=[];root.each(function(node){if(node!==root){// Don’t include the root’s parent, if any. -links.push({source:node.parent,target:node})}});return links}function hierarchy(data,children){var root=new Node(data),valued=+data.value&&(root.value=data.value),node,nodes=[root],child,childs,i,n;if(children==null)children=defaultChildren;while(node=nodes.pop()){if(valued)node.value=+node.data.value;if((childs=children(node.data))&&(n=childs.length)){node.children=new Array(n);for(i=n-1;i>=0;--i){nodes.push(child=node.children[i]=new Node(childs[i]));child.parent=node;child.depth=node.depth+1}}}return root.eachBefore(computeHeight)}function node_copy(){return hierarchy(this).eachBefore(copyData)}function defaultChildren(d){return d.children}function copyData(node){node.data=node.data.data}function computeHeight(node){var height=0;do{node.height=height}while((node=node.parent)&&node.height<++height)}function Node(data){this.data=data;this.depth=this.height=0;this.parent=null}Node.prototype=hierarchy.prototype={constructor:Node,count:node_count,each:node_each,eachAfter:node_eachAfter,eachBefore:node_eachBefore,sum:node_sum,sort:node_sort,path:node_path,ancestors:node_ancestors,descendants:node_descendants,leaves:node_leaves,links:node_links,copy:node_copy};var slice=Array.prototype.slice;function shuffle(array){var m=array.length,t,i;while(m){i=Math.random()*m--|0;t=array[m];array[m]=array[i];array[i]=t}return array}function enclose(circles){var i=0,n=(circles=shuffle(slice.call(circles))).length,B=[],p,e;while(i0&&dr*dr>dx*dx+dy*dy}function enclosesWeakAll(a,B){for(var i=0;ib2){x=(d2+b2-a2)/(2*d2);y=Math.sqrt(Math.max(0,b2/d2-x*x));c.x=b.x-x*dx-y*dy;c.y=b.y-x*dy+y*dx}else{x=(d2+a2-b2)/(2*d2);y=Math.sqrt(Math.max(0,a2/d2-x*x));c.x=a.x+x*dx-y*dy;c.y=a.y+x*dy+y*dx}}else{c.x=a.x+c.r;c.y=a.y}}function intersects(a,b){var dr=a.r+b.r-1e-6,dx=b.x-a.x,dy=b.y-a.y;return dr>0&&dr*dr>dx*dx+dy*dy}function score(node){var a=node._,b=node.next._,ab=a.r+b.r,dx=(a.x*b.r+b.x*a.r)/ab,dy=(a.y*b.r+b.y*a.r)/ab;return dx*dx+dy*dy}function Node$1(circle){this._=circle;this.next=null;this.previous=null}function packEnclose(circles){if(!(n=circles.length))return 0;var a,b,c,n,aa,ca,i,j,k,sj,sk; -// Place the first circle. -a=circles[0],a.x=0,a.y=0;if(!(n>1))return a.r; -// Place the second circle. -b=circles[1],a.x=-b.r,b.x=a.r,b.y=0;if(!(n>2))return a.r+b.r; -// Place the third circle. -place(b,a,c=circles[2]); -// Initialize the front-chain using the first three circles a, b and c. -a=new Node$1(a),b=new Node$1(b),c=new Node$1(c);a.next=c.previous=b;b.next=a.previous=c;c.next=b.previous=a; -// Attempt to place each remaining circle… -pack:for(i=3;i0)throw new Error("cycle");return root}stratify.id=function(x){return arguments.length?(id=required(x),stratify):id};stratify.parentId=function(x){return arguments.length?(parentId=required(x),stratify):parentId};return stratify}function defaultSeparation$1(a,b){return a.parent===b.parent?1:2} -// function radialSeparation(a, b) { -// return (a.parent === b.parent ? 1 : 2) / a.depth; -// } -// This function is used to traverse the left contour of a subtree (or -// subforest). It returns the successor of v on this contour. This successor is -// either given by the leftmost child of v or by the thread of v. The function -// returns null if and only if v is on the highest level of its subtree. -function nextLeft(v){var children=v.children;return children?children[0]:v.t} -// This function works analogously to nextLeft. -function nextRight(v){var children=v.children;return children?children[children.length-1]:v.t} -// Shifts the current subtree rooted at w+. This is done by increasing -// prelim(w+) and mod(w+) by shift. -function moveSubtree(wm,wp,shift){var change=shift/(wp.i-wm.i);wp.c-=change;wp.s+=shift;wm.c+=change;wp.z+=shift;wp.m+=shift} -// All other shifts, applied to the smaller subtrees between w- and w+, are -// performed by this function. To prepare the shifts, we have to adjust -// change(w+), shift(w+), and change(w-). -function executeShifts(v){var shift=0,change=0,children=v.children,i=children.length,w;while(--i>=0){w=children[i];w.z+=shift;w.m+=shift;shift+=w.s+(change+=w.c)}} -// If vi-’s ancestor is a sibling of v, returns vi-’s ancestor. Otherwise, -// returns the specified (default) ancestor. -function nextAncestor(vim,v,ancestor){return vim.a.parent===v.parent?vim.a:ancestor}function TreeNode(node,i){this._=node;this.parent=null;this.children=null;this.A=null;// default ancestor -this.a=this;// ancestor -this.z=0;// prelim -this.m=0;// mod -this.c=0;// change -this.s=0;// shift -this.t=null;// thread -this.i=i;// number -}TreeNode.prototype=Object.create(Node.prototype);function treeRoot(root){var tree=new TreeNode(root,0),node,nodes=[tree],child,children,i,n;while(node=nodes.pop()){if(children=node._.children){node.children=new Array(n=children.length);for(i=n-1;i>=0;--i){nodes.push(child=node.children[i]=new TreeNode(children[i],i));child.parent=node}}}(tree.parent=new TreeNode(null,0)).children=[tree];return tree} -// Node-link tree diagram using the Reingold-Tilford "tidy" algorithm -function tree(){var separation=defaultSeparation$1,dx=1,dy=1,nodeSize=null;function tree(root){var t=treeRoot(root); -// Compute the layout using Buchheim et al.’s algorithm. -t.eachAfter(firstWalk),t.parent.m=-t.z;t.eachBefore(secondWalk); -// If a fixed node size is specified, scale x and y. -if(nodeSize)root.eachBefore(sizeNode); -// If a fixed tree size is specified, scale x and y based on the extent. -// Compute the left-most, right-most, and depth-most nodes for extents. -else{var left=root,right=root,bottom=root;root.eachBefore(function(node){if(node.xright.x)right=node;if(node.depth>bottom.depth)bottom=node});var s=left===right?1:separation(left,right)/2,tx=s-left.x,kx=dx/(right.x+s+tx),ky=dy/(bottom.depth||1);root.eachBefore(function(node){node.x=(node.x+tx)*kx;node.y=node.depth*ky})}return root} -// Computes a preliminary x-coordinate for v. Before that, FIRST WALK is -// applied recursively to the children of v, as well as the function -// APPORTION. After spacing out the children by calling EXECUTE SHIFTS, the -// node v is placed to the midpoint of its outermost children. -function firstWalk(v){var children=v.children,siblings=v.parent.children,w=v.i?siblings[v.i-1]:null;if(children){executeShifts(v);var midpoint=(children[0].z+children[children.length-1].z)/2;if(w){v.z=w.z+separation(v._,w._);v.m=v.z-midpoint}else{v.z=midpoint}}else if(w){v.z=w.z+separation(v._,w._)}v.parent.A=apportion(v,w,v.parent.A||siblings[0])} -// Computes all real x-coordinates by summing up the modifiers recursively. -function secondWalk(v){v._.x=v.z+v.parent.m;v.m+=v.parent.m} -// The core of the algorithm. Here, a new subtree is combined with the -// previous subtrees. Threads are used to traverse the inside and outside -// contours of the left and right subtree up to the highest common level. The -// vertices used for the traversals are vi+, vi-, vo-, and vo+, where the -// superscript o means outside and i means inside, the subscript - means left -// subtree and + means right subtree. For summing up the modifiers along the -// contour, we use respective variables si+, si-, so-, and so+. Whenever two -// nodes of the inside contours conflict, we compute the left one of the -// greatest uncommon ancestors using the function ANCESTOR and call MOVE -// SUBTREE to shift the subtree and prepare the shifts of smaller subtrees. -// Finally, we add a new thread (if necessary). -function apportion(v,w,ancestor){if(w){var vip=v,vop=v,vim=w,vom=vip.parent.children[0],sip=vip.m,sop=vop.m,sim=vim.m,som=vom.m,shift;while(vim=nextRight(vim),vip=nextLeft(vip),vim&&vip){vom=nextLeft(vom);vop=nextRight(vop);vop.a=v;shift=vim.z+sim-vip.z-sip+separation(vim._,vip._);if(shift>0){moveSubtree(nextAncestor(vim,v,ancestor),v,shift);sip+=shift;sop+=shift}sim+=vim.m;sip+=vip.m;som+=vom.m;sop+=vop.m}if(vim&&!nextRight(vop)){vop.t=vim;vop.m+=sim-sop}if(vip&&!nextLeft(vom)){vom.t=vip;vom.m+=sip-som;ancestor=v}}return ancestor}function sizeNode(node){node.x*=dx;node.y=node.depth*dy}tree.separation=function(x){return arguments.length?(separation=x,tree):separation};tree.size=function(x){return arguments.length?(nodeSize=false,dx=+x[0],dy=+x[1],tree):nodeSize?null:[dx,dy]};tree.nodeSize=function(x){return arguments.length?(nodeSize=true,dx=+x[0],dy=+x[1],tree):nodeSize?[dx,dy]:null};return tree}function treemapSlice(parent,x0,y0,x1,y1){var nodes=parent.children,node,i=-1,n=nodes.length,k=parent.value&&(y1-y0)/parent.value;while(++imaxValue)maxValue=nodeValue;beta=sumValue*sumValue*alpha;newRatio=Math.max(maxValue/beta,beta/minValue);if(newRatio>minRatio){sumValue-=nodeValue;break}minRatio=newRatio} -// Position and record the row orientation. -rows.push(row={value:sumValue,dice:dx1?x:1)};return squarify}(phi);function index$1(){var tile=squarify,round=false,dx=1,dy=1,paddingStack=[0],paddingInner=constantZero,paddingTop=constantZero,paddingRight=constantZero,paddingBottom=constantZero,paddingLeft=constantZero;function treemap(root){root.x0=root.y0=0;root.x1=dx;root.y1=dy;root.eachBefore(positionNode);paddingStack=[0];if(round)root.eachBefore(roundNode);return root}function positionNode(node){var p=paddingStack[node.depth],x0=node.x0+p,y0=node.y0+p,x1=node.x1-p,y1=node.y1-p;if(x1=j-1){var node=nodes[i];node.x0=x0,node.y0=y0;node.x1=x1,node.y1=y1;return}var valueOffset=sums[i],valueTarget=value/2+valueOffset,k=i+1,hi=j-1;while(k>>1;if(sums[mid]y1-y0){var xk=(x0*valueRight+x1*valueLeft)/value;partition(i,k,valueLeft,x0,y0,xk,y1);partition(k,j,valueRight,xk,y0,x1,y1)}else{var yk=(y0*valueRight+y1*valueLeft)/value;partition(i,k,valueLeft,x0,y0,x1,yk);partition(k,j,valueRight,x0,yk,x1,y1)}}}function sliceDice(parent,x0,y0,x1,y1){(parent.depth&1?treemapSlice:treemapDice)(parent,x0,y0,x1,y1)}var resquarify=function custom(ratio){function resquarify(parent,x0,y0,x1,y1){if((rows=parent._squarify)&&rows.ratio===ratio){var rows,row,nodes,i,j=-1,n,m=rows.length,value=parent.value;while(++j1?x:1)};return resquarify}(phi);exports.cluster=cluster;exports.hierarchy=hierarchy;exports.pack=index;exports.packEnclose=enclose;exports.packSiblings=siblings;exports.partition=partition;exports.stratify=stratify;exports.tree=tree;exports.treemap=index$1;exports.treemapBinary=binary;exports.treemapDice=treemapDice;exports.treemapResquarify=resquarify;exports.treemapSlice=treemapSlice;exports.treemapSliceDice=sliceDice;exports.treemapSquarify=squarify;Object.defineProperty(exports,"__esModule",{value:true})})},{}],45:[function(require,module,exports){ -// https://d3js.org/d3-interpolate/ v1.4.0 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports,require("d3-color")):typeof define==="function"&&define.amd?define(["exports","d3-color"],factory):(global=global||self,factory(global.d3=global.d3||{},global.d3))})(this,function(exports,d3Color){"use strict";function basis(t1,v0,v1,v2,v3){var t2=t1*t1,t3=t2*t1;return((1-3*t1+3*t2-t3)*v0+(4-6*t2+3*t3)*v1+(1+3*t1+3*t2-3*t3)*v2+t3*v3)/6}function basis$1(values){var n=values.length-1;return function(t){var i=t<=0?t=0:t>=1?(t=1,n-1):Math.floor(t*n),v1=values[i],v2=values[i+1],v0=i>0?values[i-1]:2*v1-v2,v3=i180||d<-180?d-360*Math.round(d/360):d):constant(isNaN(a)?b:a)}function gamma(y){return(y=+y)===1?nogamma:function(a,b){return b-a?exponential(a,b,y):constant(isNaN(a)?b:a)}}function nogamma(a,b){var d=b-a;return d?linear(a,d):constant(isNaN(a)?b:a)}var rgb=function rgbGamma(y){var color=gamma(y);function rgb(start,end){var r=color((start=d3Color.rgb(start)).r,(end=d3Color.rgb(end)).r),g=color(start.g,end.g),b=color(start.b,end.b),opacity=nogamma(start.opacity,end.opacity);return function(t){start.r=r(t);start.g=g(t);start.b=b(t);start.opacity=opacity(t);return start+""}}rgb.gamma=rgbGamma;return rgb}(1);function rgbSpline(spline){return function(colors){var n=colors.length,r=new Array(n),g=new Array(n),b=new Array(n),i,color;for(i=0;ibi){// a string precedes the next number in b -bs=b.slice(bi,bs);if(s[i])s[i]+=bs;// coalesce with previous string -else s[++i]=bs}if((am=am[0])===(bm=bm[0])){// numbers in a & b match -if(s[i])s[i]+=bm;// coalesce with previous string -else s[++i]=bm}else{// interpolate non-matching numbers -s[++i]=null;q.push({i:i,x:number(am,bm)})}bi=reB.lastIndex} -// Add remains of b. -if(bi180)b+=360;else if(b-a>180)a+=360;// shortest path -q.push({i:s.push(pop(s)+"rotate(",null,degParen)-2,x:number(a,b)})}else if(b){s.push(pop(s)+"rotate("+b+degParen)}}function skewX(a,b,s,q){if(a!==b){q.push({i:s.push(pop(s)+"skewX(",null,degParen)-2,x:number(a,b)})}else if(b){s.push(pop(s)+"skewX("+b+degParen)}}function scale(xa,ya,xb,yb,s,q){if(xa!==xb||ya!==yb){var i=s.push(pop(s)+"scale(",null,",",null,")");q.push({i:i-4,x:number(xa,xb)},{i:i-2,x:number(ya,yb)})}else if(xb!==1||yb!==1){s.push(pop(s)+"scale("+xb+","+yb+")")}}return function(a,b){var s=[],// string constants and placeholders -q=[];// number interpolators -a=parse(a),b=parse(b);translate(a.translateX,a.translateY,b.translateX,b.translateY,s,q);rotate(a.rotate,b.rotate,s,q);skewX(a.skewX,b.skewX,s,q);scale(a.scaleX,a.scaleY,b.scaleX,b.scaleY,s,q);a=b=null;// gc -return function(t){var i=-1,n=q.length,o;while(++iepsilon));else if(!(Math.abs(y01*x21-y21*x01)>epsilon)||!r){this._+="L"+(this._x1=x1)+","+(this._y1=y1)} -// Otherwise, draw an arc! -else{var x20=x2-x0,y20=y2-y0,l21_2=x21*x21+y21*y21,l20_2=x20*x20+y20*y20,l21=Math.sqrt(l21_2),l01=Math.sqrt(l01_2),l=r*Math.tan((pi-Math.acos((l21_2+l01_2-l20_2)/(2*l21*l01)))/2),t01=l/l01,t21=l/l21; -// If the start tangent is not coincident with (x0,y0), line to. -if(Math.abs(t01-1)>epsilon){this._+="L"+(x1+t01*x01)+","+(y1+t01*y01)}this._+="A"+r+","+r+",0,0,"+ +(y01*x20>x01*y20)+","+(this._x1=x1+t21*x21)+","+(this._y1=y1+t21*y21)}},arc:function(x,y,r,a0,a1,ccw){x=+x,y=+y,r=+r,ccw=!!ccw;var dx=r*Math.cos(a0),dy=r*Math.sin(a0),x0=x+dx,y0=y+dy,cw=1^ccw,da=ccw?a0-a1:a1-a0; -// Is the radius negative? Error. -if(r<0)throw new Error("negative radius: "+r); -// Is this path empty? Move to (x0,y0). -if(this._x1===null){this._+="M"+x0+","+y0} -// Or, is (x0,y0) not coincident with the previous point? Line to (x0,y0). -else if(Math.abs(this._x1-x0)>epsilon||Math.abs(this._y1-y0)>epsilon){this._+="L"+x0+","+y0} -// Is this arc empty? We’re done. -if(!r)return; -// Does the angle go the wrong way? Flip the direction. -if(da<0)da=da%tau+tau; -// Is this a complete circle? Draw two arcs to complete the circle. -if(da>tauEpsilon){this._+="A"+r+","+r+",0,1,"+cw+","+(x-dx)+","+(y-dy)+"A"+r+","+r+",0,1,"+cw+","+(this._x1=x0)+","+(this._y1=y0)} -// Is this arc non-empty? Draw an arc! -else if(da>epsilon){this._+="A"+r+","+r+",0,"+ +(da>=pi)+","+cw+","+(this._x1=x+r*Math.cos(a1))+","+(this._y1=y+r*Math.sin(a1))}},rect:function(x,y,w,h){this._+="M"+(this._x0=this._x1=+x)+","+(this._y0=this._y1=+y)+"h"+ +w+"v"+ +h+"h"+-w+"Z"},toString:function(){return this._}};exports.path=path;Object.defineProperty(exports,"__esModule",{value:true})})},{}],47:[function(require,module,exports){ -// https://d3js.org/d3-polygon/ v1.0.6 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):(global=global||self,factory(global.d3=global.d3||{}))})(this,function(exports){"use strict";function area(polygon){var i=-1,n=polygon.length,a,b=polygon[n-1],area=0;while(++i= 3, is sorted by x, unique in y. -// Returns an array of indices into points in left-to-right order. -function computeUpperHullIndexes(points){var n=points.length,indexes=[0,1],size=2;for(var i=2;i1&&cross(points[indexes[size-2]],points[indexes[size-1]],points[i])<=0)--size;indexes[size++]=i}return indexes.slice(0,size);// remove popped points -}function hull(points){if((n=points.length)<3)return null;var i,n,sortedPoints=new Array(n),flippedPoints=new Array(n);for(i=0;i=0;--i)hull.push(points[sortedPoints[upperIndexes[i]][2]]);for(i=+skipLeft;iy!==y0>y&&x<(x0-x1)*(y-y1)/(y0-y1)+x1)inside=!inside;x0=x1,y0=y1}return inside}function length(polygon){var i=-1,n=polygon.length,b=polygon[n-1],xa,ya,xb=b[0],yb=b[1],perimeter=0;while(++i=(xm=(x0+x1)/2))x0=xm;else x1=xm;if(bottom=y>=(ym=(y0+y1)/2))y0=ym;else y1=ym;if(parent=node,!(node=node[i=bottom<<1|right]))return parent[i]=leaf,tree} -// Is the new point is exactly coincident with the existing point? -xp=+tree._x.call(null,node.data);yp=+tree._y.call(null,node.data);if(x===xp&&y===yp)return leaf.next=node,parent?parent[i]=leaf:tree._root=leaf,tree; -// Otherwise, split the leaf node until the old and new point are separated. -do{parent=parent?parent[i]=new Array(4):tree._root=new Array(4);if(right=x>=(xm=(x0+x1)/2))x0=xm;else x1=xm;if(bottom=y>=(ym=(y0+y1)/2))y0=ym;else y1=ym}while((i=bottom<<1|right)===(j=(yp>=ym)<<1|xp>=xm));return parent[j]=node,parent[i]=leaf,tree}function addAll(data){var d,i,n=data.length,x,y,xz=new Array(n),yz=new Array(n),x0=Infinity,y0=Infinity,x1=-Infinity,y1=-Infinity; -// Compute the points and their extent. -for(i=0;ix1)x1=x;if(yy1)y1=y} -// If there were no (valid) points, abort. -if(x0>x1||y0>y1)return this; -// Expand the tree to cover the new points. -this.cover(x0,y0).cover(x1,y1); -// Add the new points. -for(i=0;ix||x>=x1||y0>y||y>=y1){i=(yx3||(y1=q.y0)>y3||(x2=q.x1)=ym)<<1|x>=xm){q=quads[quads.length-1];quads[quads.length-1]=quads[quads.length-1-i];quads[quads.length-1-i]=q}} -// Visit this point. (Visiting coincident points isn’t necessary!) -else{var dx=x-+this._x.call(null,node.data),dy=y-+this._y.call(null,node.data),d2=dx*dx+dy*dy;if(d2=(xm=(x0+x1)/2))x0=xm;else x1=xm;if(bottom=y>=(ym=(y0+y1)/2))y0=ym;else y1=ym;if(!(parent=node,node=node[i=bottom<<1|right]))return this;if(!node.length)break;if(parent[i+1&3]||parent[i+2&3]||parent[i+3&3])retainer=parent,j=i} -// Find the point to remove. -while(node.data!==d)if(!(previous=node,node=node.next))return this;if(next=node.next)delete node.next; -// If there are multiple coincident points, remove just the point. -if(previous)return next?previous.next=next:delete previous.next,this; -// If this is the root point, remove it. -if(!parent)return this._root=next,this; -// Remove this leaf. -next?parent[i]=next:delete parent[i]; -// If the parent now contains exactly one leaf, collapse superfluous parents. -if((node=parent[0]||parent[1]||parent[2]||parent[3])&&node===(parent[3]||parent[2]||parent[1]||parent[0])&&!node.length){if(retainer)retainer[j]=node;else this._root=node}return this}function removeAll(data){for(var i=0,n=data.length;i1);return mu+sigma*y*Math.sqrt(-2*Math.log(r)/r)}}randomNormal.source=sourceRandomNormal;return randomNormal}(defaultSource);var logNormal=function sourceRandomLogNormal(source){function randomLogNormal(){var randomNormal=normal.source(source).apply(this,arguments);return function(){return Math.exp(randomNormal())}}randomLogNormal.source=sourceRandomLogNormal;return randomLogNormal}(defaultSource);var irwinHall=function sourceRandomIrwinHall(source){function randomIrwinHall(n){return function(){for(var sum=0,i=0;i1)t-=Math.floor(t);var ts=Math.abs(t-.5);c.h=360*t-100;c.s=1.5-1.5*ts;c.l=.8-.9*ts;return c+""}var c$1=d3Color.rgb(),pi_1_3=Math.PI/3,pi_2_3=Math.PI*2/3;function sinebow(t){var x;t=(.5-t)*Math.PI;c$1.r=255*(x=Math.sin(t))*x;c$1.g=255*(x=Math.sin(t+pi_1_3))*x;c$1.b=255*(x=Math.sin(t+pi_2_3))*x;return c$1+""}function turbo(t){t=Math.max(0,Math.min(1,t));return"rgb("+Math.max(0,Math.min(255,Math.round(34.61+t*(1172.33-t*(10793.56-t*(33300.12-t*(38394.49-t*14825.05)))))))+", "+Math.max(0,Math.min(255,Math.round(23.31+t*(557.33+t*(1225.33-t*(3574.96-t*(1073.77+t*707.56)))))))+", "+Math.max(0,Math.min(255,Math.round(27.2+t*(3211.1-t*(15327.97-t*(27814-t*(22569.18-t*6838.66)))))))+")"}function ramp$1(range){var n=range.length;return function(t){return range[Math.max(0,Math.min(n-1,Math.floor(t*n)))]}}var viridis=ramp$1(colors("44015444025645045745055946075a46085c460a5d460b5e470d60470e6147106347116447136548146748166848176948186a481a6c481b6d481c6e481d6f481f70482071482173482374482475482576482677482878482979472a7a472c7a472d7b472e7c472f7d46307e46327e46337f463480453581453781453882443983443a83443b84433d84433e85423f854240864241864142874144874045884046883f47883f48893e49893e4a893e4c8a3d4d8a3d4e8a3c4f8a3c508b3b518b3b528b3a538b3a548c39558c39568c38588c38598c375a8c375b8d365c8d365d8d355e8d355f8d34608d34618d33628d33638d32648e32658e31668e31678e31688e30698e306a8e2f6b8e2f6c8e2e6d8e2e6e8e2e6f8e2d708e2d718e2c718e2c728e2c738e2b748e2b758e2a768e2a778e2a788e29798e297a8e297b8e287c8e287d8e277e8e277f8e27808e26818e26828e26828e25838e25848e25858e24868e24878e23888e23898e238a8d228b8d228c8d228d8d218e8d218f8d21908d21918c20928c20928c20938c1f948c1f958b1f968b1f978b1f988b1f998a1f9a8a1e9b8a1e9c891e9d891f9e891f9f881fa0881fa1881fa1871fa28720a38620a48621a58521a68522a78522a88423a98324aa8325ab8225ac8226ad8127ad8128ae8029af7f2ab07f2cb17e2db27d2eb37c2fb47c31b57b32b67a34b67935b77937b87838b9773aba763bbb753dbc743fbc7340bd7242be7144bf7046c06f48c16e4ac16d4cc26c4ec36b50c46a52c56954c56856c66758c7655ac8645cc8635ec96260ca6063cb5f65cb5e67cc5c69cd5b6ccd5a6ece5870cf5773d05675d05477d1537ad1517cd2507fd34e81d34d84d44b86d54989d5488bd6468ed64590d74393d74195d84098d83e9bd93c9dd93ba0da39a2da37a5db36a8db34aadc32addc30b0dd2fb2dd2db5de2bb8de29bade28bddf26c0df25c2df23c5e021c8e020cae11fcde11dd0e11cd2e21bd5e21ad8e219dae319dde318dfe318e2e418e5e419e7e419eae51aece51befe51cf1e51df4e61ef6e620f8e621fbe723fde725"));var magma=ramp$1(colors("00000401000501010601010802010902020b02020d03030f03031204041405041606051806051a07061c08071e0907200a08220b09240c09260d0a290e0b2b100b2d110c2f120d31130d34140e36150e38160f3b180f3d19103f1a10421c10441d11471e114920114b21114e22115024125325125527125829115a2a115c2c115f2d11612f116331116533106734106936106b38106c390f6e3b0f703d0f713f0f72400f74420f75440f764510774710784910784a10794c117a4e117b4f127b51127c52137c54137d56147d57157e59157e5a167e5c167f5d177f5f187f601880621980641a80651a80671b80681c816a1c816b1d816d1d816e1e81701f81721f817320817521817621817822817922827b23827c23827e24828025828125818326818426818627818827818928818b29818c29818e2a81902a81912b81932b80942c80962c80982d80992d809b2e7f9c2e7f9e2f7fa02f7fa1307ea3307ea5317ea6317da8327daa337dab337cad347cae347bb0357bb2357bb3367ab5367ab73779b83779ba3878bc3978bd3977bf3a77c03a76c23b75c43c75c53c74c73d73c83e73ca3e72cc3f71cd4071cf4070d0416fd2426fd3436ed5446dd6456cd8456cd9466bdb476adc4869de4968df4a68e04c67e24d66e34e65e44f64e55064e75263e85362e95462ea5661eb5760ec5860ed5a5fee5b5eef5d5ef05f5ef1605df2625df2645cf3655cf4675cf4695cf56b5cf66c5cf66e5cf7705cf7725cf8745cf8765cf9785df9795df97b5dfa7d5efa7f5efa815ffb835ffb8560fb8761fc8961fc8a62fc8c63fc8e64fc9065fd9266fd9467fd9668fd9869fd9a6afd9b6bfe9d6cfe9f6dfea16efea36ffea571fea772fea973feaa74feac76feae77feb078feb27afeb47bfeb67cfeb77efeb97ffebb81febd82febf84fec185fec287fec488fec68afec88cfeca8dfecc8ffecd90fecf92fed194fed395fed597fed799fed89afdda9cfddc9efddea0fde0a1fde2a3fde3a5fde5a7fde7a9fde9aafdebacfcecaefceeb0fcf0b2fcf2b4fcf4b6fcf6b8fcf7b9fcf9bbfcfbbdfcfdbf"));var inferno=ramp$1(colors("00000401000501010601010802010a02020c02020e03021004031204031405041706041907051b08051d09061f0a07220b07240c08260d08290e092b10092d110a30120a32140b34150b37160b39180c3c190c3e1b0c411c0c431e0c451f0c48210c4a230c4c240c4f260c51280b53290b552b0b572d0b592f0a5b310a5c320a5e340a5f3609613809623909633b09643d09653e0966400a67420a68440a68450a69470b6a490b6a4a0c6b4c0c6b4d0d6c4f0d6c510e6c520e6d540f6d550f6d57106e59106e5a116e5c126e5d126e5f136e61136e62146e64156e65156e67166e69166e6a176e6c186e6d186e6f196e71196e721a6e741a6e751b6e771c6d781c6d7a1d6d7c1d6d7d1e6d7f1e6c801f6c82206c84206b85216b87216b88226a8a226a8c23698d23698f24699025689225689326679526679727669827669a28659b29649d29649f2a63a02a63a22b62a32c61a52c60a62d60a82e5fa92e5eab2f5ead305dae305cb0315bb1325ab3325ab43359b63458b73557b93556ba3655bc3754bd3853bf3952c03a51c13a50c33b4fc43c4ec63d4dc73e4cc83f4bca404acb4149cc4248ce4347cf4446d04545d24644d34743d44842d54a41d74b3fd84c3ed94d3dda4e3cdb503bdd513ade5238df5337e05536e15635e25734e35933e45a31e55c30e65d2fe75e2ee8602de9612bea632aeb6429eb6628ec6726ed6925ee6a24ef6c23ef6e21f06f20f1711ff1731df2741cf3761bf37819f47918f57b17f57d15f67e14f68013f78212f78410f8850ff8870ef8890cf98b0bf98c0af98e09fa9008fa9207fa9407fb9606fb9706fb9906fb9b06fb9d07fc9f07fca108fca309fca50afca60cfca80dfcaa0ffcac11fcae12fcb014fcb216fcb418fbb61afbb81dfbba1ffbbc21fbbe23fac026fac228fac42afac62df9c72ff9c932f9cb35f8cd37f8cf3af7d13df7d340f6d543f6d746f5d949f5db4cf4dd4ff4df53f4e156f3e35af3e55df2e661f2e865f2ea69f1ec6df1ed71f1ef75f1f179f2f27df2f482f3f586f3f68af4f88ef5f992f6fa96f8fb9af9fc9dfafda1fcffa4"));var plasma=ramp$1(colors("0d088710078813078916078a19068c1b068d1d068e20068f2206902406912605912805922a05932c05942e05952f059631059733059735049837049938049a3a049a3c049b3e049c3f049c41049d43039e44039e46039f48039f4903a04b03a14c02a14e02a25002a25102a35302a35502a45601a45801a45901a55b01a55c01a65e01a66001a66100a76300a76400a76600a76700a86900a86a00a86c00a86e00a86f00a87100a87201a87401a87501a87701a87801a87a02a87b02a87d03a87e03a88004a88104a78305a78405a78606a68707a68808a68a09a58b0aa58d0ba58e0ca48f0da4910ea3920fa39410a29511a19613a19814a099159f9a169f9c179e9d189d9e199da01a9ca11b9ba21d9aa31e9aa51f99a62098a72197a82296aa2395ab2494ac2694ad2793ae2892b02991b12a90b22b8fb32c8eb42e8db52f8cb6308bb7318ab83289ba3388bb3488bc3587bd3786be3885bf3984c03a83c13b82c23c81c33d80c43e7fc5407ec6417dc7427cc8437bc9447aca457acb4679cc4778cc4977cd4a76ce4b75cf4c74d04d73d14e72d24f71d35171d45270d5536fd5546ed6556dd7566cd8576bd9586ada5a6ada5b69db5c68dc5d67dd5e66de5f65de6164df6263e06363e16462e26561e26660e3685fe4695ee56a5de56b5de66c5ce76e5be76f5ae87059e97158e97257ea7457eb7556eb7655ec7754ed7953ed7a52ee7b51ef7c51ef7e50f07f4ff0804ef1814df1834cf2844bf3854bf3874af48849f48948f58b47f58c46f68d45f68f44f79044f79143f79342f89441f89540f9973ff9983ef99a3efa9b3dfa9c3cfa9e3bfb9f3afba139fba238fca338fca537fca636fca835fca934fdab33fdac33fdae32fdaf31fdb130fdb22ffdb42ffdb52efeb72dfeb82cfeba2cfebb2bfebd2afebe2afec029fdc229fdc328fdc527fdc627fdc827fdca26fdcb26fccd25fcce25fcd025fcd225fbd324fbd524fbd724fad824fada24f9dc24f9dd25f8df25f8e125f7e225f7e425f6e626f6e826f5e926f5eb27f4ed27f3ee27f3f027f2f227f1f426f1f525f0f724f0f921"));exports.interpolateBlues=Blues;exports.interpolateBrBG=BrBG;exports.interpolateBuGn=BuGn;exports.interpolateBuPu=BuPu;exports.interpolateCividis=cividis;exports.interpolateCool=cool;exports.interpolateCubehelixDefault=cubehelix;exports.interpolateGnBu=GnBu;exports.interpolateGreens=Greens;exports.interpolateGreys=Greys;exports.interpolateInferno=inferno;exports.interpolateMagma=magma;exports.interpolateOrRd=OrRd;exports.interpolateOranges=Oranges;exports.interpolatePRGn=PRGn;exports.interpolatePiYG=PiYG;exports.interpolatePlasma=plasma;exports.interpolatePuBu=PuBu;exports.interpolatePuBuGn=PuBuGn;exports.interpolatePuOr=PuOr;exports.interpolatePuRd=PuRd;exports.interpolatePurples=Purples;exports.interpolateRainbow=rainbow;exports.interpolateRdBu=RdBu;exports.interpolateRdGy=RdGy;exports.interpolateRdPu=RdPu;exports.interpolateRdYlBu=RdYlBu;exports.interpolateRdYlGn=RdYlGn;exports.interpolateReds=Reds;exports.interpolateSinebow=sinebow;exports.interpolateSpectral=Spectral;exports.interpolateTurbo=turbo;exports.interpolateViridis=viridis;exports.interpolateWarm=warm;exports.interpolateYlGn=YlGn;exports.interpolateYlGnBu=YlGnBu;exports.interpolateYlOrBr=YlOrBr;exports.interpolateYlOrRd=YlOrRd;exports.schemeAccent=Accent;exports.schemeBlues=scheme$l;exports.schemeBrBG=scheme;exports.schemeBuGn=scheme$9;exports.schemeBuPu=scheme$a;exports.schemeCategory10=category10;exports.schemeDark2=Dark2;exports.schemeGnBu=scheme$b;exports.schemeGreens=scheme$m;exports.schemeGreys=scheme$n;exports.schemeOrRd=scheme$c;exports.schemeOranges=scheme$q;exports.schemePRGn=scheme$1;exports.schemePaired=Paired;exports.schemePastel1=Pastel1;exports.schemePastel2=Pastel2;exports.schemePiYG=scheme$2;exports.schemePuBu=scheme$e;exports.schemePuBuGn=scheme$d;exports.schemePuOr=scheme$3;exports.schemePuRd=scheme$f;exports.schemePurples=scheme$o;exports.schemeRdBu=scheme$4;exports.schemeRdGy=scheme$5;exports.schemeRdPu=scheme$g;exports.schemeRdYlBu=scheme$6;exports.schemeRdYlGn=scheme$7;exports.schemeReds=scheme$p;exports.schemeSet1=Set1;exports.schemeSet2=Set2;exports.schemeSet3=Set3;exports.schemeSpectral=scheme$8;exports.schemeTableau10=Tableau10;exports.schemeYlGn=scheme$i;exports.schemeYlGnBu=scheme$h;exports.schemeYlOrBr=scheme$j;exports.schemeYlOrRd=scheme$k;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-color":34,"d3-interpolate":45}],51:[function(require,module,exports){ -// https://d3js.org/d3-scale/ v2.2.2 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports,require("d3-collection"),require("d3-array"),require("d3-interpolate"),require("d3-format"),require("d3-time"),require("d3-time-format")):typeof define==="function"&&define.amd?define(["exports","d3-collection","d3-array","d3-interpolate","d3-format","d3-time","d3-time-format"],factory):factory(global.d3=global.d3||{},global.d3,global.d3,global.d3,global.d3,global.d3,global.d3)})(this,function(exports,d3Collection,d3Array,d3Interpolate,d3Format,d3Time,d3TimeFormat){"use strict";function initRange(domain,range){switch(arguments.length){case 0:break;case 1:this.range(domain);break;default:this.range(range).domain(domain);break}return this}function initInterpolator(domain,interpolator){switch(arguments.length){case 0:break;case 1:this.interpolator(domain);break;default:this.interpolator(interpolator).domain(domain);break}return this}var array=Array.prototype;var map=array.map;var slice=array.slice;var implicit={name:"implicit"};function ordinal(){var index=d3Collection.map(),domain=[],range=[],unknown=implicit;function scale(d){var key=d+"",i=index.get(key);if(!i){if(unknown!==implicit)return unknown;index.set(key,i=domain.push(d))}return range[(i-1)%range.length]}scale.domain=function(_){if(!arguments.length)return domain.slice();domain=[],index=d3Collection.map();var i=-1,n=_.length,d,key;while(++ib)t=a,a=b,b=t;return function(x){return Math.max(a,Math.min(b,x))}} -// normalize(a, b)(x) takes a domain value x in [a,b] and returns the corresponding parameter t in [0,1]. -// interpolate(a, b)(t) takes a parameter t in [0,1] and returns the corresponding range value x in [a,b]. -function bimap(domain,range,interpolate){var d0=domain[0],d1=domain[1],r0=range[0],r1=range[1];if(d12?polymap:bimap;output=input=null;return scale}function scale(x){return isNaN(x=+x)?unknown:(output||(output=piecewise(domain.map(transform),range,interpolate)))(transform(clamp(x)))}scale.invert=function(y){return clamp(untransform((input||(input=piecewise(range,domain.map(transform),d3Interpolate.interpolateNumber)))(y)))};scale.domain=function(_){return arguments.length?(domain=map.call(_,number),clamp===identity||(clamp=clamper(domain)),rescale()):domain.slice()};scale.range=function(_){return arguments.length?(range=slice.call(_),rescale()):range.slice()};scale.rangeRound=function(_){return range=slice.call(_),interpolate=d3Interpolate.interpolateRound,rescale()};scale.clamp=function(_){return arguments.length?(clamp=_?clamper(domain):identity,scale):clamp!==identity};scale.interpolate=function(_){return arguments.length?(interpolate=_,rescale()):interpolate};scale.unknown=function(_){return arguments.length?(unknown=_,scale):unknown};return function(t,u){transform=t,untransform=u;return rescale()}}function continuous(transform,untransform){return transformer()(transform,untransform)}function tickFormat(start,stop,count,specifier){var step=d3Array.tickStep(start,stop,count),precision;specifier=d3Format.formatSpecifier(specifier==null?",f":specifier);switch(specifier.type){case"s":{var value=Math.max(Math.abs(start),Math.abs(stop));if(specifier.precision==null&&!isNaN(precision=d3Format.precisionPrefix(step,value)))specifier.precision=precision;return d3Format.formatPrefix(specifier,value)}case"":case"e":case"g":case"p":case"r":{if(specifier.precision==null&&!isNaN(precision=d3Format.precisionRound(step,Math.max(Math.abs(start),Math.abs(stop)))))specifier.precision=precision-(specifier.type==="e");break}case"f":case"%":{if(specifier.precision==null&&!isNaN(precision=d3Format.precisionFixed(step)))specifier.precision=precision-(specifier.type==="%")*2;break}}return d3Format.format(specifier)}function linearish(scale){var domain=scale.domain;scale.ticks=function(count){var d=domain();return d3Array.ticks(d[0],d[d.length-1],count==null?10:count)};scale.tickFormat=function(count,specifier){var d=domain();return tickFormat(d[0],d[d.length-1],count==null?10:count,specifier)};scale.nice=function(count){if(count==null)count=10;var d=domain(),i0=0,i1=d.length-1,start=d[i0],stop=d[i1],step;if(stop0){start=Math.floor(start/step)*step;stop=Math.ceil(stop/step)*step;step=d3Array.tickIncrement(start,stop,count)}else if(step<0){start=Math.ceil(start*step)/step;stop=Math.floor(stop*step)/step;step=d3Array.tickIncrement(start,stop,count)}if(step>0){d[i0]=Math.floor(start/step)*step;d[i1]=Math.ceil(stop/step)*step;domain(d)}else if(step<0){d[i0]=Math.ceil(start*step)/step;d[i1]=Math.floor(stop*step)/step;domain(d)}return scale};return scale}function linear(){var scale=continuous(identity,identity);scale.copy=function(){return copy(scale,linear())};initRange.apply(scale,arguments);return linearish(scale)}function identity$1(domain){var unknown;function scale(x){return isNaN(x=+x)?unknown:x}scale.invert=scale;scale.domain=scale.range=function(_){return arguments.length?(domain=map.call(_,number),scale):domain.slice()};scale.unknown=function(_){return arguments.length?(unknown=_,scale):unknown};scale.copy=function(){return identity$1(domain).unknown(unknown)};domain=arguments.length?map.call(domain,number):[0,1];return linearish(scale)}function nice(domain,interval){domain=domain.slice();var i0=0,i1=domain.length-1,x0=domain[i0],x1=domain[i1],t;if(x10)for(;iv)break;z.push(t)}}else for(;i=1;--k){t=p*k;if(tv)break;z.push(t)}}}else{z=d3Array.ticks(i,j,Math.min(j-i,n)).map(pows)}return r?z.reverse():z};scale.tickFormat=function(count,specifier){if(specifier==null)specifier=base===10?".0e":",";if(typeof specifier!=="function")specifier=d3Format.format(specifier);if(count===Infinity)return specifier;if(count==null)count=10;var k=Math.max(1,base*count/scale.ticks().length);// TODO fast estimate? -return function(d){var i=d/pows(Math.round(logs(d)));if(i*base0?thresholds[i-1]:domain[0],i=n?[domain[n-1],x1]:[domain[i-1],domain[i]]};scale.unknown=function(_){return arguments.length?(unknown=_,scale):scale};scale.thresholds=function(){return domain.slice()};scale.copy=function(){return quantize().domain([x0,x1]).range(range).unknown(unknown)};return initRange.apply(linearish(scale),arguments)}function threshold(){var domain=[.5],range=[0,1],unknown,n=1;function scale(x){return x<=x?range[d3Array.bisect(domain,x,0,n)]:unknown}scale.domain=function(_){return arguments.length?(domain=slice.call(_),n=Math.min(domain.length,range.length-1),scale):domain.slice()};scale.range=function(_){return arguments.length?(range=slice.call(_),n=Math.min(domain.length,range.length-1),scale):range.slice()};scale.invertExtent=function(y){var i=range.indexOf(y);return[domain[i-1],domain[i]]};scale.unknown=function(_){return arguments.length?(unknown=_,scale):unknown};scale.copy=function(){return threshold().domain(domain).range(range).unknown(unknown)};return initRange.apply(scale,arguments)}var durationSecond=1e3,durationMinute=durationSecond*60,durationHour=durationMinute*60,durationDay=durationHour*24,durationWeek=durationDay*7,durationMonth=durationDay*30,durationYear=durationDay*365;function date(t){return new Date(t)}function number$1(t){return t instanceof Date?+t:+new Date(+t)}function calendar(year,month,week,day,hour,minute,second,millisecond,format){var scale=continuous(identity,identity),invert=scale.invert,domain=scale.domain;var formatMillisecond=format(".%L"),formatSecond=format(":%S"),formatMinute=format("%I:%M"),formatHour=format("%I %p"),formatDay=format("%a %d"),formatWeek=format("%b %d"),formatMonth=format("%B"),formatYear=format("%Y");var tickIntervals=[[second,1,durationSecond],[second,5,5*durationSecond],[second,15,15*durationSecond],[second,30,30*durationSecond],[minute,1,durationMinute],[minute,5,5*durationMinute],[minute,15,15*durationMinute],[minute,30,30*durationMinute],[hour,1,durationHour],[hour,3,3*durationHour],[hour,6,6*durationHour],[hour,12,12*durationHour],[day,1,durationDay],[day,2,2*durationDay],[week,1,durationWeek],[month,1,durationMonth],[month,3,3*durationMonth],[year,1,durationYear]];function tickFormat(date){return(second(date)=0&&(prefix=name.slice(0,i))!=="xmlns")name=name.slice(i+1);return namespaces.hasOwnProperty(prefix)?{space:namespaces[prefix],local:name}:name}function creatorInherit(name){return function(){var document=this.ownerDocument,uri=this.namespaceURI;return uri===xhtml&&document.documentElement.namespaceURI===xhtml?document.createElement(name):document.createElementNS(uri,name)}}function creatorFixed(fullname){return function(){return this.ownerDocument.createElementNS(fullname.space,fullname.local)}}function creator(name){var fullname=namespace(name);return(fullname.local?creatorFixed:creatorInherit)(fullname)}function none(){}function selector(selector){return selector==null?none:function(){return this.querySelector(selector)}}function selection_select(select){if(typeof select!=="function")select=selector(select);for(var groups=this._groups,m=groups.length,subgroups=new Array(m),j=0;j=i1)i1=i0+1;while(!(next=updateGroup[i1])&&++i1=0;){if(node=group[i]){if(next&&node.compareDocumentPosition(next)^4)next.parentNode.insertBefore(node,next);next=node}}}return this}function selection_sort(compare){if(!compare)compare=ascending;function compareNode(a,b){return a&&b?compare(a.__data__,b.__data__):!a-!b}for(var groups=this._groups,m=groups.length,sortgroups=new Array(m),j=0;jb?1:a>=b?0:NaN}function selection_call(){var callback=arguments[0];arguments[0]=this;callback.apply(null,arguments);return this}function selection_nodes(){var nodes=new Array(this.size()),i=-1;this.each(function(){nodes[++i]=this});return nodes}function selection_node(){for(var groups=this._groups,j=0,m=groups.length;j1?this.each((value==null?styleRemove:typeof value==="function"?styleFunction:styleConstant)(name,value,priority==null?"":priority)):styleValue(this.node(),name)}function styleValue(node,name){return node.style.getPropertyValue(name)||defaultView(node).getComputedStyle(node,null).getPropertyValue(name)}function propertyRemove(name){return function(){delete this[name]}}function propertyConstant(name,value){return function(){this[name]=value}}function propertyFunction(name,value){return function(){var v=value.apply(this,arguments);if(v==null)delete this[name];else this[name]=v}}function selection_property(name,value){return arguments.length>1?this.each((value==null?propertyRemove:typeof value==="function"?propertyFunction:propertyConstant)(name,value)):this.node()[name]}function classArray(string){return string.trim().split(/^|\s+/)}function classList(node){return node.classList||new ClassList(node)}function ClassList(node){this._node=node;this._names=classArray(node.getAttribute("class")||"")}ClassList.prototype={add:function(name){var i=this._names.indexOf(name);if(i<0){this._names.push(name);this._node.setAttribute("class",this._names.join(" "))}},remove:function(name){var i=this._names.indexOf(name);if(i>=0){this._names.splice(i,1);this._node.setAttribute("class",this._names.join(" "))}},contains:function(name){return this._names.indexOf(name)>=0}};function classedAdd(node,names){var list=classList(node),i=-1,n=names.length;while(++i=0)name=t.slice(i+1),t=t.slice(0,i);return{type:t,name:name}})}function onRemove(typename){return function(){var on=this.__on;if(!on)return;for(var j=0,i=-1,m=on.length,o;j1?0:x<-1?pi:Math.acos(x)}function asin(x){return x>=1?halfPi:x<=-1?-halfPi:Math.asin(x)}function arcInnerRadius(d){return d.innerRadius}function arcOuterRadius(d){return d.outerRadius}function arcStartAngle(d){return d.startAngle}function arcEndAngle(d){return d.endAngle}function arcPadAngle(d){return d&&d.padAngle;// Note: optional! -}function intersect(x0,y0,x1,y1,x2,y2,x3,y3){var x10=x1-x0,y10=y1-y0,x32=x3-x2,y32=y3-y2,t=y32*x10-x32*y10;if(t*tdx1*dx1+dy1*dy1)cx0=cx1,cy0=cy1;return{cx:cx0,cy:cy0,x01:-ox,y01:-oy,x11:cx0*(r1/r-1),y11:cy0*(r1/r-1)}}function arc(){var innerRadius=arcInnerRadius,outerRadius=arcOuterRadius,cornerRadius=constant(0),padRadius=null,startAngle=arcStartAngle,endAngle=arcEndAngle,padAngle=arcPadAngle,context=null;function arc(){var buffer,r,r0=+innerRadius.apply(this,arguments),r1=+outerRadius.apply(this,arguments),a0=startAngle.apply(this,arguments)-halfPi,a1=endAngle.apply(this,arguments)-halfPi,da=abs(a1-a0),cw=a1>a0;if(!context)context=buffer=d3Path.path(); -// Ensure that the outer radius is always larger than the inner radius. -if(r1epsilon))context.moveTo(0,0); -// Or is it a circle or annulus? -else if(da>tau-epsilon){context.moveTo(r1*cos(a0),r1*sin(a0));context.arc(0,0,r1,a0,a1,!cw);if(r0>epsilon){context.moveTo(r0*cos(a1),r0*sin(a1));context.arc(0,0,r0,a1,a0,cw)}} -// Or is it a circular or annular sector? -else{var a01=a0,a11=a1,a00=a0,a10=a1,da0=da,da1=da,ap=padAngle.apply(this,arguments)/2,rp=ap>epsilon&&(padRadius?+padRadius.apply(this,arguments):sqrt(r0*r0+r1*r1)),rc=min(abs(r1-r0)/2,+cornerRadius.apply(this,arguments)),rc0=rc,rc1=rc,t0,t1; -// Apply padding? Note that since r1 ≥ r0, da1 ≥ da0. -if(rp>epsilon){var p0=asin(rp/r0*sin(ap)),p1=asin(rp/r1*sin(ap));if((da0-=p0*2)>epsilon)p0*=cw?1:-1,a00+=p0,a10-=p0;else da0=0,a00=a10=(a0+a1)/2;if((da1-=p1*2)>epsilon)p1*=cw?1:-1,a01+=p1,a11-=p1;else da1=0,a01=a11=(a0+a1)/2}var x01=r1*cos(a01),y01=r1*sin(a01),x10=r0*cos(a10),y10=r0*sin(a10); -// Apply rounded corners? -if(rc>epsilon){var x11=r1*cos(a11),y11=r1*sin(a11),x00=r0*cos(a00),y00=r0*sin(a00),oc; -// Restrict the corner radius according to the sector angle. -if(daepsilon))context.moveTo(x01,y01); -// Does the sector’s outer ring have rounded corners? -else if(rc1>epsilon){t0=cornerTangents(x00,y00,x01,y01,r1,rc1,cw);t1=cornerTangents(x11,y11,x10,y10,r1,rc1,cw);context.moveTo(t0.cx+t0.x01,t0.cy+t0.y01); -// Have the corners merged? -if(rc1epsilon)||!(da0>epsilon))context.lineTo(x10,y10); -// Does the sector’s inner ring (or point) have rounded corners? -else if(rc0>epsilon){t0=cornerTangents(x10,y10,x11,y11,r0,-rc0,cw);t1=cornerTangents(x01,y01,x00,y00,r0,-rc0,cw);context.lineTo(t0.cx+t0.x01,t0.cy+t0.y01); -// Have the corners merged? -if(rc0=j;--k){output.point(x0z[k],y0z[k])}output.lineEnd();output.areaEnd()}}if(defined0){x0z[i]=+x0(d,i,data),y0z[i]=+y0(d,i,data);output.point(x1?+x1(d,i,data):x0z[i],y1?+y1(d,i,data):y0z[i])}}if(buffer)return output=null,buffer+""||null}function arealine(){return line().defined(defined).curve(curve).context(context)}area.x=function(_){return arguments.length?(x0=typeof _==="function"?_:constant(+_),x1=null,area):x0};area.x0=function(_){return arguments.length?(x0=typeof _==="function"?_:constant(+_),area):x0};area.x1=function(_){return arguments.length?(x1=_==null?null:typeof _==="function"?_:constant(+_),area):x1};area.y=function(_){return arguments.length?(y0=typeof _==="function"?_:constant(+_),y1=null,area):y0};area.y0=function(_){return arguments.length?(y0=typeof _==="function"?_:constant(+_),area):y0};area.y1=function(_){return arguments.length?(y1=_==null?null:typeof _==="function"?_:constant(+_),area):y1};area.lineX0=area.lineY0=function(){return arealine().x(x0).y(y0)};area.lineY1=function(){return arealine().x(x0).y(y1)};area.lineX1=function(){return arealine().x(x1).y(y0)};area.defined=function(_){return arguments.length?(defined=typeof _==="function"?_:constant(!!_),area):defined};area.curve=function(_){return arguments.length?(curve=_,context!=null&&(output=curve(context)),area):curve};area.context=function(_){return arguments.length?(_==null?context=output=null:output=curve(context=_),area):context};return area}function descending(a,b){return ba?1:b>=a?0:NaN}function identity(d){return d}function pie(){var value=identity,sortValues=descending,sort=null,startAngle=constant(0),endAngle=constant(tau),padAngle=constant(0);function pie(data){var i,n=data.length,j,k,sum=0,index=new Array(n),arcs=new Array(n),a0=+startAngle.apply(this,arguments),da=Math.min(tau,Math.max(-tau,endAngle.apply(this,arguments)-a0)),a1,p=Math.min(Math.abs(da)/n,padAngle.apply(this,arguments)),pa=p*(da<0?-1:1),v;for(i=0;i0){sum+=v}} -// Optionally sort the arcs by previously-computed values or by data. -if(sortValues!=null)index.sort(function(i,j){return sortValues(arcs[i],arcs[j])});else if(sort!=null)index.sort(function(i,j){return sort(data[i],data[j])}); -// Compute the arcs! They are stored in the original data's order. -for(i=0,k=sum?(da-n*pa)/sum:0;i0?v*k:0)+pa,arcs[j]={data:data[j],index:i,value:v,startAngle:a0,endAngle:a1,padAngle:p}}return arcs}pie.value=function(_){return arguments.length?(value=typeof _==="function"?_:constant(+_),pie):value};pie.sortValues=function(_){return arguments.length?(sortValues=_,sort=null,pie):sortValues};pie.sort=function(_){return arguments.length?(sort=_,sortValues=null,pie):sort};pie.startAngle=function(_){return arguments.length?(startAngle=typeof _==="function"?_:constant(+_),pie):startAngle};pie.endAngle=function(_){return arguments.length?(endAngle=typeof _==="function"?_:constant(+_),pie):endAngle};pie.padAngle=function(_){return arguments.length?(padAngle=typeof _==="function"?_:constant(+_),pie):padAngle};return pie}var curveRadialLinear=curveRadial(curveLinear);function Radial(curve){this._curve=curve}Radial.prototype={areaStart:function(){this._curve.areaStart()},areaEnd:function(){this._curve.areaEnd()},lineStart:function(){this._curve.lineStart()},lineEnd:function(){this._curve.lineEnd()},point:function(a,r){this._curve.point(r*Math.sin(a),r*-Math.cos(a))}};function curveRadial(curve){function radial(context){return new Radial(curve(context))}radial._curve=curve;return radial}function lineRadial(l){var c=l.curve;l.angle=l.x,delete l.x;l.radius=l.y,delete l.y;l.curve=function(_){return arguments.length?c(curveRadial(_)):c()._curve};return l}function lineRadial$1(){return lineRadial(line().curve(curveRadialLinear))}function areaRadial(){var a=area().curve(curveRadialLinear),c=a.curve,x0=a.lineX0,x1=a.lineX1,y0=a.lineY0,y1=a.lineY1;a.angle=a.x,delete a.x;a.startAngle=a.x0,delete a.x0;a.endAngle=a.x1,delete a.x1;a.radius=a.y,delete a.y;a.innerRadius=a.y0,delete a.y0;a.outerRadius=a.y1,delete a.y1;a.lineStartAngle=function(){return lineRadial(x0())},delete a.lineX0;a.lineEndAngle=function(){return lineRadial(x1())},delete a.lineX1;a.lineInnerRadius=function(){return lineRadial(y0())},delete a.lineY0;a.lineOuterRadius=function(){return lineRadial(y1())},delete a.lineY1;a.curve=function(_){return arguments.length?c(curveRadial(_)):c()._curve};return a}function pointRadial(x,y){return[(y=+y)*Math.cos(x-=Math.PI/2),y*Math.sin(x)]}var slice=Array.prototype.slice;function linkSource(d){return d.source}function linkTarget(d){return d.target}function link(curve){var source=linkSource,target=linkTarget,x$1=x,y$1=y,context=null;function link(){var buffer,argv=slice.call(arguments),s=source.apply(this,argv),t=target.apply(this,argv);if(!context)context=buffer=d3Path.path();curve(context,+x$1.apply(this,(argv[0]=s,argv)),+y$1.apply(this,argv),+x$1.apply(this,(argv[0]=t,argv)),+y$1.apply(this,argv));if(buffer)return context=null,buffer+""||null}link.source=function(_){return arguments.length?(source=_,link):source};link.target=function(_){return arguments.length?(target=_,link):target};link.x=function(_){return arguments.length?(x$1=typeof _==="function"?_:constant(+_),link):x$1};link.y=function(_){return arguments.length?(y$1=typeof _==="function"?_:constant(+_),link):y$1};link.context=function(_){return arguments.length?(context=_==null?null:_,link):context};return link}function curveHorizontal(context,x0,y0,x1,y1){context.moveTo(x0,y0);context.bezierCurveTo(x0=(x0+x1)/2,y0,x0,y1,x1,y1)}function curveVertical(context,x0,y0,x1,y1){context.moveTo(x0,y0);context.bezierCurveTo(x0,y0=(y0+y1)/2,x1,y0,x1,y1)}function curveRadial$1(context,x0,y0,x1,y1){var p0=pointRadial(x0,y0),p1=pointRadial(x0,y0=(y0+y1)/2),p2=pointRadial(x1,y0),p3=pointRadial(x1,y1);context.moveTo(p0[0],p0[1]);context.bezierCurveTo(p1[0],p1[1],p2[0],p2[1],p3[0],p3[1])}function linkHorizontal(){return link(curveHorizontal)}function linkVertical(){return link(curveVertical)}function linkRadial(){var l=link(curveRadial$1);l.angle=l.x,delete l.x;l.radius=l.y,delete l.y;return l}var circle={draw:function(context,size){var r=Math.sqrt(size/pi);context.moveTo(r,0);context.arc(0,0,r,0,tau)}};var cross={draw:function(context,size){var r=Math.sqrt(size/5)/2;context.moveTo(-3*r,-r);context.lineTo(-r,-r);context.lineTo(-r,-3*r);context.lineTo(r,-3*r);context.lineTo(r,-r);context.lineTo(3*r,-r);context.lineTo(3*r,r);context.lineTo(r,r);context.lineTo(r,3*r);context.lineTo(-r,3*r);context.lineTo(-r,r);context.lineTo(-3*r,r);context.closePath()}};var tan30=Math.sqrt(1/3),tan30_2=tan30*2;var diamond={draw:function(context,size){var y=Math.sqrt(size/tan30_2),x=y*tan30;context.moveTo(0,-y);context.lineTo(x,0);context.lineTo(0,y);context.lineTo(-x,0);context.closePath()}};var ka=.8908130915292852,kr=Math.sin(pi/10)/Math.sin(7*pi/10),kx=Math.sin(tau/10)*kr,ky=-Math.cos(tau/10)*kr;var star={draw:function(context,size){var r=Math.sqrt(size*ka),x=kx*r,y=ky*r;context.moveTo(0,-r);context.lineTo(x,y);for(var i=1;i<5;++i){var a=tau*i/5,c=Math.cos(a),s=Math.sin(a);context.lineTo(s*r,-c*r);context.lineTo(c*x-s*y,s*x+c*y)}context.closePath()}};var square={draw:function(context,size){var w=Math.sqrt(size),x=-w/2;context.rect(x,x,w,w)}};var sqrt3=Math.sqrt(3);var triangle={draw:function(context,size){var y=-Math.sqrt(size/(sqrt3*3));context.moveTo(0,y*2);context.lineTo(-sqrt3*y,-y);context.lineTo(sqrt3*y,-y);context.closePath()}};var c=-.5,s=Math.sqrt(3)/2,k=1/Math.sqrt(12),a=(k/2+1)*3;var wye={draw:function(context,size){var r=Math.sqrt(size/a),x0=r/2,y0=r*k,x1=x0,y1=r*k+r,x2=-x1,y2=y1;context.moveTo(x0,y0);context.lineTo(x1,y1);context.lineTo(x2,y2);context.lineTo(c*x0-s*y0,s*x0+c*y0);context.lineTo(c*x1-s*y1,s*x1+c*y1);context.lineTo(c*x2-s*y2,s*x2+c*y2);context.lineTo(c*x0+s*y0,c*y0-s*x0);context.lineTo(c*x1+s*y1,c*y1-s*x1);context.lineTo(c*x2+s*y2,c*y2-s*x2);context.closePath()}};var symbols=[circle,cross,diamond,square,star,triangle,wye];function symbol(){var type=constant(circle),size=constant(64),context=null;function symbol(){var buffer;if(!context)context=buffer=d3Path.path();type.apply(this,arguments).draw(context,+size.apply(this,arguments));if(buffer)return context=null,buffer+""||null}symbol.type=function(_){return arguments.length?(type=typeof _==="function"?_:constant(_),symbol):type};symbol.size=function(_){return arguments.length?(size=typeof _==="function"?_:constant(+_),symbol):size};symbol.context=function(_){return arguments.length?(context=_==null?null:_,symbol):context};return symbol}function noop(){}function point(that,x,y){that._context.bezierCurveTo((2*that._x0+that._x1)/3,(2*that._y0+that._y1)/3,(that._x0+2*that._x1)/3,(that._y0+2*that._y1)/3,(that._x0+4*that._x1+x)/6,(that._y0+4*that._y1+y)/6)}function Basis(context){this._context=context}Basis.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN;this._point=0},lineEnd:function(){switch(this._point){case 3:point(this,this._x1,this._y1);// proceed -case 2:this._context.lineTo(this._x1,this._y1);break}if(this._line||this._line!==0&&this._point===1)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;this._line?this._context.lineTo(x,y):this._context.moveTo(x,y);break;case 1:this._point=2;break;case 2:this._point=3;this._context.lineTo((5*this._x0+this._x1)/6,(5*this._y0+this._y1)/6);// proceed -default:point(this,x,y);break}this._x0=this._x1,this._x1=x;this._y0=this._y1,this._y1=y}};function basis(context){return new Basis(context)}function BasisClosed(context){this._context=context}BasisClosed.prototype={areaStart:noop,areaEnd:noop,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._y0=this._y1=this._y2=this._y3=this._y4=NaN;this._point=0},lineEnd:function(){switch(this._point){case 1:{this._context.moveTo(this._x2,this._y2);this._context.closePath();break}case 2:{this._context.moveTo((this._x2+2*this._x3)/3,(this._y2+2*this._y3)/3);this._context.lineTo((this._x3+2*this._x2)/3,(this._y3+2*this._y2)/3);this._context.closePath();break}case 3:{this.point(this._x2,this._y2);this.point(this._x3,this._y3);this.point(this._x4,this._y4);break}}},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;this._x2=x,this._y2=y;break;case 1:this._point=2;this._x3=x,this._y3=y;break;case 2:this._point=3;this._x4=x,this._y4=y;this._context.moveTo((this._x0+4*this._x1+x)/6,(this._y0+4*this._y1+y)/6);break;default:point(this,x,y);break}this._x0=this._x1,this._x1=x;this._y0=this._y1,this._y1=y}};function basisClosed(context){return new BasisClosed(context)}function BasisOpen(context){this._context=context}BasisOpen.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=NaN;this._point=0},lineEnd:function(){if(this._line||this._line!==0&&this._point===3)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3;var x0=(this._x0+4*this._x1+x)/6,y0=(this._y0+4*this._y1+y)/6;this._line?this._context.lineTo(x0,y0):this._context.moveTo(x0,y0);break;case 3:this._point=4;// proceed -default:point(this,x,y);break}this._x0=this._x1,this._x1=x;this._y0=this._y1,this._y1=y}};function basisOpen(context){return new BasisOpen(context)}function Bundle(context,beta){this._basis=new Basis(context);this._beta=beta}Bundle.prototype={lineStart:function(){this._x=[];this._y=[];this._basis.lineStart()},lineEnd:function(){var x=this._x,y=this._y,j=x.length-1;if(j>0){var x0=x[0],y0=y[0],dx=x[j]-x0,dy=y[j]-y0,i=-1,t;while(++i<=j){t=i/j;this._basis.point(this._beta*x[i]+(1-this._beta)*(x0+t*dx),this._beta*y[i]+(1-this._beta)*(y0+t*dy))}}this._x=this._y=null;this._basis.lineEnd()},point:function(x,y){this._x.push(+x);this._y.push(+y)}};var bundle=function custom(beta){function bundle(context){return beta===1?new Basis(context):new Bundle(context,beta)}bundle.beta=function(beta){return custom(+beta)};return bundle}(.85);function point$1(that,x,y){that._context.bezierCurveTo(that._x1+that._k*(that._x2-that._x0),that._y1+that._k*(that._y2-that._y0),that._x2+that._k*(that._x1-x),that._y2+that._k*(that._y1-y),that._x2,that._y2)}function Cardinal(context,tension){this._context=context;this._k=(1-tension)/6}Cardinal.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN;this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:point$1(this,this._x1,this._y1);break}if(this._line||this._line!==0&&this._point===1)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;this._line?this._context.lineTo(x,y):this._context.moveTo(x,y);break;case 1:this._point=2;this._x1=x,this._y1=y;break;case 2:this._point=3;// proceed -default:point$1(this,x,y);break}this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var cardinal=function custom(tension){function cardinal(context){return new Cardinal(context,tension)}cardinal.tension=function(tension){return custom(+tension)};return cardinal}(0);function CardinalClosed(context,tension){this._context=context;this._k=(1-tension)/6}CardinalClosed.prototype={areaStart:noop,areaEnd:noop,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN;this._point=0},lineEnd:function(){switch(this._point){case 1:{this._context.moveTo(this._x3,this._y3);this._context.closePath();break}case 2:{this._context.lineTo(this._x3,this._y3);this._context.closePath();break}case 3:{this.point(this._x3,this._y3);this.point(this._x4,this._y4);this.point(this._x5,this._y5);break}}},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;this._x3=x,this._y3=y;break;case 1:this._point=2;this._context.moveTo(this._x4=x,this._y4=y);break;case 2:this._point=3;this._x5=x,this._y5=y;break;default:point$1(this,x,y);break}this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var cardinalClosed=function custom(tension){function cardinal(context){return new CardinalClosed(context,tension)}cardinal.tension=function(tension){return custom(+tension)};return cardinal}(0);function CardinalOpen(context,tension){this._context=context;this._k=(1-tension)/6}CardinalOpen.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN;this._point=0},lineEnd:function(){if(this._line||this._line!==0&&this._point===3)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3;this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;// proceed -default:point$1(this,x,y);break}this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var cardinalOpen=function custom(tension){function cardinal(context){return new CardinalOpen(context,tension)}cardinal.tension=function(tension){return custom(+tension)};return cardinal}(0);function point$2(that,x,y){var x1=that._x1,y1=that._y1,x2=that._x2,y2=that._y2;if(that._l01_a>epsilon){var a=2*that._l01_2a+3*that._l01_a*that._l12_a+that._l12_2a,n=3*that._l01_a*(that._l01_a+that._l12_a);x1=(x1*a-that._x0*that._l12_2a+that._x2*that._l01_2a)/n;y1=(y1*a-that._y0*that._l12_2a+that._y2*that._l01_2a)/n}if(that._l23_a>epsilon){var b=2*that._l23_2a+3*that._l23_a*that._l12_a+that._l12_2a,m=3*that._l23_a*(that._l23_a+that._l12_a);x2=(x2*b+that._x1*that._l23_2a-x*that._l12_2a)/m;y2=(y2*b+that._y1*that._l23_2a-y*that._l12_2a)/m}that._context.bezierCurveTo(x1,y1,x2,y2,that._x2,that._y2)}function CatmullRom(context,alpha){this._context=context;this._alpha=alpha}CatmullRom.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN;this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x2,this._y2);break;case 3:this.point(this._x2,this._y2);break}if(this._line||this._line!==0&&this._point===1)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;if(this._point){var x23=this._x2-x,y23=this._y2-y;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(x23*x23+y23*y23,this._alpha))}switch(this._point){case 0:this._point=1;this._line?this._context.lineTo(x,y):this._context.moveTo(x,y);break;case 1:this._point=2;break;case 2:this._point=3;// proceed -default:point$2(this,x,y);break}this._l01_a=this._l12_a,this._l12_a=this._l23_a;this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a;this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var catmullRom=function custom(alpha){function catmullRom(context){return alpha?new CatmullRom(context,alpha):new Cardinal(context,0)}catmullRom.alpha=function(alpha){return custom(+alpha)};return catmullRom}(.5);function CatmullRomClosed(context,alpha){this._context=context;this._alpha=alpha}CatmullRomClosed.prototype={areaStart:noop,areaEnd:noop,lineStart:function(){this._x0=this._x1=this._x2=this._x3=this._x4=this._x5=this._y0=this._y1=this._y2=this._y3=this._y4=this._y5=NaN;this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){switch(this._point){case 1:{this._context.moveTo(this._x3,this._y3);this._context.closePath();break}case 2:{this._context.lineTo(this._x3,this._y3);this._context.closePath();break}case 3:{this.point(this._x3,this._y3);this.point(this._x4,this._y4);this.point(this._x5,this._y5);break}}},point:function(x,y){x=+x,y=+y;if(this._point){var x23=this._x2-x,y23=this._y2-y;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(x23*x23+y23*y23,this._alpha))}switch(this._point){case 0:this._point=1;this._x3=x,this._y3=y;break;case 1:this._point=2;this._context.moveTo(this._x4=x,this._y4=y);break;case 2:this._point=3;this._x5=x,this._y5=y;break;default:point$2(this,x,y);break}this._l01_a=this._l12_a,this._l12_a=this._l23_a;this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a;this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var catmullRomClosed=function custom(alpha){function catmullRom(context){return alpha?new CatmullRomClosed(context,alpha):new CardinalClosed(context,0)}catmullRom.alpha=function(alpha){return custom(+alpha)};return catmullRom}(.5);function CatmullRomOpen(context,alpha){this._context=context;this._alpha=alpha}CatmullRomOpen.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._x2=this._y0=this._y1=this._y2=NaN;this._l01_a=this._l12_a=this._l23_a=this._l01_2a=this._l12_2a=this._l23_2a=this._point=0},lineEnd:function(){if(this._line||this._line!==0&&this._point===3)this._context.closePath();this._line=1-this._line},point:function(x,y){x=+x,y=+y;if(this._point){var x23=this._x2-x,y23=this._y2-y;this._l23_a=Math.sqrt(this._l23_2a=Math.pow(x23*x23+y23*y23,this._alpha))}switch(this._point){case 0:this._point=1;break;case 1:this._point=2;break;case 2:this._point=3;this._line?this._context.lineTo(this._x2,this._y2):this._context.moveTo(this._x2,this._y2);break;case 3:this._point=4;// proceed -default:point$2(this,x,y);break}this._l01_a=this._l12_a,this._l12_a=this._l23_a;this._l01_2a=this._l12_2a,this._l12_2a=this._l23_2a;this._x0=this._x1,this._x1=this._x2,this._x2=x;this._y0=this._y1,this._y1=this._y2,this._y2=y}};var catmullRomOpen=function custom(alpha){function catmullRom(context){return alpha?new CatmullRomOpen(context,alpha):new CardinalOpen(context,0)}catmullRom.alpha=function(alpha){return custom(+alpha)};return catmullRom}(.5);function LinearClosed(context){this._context=context}LinearClosed.prototype={areaStart:noop,areaEnd:noop,lineStart:function(){this._point=0},lineEnd:function(){if(this._point)this._context.closePath()},point:function(x,y){x=+x,y=+y;if(this._point)this._context.lineTo(x,y);else this._point=1,this._context.moveTo(x,y)}};function linearClosed(context){return new LinearClosed(context)}function sign(x){return x<0?-1:1} -// Calculate the slopes of the tangents (Hermite-type interpolation) based on -// the following paper: Steffen, M. 1990. A Simple Method for Monotonic -// Interpolation in One Dimension. Astronomy and Astrophysics, Vol. 239, NO. -// NOV(II), P. 443, 1990. -function slope3(that,x2,y2){var h0=that._x1-that._x0,h1=x2-that._x1,s0=(that._y1-that._y0)/(h0||h1<0&&-0),s1=(y2-that._y1)/(h1||h0<0&&-0),p=(s0*h1+s1*h0)/(h0+h1);return(sign(s0)+sign(s1))*Math.min(Math.abs(s0),Math.abs(s1),.5*Math.abs(p))||0} -// Calculate a one-sided slope. -function slope2(that,t){var h=that._x1-that._x0;return h?(3*(that._y1-that._y0)/h-t)/2:t} -// According to https://en.wikipedia.org/wiki/Cubic_Hermite_spline#Representations -// "you can express cubic Hermite interpolation in terms of cubic Bézier curves -// with respect to the four values p0, p0 + m0 / 3, p1 - m1 / 3, p1". -function point$3(that,t0,t1){var x0=that._x0,y0=that._y0,x1=that._x1,y1=that._y1,dx=(x1-x0)/3;that._context.bezierCurveTo(x0+dx,y0+dx*t0,x1-dx,y1-dx*t1,x1,y1)}function MonotoneX(context){this._context=context}MonotoneX.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x0=this._x1=this._y0=this._y1=this._t0=NaN;this._point=0},lineEnd:function(){switch(this._point){case 2:this._context.lineTo(this._x1,this._y1);break;case 3:point$3(this,this._t0,slope2(this,this._t0));break}if(this._line||this._line!==0&&this._point===1)this._context.closePath();this._line=1-this._line},point:function(x,y){var t1=NaN;x=+x,y=+y;if(x===this._x1&&y===this._y1)return;// Ignore coincident points. -switch(this._point){case 0:this._point=1;this._line?this._context.lineTo(x,y):this._context.moveTo(x,y);break;case 1:this._point=2;break;case 2:this._point=3;point$3(this,slope2(this,t1=slope3(this,x,y)),t1);break;default:point$3(this,this._t0,t1=slope3(this,x,y));break}this._x0=this._x1,this._x1=x;this._y0=this._y1,this._y1=y;this._t0=t1}};function MonotoneY(context){this._context=new ReflectContext(context)}(MonotoneY.prototype=Object.create(MonotoneX.prototype)).point=function(x,y){MonotoneX.prototype.point.call(this,y,x)};function ReflectContext(context){this._context=context}ReflectContext.prototype={moveTo:function(x,y){this._context.moveTo(y,x)},closePath:function(){this._context.closePath()},lineTo:function(x,y){this._context.lineTo(y,x)},bezierCurveTo:function(x1,y1,x2,y2,x,y){this._context.bezierCurveTo(y1,x1,y2,x2,y,x)}};function monotoneX(context){return new MonotoneX(context)}function monotoneY(context){return new MonotoneY(context)}function Natural(context){this._context=context}Natural.prototype={areaStart:function(){this._line=0},areaEnd:function(){this._line=NaN},lineStart:function(){this._x=[];this._y=[]},lineEnd:function(){var x=this._x,y=this._y,n=x.length;if(n){this._line?this._context.lineTo(x[0],y[0]):this._context.moveTo(x[0],y[0]);if(n===2){this._context.lineTo(x[1],y[1])}else{var px=controlPoints(x),py=controlPoints(y);for(var i0=0,i1=1;i1=0;--i)a[i]=(r[i]-a[i+1])/b[i];b[n-1]=(x[n]+a[n-1])/2;for(i=0;i=0)this._t=1-this._t,this._line=1-this._line},point:function(x,y){x=+x,y=+y;switch(this._point){case 0:this._point=1;this._line?this._context.lineTo(x,y):this._context.moveTo(x,y);break;case 1:this._point=2;// proceed -default:{if(this._t<=0){this._context.lineTo(this._x,y);this._context.lineTo(x,y)}else{var x1=this._x*(1-this._t)+x*this._t;this._context.lineTo(x1,this._y);this._context.lineTo(x1,y)}break}}this._x=x,this._y=y}};function step(context){return new Step(context,.5)}function stepBefore(context){return new Step(context,0)}function stepAfter(context){return new Step(context,1)}function none(series,order){if(!((n=series.length)>1))return;for(var i=1,j,s0,s1=series[order[0]],n,m=s1.length;i=0)o[n]=n;return o}function stackValue(d,key){return d[key]}function stack(){var keys=constant([]),order=none$1,offset=none,value=stackValue;function stack(data){var kz=keys.apply(this,arguments),i,m=data.length,n=kz.length,sz=new Array(n),oz;for(i=0;i0))return;for(var i,n,j=0,m=series[0].length,y;j0))return;for(var i,j=0,d,dy,yp,yn,n,m=series[order[0]].length;j0){d[0]=yp,d[1]=yp+=dy}else if(dy<0){d[1]=yn,d[0]=yn+=dy}else{d[0]=0,d[1]=dy}}}}function silhouette(series,order){if(!((n=series.length)>0))return;for(var j=0,s0=series[order[0]],n,m=s0.length;j0)||!((m=(s0=series[order[0]]).length)>0))return;for(var y=0,j=1,s0,m,n;jvj)vj=vi,j=i;return j}function ascending(series){var sums=series.map(sum);return none$1(series).sort(function(a,b){return sums[a]-sums[b]})}function sum(series){var s=0,i=-1,n=series.length,v;while(++i53)return null;if(!("w"in d))d.w=1;if("Z"in d){week=utcDate(newDate(d.y,0,1)),day=week.getUTCDay();week=day>4||day===0?d3Time.utcMonday.ceil(week):d3Time.utcMonday(week);week=d3Time.utcDay.offset(week,(d.V-1)*7);d.y=week.getUTCFullYear();d.m=week.getUTCMonth();d.d=week.getUTCDate()+(d.w+6)%7}else{week=localDate(newDate(d.y,0,1)),day=week.getDay();week=day>4||day===0?d3Time.timeMonday.ceil(week):d3Time.timeMonday(week);week=d3Time.timeDay.offset(week,(d.V-1)*7);d.y=week.getFullYear();d.m=week.getMonth();d.d=week.getDate()+(d.w+6)%7}}else if("W"in d||"U"in d){if(!("w"in d))d.w="u"in d?d.u%7:"W"in d?1:0;day="Z"in d?utcDate(newDate(d.y,0,1)).getUTCDay():localDate(newDate(d.y,0,1)).getDay();d.m=0;d.d="W"in d?(d.w+6)%7+d.W*7-(day+5)%7:d.w+d.U*7-(day+6)%7} -// If a time zone is specified, all fields are interpreted as UTC and then -// offset according to the specified time zone. -if("Z"in d){d.H+=d.Z/100|0;d.M+=d.Z%100;return utcDate(d)} -// Otherwise, all fields are in local time. -return localDate(d)}}function parseSpecifier(d,specifier,string,j){var i=0,n=specifier.length,m=string.length,c,parse;while(i=m)return-1;c=specifier.charCodeAt(i++);if(c===37){c=specifier.charAt(i++);parse=parses[c in pads?specifier.charAt(i++):c];if(!parse||(j=parse(d,string,j))<0)return-1}else if(c!=string.charCodeAt(j++)){return-1}}return j}function parsePeriod(d,string,i){var n=periodRe.exec(string.slice(i));return n?(d.p=periodLookup[n[0].toLowerCase()],i+n[0].length):-1}function parseShortWeekday(d,string,i){var n=shortWeekdayRe.exec(string.slice(i));return n?(d.w=shortWeekdayLookup[n[0].toLowerCase()],i+n[0].length):-1}function parseWeekday(d,string,i){var n=weekdayRe.exec(string.slice(i));return n?(d.w=weekdayLookup[n[0].toLowerCase()],i+n[0].length):-1}function parseShortMonth(d,string,i){var n=shortMonthRe.exec(string.slice(i));return n?(d.m=shortMonthLookup[n[0].toLowerCase()],i+n[0].length):-1}function parseMonth(d,string,i){var n=monthRe.exec(string.slice(i));return n?(d.m=monthLookup[n[0].toLowerCase()],i+n[0].length):-1}function parseLocaleDateTime(d,string,i){return parseSpecifier(d,locale_dateTime,string,i)}function parseLocaleDate(d,string,i){return parseSpecifier(d,locale_date,string,i)}function parseLocaleTime(d,string,i){return parseSpecifier(d,locale_time,string,i)}function formatShortWeekday(d){return locale_shortWeekdays[d.getDay()]}function formatWeekday(d){return locale_weekdays[d.getDay()]}function formatShortMonth(d){return locale_shortMonths[d.getMonth()]}function formatMonth(d){return locale_months[d.getMonth()]}function formatPeriod(d){return locale_periods[+(d.getHours()>=12)]}function formatQuarter(d){return 1+~~(d.getMonth()/3)}function formatUTCShortWeekday(d){return locale_shortWeekdays[d.getUTCDay()]}function formatUTCWeekday(d){return locale_weekdays[d.getUTCDay()]}function formatUTCShortMonth(d){return locale_shortMonths[d.getUTCMonth()]}function formatUTCMonth(d){return locale_months[d.getUTCMonth()]}function formatUTCPeriod(d){return locale_periods[+(d.getUTCHours()>=12)]}function formatUTCQuarter(d){return 1+~~(d.getUTCMonth()/3)}return{format:function(specifier){var f=newFormat(specifier+="",formats);f.toString=function(){return specifier};return f},parse:function(specifier){var p=newParse(specifier+="",false);p.toString=function(){return specifier};return p},utcFormat:function(specifier){var f=newFormat(specifier+="",utcFormats);f.toString=function(){return specifier};return f},utcParse:function(specifier){var p=newParse(specifier+="",true);p.toString=function(){return specifier};return p}}}var pads={"-":"",_:" ",0:"0"},numberRe=/^\s*\d+/,// note: ignores next directive -percentRe=/^%/,requoteRe=/[\\^$*+?|[\]().{}]/g;function pad(value,fill,width){var sign=value<0?"-":"",string=(sign?-value:value)+"",length=string.length;return sign+(length68?1900:2e3),i+n[0].length):-1}function parseZone(d,string,i){var n=/^(Z)|([+-]\d\d)(?::?(\d\d))?/.exec(string.slice(i,i+6));return n?(d.Z=n[1]?0:-(n[2]+(n[3]||"00")),i+n[0].length):-1}function parseQuarter(d,string,i){var n=numberRe.exec(string.slice(i,i+1));return n?(d.q=n[0]*3-3,i+n[0].length):-1}function parseMonthNumber(d,string,i){var n=numberRe.exec(string.slice(i,i+2));return n?(d.m=n[0]-1,i+n[0].length):-1}function parseDayOfMonth(d,string,i){var n=numberRe.exec(string.slice(i,i+2));return n?(d.d=+n[0],i+n[0].length):-1}function parseDayOfYear(d,string,i){var n=numberRe.exec(string.slice(i,i+3));return n?(d.m=0,d.d=+n[0],i+n[0].length):-1}function parseHour24(d,string,i){var n=numberRe.exec(string.slice(i,i+2));return n?(d.H=+n[0],i+n[0].length):-1}function parseMinutes(d,string,i){var n=numberRe.exec(string.slice(i,i+2));return n?(d.M=+n[0],i+n[0].length):-1}function parseSeconds(d,string,i){var n=numberRe.exec(string.slice(i,i+2));return n?(d.S=+n[0],i+n[0].length):-1}function parseMilliseconds(d,string,i){var n=numberRe.exec(string.slice(i,i+3));return n?(d.L=+n[0],i+n[0].length):-1}function parseMicroseconds(d,string,i){var n=numberRe.exec(string.slice(i,i+6));return n?(d.L=Math.floor(n[0]/1e3),i+n[0].length):-1}function parseLiteralPercent(d,string,i){var n=percentRe.exec(string.slice(i,i+1));return n?i+n[0].length:-1}function parseUnixTimestamp(d,string,i){var n=numberRe.exec(string.slice(i));return n?(d.Q=+n[0],i+n[0].length):-1}function parseUnixTimestampSeconds(d,string,i){var n=numberRe.exec(string.slice(i));return n?(d.s=+n[0],i+n[0].length):-1}function formatDayOfMonth(d,p){return pad(d.getDate(),p,2)}function formatHour24(d,p){return pad(d.getHours(),p,2)}function formatHour12(d,p){return pad(d.getHours()%12||12,p,2)}function formatDayOfYear(d,p){return pad(1+d3Time.timeDay.count(d3Time.timeYear(d),d),p,3)}function formatMilliseconds(d,p){return pad(d.getMilliseconds(),p,3)}function formatMicroseconds(d,p){return formatMilliseconds(d,p)+"000"}function formatMonthNumber(d,p){return pad(d.getMonth()+1,p,2)}function formatMinutes(d,p){return pad(d.getMinutes(),p,2)}function formatSeconds(d,p){return pad(d.getSeconds(),p,2)}function formatWeekdayNumberMonday(d){var day=d.getDay();return day===0?7:day}function formatWeekNumberSunday(d,p){return pad(d3Time.timeSunday.count(d3Time.timeYear(d)-1,d),p,2)}function formatWeekNumberISO(d,p){var day=d.getDay();d=day>=4||day===0?d3Time.timeThursday(d):d3Time.timeThursday.ceil(d);return pad(d3Time.timeThursday.count(d3Time.timeYear(d),d)+(d3Time.timeYear(d).getDay()===4),p,2)}function formatWeekdayNumberSunday(d){return d.getDay()}function formatWeekNumberMonday(d,p){return pad(d3Time.timeMonday.count(d3Time.timeYear(d)-1,d),p,2)}function formatYear(d,p){return pad(d.getFullYear()%100,p,2)}function formatFullYear(d,p){return pad(d.getFullYear()%1e4,p,4)}function formatZone(d){var z=d.getTimezoneOffset();return(z>0?"-":(z*=-1,"+"))+pad(z/60|0,"0",2)+pad(z%60,"0",2)}function formatUTCDayOfMonth(d,p){return pad(d.getUTCDate(),p,2)}function formatUTCHour24(d,p){return pad(d.getUTCHours(),p,2)}function formatUTCHour12(d,p){return pad(d.getUTCHours()%12||12,p,2)}function formatUTCDayOfYear(d,p){return pad(1+d3Time.utcDay.count(d3Time.utcYear(d),d),p,3)}function formatUTCMilliseconds(d,p){return pad(d.getUTCMilliseconds(),p,3)}function formatUTCMicroseconds(d,p){return formatUTCMilliseconds(d,p)+"000"}function formatUTCMonthNumber(d,p){return pad(d.getUTCMonth()+1,p,2)}function formatUTCMinutes(d,p){return pad(d.getUTCMinutes(),p,2)}function formatUTCSeconds(d,p){return pad(d.getUTCSeconds(),p,2)}function formatUTCWeekdayNumberMonday(d){var dow=d.getUTCDay();return dow===0?7:dow}function formatUTCWeekNumberSunday(d,p){return pad(d3Time.utcSunday.count(d3Time.utcYear(d)-1,d),p,2)}function formatUTCWeekNumberISO(d,p){var day=d.getUTCDay();d=day>=4||day===0?d3Time.utcThursday(d):d3Time.utcThursday.ceil(d);return pad(d3Time.utcThursday.count(d3Time.utcYear(d),d)+(d3Time.utcYear(d).getUTCDay()===4),p,2)}function formatUTCWeekdayNumberSunday(d){return d.getUTCDay()}function formatUTCWeekNumberMonday(d,p){return pad(d3Time.utcMonday.count(d3Time.utcYear(d)-1,d),p,2)}function formatUTCYear(d,p){return pad(d.getUTCFullYear()%100,p,2)}function formatUTCFullYear(d,p){return pad(d.getUTCFullYear()%1e4,p,4)}function formatUTCZone(){return"+0000"}function formatLiteralPercent(){return"%"}function formatUnixTimestamp(d){return+d}function formatUnixTimestampSeconds(d){return Math.floor(+d/1e3)}var locale;defaultLocale({dateTime:"%x, %X",date:"%-m/%-d/%Y",time:"%-I:%M:%S %p",periods:["AM","PM"],days:["Sunday","Monday","Tuesday","Wednesday","Thursday","Friday","Saturday"],shortDays:["Sun","Mon","Tue","Wed","Thu","Fri","Sat"],months:["January","February","March","April","May","June","July","August","September","October","November","December"],shortMonths:["Jan","Feb","Mar","Apr","May","Jun","Jul","Aug","Sep","Oct","Nov","Dec"]});function defaultLocale(definition){locale=formatLocale(definition);exports.timeFormat=locale.format;exports.timeParse=locale.parse;exports.utcFormat=locale.utcFormat;exports.utcParse=locale.utcParse;return locale}var isoSpecifier="%Y-%m-%dT%H:%M:%S.%LZ";function formatIsoNative(date){return date.toISOString()}var formatIso=Date.prototype.toISOString?formatIsoNative:exports.utcFormat(isoSpecifier);function parseIsoNative(string){var date=new Date(string);return isNaN(date)?null:date}var parseIso=+new Date("2000-01-01T00:00:00.000Z")?parseIsoNative:exports.utcParse(isoSpecifier);exports.isoFormat=formatIso;exports.isoParse=parseIso;exports.timeFormatDefaultLocale=defaultLocale;exports.timeFormatLocale=formatLocale;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-time":55}],55:[function(require,module,exports){ -// https://d3js.org/d3-time/ v1.1.0 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):(global=global||self,factory(global.d3=global.d3||{}))})(this,function(exports){"use strict";var t0=new Date,t1=new Date;function newInterval(floori,offseti,count,field){function interval(date){return floori(date=arguments.length===0?new Date:new Date(+date)),date}interval.floor=function(date){return floori(date=new Date(+date)),date};interval.ceil=function(date){return floori(date=new Date(date-1)),offseti(date,1),floori(date),date};interval.round=function(date){var d0=interval(date),d1=interval.ceil(date);return date-d00))return range;// also handles Invalid Date -do{range.push(previous=new Date(+start)),offseti(start,step),floori(start)}while(previous=date)while(floori(date),!test(date))date.setTime(date-1)},function(date,step){if(date>=date){if(step<0)while(++step<=0){while(offseti(date,-1),!test(date)){}// eslint-disable-line no-empty -}else while(--step>=0){while(offseti(date,+1),!test(date)){}// eslint-disable-line no-empty -}}})};if(count){interval.count=function(start,end){t0.setTime(+start),t1.setTime(+end);floori(t0),floori(t1);return Math.floor(count(t0,t1))};interval.every=function(step){step=Math.floor(step);return!isFinite(step)||!(step>0)?null:!(step>1)?interval:interval.filter(field?function(d){return field(d)%step===0}:function(d){return interval.count(0,d)%step===0})}}return interval}var millisecond=newInterval(function(){ -// noop -},function(date,step){date.setTime(+date+step)},function(start,end){return end-start}); -// An optimized implementation for this simple case. -millisecond.every=function(k){k=Math.floor(k);if(!isFinite(k)||!(k>0))return null;if(!(k>1))return millisecond;return newInterval(function(date){date.setTime(Math.floor(date/k)*k)},function(date,step){date.setTime(+date+step*k)},function(start,end){return(end-start)/k})};var milliseconds=millisecond.range;var durationSecond=1e3;var durationMinute=6e4;var durationHour=36e5;var durationDay=864e5;var durationWeek=6048e5;var second=newInterval(function(date){date.setTime(date-date.getMilliseconds())},function(date,step){date.setTime(+date+step*durationSecond)},function(start,end){return(end-start)/durationSecond},function(date){return date.getUTCSeconds()});var seconds=second.range;var minute=newInterval(function(date){date.setTime(date-date.getMilliseconds()-date.getSeconds()*durationSecond)},function(date,step){date.setTime(+date+step*durationMinute)},function(start,end){return(end-start)/durationMinute},function(date){return date.getMinutes()});var minutes=minute.range;var hour=newInterval(function(date){date.setTime(date-date.getMilliseconds()-date.getSeconds()*durationSecond-date.getMinutes()*durationMinute)},function(date,step){date.setTime(+date+step*durationHour)},function(start,end){return(end-start)/durationHour},function(date){return date.getHours()});var hours=hour.range;var day=newInterval(function(date){date.setHours(0,0,0,0)},function(date,step){date.setDate(date.getDate()+step)},function(start,end){return(end-start-(end.getTimezoneOffset()-start.getTimezoneOffset())*durationMinute)/durationDay},function(date){return date.getDate()-1});var days=day.range;function weekday(i){return newInterval(function(date){date.setDate(date.getDate()-(date.getDay()+7-i)%7);date.setHours(0,0,0,0)},function(date,step){date.setDate(date.getDate()+step*7)},function(start,end){return(end-start-(end.getTimezoneOffset()-start.getTimezoneOffset())*durationMinute)/durationWeek})}var sunday=weekday(0);var monday=weekday(1);var tuesday=weekday(2);var wednesday=weekday(3);var thursday=weekday(4);var friday=weekday(5);var saturday=weekday(6);var sundays=sunday.range;var mondays=monday.range;var tuesdays=tuesday.range;var wednesdays=wednesday.range;var thursdays=thursday.range;var fridays=friday.range;var saturdays=saturday.range;var month=newInterval(function(date){date.setDate(1);date.setHours(0,0,0,0)},function(date,step){date.setMonth(date.getMonth()+step)},function(start,end){return end.getMonth()-start.getMonth()+(end.getFullYear()-start.getFullYear())*12},function(date){return date.getMonth()});var months=month.range;var year=newInterval(function(date){date.setMonth(0,1);date.setHours(0,0,0,0)},function(date,step){date.setFullYear(date.getFullYear()+step)},function(start,end){return end.getFullYear()-start.getFullYear()},function(date){return date.getFullYear()}); -// An optimized implementation for this simple case. -year.every=function(k){return!isFinite(k=Math.floor(k))||!(k>0)?null:newInterval(function(date){date.setFullYear(Math.floor(date.getFullYear()/k)*k);date.setMonth(0,1);date.setHours(0,0,0,0)},function(date,step){date.setFullYear(date.getFullYear()+step*k)})};var years=year.range;var utcMinute=newInterval(function(date){date.setUTCSeconds(0,0)},function(date,step){date.setTime(+date+step*durationMinute)},function(start,end){return(end-start)/durationMinute},function(date){return date.getUTCMinutes()});var utcMinutes=utcMinute.range;var utcHour=newInterval(function(date){date.setUTCMinutes(0,0,0)},function(date,step){date.setTime(+date+step*durationHour)},function(start,end){return(end-start)/durationHour},function(date){return date.getUTCHours()});var utcHours=utcHour.range;var utcDay=newInterval(function(date){date.setUTCHours(0,0,0,0)},function(date,step){date.setUTCDate(date.getUTCDate()+step)},function(start,end){return(end-start)/durationDay},function(date){return date.getUTCDate()-1});var utcDays=utcDay.range;function utcWeekday(i){return newInterval(function(date){date.setUTCDate(date.getUTCDate()-(date.getUTCDay()+7-i)%7);date.setUTCHours(0,0,0,0)},function(date,step){date.setUTCDate(date.getUTCDate()+step*7)},function(start,end){return(end-start)/durationWeek})}var utcSunday=utcWeekday(0);var utcMonday=utcWeekday(1);var utcTuesday=utcWeekday(2);var utcWednesday=utcWeekday(3);var utcThursday=utcWeekday(4);var utcFriday=utcWeekday(5);var utcSaturday=utcWeekday(6);var utcSundays=utcSunday.range;var utcMondays=utcMonday.range;var utcTuesdays=utcTuesday.range;var utcWednesdays=utcWednesday.range;var utcThursdays=utcThursday.range;var utcFridays=utcFriday.range;var utcSaturdays=utcSaturday.range;var utcMonth=newInterval(function(date){date.setUTCDate(1);date.setUTCHours(0,0,0,0)},function(date,step){date.setUTCMonth(date.getUTCMonth()+step)},function(start,end){return end.getUTCMonth()-start.getUTCMonth()+(end.getUTCFullYear()-start.getUTCFullYear())*12},function(date){return date.getUTCMonth()});var utcMonths=utcMonth.range;var utcYear=newInterval(function(date){date.setUTCMonth(0,1);date.setUTCHours(0,0,0,0)},function(date,step){date.setUTCFullYear(date.getUTCFullYear()+step)},function(start,end){return end.getUTCFullYear()-start.getUTCFullYear()},function(date){return date.getUTCFullYear()}); -// An optimized implementation for this simple case. -utcYear.every=function(k){return!isFinite(k=Math.floor(k))||!(k>0)?null:newInterval(function(date){date.setUTCFullYear(Math.floor(date.getUTCFullYear()/k)*k);date.setUTCMonth(0,1);date.setUTCHours(0,0,0,0)},function(date,step){date.setUTCFullYear(date.getUTCFullYear()+step*k)})};var utcYears=utcYear.range;exports.timeDay=day;exports.timeDays=days;exports.timeFriday=friday;exports.timeFridays=fridays;exports.timeHour=hour;exports.timeHours=hours;exports.timeInterval=newInterval;exports.timeMillisecond=millisecond;exports.timeMilliseconds=milliseconds;exports.timeMinute=minute;exports.timeMinutes=minutes;exports.timeMonday=monday;exports.timeMondays=mondays;exports.timeMonth=month;exports.timeMonths=months;exports.timeSaturday=saturday;exports.timeSaturdays=saturdays;exports.timeSecond=second;exports.timeSeconds=seconds;exports.timeSunday=sunday;exports.timeSundays=sundays;exports.timeThursday=thursday;exports.timeThursdays=thursdays;exports.timeTuesday=tuesday;exports.timeTuesdays=tuesdays;exports.timeWednesday=wednesday;exports.timeWednesdays=wednesdays;exports.timeWeek=sunday;exports.timeWeeks=sundays;exports.timeYear=year;exports.timeYears=years;exports.utcDay=utcDay;exports.utcDays=utcDays;exports.utcFriday=utcFriday;exports.utcFridays=utcFridays;exports.utcHour=utcHour;exports.utcHours=utcHours;exports.utcMillisecond=millisecond;exports.utcMilliseconds=milliseconds;exports.utcMinute=utcMinute;exports.utcMinutes=utcMinutes;exports.utcMonday=utcMonday;exports.utcMondays=utcMondays;exports.utcMonth=utcMonth;exports.utcMonths=utcMonths;exports.utcSaturday=utcSaturday;exports.utcSaturdays=utcSaturdays;exports.utcSecond=second;exports.utcSeconds=seconds;exports.utcSunday=utcSunday;exports.utcSundays=utcSundays;exports.utcThursday=utcThursday;exports.utcThursdays=utcThursdays;exports.utcTuesday=utcTuesday;exports.utcTuesdays=utcTuesdays;exports.utcWednesday=utcWednesday;exports.utcWednesdays=utcWednesdays;exports.utcWeek=utcSunday;exports.utcWeeks=utcSundays;exports.utcYear=utcYear;exports.utcYears=utcYears;Object.defineProperty(exports,"__esModule",{value:true})})},{}],56:[function(require,module,exports){ -// https://d3js.org/d3-timer/ v1.0.10 Copyright 2019 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):(global=global||self,factory(global.d3=global.d3||{}))})(this,function(exports){"use strict";var frame=0,// is an animation frame pending? -timeout=0,// is a timeout pending? -interval=0,// are any timers active? -pokeDelay=1e3,// how frequently we check for clock skew -taskHead,taskTail,clockLast=0,clockNow=0,clockSkew=0,clock=typeof performance==="object"&&performance.now?performance:Date,setFrame=typeof window==="object"&&window.requestAnimationFrame?window.requestAnimationFrame.bind(window):function(f){setTimeout(f,17)};function now(){return clockNow||(setFrame(clearNow),clockNow=clock.now()+clockSkew)}function clearNow(){clockNow=0}function Timer(){this._call=this._time=this._next=null}Timer.prototype=timer.prototype={constructor:Timer,restart:function(callback,delay,time){if(typeof callback!=="function")throw new TypeError("callback is not a function");time=(time==null?now():+time)+(delay==null?0:+delay);if(!this._next&&taskTail!==this){if(taskTail)taskTail._next=this;else taskHead=this;taskTail=this}this._call=callback;this._time=time;sleep()},stop:function(){if(this._call){this._call=null;this._time=Infinity;sleep()}}};function timer(callback,delay,time){var t=new Timer;t.restart(callback,delay,time);return t}function timerFlush(){now();// Get the current time, if not already set. -++frame;// Pretend we’ve set an alarm, if we haven’t already. -var t=taskHead,e;while(t){if((e=clockNow-t._time)>=0)t._call.call(null,e);t=t._next}--frame}function wake(){clockNow=(clockLast=clock.now())+clockSkew;frame=timeout=0;try{timerFlush()}finally{frame=0;nap();clockNow=0}}function poke(){var now=clock.now(),delay=now-clockLast;if(delay>pokeDelay)clockSkew-=delay,clockLast=now}function nap(){var t0,t1=taskHead,t2,time=Infinity;while(t1){if(t1._call){if(time>t1._time)time=t1._time;t0=t1,t1=t1._next}else{t2=t1._next,t1._next=null;t1=t0?t0._next=t2:taskHead=t2}}taskTail=t0;sleep(time)}function sleep(time){if(frame)return;// Soonest alarm already set, or will be. -if(timeout)timeout=clearTimeout(timeout);var delay=time-clockNow;// Strictly less than if we recomputed clockNow. -if(delay>24){if(timeCREATED)throw new Error("too late; already scheduled");return schedule}function set(node,id){var schedule=get(node,id);if(schedule.state>STARTED)throw new Error("too late; already running");return schedule}function get(node,id){var schedule=node.__transition;if(!schedule||!(schedule=schedule[id]))throw new Error("transition not found");return schedule}function create(node,id,self){var schedules=node.__transition,tween; -// Initialize the self timer when the transition is created. -// Note the actual delay is not known until the first callback! -schedules[id]=self;self.timer=d3Timer.timer(schedule,0,self.time);function schedule(elapsed){self.state=SCHEDULED;self.timer.restart(start,self.delay,self.time); -// If the elapsed delay is less than our first sleep, start immediately. -if(self.delay<=elapsed)start(elapsed-self.delay)}function start(elapsed){var i,j,n,o; -// If the state is not SCHEDULED, then we previously errored on start. -if(self.state!==SCHEDULED)return stop();for(i in schedules){o=schedules[i];if(o.name!==self.name)continue; -// While this element already has a starting transition during this frame, -// defer starting an interrupting transition until that transition has a -// chance to tick (and possibly end); see d3/d3-transition#54! -if(o.state===STARTED)return d3Timer.timeout(start); -// Interrupt the active transition, if any. -if(o.state===RUNNING){o.state=ENDED;o.timer.stop();o.on.call("interrupt",node,node.__data__,o.index,o.group);delete schedules[i]} -// Cancel any pre-empted transitions. -else if(+iSTARTING&&schedule.state=0)t=t.slice(0,i);return!t||t==="start"})}function onFunction(id,name,listener){var on0,on1,sit=start(name)?init:set;return function(){var schedule=sit(this,id),on=schedule.on; -// If this node shared a dispatch with the previous node, -// just assign the updated shared dispatch and we’re done! -// Otherwise, copy-on-write. -if(on!==on0)(on1=(on0=on).copy()).on(name,listener);schedule.on=on1}}function transition_on(name,listener){var id=this._id;return arguments.length<2?get(this.node(),id).on.on(name):this.each(onFunction(id,name,listener))}function removeFunction(id){return function(){var parent=this.parentNode;for(var i in this.__transition)if(+i!==id)return;if(parent)parent.removeChild(this)}}function transition_remove(){return this.on("end.remove",removeFunction(this._id))}function transition_select(select){var name=this._name,id=this._id;if(typeof select!=="function")select=d3Selection.selector(select);for(var groups=this._groups,m=groups.length,subgroups=new Array(m),j=0;jSCHEDULED&&schedule.name===name){return new Transition([[node]],root,name,+i)}}}return null}exports.active=active;exports.interrupt=interrupt;exports.transition=transition;Object.defineProperty(exports,"__esModule",{value:true})})},{"d3-color":34,"d3-dispatch":36,"d3-ease":39,"d3-interpolate":45,"d3-selection":52,"d3-timer":56}],58:[function(require,module,exports){ -// https://d3js.org/d3-voronoi/ v1.1.4 Copyright 2018 Mike Bostock -(function(global,factory){typeof exports==="object"&&typeof module!=="undefined"?factory(exports):typeof define==="function"&&define.amd?define(["exports"],factory):factory(global.d3=global.d3||{})})(this,function(exports){"use strict";function constant(x){return function(){return x}}function x(d){return d[0]}function y(d){return d[1]}function RedBlackTree(){this._=null;// root node -}function RedBlackNode(node){node.U=// parent node -node.C=// color - true for red, false for black -node.L=// left node -node.R=// right node -node.P=// previous node -node.N=null;// next node -}RedBlackTree.prototype={constructor:RedBlackTree,insert:function(after,node){var parent,grandpa,uncle;if(after){node.P=after;node.N=after.N;if(after.N)after.N.P=node;after.N=node;if(after.R){after=after.R;while(after.L)after=after.L;after.L=node}else{after.R=node}parent=after}else if(this._){after=RedBlackFirst(this._);node.P=null;node.N=after;after.P=after.L=node;parent=after}else{node.P=node.N=null;this._=node;parent=null}node.L=node.R=null;node.U=parent;node.C=true;after=node;while(parent&&parent.C){grandpa=parent.U;if(parent===grandpa.L){uncle=grandpa.R;if(uncle&&uncle.C){parent.C=uncle.C=false;grandpa.C=true;after=grandpa}else{if(after===parent.R){RedBlackRotateLeft(this,parent);after=parent;parent=after.U}parent.C=false;grandpa.C=true;RedBlackRotateRight(this,grandpa)}}else{uncle=grandpa.L;if(uncle&&uncle.C){parent.C=uncle.C=false;grandpa.C=true;after=grandpa}else{if(after===parent.L){RedBlackRotateRight(this,parent);after=parent;parent=after.U}parent.C=false;grandpa.C=true;RedBlackRotateLeft(this,grandpa)}}parent=after.U}this._.C=false},remove:function(node){if(node.N)node.N.P=node.P;if(node.P)node.P.N=node.N;node.N=node.P=null;var parent=node.U,sibling,left=node.L,right=node.R,next,red;if(!left)next=right;else if(!right)next=left;else next=RedBlackFirst(right);if(parent){if(parent.L===node)parent.L=next;else parent.R=next}else{this._=next}if(left&&right){red=next.C;next.C=node.C;next.L=left;left.U=next;if(next!==right){parent=next.U;next.U=node.U;node=next.R;parent.L=node;next.R=right;right.U=next}else{next.U=parent;parent=next;node=next.R}}else{red=node.C;node=next}if(node)node.U=parent;if(red)return;if(node&&node.C){node.C=false;return}do{if(node===this._)break;if(node===parent.L){sibling=parent.R;if(sibling.C){sibling.C=false;parent.C=true;RedBlackRotateLeft(this,parent);sibling=parent.R}if(sibling.L&&sibling.L.C||sibling.R&&sibling.R.C){if(!sibling.R||!sibling.R.C){sibling.L.C=false;sibling.C=true;RedBlackRotateRight(this,sibling);sibling=parent.R}sibling.C=parent.C;parent.C=sibling.R.C=false;RedBlackRotateLeft(this,parent);node=this._;break}}else{sibling=parent.L;if(sibling.C){sibling.C=false;parent.C=true;RedBlackRotateRight(this,parent);sibling=parent.L}if(sibling.L&&sibling.L.C||sibling.R&&sibling.R.C){if(!sibling.L||!sibling.L.C){sibling.R.C=false;sibling.C=true;RedBlackRotateLeft(this,sibling);sibling=parent.L}sibling.C=parent.C;parent.C=sibling.L.C=false;RedBlackRotateRight(this,parent);node=this._;break}}sibling.C=true;node=parent;parent=parent.U}while(!node.C);if(node)node.C=false}};function RedBlackRotateLeft(tree,node){var p=node,q=node.R,parent=p.U;if(parent){if(parent.L===p)parent.L=q;else parent.R=q}else{tree._=q}q.U=parent;p.U=q;p.R=q.L;if(p.R)p.R.U=p;q.L=p}function RedBlackRotateRight(tree,node){var p=node,q=node.L,parent=p.U;if(parent){if(parent.L===p)parent.L=q;else parent.R=q}else{tree._=q}q.U=parent;p.U=q;p.L=q.R;if(p.L)p.L.U=p;q.R=p}function RedBlackFirst(node){while(node.L)node=node.L;return node}function createEdge(left,right,v0,v1){var edge=[null,null],index=edges.push(edge)-1;edge.left=left;edge.right=right;if(v0)setEdgeEnd(edge,left,right,v0);if(v1)setEdgeEnd(edge,right,left,v1);cells[left.index].halfedges.push(index);cells[right.index].halfedges.push(index);return edge}function createBorderEdge(left,v0,v1){var edge=[v0,v1];edge.left=left;return edge}function setEdgeEnd(edge,left,right,vertex){if(!edge[0]&&!edge[1]){edge[0]=vertex;edge.left=left;edge.right=right}else if(edge.left===right){edge[1]=vertex}else{edge[0]=vertex}} -// Liang–Barsky line clipping. -function clipEdge(edge,x0,y0,x1,y1){var a=edge[0],b=edge[1],ax=a[0],ay=a[1],bx=b[0],by=b[1],t0=0,t1=1,dx=bx-ax,dy=by-ay,r;r=x0-ax;if(!dx&&r>0)return;r/=dx;if(dx<0){if(r0){if(r>t1)return;if(r>t0)t0=r}r=x1-ax;if(!dx&&r<0)return;r/=dx;if(dx<0){if(r>t1)return;if(r>t0)t0=r}else if(dx>0){if(r0)return;r/=dy;if(dy<0){if(r0){if(r>t1)return;if(r>t0)t0=r}r=y1-ay;if(!dy&&r<0)return;r/=dy;if(dy<0){if(r>t1)return;if(r>t0)t0=r}else if(dy>0){if(r0)&&!(t1<1))return true;// TODO Better check? -if(t0>0)edge[0]=[ax+t0*dx,ay+t0*dy];if(t1<1)edge[1]=[ax+t1*dx,ay+t1*dy];return true}function connectEdge(edge,x0,y0,x1,y1){var v1=edge[1];if(v1)return true;var v0=edge[0],left=edge.left,right=edge.right,lx=left[0],ly=left[1],rx=right[0],ry=right[1],fx=(lx+rx)/2,fy=(ly+ry)/2,fm,fb;if(ry===ly){if(fx=x1)return;if(lx>rx){if(!v0)v0=[fx,y0];else if(v0[1]>=y1)return;v1=[fx,y1]}else{if(!v0)v0=[fx,y1];else if(v0[1]1){if(lx>rx){if(!v0)v0=[(y0-fb)/fm,y0];else if(v0[1]>=y1)return;v1=[(y1-fb)/fm,y1]}else{if(!v0)v0=[(y1-fb)/fm,y1];else if(v0[1]=x1)return;v1=[x1,fm*x1+fb]}else{if(!v0)v0=[x1,fm*x1+fb];else if(v0[0]epsilon||Math.abs(edge[0][1]-edge[1][1])>epsilon)){delete edges[i]}}}function createCell(site){return cells[site.index]={site:site,halfedges:[]}}function cellHalfedgeAngle(cell,edge){var site=cell.site,va=edge.left,vb=edge.right;if(site===vb)vb=va,va=site;if(vb)return Math.atan2(vb[1]-va[1],vb[0]-va[0]);if(site===va)va=edge[1],vb=edge[0];else va=edge[0],vb=edge[1];return Math.atan2(va[0]-vb[0],vb[1]-va[1])}function cellHalfedgeStart(cell,edge){return edge[+(edge.left!==cell.site)]}function cellHalfedgeEnd(cell,edge){return edge[+(edge.left===cell.site)]}function sortCellHalfedges(){for(var i=0,n=cells.length,cell,halfedges,j,m;iepsilon||Math.abs(endY-startY)>epsilon){halfedges.splice(iHalfedge,0,edges.push(createBorderEdge(site,end,Math.abs(endX-x0)epsilon?[x0,Math.abs(startX-x0)epsilon?[Math.abs(startY-y1)epsilon?[x1,Math.abs(startX-x1)epsilon?[Math.abs(startY-y0)=-epsilon2)return;var ha=ax*ax+ay*ay,hc=cx*cx+cy*cy,x=(cy*ha-ay*hc)/d,y=(ax*hc-cx*ha)/d;var circle=circlePool.pop()||new Circle;circle.arc=arc;circle.site=cSite;circle.x=x+bx;circle.y=(circle.cy=y+by)+Math.sqrt(x*x+y*y);// y bottom -arc.circle=circle;var before=null,node=circles._;while(node){if(circle.yepsilon)node=node.L;else{dxr=x-rightBreakPoint(node,directrix);if(dxr>epsilon){if(!node.R){lArc=node;break}node=node.R}else{if(dxl>-epsilon){lArc=node.P;rArc=node}else if(dxr>-epsilon){lArc=node;rArc=node.N}else{lArc=rArc=node}break}}}createCell(site);var newArc=createBeach(site);beaches.insert(lArc,newArc);if(!lArc&&!rArc)return;if(lArc===rArc){detachCircle(lArc);rArc=createBeach(lArc.site);beaches.insert(newArc,rArc);newArc.edge=rArc.edge=createEdge(lArc.site,newArc.site);attachCircle(lArc);attachCircle(rArc);return}if(!rArc){// && lArc -newArc.edge=createEdge(lArc.site,newArc.site);return} -// else lArc !== rArc -detachCircle(lArc);detachCircle(rArc);var lSite=lArc.site,ax=lSite[0],ay=lSite[1],bx=site[0]-ax,by=site[1]-ay,rSite=rArc.site,cx=rSite[0]-ax,cy=rSite[1]-ay,d=2*(bx*cy-by*cx),hb=bx*bx+by*by,hc=cx*cx+cy*cy,vertex=[(cy*hb-by*hc)/d+ax,(bx*hc-cx*hb)/d+ay];setEdgeEnd(rArc.edge,lSite,rSite,vertex);newArc.edge=createEdge(lSite,site,null,vertex);rArc.edge=createEdge(site,rSite,null,vertex);attachCircle(lArc);attachCircle(rArc)}function leftBreakPoint(arc,directrix){var site=arc.site,rfocx=site[0],rfocy=site[1],pby2=rfocy-directrix;if(!pby2)return rfocx;var lArc=arc.P;if(!lArc)return-Infinity;site=lArc.site;var lfocx=site[0],lfocy=site[1],plby2=lfocy-directrix;if(!plby2)return lfocx;var hl=lfocx-rfocx,aby2=1/pby2-1/plby2,b=hl/plby2;if(aby2)return(-b+Math.sqrt(b*b-2*aby2*(hl*hl/(-2*plby2)-lfocy+plby2/2+rfocy-pby2/2)))/aby2+rfocx;return(rfocx+lfocx)/2}function rightBreakPoint(arc,directrix){var rArc=arc.N;if(rArc)return leftBreakPoint(rArc,directrix);var site=arc.site;return site[1]===directrix?site[0]:Infinity}var epsilon=1e-6;var epsilon2=1e-12;var beaches;var cells;var circles;var edges;function triangleArea(a,b,c){return(a[0]-c[0])*(b[1]-a[1])-(a[0]-b[0])*(c[1]-a[1])}function lexicographic(a,b){return b[1]-a[1]||b[0]-a[0]}function Diagram(sites,extent){var site=sites.sort(lexicographic).pop(),x,y,circle;edges=[];cells=new Array(sites.length);beaches=new RedBlackTree;circles=new RedBlackTree;while(true){circle=firstCircle;if(site&&(!circle||site[1]=n)return null;var dx=x-cell.site[0],dy=y-cell.site[1],d2=dx*dx+dy*dy; -// Traverse the half-edges to find a closer cell, if any. -do{cell=that.cells[i0=i1],i1=null;cell.halfedges.forEach(function(e){var edge=that.edges[e],v=edge.left;if((v===cell.site||!v)&&!(v=edge.right))return;var vx=x-v[0],vy=y-v[1],v2=vx*vx+vy*vy;if(v2dx0?(dx0+dx1)/2:Math.min(0,dx0)||Math.max(0,dx1),dy1>dy0?(dy0+dy1)/2:Math.min(0,dy0)||Math.max(0,dy1))}function zoom(){var filter=defaultFilter,extent=defaultExtent,constrain=defaultConstrain,wheelDelta=defaultWheelDelta,touchable=defaultTouchable,scaleExtent=[0,Infinity],translateExtent=[[-Infinity,-Infinity],[Infinity,Infinity]],duration=250,interpolate=d3Interpolate.interpolateZoom,listeners=d3Dispatch.dispatch("start","zoom","end"),touchstarting,touchending,touchDelay=500,wheelDelay=150,clickDistance2=0;function zoom(selection){selection.property("__zoom",defaultTransform).on("wheel.zoom",wheeled).on("mousedown.zoom",mousedowned).on("dblclick.zoom",dblclicked).filter(touchable).on("touchstart.zoom",touchstarted).on("touchmove.zoom",touchmoved).on("touchend.zoom touchcancel.zoom",touchended).style("touch-action","none").style("-webkit-tap-highlight-color","rgba(0,0,0,0)")}zoom.transform=function(collection,transform,point){var selection=collection.selection?collection.selection():collection;selection.property("__zoom",defaultTransform);if(collection!==selection){schedule(collection,transform,point)}else{selection.interrupt().each(function(){gesture(this,arguments).start().zoom(null,typeof transform==="function"?transform.apply(this,arguments):transform).end()})}};zoom.scaleBy=function(selection,k,p){zoom.scaleTo(selection,function(){var k0=this.__zoom.k,k1=typeof k==="function"?k.apply(this,arguments):k;return k0*k1},p)};zoom.scaleTo=function(selection,k,p){zoom.transform(selection,function(){var e=extent.apply(this,arguments),t0=this.__zoom,p0=p==null?centroid(e):typeof p==="function"?p.apply(this,arguments):p,p1=t0.invert(p0),k1=typeof k==="function"?k.apply(this,arguments):k;return constrain(translate(scale(t0,k1),p0,p1),e,translateExtent)},p)};zoom.translateBy=function(selection,x,y){zoom.transform(selection,function(){return constrain(this.__zoom.translate(typeof x==="function"?x.apply(this,arguments):x,typeof y==="function"?y.apply(this,arguments):y),extent.apply(this,arguments),translateExtent)})};zoom.translateTo=function(selection,x,y,p){zoom.transform(selection,function(){var e=extent.apply(this,arguments),t=this.__zoom,p0=p==null?centroid(e):typeof p==="function"?p.apply(this,arguments):p;return constrain(identity.translate(p0[0],p0[1]).scale(t.k).translate(typeof x==="function"?-x.apply(this,arguments):-x,typeof y==="function"?-y.apply(this,arguments):-y),e,translateExtent)},p)};function scale(transform,k){k=Math.max(scaleExtent[0],Math.min(scaleExtent[1],k));return k===transform.k?transform:new Transform(k,transform.x,transform.y)}function translate(transform,p0,p1){var x=p0[0]-p1[0]*transform.k,y=p0[1]-p1[1]*transform.k;return x===transform.x&&y===transform.y?transform:new Transform(transform.k,x,y)}function centroid(extent){return[(+extent[0][0]+ +extent[1][0])/2,(+extent[0][1]+ +extent[1][1])/2]}function schedule(transition,transform,point){transition.on("start.zoom",function(){gesture(this,arguments).start()}).on("interrupt.zoom end.zoom",function(){gesture(this,arguments).end()}).tween("zoom",function(){var that=this,args=arguments,g=gesture(that,args),e=extent.apply(that,args),p=point==null?centroid(e):typeof point==="function"?point.apply(that,args):point,w=Math.max(e[1][0]-e[0][0],e[1][1]-e[0][1]),a=that.__zoom,b=typeof transform==="function"?transform.apply(that,args):transform,i=interpolate(a.invert(p).concat(w/a.k),b.invert(p).concat(w/b.k));return function(t){if(t===1)t=b;// Avoid rounding error on end. -else{var l=i(t),k=w/l[2];t=new Transform(k,p[0]-l[0]*k,p[1]-l[1]*k)}g.zoom(null,t)}})}function gesture(that,args,clean){return!clean&&that.__zooming||new Gesture(that,args)}function Gesture(that,args){this.that=that;this.args=args;this.active=0;this.extent=extent.apply(that,args);this.taps=0}Gesture.prototype={start:function(){if(++this.active===1){this.that.__zooming=this;this.emit("start")}return this},zoom:function(key,transform){if(this.mouse&&key!=="mouse")this.mouse[1]=transform.invert(this.mouse[0]);if(this.touch0&&key!=="touch")this.touch0[1]=transform.invert(this.touch0[0]);if(this.touch1&&key!=="touch")this.touch1[1]=transform.invert(this.touch1[0]);this.that.__zoom=transform;this.emit("zoom");return this},end:function(){if(--this.active===0){delete this.that.__zooming;this.emit("end")}return this},emit:function(type){d3Selection.customEvent(new ZoomEvent(zoom,type,this.that.__zoom),listeners.apply,listeners,[type,this.that,this.args])}};function wheeled(){if(!filter.apply(this,arguments))return;var g=gesture(this,arguments),t=this.__zoom,k=Math.max(scaleExtent[0],Math.min(scaleExtent[1],t.k*Math.pow(2,wheelDelta.apply(this,arguments)))),p=d3Selection.mouse(this); -// If the mouse is in the same location as before, reuse it. -// If there were recent wheel events, reset the wheel idle timeout. -if(g.wheel){if(g.mouse[0][0]!==p[0]||g.mouse[0][1]!==p[1]){g.mouse[1]=t.invert(g.mouse[0]=p)}clearTimeout(g.wheel)} -// If this wheel event won’t trigger a transform change, ignore it. -else if(t.k===k)return; -// Otherwise, capture the mouse point and location at the start. -else{g.mouse=[p,t.invert(p)];d3Transition.interrupt(this);g.start()}noevent();g.wheel=setTimeout(wheelidled,wheelDelay);g.zoom("mouse",constrain(translate(scale(t,k),g.mouse[0],g.mouse[1]),g.extent,translateExtent));function wheelidled(){g.wheel=null;g.end()}}function mousedowned(){if(touchending||!filter.apply(this,arguments))return;var g=gesture(this,arguments,true),v=d3Selection.select(d3Selection.event.view).on("mousemove.zoom",mousemoved,true).on("mouseup.zoom",mouseupped,true),p=d3Selection.mouse(this),x0=d3Selection.event.clientX,y0=d3Selection.event.clientY;d3Drag.dragDisable(d3Selection.event.view);nopropagation();g.mouse=[p,this.__zoom.invert(p)];d3Transition.interrupt(this);g.start();function mousemoved(){noevent();if(!g.moved){var dx=d3Selection.event.clientX-x0,dy=d3Selection.event.clientY-y0;g.moved=dx*dx+dy*dy>clickDistance2}g.zoom("mouse",constrain(translate(g.that.__zoom,g.mouse[0]=d3Selection.mouse(g.that),g.mouse[1]),g.extent,translateExtent))}function mouseupped(){v.on("mousemove.zoom mouseup.zoom",null);d3Drag.dragEnable(d3Selection.event.view,g.moved);noevent();g.end()}}function dblclicked(){if(!filter.apply(this,arguments))return;var t0=this.__zoom,p0=d3Selection.mouse(this),p1=t0.invert(p0),k1=t0.k*(d3Selection.event.shiftKey?.5:2),t1=constrain(translate(scale(t0,k1),p0,p1),extent.apply(this,arguments),translateExtent);noevent();if(duration>0)d3Selection.select(this).transition().duration(duration).call(schedule,t1,p0);else d3Selection.select(this).call(zoom.transform,t1)}function touchstarted(){if(!filter.apply(this,arguments))return;var touches=d3Selection.event.touches,n=touches.length,g=gesture(this,arguments,d3Selection.event.changedTouches.length===n),started,i,t,p;nopropagation();for(i=0;i0;--i){entry=buckets[i].dequeue();if(entry){results=results.concat(removeNode(g,buckets,zeroIdx,entry,true));break}}}}return results}function removeNode(g,buckets,zeroIdx,entry,collectPredecessors){var results=collectPredecessors?[]:undefined;_.forEach(g.inEdges(entry.v),function(edge){var weight=g.edge(edge);var uEntry=g.node(edge.v);if(collectPredecessors){results.push({v:edge.v,w:edge.w})}uEntry.out-=weight;assignBucket(buckets,zeroIdx,uEntry)});_.forEach(g.outEdges(entry.v),function(edge){var weight=g.edge(edge);var w=edge.w;var wEntry=g.node(w);wEntry["in"]-=weight;assignBucket(buckets,zeroIdx,wEntry)});g.removeNode(entry.v);return results}function buildState(g,weightFn){var fasGraph=new Graph;var maxIn=0;var maxOut=0;_.forEach(g.nodes(),function(v){fasGraph.setNode(v,{v:v,in:0,out:0})}); -// Aggregate weights on nodes, but also sum the weights across multi-edges -// into a single edge for the fasGraph. -_.forEach(g.edges(),function(e){var prevWeight=fasGraph.edge(e.v,e.w)||0;var weight=weightFn(e);var edgeWeight=prevWeight+weight;fasGraph.setEdge(e.v,e.w,edgeWeight);maxOut=Math.max(maxOut,fasGraph.node(e.v).out+=weight);maxIn=Math.max(maxIn,fasGraph.node(e.w)["in"]+=weight)});var buckets=_.range(maxOut+maxIn+3).map(function(){return new List});var zeroIdx=maxIn+1;_.forEach(fasGraph.nodes(),function(v){assignBucket(buckets,zeroIdx,fasGraph.node(v))});return{graph:fasGraph,buckets:buckets,zeroIdx:zeroIdx}}function assignBucket(buckets,zeroIdx,entry){if(!entry.out){buckets[0].enqueue(entry)}else if(!entry["in"]){buckets[buckets.length-1].enqueue(entry)}else{buckets[entry.out-entry["in"]+zeroIdx].enqueue(entry)}}},{"./data/list":65,"./graphlib":67,"./lodash":70}],69:[function(require,module,exports){"use strict";var _=require("./lodash");var acyclic=require("./acyclic");var normalize=require("./normalize");var rank=require("./rank");var normalizeRanks=require("./util").normalizeRanks;var parentDummyChains=require("./parent-dummy-chains");var removeEmptyRanks=require("./util").removeEmptyRanks;var nestingGraph=require("./nesting-graph");var addBorderSegments=require("./add-border-segments");var coordinateSystem=require("./coordinate-system");var order=require("./order");var position=require("./position");var util=require("./util");var Graph=require("./graphlib").Graph;module.exports=layout;function layout(g,opts){var time=opts&&opts.debugTiming?util.time:util.notime;time("layout",function(){var layoutGraph=time(" buildLayoutGraph",function(){return buildLayoutGraph(g)});time(" runLayout",function(){runLayout(layoutGraph,time)});time(" updateInputGraph",function(){updateInputGraph(g,layoutGraph)})})}function runLayout(g,time){time(" makeSpaceForEdgeLabels",function(){makeSpaceForEdgeLabels(g)});time(" removeSelfEdges",function(){removeSelfEdges(g)});time(" acyclic",function(){acyclic.run(g)});time(" nestingGraph.run",function(){nestingGraph.run(g)});time(" rank",function(){rank(util.asNonCompoundGraph(g))});time(" injectEdgeLabelProxies",function(){injectEdgeLabelProxies(g)});time(" removeEmptyRanks",function(){removeEmptyRanks(g)});time(" nestingGraph.cleanup",function(){nestingGraph.cleanup(g)});time(" normalizeRanks",function(){normalizeRanks(g)});time(" assignRankMinMax",function(){assignRankMinMax(g)});time(" removeEdgeLabelProxies",function(){removeEdgeLabelProxies(g)});time(" normalize.run",function(){normalize.run(g)});time(" parentDummyChains",function(){parentDummyChains(g)});time(" addBorderSegments",function(){addBorderSegments(g)});time(" order",function(){order(g)});time(" insertSelfEdges",function(){insertSelfEdges(g)});time(" adjustCoordinateSystem",function(){coordinateSystem.adjust(g)});time(" position",function(){position(g)});time(" positionSelfEdges",function(){positionSelfEdges(g)});time(" removeBorderNodes",function(){removeBorderNodes(g)});time(" normalize.undo",function(){normalize.undo(g)});time(" fixupEdgeLabelCoords",function(){fixupEdgeLabelCoords(g)});time(" undoCoordinateSystem",function(){coordinateSystem.undo(g)});time(" translateGraph",function(){translateGraph(g)});time(" assignNodeIntersects",function(){assignNodeIntersects(g)});time(" reversePoints",function(){reversePointsForReversedEdges(g)});time(" acyclic.undo",function(){acyclic.undo(g)})} -/* - * Copies final layout information from the layout graph back to the input - * graph. This process only copies whitelisted attributes from the layout graph - * to the input graph, so it serves as a good place to determine what - * attributes can influence layout. - */function updateInputGraph(inputGraph,layoutGraph){_.forEach(inputGraph.nodes(),function(v){var inputLabel=inputGraph.node(v);var layoutLabel=layoutGraph.node(v);if(inputLabel){inputLabel.x=layoutLabel.x;inputLabel.y=layoutLabel.y;if(layoutGraph.children(v).length){inputLabel.width=layoutLabel.width;inputLabel.height=layoutLabel.height}}});_.forEach(inputGraph.edges(),function(e){var inputLabel=inputGraph.edge(e);var layoutLabel=layoutGraph.edge(e);inputLabel.points=layoutLabel.points;if(_.has(layoutLabel,"x")){inputLabel.x=layoutLabel.x;inputLabel.y=layoutLabel.y}});inputGraph.graph().width=layoutGraph.graph().width;inputGraph.graph().height=layoutGraph.graph().height}var graphNumAttrs=["nodesep","edgesep","ranksep","marginx","marginy"];var graphDefaults={ranksep:50,edgesep:20,nodesep:50,rankdir:"tb"};var graphAttrs=["acyclicer","ranker","rankdir","align"];var nodeNumAttrs=["width","height"];var nodeDefaults={width:0,height:0};var edgeNumAttrs=["minlen","weight","width","height","labeloffset"];var edgeDefaults={minlen:1,weight:1,width:0,height:0,labeloffset:10,labelpos:"r"};var edgeAttrs=["labelpos"]; -/* - * Constructs a new graph from the input graph, which can be used for layout. - * This process copies only whitelisted attributes from the input graph to the - * layout graph. Thus this function serves as a good place to determine what - * attributes can influence layout. - */function buildLayoutGraph(inputGraph){var g=new Graph({multigraph:true,compound:true});var graph=canonicalize(inputGraph.graph());g.setGraph(_.merge({},graphDefaults,selectNumberAttrs(graph,graphNumAttrs),_.pick(graph,graphAttrs)));_.forEach(inputGraph.nodes(),function(v){var node=canonicalize(inputGraph.node(v));g.setNode(v,_.defaults(selectNumberAttrs(node,nodeNumAttrs),nodeDefaults));g.setParent(v,inputGraph.parent(v))});_.forEach(inputGraph.edges(),function(e){var edge=canonicalize(inputGraph.edge(e));g.setEdge(e,_.merge({},edgeDefaults,selectNumberAttrs(edge,edgeNumAttrs),_.pick(edge,edgeAttrs)))});return g} -/* - * This idea comes from the Gansner paper: to account for edge labels in our - * layout we split each rank in half by doubling minlen and halving ranksep. - * Then we can place labels at these mid-points between nodes. - * - * We also add some minimal padding to the width to push the label for the edge - * away from the edge itself a bit. - */function makeSpaceForEdgeLabels(g){var graph=g.graph();graph.ranksep/=2;_.forEach(g.edges(),function(e){var edge=g.edge(e);edge.minlen*=2;if(edge.labelpos.toLowerCase()!=="c"){if(graph.rankdir==="TB"||graph.rankdir==="BT"){edge.width+=edge.labeloffset}else{edge.height+=edge.labeloffset}}})} -/* - * Creates temporary dummy nodes that capture the rank in which each edge's - * label is going to, if it has one of non-zero width and height. We do this - * so that we can safely remove empty ranks while preserving balance for the - * label's position. - */function injectEdgeLabelProxies(g){_.forEach(g.edges(),function(e){var edge=g.edge(e);if(edge.width&&edge.height){var v=g.node(e.v);var w=g.node(e.w);var label={rank:(w.rank-v.rank)/2+v.rank,e:e};util.addDummyNode(g,"edge-proxy",label,"_ep")}})}function assignRankMinMax(g){var maxRank=0;_.forEach(g.nodes(),function(v){var node=g.node(v);if(node.borderTop){node.minRank=g.node(node.borderTop).rank;node.maxRank=g.node(node.borderBottom).rank;maxRank=_.max(maxRank,node.maxRank)}});g.graph().maxRank=maxRank}function removeEdgeLabelProxies(g){_.forEach(g.nodes(),function(v){var node=g.node(v);if(node.dummy==="edge-proxy"){g.edge(node.e).labelRank=node.rank;g.removeNode(v)}})}function translateGraph(g){var minX=Number.POSITIVE_INFINITY;var maxX=0;var minY=Number.POSITIVE_INFINITY;var maxY=0;var graphLabel=g.graph();var marginX=graphLabel.marginx||0;var marginY=graphLabel.marginy||0;function getExtremes(attrs){var x=attrs.x;var y=attrs.y;var w=attrs.width;var h=attrs.height;minX=Math.min(minX,x-w/2);maxX=Math.max(maxX,x+w/2);minY=Math.min(minY,y-h/2);maxY=Math.max(maxY,y+h/2)}_.forEach(g.nodes(),function(v){getExtremes(g.node(v))});_.forEach(g.edges(),function(e){var edge=g.edge(e);if(_.has(edge,"x")){getExtremes(edge)}});minX-=marginX;minY-=marginY;_.forEach(g.nodes(),function(v){var node=g.node(v);node.x-=minX;node.y-=minY});_.forEach(g.edges(),function(e){var edge=g.edge(e);_.forEach(edge.points,function(p){p.x-=minX;p.y-=minY});if(_.has(edge,"x")){edge.x-=minX}if(_.has(edge,"y")){edge.y-=minY}});graphLabel.width=maxX-minX+marginX;graphLabel.height=maxY-minY+marginY}function assignNodeIntersects(g){_.forEach(g.edges(),function(e){var edge=g.edge(e);var nodeV=g.node(e.v);var nodeW=g.node(e.w);var p1,p2;if(!edge.points){edge.points=[];p1=nodeW;p2=nodeV}else{p1=edge.points[0];p2=edge.points[edge.points.length-1]}edge.points.unshift(util.intersectRect(nodeV,p1));edge.points.push(util.intersectRect(nodeW,p2))})}function fixupEdgeLabelCoords(g){_.forEach(g.edges(),function(e){var edge=g.edge(e);if(_.has(edge,"x")){if(edge.labelpos==="l"||edge.labelpos==="r"){edge.width-=edge.labeloffset}switch(edge.labelpos){case"l":edge.x-=edge.width/2+edge.labeloffset;break;case"r":edge.x+=edge.width/2+edge.labeloffset;break}}})}function reversePointsForReversedEdges(g){_.forEach(g.edges(),function(e){var edge=g.edge(e);if(edge.reversed){edge.points.reverse()}})}function removeBorderNodes(g){_.forEach(g.nodes(),function(v){if(g.children(v).length){var node=g.node(v);var t=g.node(node.borderTop);var b=g.node(node.borderBottom);var l=g.node(_.last(node.borderLeft));var r=g.node(_.last(node.borderRight));node.width=Math.abs(r.x-l.x);node.height=Math.abs(b.y-t.y);node.x=l.x+node.width/2;node.y=t.y+node.height/2}});_.forEach(g.nodes(),function(v){if(g.node(v).dummy==="border"){g.removeNode(v)}})}function removeSelfEdges(g){_.forEach(g.edges(),function(e){if(e.v===e.w){var node=g.node(e.v);if(!node.selfEdges){node.selfEdges=[]}node.selfEdges.push({e:e,label:g.edge(e)});g.removeEdge(e)}})}function insertSelfEdges(g){var layers=util.buildLayerMatrix(g);_.forEach(layers,function(layer){var orderShift=0;_.forEach(layer,function(v,i){var node=g.node(v);node.order=i+orderShift;_.forEach(node.selfEdges,function(selfEdge){util.addDummyNode(g,"selfedge",{width:selfEdge.label.width,height:selfEdge.label.height,rank:node.rank,order:i+ ++orderShift,e:selfEdge.e,label:selfEdge.label},"_se")});delete node.selfEdges})})}function positionSelfEdges(g){_.forEach(g.nodes(),function(v){var node=g.node(v);if(node.dummy==="selfedge"){var selfNode=g.node(node.e.v);var x=selfNode.x+selfNode.width/2;var y=selfNode.y;var dx=node.x-x;var dy=selfNode.height/2;g.setEdge(node.e,node.label);g.removeNode(v);node.label.points=[{x:x+2*dx/3,y:y-dy},{x:x+5*dx/6,y:y-dy},{x:x+dx,y:y},{x:x+5*dx/6,y:y+dy},{x:x+2*dx/3,y:y+dy}];node.label.x=node.x;node.label.y=node.y}})}function selectNumberAttrs(obj,attrs){return _.mapValues(_.pick(obj,attrs),Number)}function canonicalize(attrs){var newAttrs={};_.forEach(attrs,function(v,k){newAttrs[k.toLowerCase()]=v});return newAttrs}},{"./acyclic":62,"./add-border-segments":63,"./coordinate-system":64,"./graphlib":67,"./lodash":70,"./nesting-graph":71,"./normalize":72,"./order":77,"./parent-dummy-chains":82,"./position":84,"./rank":86,"./util":89}],70:[function(require,module,exports){ -/* global window */ -var lodash;if(typeof require==="function"){try{lodash={cloneDeep:require("lodash/cloneDeep"),constant:require("lodash/constant"),defaults:require("lodash/defaults"),each:require("lodash/each"),filter:require("lodash/filter"),find:require("lodash/find"),flatten:require("lodash/flatten"),forEach:require("lodash/forEach"),forIn:require("lodash/forIn"),has:require("lodash/has"),isUndefined:require("lodash/isUndefined"),last:require("lodash/last"),map:require("lodash/map"),mapValues:require("lodash/mapValues"),max:require("lodash/max"),merge:require("lodash/merge"),min:require("lodash/min"),minBy:require("lodash/minBy"),now:require("lodash/now"),pick:require("lodash/pick"),range:require("lodash/range"),reduce:require("lodash/reduce"),sortBy:require("lodash/sortBy"),uniqueId:require("lodash/uniqueId"),values:require("lodash/values"),zipObject:require("lodash/zipObject")}}catch(e){ -// continue regardless of error -}}if(!lodash){lodash=window._}module.exports=lodash},{"lodash/cloneDeep":287,"lodash/constant":288,"lodash/defaults":289,"lodash/each":290,"lodash/filter":292,"lodash/find":293,"lodash/flatten":295,"lodash/forEach":296,"lodash/forIn":297,"lodash/has":299,"lodash/isUndefined":318,"lodash/last":321,"lodash/map":322,"lodash/mapValues":323,"lodash/max":324,"lodash/merge":326,"lodash/min":327,"lodash/minBy":328,"lodash/now":330,"lodash/pick":331,"lodash/range":333,"lodash/reduce":334,"lodash/sortBy":336,"lodash/uniqueId":346,"lodash/values":347,"lodash/zipObject":348}],71:[function(require,module,exports){var _=require("./lodash");var util=require("./util");module.exports={run:run,cleanup:cleanup}; -/* - * A nesting graph creates dummy nodes for the tops and bottoms of subgraphs, - * adds appropriate edges to ensure that all cluster nodes are placed between - * these boundries, and ensures that the graph is connected. - * - * In addition we ensure, through the use of the minlen property, that nodes - * and subgraph border nodes to not end up on the same rank. - * - * Preconditions: - * - * 1. Input graph is a DAG - * 2. Nodes in the input graph has a minlen attribute - * - * Postconditions: - * - * 1. Input graph is connected. - * 2. Dummy nodes are added for the tops and bottoms of subgraphs. - * 3. The minlen attribute for nodes is adjusted to ensure nodes do not - * get placed on the same rank as subgraph border nodes. - * - * The nesting graph idea comes from Sander, "Layout of Compound Directed - * Graphs." - */function run(g){var root=util.addDummyNode(g,"root",{},"_root");var depths=treeDepths(g);var height=_.max(_.values(depths))-1;// Note: depths is an Object not an array -var nodeSep=2*height+1;g.graph().nestingRoot=root; -// Multiply minlen by nodeSep to align nodes on non-border ranks. -_.forEach(g.edges(),function(e){g.edge(e).minlen*=nodeSep}); -// Calculate a weight that is sufficient to keep subgraphs vertically compact -var weight=sumWeights(g)+1; -// Create border nodes and link them up -_.forEach(g.children(),function(child){dfs(g,root,nodeSep,weight,height,depths,child)}); -// Save the multiplier for node layers for later removal of empty border -// layers. -g.graph().nodeRankFactor=nodeSep}function dfs(g,root,nodeSep,weight,height,depths,v){var children=g.children(v);if(!children.length){if(v!==root){g.setEdge(root,v,{weight:0,minlen:nodeSep})}return}var top=util.addBorderNode(g,"_bt");var bottom=util.addBorderNode(g,"_bb");var label=g.node(v);g.setParent(top,v);label.borderTop=top;g.setParent(bottom,v);label.borderBottom=bottom;_.forEach(children,function(child){dfs(g,root,nodeSep,weight,height,depths,child);var childNode=g.node(child);var childTop=childNode.borderTop?childNode.borderTop:child;var childBottom=childNode.borderBottom?childNode.borderBottom:child;var thisWeight=childNode.borderTop?weight:2*weight;var minlen=childTop!==childBottom?1:height-depths[v]+1;g.setEdge(top,childTop,{weight:thisWeight,minlen:minlen,nestingEdge:true});g.setEdge(childBottom,bottom,{weight:thisWeight,minlen:minlen,nestingEdge:true})});if(!g.parent(v)){g.setEdge(root,top,{weight:0,minlen:height+depths[v]})}}function treeDepths(g){var depths={};function dfs(v,depth){var children=g.children(v);if(children&&children.length){_.forEach(children,function(child){dfs(child,depth+1)})}depths[v]=depth}_.forEach(g.children(),function(v){dfs(v,1)});return depths}function sumWeights(g){return _.reduce(g.edges(),function(acc,e){return acc+g.edge(e).weight},0)}function cleanup(g){var graphLabel=g.graph();g.removeNode(graphLabel.nestingRoot);delete graphLabel.nestingRoot;_.forEach(g.edges(),function(e){var edge=g.edge(e);if(edge.nestingEdge){g.removeEdge(e)}})}},{"./lodash":70,"./util":89}],72:[function(require,module,exports){"use strict";var _=require("./lodash");var util=require("./util");module.exports={run:run,undo:undo}; -/* - * Breaks any long edges in the graph into short segments that span 1 layer - * each. This operation is undoable with the denormalize function. - * - * Pre-conditions: - * - * 1. The input graph is a DAG. - * 2. Each node in the graph has a "rank" property. - * - * Post-condition: - * - * 1. All edges in the graph have a length of 1. - * 2. Dummy nodes are added where edges have been split into segments. - * 3. The graph is augmented with a "dummyChains" attribute which contains - * the first dummy in each chain of dummy nodes produced. - */function run(g){g.graph().dummyChains=[];_.forEach(g.edges(),function(edge){normalizeEdge(g,edge)})}function normalizeEdge(g,e){var v=e.v;var vRank=g.node(v).rank;var w=e.w;var wRank=g.node(w).rank;var name=e.name;var edgeLabel=g.edge(e);var labelRank=edgeLabel.labelRank;if(wRank===vRank+1)return;g.removeEdge(e);var dummy,attrs,i;for(i=0,++vRank;vRank0){if(index%2){weightSum+=tree[index+1]}index=index-1>>1;tree[index]+=entry.weight}cc+=entry.weight*weightSum}));return cc}},{"../lodash":70}],77:[function(require,module,exports){"use strict";var _=require("../lodash");var initOrder=require("./init-order");var crossCount=require("./cross-count");var sortSubgraph=require("./sort-subgraph");var buildLayerGraph=require("./build-layer-graph");var addSubgraphConstraints=require("./add-subgraph-constraints");var Graph=require("../graphlib").Graph;var util=require("../util");module.exports=order; -/* - * Applies heuristics to minimize edge crossings in the graph and sets the best - * order solution as an order attribute on each node. - * - * Pre-conditions: - * - * 1. Graph must be DAG - * 2. Graph nodes must be objects with a "rank" attribute - * 3. Graph edges must have the "weight" attribute - * - * Post-conditions: - * - * 1. Graph nodes will have an "order" attribute based on the results of the - * algorithm. - */function order(g){var maxRank=util.maxRank(g),downLayerGraphs=buildLayerGraphs(g,_.range(1,maxRank+1),"inEdges"),upLayerGraphs=buildLayerGraphs(g,_.range(maxRank-1,-1,-1),"outEdges");var layering=initOrder(g);assignOrder(g,layering);var bestCC=Number.POSITIVE_INFINITY,best;for(var i=0,lastBest=0;lastBest<4;++i,++lastBest){sweepLayerGraphs(i%2?downLayerGraphs:upLayerGraphs,i%4>=2);layering=util.buildLayerMatrix(g);var cc=crossCount(g,layering);if(cc=vEntry.barycenter){mergeEntries(vEntry,uEntry)}}}function handleOut(vEntry){return function(wEntry){wEntry["in"].push(vEntry);if(--wEntry.indegree===0){sourceSet.push(wEntry)}}}while(sourceSet.length){var entry=sourceSet.pop();entries.push(entry);_.forEach(entry["in"].reverse(),handleIn(entry));_.forEach(entry.out,handleOut(entry))}return _.map(_.filter(entries,function(entry){return!entry.merged}),function(entry){return _.pick(entry,["vs","i","barycenter","weight"])})}function mergeEntries(target,source){var sum=0;var weight=0;if(target.weight){sum+=target.barycenter*target.weight;weight+=target.weight}if(source.weight){sum+=source.barycenter*source.weight;weight+=source.weight}target.vs=source.vs.concat(target.vs);target.barycenter=sum/weight;target.weight=weight;target.i=Math.min(source.i,target.i);source.merged=true}},{"../lodash":70}],80:[function(require,module,exports){var _=require("../lodash");var barycenter=require("./barycenter");var resolveConflicts=require("./resolve-conflicts");var sort=require("./sort");module.exports=sortSubgraph;function sortSubgraph(g,v,cg,biasRight){var movable=g.children(v);var node=g.node(v);var bl=node?node.borderLeft:undefined;var br=node?node.borderRight:undefined;var subgraphs={};if(bl){movable=_.filter(movable,function(w){return w!==bl&&w!==br})}var barycenters=barycenter(g,movable);_.forEach(barycenters,function(entry){if(g.children(entry.v).length){var subgraphResult=sortSubgraph(g,entry.v,cg,biasRight);subgraphs[entry.v]=subgraphResult;if(_.has(subgraphResult,"barycenter")){mergeBarycenters(entry,subgraphResult)}}});var entries=resolveConflicts(barycenters,cg);expandSubgraphs(entries,subgraphs);var result=sort(entries,biasRight);if(bl){result.vs=_.flatten([bl,result.vs,br],true);if(g.predecessors(bl).length){var blPred=g.node(g.predecessors(bl)[0]),brPred=g.node(g.predecessors(br)[0]);if(!_.has(result,"barycenter")){result.barycenter=0;result.weight=0}result.barycenter=(result.barycenter*result.weight+blPred.order+brPred.order)/(result.weight+2);result.weight+=2}}return result}function expandSubgraphs(entries,subgraphs){_.forEach(entries,function(entry){entry.vs=_.flatten(entry.vs.map(function(v){if(subgraphs[v]){return subgraphs[v].vs}return v}),true)})}function mergeBarycenters(target,other){if(!_.isUndefined(target.barycenter)){target.barycenter=(target.barycenter*target.weight+other.barycenter*other.weight)/(target.weight+other.weight);target.weight+=other.weight}else{target.barycenter=other.barycenter;target.weight=other.weight}}},{"../lodash":70,"./barycenter":74,"./resolve-conflicts":79,"./sort":81}],81:[function(require,module,exports){var _=require("../lodash");var util=require("../util");module.exports=sort;function sort(entries,biasRight){var parts=util.partition(entries,function(entry){return _.has(entry,"barycenter")});var sortable=parts.lhs,unsortable=_.sortBy(parts.rhs,function(entry){return-entry.i}),vs=[],sum=0,weight=0,vsIndex=0;sortable.sort(compareWithBias(!!biasRight));vsIndex=consumeUnsortable(vs,unsortable,vsIndex);_.forEach(sortable,function(entry){vsIndex+=entry.vs.length;vs.push(entry.vs);sum+=entry.barycenter*entry.weight;weight+=entry.weight;vsIndex=consumeUnsortable(vs,unsortable,vsIndex)});var result={vs:_.flatten(vs,true)};if(weight){result.barycenter=sum/weight;result.weight=weight}return result}function consumeUnsortable(vs,unsortable,index){var last;while(unsortable.length&&(last=_.last(unsortable)).i<=index){unsortable.pop();vs.push(last.vs);index++}return index}function compareWithBias(bias){return function(entryV,entryW){if(entryV.barycenterentryW.barycenter){return 1}return!bias?entryV.i-entryW.i:entryW.i-entryV.i}}},{"../lodash":70,"../util":89}],82:[function(require,module,exports){var _=require("./lodash");module.exports=parentDummyChains;function parentDummyChains(g){var postorderNums=postorder(g);_.forEach(g.graph().dummyChains,function(v){var node=g.node(v);var edgeObj=node.edgeObj;var pathData=findPath(g,postorderNums,edgeObj.v,edgeObj.w);var path=pathData.path;var lca=pathData.lca;var pathIdx=0;var pathV=path[pathIdx];var ascending=true;while(v!==edgeObj.w){node=g.node(v);if(ascending){while((pathV=path[pathIdx])!==lca&&g.node(pathV).maxRanklow||lim>postorderNums[parent].lim));lca=parent; -// Traverse from w to LCA -parent=w;while((parent=g.parent(parent))!==lca){wPath.push(parent)}return{path:vPath.concat(wPath.reverse()),lca:lca}}function postorder(g){var result={};var lim=0;function dfs(v){var low=lim;_.forEach(g.children(v),dfs);result[v]={low:low,lim:lim++}}_.forEach(g.children(),dfs);return result}},{"./lodash":70}],83:[function(require,module,exports){"use strict";var _=require("../lodash");var Graph=require("../graphlib").Graph;var util=require("../util"); -/* - * This module provides coordinate assignment based on Brandes and Köpf, "Fast - * and Simple Horizontal Coordinate Assignment." - */module.exports={positionX:positionX,findType1Conflicts:findType1Conflicts,findType2Conflicts:findType2Conflicts,addConflict:addConflict,hasConflict:hasConflict,verticalAlignment:verticalAlignment,horizontalCompaction:horizontalCompaction,alignCoordinates:alignCoordinates,findSmallestWidthAlignment:findSmallestWidthAlignment,balance:balance}; -/* - * Marks all edges in the graph with a type-1 conflict with the "type1Conflict" - * property. A type-1 conflict is one where a non-inner segment crosses an - * inner segment. An inner segment is an edge with both incident nodes marked - * with the "dummy" property. - * - * This algorithm scans layer by layer, starting with the second, for type-1 - * conflicts between the current layer and the previous layer. For each layer - * it scans the nodes from left to right until it reaches one that is incident - * on an inner segment. It then scans predecessors to determine if they have - * edges that cross that inner segment. At the end a final scan is done for all - * nodes on the current rank to see if they cross the last visited inner - * segment. - * - * This algorithm (safely) assumes that a dummy node will only be incident on a - * single node in the layers being scanned. - */function findType1Conflicts(g,layering){var conflicts={};function visitLayer(prevLayer,layer){var -// last visited node in the previous layer that is incident on an inner -// segment. -k0=0, -// Tracks the last node in this layer scanned for crossings with a type-1 -// segment. -scanPos=0,prevLayerLength=prevLayer.length,lastNode=_.last(layer);_.forEach(layer,function(v,i){var w=findOtherInnerSegmentNode(g,v),k1=w?g.node(w).order:prevLayerLength;if(w||v===lastNode){_.forEach(layer.slice(scanPos,i+1),function(scanNode){_.forEach(g.predecessors(scanNode),function(u){var uLabel=g.node(u),uPos=uLabel.order;if((uPosnextNorthBorder)){addConflict(conflicts,u,v)}})}})}function visitLayer(north,south){var prevNorthPos=-1,nextNorthPos,southPos=0;_.forEach(south,function(v,southLookahead){if(g.node(v).dummy==="border"){var predecessors=g.predecessors(v);if(predecessors.length){nextNorthPos=g.node(predecessors[0]).order;scan(south,southPos,southLookahead,prevNorthPos,nextNorthPos);southPos=southLookahead;prevNorthPos=nextNorthPos}}scan(south,southPos,south.length,nextNorthPos,north.length)});return south}_.reduce(layering,visitLayer);return conflicts}function findOtherInnerSegmentNode(g,v){if(g.node(v).dummy){return _.find(g.predecessors(v),function(u){return g.node(u).dummy})}}function addConflict(conflicts,v,w){if(v>w){var tmp=v;v=w;w=tmp}var conflictsV=conflicts[v];if(!conflictsV){conflicts[v]=conflictsV={}}conflictsV[w]=true}function hasConflict(conflicts,v,w){if(v>w){var tmp=v;v=w;w=tmp}return _.has(conflicts[v],w)} -/* - * Try to align nodes into vertical "blocks" where possible. This algorithm - * attempts to align a node with one of its median neighbors. If the edge - * connecting a neighbor is a type-1 conflict then we ignore that possibility. - * If a previous node has already formed a block with a node after the node - * we're trying to form a block with, we also ignore that possibility - our - * blocks would be split in that scenario. - */function verticalAlignment(g,layering,conflicts,neighborFn){var root={},align={},pos={}; -// We cache the position here based on the layering because the graph and -// layering may be out of sync. The layering matrix is manipulated to -// generate different extreme alignments. -_.forEach(layering,function(layer){_.forEach(layer,function(v,order){root[v]=v;align[v]=v;pos[v]=order})});_.forEach(layering,function(layer){var prevIdx=-1;_.forEach(layer,function(v){var ws=neighborFn(v);if(ws.length){ws=_.sortBy(ws,function(w){return pos[w]});var mp=(ws.length-1)/2;for(var i=Math.floor(mp),il=Math.ceil(mp);i<=il;++i){var w=ws[i];if(align[v]===v&&prevIdxwLabel.lim){tailLabel=wLabel;flip=true}var candidates=_.filter(g.edges(),function(edge){return flip===isDescendant(t,t.node(edge.v),tailLabel)&&flip!==isDescendant(t,t.node(edge.w),tailLabel)});return _.minBy(candidates,function(edge){return slack(g,edge)})}function exchangeEdges(t,g,e,f){var v=e.v;var w=e.w;t.removeEdge(v,w);t.setEdge(f.v,f.w,{});initLowLimValues(t);initCutValues(t,g);updateRanks(t,g)}function updateRanks(t,g){var root=_.find(t.nodes(),function(v){return!g.node(v).parent});var vs=preorder(t,root);vs=vs.slice(1);_.forEach(vs,function(v){var parent=t.node(v).parent,edge=g.edge(v,parent),flipped=false;if(!edge){edge=g.edge(parent,v);flipped=true}g.node(v).rank=g.node(parent).rank+(flipped?edge.minlen:-edge.minlen)})} -/* - * Returns true if the edge is in the tree. - */function isTreeEdge(tree,u,v){return tree.hasEdge(u,v)} -/* - * Returns true if the specified node is descendant of the root node per the - * assigned low and lim attributes in the tree. - */function isDescendant(tree,vLabel,rootLabel){return rootLabel.low<=vLabel.lim&&vLabel.lim<=rootLabel.lim}},{"../graphlib":67,"../lodash":70,"../util":89,"./feasible-tree":85,"./util":88}],88:[function(require,module,exports){"use strict";var _=require("../lodash");module.exports={longestPath:longestPath,slack:slack}; -/* - * Initializes ranks for the input graph using the longest path algorithm. This - * algorithm scales well and is fast in practice, it yields rather poor - * solutions. Nodes are pushed to the lowest layer possible, leaving the bottom - * ranks wide and leaving edges longer than necessary. However, due to its - * speed, this algorithm is good for getting an initial ranking that can be fed - * into other algorithms. - * - * This algorithm does not normalize layers because it will be used by other - * algorithms in most cases. If using this algorithm directly, be sure to - * run normalize at the end. - * - * Pre-conditions: - * - * 1. Input graph is a DAG. - * 2. Input graph node labels can be assigned properties. - * - * Post-conditions: - * - * 1. Each node will be assign an (unnormalized) "rank" property. - */function longestPath(g){var visited={};function dfs(v){var label=g.node(v);if(_.has(visited,v)){return label.rank}visited[v]=true;var rank=_.min(_.map(g.outEdges(v),function(e){return dfs(e.w)-g.edge(e).minlen}));if(rank===Number.POSITIVE_INFINITY||// return value of _.map([]) for Lodash 3 -rank===undefined||// return value of _.map([]) for Lodash 4 -rank===null){// return value of _.map([null]) -rank=0}return label.rank=rank}_.forEach(g.sources(),dfs)} -/* - * Returns the amount of slack for the given edge. The slack is defined as the - * difference between the length of the edge and its minimum length. - */function slack(g,e){return g.node(e.w).rank-g.node(e.v).rank-g.edge(e).minlen}},{"../lodash":70}],89:[function(require,module,exports){ -/* eslint "no-console": off */ -"use strict";var _=require("./lodash");var Graph=require("./graphlib").Graph;module.exports={addDummyNode:addDummyNode,simplify:simplify,asNonCompoundGraph:asNonCompoundGraph,successorWeights:successorWeights,predecessorWeights:predecessorWeights,intersectRect:intersectRect,buildLayerMatrix:buildLayerMatrix,normalizeRanks:normalizeRanks,removeEmptyRanks:removeEmptyRanks,addBorderNode:addBorderNode,maxRank:maxRank,partition:partition,time:time,notime:notime}; -/* - * Adds a dummy node to the graph and return v. - */function addDummyNode(g,type,attrs,name){var v;do{v=_.uniqueId(name)}while(g.hasNode(v));attrs.dummy=type;g.setNode(v,attrs);return v} -/* - * Returns a new graph with only simple edges. Handles aggregation of data - * associated with multi-edges. - */function simplify(g){var simplified=(new Graph).setGraph(g.graph());_.forEach(g.nodes(),function(v){simplified.setNode(v,g.node(v))});_.forEach(g.edges(),function(e){var simpleLabel=simplified.edge(e.v,e.w)||{weight:0,minlen:1};var label=g.edge(e);simplified.setEdge(e.v,e.w,{weight:simpleLabel.weight+label.weight,minlen:Math.max(simpleLabel.minlen,label.minlen)})});return simplified}function asNonCompoundGraph(g){var simplified=new Graph({multigraph:g.isMultigraph()}).setGraph(g.graph());_.forEach(g.nodes(),function(v){if(!g.children(v).length){simplified.setNode(v,g.node(v))}});_.forEach(g.edges(),function(e){simplified.setEdge(e,g.edge(e))});return simplified}function successorWeights(g){var weightMap=_.map(g.nodes(),function(v){var sucs={};_.forEach(g.outEdges(v),function(e){sucs[e.w]=(sucs[e.w]||0)+g.edge(e).weight});return sucs});return _.zipObject(g.nodes(),weightMap)}function predecessorWeights(g){var weightMap=_.map(g.nodes(),function(v){var preds={};_.forEach(g.inEdges(v),function(e){preds[e.v]=(preds[e.v]||0)+g.edge(e).weight});return preds});return _.zipObject(g.nodes(),weightMap)} -/* - * Finds where a line starting at point ({x, y}) would intersect a rectangle - * ({x, y, width, height}) if it were pointing at the rectangle's center. - */function intersectRect(rect,point){var x=rect.x;var y=rect.y; -// Rectangle intersection algorithm from: -// http://math.stackexchange.com/questions/108113/find-edge-between-two-boxes -var dx=point.x-x;var dy=point.y-y;var w=rect.width/2;var h=rect.height/2;if(!dx&&!dy){throw new Error("Not possible to find intersection inside of the rectangle")}var sx,sy;if(Math.abs(dy)*w>Math.abs(dx)*h){ -// Intersection is top or bottom of rect. -if(dy<0){h=-h}sx=h*dx/dy;sy=h}else{ -// Intersection is left or right of rect. -if(dx<0){w=-w}sx=w;sy=w*dy/dx}return{x:x+sx,y:y+sy}} -/* - * Given a DAG with each node assigned "rank" and "order" properties, this - * function will produce a matrix with the ids of each node. - */function buildLayerMatrix(g){var layering=_.map(_.range(maxRank(g)+1),function(){return[]});_.forEach(g.nodes(),function(v){var node=g.node(v);var rank=node.rank;if(!_.isUndefined(rank)){layering[rank][node.order]=v}});return layering} -/* - * Adjusts the ranks for all nodes in the graph such that all nodes v have - * rank(v) >= 0 and at least one node w has rank(w) = 0. - */function normalizeRanks(g){var min=_.min(_.map(g.nodes(),function(v){return g.node(v).rank}));_.forEach(g.nodes(),function(v){var node=g.node(v);if(_.has(node,"rank")){node.rank-=min}})}function removeEmptyRanks(g){ -// Ranks may not start at 0, so we need to offset them -var offset=_.min(_.map(g.nodes(),function(v){return g.node(v).rank}));var layers=[];_.forEach(g.nodes(),function(v){var rank=g.node(v).rank-offset;if(!layers[rank]){layers[rank]=[]}layers[rank].push(v)});var delta=0;var nodeRankFactor=g.graph().nodeRankFactor;_.forEach(layers,function(vs,i){if(_.isUndefined(vs)&&i%nodeRankFactor!==0){--delta}else if(delta){_.forEach(vs,function(v){g.node(v).rank+=delta})}})}function addBorderNode(g,prefix,rank,order){var node={width:0,height:0};if(arguments.length>=4){node.rank=rank;node.order=order}return addDummyNode(g,"border",node,prefix)}function maxRank(g){return _.max(_.map(g.nodes(),function(v){var rank=g.node(v).rank;if(!_.isUndefined(rank)){return rank}}))} -/* - * Partition a collection into two groups: `lhs` and `rhs`. If the supplied - * function returns true for an entry it goes into `lhs`. Otherwise it goes - * into `rhs. - */function partition(collection,fn){var result={lhs:[],rhs:[]};_.forEach(collection,function(value){if(fn(value)){result.lhs.push(value)}else{result.rhs.push(value)}});return result} -/* - * Returns a new function that wraps `fn` with a timer. The wrapper logs the - * time it takes to execute the function. - */function time(name,fn){var start=_.now();try{return fn()}finally{console.log(name+" time: "+(_.now()-start)+"ms")}}function notime(name,fn){return fn()}},{"./graphlib":67,"./lodash":70}],90:[function(require,module,exports){module.exports="0.8.5"},{}],91:[function(require,module,exports){ -/** - * Copyright (c) 2014, Chris Pettitt - * All rights reserved. - * - * 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 the copyright holder 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. - */ -var lib=require("./lib");module.exports={Graph:lib.Graph,json:require("./lib/json"),alg:require("./lib/alg"),version:lib.version}},{"./lib":107,"./lib/alg":98,"./lib/json":108}],92:[function(require,module,exports){var _=require("../lodash");module.exports=components;function components(g){var visited={};var cmpts=[];var cmpt;function dfs(v){if(_.has(visited,v))return;visited[v]=true;cmpt.push(v);_.each(g.successors(v),dfs);_.each(g.predecessors(v),dfs)}_.each(g.nodes(),function(v){cmpt=[];dfs(v);if(cmpt.length){cmpts.push(cmpt)}});return cmpts}},{"../lodash":109}],93:[function(require,module,exports){var _=require("../lodash");module.exports=dfs; -/* - * A helper that preforms a pre- or post-order traversal on the input graph - * and returns the nodes in the order they were visited. If the graph is - * undirected then this algorithm will navigate using neighbors. If the graph - * is directed then this algorithm will navigate using successors. - * - * Order must be one of "pre" or "post". - */function dfs(g,vs,order){if(!_.isArray(vs)){vs=[vs]}var navigation=(g.isDirected()?g.successors:g.neighbors).bind(g);var acc=[];var visited={};_.each(vs,function(v){if(!g.hasNode(v)){throw new Error("Graph does not have node: "+v)}doDfs(g,v,order==="post",visited,navigation,acc)});return acc}function doDfs(g,v,postorder,visited,navigation,acc){if(!_.has(visited,v)){visited[v]=true;if(!postorder){acc.push(v)}_.each(navigation(v),function(w){doDfs(g,w,postorder,visited,navigation,acc)});if(postorder){acc.push(v)}}}},{"../lodash":109}],94:[function(require,module,exports){var dijkstra=require("./dijkstra");var _=require("../lodash");module.exports=dijkstraAll;function dijkstraAll(g,weightFunc,edgeFunc){return _.transform(g.nodes(),function(acc,v){acc[v]=dijkstra(g,v,weightFunc,edgeFunc)},{})}},{"../lodash":109,"./dijkstra":95}],95:[function(require,module,exports){var _=require("../lodash");var PriorityQueue=require("../data/priority-queue");module.exports=dijkstra;var DEFAULT_WEIGHT_FUNC=_.constant(1);function dijkstra(g,source,weightFn,edgeFn){return runDijkstra(g,String(source),weightFn||DEFAULT_WEIGHT_FUNC,edgeFn||function(v){return g.outEdges(v)})}function runDijkstra(g,source,weightFn,edgeFn){var results={};var pq=new PriorityQueue;var v,vEntry;var updateNeighbors=function(edge){var w=edge.v!==v?edge.v:edge.w;var wEntry=results[w];var weight=weightFn(edge);var distance=vEntry.distance+weight;if(weight<0){throw new Error("dijkstra does not allow negative edge weights. "+"Bad edge: "+edge+" Weight: "+weight)}if(distance0){v=pq.removeMin();vEntry=results[v];if(vEntry.distance===Number.POSITIVE_INFINITY){break}edgeFn(v).forEach(updateNeighbors)}return results}},{"../data/priority-queue":105,"../lodash":109}],96:[function(require,module,exports){var _=require("../lodash");var tarjan=require("./tarjan");module.exports=findCycles;function findCycles(g){return _.filter(tarjan(g),function(cmpt){return cmpt.length>1||cmpt.length===1&&g.hasEdge(cmpt[0],cmpt[0])})}},{"../lodash":109,"./tarjan":103}],97:[function(require,module,exports){var _=require("../lodash");module.exports=floydWarshall;var DEFAULT_WEIGHT_FUNC=_.constant(1);function floydWarshall(g,weightFn,edgeFn){return runFloydWarshall(g,weightFn||DEFAULT_WEIGHT_FUNC,edgeFn||function(v){return g.outEdges(v)})}function runFloydWarshall(g,weightFn,edgeFn){var results={};var nodes=g.nodes();nodes.forEach(function(v){results[v]={};results[v][v]={distance:0};nodes.forEach(function(w){if(v!==w){results[v][w]={distance:Number.POSITIVE_INFINITY}}});edgeFn(v).forEach(function(edge){var w=edge.v===v?edge.w:edge.v;var d=weightFn(edge);results[v][w]={distance:d,predecessor:v}})});nodes.forEach(function(k){var rowK=results[k];nodes.forEach(function(i){var rowI=results[i];nodes.forEach(function(j){var ik=rowI[k];var kj=rowK[j];var ij=rowI[j];var altDistance=ik.distance+kj.distance;if(altDistance0){v=pq.removeMin();if(_.has(parents,v)){result.setEdge(v,parents[v])}else if(init){throw new Error("Input graph is not connected: "+g)}else{init=true}g.nodeEdges(v).forEach(updateNeighbors)}return result}},{"../data/priority-queue":105,"../graph":106,"../lodash":109}],103:[function(require,module,exports){var _=require("../lodash");module.exports=tarjan;function tarjan(g){var index=0;var stack=[];var visited={};// node id -> { onStack, lowlink, index } -var results=[];function dfs(v){var entry=visited[v]={onStack:true,lowlink:index,index:index++};stack.push(v);g.successors(v).forEach(function(w){if(!_.has(visited,w)){dfs(w);entry.lowlink=Math.min(entry.lowlink,visited[w].lowlink)}else if(visited[w].onStack){entry.lowlink=Math.min(entry.lowlink,visited[w].index)}});if(entry.lowlink===entry.index){var cmpt=[];var w;do{w=stack.pop();visited[w].onStack=false;cmpt.push(w)}while(v!==w);results.push(cmpt)}}g.nodes().forEach(function(v){if(!_.has(visited,v)){dfs(v)}});return results}},{"../lodash":109}],104:[function(require,module,exports){var _=require("../lodash");module.exports=topsort;topsort.CycleException=CycleException;function topsort(g){var visited={};var stack={};var results=[];function visit(node){if(_.has(stack,node)){throw new CycleException}if(!_.has(visited,node)){stack[node]=true;visited[node]=true;_.each(g.predecessors(node),visit);delete stack[node];results.push(node)}}_.each(g.sinks(),visit);if(_.size(visited)!==g.nodeCount()){throw new CycleException}return results}function CycleException(){}CycleException.prototype=new Error;// must be an instance of Error to pass testing -},{"../lodash":109}],105:[function(require,module,exports){var _=require("../lodash");module.exports=PriorityQueue; -/** - * A min-priority queue data structure. This algorithm is derived from Cormen, - * et al., "Introduction to Algorithms". The basic idea of a min-priority - * queue is that you can efficiently (in O(1) time) get the smallest key in - * the queue. Adding and removing elements takes O(log n) time. A key can - * have its priority decreased in O(log n) time. - */function PriorityQueue(){this._arr=[];this._keyIndices={}} -/** - * Returns the number of elements in the queue. Takes `O(1)` time. - */PriorityQueue.prototype.size=function(){return this._arr.length}; -/** - * Returns the keys that are in the queue. Takes `O(n)` time. - */PriorityQueue.prototype.keys=function(){return this._arr.map(function(x){return x.key})}; -/** - * Returns `true` if **key** is in the queue and `false` if not. - */PriorityQueue.prototype.has=function(key){return _.has(this._keyIndices,key)}; -/** - * Returns the priority for **key**. If **key** is not present in the queue - * then this function returns `undefined`. Takes `O(1)` time. - * - * @param {Object} key - */PriorityQueue.prototype.priority=function(key){var index=this._keyIndices[key];if(index!==undefined){return this._arr[index].priority}}; -/** - * Returns the key for the minimum element in this queue. If the queue is - * empty this function throws an Error. Takes `O(1)` time. - */PriorityQueue.prototype.min=function(){if(this.size()===0){throw new Error("Queue underflow")}return this._arr[0].key}; -/** - * Inserts a new key into the priority queue. If the key already exists in - * the queue this function returns `false`; otherwise it will return `true`. - * Takes `O(n)` time. - * - * @param {Object} key the key to add - * @param {Number} priority the initial priority for the key - */PriorityQueue.prototype.add=function(key,priority){var keyIndices=this._keyIndices;key=String(key);if(!_.has(keyIndices,key)){var arr=this._arr;var index=arr.length;keyIndices[key]=index;arr.push({key:key,priority:priority});this._decrease(index);return true}return false}; -/** - * Removes and returns the smallest key in the queue. Takes `O(log n)` time. - */PriorityQueue.prototype.removeMin=function(){this._swap(0,this._arr.length-1);var min=this._arr.pop();delete this._keyIndices[min.key];this._heapify(0);return min.key}; -/** - * Decreases the priority for **key** to **priority**. If the new priority is - * greater than the previous priority, this function will throw an Error. - * - * @param {Object} key the key for which to raise priority - * @param {Number} priority the new priority for the key - */PriorityQueue.prototype.decrease=function(key,priority){var index=this._keyIndices[key];if(priority>this._arr[index].priority){throw new Error("New priority is greater than current priority. "+"Key: "+key+" Old: "+this._arr[index].priority+" New: "+priority)}this._arr[index].priority=priority;this._decrease(index)};PriorityQueue.prototype._heapify=function(i){var arr=this._arr;var l=2*i;var r=l+1;var largest=i;if(l>1;if(arr[parent].priority label -this._nodes={};if(this._isCompound){ -// v -> parent -this._parent={}; -// v -> children -this._children={};this._children[GRAPH_NODE]={}} -// v -> edgeObj -this._in={}; -// u -> v -> Number -this._preds={}; -// v -> edgeObj -this._out={}; -// v -> w -> Number -this._sucs={}; -// e -> edgeObj -this._edgeObjs={}; -// e -> label -this._edgeLabels={}} -/* Number of nodes in the graph. Should only be changed by the implementation. */Graph.prototype._nodeCount=0; -/* Number of edges in the graph. Should only be changed by the implementation. */Graph.prototype._edgeCount=0; -/* === Graph functions ========= */Graph.prototype.isDirected=function(){return this._isDirected};Graph.prototype.isMultigraph=function(){return this._isMultigraph};Graph.prototype.isCompound=function(){return this._isCompound};Graph.prototype.setGraph=function(label){this._label=label;return this};Graph.prototype.graph=function(){return this._label}; -/* === Node functions ========== */Graph.prototype.setDefaultNodeLabel=function(newDefault){if(!_.isFunction(newDefault)){newDefault=_.constant(newDefault)}this._defaultNodeLabelFn=newDefault;return this};Graph.prototype.nodeCount=function(){return this._nodeCount};Graph.prototype.nodes=function(){return _.keys(this._nodes)};Graph.prototype.sources=function(){var self=this;return _.filter(this.nodes(),function(v){return _.isEmpty(self._in[v])})};Graph.prototype.sinks=function(){var self=this;return _.filter(this.nodes(),function(v){return _.isEmpty(self._out[v])})};Graph.prototype.setNodes=function(vs,value){var args=arguments;var self=this;_.each(vs,function(v){if(args.length>1){self.setNode(v,value)}else{self.setNode(v)}});return this};Graph.prototype.setNode=function(v,value){if(_.has(this._nodes,v)){if(arguments.length>1){this._nodes[v]=value}return this}this._nodes[v]=arguments.length>1?value:this._defaultNodeLabelFn(v);if(this._isCompound){this._parent[v]=GRAPH_NODE;this._children[v]={};this._children[GRAPH_NODE][v]=true}this._in[v]={};this._preds[v]={};this._out[v]={};this._sucs[v]={};++this._nodeCount;return this};Graph.prototype.node=function(v){return this._nodes[v]};Graph.prototype.hasNode=function(v){return _.has(this._nodes,v)};Graph.prototype.removeNode=function(v){var self=this;if(_.has(this._nodes,v)){var removeEdge=function(e){self.removeEdge(self._edgeObjs[e])};delete this._nodes[v];if(this._isCompound){this._removeFromParentsChildList(v);delete this._parent[v];_.each(this.children(v),function(child){self.setParent(child)});delete this._children[v]}_.each(_.keys(this._in[v]),removeEdge);delete this._in[v];delete this._preds[v];_.each(_.keys(this._out[v]),removeEdge);delete this._out[v];delete this._sucs[v];--this._nodeCount}return this};Graph.prototype.setParent=function(v,parent){if(!this._isCompound){throw new Error("Cannot set parent in a non-compound graph")}if(_.isUndefined(parent)){parent=GRAPH_NODE}else{ -// Coerce parent to string -parent+="";for(var ancestor=parent;!_.isUndefined(ancestor);ancestor=this.parent(ancestor)){if(ancestor===v){throw new Error("Setting "+parent+" as parent of "+v+" would create a cycle")}}this.setNode(parent)}this.setNode(v);this._removeFromParentsChildList(v);this._parent[v]=parent;this._children[parent][v]=true;return this};Graph.prototype._removeFromParentsChildList=function(v){delete this._children[this._parent[v]][v]};Graph.prototype.parent=function(v){if(this._isCompound){var parent=this._parent[v];if(parent!==GRAPH_NODE){return parent}}};Graph.prototype.children=function(v){if(_.isUndefined(v)){v=GRAPH_NODE}if(this._isCompound){var children=this._children[v];if(children){return _.keys(children)}}else if(v===GRAPH_NODE){return this.nodes()}else if(this.hasNode(v)){return[]}};Graph.prototype.predecessors=function(v){var predsV=this._preds[v];if(predsV){return _.keys(predsV)}};Graph.prototype.successors=function(v){var sucsV=this._sucs[v];if(sucsV){return _.keys(sucsV)}};Graph.prototype.neighbors=function(v){var preds=this.predecessors(v);if(preds){return _.union(preds,this.successors(v))}};Graph.prototype.isLeaf=function(v){var neighbors;if(this.isDirected()){neighbors=this.successors(v)}else{neighbors=this.neighbors(v)}return neighbors.length===0};Graph.prototype.filterNodes=function(filter){var copy=new this.constructor({directed:this._isDirected,multigraph:this._isMultigraph,compound:this._isCompound});copy.setGraph(this.graph());var self=this;_.each(this._nodes,function(value,v){if(filter(v)){copy.setNode(v,value)}});_.each(this._edgeObjs,function(e){if(copy.hasNode(e.v)&©.hasNode(e.w)){copy.setEdge(e,self.edge(e))}});var parents={};function findParent(v){var parent=self.parent(v);if(parent===undefined||copy.hasNode(parent)){parents[v]=parent;return parent}else if(parent in parents){return parents[parent]}else{return findParent(parent)}}if(this._isCompound){_.each(copy.nodes(),function(v){copy.setParent(v,findParent(v))})}return copy}; -/* === Edge functions ========== */Graph.prototype.setDefaultEdgeLabel=function(newDefault){if(!_.isFunction(newDefault)){newDefault=_.constant(newDefault)}this._defaultEdgeLabelFn=newDefault;return this};Graph.prototype.edgeCount=function(){return this._edgeCount};Graph.prototype.edges=function(){return _.values(this._edgeObjs)};Graph.prototype.setPath=function(vs,value){var self=this;var args=arguments;_.reduce(vs,function(v,w){if(args.length>1){self.setEdge(v,w,value)}else{self.setEdge(v,w)}return w});return this}; -/* - * setEdge(v, w, [value, [name]]) - * setEdge({ v, w, [name] }, [value]) - */Graph.prototype.setEdge=function(){var v,w,name,value;var valueSpecified=false;var arg0=arguments[0];if(typeof arg0==="object"&&arg0!==null&&"v"in arg0){v=arg0.v;w=arg0.w;name=arg0.name;if(arguments.length===2){value=arguments[1];valueSpecified=true}}else{v=arg0;w=arguments[1];name=arguments[3];if(arguments.length>2){value=arguments[2];valueSpecified=true}}v=""+v;w=""+w;if(!_.isUndefined(name)){name=""+name}var e=edgeArgsToId(this._isDirected,v,w,name);if(_.has(this._edgeLabels,e)){if(valueSpecified){this._edgeLabels[e]=value}return this}if(!_.isUndefined(name)&&!this._isMultigraph){throw new Error("Cannot set a named edge when isMultigraph = false")} -// It didn't exist, so we need to create it. -// First ensure the nodes exist. -this.setNode(v);this.setNode(w);this._edgeLabels[e]=valueSpecified?value:this._defaultEdgeLabelFn(v,w,name);var edgeObj=edgeArgsToObj(this._isDirected,v,w,name); -// Ensure we add undirected edges in a consistent way. -v=edgeObj.v;w=edgeObj.w;Object.freeze(edgeObj);this._edgeObjs[e]=edgeObj;incrementOrInitEntry(this._preds[w],v);incrementOrInitEntry(this._sucs[v],w);this._in[w][e]=edgeObj;this._out[v][e]=edgeObj;this._edgeCount++;return this};Graph.prototype.edge=function(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);return this._edgeLabels[e]};Graph.prototype.hasEdge=function(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);return _.has(this._edgeLabels,e)};Graph.prototype.removeEdge=function(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);var edge=this._edgeObjs[e];if(edge){v=edge.v;w=edge.w;delete this._edgeLabels[e];delete this._edgeObjs[e];decrementOrRemoveEntry(this._preds[w],v);decrementOrRemoveEntry(this._sucs[v],w);delete this._in[w][e];delete this._out[v][e];this._edgeCount--}return this};Graph.prototype.inEdges=function(v,u){var inV=this._in[v];if(inV){var edges=_.values(inV);if(!u){return edges}return _.filter(edges,function(edge){return edge.v===u})}};Graph.prototype.outEdges=function(v,w){var outV=this._out[v];if(outV){var edges=_.values(outV);if(!w){return edges}return _.filter(edges,function(edge){return edge.w===w})}};Graph.prototype.nodeEdges=function(v,w){var inEdges=this.inEdges(v,w);if(inEdges){return inEdges.concat(this.outEdges(v,w))}};function incrementOrInitEntry(map,k){if(map[k]){map[k]++}else{map[k]=1}}function decrementOrRemoveEntry(map,k){if(!--map[k]){delete map[k]}}function edgeArgsToId(isDirected,v_,w_,name){var v=""+v_;var w=""+w_;if(!isDirected&&v>w){var tmp=v;v=w;w=tmp}return v+EDGE_KEY_DELIM+w+EDGE_KEY_DELIM+(_.isUndefined(name)?DEFAULT_EDGE_NAME:name)}function edgeArgsToObj(isDirected,v_,w_,name){var v=""+v_;var w=""+w_;if(!isDirected&&v>w){var tmp=v;v=w;w=tmp}var edgeObj={v:v,w:w};if(name){edgeObj.name=name}return edgeObj}function edgeObjToId(isDirected,edgeObj){return edgeArgsToId(isDirected,edgeObj.v,edgeObj.w,edgeObj.name)}},{"./lodash":109}],107:[function(require,module,exports){ -// Includes only the "core" of graphlib -module.exports={Graph:require("./graph"),version:require("./version")}},{"./graph":106,"./version":110}],108:[function(require,module,exports){var _=require("./lodash");var Graph=require("./graph");module.exports={write:write,read:read};function write(g){var json={options:{directed:g.isDirected(),multigraph:g.isMultigraph(),compound:g.isCompound()},nodes:writeNodes(g),edges:writeEdges(g)};if(!_.isUndefined(g.graph())){json.value=_.clone(g.graph())}return json}function writeNodes(g){return _.map(g.nodes(),function(v){var nodeValue=g.node(v);var parent=g.parent(v);var node={v:v};if(!_.isUndefined(nodeValue)){node.value=nodeValue}if(!_.isUndefined(parent)){node.parent=parent}return node})}function writeEdges(g){return _.map(g.edges(),function(e){var edgeValue=g.edge(e);var edge={v:e.v,w:e.w};if(!_.isUndefined(e.name)){edge.name=e.name}if(!_.isUndefined(edgeValue)){edge.value=edgeValue}return edge})}function read(json){var g=new Graph(json.options).setGraph(json.value);_.each(json.nodes,function(entry){g.setNode(entry.v,entry.value);if(entry.parent){g.setParent(entry.v,entry.parent)}});_.each(json.edges,function(entry){g.setEdge({v:entry.v,w:entry.w,name:entry.name},entry.value)});return g}},{"./graph":106,"./lodash":109}],109:[function(require,module,exports){ -/* global window */ -var lodash;if(typeof require==="function"){try{lodash={clone:require("lodash/clone"),constant:require("lodash/constant"),each:require("lodash/each"),filter:require("lodash/filter"),has:require("lodash/has"),isArray:require("lodash/isArray"),isEmpty:require("lodash/isEmpty"),isFunction:require("lodash/isFunction"),isUndefined:require("lodash/isUndefined"),keys:require("lodash/keys"),map:require("lodash/map"),reduce:require("lodash/reduce"),size:require("lodash/size"),transform:require("lodash/transform"),union:require("lodash/union"),values:require("lodash/values")}}catch(e){ -// continue regardless of error -}}if(!lodash){lodash=window._}module.exports=lodash},{"lodash/clone":286,"lodash/constant":288,"lodash/each":290,"lodash/filter":292,"lodash/has":299,"lodash/isArray":303,"lodash/isEmpty":307,"lodash/isFunction":308,"lodash/isUndefined":318,"lodash/keys":319,"lodash/map":322,"lodash/reduce":334,"lodash/size":335,"lodash/transform":344,"lodash/union":345,"lodash/values":347}],110:[function(require,module,exports){module.exports="2.1.8"},{}],111:[function(require,module,exports){var getNative=require("./_getNative"),root=require("./_root"); -/* Built-in method references that are verified to be native. */var DataView=getNative(root,"DataView");module.exports=DataView},{"./_getNative":223,"./_root":268}],112:[function(require,module,exports){var hashClear=require("./_hashClear"),hashDelete=require("./_hashDelete"),hashGet=require("./_hashGet"),hashHas=require("./_hashHas"),hashSet=require("./_hashSet"); -/** - * Creates a hash object. - * - * @private - * @constructor - * @param {Array} [entries] The key-value pairs to cache. - */function Hash(entries){var index=-1,length=entries==null?0:entries.length;this.clear();while(++index-1}module.exports=arrayIncludes},{"./_baseIndexOf":155}],127:[function(require,module,exports){ -/** - * This function is like `arrayIncludes` except that it accepts a comparator. - * - * @private - * @param {Array} [array] The array to inspect. - * @param {*} target The value to search for. - * @param {Function} comparator The comparator invoked per element. - * @returns {boolean} Returns `true` if `target` is found, else `false`. - */ -function arrayIncludesWith(array,value,comparator){var index=-1,length=array==null?0:array.length;while(++index0&&predicate(value)){if(depth>1){ -// Recursively flatten arrays (susceptible to call stack limits). -baseFlatten(value,depth-1,predicate,isStrict,result)}else{arrayPush(result,value)}}else if(!isStrict){result[result.length]=value}}return result}module.exports=baseFlatten},{"./_arrayPush":130,"./_isFlattenable":240}],147:[function(require,module,exports){var createBaseFor=require("./_createBaseFor"); -/** - * The base implementation of `baseForOwn` which iterates over `object` - * properties returned by `keysFunc` and invokes `iteratee` for each property. - * Iteratee functions may exit iteration early by explicitly returning `false`. - * - * @private - * @param {Object} object The object to iterate over. - * @param {Function} iteratee The function invoked per iteration. - * @param {Function} keysFunc The function to get the keys of `object`. - * @returns {Object} Returns `object`. - */var baseFor=createBaseFor();module.exports=baseFor},{"./_createBaseFor":209}],148:[function(require,module,exports){var baseFor=require("./_baseFor"),keys=require("./keys"); -/** - * The base implementation of `_.forOwn` without support for iteratee shorthands. - * - * @private - * @param {Object} object The object to iterate over. - * @param {Function} iteratee The function invoked per iteration. - * @returns {Object} Returns `object`. - */function baseForOwn(object,iteratee){return object&&baseFor(object,iteratee,keys)}module.exports=baseForOwn},{"./_baseFor":147,"./keys":319}],149:[function(require,module,exports){var castPath=require("./_castPath"),toKey=require("./_toKey"); -/** - * The base implementation of `_.get` without support for default values. - * - * @private - * @param {Object} object The object to query. - * @param {Array|string} path The path of the property to get. - * @returns {*} Returns the resolved value. - */function baseGet(object,path){path=castPath(path,object);var index=0,length=path.length;while(object!=null&&indexother}module.exports=baseGt},{}],153:[function(require,module,exports){ -/** Used for built-in method references. */ -var objectProto=Object.prototype; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** - * The base implementation of `_.has` without support for deep paths. - * - * @private - * @param {Object} [object] The object to query. - * @param {Array|string} key The key to check. - * @returns {boolean} Returns `true` if `key` exists, else `false`. - */function baseHas(object,key){return object!=null&&hasOwnProperty.call(object,key)}module.exports=baseHas},{}],154:[function(require,module,exports){ -/** - * The base implementation of `_.hasIn` without support for deep paths. - * - * @private - * @param {Object} [object] The object to query. - * @param {Array|string} key The key to check. - * @returns {boolean} Returns `true` if `key` exists, else `false`. - */ -function baseHasIn(object,key){return object!=null&&key in Object(object)}module.exports=baseHasIn},{}],155:[function(require,module,exports){var baseFindIndex=require("./_baseFindIndex"),baseIsNaN=require("./_baseIsNaN"),strictIndexOf=require("./_strictIndexOf"); -/** - * The base implementation of `_.indexOf` without `fromIndex` bounds checks. - * - * @private - * @param {Array} array The array to inspect. - * @param {*} value The value to search for. - * @param {number} fromIndex The index to search from. - * @returns {number} Returns the index of the matched value, else `-1`. - */function baseIndexOf(array,value,fromIndex){return value===value?strictIndexOf(array,value,fromIndex):baseFindIndex(array,baseIsNaN,fromIndex)}module.exports=baseIndexOf},{"./_baseFindIndex":145,"./_baseIsNaN":161,"./_strictIndexOf":280}],156:[function(require,module,exports){var baseGetTag=require("./_baseGetTag"),isObjectLike=require("./isObjectLike"); -/** `Object#toString` result references. */var argsTag="[object Arguments]"; -/** - * The base implementation of `_.isArguments`. - * - * @private - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is an `arguments` object, - */function baseIsArguments(value){return isObjectLike(value)&&baseGetTag(value)==argsTag}module.exports=baseIsArguments},{"./_baseGetTag":151,"./isObjectLike":312}],157:[function(require,module,exports){var baseIsEqualDeep=require("./_baseIsEqualDeep"),isObjectLike=require("./isObjectLike"); -/** - * The base implementation of `_.isEqual` which supports partial comparisons - * and tracks traversed objects. - * - * @private - * @param {*} value The value to compare. - * @param {*} other The other value to compare. - * @param {boolean} bitmask The bitmask flags. - * 1 - Unordered comparison - * 2 - Partial comparison - * @param {Function} [customizer] The function to customize comparisons. - * @param {Object} [stack] Tracks traversed `value` and `other` objects. - * @returns {boolean} Returns `true` if the values are equivalent, else `false`. - */function baseIsEqual(value,other,bitmask,customizer,stack){if(value===other){return true}if(value==null||other==null||!isObjectLike(value)&&!isObjectLike(other)){return value!==value&&other!==other}return baseIsEqualDeep(value,other,bitmask,customizer,baseIsEqual,stack)}module.exports=baseIsEqual},{"./_baseIsEqualDeep":158,"./isObjectLike":312}],158:[function(require,module,exports){var Stack=require("./_Stack"),equalArrays=require("./_equalArrays"),equalByTag=require("./_equalByTag"),equalObjects=require("./_equalObjects"),getTag=require("./_getTag"),isArray=require("./isArray"),isBuffer=require("./isBuffer"),isTypedArray=require("./isTypedArray"); -/** Used to compose bitmasks for value comparisons. */var COMPARE_PARTIAL_FLAG=1; -/** `Object#toString` result references. */var argsTag="[object Arguments]",arrayTag="[object Array]",objectTag="[object Object]"; -/** Used for built-in method references. */var objectProto=Object.prototype; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** - * A specialized version of `baseIsEqual` for arrays and objects which performs - * deep comparisons and tracks traversed objects enabling objects with circular - * references to be compared. - * - * @private - * @param {Object} object The object to compare. - * @param {Object} other The other object to compare. - * @param {number} bitmask The bitmask flags. See `baseIsEqual` for more details. - * @param {Function} customizer The function to customize comparisons. - * @param {Function} equalFunc The function to determine equivalents of values. - * @param {Object} [stack] Tracks traversed `object` and `other` objects. - * @returns {boolean} Returns `true` if the objects are equivalent, else `false`. - */function baseIsEqualDeep(object,other,bitmask,customizer,equalFunc,stack){var objIsArr=isArray(object),othIsArr=isArray(other),objTag=objIsArr?arrayTag:getTag(object),othTag=othIsArr?arrayTag:getTag(other);objTag=objTag==argsTag?objectTag:objTag;othTag=othTag==argsTag?objectTag:othTag;var objIsObj=objTag==objectTag,othIsObj=othTag==objectTag,isSameTag=objTag==othTag;if(isSameTag&&isBuffer(object)){if(!isBuffer(other)){return false}objIsArr=true;objIsObj=false}if(isSameTag&&!objIsObj){stack||(stack=new Stack);return objIsArr||isTypedArray(object)?equalArrays(object,other,bitmask,customizer,equalFunc,stack):equalByTag(object,other,objTag,bitmask,customizer,equalFunc,stack)}if(!(bitmask&COMPARE_PARTIAL_FLAG)){var objIsWrapped=objIsObj&&hasOwnProperty.call(object,"__wrapped__"),othIsWrapped=othIsObj&&hasOwnProperty.call(other,"__wrapped__");if(objIsWrapped||othIsWrapped){var objUnwrapped=objIsWrapped?object.value():object,othUnwrapped=othIsWrapped?other.value():other;stack||(stack=new Stack);return equalFunc(objUnwrapped,othUnwrapped,bitmask,customizer,stack)}}if(!isSameTag){return false}stack||(stack=new Stack);return equalObjects(object,other,bitmask,customizer,equalFunc,stack)}module.exports=baseIsEqualDeep},{"./_Stack":119,"./_equalArrays":214,"./_equalByTag":215,"./_equalObjects":216,"./_getTag":228,"./isArray":303,"./isBuffer":306,"./isTypedArray":317}],159:[function(require,module,exports){var getTag=require("./_getTag"),isObjectLike=require("./isObjectLike"); -/** `Object#toString` result references. */var mapTag="[object Map]"; -/** - * The base implementation of `_.isMap` without Node.js optimizations. - * - * @private - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a map, else `false`. - */function baseIsMap(value){return isObjectLike(value)&&getTag(value)==mapTag}module.exports=baseIsMap},{"./_getTag":228,"./isObjectLike":312}],160:[function(require,module,exports){var Stack=require("./_Stack"),baseIsEqual=require("./_baseIsEqual"); -/** Used to compose bitmasks for value comparisons. */var COMPARE_PARTIAL_FLAG=1,COMPARE_UNORDERED_FLAG=2; -/** - * The base implementation of `_.isMatch` without support for iteratee shorthands. - * - * @private - * @param {Object} object The object to inspect. - * @param {Object} source The object of property values to match. - * @param {Array} matchData The property names, values, and compare flags to match. - * @param {Function} [customizer] The function to customize comparisons. - * @returns {boolean} Returns `true` if `object` is a match, else `false`. - */function baseIsMatch(object,source,matchData,customizer){var index=matchData.length,length=index,noCustomizer=!customizer;if(object==null){return!length}object=Object(object);while(index--){var data=matchData[index];if(noCustomizer&&data[2]?data[1]!==object[data[0]]:!(data[0]in object)){return false}}while(++index=LARGE_ARRAY_SIZE){var set=iteratee?null:createSet(array);if(set){return setToArray(set)}isCommon=false;includes=cacheHas;seen=new SetCache}else{seen=iteratee?[]:result}outer:while(++indexother||valIsSymbol&&othIsDefined&&othIsReflexive&&!othIsNull&&!othIsSymbol||valIsNull&&othIsDefined&&othIsReflexive||!valIsDefined&&othIsReflexive||!valIsReflexive){return 1}if(!valIsNull&&!valIsSymbol&&!othIsSymbol&&value=ordersLength){return result}var order=orders[index];return result*(order=="desc"?-1:1)}} -// Fixes an `Array#sort` bug in the JS engine embedded in Adobe applications -// that causes it, under certain circumstances, to provide the same value for -// `object` and `other`. See https://github.com/jashkenas/underscore/pull/1247 -// for more details. -// -// This also ensures a stable sort in V8 and other engines. -// See https://bugs.chromium.org/p/v8/issues/detail?id=90 for more details. -return object.index-other.index}module.exports=compareMultiple},{"./_compareAscending":200}],202:[function(require,module,exports){ -/** - * Copies the values of `source` to `array`. - * - * @private - * @param {Array} source The array to copy values from. - * @param {Array} [array=[]] The array to copy values to. - * @returns {Array} Returns `array`. - */ -function copyArray(source,array){var index=-1,length=source.length;array||(array=Array(length));while(++index1?sources[length-1]:undefined,guard=length>2?sources[2]:undefined;customizer=assigner.length>3&&typeof customizer=="function"?(length--,customizer):undefined;if(guard&&isIterateeCall(sources[0],sources[1],guard)){customizer=length<3?undefined:customizer;length=1}object=Object(object);while(++index-1?iterable[iteratee?collection[index]:index]:undefined}}module.exports=createFind},{"./_baseIteratee":165,"./isArrayLike":304,"./keys":319}],211:[function(require,module,exports){var baseRange=require("./_baseRange"),isIterateeCall=require("./_isIterateeCall"),toFinite=require("./toFinite"); -/** - * Creates a `_.range` or `_.rangeRight` function. - * - * @private - * @param {boolean} [fromRight] Specify iterating from right to left. - * @returns {Function} Returns the new range function. - */function createRange(fromRight){return function(start,end,step){if(step&&typeof step!="number"&&isIterateeCall(start,end,step)){end=step=undefined} -// Ensure the sign of `-0` is preserved. -start=toFinite(start);if(end===undefined){end=start;start=0}else{end=toFinite(end)}step=step===undefined?startarrLength)){return false} -// Assume cyclic values are equal. -var stacked=stack.get(array);if(stacked&&stack.get(other)){return stacked==other}var index=-1,result=true,seen=bitmask&COMPARE_UNORDERED_FLAG?new SetCache:undefined;stack.set(array,other);stack.set(other,array); -// Ignore non-index properties. -while(++index-1&&value%1==0&&value-1}module.exports=listCacheHas},{"./_assocIndexOf":136}],252:[function(require,module,exports){var assocIndexOf=require("./_assocIndexOf"); -/** - * Sets the list cache `key` to `value`. - * - * @private - * @name set - * @memberOf ListCache - * @param {string} key The key of the value to set. - * @param {*} value The value to set. - * @returns {Object} Returns the list cache instance. - */function listCacheSet(key,value){var data=this.__data__,index=assocIndexOf(data,key);if(index<0){++this.size;data.push([key,value])}else{data[index][1]=value}return this}module.exports=listCacheSet},{"./_assocIndexOf":136}],253:[function(require,module,exports){var Hash=require("./_Hash"),ListCache=require("./_ListCache"),Map=require("./_Map"); -/** - * Removes all key-value entries from the map. - * - * @private - * @name clear - * @memberOf MapCache - */function mapCacheClear(){this.size=0;this.__data__={hash:new Hash,map:new(Map||ListCache),string:new Hash}}module.exports=mapCacheClear},{"./_Hash":112,"./_ListCache":113,"./_Map":114}],254:[function(require,module,exports){var getMapData=require("./_getMapData"); -/** - * Removes `key` and its value from the map. - * - * @private - * @name delete - * @memberOf MapCache - * @param {string} key The key of the value to remove. - * @returns {boolean} Returns `true` if the entry was removed, else `false`. - */function mapCacheDelete(key){var result=getMapData(this,key)["delete"](key);this.size-=result?1:0;return result}module.exports=mapCacheDelete},{"./_getMapData":221}],255:[function(require,module,exports){var getMapData=require("./_getMapData"); -/** - * Gets the map value for `key`. - * - * @private - * @name get - * @memberOf MapCache - * @param {string} key The key of the value to get. - * @returns {*} Returns the entry value. - */function mapCacheGet(key){return getMapData(this,key).get(key)}module.exports=mapCacheGet},{"./_getMapData":221}],256:[function(require,module,exports){var getMapData=require("./_getMapData"); -/** - * Checks if a map value for `key` exists. - * - * @private - * @name has - * @memberOf MapCache - * @param {string} key The key of the entry to check. - * @returns {boolean} Returns `true` if an entry for `key` exists, else `false`. - */function mapCacheHas(key){return getMapData(this,key).has(key)}module.exports=mapCacheHas},{"./_getMapData":221}],257:[function(require,module,exports){var getMapData=require("./_getMapData"); -/** - * Sets the map `key` to `value`. - * - * @private - * @name set - * @memberOf MapCache - * @param {string} key The key of the value to set. - * @param {*} value The value to set. - * @returns {Object} Returns the map cache instance. - */function mapCacheSet(key,value){var data=getMapData(this,key),size=data.size;data.set(key,value);this.size+=data.size==size?0:1;return this}module.exports=mapCacheSet},{"./_getMapData":221}],258:[function(require,module,exports){ -/** - * Converts `map` to its key-value pairs. - * - * @private - * @param {Object} map The map to convert. - * @returns {Array} Returns the key-value pairs. - */ -function mapToArray(map){var index=-1,result=Array(map.size);map.forEach(function(value,key){result[++index]=[key,value]});return result}module.exports=mapToArray},{}],259:[function(require,module,exports){ -/** - * A specialized version of `matchesProperty` for source values suitable - * for strict equality comparisons, i.e. `===`. - * - * @private - * @param {string} key The key of the property to get. - * @param {*} srcValue The value to match. - * @returns {Function} Returns the new spec function. - */ -function matchesStrictComparable(key,srcValue){return function(object){if(object==null){return false}return object[key]===srcValue&&(srcValue!==undefined||key in Object(object))}}module.exports=matchesStrictComparable},{}],260:[function(require,module,exports){var memoize=require("./memoize"); -/** Used as the maximum memoize cache size. */var MAX_MEMOIZE_SIZE=500; -/** - * A specialized version of `_.memoize` which clears the memoized function's - * cache when it exceeds `MAX_MEMOIZE_SIZE`. - * - * @private - * @param {Function} func The function to have its output memoized. - * @returns {Function} Returns the new memoized function. - */function memoizeCapped(func){var result=memoize(func,function(key){if(cache.size===MAX_MEMOIZE_SIZE){cache.clear()}return key});var cache=result.cache;return result}module.exports=memoizeCapped},{"./memoize":325}],261:[function(require,module,exports){var getNative=require("./_getNative"); -/* Built-in method references that are verified to be native. */var nativeCreate=getNative(Object,"create");module.exports=nativeCreate},{"./_getNative":223}],262:[function(require,module,exports){var overArg=require("./_overArg"); -/* Built-in method references for those with the same name as other `lodash` methods. */var nativeKeys=overArg(Object.keys,Object);module.exports=nativeKeys},{"./_overArg":266}],263:[function(require,module,exports){ -/** - * This function is like - * [`Object.keys`](http://ecma-international.org/ecma-262/7.0/#sec-object.keys) - * except that it includes inherited enumerable properties. - * - * @private - * @param {Object} object The object to query. - * @returns {Array} Returns the array of property names. - */ -function nativeKeysIn(object){var result=[];if(object!=null){for(var key in Object(object)){result.push(key)}}return result}module.exports=nativeKeysIn},{}],264:[function(require,module,exports){var freeGlobal=require("./_freeGlobal"); -/** Detect free variable `exports`. */var freeExports=typeof exports=="object"&&exports&&!exports.nodeType&&exports; -/** Detect free variable `module`. */var freeModule=freeExports&&typeof module=="object"&&module&&!module.nodeType&&module; -/** Detect the popular CommonJS extension `module.exports`. */var moduleExports=freeModule&&freeModule.exports===freeExports; -/** Detect free variable `process` from Node.js. */var freeProcess=moduleExports&&freeGlobal.process; -/** Used to access faster Node.js helpers. */var nodeUtil=function(){try{ -// Use `util.types` for Node.js 10+. -var types=freeModule&&freeModule.require&&freeModule.require("util").types;if(types){return types} -// Legacy `process.binding('util')` for Node.js < 10. -return freeProcess&&freeProcess.binding&&freeProcess.binding("util")}catch(e){}}();module.exports=nodeUtil},{"./_freeGlobal":218}],265:[function(require,module,exports){ -/** Used for built-in method references. */ -var objectProto=Object.prototype; -/** - * Used to resolve the - * [`toStringTag`](http://ecma-international.org/ecma-262/7.0/#sec-object.prototype.tostring) - * of values. - */var nativeObjectToString=objectProto.toString; -/** - * Converts `value` to a string using `Object.prototype.toString`. - * - * @private - * @param {*} value The value to convert. - * @returns {string} Returns the converted string. - */function objectToString(value){return nativeObjectToString.call(value)}module.exports=objectToString},{}],266:[function(require,module,exports){ -/** - * Creates a unary function that invokes `func` with its argument transformed. - * - * @private - * @param {Function} func The function to wrap. - * @param {Function} transform The argument transform. - * @returns {Function} Returns the new function. - */ -function overArg(func,transform){return function(arg){return func(transform(arg))}}module.exports=overArg},{}],267:[function(require,module,exports){var apply=require("./_apply"); -/* Built-in method references for those with the same name as other `lodash` methods. */var nativeMax=Math.max; -/** - * A specialized version of `baseRest` which transforms the rest array. - * - * @private - * @param {Function} func The function to apply a rest parameter to. - * @param {number} [start=func.length-1] The start position of the rest parameter. - * @param {Function} transform The rest array transform. - * @returns {Function} Returns the new function. - */function overRest(func,start,transform){start=nativeMax(start===undefined?func.length-1:start,0);return function(){var args=arguments,index=-1,length=nativeMax(args.length-start,0),array=Array(length);while(++index0){if(++count>=HOT_COUNT){return arguments[0]}}else{count=0}return func.apply(undefined,arguments)}}module.exports=shortOut},{}],275:[function(require,module,exports){var ListCache=require("./_ListCache"); -/** - * Removes all key-value entries from the stack. - * - * @private - * @name clear - * @memberOf Stack - */function stackClear(){this.__data__=new ListCache;this.size=0}module.exports=stackClear},{"./_ListCache":113}],276:[function(require,module,exports){ -/** - * Removes `key` and its value from the stack. - * - * @private - * @name delete - * @memberOf Stack - * @param {string} key The key of the value to remove. - * @returns {boolean} Returns `true` if the entry was removed, else `false`. - */ -function stackDelete(key){var data=this.__data__,result=data["delete"](key);this.size=data.size;return result}module.exports=stackDelete},{}],277:[function(require,module,exports){ -/** - * Gets the stack value for `key`. - * - * @private - * @name get - * @memberOf Stack - * @param {string} key The key of the value to get. - * @returns {*} Returns the entry value. - */ -function stackGet(key){return this.__data__.get(key)}module.exports=stackGet},{}],278:[function(require,module,exports){ -/** - * Checks if a stack value for `key` exists. - * - * @private - * @name has - * @memberOf Stack - * @param {string} key The key of the entry to check. - * @returns {boolean} Returns `true` if an entry for `key` exists, else `false`. - */ -function stackHas(key){return this.__data__.has(key)}module.exports=stackHas},{}],279:[function(require,module,exports){var ListCache=require("./_ListCache"),Map=require("./_Map"),MapCache=require("./_MapCache"); -/** Used as the size to enable large array optimizations. */var LARGE_ARRAY_SIZE=200; -/** - * Sets the stack `key` to `value`. - * - * @private - * @name set - * @memberOf Stack - * @param {string} key The key of the value to set. - * @param {*} value The value to set. - * @returns {Object} Returns the stack cache instance. - */function stackSet(key,value){var data=this.__data__;if(data instanceof ListCache){var pairs=data.__data__;if(!Map||pairs.length true - */function clone(value){return baseClone(value,CLONE_SYMBOLS_FLAG)}module.exports=clone},{"./_baseClone":140}],287:[function(require,module,exports){var baseClone=require("./_baseClone"); -/** Used to compose bitmasks for cloning. */var CLONE_DEEP_FLAG=1,CLONE_SYMBOLS_FLAG=4; -/** - * This method is like `_.clone` except that it recursively clones `value`. - * - * @static - * @memberOf _ - * @since 1.0.0 - * @category Lang - * @param {*} value The value to recursively clone. - * @returns {*} Returns the deep cloned value. - * @see _.clone - * @example - * - * var objects = [{ 'a': 1 }, { 'b': 2 }]; - * - * var deep = _.cloneDeep(objects); - * console.log(deep[0] === objects[0]); - * // => false - */function cloneDeep(value){return baseClone(value,CLONE_DEEP_FLAG|CLONE_SYMBOLS_FLAG)}module.exports=cloneDeep},{"./_baseClone":140}],288:[function(require,module,exports){ -/** - * Creates a function that returns `value`. - * - * @static - * @memberOf _ - * @since 2.4.0 - * @category Util - * @param {*} value The value to return from the new function. - * @returns {Function} Returns the new constant function. - * @example - * - * var objects = _.times(2, _.constant({ 'a': 1 })); - * - * console.log(objects); - * // => [{ 'a': 1 }, { 'a': 1 }] - * - * console.log(objects[0] === objects[1]); - * // => true - */ -function constant(value){return function(){return value}}module.exports=constant},{}],289:[function(require,module,exports){var baseRest=require("./_baseRest"),eq=require("./eq"),isIterateeCall=require("./_isIterateeCall"),keysIn=require("./keysIn"); -/** Used for built-in method references. */var objectProto=Object.prototype; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** - * Assigns own and inherited enumerable string keyed properties of source - * objects to the destination object for all destination properties that - * resolve to `undefined`. Source objects are applied from left to right. - * Once a property is set, additional values of the same property are ignored. - * - * **Note:** This method mutates `object`. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Object - * @param {Object} object The destination object. - * @param {...Object} [sources] The source objects. - * @returns {Object} Returns `object`. - * @see _.defaultsDeep - * @example - * - * _.defaults({ 'a': 1 }, { 'b': 2 }, { 'a': 3 }); - * // => { 'a': 1, 'b': 2 } - */var defaults=baseRest(function(object,sources){object=Object(object);var index=-1;var length=sources.length;var guard=length>2?sources[2]:undefined;if(guard&&isIterateeCall(sources[0],sources[1],guard)){length=1}while(++index true - * - * _.eq(object, other); - * // => false - * - * _.eq('a', 'a'); - * // => true - * - * _.eq('a', Object('a')); - * // => false - * - * _.eq(NaN, NaN); - * // => true - */ -function eq(value,other){return value===other||value!==value&&other!==other}module.exports=eq},{}],292:[function(require,module,exports){var arrayFilter=require("./_arrayFilter"),baseFilter=require("./_baseFilter"),baseIteratee=require("./_baseIteratee"),isArray=require("./isArray"); -/** - * Iterates over elements of `collection`, returning an array of all elements - * `predicate` returns truthy for. The predicate is invoked with three - * arguments: (value, index|key, collection). - * - * **Note:** Unlike `_.remove`, this method returns a new array. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object} collection The collection to iterate over. - * @param {Function} [predicate=_.identity] The function invoked per iteration. - * @returns {Array} Returns the new filtered array. - * @see _.reject - * @example - * - * var users = [ - * { 'user': 'barney', 'age': 36, 'active': true }, - * { 'user': 'fred', 'age': 40, 'active': false } - * ]; - * - * _.filter(users, function(o) { return !o.active; }); - * // => objects for ['fred'] - * - * // The `_.matches` iteratee shorthand. - * _.filter(users, { 'age': 36, 'active': true }); - * // => objects for ['barney'] - * - * // The `_.matchesProperty` iteratee shorthand. - * _.filter(users, ['active', false]); - * // => objects for ['fred'] - * - * // The `_.property` iteratee shorthand. - * _.filter(users, 'active'); - * // => objects for ['barney'] - */function filter(collection,predicate){var func=isArray(collection)?arrayFilter:baseFilter;return func(collection,baseIteratee(predicate,3))}module.exports=filter},{"./_arrayFilter":125,"./_baseFilter":144,"./_baseIteratee":165,"./isArray":303}],293:[function(require,module,exports){var createFind=require("./_createFind"),findIndex=require("./findIndex"); -/** - * Iterates over elements of `collection`, returning the first element - * `predicate` returns truthy for. The predicate is invoked with three - * arguments: (value, index|key, collection). - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object} collection The collection to inspect. - * @param {Function} [predicate=_.identity] The function invoked per iteration. - * @param {number} [fromIndex=0] The index to search from. - * @returns {*} Returns the matched element, else `undefined`. - * @example - * - * var users = [ - * { 'user': 'barney', 'age': 36, 'active': true }, - * { 'user': 'fred', 'age': 40, 'active': false }, - * { 'user': 'pebbles', 'age': 1, 'active': true } - * ]; - * - * _.find(users, function(o) { return o.age < 40; }); - * // => object for 'barney' - * - * // The `_.matches` iteratee shorthand. - * _.find(users, { 'age': 1, 'active': true }); - * // => object for 'pebbles' - * - * // The `_.matchesProperty` iteratee shorthand. - * _.find(users, ['active', false]); - * // => object for 'fred' - * - * // The `_.property` iteratee shorthand. - * _.find(users, 'active'); - * // => object for 'barney' - */var find=createFind(findIndex);module.exports=find},{"./_createFind":210,"./findIndex":294}],294:[function(require,module,exports){var baseFindIndex=require("./_baseFindIndex"),baseIteratee=require("./_baseIteratee"),toInteger=require("./toInteger"); -/* Built-in method references for those with the same name as other `lodash` methods. */var nativeMax=Math.max; -/** - * This method is like `_.find` except that it returns the index of the first - * element `predicate` returns truthy for instead of the element itself. - * - * @static - * @memberOf _ - * @since 1.1.0 - * @category Array - * @param {Array} array The array to inspect. - * @param {Function} [predicate=_.identity] The function invoked per iteration. - * @param {number} [fromIndex=0] The index to search from. - * @returns {number} Returns the index of the found element, else `-1`. - * @example - * - * var users = [ - * { 'user': 'barney', 'active': false }, - * { 'user': 'fred', 'active': false }, - * { 'user': 'pebbles', 'active': true } - * ]; - * - * _.findIndex(users, function(o) { return o.user == 'barney'; }); - * // => 0 - * - * // The `_.matches` iteratee shorthand. - * _.findIndex(users, { 'user': 'fred', 'active': false }); - * // => 1 - * - * // The `_.matchesProperty` iteratee shorthand. - * _.findIndex(users, ['active', false]); - * // => 0 - * - * // The `_.property` iteratee shorthand. - * _.findIndex(users, 'active'); - * // => 2 - */function findIndex(array,predicate,fromIndex){var length=array==null?0:array.length;if(!length){return-1}var index=fromIndex==null?0:toInteger(fromIndex);if(index<0){index=nativeMax(length+index,0)}return baseFindIndex(array,baseIteratee(predicate,3),index)}module.exports=findIndex},{"./_baseFindIndex":145,"./_baseIteratee":165,"./toInteger":340}],295:[function(require,module,exports){var baseFlatten=require("./_baseFlatten"); -/** - * Flattens `array` a single level deep. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Array - * @param {Array} array The array to flatten. - * @returns {Array} Returns the new flattened array. - * @example - * - * _.flatten([1, [2, [3, [4]], 5]]); - * // => [1, 2, [3, [4]], 5] - */function flatten(array){var length=array==null?0:array.length;return length?baseFlatten(array,1):[]}module.exports=flatten},{"./_baseFlatten":146}],296:[function(require,module,exports){var arrayEach=require("./_arrayEach"),baseEach=require("./_baseEach"),castFunction=require("./_castFunction"),isArray=require("./isArray"); -/** - * Iterates over elements of `collection` and invokes `iteratee` for each element. - * The iteratee is invoked with three arguments: (value, index|key, collection). - * Iteratee functions may exit iteration early by explicitly returning `false`. - * - * **Note:** As with other "Collections" methods, objects with a "length" - * property are iterated like arrays. To avoid this behavior use `_.forIn` - * or `_.forOwn` for object iteration. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @alias each - * @category Collection - * @param {Array|Object} collection The collection to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @returns {Array|Object} Returns `collection`. - * @see _.forEachRight - * @example - * - * _.forEach([1, 2], function(value) { - * console.log(value); - * }); - * // => Logs `1` then `2`. - * - * _.forEach({ 'a': 1, 'b': 2 }, function(value, key) { - * console.log(key); - * }); - * // => Logs 'a' then 'b' (iteration order is not guaranteed). - */function forEach(collection,iteratee){var func=isArray(collection)?arrayEach:baseEach;return func(collection,castFunction(iteratee))}module.exports=forEach},{"./_arrayEach":124,"./_baseEach":142,"./_castFunction":192,"./isArray":303}],297:[function(require,module,exports){var baseFor=require("./_baseFor"),castFunction=require("./_castFunction"),keysIn=require("./keysIn"); -/** - * Iterates over own and inherited enumerable string keyed properties of an - * object and invokes `iteratee` for each property. The iteratee is invoked - * with three arguments: (value, key, object). Iteratee functions may exit - * iteration early by explicitly returning `false`. - * - * @static - * @memberOf _ - * @since 0.3.0 - * @category Object - * @param {Object} object The object to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @returns {Object} Returns `object`. - * @see _.forInRight - * @example - * - * function Foo() { - * this.a = 1; - * this.b = 2; - * } - * - * Foo.prototype.c = 3; - * - * _.forIn(new Foo, function(value, key) { - * console.log(key); - * }); - * // => Logs 'a', 'b', then 'c' (iteration order is not guaranteed). - */function forIn(object,iteratee){return object==null?object:baseFor(object,castFunction(iteratee),keysIn)}module.exports=forIn},{"./_baseFor":147,"./_castFunction":192,"./keysIn":320}],298:[function(require,module,exports){var baseGet=require("./_baseGet"); -/** - * Gets the value at `path` of `object`. If the resolved value is - * `undefined`, the `defaultValue` is returned in its place. - * - * @static - * @memberOf _ - * @since 3.7.0 - * @category Object - * @param {Object} object The object to query. - * @param {Array|string} path The path of the property to get. - * @param {*} [defaultValue] The value returned for `undefined` resolved values. - * @returns {*} Returns the resolved value. - * @example - * - * var object = { 'a': [{ 'b': { 'c': 3 } }] }; - * - * _.get(object, 'a[0].b.c'); - * // => 3 - * - * _.get(object, ['a', '0', 'b', 'c']); - * // => 3 - * - * _.get(object, 'a.b.c', 'default'); - * // => 'default' - */function get(object,path,defaultValue){var result=object==null?undefined:baseGet(object,path);return result===undefined?defaultValue:result}module.exports=get},{"./_baseGet":149}],299:[function(require,module,exports){var baseHas=require("./_baseHas"),hasPath=require("./_hasPath"); -/** - * Checks if `path` is a direct property of `object`. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Object - * @param {Object} object The object to query. - * @param {Array|string} path The path to check. - * @returns {boolean} Returns `true` if `path` exists, else `false`. - * @example - * - * var object = { 'a': { 'b': 2 } }; - * var other = _.create({ 'a': _.create({ 'b': 2 }) }); - * - * _.has(object, 'a'); - * // => true - * - * _.has(object, 'a.b'); - * // => true - * - * _.has(object, ['a', 'b']); - * // => true - * - * _.has(other, 'a'); - * // => false - */function has(object,path){return object!=null&&hasPath(object,path,baseHas)}module.exports=has},{"./_baseHas":153,"./_hasPath":230}],300:[function(require,module,exports){var baseHasIn=require("./_baseHasIn"),hasPath=require("./_hasPath"); -/** - * Checks if `path` is a direct or inherited property of `object`. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Object - * @param {Object} object The object to query. - * @param {Array|string} path The path to check. - * @returns {boolean} Returns `true` if `path` exists, else `false`. - * @example - * - * var object = _.create({ 'a': _.create({ 'b': 2 }) }); - * - * _.hasIn(object, 'a'); - * // => true - * - * _.hasIn(object, 'a.b'); - * // => true - * - * _.hasIn(object, ['a', 'b']); - * // => true - * - * _.hasIn(object, 'b'); - * // => false - */function hasIn(object,path){return object!=null&&hasPath(object,path,baseHasIn)}module.exports=hasIn},{"./_baseHasIn":154,"./_hasPath":230}],301:[function(require,module,exports){ -/** - * This method returns the first argument it receives. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Util - * @param {*} value Any value. - * @returns {*} Returns `value`. - * @example - * - * var object = { 'a': 1 }; - * - * console.log(_.identity(object) === object); - * // => true - */ -function identity(value){return value}module.exports=identity},{}],302:[function(require,module,exports){var baseIsArguments=require("./_baseIsArguments"),isObjectLike=require("./isObjectLike"); -/** Used for built-in method references. */var objectProto=Object.prototype; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** Built-in value references. */var propertyIsEnumerable=objectProto.propertyIsEnumerable; -/** - * Checks if `value` is likely an `arguments` object. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is an `arguments` object, - * else `false`. - * @example - * - * _.isArguments(function() { return arguments; }()); - * // => true - * - * _.isArguments([1, 2, 3]); - * // => false - */var isArguments=baseIsArguments(function(){return arguments}())?baseIsArguments:function(value){return isObjectLike(value)&&hasOwnProperty.call(value,"callee")&&!propertyIsEnumerable.call(value,"callee")};module.exports=isArguments},{"./_baseIsArguments":156,"./isObjectLike":312}],303:[function(require,module,exports){ -/** - * Checks if `value` is classified as an `Array` object. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is an array, else `false`. - * @example - * - * _.isArray([1, 2, 3]); - * // => true - * - * _.isArray(document.body.children); - * // => false - * - * _.isArray('abc'); - * // => false - * - * _.isArray(_.noop); - * // => false - */ -var isArray=Array.isArray;module.exports=isArray},{}],304:[function(require,module,exports){var isFunction=require("./isFunction"),isLength=require("./isLength"); -/** - * Checks if `value` is array-like. A value is considered array-like if it's - * not a function and has a `value.length` that's an integer greater than or - * equal to `0` and less than or equal to `Number.MAX_SAFE_INTEGER`. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is array-like, else `false`. - * @example - * - * _.isArrayLike([1, 2, 3]); - * // => true - * - * _.isArrayLike(document.body.children); - * // => true - * - * _.isArrayLike('abc'); - * // => true - * - * _.isArrayLike(_.noop); - * // => false - */function isArrayLike(value){return value!=null&&isLength(value.length)&&!isFunction(value)}module.exports=isArrayLike},{"./isFunction":308,"./isLength":309}],305:[function(require,module,exports){var isArrayLike=require("./isArrayLike"),isObjectLike=require("./isObjectLike"); -/** - * This method is like `_.isArrayLike` except that it also checks if `value` - * is an object. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is an array-like object, - * else `false`. - * @example - * - * _.isArrayLikeObject([1, 2, 3]); - * // => true - * - * _.isArrayLikeObject(document.body.children); - * // => true - * - * _.isArrayLikeObject('abc'); - * // => false - * - * _.isArrayLikeObject(_.noop); - * // => false - */function isArrayLikeObject(value){return isObjectLike(value)&&isArrayLike(value)}module.exports=isArrayLikeObject},{"./isArrayLike":304,"./isObjectLike":312}],306:[function(require,module,exports){var root=require("./_root"),stubFalse=require("./stubFalse"); -/** Detect free variable `exports`. */var freeExports=typeof exports=="object"&&exports&&!exports.nodeType&&exports; -/** Detect free variable `module`. */var freeModule=freeExports&&typeof module=="object"&&module&&!module.nodeType&&module; -/** Detect the popular CommonJS extension `module.exports`. */var moduleExports=freeModule&&freeModule.exports===freeExports; -/** Built-in value references. */var Buffer=moduleExports?root.Buffer:undefined; -/* Built-in method references for those with the same name as other `lodash` methods. */var nativeIsBuffer=Buffer?Buffer.isBuffer:undefined; -/** - * Checks if `value` is a buffer. - * - * @static - * @memberOf _ - * @since 4.3.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a buffer, else `false`. - * @example - * - * _.isBuffer(new Buffer(2)); - * // => true - * - * _.isBuffer(new Uint8Array(2)); - * // => false - */var isBuffer=nativeIsBuffer||stubFalse;module.exports=isBuffer},{"./_root":268,"./stubFalse":338}],307:[function(require,module,exports){var baseKeys=require("./_baseKeys"),getTag=require("./_getTag"),isArguments=require("./isArguments"),isArray=require("./isArray"),isArrayLike=require("./isArrayLike"),isBuffer=require("./isBuffer"),isPrototype=require("./_isPrototype"),isTypedArray=require("./isTypedArray"); -/** `Object#toString` result references. */var mapTag="[object Map]",setTag="[object Set]"; -/** Used for built-in method references. */var objectProto=Object.prototype; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** - * Checks if `value` is an empty object, collection, map, or set. - * - * Objects are considered empty if they have no own enumerable string keyed - * properties. - * - * Array-like values such as `arguments` objects, arrays, buffers, strings, or - * jQuery-like collections are considered empty if they have a `length` of `0`. - * Similarly, maps and sets are considered empty if they have a `size` of `0`. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is empty, else `false`. - * @example - * - * _.isEmpty(null); - * // => true - * - * _.isEmpty(true); - * // => true - * - * _.isEmpty(1); - * // => true - * - * _.isEmpty([1, 2, 3]); - * // => false - * - * _.isEmpty({ 'a': 1 }); - * // => false - */function isEmpty(value){if(value==null){return true}if(isArrayLike(value)&&(isArray(value)||typeof value=="string"||typeof value.splice=="function"||isBuffer(value)||isTypedArray(value)||isArguments(value))){return!value.length}var tag=getTag(value);if(tag==mapTag||tag==setTag){return!value.size}if(isPrototype(value)){return!baseKeys(value).length}for(var key in value){if(hasOwnProperty.call(value,key)){return false}}return true}module.exports=isEmpty},{"./_baseKeys":166,"./_getTag":228,"./_isPrototype":246,"./isArguments":302,"./isArray":303,"./isArrayLike":304,"./isBuffer":306,"./isTypedArray":317}],308:[function(require,module,exports){var baseGetTag=require("./_baseGetTag"),isObject=require("./isObject"); -/** `Object#toString` result references. */var asyncTag="[object AsyncFunction]",funcTag="[object Function]",genTag="[object GeneratorFunction]",proxyTag="[object Proxy]"; -/** - * Checks if `value` is classified as a `Function` object. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a function, else `false`. - * @example - * - * _.isFunction(_); - * // => true - * - * _.isFunction(/abc/); - * // => false - */function isFunction(value){if(!isObject(value)){return false} -// The use of `Object#toString` avoids issues with the `typeof` operator -// in Safari 9 which returns 'object' for typed arrays and other constructors. -var tag=baseGetTag(value);return tag==funcTag||tag==genTag||tag==asyncTag||tag==proxyTag}module.exports=isFunction},{"./_baseGetTag":151,"./isObject":311}],309:[function(require,module,exports){ -/** Used as references for various `Number` constants. */ -var MAX_SAFE_INTEGER=9007199254740991; -/** - * Checks if `value` is a valid array-like length. - * - * **Note:** This method is loosely based on - * [`ToLength`](http://ecma-international.org/ecma-262/7.0/#sec-tolength). - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a valid length, else `false`. - * @example - * - * _.isLength(3); - * // => true - * - * _.isLength(Number.MIN_VALUE); - * // => false - * - * _.isLength(Infinity); - * // => false - * - * _.isLength('3'); - * // => false - */function isLength(value){return typeof value=="number"&&value>-1&&value%1==0&&value<=MAX_SAFE_INTEGER}module.exports=isLength},{}],310:[function(require,module,exports){var baseIsMap=require("./_baseIsMap"),baseUnary=require("./_baseUnary"),nodeUtil=require("./_nodeUtil"); -/* Node.js helper references. */var nodeIsMap=nodeUtil&&nodeUtil.isMap; -/** - * Checks if `value` is classified as a `Map` object. - * - * @static - * @memberOf _ - * @since 4.3.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a map, else `false`. - * @example - * - * _.isMap(new Map); - * // => true - * - * _.isMap(new WeakMap); - * // => false - */var isMap=nodeIsMap?baseUnary(nodeIsMap):baseIsMap;module.exports=isMap},{"./_baseIsMap":159,"./_baseUnary":187,"./_nodeUtil":264}],311:[function(require,module,exports){ -/** - * Checks if `value` is the - * [language type](http://www.ecma-international.org/ecma-262/7.0/#sec-ecmascript-language-types) - * of `Object`. (e.g. arrays, functions, objects, regexes, `new Number(0)`, and `new String('')`) - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is an object, else `false`. - * @example - * - * _.isObject({}); - * // => true - * - * _.isObject([1, 2, 3]); - * // => true - * - * _.isObject(_.noop); - * // => true - * - * _.isObject(null); - * // => false - */ -function isObject(value){var type=typeof value;return value!=null&&(type=="object"||type=="function")}module.exports=isObject},{}],312:[function(require,module,exports){ -/** - * Checks if `value` is object-like. A value is object-like if it's not `null` - * and has a `typeof` result of "object". - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is object-like, else `false`. - * @example - * - * _.isObjectLike({}); - * // => true - * - * _.isObjectLike([1, 2, 3]); - * // => true - * - * _.isObjectLike(_.noop); - * // => false - * - * _.isObjectLike(null); - * // => false - */ -function isObjectLike(value){return value!=null&&typeof value=="object"}module.exports=isObjectLike},{}],313:[function(require,module,exports){var baseGetTag=require("./_baseGetTag"),getPrototype=require("./_getPrototype"),isObjectLike=require("./isObjectLike"); -/** `Object#toString` result references. */var objectTag="[object Object]"; -/** Used for built-in method references. */var funcProto=Function.prototype,objectProto=Object.prototype; -/** Used to resolve the decompiled source of functions. */var funcToString=funcProto.toString; -/** Used to check objects for own properties. */var hasOwnProperty=objectProto.hasOwnProperty; -/** Used to infer the `Object` constructor. */var objectCtorString=funcToString.call(Object); -/** - * Checks if `value` is a plain object, that is, an object created by the - * `Object` constructor or one with a `[[Prototype]]` of `null`. - * - * @static - * @memberOf _ - * @since 0.8.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a plain object, else `false`. - * @example - * - * function Foo() { - * this.a = 1; - * } - * - * _.isPlainObject(new Foo); - * // => false - * - * _.isPlainObject([1, 2, 3]); - * // => false - * - * _.isPlainObject({ 'x': 0, 'y': 0 }); - * // => true - * - * _.isPlainObject(Object.create(null)); - * // => true - */function isPlainObject(value){if(!isObjectLike(value)||baseGetTag(value)!=objectTag){return false}var proto=getPrototype(value);if(proto===null){return true}var Ctor=hasOwnProperty.call(proto,"constructor")&&proto.constructor;return typeof Ctor=="function"&&Ctor instanceof Ctor&&funcToString.call(Ctor)==objectCtorString}module.exports=isPlainObject},{"./_baseGetTag":151,"./_getPrototype":224,"./isObjectLike":312}],314:[function(require,module,exports){var baseIsSet=require("./_baseIsSet"),baseUnary=require("./_baseUnary"),nodeUtil=require("./_nodeUtil"); -/* Node.js helper references. */var nodeIsSet=nodeUtil&&nodeUtil.isSet; -/** - * Checks if `value` is classified as a `Set` object. - * - * @static - * @memberOf _ - * @since 4.3.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a set, else `false`. - * @example - * - * _.isSet(new Set); - * // => true - * - * _.isSet(new WeakSet); - * // => false - */var isSet=nodeIsSet?baseUnary(nodeIsSet):baseIsSet;module.exports=isSet},{"./_baseIsSet":163,"./_baseUnary":187,"./_nodeUtil":264}],315:[function(require,module,exports){var baseGetTag=require("./_baseGetTag"),isArray=require("./isArray"),isObjectLike=require("./isObjectLike"); -/** `Object#toString` result references. */var stringTag="[object String]"; -/** - * Checks if `value` is classified as a `String` primitive or object. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a string, else `false`. - * @example - * - * _.isString('abc'); - * // => true - * - * _.isString(1); - * // => false - */function isString(value){return typeof value=="string"||!isArray(value)&&isObjectLike(value)&&baseGetTag(value)==stringTag}module.exports=isString},{"./_baseGetTag":151,"./isArray":303,"./isObjectLike":312}],316:[function(require,module,exports){var baseGetTag=require("./_baseGetTag"),isObjectLike=require("./isObjectLike"); -/** `Object#toString` result references. */var symbolTag="[object Symbol]"; -/** - * Checks if `value` is classified as a `Symbol` primitive or object. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a symbol, else `false`. - * @example - * - * _.isSymbol(Symbol.iterator); - * // => true - * - * _.isSymbol('abc'); - * // => false - */function isSymbol(value){return typeof value=="symbol"||isObjectLike(value)&&baseGetTag(value)==symbolTag}module.exports=isSymbol},{"./_baseGetTag":151,"./isObjectLike":312}],317:[function(require,module,exports){var baseIsTypedArray=require("./_baseIsTypedArray"),baseUnary=require("./_baseUnary"),nodeUtil=require("./_nodeUtil"); -/* Node.js helper references. */var nodeIsTypedArray=nodeUtil&&nodeUtil.isTypedArray; -/** - * Checks if `value` is classified as a typed array. - * - * @static - * @memberOf _ - * @since 3.0.0 - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is a typed array, else `false`. - * @example - * - * _.isTypedArray(new Uint8Array); - * // => true - * - * _.isTypedArray([]); - * // => false - */var isTypedArray=nodeIsTypedArray?baseUnary(nodeIsTypedArray):baseIsTypedArray;module.exports=isTypedArray},{"./_baseIsTypedArray":164,"./_baseUnary":187,"./_nodeUtil":264}],318:[function(require,module,exports){ -/** - * Checks if `value` is `undefined`. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Lang - * @param {*} value The value to check. - * @returns {boolean} Returns `true` if `value` is `undefined`, else `false`. - * @example - * - * _.isUndefined(void 0); - * // => true - * - * _.isUndefined(null); - * // => false - */ -function isUndefined(value){return value===undefined}module.exports=isUndefined},{}],319:[function(require,module,exports){var arrayLikeKeys=require("./_arrayLikeKeys"),baseKeys=require("./_baseKeys"),isArrayLike=require("./isArrayLike"); -/** - * Creates an array of the own enumerable property names of `object`. - * - * **Note:** Non-object values are coerced to objects. See the - * [ES spec](http://ecma-international.org/ecma-262/7.0/#sec-object.keys) - * for more details. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Object - * @param {Object} object The object to query. - * @returns {Array} Returns the array of property names. - * @example - * - * function Foo() { - * this.a = 1; - * this.b = 2; - * } - * - * Foo.prototype.c = 3; - * - * _.keys(new Foo); - * // => ['a', 'b'] (iteration order is not guaranteed) - * - * _.keys('hi'); - * // => ['0', '1'] - */function keys(object){return isArrayLike(object)?arrayLikeKeys(object):baseKeys(object)}module.exports=keys},{"./_arrayLikeKeys":128,"./_baseKeys":166,"./isArrayLike":304}],320:[function(require,module,exports){var arrayLikeKeys=require("./_arrayLikeKeys"),baseKeysIn=require("./_baseKeysIn"),isArrayLike=require("./isArrayLike"); -/** - * Creates an array of the own and inherited enumerable property names of `object`. - * - * **Note:** Non-object values are coerced to objects. - * - * @static - * @memberOf _ - * @since 3.0.0 - * @category Object - * @param {Object} object The object to query. - * @returns {Array} Returns the array of property names. - * @example - * - * function Foo() { - * this.a = 1; - * this.b = 2; - * } - * - * Foo.prototype.c = 3; - * - * _.keysIn(new Foo); - * // => ['a', 'b', 'c'] (iteration order is not guaranteed) - */function keysIn(object){return isArrayLike(object)?arrayLikeKeys(object,true):baseKeysIn(object)}module.exports=keysIn},{"./_arrayLikeKeys":128,"./_baseKeysIn":167,"./isArrayLike":304}],321:[function(require,module,exports){ -/** - * Gets the last element of `array`. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Array - * @param {Array} array The array to query. - * @returns {*} Returns the last element of `array`. - * @example - * - * _.last([1, 2, 3]); - * // => 3 - */ -function last(array){var length=array==null?0:array.length;return length?array[length-1]:undefined}module.exports=last},{}],322:[function(require,module,exports){var arrayMap=require("./_arrayMap"),baseIteratee=require("./_baseIteratee"),baseMap=require("./_baseMap"),isArray=require("./isArray"); -/** - * Creates an array of values by running each element in `collection` thru - * `iteratee`. The iteratee is invoked with three arguments: - * (value, index|key, collection). - * - * Many lodash methods are guarded to work as iteratees for methods like - * `_.every`, `_.filter`, `_.map`, `_.mapValues`, `_.reject`, and `_.some`. - * - * The guarded methods are: - * `ary`, `chunk`, `curry`, `curryRight`, `drop`, `dropRight`, `every`, - * `fill`, `invert`, `parseInt`, `random`, `range`, `rangeRight`, `repeat`, - * `sampleSize`, `slice`, `some`, `sortBy`, `split`, `take`, `takeRight`, - * `template`, `trim`, `trimEnd`, `trimStart`, and `words` - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object} collection The collection to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @returns {Array} Returns the new mapped array. - * @example - * - * function square(n) { - * return n * n; - * } - * - * _.map([4, 8], square); - * // => [16, 64] - * - * _.map({ 'a': 4, 'b': 8 }, square); - * // => [16, 64] (iteration order is not guaranteed) - * - * var users = [ - * { 'user': 'barney' }, - * { 'user': 'fred' } - * ]; - * - * // The `_.property` iteratee shorthand. - * _.map(users, 'user'); - * // => ['barney', 'fred'] - */function map(collection,iteratee){var func=isArray(collection)?arrayMap:baseMap;return func(collection,baseIteratee(iteratee,3))}module.exports=map},{"./_arrayMap":129,"./_baseIteratee":165,"./_baseMap":169,"./isArray":303}],323:[function(require,module,exports){var baseAssignValue=require("./_baseAssignValue"),baseForOwn=require("./_baseForOwn"),baseIteratee=require("./_baseIteratee"); -/** - * Creates an object with the same keys as `object` and values generated - * by running each own enumerable string keyed property of `object` thru - * `iteratee`. The iteratee is invoked with three arguments: - * (value, key, object). - * - * @static - * @memberOf _ - * @since 2.4.0 - * @category Object - * @param {Object} object The object to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @returns {Object} Returns the new mapped object. - * @see _.mapKeys - * @example - * - * var users = { - * 'fred': { 'user': 'fred', 'age': 40 }, - * 'pebbles': { 'user': 'pebbles', 'age': 1 } - * }; - * - * _.mapValues(users, function(o) { return o.age; }); - * // => { 'fred': 40, 'pebbles': 1 } (iteration order is not guaranteed) - * - * // The `_.property` iteratee shorthand. - * _.mapValues(users, 'age'); - * // => { 'fred': 40, 'pebbles': 1 } (iteration order is not guaranteed) - */function mapValues(object,iteratee){var result={};iteratee=baseIteratee(iteratee,3);baseForOwn(object,function(value,key,object){baseAssignValue(result,key,iteratee(value,key,object))});return result}module.exports=mapValues},{"./_baseAssignValue":139,"./_baseForOwn":148,"./_baseIteratee":165}],324:[function(require,module,exports){var baseExtremum=require("./_baseExtremum"),baseGt=require("./_baseGt"),identity=require("./identity"); -/** - * Computes the maximum value of `array`. If `array` is empty or falsey, - * `undefined` is returned. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Math - * @param {Array} array The array to iterate over. - * @returns {*} Returns the maximum value. - * @example - * - * _.max([4, 2, 8, 6]); - * // => 8 - * - * _.max([]); - * // => undefined - */function max(array){return array&&array.length?baseExtremum(array,identity,baseGt):undefined}module.exports=max},{"./_baseExtremum":143,"./_baseGt":152,"./identity":301}],325:[function(require,module,exports){var MapCache=require("./_MapCache"); -/** Error message constants. */var FUNC_ERROR_TEXT="Expected a function"; -/** - * Creates a function that memoizes the result of `func`. If `resolver` is - * provided, it determines the cache key for storing the result based on the - * arguments provided to the memoized function. By default, the first argument - * provided to the memoized function is used as the map cache key. The `func` - * is invoked with the `this` binding of the memoized function. - * - * **Note:** The cache is exposed as the `cache` property on the memoized - * function. Its creation may be customized by replacing the `_.memoize.Cache` - * constructor with one whose instances implement the - * [`Map`](http://ecma-international.org/ecma-262/7.0/#sec-properties-of-the-map-prototype-object) - * method interface of `clear`, `delete`, `get`, `has`, and `set`. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Function - * @param {Function} func The function to have its output memoized. - * @param {Function} [resolver] The function to resolve the cache key. - * @returns {Function} Returns the new memoized function. - * @example - * - * var object = { 'a': 1, 'b': 2 }; - * var other = { 'c': 3, 'd': 4 }; - * - * var values = _.memoize(_.values); - * values(object); - * // => [1, 2] - * - * values(other); - * // => [3, 4] - * - * object.a = 2; - * values(object); - * // => [1, 2] - * - * // Modify the result cache. - * values.cache.set(object, ['a', 'b']); - * values(object); - * // => ['a', 'b'] - * - * // Replace `_.memoize.Cache`. - * _.memoize.Cache = WeakMap; - */function memoize(func,resolver){if(typeof func!="function"||resolver!=null&&typeof resolver!="function"){throw new TypeError(FUNC_ERROR_TEXT)}var memoized=function(){var args=arguments,key=resolver?resolver.apply(this,args):args[0],cache=memoized.cache;if(cache.has(key)){return cache.get(key)}var result=func.apply(this,args);memoized.cache=cache.set(key,result)||cache;return result};memoized.cache=new(memoize.Cache||MapCache);return memoized} -// Expose `MapCache`. -memoize.Cache=MapCache;module.exports=memoize},{"./_MapCache":115}],326:[function(require,module,exports){var baseMerge=require("./_baseMerge"),createAssigner=require("./_createAssigner"); -/** - * This method is like `_.assign` except that it recursively merges own and - * inherited enumerable string keyed properties of source objects into the - * destination object. Source properties that resolve to `undefined` are - * skipped if a destination value exists. Array and plain object properties - * are merged recursively. Other objects and value types are overridden by - * assignment. Source objects are applied from left to right. Subsequent - * sources overwrite property assignments of previous sources. - * - * **Note:** This method mutates `object`. - * - * @static - * @memberOf _ - * @since 0.5.0 - * @category Object - * @param {Object} object The destination object. - * @param {...Object} [sources] The source objects. - * @returns {Object} Returns `object`. - * @example - * - * var object = { - * 'a': [{ 'b': 2 }, { 'd': 4 }] - * }; - * - * var other = { - * 'a': [{ 'c': 3 }, { 'e': 5 }] - * }; - * - * _.merge(object, other); - * // => { 'a': [{ 'b': 2, 'c': 3 }, { 'd': 4, 'e': 5 }] } - */var merge=createAssigner(function(object,source,srcIndex){baseMerge(object,source,srcIndex)});module.exports=merge},{"./_baseMerge":172,"./_createAssigner":207}],327:[function(require,module,exports){var baseExtremum=require("./_baseExtremum"),baseLt=require("./_baseLt"),identity=require("./identity"); -/** - * Computes the minimum value of `array`. If `array` is empty or falsey, - * `undefined` is returned. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Math - * @param {Array} array The array to iterate over. - * @returns {*} Returns the minimum value. - * @example - * - * _.min([4, 2, 8, 6]); - * // => 2 - * - * _.min([]); - * // => undefined - */function min(array){return array&&array.length?baseExtremum(array,identity,baseLt):undefined}module.exports=min},{"./_baseExtremum":143,"./_baseLt":168,"./identity":301}],328:[function(require,module,exports){var baseExtremum=require("./_baseExtremum"),baseIteratee=require("./_baseIteratee"),baseLt=require("./_baseLt"); -/** - * This method is like `_.min` except that it accepts `iteratee` which is - * invoked for each element in `array` to generate the criterion by which - * the value is ranked. The iteratee is invoked with one argument: (value). - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Math - * @param {Array} array The array to iterate over. - * @param {Function} [iteratee=_.identity] The iteratee invoked per element. - * @returns {*} Returns the minimum value. - * @example - * - * var objects = [{ 'n': 1 }, { 'n': 2 }]; - * - * _.minBy(objects, function(o) { return o.n; }); - * // => { 'n': 1 } - * - * // The `_.property` iteratee shorthand. - * _.minBy(objects, 'n'); - * // => { 'n': 1 } - */function minBy(array,iteratee){return array&&array.length?baseExtremum(array,baseIteratee(iteratee,2),baseLt):undefined}module.exports=minBy},{"./_baseExtremum":143,"./_baseIteratee":165,"./_baseLt":168}],329:[function(require,module,exports){ -/** - * This method returns `undefined`. - * - * @static - * @memberOf _ - * @since 2.3.0 - * @category Util - * @example - * - * _.times(2, _.noop); - * // => [undefined, undefined] - */ -function noop(){ -// No operation performed. -}module.exports=noop},{}],330:[function(require,module,exports){var root=require("./_root"); -/** - * Gets the timestamp of the number of milliseconds that have elapsed since - * the Unix epoch (1 January 1970 00:00:00 UTC). - * - * @static - * @memberOf _ - * @since 2.4.0 - * @category Date - * @returns {number} Returns the timestamp. - * @example - * - * _.defer(function(stamp) { - * console.log(_.now() - stamp); - * }, _.now()); - * // => Logs the number of milliseconds it took for the deferred invocation. - */var now=function(){return root.Date.now()};module.exports=now},{"./_root":268}],331:[function(require,module,exports){var basePick=require("./_basePick"),flatRest=require("./_flatRest"); -/** - * Creates an object composed of the picked `object` properties. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Object - * @param {Object} object The source object. - * @param {...(string|string[])} [paths] The property paths to pick. - * @returns {Object} Returns the new object. - * @example - * - * var object = { 'a': 1, 'b': '2', 'c': 3 }; - * - * _.pick(object, ['a', 'c']); - * // => { 'a': 1, 'c': 3 } - */var pick=flatRest(function(object,paths){return object==null?{}:basePick(object,paths)});module.exports=pick},{"./_basePick":175,"./_flatRest":217}],332:[function(require,module,exports){var baseProperty=require("./_baseProperty"),basePropertyDeep=require("./_basePropertyDeep"),isKey=require("./_isKey"),toKey=require("./_toKey"); -/** - * Creates a function that returns the value at `path` of a given object. - * - * @static - * @memberOf _ - * @since 2.4.0 - * @category Util - * @param {Array|string} path The path of the property to get. - * @returns {Function} Returns the new accessor function. - * @example - * - * var objects = [ - * { 'a': { 'b': 2 } }, - * { 'a': { 'b': 1 } } - * ]; - * - * _.map(objects, _.property('a.b')); - * // => [2, 1] - * - * _.map(_.sortBy(objects, _.property(['a', 'b'])), 'a.b'); - * // => [1, 2] - */function property(path){return isKey(path)?baseProperty(toKey(path)):basePropertyDeep(path)}module.exports=property},{"./_baseProperty":177,"./_basePropertyDeep":178,"./_isKey":243,"./_toKey":283}],333:[function(require,module,exports){var createRange=require("./_createRange"); -/** - * Creates an array of numbers (positive and/or negative) progressing from - * `start` up to, but not including, `end`. A step of `-1` is used if a negative - * `start` is specified without an `end` or `step`. If `end` is not specified, - * it's set to `start` with `start` then set to `0`. - * - * **Note:** JavaScript follows the IEEE-754 standard for resolving - * floating-point values which can produce unexpected results. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Util - * @param {number} [start=0] The start of the range. - * @param {number} end The end of the range. - * @param {number} [step=1] The value to increment or decrement by. - * @returns {Array} Returns the range of numbers. - * @see _.inRange, _.rangeRight - * @example - * - * _.range(4); - * // => [0, 1, 2, 3] - * - * _.range(-4); - * // => [0, -1, -2, -3] - * - * _.range(1, 5); - * // => [1, 2, 3, 4] - * - * _.range(0, 20, 5); - * // => [0, 5, 10, 15] - * - * _.range(0, -4, -1); - * // => [0, -1, -2, -3] - * - * _.range(1, 4, 0); - * // => [1, 1, 1] - * - * _.range(0); - * // => [] - */var range=createRange();module.exports=range},{"./_createRange":211}],334:[function(require,module,exports){var arrayReduce=require("./_arrayReduce"),baseEach=require("./_baseEach"),baseIteratee=require("./_baseIteratee"),baseReduce=require("./_baseReduce"),isArray=require("./isArray"); -/** - * Reduces `collection` to a value which is the accumulated result of running - * each element in `collection` thru `iteratee`, where each successive - * invocation is supplied the return value of the previous. If `accumulator` - * is not given, the first element of `collection` is used as the initial - * value. The iteratee is invoked with four arguments: - * (accumulator, value, index|key, collection). - * - * Many lodash methods are guarded to work as iteratees for methods like - * `_.reduce`, `_.reduceRight`, and `_.transform`. - * - * The guarded methods are: - * `assign`, `defaults`, `defaultsDeep`, `includes`, `merge`, `orderBy`, - * and `sortBy` - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object} collection The collection to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @param {*} [accumulator] The initial value. - * @returns {*} Returns the accumulated value. - * @see _.reduceRight - * @example - * - * _.reduce([1, 2], function(sum, n) { - * return sum + n; - * }, 0); - * // => 3 - * - * _.reduce({ 'a': 1, 'b': 2, 'c': 1 }, function(result, value, key) { - * (result[value] || (result[value] = [])).push(key); - * return result; - * }, {}); - * // => { '1': ['a', 'c'], '2': ['b'] } (iteration order is not guaranteed) - */function reduce(collection,iteratee,accumulator){var func=isArray(collection)?arrayReduce:baseReduce,initAccum=arguments.length<3;return func(collection,baseIteratee(iteratee,4),accumulator,initAccum,baseEach)}module.exports=reduce},{"./_arrayReduce":131,"./_baseEach":142,"./_baseIteratee":165,"./_baseReduce":180,"./isArray":303}],335:[function(require,module,exports){var baseKeys=require("./_baseKeys"),getTag=require("./_getTag"),isArrayLike=require("./isArrayLike"),isString=require("./isString"),stringSize=require("./_stringSize"); -/** `Object#toString` result references. */var mapTag="[object Map]",setTag="[object Set]"; -/** - * Gets the size of `collection` by returning its length for array-like - * values or the number of own enumerable string keyed properties for objects. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object|string} collection The collection to inspect. - * @returns {number} Returns the collection size. - * @example - * - * _.size([1, 2, 3]); - * // => 3 - * - * _.size({ 'a': 1, 'b': 2 }); - * // => 2 - * - * _.size('pebbles'); - * // => 7 - */function size(collection){if(collection==null){return 0}if(isArrayLike(collection)){return isString(collection)?stringSize(collection):collection.length}var tag=getTag(collection);if(tag==mapTag||tag==setTag){return collection.size}return baseKeys(collection).length}module.exports=size},{"./_baseKeys":166,"./_getTag":228,"./_stringSize":281,"./isArrayLike":304,"./isString":315}],336:[function(require,module,exports){var baseFlatten=require("./_baseFlatten"),baseOrderBy=require("./_baseOrderBy"),baseRest=require("./_baseRest"),isIterateeCall=require("./_isIterateeCall"); -/** - * Creates an array of elements, sorted in ascending order by the results of - * running each element in a collection thru each iteratee. This method - * performs a stable sort, that is, it preserves the original sort order of - * equal elements. The iteratees are invoked with one argument: (value). - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Collection - * @param {Array|Object} collection The collection to iterate over. - * @param {...(Function|Function[])} [iteratees=[_.identity]] - * The iteratees to sort by. - * @returns {Array} Returns the new sorted array. - * @example - * - * var users = [ - * { 'user': 'fred', 'age': 48 }, - * { 'user': 'barney', 'age': 36 }, - * { 'user': 'fred', 'age': 40 }, - * { 'user': 'barney', 'age': 34 } - * ]; - * - * _.sortBy(users, [function(o) { return o.user; }]); - * // => objects for [['barney', 36], ['barney', 34], ['fred', 48], ['fred', 40]] - * - * _.sortBy(users, ['user', 'age']); - * // => objects for [['barney', 34], ['barney', 36], ['fred', 40], ['fred', 48]] - */var sortBy=baseRest(function(collection,iteratees){if(collection==null){return[]}var length=iteratees.length;if(length>1&&isIterateeCall(collection,iteratees[0],iteratees[1])){iteratees=[]}else if(length>2&&isIterateeCall(iteratees[0],iteratees[1],iteratees[2])){iteratees=[iteratees[0]]}return baseOrderBy(collection,baseFlatten(iteratees,1),[])});module.exports=sortBy},{"./_baseFlatten":146,"./_baseOrderBy":174,"./_baseRest":181,"./_isIterateeCall":242}],337:[function(require,module,exports){ -/** - * This method returns a new empty array. - * - * @static - * @memberOf _ - * @since 4.13.0 - * @category Util - * @returns {Array} Returns the new empty array. - * @example - * - * var arrays = _.times(2, _.stubArray); - * - * console.log(arrays); - * // => [[], []] - * - * console.log(arrays[0] === arrays[1]); - * // => false - */ -function stubArray(){return[]}module.exports=stubArray},{}],338:[function(require,module,exports){ -/** - * This method returns `false`. - * - * @static - * @memberOf _ - * @since 4.13.0 - * @category Util - * @returns {boolean} Returns `false`. - * @example - * - * _.times(2, _.stubFalse); - * // => [false, false] - */ -function stubFalse(){return false}module.exports=stubFalse},{}],339:[function(require,module,exports){var toNumber=require("./toNumber"); -/** Used as references for various `Number` constants. */var INFINITY=1/0,MAX_INTEGER=17976931348623157e292; -/** - * Converts `value` to a finite number. - * - * @static - * @memberOf _ - * @since 4.12.0 - * @category Lang - * @param {*} value The value to convert. - * @returns {number} Returns the converted number. - * @example - * - * _.toFinite(3.2); - * // => 3.2 - * - * _.toFinite(Number.MIN_VALUE); - * // => 5e-324 - * - * _.toFinite(Infinity); - * // => 1.7976931348623157e+308 - * - * _.toFinite('3.2'); - * // => 3.2 - */function toFinite(value){if(!value){return value===0?value:0}value=toNumber(value);if(value===INFINITY||value===-INFINITY){var sign=value<0?-1:1;return sign*MAX_INTEGER}return value===value?value:0}module.exports=toFinite},{"./toNumber":341}],340:[function(require,module,exports){var toFinite=require("./toFinite"); -/** - * Converts `value` to an integer. - * - * **Note:** This method is loosely based on - * [`ToInteger`](http://www.ecma-international.org/ecma-262/7.0/#sec-tointeger). - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to convert. - * @returns {number} Returns the converted integer. - * @example - * - * _.toInteger(3.2); - * // => 3 - * - * _.toInteger(Number.MIN_VALUE); - * // => 0 - * - * _.toInteger(Infinity); - * // => 1.7976931348623157e+308 - * - * _.toInteger('3.2'); - * // => 3 - */function toInteger(value){var result=toFinite(value),remainder=result%1;return result===result?remainder?result-remainder:result:0}module.exports=toInteger},{"./toFinite":339}],341:[function(require,module,exports){var isObject=require("./isObject"),isSymbol=require("./isSymbol"); -/** Used as references for various `Number` constants. */var NAN=0/0; -/** Used to match leading and trailing whitespace. */var reTrim=/^\s+|\s+$/g; -/** Used to detect bad signed hexadecimal string values. */var reIsBadHex=/^[-+]0x[0-9a-f]+$/i; -/** Used to detect binary string values. */var reIsBinary=/^0b[01]+$/i; -/** Used to detect octal string values. */var reIsOctal=/^0o[0-7]+$/i; -/** Built-in method references without a dependency on `root`. */var freeParseInt=parseInt; -/** - * Converts `value` to a number. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to process. - * @returns {number} Returns the number. - * @example - * - * _.toNumber(3.2); - * // => 3.2 - * - * _.toNumber(Number.MIN_VALUE); - * // => 5e-324 - * - * _.toNumber(Infinity); - * // => Infinity - * - * _.toNumber('3.2'); - * // => 3.2 - */function toNumber(value){if(typeof value=="number"){return value}if(isSymbol(value)){return NAN}if(isObject(value)){var other=typeof value.valueOf=="function"?value.valueOf():value;value=isObject(other)?other+"":other}if(typeof value!="string"){return value===0?value:+value}value=value.replace(reTrim,"");var isBinary=reIsBinary.test(value);return isBinary||reIsOctal.test(value)?freeParseInt(value.slice(2),isBinary?2:8):reIsBadHex.test(value)?NAN:+value}module.exports=toNumber},{"./isObject":311,"./isSymbol":316}],342:[function(require,module,exports){var copyObject=require("./_copyObject"),keysIn=require("./keysIn"); -/** - * Converts `value` to a plain object flattening inherited enumerable string - * keyed properties of `value` to own properties of the plain object. - * - * @static - * @memberOf _ - * @since 3.0.0 - * @category Lang - * @param {*} value The value to convert. - * @returns {Object} Returns the converted plain object. - * @example - * - * function Foo() { - * this.b = 2; - * } - * - * Foo.prototype.c = 3; - * - * _.assign({ 'a': 1 }, new Foo); - * // => { 'a': 1, 'b': 2 } - * - * _.assign({ 'a': 1 }, _.toPlainObject(new Foo)); - * // => { 'a': 1, 'b': 2, 'c': 3 } - */function toPlainObject(value){return copyObject(value,keysIn(value))}module.exports=toPlainObject},{"./_copyObject":203,"./keysIn":320}],343:[function(require,module,exports){var baseToString=require("./_baseToString"); -/** - * Converts `value` to a string. An empty string is returned for `null` - * and `undefined` values. The sign of `-0` is preserved. - * - * @static - * @memberOf _ - * @since 4.0.0 - * @category Lang - * @param {*} value The value to convert. - * @returns {string} Returns the converted string. - * @example - * - * _.toString(null); - * // => '' - * - * _.toString(-0); - * // => '-0' - * - * _.toString([1, 2, 3]); - * // => '1,2,3' - */function toString(value){return value==null?"":baseToString(value)}module.exports=toString},{"./_baseToString":186}],344:[function(require,module,exports){var arrayEach=require("./_arrayEach"),baseCreate=require("./_baseCreate"),baseForOwn=require("./_baseForOwn"),baseIteratee=require("./_baseIteratee"),getPrototype=require("./_getPrototype"),isArray=require("./isArray"),isBuffer=require("./isBuffer"),isFunction=require("./isFunction"),isObject=require("./isObject"),isTypedArray=require("./isTypedArray"); -/** - * An alternative to `_.reduce`; this method transforms `object` to a new - * `accumulator` object which is the result of running each of its own - * enumerable string keyed properties thru `iteratee`, with each invocation - * potentially mutating the `accumulator` object. If `accumulator` is not - * provided, a new object with the same `[[Prototype]]` will be used. The - * iteratee is invoked with four arguments: (accumulator, value, key, object). - * Iteratee functions may exit iteration early by explicitly returning `false`. - * - * @static - * @memberOf _ - * @since 1.3.0 - * @category Object - * @param {Object} object The object to iterate over. - * @param {Function} [iteratee=_.identity] The function invoked per iteration. - * @param {*} [accumulator] The custom accumulator value. - * @returns {*} Returns the accumulated value. - * @example - * - * _.transform([2, 3, 4], function(result, n) { - * result.push(n *= n); - * return n % 2 == 0; - * }, []); - * // => [4, 9] - * - * _.transform({ 'a': 1, 'b': 2, 'c': 1 }, function(result, value, key) { - * (result[value] || (result[value] = [])).push(key); - * }, {}); - * // => { '1': ['a', 'c'], '2': ['b'] } - */function transform(object,iteratee,accumulator){var isArr=isArray(object),isArrLike=isArr||isBuffer(object)||isTypedArray(object);iteratee=baseIteratee(iteratee,4);if(accumulator==null){var Ctor=object&&object.constructor;if(isArrLike){accumulator=isArr?new Ctor:[]}else if(isObject(object)){accumulator=isFunction(Ctor)?baseCreate(getPrototype(object)):{}}else{accumulator={}}}(isArrLike?arrayEach:baseForOwn)(object,function(value,index,object){return iteratee(accumulator,value,index,object)});return accumulator}module.exports=transform},{"./_arrayEach":124,"./_baseCreate":141,"./_baseForOwn":148,"./_baseIteratee":165,"./_getPrototype":224,"./isArray":303,"./isBuffer":306,"./isFunction":308,"./isObject":311,"./isTypedArray":317}],345:[function(require,module,exports){var baseFlatten=require("./_baseFlatten"),baseRest=require("./_baseRest"),baseUniq=require("./_baseUniq"),isArrayLikeObject=require("./isArrayLikeObject"); -/** - * Creates an array of unique values, in order, from all given arrays using - * [`SameValueZero`](http://ecma-international.org/ecma-262/7.0/#sec-samevaluezero) - * for equality comparisons. - * - * @static - * @memberOf _ - * @since 0.1.0 - * @category Array - * @param {...Array} [arrays] The arrays to inspect. - * @returns {Array} Returns the new array of combined values. - * @example - * - * _.union([2], [1, 2]); - * // => [2, 1] - */var union=baseRest(function(arrays){return baseUniq(baseFlatten(arrays,1,isArrayLikeObject,true))});module.exports=union},{"./_baseFlatten":146,"./_baseRest":181,"./_baseUniq":188,"./isArrayLikeObject":305}],346:[function(require,module,exports){var toString=require("./toString"); -/** Used to generate unique IDs. */var idCounter=0; -/** - * Generates a unique ID. If `prefix` is given, the ID is appended to it. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Util - * @param {string} [prefix=''] The value to prefix the ID with. - * @returns {string} Returns the unique ID. - * @example - * - * _.uniqueId('contact_'); - * // => 'contact_104' - * - * _.uniqueId(); - * // => '105' - */function uniqueId(prefix){var id=++idCounter;return toString(prefix)+id}module.exports=uniqueId},{"./toString":343}],347:[function(require,module,exports){var baseValues=require("./_baseValues"),keys=require("./keys"); -/** - * Creates an array of the own enumerable string keyed property values of `object`. - * - * **Note:** Non-object values are coerced to objects. - * - * @static - * @since 0.1.0 - * @memberOf _ - * @category Object - * @param {Object} object The object to query. - * @returns {Array} Returns the array of property values. - * @example - * - * function Foo() { - * this.a = 1; - * this.b = 2; - * } - * - * Foo.prototype.c = 3; - * - * _.values(new Foo); - * // => [1, 2] (iteration order is not guaranteed) - * - * _.values('hi'); - * // => ['h', 'i'] - */function values(object){return object==null?[]:baseValues(object,keys(object))}module.exports=values},{"./_baseValues":189,"./keys":319}],348:[function(require,module,exports){var assignValue=require("./_assignValue"),baseZipObject=require("./_baseZipObject"); -/** - * This method is like `_.fromPairs` except that it accepts two arrays, - * one of property identifiers and one of corresponding values. - * - * @static - * @memberOf _ - * @since 0.4.0 - * @category Array - * @param {Array} [props=[]] The property identifiers. - * @param {Array} [values=[]] The property values. - * @returns {Object} Returns the new object. - * @example - * - * _.zipObject(['a', 'b'], [1, 2]); - * // => { 'a': 1, 'b': 2 } - */function zipObject(props,values){return baseZipObject(props||[],values||[],assignValue)}module.exports=zipObject},{"./_assignValue":135,"./_baseZipObject":190}]},{},[1])(1)}); \ No newline at end of file diff --git a/tinygrad_repo/tinygrad/viz/assets/dagrejs.github.io/project/dagre/latest/dagre.min.js b/tinygrad_repo/tinygrad/viz/assets/dagrejs.github.io/project/dagre/latest/dagre.min.js new file mode 100644 index 0000000000..01b25ea0f8 --- /dev/null +++ b/tinygrad_repo/tinygrad/viz/assets/dagrejs.github.io/project/dagre/latest/dagre.min.js @@ -0,0 +1,801 @@ +(function(f){if(typeof exports==="object"&&typeof module!=="undefined"){module.exports=f()}else if(typeof define==="function"&&define.amd){define([],f)}else{var g;if(typeof window!=="undefined"){g=window}else if(typeof global!=="undefined"){g=global}else if(typeof self!=="undefined"){g=self}else{g=this}g.dagre=f()}})(function(){var define,module,exports;return function(){function r(e,n,t){function o(i,f){if(!n[i]){if(!e[i]){var c="function"==typeof require&&require;if(!f&&c)return c(i,!0);if(u)return u(i,!0);var a=new Error("Cannot find module '"+i+"'");throw a.code="MODULE_NOT_FOUND",a}var p=n[i]={exports:{}};e[i][0].call(p.exports,function(r){var n=e[i][1][r];return o(n||r)},p,p.exports,r,e,n,t)}return n[i].exports}for(var u="function"==typeof require&&require,i=0;i{let label=g.edge(e);g.removeEdge(e);label.forwardName=e.name;label.reversed=true;g.setEdge(e.w,e.v,label,uniqueId("rev"))});function weightFn(g){return e=>{return g.edge(e).weight}}}function dfsFAS(g){let fas=[];let stack={};let visited={};function dfs(v){if(Object.hasOwn(visited,v)){return}visited[v]=true;stack[v]=true;g.outEdges(v).forEach(e=>{if(Object.hasOwn(stack,e.w)){fas.push(e)}else{dfs(e.w)}});delete stack[v]}g.nodes().forEach(dfs);return fas}function undo(g){g.edges().forEach(e=>{let label=g.edge(e);if(label.reversed){g.removeEdge(e);let forwardName=label.forwardName;delete label.reversed;delete label.forwardName;g.setEdge(e.w,e.v,label,forwardName)}})}},{"./greedy-fas":7,"./util":27}],3:[function(require,module,exports){let util=require("./util");module.exports=addBorderSegments;function addBorderSegments(g){function dfs(v){let children=g.children(v);let node=g.node(v);if(children.length){children.forEach(dfs)}if(Object.hasOwn(node,"minRank")){node.borderLeft=[];node.borderRight=[];for(let rank=node.minRank,maxRank=node.maxRank+1;rankswapWidthHeightOne(g.node(v)));g.edges().forEach(e=>swapWidthHeightOne(g.edge(e)))}function swapWidthHeightOne(attrs){let w=attrs.width;attrs.width=attrs.height;attrs.height=w}function reverseY(g){g.nodes().forEach(v=>reverseYOne(g.node(v)));g.edges().forEach(e=>{let edge=g.edge(e);edge.points.forEach(reverseYOne);if(Object.hasOwn(edge,"y")){reverseYOne(edge)}})}function reverseYOne(attrs){attrs.y=-attrs.y}function swapXY(g){g.nodes().forEach(v=>swapXYOne(g.node(v)));g.edges().forEach(e=>{let edge=g.edge(e);edge.points.forEach(swapXYOne);if(Object.hasOwn(edge,"x")){swapXYOne(edge)}})}function swapXYOne(attrs){let x=attrs.x;attrs.x=attrs.y;attrs.y=x}},{}],5:[function(require,module,exports){ +/* + * Simple doubly linked list implementation derived from Cormen, et al., + * "Introduction to Algorithms". + */ +class List{constructor(){let sentinel={};sentinel._next=sentinel._prev=sentinel;this._sentinel=sentinel}dequeue(){let sentinel=this._sentinel;let entry=sentinel._prev;if(entry!==sentinel){unlink(entry);return entry}}enqueue(entry){let sentinel=this._sentinel;if(entry._prev&&entry._next){unlink(entry)}entry._next=sentinel._next;sentinel._next._prev=entry;sentinel._next=entry;entry._prev=sentinel}toString(){let strs=[];let sentinel=this._sentinel;let curr=sentinel._prev;while(curr!==sentinel){strs.push(JSON.stringify(curr,filterOutLinks));curr=curr._prev}return"["+strs.join(", ")+"]"}}function unlink(entry){entry._prev._next=entry._next;entry._next._prev=entry._prev;delete entry._next;delete entry._prev}function filterOutLinks(k,v){if(k!=="_next"&&k!=="_prev"){return v}}module.exports=List},{}],6:[function(require,module,exports){let util=require("./util");let Graph=require("@dagrejs/graphlib").Graph;module.exports={debugOrdering:debugOrdering}; +/* istanbul ignore next */function debugOrdering(g){let layerMatrix=util.buildLayerMatrix(g);let h=new Graph({compound:true,multigraph:true}).setGraph({});g.nodes().forEach(v=>{h.setNode(v,{label:v});h.setParent(v,"layer"+g.node(v).rank)});g.edges().forEach(e=>h.setEdge(e.v,e.w,{},e.name));layerMatrix.forEach((layer,i)=>{let layerV="layer"+i;h.setNode(layerV,{rank:"same"});layer.reduce((u,v)=>{h.setEdge(u,v,{style:"invis"});return v})});return h}},{"./util":27,"@dagrejs/graphlib":29}],7:[function(require,module,exports){let Graph=require("@dagrejs/graphlib").Graph;let List=require("./data/list"); +/* + * A greedy heuristic for finding a feedback arc set for a graph. A feedback + * arc set is a set of edges that can be removed to make a graph acyclic. + * The algorithm comes from: P. Eades, X. Lin, and W. F. Smyth, "A fast and + * effective heuristic for the feedback arc set problem." This implementation + * adjusts that from the paper to allow for weighted edges. + */module.exports=greedyFAS;let DEFAULT_WEIGHT_FN=()=>1;function greedyFAS(g,weightFn){if(g.nodeCount()<=1){return[]}let state=buildState(g,weightFn||DEFAULT_WEIGHT_FN);let results=doGreedyFAS(state.graph,state.buckets,state.zeroIdx); +// Expand multi-edges +return results.flatMap(e=>g.outEdges(e.v,e.w))}function doGreedyFAS(g,buckets,zeroIdx){let results=[];let sources=buckets[buckets.length-1];let sinks=buckets[0];let entry;while(g.nodeCount()){while(entry=sinks.dequeue()){removeNode(g,buckets,zeroIdx,entry)}while(entry=sources.dequeue()){removeNode(g,buckets,zeroIdx,entry)}if(g.nodeCount()){for(let i=buckets.length-2;i>0;--i){entry=buckets[i].dequeue();if(entry){results=results.concat(removeNode(g,buckets,zeroIdx,entry,true));break}}}}return results}function removeNode(g,buckets,zeroIdx,entry,collectPredecessors){let results=collectPredecessors?[]:undefined;g.inEdges(entry.v).forEach(edge=>{let weight=g.edge(edge);let uEntry=g.node(edge.v);if(collectPredecessors){results.push({v:edge.v,w:edge.w})}uEntry.out-=weight;assignBucket(buckets,zeroIdx,uEntry)});g.outEdges(entry.v).forEach(edge=>{let weight=g.edge(edge);let w=edge.w;let wEntry=g.node(w);wEntry["in"]-=weight;assignBucket(buckets,zeroIdx,wEntry)});g.removeNode(entry.v);return results}function buildState(g,weightFn){let fasGraph=new Graph;let maxIn=0;let maxOut=0;g.nodes().forEach(v=>{fasGraph.setNode(v,{v:v,in:0,out:0})}); +// Aggregate weights on nodes, but also sum the weights across multi-edges +// into a single edge for the fasGraph. +g.edges().forEach(e=>{let prevWeight=fasGraph.edge(e.v,e.w)||0;let weight=weightFn(e);let edgeWeight=prevWeight+weight;fasGraph.setEdge(e.v,e.w,edgeWeight);maxOut=Math.max(maxOut,fasGraph.node(e.v).out+=weight);maxIn=Math.max(maxIn,fasGraph.node(e.w)["in"]+=weight)});let buckets=range(maxOut+maxIn+3).map(()=>new List);let zeroIdx=maxIn+1;fasGraph.nodes().forEach(v=>{assignBucket(buckets,zeroIdx,fasGraph.node(v))});return{graph:fasGraph,buckets:buckets,zeroIdx:zeroIdx}}function assignBucket(buckets,zeroIdx,entry){if(!entry.out){buckets[0].enqueue(entry)}else if(!entry["in"]){buckets[buckets.length-1].enqueue(entry)}else{buckets[entry.out-entry["in"]+zeroIdx].enqueue(entry)}}function range(limit){const range=[];for(let i=0;i{let layoutGraph=time(" buildLayoutGraph",()=>buildLayoutGraph(g));time(" runLayout",()=>runLayout(layoutGraph,time,opts));time(" updateInputGraph",()=>updateInputGraph(g,layoutGraph))})}function runLayout(g,time,opts){time(" makeSpaceForEdgeLabels",()=>makeSpaceForEdgeLabels(g));time(" removeSelfEdges",()=>removeSelfEdges(g));time(" acyclic",()=>acyclic.run(g));time(" nestingGraph.run",()=>nestingGraph.run(g));time(" rank",()=>rank(util.asNonCompoundGraph(g)));time(" injectEdgeLabelProxies",()=>injectEdgeLabelProxies(g));time(" removeEmptyRanks",()=>removeEmptyRanks(g));time(" nestingGraph.cleanup",()=>nestingGraph.cleanup(g));time(" normalizeRanks",()=>normalizeRanks(g));time(" assignRankMinMax",()=>assignRankMinMax(g));time(" removeEdgeLabelProxies",()=>removeEdgeLabelProxies(g));time(" normalize.run",()=>normalize.run(g));time(" parentDummyChains",()=>parentDummyChains(g));time(" addBorderSegments",()=>addBorderSegments(g));time(" order",()=>order(g,opts));time(" insertSelfEdges",()=>insertSelfEdges(g));time(" adjustCoordinateSystem",()=>coordinateSystem.adjust(g));time(" position",()=>position(g));time(" positionSelfEdges",()=>positionSelfEdges(g));time(" removeBorderNodes",()=>removeBorderNodes(g));time(" normalize.undo",()=>normalize.undo(g));time(" fixupEdgeLabelCoords",()=>fixupEdgeLabelCoords(g));time(" undoCoordinateSystem",()=>coordinateSystem.undo(g));time(" translateGraph",()=>translateGraph(g));time(" assignNodeIntersects",()=>assignNodeIntersects(g));time(" reversePoints",()=>reversePointsForReversedEdges(g));time(" acyclic.undo",()=>acyclic.undo(g))} +/* + * Copies final layout information from the layout graph back to the input + * graph. This process only copies whitelisted attributes from the layout graph + * to the input graph, so it serves as a good place to determine what + * attributes can influence layout. + */function updateInputGraph(inputGraph,layoutGraph){inputGraph.nodes().forEach(v=>{let inputLabel=inputGraph.node(v);let layoutLabel=layoutGraph.node(v);if(inputLabel){inputLabel.x=layoutLabel.x;inputLabel.y=layoutLabel.y;inputLabel.rank=layoutLabel.rank;if(layoutGraph.children(v).length){inputLabel.width=layoutLabel.width;inputLabel.height=layoutLabel.height}}});inputGraph.edges().forEach(e=>{let inputLabel=inputGraph.edge(e);let layoutLabel=layoutGraph.edge(e);inputLabel.points=layoutLabel.points;if(Object.hasOwn(layoutLabel,"x")){inputLabel.x=layoutLabel.x;inputLabel.y=layoutLabel.y}});inputGraph.graph().width=layoutGraph.graph().width;inputGraph.graph().height=layoutGraph.graph().height}let graphNumAttrs=["nodesep","edgesep","ranksep","marginx","marginy"];let graphDefaults={ranksep:50,edgesep:20,nodesep:50,rankdir:"tb"};let graphAttrs=["acyclicer","ranker","rankdir","align"];let nodeNumAttrs=["width","height"];let nodeDefaults={width:0,height:0};let edgeNumAttrs=["minlen","weight","width","height","labeloffset"];let edgeDefaults={minlen:1,weight:1,width:0,height:0,labeloffset:10,labelpos:"r"};let edgeAttrs=["labelpos"]; +/* + * Constructs a new graph from the input graph, which can be used for layout. + * This process copies only whitelisted attributes from the input graph to the + * layout graph. Thus this function serves as a good place to determine what + * attributes can influence layout. + */function buildLayoutGraph(inputGraph){let g=new Graph({multigraph:true,compound:true});let graph=canonicalize(inputGraph.graph());g.setGraph(Object.assign({},graphDefaults,selectNumberAttrs(graph,graphNumAttrs),util.pick(graph,graphAttrs)));inputGraph.nodes().forEach(v=>{let node=canonicalize(inputGraph.node(v));const newNode=selectNumberAttrs(node,nodeNumAttrs);Object.keys(nodeDefaults).forEach(k=>{if(newNode[k]===undefined){newNode[k]=nodeDefaults[k]}});g.setNode(v,newNode);g.setParent(v,inputGraph.parent(v))});inputGraph.edges().forEach(e=>{let edge=canonicalize(inputGraph.edge(e));g.setEdge(e,Object.assign({},edgeDefaults,selectNumberAttrs(edge,edgeNumAttrs),util.pick(edge,edgeAttrs)))});return g} +/* + * This idea comes from the Gansner paper: to account for edge labels in our + * layout we split each rank in half by doubling minlen and halving ranksep. + * Then we can place labels at these mid-points between nodes. + * + * We also add some minimal padding to the width to push the label for the edge + * away from the edge itself a bit. + */function makeSpaceForEdgeLabels(g){let graph=g.graph();graph.ranksep/=2;g.edges().forEach(e=>{let edge=g.edge(e);edge.minlen*=2;if(edge.labelpos.toLowerCase()!=="c"){if(graph.rankdir==="TB"||graph.rankdir==="BT"){edge.width+=edge.labeloffset}else{edge.height+=edge.labeloffset}}})} +/* + * Creates temporary dummy nodes that capture the rank in which each edge's + * label is going to, if it has one of non-zero width and height. We do this + * so that we can safely remove empty ranks while preserving balance for the + * label's position. + */function injectEdgeLabelProxies(g){g.edges().forEach(e=>{let edge=g.edge(e);if(edge.width&&edge.height){let v=g.node(e.v);let w=g.node(e.w);let label={rank:(w.rank-v.rank)/2+v.rank,e:e};util.addDummyNode(g,"edge-proxy",label,"_ep")}})}function assignRankMinMax(g){let maxRank=0;g.nodes().forEach(v=>{let node=g.node(v);if(node.borderTop){node.minRank=g.node(node.borderTop).rank;node.maxRank=g.node(node.borderBottom).rank;maxRank=Math.max(maxRank,node.maxRank)}});g.graph().maxRank=maxRank}function removeEdgeLabelProxies(g){g.nodes().forEach(v=>{let node=g.node(v);if(node.dummy==="edge-proxy"){g.edge(node.e).labelRank=node.rank;g.removeNode(v)}})}function translateGraph(g){let minX=Number.POSITIVE_INFINITY;let maxX=0;let minY=Number.POSITIVE_INFINITY;let maxY=0;let graphLabel=g.graph();let marginX=graphLabel.marginx||0;let marginY=graphLabel.marginy||0;function getExtremes(attrs){let x=attrs.x;let y=attrs.y;let w=attrs.width;let h=attrs.height;minX=Math.min(minX,x-w/2);maxX=Math.max(maxX,x+w/2);minY=Math.min(minY,y-h/2);maxY=Math.max(maxY,y+h/2)}g.nodes().forEach(v=>getExtremes(g.node(v)));g.edges().forEach(e=>{let edge=g.edge(e);if(Object.hasOwn(edge,"x")){getExtremes(edge)}});minX-=marginX;minY-=marginY;g.nodes().forEach(v=>{let node=g.node(v);node.x-=minX;node.y-=minY});g.edges().forEach(e=>{let edge=g.edge(e);edge.points.forEach(p=>{p.x-=minX;p.y-=minY});if(Object.hasOwn(edge,"x")){edge.x-=minX}if(Object.hasOwn(edge,"y")){edge.y-=minY}});graphLabel.width=maxX-minX+marginX;graphLabel.height=maxY-minY+marginY}function assignNodeIntersects(g){g.edges().forEach(e=>{let edge=g.edge(e);let nodeV=g.node(e.v);let nodeW=g.node(e.w);let p1,p2;if(!edge.points){edge.points=[];p1=nodeW;p2=nodeV}else{p1=edge.points[0];p2=edge.points[edge.points.length-1]}edge.points.unshift(util.intersectRect(nodeV,p1));edge.points.push(util.intersectRect(nodeW,p2))})}function fixupEdgeLabelCoords(g){g.edges().forEach(e=>{let edge=g.edge(e);if(Object.hasOwn(edge,"x")){if(edge.labelpos==="l"||edge.labelpos==="r"){edge.width-=edge.labeloffset}switch(edge.labelpos){case"l":edge.x-=edge.width/2+edge.labeloffset;break;case"r":edge.x+=edge.width/2+edge.labeloffset;break}}})}function reversePointsForReversedEdges(g){g.edges().forEach(e=>{let edge=g.edge(e);if(edge.reversed){edge.points.reverse()}})}function removeBorderNodes(g){g.nodes().forEach(v=>{if(g.children(v).length){let node=g.node(v);let t=g.node(node.borderTop);let b=g.node(node.borderBottom);let l=g.node(node.borderLeft[node.borderLeft.length-1]);let r=g.node(node.borderRight[node.borderRight.length-1]);node.width=Math.abs(r.x-l.x);node.height=Math.abs(b.y-t.y);node.x=l.x+node.width/2;node.y=t.y+node.height/2}});g.nodes().forEach(v=>{if(g.node(v).dummy==="border"){g.removeNode(v)}})}function removeSelfEdges(g){g.edges().forEach(e=>{if(e.v===e.w){var node=g.node(e.v);if(!node.selfEdges){node.selfEdges=[]}node.selfEdges.push({e:e,label:g.edge(e)});g.removeEdge(e)}})}function insertSelfEdges(g){var layers=util.buildLayerMatrix(g);layers.forEach(layer=>{var orderShift=0;layer.forEach((v,i)=>{var node=g.node(v);node.order=i+orderShift;(node.selfEdges||[]).forEach(selfEdge=>{util.addDummyNode(g,"selfedge",{width:selfEdge.label.width,height:selfEdge.label.height,rank:node.rank,order:i+ ++orderShift,e:selfEdge.e,label:selfEdge.label},"_se")});delete node.selfEdges})})}function positionSelfEdges(g){g.nodes().forEach(v=>{var node=g.node(v);if(node.dummy==="selfedge"){var selfNode=g.node(node.e.v);var x=selfNode.x+selfNode.width/2;var y=selfNode.y;var dx=node.x-x;var dy=selfNode.height/2;g.setEdge(node.e,node.label);g.removeNode(v);node.label.points=[{x:x+2*dx/3,y:y-dy},{x:x+5*dx/6,y:y-dy},{x:x+dx,y:y},{x:x+5*dx/6,y:y+dy},{x:x+2*dx/3,y:y+dy}];node.label.x=node.x;node.label.y=node.y}})}function selectNumberAttrs(obj,attrs){return util.mapValues(util.pick(obj,attrs),Number)}function canonicalize(attrs){var newAttrs={};if(attrs){Object.entries(attrs).forEach(([k,v])=>{if(typeof k==="string"){k=k.toLowerCase()}newAttrs[k]=v})}return newAttrs}},{"./acyclic":2,"./add-border-segments":3,"./coordinate-system":4,"./nesting-graph":9,"./normalize":10,"./order":15,"./parent-dummy-chains":20,"./position":22,"./rank":24,"./util":27,"@dagrejs/graphlib":29}],9:[function(require,module,exports){let util=require("./util");module.exports={run:run,cleanup:cleanup}; +/* + * A nesting graph creates dummy nodes for the tops and bottoms of subgraphs, + * adds appropriate edges to ensure that all cluster nodes are placed between + * these boundaries, and ensures that the graph is connected. + * + * In addition we ensure, through the use of the minlen property, that nodes + * and subgraph border nodes to not end up on the same rank. + * + * Preconditions: + * + * 1. Input graph is a DAG + * 2. Nodes in the input graph has a minlen attribute + * + * Postconditions: + * + * 1. Input graph is connected. + * 2. Dummy nodes are added for the tops and bottoms of subgraphs. + * 3. The minlen attribute for nodes is adjusted to ensure nodes do not + * get placed on the same rank as subgraph border nodes. + * + * The nesting graph idea comes from Sander, "Layout of Compound Directed + * Graphs." + */function run(g){let root=util.addDummyNode(g,"root",{},"_root");let depths=treeDepths(g);let depthsArr=Object.values(depths);let height=util.applyWithChunking(Math.max,depthsArr)-1;// Note: depths is an Object not an array +let nodeSep=2*height+1;g.graph().nestingRoot=root; +// Multiply minlen by nodeSep to align nodes on non-border ranks. +g.edges().forEach(e=>g.edge(e).minlen*=nodeSep); +// Calculate a weight that is sufficient to keep subgraphs vertically compact +let weight=sumWeights(g)+1; +// Create border nodes and link them up +g.children().forEach(child=>dfs(g,root,nodeSep,weight,height,depths,child)); +// Save the multiplier for node layers for later removal of empty border +// layers. +g.graph().nodeRankFactor=nodeSep}function dfs(g,root,nodeSep,weight,height,depths,v){let children=g.children(v);if(!children.length){if(v!==root){g.setEdge(root,v,{weight:0,minlen:nodeSep})}return}let top=util.addBorderNode(g,"_bt");let bottom=util.addBorderNode(g,"_bb");let label=g.node(v);g.setParent(top,v);label.borderTop=top;g.setParent(bottom,v);label.borderBottom=bottom;children.forEach(child=>{dfs(g,root,nodeSep,weight,height,depths,child);let childNode=g.node(child);let childTop=childNode.borderTop?childNode.borderTop:child;let childBottom=childNode.borderBottom?childNode.borderBottom:child;let thisWeight=childNode.borderTop?weight:2*weight;let minlen=childTop!==childBottom?1:height-depths[v]+1;g.setEdge(top,childTop,{weight:thisWeight,minlen:minlen,nestingEdge:true});g.setEdge(childBottom,bottom,{weight:thisWeight,minlen:minlen,nestingEdge:true})});if(!g.parent(v)){g.setEdge(root,top,{weight:0,minlen:height+depths[v]})}}function treeDepths(g){var depths={};function dfs(v,depth){var children=g.children(v);if(children&&children.length){children.forEach(child=>dfs(child,depth+1))}depths[v]=depth}g.children().forEach(v=>dfs(v,1));return depths}function sumWeights(g){return g.edges().reduce((acc,e)=>acc+g.edge(e).weight,0)}function cleanup(g){var graphLabel=g.graph();g.removeNode(graphLabel.nestingRoot);delete graphLabel.nestingRoot;g.edges().forEach(e=>{var edge=g.edge(e);if(edge.nestingEdge){g.removeEdge(e)}})}},{"./util":27}],10:[function(require,module,exports){"use strict";let util=require("./util");module.exports={run:run,undo:undo}; +/* + * Breaks any long edges in the graph into short segments that span 1 layer + * each. This operation is undoable with the denormalize function. + * + * Pre-conditions: + * + * 1. The input graph is a DAG. + * 2. Each node in the graph has a "rank" property. + * + * Post-condition: + * + * 1. All edges in the graph have a length of 1. + * 2. Dummy nodes are added where edges have been split into segments. + * 3. The graph is augmented with a "dummyChains" attribute which contains + * the first dummy in each chain of dummy nodes produced. + */function run(g){g.graph().dummyChains=[];g.edges().forEach(edge=>normalizeEdge(g,edge))}function normalizeEdge(g,e){let v=e.v;let vRank=g.node(v).rank;let w=e.w;let wRank=g.node(w).rank;let name=e.name;let edgeLabel=g.edge(e);let labelRank=edgeLabel.labelRank;if(wRank===vRank+1)return;g.removeEdge(e);let dummy,attrs,i;for(i=0,++vRank;vRank{let node=g.node(v);let origLabel=node.edgeLabel;let w;g.setEdge(node.edgeObj,origLabel);while(node.dummy){w=g.successors(v)[0];g.removeNode(v);origLabel.points.push({x:node.x,y:node.y});if(node.dummy==="edge-label"){origLabel.x=node.x;origLabel.y=node.y;origLabel.width=node.width;origLabel.height=node.height}v=w;node=g.node(v)}})}},{"./util":27}],11:[function(require,module,exports){module.exports=addSubgraphConstraints;function addSubgraphConstraints(g,cg,vs){let prev={},rootPrev;vs.forEach(v=>{let child=g.parent(v),parent,prevChild;while(child){parent=g.parent(child);if(parent){prevChild=prev[parent];prev[parent]=child}else{prevChild=rootPrev;rootPrev=child}if(prevChild&&prevChild!==child){cg.setEdge(prevChild,child);return}child=parent}}); +/* + function dfs(v) { + var children = v ? g.children(v) : g.children(); + if (children.length) { + var min = Number.POSITIVE_INFINITY, + subgraphs = []; + children.forEach(function(child) { + var childMin = dfs(child); + if (g.children(child).length) { + subgraphs.push({ v: child, order: childMin }); + } + min = Math.min(min, childMin); + }); + _.sortBy(subgraphs, "order").reduce(function(prev, curr) { + cg.setEdge(prev.v, curr.v); + return curr; + }); + return min; + } + return g.node(v).order; + } + dfs(undefined); + */}},{}],12:[function(require,module,exports){module.exports=barycenter;function barycenter(g,movable=[]){return movable.map(v=>{let inV=g.inEdges(v);if(!inV.length){return{v:v}}else{let result=inV.reduce((acc,e)=>{let edge=g.edge(e),nodeU=g.node(e.v);return{sum:acc.sum+edge.weight*nodeU.order,weight:acc.weight+edge.weight}},{sum:0,weight:0});return{v:v,barycenter:result.sum/result.weight,weight:result.weight}}})}},{}],13:[function(require,module,exports){let Graph=require("@dagrejs/graphlib").Graph;let util=require("../util");module.exports=buildLayerGraph; +/* + * Constructs a graph that can be used to sort a layer of nodes. The graph will + * contain all base and subgraph nodes from the request layer in their original + * hierarchy and any edges that are incident on these nodes and are of the type + * requested by the "relationship" parameter. + * + * Nodes from the requested rank that do not have parents are assigned a root + * node in the output graph, which is set in the root graph attribute. This + * makes it easy to walk the hierarchy of movable nodes during ordering. + * + * Pre-conditions: + * + * 1. Input graph is a DAG + * 2. Base nodes in the input graph have a rank attribute + * 3. Subgraph nodes in the input graph has minRank and maxRank attributes + * 4. Edges have an assigned weight + * + * Post-conditions: + * + * 1. Output graph has all nodes in the movable rank with preserved + * hierarchy. + * 2. Root nodes in the movable layer are made children of the node + * indicated by the root attribute of the graph. + * 3. Non-movable nodes incident on movable nodes, selected by the + * relationship parameter, are included in the graph (without hierarchy). + * 4. Edges incident on movable nodes, selected by the relationship + * parameter, are added to the output graph. + * 5. The weights for copied edges are aggregated as need, since the output + * graph is not a multi-graph. + */function buildLayerGraph(g,rank,relationship){let root=createRootNode(g),result=new Graph({compound:true}).setGraph({root:root}).setDefaultNodeLabel(v=>g.node(v));g.nodes().forEach(v=>{let node=g.node(v),parent=g.parent(v);if(node.rank===rank||node.minRank<=rank&&rank<=node.maxRank){result.setNode(v);result.setParent(v,parent||root); +// This assumes we have only short edges! +g[relationship](v).forEach(e=>{let u=e.v===v?e.w:e.v,edge=result.edge(u,v),weight=edge!==undefined?edge.weight:0;result.setEdge(u,v,{weight:g.edge(e).weight+weight})});if(Object.hasOwn(node,"minRank")){result.setNode(v,{borderLeft:node.borderLeft[rank],borderRight:node.borderRight[rank]})}}});return result}function createRootNode(g){var v;while(g.hasNode(v=util.uniqueId("_root")));return v}},{"../util":27,"@dagrejs/graphlib":29}],14:[function(require,module,exports){"use strict";let zipObject=require("../util").zipObject;module.exports=crossCount; +/* + * A function that takes a layering (an array of layers, each with an array of + * ordererd nodes) and a graph and returns a weighted crossing count. + * + * Pre-conditions: + * + * 1. Input graph must be simple (not a multigraph), directed, and include + * only simple edges. + * 2. Edges in the input graph must have assigned weights. + * + * Post-conditions: + * + * 1. The graph and layering matrix are left unchanged. + * + * This algorithm is derived from Barth, et al., "Bilayer Cross Counting." + */function crossCount(g,layering){let cc=0;for(let i=1;ii));let southEntries=northLayer.flatMap(v=>{return g.outEdges(v).map(e=>{return{pos:southPos[e.w],weight:g.edge(e).weight}}).sort((a,b)=>a.pos-b.pos)}); +// Build the accumulator tree +let firstIndex=1;while(firstIndex{let index=entry.pos+firstIndex;tree[index]+=entry.weight;let weightSum=0;while(index>0){if(index%2){weightSum+=tree[index+1]}index=index-1>>1;tree[index]+=entry.weight}cc+=entry.weight*weightSum});return cc}},{"../util":27}],15:[function(require,module,exports){"use strict";let initOrder=require("./init-order");let crossCount=require("./cross-count");let sortSubgraph=require("./sort-subgraph");let buildLayerGraph=require("./build-layer-graph");let addSubgraphConstraints=require("./add-subgraph-constraints");let Graph=require("@dagrejs/graphlib").Graph;let util=require("../util");module.exports=order; +/* + * Applies heuristics to minimize edge crossings in the graph and sets the best + * order solution as an order attribute on each node. + * + * Pre-conditions: + * + * 1. Graph must be DAG + * 2. Graph nodes must be objects with a "rank" attribute + * 3. Graph edges must have the "weight" attribute + * + * Post-conditions: + * + * 1. Graph nodes will have an "order" attribute based on the results of the + * algorithm. + */function order(g,opts){if(opts&&typeof opts.customOrder==="function"){opts.customOrder(g,order);return}let maxRank=util.maxRank(g),downLayerGraphs=buildLayerGraphs(g,util.range(1,maxRank+1),"inEdges"),upLayerGraphs=buildLayerGraphs(g,util.range(maxRank-1,-1,-1),"outEdges");let layering=initOrder(g);assignOrder(g,layering);if(opts&&opts.disableOptimalOrderHeuristic){return}let bestCC=Number.POSITIVE_INFINITY,best;for(let i=0,lastBest=0;lastBest<4;++i,++lastBest){sweepLayerGraphs(i%2?downLayerGraphs:upLayerGraphs,i%4>=2);layering=util.buildLayerMatrix(g);let cc=crossCount(g,layering);if(cclg.node(v).order=i);addSubgraphConstraints(lg,cg,sorted.vs)})}function assignOrder(g,layering){Object.values(layering).forEach(layer=>layer.forEach((v,i)=>g.node(v).order=i))}},{"../util":27,"./add-subgraph-constraints":11,"./build-layer-graph":13,"./cross-count":14,"./init-order":16,"./sort-subgraph":18,"@dagrejs/graphlib":29}],16:[function(require,module,exports){"use strict";let util=require("../util");module.exports=initOrder; +/* + * Assigns an initial order value for each node by performing a DFS search + * starting from nodes in the first rank. Nodes are assigned an order in their + * rank as they are first visited. + * + * This approach comes from Gansner, et al., "A Technique for Drawing Directed + * Graphs." + * + * Returns a layering matrix with an array per layer and each layer sorted by + * the order of its nodes. + */function initOrder(g){let visited={};let simpleNodes=g.nodes().filter(v=>!g.children(v).length);let simpleNodesRanks=simpleNodes.map(v=>g.node(v).rank);let maxRank=util.applyWithChunking(Math.max,simpleNodesRanks);let layers=util.range(maxRank+1).map(()=>[]);function dfs(v){if(visited[v])return;visited[v]=true;let node=g.node(v);layers[node.rank].push(v);g.successors(v).forEach(dfs)}let orderedVs=simpleNodes.sort((a,b)=>g.node(a).rank-g.node(b).rank);orderedVs.forEach(dfs);return layers}},{"../util":27}],17:[function(require,module,exports){"use strict";let util=require("../util");module.exports=resolveConflicts; +/* + * Given a list of entries of the form {v, barycenter, weight} and a + * constraint graph this function will resolve any conflicts between the + * constraint graph and the barycenters for the entries. If the barycenters for + * an entry would violate a constraint in the constraint graph then we coalesce + * the nodes in the conflict into a new node that respects the contraint and + * aggregates barycenter and weight information. + * + * This implementation is based on the description in Forster, "A Fast and + * Simple Hueristic for Constrained Two-Level Crossing Reduction," thought it + * differs in some specific details. + * + * Pre-conditions: + * + * 1. Each entry has the form {v, barycenter, weight}, or if the node has + * no barycenter, then {v}. + * + * Returns: + * + * A new list of entries of the form {vs, i, barycenter, weight}. The list + * `vs` may either be a singleton or it may be an aggregation of nodes + * ordered such that they do not violate constraints from the constraint + * graph. The property `i` is the lowest original index of any of the + * elements in `vs`. + */function resolveConflicts(entries,cg){let mappedEntries={};entries.forEach((entry,i)=>{let tmp=mappedEntries[entry.v]={indegree:0,in:[],out:[],vs:[entry.v],i:i};if(entry.barycenter!==undefined){tmp.barycenter=entry.barycenter;tmp.weight=entry.weight}});cg.edges().forEach(e=>{let entryV=mappedEntries[e.v];let entryW=mappedEntries[e.w];if(entryV!==undefined&&entryW!==undefined){entryW.indegree++;entryV.out.push(mappedEntries[e.w])}});let sourceSet=Object.values(mappedEntries).filter(entry=>!entry.indegree);return doResolveConflicts(sourceSet)}function doResolveConflicts(sourceSet){let entries=[];function handleIn(vEntry){return uEntry=>{if(uEntry.merged){return}if(uEntry.barycenter===undefined||vEntry.barycenter===undefined||uEntry.barycenter>=vEntry.barycenter){mergeEntries(vEntry,uEntry)}}}function handleOut(vEntry){return wEntry=>{wEntry["in"].push(vEntry);if(--wEntry.indegree===0){sourceSet.push(wEntry)}}}while(sourceSet.length){let entry=sourceSet.pop();entries.push(entry);entry["in"].reverse().forEach(handleIn(entry));entry.out.forEach(handleOut(entry))}return entries.filter(entry=>!entry.merged).map(entry=>{return util.pick(entry,["vs","i","barycenter","weight"])})}function mergeEntries(target,source){let sum=0;let weight=0;if(target.weight){sum+=target.barycenter*target.weight;weight+=target.weight}if(source.weight){sum+=source.barycenter*source.weight;weight+=source.weight}target.vs=source.vs.concat(target.vs);target.barycenter=sum/weight;target.weight=weight;target.i=Math.min(source.i,target.i);source.merged=true}},{"../util":27}],18:[function(require,module,exports){let barycenter=require("./barycenter");let resolveConflicts=require("./resolve-conflicts");let sort=require("./sort");module.exports=sortSubgraph;function sortSubgraph(g,v,cg,biasRight){let movable=g.children(v);let node=g.node(v);let bl=node?node.borderLeft:undefined;let br=node?node.borderRight:undefined;let subgraphs={};if(bl){movable=movable.filter(w=>w!==bl&&w!==br)}let barycenters=barycenter(g,movable);barycenters.forEach(entry=>{if(g.children(entry.v).length){let subgraphResult=sortSubgraph(g,entry.v,cg,biasRight);subgraphs[entry.v]=subgraphResult;if(Object.hasOwn(subgraphResult,"barycenter")){mergeBarycenters(entry,subgraphResult)}}});let entries=resolveConflicts(barycenters,cg);expandSubgraphs(entries,subgraphs);let result=sort(entries,biasRight);if(bl){result.vs=[bl,result.vs,br].flat(true);if(g.predecessors(bl).length){let blPred=g.node(g.predecessors(bl)[0]),brPred=g.node(g.predecessors(br)[0]);if(!Object.hasOwn(result,"barycenter")){result.barycenter=0;result.weight=0}result.barycenter=(result.barycenter*result.weight+blPred.order+brPred.order)/(result.weight+2);result.weight+=2}}return result}function expandSubgraphs(entries,subgraphs){entries.forEach(entry=>{entry.vs=entry.vs.flatMap(v=>{if(subgraphs[v]){return subgraphs[v].vs}return v})})}function mergeBarycenters(target,other){if(target.barycenter!==undefined){target.barycenter=(target.barycenter*target.weight+other.barycenter*other.weight)/(target.weight+other.weight);target.weight+=other.weight}else{target.barycenter=other.barycenter;target.weight=other.weight}}},{"./barycenter":12,"./resolve-conflicts":17,"./sort":19}],19:[function(require,module,exports){let util=require("../util");module.exports=sort;function sort(entries,biasRight){let parts=util.partition(entries,entry=>{return Object.hasOwn(entry,"barycenter")});let sortable=parts.lhs,unsortable=parts.rhs.sort((a,b)=>b.i-a.i),vs=[],sum=0,weight=0,vsIndex=0;sortable.sort(compareWithBias(!!biasRight));vsIndex=consumeUnsortable(vs,unsortable,vsIndex);sortable.forEach(entry=>{vsIndex+=entry.vs.length;vs.push(entry.vs);sum+=entry.barycenter*entry.weight;weight+=entry.weight;vsIndex=consumeUnsortable(vs,unsortable,vsIndex)});let result={vs:vs.flat(true)};if(weight){result.barycenter=sum/weight;result.weight=weight}return result}function consumeUnsortable(vs,unsortable,index){let last;while(unsortable.length&&(last=unsortable[unsortable.length-1]).i<=index){unsortable.pop();vs.push(last.vs);index++}return index}function compareWithBias(bias){return(entryV,entryW)=>{if(entryV.barycenterentryW.barycenter){return 1}return!bias?entryV.i-entryW.i:entryW.i-entryV.i}}},{"../util":27}],20:[function(require,module,exports){module.exports=parentDummyChains;function parentDummyChains(g){let postorderNums=postorder(g);g.graph().dummyChains.forEach(v=>{let node=g.node(v);let edgeObj=node.edgeObj;let pathData=findPath(g,postorderNums,edgeObj.v,edgeObj.w);let path=pathData.path;let lca=pathData.lca;let pathIdx=0;let pathV=path[pathIdx];let ascending=true;while(v!==edgeObj.w){node=g.node(v);if(ascending){while((pathV=path[pathIdx])!==lca&&g.node(pathV).maxRanklow||lim>postorderNums[parent].lim));lca=parent; +// Traverse from w to LCA +parent=w;while((parent=g.parent(parent))!==lca){wPath.push(parent)}return{path:vPath.concat(wPath.reverse()),lca:lca}}function postorder(g){let result={};let lim=0;function dfs(v){let low=lim;g.children(v).forEach(dfs);result[v]={low:low,lim:lim++}}g.children().forEach(dfs);return result}},{}],21:[function(require,module,exports){"use strict";let Graph=require("@dagrejs/graphlib").Graph;let util=require("../util"); +/* + * This module provides coordinate assignment based on Brandes and Köpf, "Fast + * and Simple Horizontal Coordinate Assignment." + */module.exports={positionX:positionX,findType1Conflicts:findType1Conflicts,findType2Conflicts:findType2Conflicts,addConflict:addConflict,hasConflict:hasConflict,verticalAlignment:verticalAlignment,horizontalCompaction:horizontalCompaction,alignCoordinates:alignCoordinates,findSmallestWidthAlignment:findSmallestWidthAlignment,balance:balance}; +/* + * Marks all edges in the graph with a type-1 conflict with the "type1Conflict" + * property. A type-1 conflict is one where a non-inner segment crosses an + * inner segment. An inner segment is an edge with both incident nodes marked + * with the "dummy" property. + * + * This algorithm scans layer by layer, starting with the second, for type-1 + * conflicts between the current layer and the previous layer. For each layer + * it scans the nodes from left to right until it reaches one that is incident + * on an inner segment. It then scans predecessors to determine if they have + * edges that cross that inner segment. At the end a final scan is done for all + * nodes on the current rank to see if they cross the last visited inner + * segment. + * + * This algorithm (safely) assumes that a dummy node will only be incident on a + * single node in the layers being scanned. + */function findType1Conflicts(g,layering){let conflicts={};function visitLayer(prevLayer,layer){let +// last visited node in the previous layer that is incident on an inner +// segment. +k0=0, +// Tracks the last node in this layer scanned for crossings with a type-1 +// segment. +scanPos=0,prevLayerLength=prevLayer.length,lastNode=layer[layer.length-1];layer.forEach((v,i)=>{let w=findOtherInnerSegmentNode(g,v),k1=w?g.node(w).order:prevLayerLength;if(w||v===lastNode){layer.slice(scanPos,i+1).forEach(scanNode=>{g.predecessors(scanNode).forEach(u=>{let uLabel=g.node(u),uPos=uLabel.order;if((uPos{v=south[i];if(g.node(v).dummy){g.predecessors(v).forEach(u=>{let uNode=g.node(u);if(uNode.dummy&&(uNode.ordernextNorthBorder)){addConflict(conflicts,u,v)}})}})}function visitLayer(north,south){let prevNorthPos=-1,nextNorthPos,southPos=0;south.forEach((v,southLookahead)=>{if(g.node(v).dummy==="border"){let predecessors=g.predecessors(v);if(predecessors.length){nextNorthPos=g.node(predecessors[0]).order;scan(south,southPos,southLookahead,prevNorthPos,nextNorthPos);southPos=southLookahead;prevNorthPos=nextNorthPos}}scan(south,southPos,south.length,nextNorthPos,north.length)});return south}layering.length&&layering.reduce(visitLayer);return conflicts}function findOtherInnerSegmentNode(g,v){if(g.node(v).dummy){return g.predecessors(v).find(u=>g.node(u).dummy)}}function addConflict(conflicts,v,w){if(v>w){let tmp=v;v=w;w=tmp}let conflictsV=conflicts[v];if(!conflictsV){conflicts[v]=conflictsV={}}conflictsV[w]=true}function hasConflict(conflicts,v,w){if(v>w){let tmp=v;v=w;w=tmp}return!!conflicts[v]&&Object.hasOwn(conflicts[v],w)} +/* + * Try to align nodes into vertical "blocks" where possible. This algorithm + * attempts to align a node with one of its median neighbors. If the edge + * connecting a neighbor is a type-1 conflict then we ignore that possibility. + * If a previous node has already formed a block with a node after the node + * we're trying to form a block with, we also ignore that possibility - our + * blocks would be split in that scenario. + */function verticalAlignment(g,layering,conflicts,neighborFn){let root={},align={},pos={}; +// We cache the position here based on the layering because the graph and +// layering may be out of sync. The layering matrix is manipulated to +// generate different extreme alignments. +layering.forEach(layer=>{layer.forEach((v,order)=>{root[v]=v;align[v]=v;pos[v]=order})});layering.forEach(layer=>{let prevIdx=-1;layer.forEach(v=>{let ws=neighborFn(v);if(ws.length){ws=ws.sort((a,b)=>pos[a]-pos[b]);let mp=(ws.length-1)/2;for(let i=Math.floor(mp),il=Math.ceil(mp);i<=il;++i){let w=ws[i];if(align[v]===v&&prevIdx{return Math.max(acc,xs[e.v]+blockG.edge(e))},0)} +// Second pass, assign greatest coordinates +function pass2(elem){let min=blockG.outEdges(elem).reduce((acc,e)=>{return Math.min(acc,xs[e.w]-blockG.edge(e))},Number.POSITIVE_INFINITY);let node=g.node(elem);if(min!==Number.POSITIVE_INFINITY&&node.borderType!==borderType){xs[elem]=Math.max(xs[elem],min)}}iterate(pass1,blockG.predecessors.bind(blockG));iterate(pass2,blockG.successors.bind(blockG)); +// Assign x coordinates to all nodes +Object.keys(align).forEach(v=>xs[v]=xs[root[v]]);return xs}function buildBlockGraph(g,layering,root,reverseSep){let blockGraph=new Graph,graphLabel=g.graph(),sepFn=sep(graphLabel.nodesep,graphLabel.edgesep,reverseSep);layering.forEach(layer=>{let u;layer.forEach(v=>{let vRoot=root[v];blockGraph.setNode(vRoot);if(u){var uRoot=root[u],prevMax=blockGraph.edge(uRoot,vRoot);blockGraph.setEdge(uRoot,vRoot,Math.max(sepFn(g,v,u),prevMax||0))}u=v})});return blockGraph} +/* + * Returns the alignment that has the smallest width of the given alignments. + */function findSmallestWidthAlignment(g,xss){return Object.values(xss).reduce((currentMinAndXs,xs)=>{let max=Number.NEGATIVE_INFINITY;let min=Number.POSITIVE_INFINITY;Object.entries(xs).forEach(([v,x])=>{let halfWidth=width(g,v)/2;max=Math.max(x+halfWidth,max);min=Math.min(x-halfWidth,min)});const newMin=max-min;if(newMin{["l","r"].forEach(horiz=>{let alignment=vert+horiz,xs=xss[alignment];if(xs===alignTo)return;let xsVals=Object.values(xs);let delta=alignToMin-util.applyWithChunking(Math.min,xsVals);if(horiz!=="l"){delta=alignToMax-util.applyWithChunking(Math.max,xsVals)}if(delta){xss[alignment]=util.mapValues(xs,x=>x+delta)}})})}function balance(xss,align){return util.mapValues(xss.ul,(num,v)=>{if(align){return xss[align.toLowerCase()][v]}else{let xs=Object.values(xss).map(xs=>xs[v]).sort((a,b)=>a-b);return(xs[1]+xs[2])/2}})}function positionX(g){let layering=util.buildLayerMatrix(g);let conflicts=Object.assign(findType1Conflicts(g,layering),findType2Conflicts(g,layering));let xss={};let adjustedLayering;["u","d"].forEach(vert=>{adjustedLayering=vert==="u"?layering:Object.values(layering).reverse();["l","r"].forEach(horiz=>{if(horiz==="r"){adjustedLayering=adjustedLayering.map(inner=>{return Object.values(inner).reverse()})}let neighborFn=(vert==="u"?g.predecessors:g.successors).bind(g);let align=verticalAlignment(g,adjustedLayering,conflicts,neighborFn);let xs=horizontalCompaction(g,adjustedLayering,align.root,align.align,horiz==="r");if(horiz==="r"){xs=util.mapValues(xs,x=>-x)}xss[vert+horiz]=xs})});let smallestWidth=findSmallestWidthAlignment(g,xss);alignCoordinates(xss,smallestWidth);return balance(xss,g.graph().align)}function sep(nodeSep,edgeSep,reverseSep){return(g,v,w)=>{let vLabel=g.node(v);let wLabel=g.node(w);let sum=0;let delta;sum+=vLabel.width/2;if(Object.hasOwn(vLabel,"labelpos")){switch(vLabel.labelpos.toLowerCase()){case"l":delta=-vLabel.width/2;break;case"r":delta=vLabel.width/2;break}}if(delta){sum+=reverseSep?delta:-delta}delta=0;sum+=(vLabel.dummy?edgeSep:nodeSep)/2;sum+=(wLabel.dummy?edgeSep:nodeSep)/2;sum+=wLabel.width/2;if(Object.hasOwn(wLabel,"labelpos")){switch(wLabel.labelpos.toLowerCase()){case"l":delta=wLabel.width/2;break;case"r":delta=-wLabel.width/2;break}}if(delta){sum+=reverseSep?delta:-delta}delta=0;return sum}}function width(g,v){return g.node(v).width}},{"../util":27,"@dagrejs/graphlib":29}],22:[function(require,module,exports){"use strict";let util=require("../util");let positionX=require("./bk").positionX;module.exports=position;function position(g){g=util.asNonCompoundGraph(g);positionY(g);Object.entries(positionX(g)).forEach(([v,x])=>g.node(v).x=x)}function positionY(g){let layering=util.buildLayerMatrix(g);let rankSep=g.graph().ranksep;let prevY=0;layering.forEach(layer=>{const maxHeight=layer.reduce((acc,v)=>{const height=g.node(v).height;if(acc>height){return acc}else{return height}},0);layer.forEach(v=>g.node(v).y=prevY+maxHeight/2);prevY+=maxHeight+rankSep})}},{"../util":27,"./bk":21}],23:[function(require,module,exports){"use strict";var Graph=require("@dagrejs/graphlib").Graph;var slack=require("./util").slack;module.exports=feasibleTree; +/* + * Constructs a spanning tree with tight edges and adjusted the input node's + * ranks to achieve this. A tight edge is one that is has a length that matches + * its "minlen" attribute. + * + * The basic structure for this function is derived from Gansner, et al., "A + * Technique for Drawing Directed Graphs." + * + * Pre-conditions: + * + * 1. Graph must be a DAG. + * 2. Graph must be connected. + * 3. Graph must have at least one node. + * 5. Graph nodes must have been previously assigned a "rank" property that + * respects the "minlen" property of incident edges. + * 6. Graph edges must have a "minlen" property. + * + * Post-conditions: + * + * - Graph nodes will have their rank adjusted to ensure that all edges are + * tight. + * + * Returns a tree (undirected graph) that is constructed using only "tight" + * edges. + */function feasibleTree(g){var t=new Graph({directed:false}); +// Choose arbitrary node from which to start our tree +var start=g.nodes()[0];var size=g.nodeCount();t.setNode(start,{});var edge,delta;while(tightTree(t,g){var edgeV=e.v,w=v===edgeV?e.w:edgeV;if(!t.hasNode(w)&&!slack(g,e)){t.setNode(w,{});t.setEdge(v,w,{});dfs(w)}})}t.nodes().forEach(dfs);return t.nodeCount()} +/* + * Finds the edge with the smallest slack that is incident on tree and returns + * it. + */function findMinSlackEdge(t,g){const edges=g.edges();return edges.reduce((acc,edge)=>{let edgeSlack=Number.POSITIVE_INFINITY;if(t.hasNode(edge.v)!==t.hasNode(edge.w)){edgeSlack=slack(g,edge)}if(edgeSlackg.node(v).rank+=delta)}},{"./util":26,"@dagrejs/graphlib":29}],24:[function(require,module,exports){"use strict";var rankUtil=require("./util");var longestPath=rankUtil.longestPath;var feasibleTree=require("./feasible-tree");var networkSimplex=require("./network-simplex");module.exports=rank; +/* + * Assigns a rank to each node in the input graph that respects the "minlen" + * constraint specified on edges between nodes. + * + * This basic structure is derived from Gansner, et al., "A Technique for + * Drawing Directed Graphs." + * + * Pre-conditions: + * + * 1. Graph must be a connected DAG + * 2. Graph nodes must be objects + * 3. Graph edges must have "weight" and "minlen" attributes + * + * Post-conditions: + * + * 1. Graph nodes will have a "rank" attribute based on the results of the + * algorithm. Ranks can start at any index (including negative), we'll + * fix them up later. + */function rank(g){switch(g.graph().ranker){case"network-simplex":networkSimplexRanker(g);break;case"tight-tree":tightTreeRanker(g);break;case"longest-path":longestPathRanker(g);break;default:networkSimplexRanker(g)}} +// A fast and simple ranker, but results are far from optimal. +var longestPathRanker=longestPath;function tightTreeRanker(g){longestPath(g);feasibleTree(g)}function networkSimplexRanker(g){networkSimplex(g)}},{"./feasible-tree":23,"./network-simplex":25,"./util":26}],25:[function(require,module,exports){"use strict";var feasibleTree=require("./feasible-tree");var slack=require("./util").slack;var initRank=require("./util").longestPath;var preorder=require("@dagrejs/graphlib").alg.preorder;var postorder=require("@dagrejs/graphlib").alg.postorder;var simplify=require("../util").simplify;module.exports=networkSimplex; +// Expose some internals for testing purposes +networkSimplex.initLowLimValues=initLowLimValues;networkSimplex.initCutValues=initCutValues;networkSimplex.calcCutValue=calcCutValue;networkSimplex.leaveEdge=leaveEdge;networkSimplex.enterEdge=enterEdge;networkSimplex.exchangeEdges=exchangeEdges; +/* + * The network simplex algorithm assigns ranks to each node in the input graph + * and iteratively improves the ranking to reduce the length of edges. + * + * Preconditions: + * + * 1. The input graph must be a DAG. + * 2. All nodes in the graph must have an object value. + * 3. All edges in the graph must have "minlen" and "weight" attributes. + * + * Postconditions: + * + * 1. All nodes in the graph will have an assigned "rank" attribute that has + * been optimized by the network simplex algorithm. Ranks start at 0. + * + * + * A rough sketch of the algorithm is as follows: + * + * 1. Assign initial ranks to each node. We use the longest path algorithm, + * which assigns ranks to the lowest position possible. In general this + * leads to very wide bottom ranks and unnecessarily long edges. + * 2. Construct a feasible tight tree. A tight tree is one such that all + * edges in the tree have no slack (difference between length of edge + * and minlen for the edge). This by itself greatly improves the assigned + * rankings by shorting edges. + * 3. Iteratively find edges that have negative cut values. Generally a + * negative cut value indicates that the edge could be removed and a new + * tree edge could be added to produce a more compact graph. + * + * Much of the algorithms here are derived from Gansner, et al., "A Technique + * for Drawing Directed Graphs." The structure of the file roughly follows the + * structure of the overall algorithm. + */function networkSimplex(g){g=simplify(g);initRank(g);var t=feasibleTree(g);initLowLimValues(t);initCutValues(t,g);var e,f;while(e=leaveEdge(t)){f=enterEdge(t,g,e);exchangeEdges(t,g,e,f)}} +/* + * Initializes cut values for all edges in the tree. + */function initCutValues(t,g){var vs=postorder(t,t.nodes());vs=vs.slice(0,vs.length-1);vs.forEach(v=>assignCutValue(t,g,v))}function assignCutValue(t,g,child){var childLab=t.node(child);var parent=childLab.parent;t.edge(child,parent).cutvalue=calcCutValue(t,g,child)} +/* + * Given the tight tree, its graph, and a child in the graph calculate and + * return the cut value for the edge between the child and its parent. + */function calcCutValue(t,g,child){var childLab=t.node(child);var parent=childLab.parent; +// True if the child is on the tail end of the edge in the directed graph +var childIsTail=true; +// The graph's view of the tree edge we're inspecting +var graphEdge=g.edge(child,parent); +// The accumulated cut value for the edge between this node and its parent +var cutValue=0;if(!graphEdge){childIsTail=false;graphEdge=g.edge(parent,child)}cutValue=graphEdge.weight;g.nodeEdges(child).forEach(e=>{var isOutEdge=e.v===child,other=isOutEdge?e.w:e.v;if(other!==parent){var pointsToHead=isOutEdge===childIsTail,otherWeight=g.edge(e).weight;cutValue+=pointsToHead?otherWeight:-otherWeight;if(isTreeEdge(t,child,other)){var otherCutValue=t.edge(child,other).cutvalue;cutValue+=pointsToHead?-otherCutValue:otherCutValue}}});return cutValue}function initLowLimValues(tree,root){if(arguments.length<2){root=tree.nodes()[0]}dfsAssignLowLim(tree,{},1,root)}function dfsAssignLowLim(tree,visited,nextLim,v,parent){var low=nextLim;var label=tree.node(v);visited[v]=true;tree.neighbors(v).forEach(w=>{if(!Object.hasOwn(visited,w)){nextLim=dfsAssignLowLim(tree,visited,nextLim,w,v)}});label.low=low;label.lim=nextLim++;if(parent){label.parent=parent}else{ +// TODO should be able to remove this when we incrementally update low lim +delete label.parent}return nextLim}function leaveEdge(tree){return tree.edges().find(e=>tree.edge(e).cutvalue<0)}function enterEdge(t,g,edge){var v=edge.v;var w=edge.w; +// For the rest of this function we assume that v is the tail and w is the +// head, so if we don't have this edge in the graph we should flip it to +// match the correct orientation. +if(!g.hasEdge(v,w)){v=edge.w;w=edge.v}var vLabel=t.node(v);var wLabel=t.node(w);var tailLabel=vLabel;var flip=false; +// If the root is in the tail of the edge then we need to flip the logic that +// checks for the head and tail nodes in the candidates function below. +if(vLabel.lim>wLabel.lim){tailLabel=wLabel;flip=true}var candidates=g.edges().filter(edge=>{return flip===isDescendant(t,t.node(edge.v),tailLabel)&&flip!==isDescendant(t,t.node(edge.w),tailLabel)});return candidates.reduce((acc,edge)=>{if(slack(g,edge)!g.node(v).parent);var vs=preorder(t,root);vs=vs.slice(1);vs.forEach(v=>{var parent=t.node(v).parent,edge=g.edge(v,parent),flipped=false;if(!edge){edge=g.edge(parent,v);flipped=true}g.node(v).rank=g.node(parent).rank+(flipped?edge.minlen:-edge.minlen)})} +/* + * Returns true if the edge is in the tree. + */function isTreeEdge(tree,u,v){return tree.hasEdge(u,v)} +/* + * Returns true if the specified node is descendant of the root node per the + * assigned low and lim attributes in the tree. + */function isDescendant(tree,vLabel,rootLabel){return rootLabel.low<=vLabel.lim&&vLabel.lim<=rootLabel.lim}},{"../util":27,"./feasible-tree":23,"./util":26,"@dagrejs/graphlib":29}],26:[function(require,module,exports){"use strict";const{applyWithChunking}=require("../util");module.exports={longestPath:longestPath,slack:slack}; +/* + * Initializes ranks for the input graph using the longest path algorithm. This + * algorithm scales well and is fast in practice, it yields rather poor + * solutions. Nodes are pushed to the lowest layer possible, leaving the bottom + * ranks wide and leaving edges longer than necessary. However, due to its + * speed, this algorithm is good for getting an initial ranking that can be fed + * into other algorithms. + * + * This algorithm does not normalize layers because it will be used by other + * algorithms in most cases. If using this algorithm directly, be sure to + * run normalize at the end. + * + * Pre-conditions: + * + * 1. Input graph is a DAG. + * 2. Input graph node labels can be assigned properties. + * + * Post-conditions: + * + * 1. Each node will be assign an (unnormalized) "rank" property. + */function longestPath(g){var visited={};function dfs(v){var label=g.node(v);if(Object.hasOwn(visited,v)){return label.rank}visited[v]=true;let outEdgesMinLens=g.outEdges(v).map(e=>{if(e==null){return Number.POSITIVE_INFINITY}return dfs(e.w)-g.edge(e).minlen});var rank=applyWithChunking(Math.min,outEdgesMinLens);if(rank===Number.POSITIVE_INFINITY){rank=0}return label.rank=rank}g.sources().forEach(dfs)} +/* + * Returns the amount of slack for the given edge. The slack is defined as the + * difference between the length of the edge and its minimum length. + */function slack(g,e){return g.node(e.w).rank-g.node(e.v).rank-g.edge(e).minlen}},{"../util":27}],27:[function(require,module,exports){ +/* eslint "no-console": off */ +"use strict";let Graph=require("@dagrejs/graphlib").Graph;module.exports={addBorderNode:addBorderNode,addDummyNode:addDummyNode,applyWithChunking:applyWithChunking,asNonCompoundGraph:asNonCompoundGraph,buildLayerMatrix:buildLayerMatrix,intersectRect:intersectRect,mapValues:mapValues,maxRank:maxRank,normalizeRanks:normalizeRanks,notime:notime,partition:partition,pick:pick,predecessorWeights:predecessorWeights,range:range,removeEmptyRanks:removeEmptyRanks,simplify:simplify,successorWeights:successorWeights,time:time,uniqueId:uniqueId,zipObject:zipObject}; +/* + * Adds a dummy node to the graph and return v. + */function addDummyNode(g,type,attrs,name){let v;do{v=uniqueId(name)}while(g.hasNode(v));attrs.dummy=type;g.setNode(v,attrs);return v} +/* + * Returns a new graph with only simple edges. Handles aggregation of data + * associated with multi-edges. + */function simplify(g){let simplified=(new Graph).setGraph(g.graph());g.nodes().forEach(v=>simplified.setNode(v,g.node(v)));g.edges().forEach(e=>{let simpleLabel=simplified.edge(e.v,e.w)||{weight:0,minlen:1};let label=g.edge(e);simplified.setEdge(e.v,e.w,{weight:simpleLabel.weight+label.weight,minlen:Math.max(simpleLabel.minlen,label.minlen)})});return simplified}function asNonCompoundGraph(g){let simplified=new Graph({multigraph:g.isMultigraph()}).setGraph(g.graph());g.nodes().forEach(v=>{if(!g.children(v).length){simplified.setNode(v,g.node(v))}});g.edges().forEach(e=>{simplified.setEdge(e,g.edge(e))});return simplified}function successorWeights(g){let weightMap=g.nodes().map(v=>{let sucs={};g.outEdges(v).forEach(e=>{sucs[e.w]=(sucs[e.w]||0)+g.edge(e).weight});return sucs});return zipObject(g.nodes(),weightMap)}function predecessorWeights(g){let weightMap=g.nodes().map(v=>{let preds={};g.inEdges(v).forEach(e=>{preds[e.v]=(preds[e.v]||0)+g.edge(e).weight});return preds});return zipObject(g.nodes(),weightMap)} +/* + * Finds where a line starting at point ({x, y}) would intersect a rectangle + * ({x, y, width, height}) if it were pointing at the rectangle's center. + */function intersectRect(rect,point){let x=rect.x;let y=rect.y; +// Rectangle intersection algorithm from: +// http://math.stackexchange.com/questions/108113/find-edge-between-two-boxes +let dx=point.x-x;let dy=point.y-y;let w=rect.width/2;let h=rect.height/2;if(!dx&&!dy){throw new Error("Not possible to find intersection inside of the rectangle")}let sx,sy;if(Math.abs(dy)*w>Math.abs(dx)*h){ +// Intersection is top or bottom of rect. +if(dy<0){h=-h}sx=h*dx/dy;sy=h}else{ +// Intersection is left or right of rect. +if(dx<0){w=-w}sx=w;sy=w*dy/dx}return{x:x+sx,y:y+sy}} +/* + * Given a DAG with each node assigned "rank" and "order" properties, this + * function will produce a matrix with the ids of each node. + */function buildLayerMatrix(g){let layering=range(maxRank(g)+1).map(()=>[]);g.nodes().forEach(v=>{let node=g.node(v);let rank=node.rank;if(rank!==undefined){layering[rank][node.order]=v}});return layering} +/* + * Adjusts the ranks for all nodes in the graph such that all nodes v have + * rank(v) >= 0 and at least one node w has rank(w) = 0. + */function normalizeRanks(g){let nodeRanks=g.nodes().map(v=>{let rank=g.node(v).rank;if(rank===undefined){return Number.MAX_VALUE}return rank});let min=applyWithChunking(Math.min,nodeRanks);g.nodes().forEach(v=>{let node=g.node(v);if(Object.hasOwn(node,"rank")){node.rank-=min}})}function removeEmptyRanks(g){ +// Ranks may not start at 0, so we need to offset them +let nodeRanks=g.nodes().map(v=>g.node(v).rank);let offset=applyWithChunking(Math.min,nodeRanks);let layers=[];g.nodes().forEach(v=>{let rank=g.node(v).rank-offset;if(!layers[rank]){layers[rank]=[]}layers[rank].push(v)});let delta=0;let nodeRankFactor=g.graph().nodeRankFactor;Array.from(layers).forEach((vs,i)=>{if(vs===undefined&&i%nodeRankFactor!==0){--delta}else if(vs!==undefined&&delta){vs.forEach(v=>g.node(v).rank+=delta)}})}function addBorderNode(g,prefix,rank,order){let node={width:0,height:0};if(arguments.length>=4){node.rank=rank;node.order=order}return addDummyNode(g,"border",node,prefix)}function splitToChunks(array,chunkSize=CHUNKING_THRESHOLD){const chunks=[];for(let i=0;iCHUNKING_THRESHOLD){const chunks=splitToChunks(argsArray);return fn.apply(null,chunks.map(chunk=>fn.apply(null,chunk)))}else{return fn.apply(null,argsArray)}}function maxRank(g){const nodes=g.nodes();const nodeRanks=nodes.map(v=>{let rank=g.node(v).rank;if(rank===undefined){return Number.MIN_VALUE}return rank});return applyWithChunking(Math.max,nodeRanks)} +/* + * Partition a collection into two groups: `lhs` and `rhs`. If the supplied + * function returns true for an entry it goes into `lhs`. Otherwise it goes + * into `rhs. + */function partition(collection,fn){let result={lhs:[],rhs:[]};collection.forEach(value=>{if(fn(value)){result.lhs.push(value)}else{result.rhs.push(value)}});return result} +/* + * Returns a new function that wraps `fn` with a timer. The wrapper logs the + * time it takes to execute the function. + */function time(name,fn){let start=Date.now();try{return fn()}finally{console.log(name+" time: "+(Date.now()-start)+"ms")}}function notime(name,fn){return fn()}let idCounter=0;function uniqueId(prefix){var id=++idCounter;return toString(prefix)+id}function range(start,limit,step=1){if(limit==null){limit=start;start=0}let endCon=i=>ilimitval[funcOrProp]}return Object.entries(obj).reduce((acc,[k,v])=>{acc[k]=func(v,k);return acc},{})}function zipObject(props,values){return props.reduce((acc,key,i)=>{acc[key]=values[i];return acc},{})}},{"@dagrejs/graphlib":29}],28:[function(require,module,exports){module.exports="1.1.4"},{}],29:[function(require,module,exports){ +/** + * Copyright (c) 2014, Chris Pettitt + * All rights reserved. + * + * 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 the copyright holder 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. + */ +var lib=require("./lib");module.exports={Graph:lib.Graph,json:require("./lib/json"),alg:require("./lib/alg"),version:lib.version}},{"./lib":45,"./lib/alg":36,"./lib/json":46}],30:[function(require,module,exports){module.exports=components;function components(g){var visited={};var cmpts=[];var cmpt;function dfs(v){if(Object.hasOwn(visited,v))return;visited[v]=true;cmpt.push(v);g.successors(v).forEach(dfs);g.predecessors(v).forEach(dfs)}g.nodes().forEach(function(v){cmpt=[];dfs(v);if(cmpt.length){cmpts.push(cmpt)}});return cmpts}},{}],31:[function(require,module,exports){module.exports=dfs; +/* + * A helper that preforms a pre- or post-order traversal on the input graph + * and returns the nodes in the order they were visited. If the graph is + * undirected then this algorithm will navigate using neighbors. If the graph + * is directed then this algorithm will navigate using successors. + * + * If the order is not "post", it will be treated as "pre". + */function dfs(g,vs,order){if(!Array.isArray(vs)){vs=[vs]}var navigation=g.isDirected()?v=>g.successors(v):v=>g.neighbors(v);var orderFunc=order==="post"?postOrderDfs:preOrderDfs;var acc=[];var visited={};vs.forEach(v=>{if(!g.hasNode(v)){throw new Error("Graph does not have node: "+v)}orderFunc(v,navigation,visited,acc)});return acc}function postOrderDfs(v,navigation,visited,acc){var stack=[[v,false]];while(stack.length>0){var curr=stack.pop();if(curr[1]){acc.push(curr[0])}else{if(!Object.hasOwn(visited,curr[0])){visited[curr[0]]=true;stack.push([curr[0],true]);forEachRight(navigation(curr[0]),w=>stack.push([w,false]))}}}}function preOrderDfs(v,navigation,visited,acc){var stack=[v];while(stack.length>0){var curr=stack.pop();if(!Object.hasOwn(visited,curr)){visited[curr]=true;acc.push(curr);forEachRight(navigation(curr),w=>stack.push(w))}}}function forEachRight(array,iteratee){var length=array.length;while(length--){iteratee(array[length],length,array)}return array}},{}],32:[function(require,module,exports){var dijkstra=require("./dijkstra");module.exports=dijkstraAll;function dijkstraAll(g,weightFunc,edgeFunc){return g.nodes().reduce(function(acc,v){acc[v]=dijkstra(g,v,weightFunc,edgeFunc);return acc},{})}},{"./dijkstra":33}],33:[function(require,module,exports){var PriorityQueue=require("../data/priority-queue");module.exports=dijkstra;var DEFAULT_WEIGHT_FUNC=()=>1;function dijkstra(g,source,weightFn,edgeFn){return runDijkstra(g,String(source),weightFn||DEFAULT_WEIGHT_FUNC,edgeFn||function(v){return g.outEdges(v)})}function runDijkstra(g,source,weightFn,edgeFn){var results={};var pq=new PriorityQueue;var v,vEntry;var updateNeighbors=function(edge){var w=edge.v!==v?edge.v:edge.w;var wEntry=results[w];var weight=weightFn(edge);var distance=vEntry.distance+weight;if(weight<0){throw new Error("dijkstra does not allow negative edge weights. "+"Bad edge: "+edge+" Weight: "+weight)}if(distance0){v=pq.removeMin();vEntry=results[v];if(vEntry.distance===Number.POSITIVE_INFINITY){break}edgeFn(v).forEach(updateNeighbors)}return results}},{"../data/priority-queue":43}],34:[function(require,module,exports){var tarjan=require("./tarjan");module.exports=findCycles;function findCycles(g){return tarjan(g).filter(function(cmpt){return cmpt.length>1||cmpt.length===1&&g.hasEdge(cmpt[0],cmpt[0])})}},{"./tarjan":41}],35:[function(require,module,exports){module.exports=floydWarshall;var DEFAULT_WEIGHT_FUNC=()=>1;function floydWarshall(g,weightFn,edgeFn){return runFloydWarshall(g,weightFn||DEFAULT_WEIGHT_FUNC,edgeFn||function(v){return g.outEdges(v)})}function runFloydWarshall(g,weightFn,edgeFn){var results={};var nodes=g.nodes();nodes.forEach(function(v){results[v]={};results[v][v]={distance:0};nodes.forEach(function(w){if(v!==w){results[v][w]={distance:Number.POSITIVE_INFINITY}}});edgeFn(v).forEach(function(edge){var w=edge.v===v?edge.w:edge.v;var d=weightFn(edge);results[v][w]={distance:d,predecessor:v}})});nodes.forEach(function(k){var rowK=results[k];nodes.forEach(function(i){var rowI=results[i];nodes.forEach(function(j){var ik=rowI[k];var kj=rowK[j];var ij=rowI[j];var altDistance=ik.distance+kj.distance;if(altDistance0){v=pq.removeMin();if(Object.hasOwn(parents,v)){result.setEdge(v,parents[v])}else if(init){throw new Error("Input graph is not connected: "+g)}else{init=true}g.nodeEdges(v).forEach(updateNeighbors)}return result}},{"../data/priority-queue":43,"../graph":44}],41:[function(require,module,exports){module.exports=tarjan;function tarjan(g){var index=0;var stack=[];var visited={};// node id -> { onStack, lowlink, index } +var results=[];function dfs(v){var entry=visited[v]={onStack:true,lowlink:index,index:index++};stack.push(v);g.successors(v).forEach(function(w){if(!Object.hasOwn(visited,w)){dfs(w);entry.lowlink=Math.min(entry.lowlink,visited[w].lowlink)}else if(visited[w].onStack){entry.lowlink=Math.min(entry.lowlink,visited[w].index)}});if(entry.lowlink===entry.index){var cmpt=[];var w;do{w=stack.pop();visited[w].onStack=false;cmpt.push(w)}while(v!==w);results.push(cmpt)}}g.nodes().forEach(function(v){if(!Object.hasOwn(visited,v)){dfs(v)}});return results}},{}],42:[function(require,module,exports){function topsort(g){var visited={};var stack={};var results=[];function visit(node){if(Object.hasOwn(stack,node)){throw new CycleException}if(!Object.hasOwn(visited,node)){stack[node]=true;visited[node]=true;g.predecessors(node).forEach(visit);delete stack[node];results.push(node)}}g.sinks().forEach(visit);if(Object.keys(visited).length!==g.nodeCount()){throw new CycleException}return results}class CycleException extends Error{constructor(){super(...arguments)}}module.exports=topsort;topsort.CycleException=CycleException},{}],43:[function(require,module,exports){ +/** + * A min-priority queue data structure. This algorithm is derived from Cormen, + * et al., "Introduction to Algorithms". The basic idea of a min-priority + * queue is that you can efficiently (in O(1) time) get the smallest key in + * the queue. Adding and removing elements takes O(log n) time. A key can + * have its priority decreased in O(log n) time. + */ +class PriorityQueue{_arr=[];_keyIndices={}; +/** + * Returns the number of elements in the queue. Takes `O(1)` time. + */size(){return this._arr.length} +/** + * Returns the keys that are in the queue. Takes `O(n)` time. + */keys(){return this._arr.map(function(x){return x.key})} +/** + * Returns `true` if **key** is in the queue and `false` if not. + */has(key){return Object.hasOwn(this._keyIndices,key)} +/** + * Returns the priority for **key**. If **key** is not present in the queue + * then this function returns `undefined`. Takes `O(1)` time. + * + * @param {Object} key + */priority(key){var index=this._keyIndices[key];if(index!==undefined){return this._arr[index].priority}} +/** + * Returns the key for the minimum element in this queue. If the queue is + * empty this function throws an Error. Takes `O(1)` time. + */min(){if(this.size()===0){throw new Error("Queue underflow")}return this._arr[0].key} +/** + * Inserts a new key into the priority queue. If the key already exists in + * the queue this function returns `false`; otherwise it will return `true`. + * Takes `O(n)` time. + * + * @param {Object} key the key to add + * @param {Number} priority the initial priority for the key + */add(key,priority){var keyIndices=this._keyIndices;key=String(key);if(!Object.hasOwn(keyIndices,key)){var arr=this._arr;var index=arr.length;keyIndices[key]=index;arr.push({key:key,priority:priority});this._decrease(index);return true}return false} +/** + * Removes and returns the smallest key in the queue. Takes `O(log n)` time. + */removeMin(){this._swap(0,this._arr.length-1);var min=this._arr.pop();delete this._keyIndices[min.key];this._heapify(0);return min.key} +/** + * Decreases the priority for **key** to **priority**. If the new priority is + * greater than the previous priority, this function will throw an Error. + * + * @param {Object} key the key for which to raise priority + * @param {Number} priority the new priority for the key + */decrease(key,priority){var index=this._keyIndices[key];if(priority>this._arr[index].priority){throw new Error("New priority is greater than current priority. "+"Key: "+key+" Old: "+this._arr[index].priority+" New: "+priority)}this._arr[index].priority=priority;this._decrease(index)}_heapify(i){var arr=this._arr;var l=2*i;var r=l+1;var largest=i;if(l>1;if(arr[parent].priorityundefined; +// Defaults to be set when creating a new edge +_defaultEdgeLabelFn=()=>undefined; +// v -> label +_nodes={}; +// v -> edgeObj +_in={}; +// u -> v -> Number +_preds={}; +// v -> edgeObj +_out={}; +// v -> w -> Number +_sucs={}; +// e -> edgeObj +_edgeObjs={}; +// e -> label +_edgeLabels={}; +/* Number of nodes in the graph. Should only be changed by the implementation. */_nodeCount=0; +/* Number of edges in the graph. Should only be changed by the implementation. */_edgeCount=0;_parent;_children;constructor(opts){if(opts){this._isDirected=Object.hasOwn(opts,"directed")?opts.directed:true;this._isMultigraph=Object.hasOwn(opts,"multigraph")?opts.multigraph:false;this._isCompound=Object.hasOwn(opts,"compound")?opts.compound:false}if(this._isCompound){ +// v -> parent +this._parent={}; +// v -> children +this._children={};this._children[GRAPH_NODE]={}}} +/* === Graph functions ========= */ +/** + * Whether graph was created with 'directed' flag set to true or not. + */isDirected(){return this._isDirected} +/** + * Whether graph was created with 'multigraph' flag set to true or not. + */isMultigraph(){return this._isMultigraph} +/** + * Whether graph was created with 'compound' flag set to true or not. + */isCompound(){return this._isCompound} +/** + * Sets the label of the graph. + */setGraph(label){this._label=label;return this} +/** + * Gets the graph label. + */graph(){return this._label} +/* === Node functions ========== */ +/** + * Sets the default node label. If newDefault is a function, it will be + * invoked ach time when setting a label for a node. Otherwise, this label + * will be assigned as default label in case if no label was specified while + * setting a node. + * Complexity: O(1). + */setDefaultNodeLabel(newDefault){this._defaultNodeLabelFn=newDefault;if(typeof newDefault!=="function"){this._defaultNodeLabelFn=()=>newDefault}return this} +/** + * Gets the number of nodes in the graph. + * Complexity: O(1). + */nodeCount(){return this._nodeCount} +/** + * Gets all nodes of the graph. Note, the in case of compound graph subnodes are + * not included in list. + * Complexity: O(1). + */nodes(){return Object.keys(this._nodes)} +/** + * Gets list of nodes without in-edges. + * Complexity: O(|V|). + */sources(){var self=this;return this.nodes().filter(v=>Object.keys(self._in[v]).length===0)} +/** + * Gets list of nodes without out-edges. + * Complexity: O(|V|). + */sinks(){var self=this;return this.nodes().filter(v=>Object.keys(self._out[v]).length===0)} +/** + * Invokes setNode method for each node in names list. + * Complexity: O(|names|). + */setNodes(vs,value){var args=arguments;var self=this;vs.forEach(function(v){if(args.length>1){self.setNode(v,value)}else{self.setNode(v)}});return this} +/** + * Creates or updates the value for the node v in the graph. If label is supplied + * it is set as the value for the node. If label is not supplied and the node was + * created by this call then the default node label will be assigned. + * Complexity: O(1). + */setNode(v,value){if(Object.hasOwn(this._nodes,v)){if(arguments.length>1){this._nodes[v]=value}return this}this._nodes[v]=arguments.length>1?value:this._defaultNodeLabelFn(v);if(this._isCompound){this._parent[v]=GRAPH_NODE;this._children[v]={};this._children[GRAPH_NODE][v]=true}this._in[v]={};this._preds[v]={};this._out[v]={};this._sucs[v]={};++this._nodeCount;return this} +/** + * Gets the label of node with specified name. + * Complexity: O(|V|). + */node(v){return this._nodes[v]} +/** + * Detects whether graph has a node with specified name or not. + */hasNode(v){return Object.hasOwn(this._nodes,v)} +/** + * Remove the node with the name from the graph or do nothing if the node is not in + * the graph. If the node was removed this function also removes any incident + * edges. + * Complexity: O(1). + */removeNode(v){var self=this;if(Object.hasOwn(this._nodes,v)){var removeEdge=e=>self.removeEdge(self._edgeObjs[e]);delete this._nodes[v];if(this._isCompound){this._removeFromParentsChildList(v);delete this._parent[v];this.children(v).forEach(function(child){self.setParent(child)});delete this._children[v]}Object.keys(this._in[v]).forEach(removeEdge);delete this._in[v];delete this._preds[v];Object.keys(this._out[v]).forEach(removeEdge);delete this._out[v];delete this._sucs[v];--this._nodeCount}return this} +/** + * Sets node p as a parent for node v if it is defined, or removes the + * parent for v if p is undefined. Method throws an exception in case of + * invoking it in context of noncompound graph. + * Average-case complexity: O(1). + */setParent(v,parent){if(!this._isCompound){throw new Error("Cannot set parent in a non-compound graph")}if(parent===undefined){parent=GRAPH_NODE}else{ +// Coerce parent to string +parent+="";for(var ancestor=parent;ancestor!==undefined;ancestor=this.parent(ancestor)){if(ancestor===v){throw new Error("Setting "+parent+" as parent of "+v+" would create a cycle")}}this.setNode(parent)}this.setNode(v);this._removeFromParentsChildList(v);this._parent[v]=parent;this._children[parent][v]=true;return this}_removeFromParentsChildList(v){delete this._children[this._parent[v]][v]} +/** + * Gets parent node for node v. + * Complexity: O(1). + */parent(v){if(this._isCompound){var parent=this._parent[v];if(parent!==GRAPH_NODE){return parent}}} +/** + * Gets list of direct children of node v. + * Complexity: O(1). + */children(v=GRAPH_NODE){if(this._isCompound){var children=this._children[v];if(children){return Object.keys(children)}}else if(v===GRAPH_NODE){return this.nodes()}else if(this.hasNode(v)){return[]}} +/** + * Return all nodes that are predecessors of the specified node or undefined if node v is not in + * the graph. Behavior is undefined for undirected graphs - use neighbors instead. + * Complexity: O(|V|). + */predecessors(v){var predsV=this._preds[v];if(predsV){return Object.keys(predsV)}} +/** + * Return all nodes that are successors of the specified node or undefined if node v is not in + * the graph. Behavior is undefined for undirected graphs - use neighbors instead. + * Complexity: O(|V|). + */successors(v){var sucsV=this._sucs[v];if(sucsV){return Object.keys(sucsV)}} +/** + * Return all nodes that are predecessors or successors of the specified node or undefined if + * node v is not in the graph. + * Complexity: O(|V|). + */neighbors(v){var preds=this.predecessors(v);if(preds){const union=new Set(preds);for(var succ of this.successors(v)){union.add(succ)}return Array.from(union.values())}}isLeaf(v){var neighbors;if(this.isDirected()){neighbors=this.successors(v)}else{neighbors=this.neighbors(v)}return neighbors.length===0} +/** + * Creates new graph with nodes filtered via filter. Edges incident to rejected node + * are also removed. In case of compound graph, if parent is rejected by filter, + * than all its children are rejected too. + * Average-case complexity: O(|E|+|V|). + */filterNodes(filter){var copy=new this.constructor({directed:this._isDirected,multigraph:this._isMultigraph,compound:this._isCompound});copy.setGraph(this.graph());var self=this;Object.entries(this._nodes).forEach(function([v,value]){if(filter(v)){copy.setNode(v,value)}});Object.values(this._edgeObjs).forEach(function(e){if(copy.hasNode(e.v)&©.hasNode(e.w)){copy.setEdge(e,self.edge(e))}});var parents={};function findParent(v){var parent=self.parent(v);if(parent===undefined||copy.hasNode(parent)){parents[v]=parent;return parent}else if(parent in parents){return parents[parent]}else{return findParent(parent)}}if(this._isCompound){copy.nodes().forEach(v=>copy.setParent(v,findParent(v)))}return copy} +/* === Edge functions ========== */ +/** + * Sets the default edge label or factory function. This label will be + * assigned as default label in case if no label was specified while setting + * an edge or this function will be invoked each time when setting an edge + * with no label specified and returned value * will be used as a label for edge. + * Complexity: O(1). + */setDefaultEdgeLabel(newDefault){this._defaultEdgeLabelFn=newDefault;if(typeof newDefault!=="function"){this._defaultEdgeLabelFn=()=>newDefault}return this} +/** + * Gets the number of edges in the graph. + * Complexity: O(1). + */edgeCount(){return this._edgeCount} +/** + * Gets edges of the graph. In case of compound graph subgraphs are not considered. + * Complexity: O(|E|). + */edges(){return Object.values(this._edgeObjs)} +/** + * Establish an edges path over the nodes in nodes list. If some edge is already + * exists, it will update its label, otherwise it will create an edge between pair + * of nodes with label provided or default label if no label provided. + * Complexity: O(|nodes|). + */setPath(vs,value){var self=this;var args=arguments;vs.reduce(function(v,w){if(args.length>1){self.setEdge(v,w,value)}else{self.setEdge(v,w)}return w});return this} +/** + * Creates or updates the label for the edge (v, w) with the optionally supplied + * name. If label is supplied it is set as the value for the edge. If label is not + * supplied and the edge was created by this call then the default edge label will + * be assigned. The name parameter is only useful with multigraphs. + */setEdge(){var v,w,name,value;var valueSpecified=false;var arg0=arguments[0];if(typeof arg0==="object"&&arg0!==null&&"v"in arg0){v=arg0.v;w=arg0.w;name=arg0.name;if(arguments.length===2){value=arguments[1];valueSpecified=true}}else{v=arg0;w=arguments[1];name=arguments[3];if(arguments.length>2){value=arguments[2];valueSpecified=true}}v=""+v;w=""+w;if(name!==undefined){name=""+name}var e=edgeArgsToId(this._isDirected,v,w,name);if(Object.hasOwn(this._edgeLabels,e)){if(valueSpecified){this._edgeLabels[e]=value}return this}if(name!==undefined&&!this._isMultigraph){throw new Error("Cannot set a named edge when isMultigraph = false")} +// It didn't exist, so we need to create it. +// First ensure the nodes exist. +this.setNode(v);this.setNode(w);this._edgeLabels[e]=valueSpecified?value:this._defaultEdgeLabelFn(v,w,name);var edgeObj=edgeArgsToObj(this._isDirected,v,w,name); +// Ensure we add undirected edges in a consistent way. +v=edgeObj.v;w=edgeObj.w;Object.freeze(edgeObj);this._edgeObjs[e]=edgeObj;incrementOrInitEntry(this._preds[w],v);incrementOrInitEntry(this._sucs[v],w);this._in[w][e]=edgeObj;this._out[v][e]=edgeObj;this._edgeCount++;return this} +/** + * Gets the label for the specified edge. + * Complexity: O(1). + */edge(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);return this._edgeLabels[e]} +/** + * Gets the label for the specified edge and converts it to an object. + * Complexity: O(1) + */edgeAsObj(){const edge=this.edge(...arguments);if(typeof edge!=="object"){return{label:edge}}return edge} +/** + * Detects whether the graph contains specified edge or not. No subgraphs are considered. + * Complexity: O(1). + */hasEdge(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);return Object.hasOwn(this._edgeLabels,e)} +/** + * Removes the specified edge from the graph. No subgraphs are considered. + * Complexity: O(1). + */removeEdge(v,w,name){var e=arguments.length===1?edgeObjToId(this._isDirected,arguments[0]):edgeArgsToId(this._isDirected,v,w,name);var edge=this._edgeObjs[e];if(edge){v=edge.v;w=edge.w;delete this._edgeLabels[e];delete this._edgeObjs[e];decrementOrRemoveEntry(this._preds[w],v);decrementOrRemoveEntry(this._sucs[v],w);delete this._in[w][e];delete this._out[v][e];this._edgeCount--}return this} +/** + * Return all edges that point to the node v. Optionally filters those edges down to just those + * coming from node u. Behavior is undefined for undirected graphs - use nodeEdges instead. + * Complexity: O(|E|). + */inEdges(v,u){var inV=this._in[v];if(inV){var edges=Object.values(inV);if(!u){return edges}return edges.filter(edge=>edge.v===u)}} +/** + * Return all edges that are pointed at by node v. Optionally filters those edges down to just + * those point to w. Behavior is undefined for undirected graphs - use nodeEdges instead. + * Complexity: O(|E|). + */outEdges(v,w){var outV=this._out[v];if(outV){var edges=Object.values(outV);if(!w){return edges}return edges.filter(edge=>edge.w===w)}} +/** + * Returns all edges to or from node v regardless of direction. Optionally filters those edges + * down to just those between nodes v and w regardless of direction. + * Complexity: O(|E|). + */nodeEdges(v,w){var inEdges=this.inEdges(v,w);if(inEdges){return inEdges.concat(this.outEdges(v,w))}}}function incrementOrInitEntry(map,k){if(map[k]){map[k]++}else{map[k]=1}}function decrementOrRemoveEntry(map,k){if(!--map[k]){delete map[k]}}function edgeArgsToId(isDirected,v_,w_,name){var v=""+v_;var w=""+w_;if(!isDirected&&v>w){var tmp=v;v=w;w=tmp}return v+EDGE_KEY_DELIM+w+EDGE_KEY_DELIM+(name===undefined?DEFAULT_EDGE_NAME:name)}function edgeArgsToObj(isDirected,v_,w_,name){var v=""+v_;var w=""+w_;if(!isDirected&&v>w){var tmp=v;v=w;w=tmp}var edgeObj={v:v,w:w};if(name){edgeObj.name=name}return edgeObj}function edgeObjToId(isDirected,edgeObj){return edgeArgsToId(isDirected,edgeObj.v,edgeObj.w,edgeObj.name)}module.exports=Graph},{}],45:[function(require,module,exports){ +// Includes only the "core" of graphlib +module.exports={Graph:require("./graph"),version:require("./version")}},{"./graph":44,"./version":47}],46:[function(require,module,exports){var Graph=require("./graph");module.exports={write:write,read:read}; +/** + * Creates a JSON representation of the graph that can be serialized to a string with + * JSON.stringify. The graph can later be restored using json.read. + */function write(g){var json={options:{directed:g.isDirected(),multigraph:g.isMultigraph(),compound:g.isCompound()},nodes:writeNodes(g),edges:writeEdges(g)};if(g.graph()!==undefined){json.value=structuredClone(g.graph())}return json}function writeNodes(g){return g.nodes().map(function(v){var nodeValue=g.node(v);var parent=g.parent(v);var node={v:v};if(nodeValue!==undefined){node.value=nodeValue}if(parent!==undefined){node.parent=parent}return node})}function writeEdges(g){return g.edges().map(function(e){var edgeValue=g.edge(e);var edge={v:e.v,w:e.w};if(e.name!==undefined){edge.name=e.name}if(edgeValue!==undefined){edge.value=edgeValue}return edge})} +/** + * Takes JSON as input and returns the graph representation. + * + * @example + * var g2 = graphlib.json.read(JSON.parse(str)); + * g2.nodes(); + * // ['a', 'b'] + * g2.edges() + * // [ { v: 'a', w: 'b' } ] + */function read(json){var g=new Graph(json.options).setGraph(json.value);json.nodes.forEach(function(entry){g.setNode(entry.v,entry.value);if(entry.parent){g.setParent(entry.v,entry.parent)}});json.edges.forEach(function(entry){g.setEdge({v:entry.v,w:entry.w,name:entry.name},entry.value)});return g}},{"./graph":44}],47:[function(require,module,exports){module.exports="2.2.4"},{}]},{},[1])(1)}); diff --git a/tinygrad_repo/tinygrad/viz/fetch_assets.sh b/tinygrad_repo/tinygrad/viz/fetch_assets.sh index 0bea85055e..ae4720ce86 100755 --- a/tinygrad_repo/tinygrad/viz/fetch_assets.sh +++ b/tinygrad_repo/tinygrad/viz/fetch_assets.sh @@ -5,12 +5,10 @@ fetch() { rmdir assets/$1 curl -o assets/$1 https://$1 } -fetch "d3js.org/d3.v5.min.js" -fetch "dagrejs.github.io/project/dagre-d3/latest/dagre-d3.min.js" +fetch "d3js.org/d3.v7.min.js" +fetch "dagrejs.github.io/project/dagre/latest/dagre.min.js" fetch "cdnjs.cloudflare.com/ajax/libs/highlight.js/11.10.0/styles/default.min.css" fetch "cdnjs.cloudflare.com/ajax/libs/highlight.js/11.10.0/highlight.min.js" fetch "cdnjs.cloudflare.com/ajax/libs/highlight.js/11.10.0/languages/python.min.js" fetch "cdnjs.cloudflare.com/ajax/libs/highlight.js/11.10.0/languages/cpp.min.js" -fetch "cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js" -fetch "cdnjs.cloudflare.com/ajax/libs/dompurify/1.0.3/purify.min.js.map" fetch "unpkg.com/@highlightjs/cdn-assets@11.10.0/styles/tokyo-night-dark.min.css" diff --git a/tinygrad_repo/tinygrad/viz/index.html b/tinygrad_repo/tinygrad/viz/index.html index f42ac724e8..a6d847a41b 100644 --- a/tinygrad_repo/tinygrad/viz/index.html +++ b/tinygrad_repo/tinygrad/viz/index.html @@ -4,22 +4,18 @@ tinygrad viz - - + + -

Profiler +
-
+
- - +
Rendering new layout...
+ + + + + + + + + + + +
- +
- - + + diff --git a/tinygrad_repo/tinygrad/viz/js/index.js b/tinygrad_repo/tinygrad/viz/js/index.js new file mode 100644 index 0000000000..2469ff7ec8 --- /dev/null +++ b/tinygrad_repo/tinygrad/viz/js/index.js @@ -0,0 +1,456 @@ +// **** graph renderers + +// ** UOp graph + +function intersectRect(r1, r2) { + const dx = r2.x-r1.x; + const dy = r2.y-r1.y; + if (dx === 0 && dy === 0) throw new Error("Invalid node coordinates, rects must not overlap"); + const scaleX = dx !== 0 ? (r1.width/2)/Math.abs(dx) : Infinity; + const scaleY = dy !== 0 ? (r1.height/2)/Math.abs(dy) : Infinity; + const scale = Math.min(scaleX, scaleY); + return {x:r1.x+dx*scale, y:r1.y+dy*scale}; +} + +const rect = (s) => document.querySelector(s).getBoundingClientRect(); + +let [workerUrl, worker, timeout] = [null, null, null]; +async function renderDag(graph, additions, recenter=false) { + // start calculating the new layout (non-blocking) + if (worker == null) { + const resp = await Promise.all(["/assets/dagrejs.github.io/project/dagre/latest/dagre.min.js","/js/worker.js"].map(u => fetch(u))); + workerUrl = URL.createObjectURL(new Blob([(await Promise.all(resp.map((r) => r.text()))).join("\n")], { type: "application/javascript" })); + worker = new Worker(workerUrl); + } else { + worker.terminate(); + worker = new Worker(workerUrl); + } + if (timeout != null) clearTimeout(timeout); + const progressMessage = document.querySelector(".progress-message"); + timeout = setTimeout(() => {progressMessage.style.display = "block"}, 2000); + worker.postMessage({graph, additions}); + worker.onmessage = (e) => { + progressMessage.style.display = "none"; + clearTimeout(timeout); + d3.select("#bars").html(""); + const g = dagre.graphlib.json.read(e.data); + // draw nodes + const STROKE_WIDTH = 1.4; + const nodes = d3.select("#nodes").selectAll("g").data(g.nodes().map(id => g.node(id)), d => d).join("g") + .attr("transform", d => `translate(${d.x},${d.y})`); + nodes.selectAll("rect").data(d => [d]).join("rect").attr("width", d => d.width).attr("height", d => d.height).attr("fill", d => d.color) + .attr("x", d => -d.width/2).attr("y", d => -d.height/2).attr("style", d => `stroke:#4a4b57; stroke-width:${STROKE_WIDTH}px; ${d.style}`); + nodes.selectAll("g.label").data(d => [d]).join("g").attr("class", "label").attr("transform", d => { + const x = (d.width-d.padding*2)/2; + const y = (d.height-d.padding*2)/2+STROKE_WIDTH; + return `translate(-${x}, -${y})`; + }).selectAll("text").data(d => [d.label.split("\n")]).join("text").selectAll("tspan").data(d => d).join("tspan").text(d => d).attr("x", "0") + .attr("dy", 14).attr("xml:space", "preserve"); + // draw edges + const line = d3.line().x(d => d.x).y(d => d.y).curve(d3.curveBasis); + d3.select("#edges").selectAll("path.edgePath").data(g.edges()).join("path").attr("class", "edgePath").attr("d", (e) => { + const edge = g.edge(e); + const points = edge.points.slice(1, edge.points.length-1); + points.unshift(intersectRect(g.node(e.v), points[0])); + points.push(intersectRect(g.node(e.w), points[points.length-1])); + return line(points); + }).attr("marker-end", "url(#arrowhead)"); + const edgeLabels = d3.select("#edge-labels").selectAll("g").data(g.edges().filter(e => g.edge(e).label != null)).join("g").attr("transform", (e) => { + // get a point near the end + const [p1, p2] = g.edge(e).points.slice(-2); + const dx = p2.x-p1.x; + const dy = p2.y-p1.y; + // normalize to the unit vector + const len = Math.sqrt(dx*dx + dy*dy); + const ux = dx / len; + const uy = dy / len; + // avoid overlap with the arrowhead + const offset = 17; + const x = p2.x - ux * offset; + const y = p2.y - uy * offset; + return `translate(${x}, ${y})` + }); + edgeLabels.selectAll("circle").data(e => [g.edge(e).label]).join("circle").attr("r", 5).attr("fill", "#FFD700").attr("stroke", "#B8860B") + .attr("stroke-width", 0.8); + edgeLabels.selectAll("text").data(e => [g.edge(e).label]).join("text").text(d => d).attr("text-anchor", "middle").attr("dy", "0.35em") + .attr("font-size", "6px").attr("fill", "black"); + if (recenter) document.getElementById("zoom-to-fit-btn").click(); + }; + +} + +// ** Memory graph (WIP) + +DTYPE_SIZE = {"bool": 1, "char": 1, "uchar": 1, "short": 2, "ushort": 2, "int": 4, "uint": 4, + "long": 8, "ulong": 8, "half": 2, "bfloat": 2, "float": 4, "double": 8} +function getBuffer(e) { + const [_, size, dtype, num, device] = e.label.split("\n"); + return {nbytes:size*DTYPE_SIZE[dtype.split("dtypes.")[1]], dtype, device:device.split(" ")[1], num:parseInt(num.split(" ")[1])}; +} + +function pluralize(num, name, alt=null) { + return num === 1 ? `${num} ${name}` : `${num} ${alt ?? name+'s'}` +} + +function renderMemoryGraph(graph) { + // ** construct alloc/free traces + // we can map reads/writes from the kernel graph + const actions = []; + const children = new Map(); // {buffer: [...assign]} + for (const [k,v] of Object.entries(graph)) { + if (!v.label.startsWith("ASSIGN")) continue; + actions.push({ op: "write", buffer: v.src[0] }); + for (const ks of graph[v.src[1]].src) { + const node = graph[ks]; + const s = node.label.startsWith("ASSIGN") ? node.src[0] : ks; + if (!children.has(s)) children.set(s, []); + children.get(s).push(v); + if (s !== v.src[0]) actions.push({ op: "read", buffer: s }); + } + } + const prealloc = new Set(); + const traces = []; + for (const a of actions) { + // a buffer is allocated immediately before the first write + // TODO: we don't know the buffer is preallocated if there's only an assign in the graph + if (a.op === "write") { + traces.push({ type: "alloc", buffer: a.buffer }); + } + else { + if (traces.find(t => t.buffer === a.buffer && t.type === "alloc") == null) { + prealloc.add(a.buffer); + } + else if (a === actions.findLast(({ buffer }) => buffer === a.buffer)) { + traces.push({type: "free", buffer: a.buffer }); + } + } + } + // ** get coordinates and layout for each buffer + const ret = {}; + let timestep = 0; // x + let memUsed = 0; // y + for (const id of prealloc) { + const buf = getBuffer(graph[id]); + ret[id] = { x: [timestep], y: [memUsed], buf, id }; + memUsed += buf.nbytes; + } + let peak = memUsed; + const liveBufs = [...prealloc]; + for (const t of traces) { + const buf = getBuffer(graph[t.buffer]); + const idx = liveBufs.findLastIndex(b => t.buffer === b); + // alloc + if (idx === -1) { + liveBufs.push(t.buffer); + ret[t.buffer] = { x: [timestep], y: [memUsed], buf, id: t.buffer }; + memUsed += buf.nbytes; + peak = Math.max(memUsed, peak); + timestep += 1; + } // free + else { + memUsed -= buf.nbytes; + timestep += 1; + const removed = ret[liveBufs.splice(idx, 1)[0]]; + removed.x.push(timestep); + removed.y.push(removed.y.at(-1)); + if (idx < liveBufs.length) { + for (let j=idx; j d3.format(".3~s")(d)+"B"; + axesGroup.append("g").call(d3.axisLeft(yscale).tickFormat(nbytes_format)); + axesGroup.append("g").attr("transform", `translate(0, ${yscale.range()[0]})`).call(d3.axisBottom(xscale).tickFormat(() => "")); + const polygonGroup = render.append("g").attr("id", "polygons"); + const colors = ["7aa2f7", "ff9e64", "f7768e", "2ac3de", "7dcfff", "1abc9c", "9ece6a", "e0af68", "bb9af7", "9d7cd8", "ff007c"]; + const polygons = polygonGroup.selectAll("polygon").data(Object.values(ret)).join("polygon").attr("points", (d) => { + const xs = d.x.map(t => xscale(t)); + const y1 = d.y.map(t => yscale(t)); + const y2 = d.y.map(t => yscale(t+d.buf.nbytes)); + const p0 = xs.map((x, i) => `${x},${y1[i]}`); + const p1 = xs.map((x, i) => `${x},${y2[i]}`).reverse(); + return `${p0.join(' ')} ${p1.join(' ')}`; + }).attr("fill", d => `#${colors[d.buf.num % colors.length]}`).on("mouseover", (e, { id, buf, x }) => { + d3.select(e.currentTarget).attr("stroke", "rgba(26, 27, 38, 0.8)").attr("stroke-width", 0.8); + const metadata = document.querySelector(".metadata"); + document.getElementById("current-buf")?.remove(); + const { num, dtype, nbytes, ...rest } = buf; + let label = `\nalive for ${pluralize(x[x.length-1]-x[0], 'timestep')}`; + label += '\n'+Object.entries(rest).map(([k, v]) => `${k}=${v}`).join('\n'); + const buf_children = children.get(id); + if (buf_children) { + label += `\n${pluralize(buf_children.length, 'child', 'children')}\n`; + label += buf_children.map((c,i) => `[${i+1}] `+graph[c.src[1]].label.split("\n")[1]).join("\n"); + } + metadata.appendChild(Object.assign(document.createElement("pre"), { innerText: label, id: "current-buf", className: "wrap" })); + }).on("mouseout", (e, _) => { + d3.select(e.currentTarget).attr("stroke", null).attr("stroke-width", null); + document.getElementById("current-buf")?.remove() + }); + // TODO: add the toposort graph here + document.querySelector(".progress-message").style.display = "none"; + d3.select("#nodes").html(""); + d3.select("#edges").html(""); + document.getElementById("zoom-to-fit-btn").click(); +} + +// ** zoom and recentering + +const zoom = d3.zoom().on("zoom", (e) => d3.select("#render").attr("transform", e.transform)); +d3.select("#graph-svg").call(zoom); +// zoom to fit into view +document.getElementById("zoom-to-fit-btn").addEventListener("click", () => { + const svg = d3.select("#graph-svg"); + svg.call(zoom.transform, d3.zoomIdentity); + const mainRect = rect(".main-container"); + const x0 = rect(".kernel-list-parent").right; + const x1 = rect(".metadata-parent").left; + const pad = 16; + const R = { x: x0+pad, y: mainRect.top+pad, width: (x1>0 ? x1-x0 : mainRect.width)-2*pad, height: mainRect.height-2*pad }; + const r = rect("#render"); + if (r.width === 0) return; + const scale = Math.min(R.width/r.width, R.height/r.height); + const [tx, ty] = [R.x+(R.width-r.width*scale)/2, R.y+(R.height-r.height*scale)/2]; + svg.call(zoom.transform, d3.zoomIdentity.translate(tx, ty).scale(scale)); +}); + +// **** main VIZ interfacae + +function codeBlock(st, language, { loc, wrap }) { + const code = document.createElement("code"); + code.innerHTML = hljs.highlight(st, { language }).value; + code.className = "hljs"; + const ret = document.createElement("pre"); + if (wrap) ret.className = "wrap"; + if (loc != null) { + const link = ret.appendChild(document.createElement("a")); + link.href = "vscode://file"+loc.join(":"); + link.textContent = `${loc[0].split("/").at(-1)}:${loc[1]}`+"\n\n"; + } + ret.appendChild(code); + return ret; +} + +// ** hljs extra definitions for UOps and float4 +hljs.registerLanguage("python", (hljs) => ({ + ...hljs.getLanguage("python"), + case_insensitive: false, + contains: [ + { begin: 'dtypes\\.[a-zA-Z_][a-zA-Z0-9_-]*(\\.[a-zA-Z_][a-zA-Z0-9_-]*)*' + '(?=[.\\s\\n[:,(])', className: "type" }, + { begin: 'dtypes\\.[a-zA-Z_][a-zA-Z0-9_-].vec*' + '(?=[.\\s\\n[:,(])', className: "type" }, + { begin: '[a-zA-Z_][a-zA-Z0-9_-]*\\.[a-zA-Z_][a-zA-Z0-9_-]*' + '(?=[.\\s\\n[:,()])', className: "operator" }, + { begin: '[A-Z][a-zA-Z0-9_]*(?=\\()', className: "section", ignoreEnd: true }, + ...hljs.getLanguage("python").contains, + ] +})); +hljs.registerLanguage("cpp", (hljs) => ({ + ...hljs.getLanguage('cpp'), + contains: [{ begin: '\\b(?:float|half)[0-9]+\\b', className: 'type' }, ...hljs.getLanguage('cpp').contains] +})); + +var ret = []; +var cache = {}; +var kernels = null; +const evtSources = []; +const state = {currentKernel:-1, currentUOp:0, currentRewrite:0, expandKernel:false}; +function setState(ns) { + Object.assign(state, ns); + main(); +} +async function main() { + const { currentKernel, currentUOp, currentRewrite, expandKernel } = state; + // ** left sidebar kernel list + if (kernels == null) { + kernels = await (await fetch("/kernels")).json(); + setState({ currentKernel:-1 }); + } + const kernelList = document.querySelector(".kernel-list"); + kernelList.innerHTML = ""; + for (const [i,k] of kernels.entries()) { + const ul = kernelList.appendChild(document.createElement("ul")); + if (i === currentKernel) { + ul.className = "active"; + requestAnimationFrame(() => ul.scrollIntoView({ behavior: "auto", block: "nearest" })); + } + const p = ul.appendChild(document.createElement("p")); + p.innerHTML = k[0].replace(/\u001b\[(\d+)m(.*?)\u001b\[0m/g, (_, code, st) => { + const colors = ['gray','red','green','yellow','blue','magenta','cyan','white']; + return `${st}`; + }); + p.onclick = () => { + setState(i === currentKernel ? { expandKernel:!expandKernel } : { expandKernel:true, currentKernel:i, currentUOp:0, currentRewrite:0 }); + } + for (const [j,u] of k[1].entries()) { + const inner = ul.appendChild(document.createElement("ul")); + if (i === currentKernel && j === currentUOp) { + inner.className = "active"; + requestAnimationFrame(() => inner.scrollIntoView({ behavior: "auto", block: "nearest" })); + } + inner.innerText = `${u.name ?? u.loc[0].replaceAll("\\", "/").split("/").pop()+':'+u.loc[1]} - ${u.match_count}`; + inner.style.marginLeft = `${8*u.depth}px`; + inner.style.display = i === currentKernel && expandKernel ? "block" : "none"; + inner.onclick = (e) => { + e.stopPropagation(); + setState({ currentUOp:j, currentKernel:i, currentRewrite:0 }); + } + } + } + // ** center graph + if (currentKernel == -1) return; + const kernel = kernels[currentKernel][1][currentUOp]; + const cacheKey = `kernel=${currentKernel}&idx=${currentUOp}`; + // close any pending event sources + let activeSrc = null; + for (const e of evtSources) { + if (e.url.split("?")[1] !== cacheKey) e.close(); + else if (e.readyState === EventSource.OPEN) activeSrc = e; + } + if (cacheKey in cache) { + ret = cache[cacheKey]; + } + // if we don't have a complete cache yet we start streaming this kernel + if (!(cacheKey in cache) || (cache[cacheKey].length !== kernel.match_count+1 && activeSrc == null)) { + ret = []; + cache[cacheKey] = ret; + const eventSource = new EventSource(`/kernels?kernel=${currentKernel}&idx=${currentUOp}`); + evtSources.push(eventSource); + eventSource.onmessage = (e) => { + if (e.data === "END") return eventSource.close(); + const chunk = JSON.parse(e.data); + ret.push(chunk); + // if it's the first one render this new rgaph + if (ret.length === 1) return main(); + // otherwise just enable the graph selector + const ul = document.getElementById(`rewrite-${ret.length-1}`); + if (ul != null) ul.classList.remove("disabled"); + }; + } + if (ret.length === 0) return; + if (kernel.name == "View Memory Graph") { + renderMemoryGraph(ret[currentRewrite].graph); + } else { + renderDag(ret[currentRewrite].graph, ret[currentRewrite].changed_nodes || [], recenter=currentRewrite === 0); + } + // ** right sidebar code blocks + const metadata = document.querySelector(".metadata"); + const [code, lang] = kernel.kernel_code != null ? [kernel.kernel_code, "cpp"] : [ret[currentRewrite].uop, "python"]; + metadata.replaceChildren(codeBlock(kernel.code_line, "python", { loc:kernel.loc, wrap:true }), codeBlock(code, lang, { wrap:false })); + // ** rewrite steps + if (kernel.match_count >= 1) { + const rewriteList = metadata.appendChild(document.createElement("div")); + rewriteList.className = "rewrite-list"; + for (let s=0; s<=kernel.match_count; s++) { + const ul = rewriteList.appendChild(document.createElement("ul")); + ul.innerText = s; + ul.id = `rewrite-${s}`; + ul.onclick = () => setState({ currentRewrite:s }); + ul.className = s > ret.length-1 ? "disabled" : s === currentRewrite ? "active" : ""; + if (s > 0 && s === currentRewrite) { + const { upat, diff } = ret[s]; + metadata.appendChild(codeBlock(upat[1], "python", { loc:upat[0], wrap:true })); + const diffCode = metadata.appendChild(document.createElement("pre")); + diffCode.innerHTML = ``+diff.map((line) => { + const color = line.startsWith("+") ? "#3aa56d" : line.startsWith("-") ? "#d14b4b" : "#f0f0f5"; + return `${line}`; + }).join("
")+`
`; + diffCode.className = "wrap"; + } + } + } +} + +// **** collapse/expand + +let isCollapsed = false; +document.querySelector(".collapse-btn").addEventListener("click", (e) => { + isCollapsed = !isCollapsed; + document.querySelector(".main-container").classList.toggle("collapsed", isCollapsed); + e.currentTarget.blur(); + e.currentTarget.style.transform = isCollapsed ? "rotate(180deg)" : "rotate(0deg)"; +}); + +// **** resizer + +function appendResizer(element, { minWidth, maxWidth }, left=false) { + const handle = Object.assign(document.createElement("div"), { className: "resize-handle", style: left ? "right: 0" : "left: 0; margin-top: 0" }); + element.appendChild(handle); + const resize = (e) => { + const change = e.clientX - element.dataset.startX; + let newWidth = ((Number(element.dataset.startWidth)+(left ? change : -change))/Number(element.dataset.containerWidth))*100; + element.style.width = `${Math.max(minWidth, Math.min(maxWidth, newWidth))}%`; + }; + handle.addEventListener("mousedown", (e) => { + e.preventDefault(); + element.dataset.startX = e.clientX; + element.dataset.containerWidth = rect(".main-container").width; + element.dataset.startWidth = element.getBoundingClientRect().width; + document.documentElement.addEventListener("mousemove", resize, false); + document.documentElement.addEventListener("mouseup", () => { + document.documentElement.removeEventListener("mousemove", resize, false); + element.style.userSelect = "initial"; + }, { once: true }); + }); +} +appendResizer(document.querySelector(".kernel-list-parent"), { minWidth: 15, maxWidth: 50 }, left=true); +appendResizer(document.querySelector(".metadata-parent"), { minWidth: 20, maxWidth: 50 }); + +// **** keyboard shortcuts + +document.addEventListener("keydown", async function(event) { + const { currentKernel, currentUOp, currentRewrite, expandKernel } = state; + // up and down change the UOp or kernel from the list + if (event.key == "ArrowUp") { + event.preventDefault(); + if (expandKernel) { + return setState({ currentRewrite:0, currentUOp:Math.max(0, currentUOp-1) }); + } + return setState({ currentUOp:0, currentRewrite:0, currentKernel:Math.max(0, currentKernel-1) }); + } + if (event.key == "ArrowDown") { + event.preventDefault(); + if (expandKernel) { + const totalUOps = kernels[currentKernel][1].length-1; + return setState({ currentRewrite:0, currentUOp:Math.min(totalUOps, currentUOp+1) }); + } + return setState({ currentUOp:0, currentRewrite:0, currentKernel:Math.min(kernels.length-1, currentKernel+1) }); + } + // enter toggles focus on a single rewrite stage + if (event.key == "Enter") { + event.preventDefault() + if (state.currentKernel === -1) { + return setState({ currentKernel:0, expandKernel:true }); + } + return setState({ currentUOp:0, currentRewrite:0, expandKernel:!expandKernel }); + } + // left and right go through rewrites in a single UOp + if (event.key == "ArrowLeft") { + event.preventDefault() + return setState({ currentRewrite:Math.max(0, currentRewrite-1) }); + } + if (event.key == "ArrowRight") { + event.preventDefault() + const totalRewrites = ret.length-1; + return setState({ currentRewrite:Math.min(totalRewrites, currentRewrite+1) }); + } + // space recenters the graph + if (event.key == " ") { + event.preventDefault() + document.getElementById("zoom-to-fit-btn").click(); + } +}); + +main() diff --git a/tinygrad_repo/tinygrad/viz/js/worker.js b/tinygrad_repo/tinygrad/viz/js/worker.js new file mode 100644 index 0000000000..973a484616 --- /dev/null +++ b/tinygrad_repo/tinygrad/viz/js/worker.js @@ -0,0 +1,28 @@ +const NODE_PADDING = 10; +const LINE_HEIGHT = 14; +const canvas = new OffscreenCanvas(0, 0); +const ctx = canvas.getContext("2d"); +ctx.font = `${LINE_HEIGHT}px sans-serif`; + +onmessage = (e) => { + const { graph, additions } = e.data; + const g = new dagre.graphlib.Graph({ compound: true }); + g.setGraph({ rankdir: "LR" }).setDefaultEdgeLabel(function() { return {}; }); + if (additions.length !== 0) g.setNode("addition", {label:"", style:"fill: rgba(26, 27, 38, 0.5); stroke: none;", padding:0}); + for (const [k, {label, src, color}] of Object.entries(graph)) { + // adjust node dims by label size + add padding + let [width, height] = [0, 0]; + for (line of label.split("\n")) { + width = Math.max(width, ctx.measureText(line).width); + height += LINE_HEIGHT; + } + g.setNode(k, {label, color, width:width+NODE_PADDING*2, height:height+NODE_PADDING*2, padding:NODE_PADDING}); + const edgeCounts = {} + for (const s of src) edgeCounts[s] = (edgeCounts[s] || 0)+1; + for (const s of src) g.setEdge(s, k, { label: edgeCounts[s] > 1 ? edgeCounts[s] : null }); + if (additions.includes(parseInt(k))) g.setParent(k, "addition"); + } + dagre.layout(g); + postMessage(dagre.graphlib.json.write(g)); + self.close(); +} diff --git a/tinygrad_repo/tinygrad/viz/serve.py b/tinygrad_repo/tinygrad/viz/serve.py index 5051a88490..bcf26b9c64 100755 --- a/tinygrad_repo/tinygrad/viz/serve.py +++ b/tinygrad_repo/tinygrad/viz/serve.py @@ -1,109 +1,100 @@ #!/usr/bin/env python3 -import multiprocessing, pickle, functools, difflib, os, threading, json, time, sys, webbrowser, socket, argparse, decimal -from http.server import HTTPServer, BaseHTTPRequestHandler +import multiprocessing, pickle, functools, difflib, os, threading, json, time, sys, webbrowser, socket, argparse, decimal, socketserver +from http.server import BaseHTTPRequestHandler from urllib.parse import parse_qs, urlparse -from dataclasses import asdict, dataclass -from typing import Any, Callable, Optional -from tinygrad.helpers import colored, getenv, to_function_name, tqdm, unwrap, word_wrap -from tinygrad.ops import TrackedGraphRewrite, UOp, Ops, lines, GroupOp +from typing import Any, TypedDict, Generator +from tinygrad.helpers import colored, getenv, tqdm, unwrap, word_wrap, TRACEMETA +from tinygrad.uop.ops import TrackedGraphRewrite, UOp, Ops, lines, GroupOp, srender, sint from tinygrad.codegen.kernel import Kernel from tinygrad.device import ProfileEvent, ProfileDeviceEvent, ProfileRangeEvent, ProfileGraphEvent +from tinygrad.dtype import dtypes -uops_colors = {Ops.LOAD: "#ffc0c0", Ops.PRELOAD: "#ffc0c0", Ops.STORE: "#87CEEB", Ops.CONST: "#e0e0e0", Ops.VCONST: "#e0e0e0", +uops_colors = {Ops.LOAD: "#ffc0c0", Ops.STORE: "#87CEEB", Ops.CONST: "#e0e0e0", Ops.VCONST: "#e0e0e0", Ops.REDUCE: "#FF5B5B", Ops.DEFINE_GLOBAL: "#ffe0b0", Ops.DEFINE_LOCAL: "#ffe0d0", Ops.DEFINE_ACC: "#f0ffe0", Ops.REDUCE_AXIS: "#FF6B6B", - Ops.RANGE: "#c8a0e0", Ops.ASSIGN: "#e0ffc0", Ops.BARRIER: "#ff8080", Ops.IF: "#c8b0c0", Ops.SPECIAL: "#c0c0ff", - Ops.INDEX: "#e8ffa0", Ops.WMMA: "#efefc0", Ops.VIEW: "#C8F9D4", - **{x:"#D8F9E4" for x in GroupOp.Movement}, **{x:"#ffffc0" for x in GroupOp.ALU}, Ops.THREEFRY:"#ffff80", - Ops.BLOCK: "#C4A484", Ops.BLOCKEND: "#C4A4A4", Ops.BUFFER: "#B0BDFF", Ops.COPY: "#a040a0"} - -# ** API spec - -@dataclass -class GraphRewriteMetadata: - """Overview of a tracked rewrite to viz the sidebar""" - loc: tuple[str, int] - """File_path, Lineno""" - code_line: str - """The Python line calling graph_rewrite""" - kernel_name: str - """The kernel calling graph_rewrite""" - upats: list[tuple[tuple[str, int], str, float]] - """List of all the applied UPats""" - -@dataclass -class GraphRewriteDetails(GraphRewriteMetadata): - """Full details about a single call to graph_rewrite""" - graphs: list[UOp] - """Sink at every step of graph_rewrite""" - diffs: list[list[str]] - """.diff style before and after of the rewritten UOp child""" - changed_nodes: list[list[int]] - """Nodes that changed at every step of graph_rewrite""" - kernel_code: Optional[str] - """The program after all rewrites""" - -# ** API functions - -# NOTE: if any extra rendering in VIZ fails, we don't crash -def pcall(fxn:Callable[..., str], *args, **kwargs) -> str: - try: return fxn(*args, **kwargs) - except Exception as e: return f"ERROR: {e}" - -def get_metadata(keys:list[Any], contexts:list[list[TrackedGraphRewrite]]) -> list[list[tuple[Any, TrackedGraphRewrite, GraphRewriteMetadata]]]: - kernels: dict[str, list[tuple[Any, TrackedGraphRewrite, GraphRewriteMetadata]]] = {} - for k,ctxs in tqdm(zip(keys, contexts), desc="preparing kernels"): - name = to_function_name(k.name) if isinstance(k, Kernel) else str(k) - for ctx in ctxs: - if pickle.loads(ctx.sink).op is Ops.CONST: continue - upats = [(upat.location, upat.printable(), tm) for _,_,upat,tm in ctx.matches if upat is not None] - kernels.setdefault(name, []).append((k, ctx, GraphRewriteMetadata(ctx.loc, lines(ctx.loc[0])[ctx.loc[1]-1].strip(), name, upats))) - return list(kernels.values()) - -def uop_to_json(x:UOp) -> dict[int, tuple[str, str, list[int], str, str]]: + Ops.RANGE: "#c8a0e0", Ops.ASSIGN: "#909090", Ops.BARRIER: "#ff8080", Ops.IF: "#c8b0c0", Ops.SPECIAL: "#c0c0ff", + Ops.INDEX: "#e8ffa0", Ops.WMMA: "#efefc0", Ops.VIEW: "#C8F9D4", Ops.MULTI: "#f6ccff", Ops.KERNEL: "#3e7f55", Ops.IGNORE: "#00C000", + **{x:"#D8F9E4" for x in GroupOp.Movement}, **{x:"#ffffc0" for x in GroupOp.ALU}, Ops.THREEFRY:"#ffff80", Ops.BUFFER_VIEW: "#E5EAFF", + Ops.BLOCK: "#C4A484", Ops.BLOCKEND: "#C4A4A4", Ops.BUFFER: "#B0BDFF", Ops.COPY: "#a040a0", Ops.FUSE: "#FFa500", + Ops.ALLREDUCE: "#ff40a0"} + +# VIZ API + +# ** Metadata for a track_rewrites scope + +class GraphRewriteMetadata(TypedDict): + loc: tuple[str, int] # [path, lineno] calling graph_rewrite + match_count: int # total match count in this context + code_line: str # source code calling graph_rewrite + kernel_code: str|None # optionally render the final kernel code + name: str|None # optional name of the rewrite + depth: int # depth if it's a subrewrite + +@functools.cache +def render_program(k:Kernel): + try: return k.opts.render(k.uops) + except Exception as e: return f"ISSUE RENDERING KERNEL: {e}\nast = {k.ast}\nopts = {k.applied_opts}" + +def to_metadata(k:Any, v:TrackedGraphRewrite) -> GraphRewriteMetadata: + return {"loc":v.loc, "match_count":len(v.matches), "name":v.name, "depth":v.depth, "code_line":lines(v.loc[0])[v.loc[1]-1].strip(), + "kernel_code":render_program(k) if isinstance(k, Kernel) else None} + +def get_metadata(keys:list[Any], contexts:list[list[TrackedGraphRewrite]]) -> list[tuple[str, list[GraphRewriteMetadata]]]: + return [(k.name if isinstance(k, Kernel) else str(k), [to_metadata(k, v) for v in vals]) for k,vals in zip(keys, contexts)] + +# ** Complete rewrite details for a graph_rewrite call + +class GraphRewriteDetails(TypedDict): + graph: dict # JSON serialized UOp for this rewrite step + uop: str # strigified UOp for this rewrite step + diff: list[str]|None # diff of the single UOp that changed + changed_nodes: list[int]|None # the changed UOp id + all its parents ids + upat: tuple[tuple[str, int], str]|None # [loc, source_code] of the matched UPat + +def shape_to_str(s:tuple[sint, ...]): return "(" + ','.join(srender(x) for x in s) + ")" +def mask_to_str(s:tuple[tuple[sint, sint], ...]): return "(" + ','.join(shape_to_str(x) for x in s) + ")" + +def uop_to_json(x:UOp) -> dict[int, dict]: assert isinstance(x, UOp) - graph: dict[int, tuple[str, str, list[int], str, str]] = {} - excluded = set() - for u in x.toposort: - if u.op in {Ops.CONST, Ops.DEVICE}: - excluded.add(u) - continue - argst = ("\n".join([f"{v.shape} / {v.strides}"+(f" / {v.offset}" if v.offset else "") for v in u.arg.views])) if u.op is Ops.VIEW else str(u.arg) - label = f"{str(u.op).split('.')[1]}{(' '+word_wrap(argst.replace(':', ''))) if u.arg is not None else ''}\n{str(u.dtype)}" + graph: dict[int, dict] = {} + excluded: set[UOp] = set() + for u in (toposort:=x.toposort()): + # always exclude DEVICE/CONST/UNIQUE + if u.op in {Ops.DEVICE, Ops.CONST, Ops.UNIQUE}: excluded.add(u) + # only exclude CONST VIEW source if it has no other children in the graph + if u.op is Ops.CONST and len(u.src) != 0 and all(cr.op is Ops.CONST for c in u.src[0].children if (cr:=c()) is not None and cr in toposort): + excluded.update(u.src) + for u in toposort: + if u in excluded: continue + argst = str(u.arg) + if u.op is Ops.VIEW: + argst = ("\n".join([f"{shape_to_str(v.shape)} / {shape_to_str(v.strides)}"+("" if v.offset == 0 else f" / {srender(v.offset)}")+ + (f"\nMASK {mask_to_str(v.mask)}" if v.mask is not None else "") for v in unwrap(u.st).views])) + label = f"{str(u.op).split('.')[1]}{(chr(10)+word_wrap(argst.replace(':', ''))) if u.arg is not None else ''}" + if u.dtype != dtypes.void: label += f"\n{u.dtype}" for idx,x in enumerate(u.src): - if x.op is Ops.CONST: label += f"\nCONST{idx} {x.arg:g}" - if x.op is Ops.DEVICE: label += f"\nDEVICE{idx} {x.arg}" - graph[id(u)] = (label, str(u.dtype), [id(x) for x in u.src if x not in excluded], str(u.arg), uops_colors.get(u.op, "#ffffff")) + if x in excluded: + if x.op is Ops.CONST and dtypes.is_float(u.dtype): label += f"\nCONST{idx} {x.arg:g}" + else: label += f"\n{x.op.name}{idx} {x.arg}" + try: + if u.op not in {Ops.VIEW, Ops.BUFFER, Ops.KERNEL, Ops.ASSIGN, Ops.COPY, Ops.SINK, *GroupOp.Buffer} and u.st is not None: + label += f"\n{shape_to_str(u.shape)}" + except Exception: + label += "\n" + # NOTE: kernel already has metadata in arg + if TRACEMETA >= 2 and u.metadata is not None and u.op is not Ops.KERNEL: label += "\n"+repr(u.metadata) + graph[id(u)] = {"label":label, "src":[id(x) for x in u.src if x not in excluded], "color":uops_colors.get(u.op, "#ffffff")} return graph -def _replace_uop(base:UOp, replaces:dict[UOp, UOp]) -> UOp: - if (found:=replaces.get(base)) is not None: return found - ret = base.replace(src=tuple(_replace_uop(x, replaces) for x in base.src)) - if (final := replaces.get(ret)) is not None: - return final - replaces[base] = ret - return ret -@functools.lru_cache(None) -def _prg(k:Kernel): return k.to_program().src -def get_details(k:Any, ctx:TrackedGraphRewrite, metadata:GraphRewriteMetadata) -> GraphRewriteDetails: - g = GraphRewriteDetails(**asdict(metadata), graphs=[pickle.loads(ctx.sink)], diffs=[], changed_nodes=[], - kernel_code=pcall(_prg, k) if isinstance(k, Kernel) else None) + +def get_details(k:Any, ctx:TrackedGraphRewrite) -> Generator[GraphRewriteDetails, None, None]: + yield {"graph":uop_to_json(next_sink:=ctx.sink), "uop":str(ctx.sink), "changed_nodes":None, "diff":None, "upat":None} replaces: dict[UOp, UOp] = {} - sink = g.graphs[0] - for i,(u0_b,u1_b,upat,_) in enumerate(ctx.matches): - u0 = pickle.loads(u0_b) - # if the match didn't result in a rewrite we move forward - if u1_b is None: - replaces[u0] = u0 - continue - replaces[u0] = u1 = pickle.loads(u1_b) - # first, rewrite this UOp with the current rewrite + all the matches in replaces - new_sink = _replace_uop(sink, {**replaces}) - # sanity check - if new_sink is sink: raise AssertionError(f"rewritten sink wasn't rewritten! {i} {unwrap(upat).location}") - # update ret data - g.changed_nodes.append([id(x) for x in u1.toposort if x.op is not Ops.CONST]) - g.diffs.append(list(difflib.unified_diff(pcall(str, u0).splitlines(), pcall(str, u1).splitlines()))) - g.graphs.append(sink:=new_sink) - return g + for u0,u1,upat in tqdm(ctx.matches): + replaces[u0] = u1 + try: new_sink = next_sink.substitute(replaces) + except RecursionError as e: new_sink = UOp(Ops.NOOP, arg=str(e)) + yield {"graph":(sink_json:=uop_to_json(new_sink)), "uop":str(new_sink), "changed_nodes":[id(x) for x in u1.toposort() if id(x) in sink_json], + "diff":list(difflib.unified_diff(str(u0).splitlines(), str(u1).splitlines())), "upat":(upat.location, upat.printable())} + if not ctx.bottom_up: next_sink = new_sink # Profiler API devices:dict[str, tuple[decimal.Decimal, decimal.Decimal, int]] = {} @@ -140,23 +131,31 @@ class Handler(BaseHTTPRequestHandler): def do_GET(self): ret, status_code, content_type = b"", 200, "text/html" - if (url:=urlparse(self.path)).path == "/": - with open(os.path.join(os.path.dirname(__file__), "index.html"), "rb") as f: ret = f.read() - elif (url:=urlparse(self.path)).path == "/profiler": - with open(os.path.join(os.path.dirname(__file__), "perfetto.html"), "rb") as f: ret = f.read() - elif self.path.startswith("/assets/") and '/..' not in self.path: + if (fn:={"/":"index", "/profiler":"perfetto"}.get((url:=urlparse(self.path)).path)): + with open(os.path.join(os.path.dirname(__file__), f"{fn}.html"), "rb") as f: ret = f.read() + elif self.path.startswith(("/assets/", "/js/")) and '/..' not in self.path: try: with open(os.path.join(os.path.dirname(__file__), self.path.strip('/')), "rb") as f: ret = f.read() if url.path.endswith(".js"): content_type = "application/javascript" if url.path.endswith(".css"): content_type = "text/css" except FileNotFoundError: status_code = 404 elif url.path == "/kernels": - query = parse_qs(url.query) - if (qkernel:=query.get("kernel")) is not None: - g = get_details(*kernels[int(qkernel[0])][int(query["idx"][0])]) - jret: Any = {**asdict(g), "graphs": [uop_to_json(x) for x in g.graphs], "uops": [pcall(str,x) for x in g.graphs]} - else: jret = [list(map(lambda x:asdict(x[2]), v)) for v in kernels] - ret, content_type = json.dumps(jret).encode(), "application/json" + if "kernel" in (query:=parse_qs(url.query)): + kidx, ridx = int(query["kernel"][0]), int(query["idx"][0]) + try: + # stream details + self.send_response(200) + self.send_header("Content-Type", "text/event-stream") + self.send_header("Cache-Control", "no-cache") + self.end_headers() + for r in get_details(contexts[0][kidx], contexts[1][kidx][ridx]): + self.wfile.write(f"data: {json.dumps(r)}\n\n".encode("utf-8")) + self.wfile.flush() + self.wfile.write("data: END\n\n".encode("utf-8")) + return self.wfile.flush() + # pass if client closed connection + except (BrokenPipeError, ConnectionResetError): return + ret, content_type = json.dumps(kernels).encode(), "application/json" elif url.path == "/get_profile" and perfetto_profile is not None: ret, content_type = perfetto_profile, "application/json" else: status_code = 404 @@ -181,6 +180,9 @@ def load_pickle(path:str): if path is None or not os.path.exists(path): return None with open(path, "rb") as f: return pickle.load(f) +# NOTE: using HTTPServer forces a potentially slow socket.getfqdn +class TCPServerWithReuse(socketserver.TCPServer): allow_reuse_address = True + if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument('--kernels', type=str, help='Path to kernels', default=None) @@ -197,15 +199,12 @@ if __name__ == "__main__": contexts, profile = load_pickle(args.kernels), load_pickle(args.profile) + # NOTE: this context is a tuple of list[keys] and list[values] kernels = get_metadata(*contexts) if contexts is not None else [] - if getenv("FUZZ_VIZ"): - ret = [get_details(*args) for v in tqdm(kernels) for args in v] - print(f"fuzzed {len(ret)} rewrite details") - perfetto_profile = to_perfetto(profile) if profile is not None else None - server = HTTPServer(('', PORT), Handler) + server = TCPServerWithReuse(('', PORT), Handler) reloader_thread = threading.Thread(target=reloader) reloader_thread.start() print(f"*** started viz on {HOST}:{PORT}") diff --git a/tools/adb_shell.sh b/tools/adb_shell.sh deleted file mode 100755 index f757f7d4d0..0000000000 --- a/tools/adb_shell.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env expect -spawn adb shell -expect "#" -send "cd data/openpilot\r" -send "export TERM=xterm-256color\r" -send "su comma\r" -send "clear\r" -interact diff --git a/tools/auto_source.py b/tools/auto_source.py new file mode 100755 index 0000000000..401929a9ad --- /dev/null +++ b/tools/auto_source.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python3 +import sys +from openpilot.tools.lib.logreader import LogReader + + +def main(): + if len(sys.argv) != 2: + print("Usage: python auto_source.py ") + sys.exit(1) + + log_path = sys.argv[1] + lr = LogReader(log_path, sort_by_time=True) + print("\n".join(lr.logreader_identifiers)) + + +if __name__ == "__main__": + main() diff --git a/tools/cabana/README.md b/tools/cabana/README.md index 0b7c5bf3ee..7933098e34 100644 --- a/tools/cabana/README.md +++ b/tools/cabana/README.md @@ -12,6 +12,8 @@ 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 + --auto Auto load the route from the best available source (no video): + internal, openpilotci, comma_api, car_segments, testing_closet --qcam load qcamera --ecam load wide road camera --msgq read can messages from msgq diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index 1cacaba4a2..c8e6093b86 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -29,7 +29,7 @@ cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/socketcans 'streams/routes.cc', 'dbc/dbc.cc', 'dbc/dbcfile.cc', 'dbc/dbcmanager.cc', 'utils/export.cc', 'utils/util.cc', 'chart/chartswidget.cc', 'chart/chart.cc', 'chart/signalselector.cc', 'chart/tiplabel.cc', 'chart/sparkline.cc', - 'commands.cc', 'messageswidget.cc', 'streamselector.cc', 'settings.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc', 'tools/findsignal.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) + 'commands.cc', 'messageswidget.cc', 'streamselector.cc', 'settings.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc', 'tools/findsignal.cc', 'tools/routeinfo.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'): diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc index d140a323e1..97f178b1f3 100644 --- a/tools/cabana/cabana.cc +++ b/tools/cabana/cabana.cc @@ -23,6 +23,7 @@ int main(int argc, char *argv[]) { 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({"auto", "Auto load the route from the best available source (no video): internal, openpilotci, comma_api, car_segments, testing_closet"}); cmd_parser.addOption({"qcam", "load qcamera"}); cmd_parser.addOption({"ecam", "load wide road camera"}); cmd_parser.addOption({"dcam", "load driver camera"}); @@ -69,7 +70,8 @@ int main(int argc, char *argv[]) { } if (!route.isEmpty()) { auto replay_stream = std::make_unique(&app); - if (!replay_stream->loadRoute(route, cmd_parser.value("data_dir"), replay_flags)) { + bool auto_source = cmd_parser.isSet("auto"); + if (!replay_stream->loadRoute(route, cmd_parser.value("data_dir"), replay_flags, auto_source)) { return 0; } stream = replay_stream.release(); diff --git a/tools/cabana/dbc/dbc.cc b/tools/cabana/dbc/dbc.cc index ba979f258c..e9c869fce7 100644 --- a/tools/cabana/dbc/dbc.cc +++ b/tools/cabana/dbc/dbc.cc @@ -180,25 +180,36 @@ bool cabana::Signal::operator==(const cabana::Signal &other) const { // helper functions double get_raw_value(const uint8_t *data, size_t data_size, const cabana::Signal &sig) { - int64_t val = 0; + const int msb_byte = sig.msb / 8; + if (msb_byte >= (int)data_size) return 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; + const int lsb_byte = sig.lsb / 8; + uint64_t val = 0; - 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; + // Fast path: signal fits in a single byte + if (msb_byte == lsb_byte) { + val = (data[msb_byte] >> (sig.lsb & 7)) & ((1ULL << sig.size) - 1); + } else { + // Multi-byte case: signal spans across multiple bytes + int bits = sig.size; + int i = msb_byte; + const int step = sig.is_little_endian ? -1 : 1; + while (i >= 0 && i < (int)data_size && bits > 0) { + const int msb = (i == msb_byte) ? sig.msb & 7 : 7; + const int lsb = (i == lsb_byte) ? sig.lsb & 7 : 0; + const int nbits = msb - lsb + 1; + val = (val << nbits) | ((data[i] >> lsb) & ((1ULL << nbits) - 1)); + bits -= nbits; + i += step; + } } - if (sig.is_signed) { - val -= ((val >> (sig.size - 1)) & 0x1) ? (1ULL << sig.size) : 0; + + // Sign extension (if needed) + if (sig.is_signed && (val & (1ULL << (sig.size - 1)))) { + val |= ~((1ULL << sig.size) - 1); } - return val * sig.factor + sig.offset; + + return static_cast(val) * sig.factor + sig.offset; } void updateMsbLsb(cabana::Signal &s) { diff --git a/tools/cabana/streams/replaystream.cc b/tools/cabana/streams/replaystream.cc index ebe478ded7..b8cf1be299 100644 --- a/tools/cabana/streams/replaystream.cc +++ b/tools/cabana/streams/replaystream.cc @@ -7,6 +7,7 @@ #include #include "common/timing.h" +#include "common/util.h" #include "tools/cabana/streams/routes.h" ReplayStream::ReplayStream(QObject *parent) : AbstractStream(parent) { @@ -45,9 +46,9 @@ void ReplayStream::mergeSegments() { } } -bool ReplayStream::loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags) { +bool ReplayStream::loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags, bool auto_source) { replay.reset(new Replay(route.toStdString(), {"can", "roadEncodeIdx", "driverEncodeIdx", "wideRoadEncodeIdx", "carParams"}, - {}, nullptr, replay_flags, data_dir.toStdString())); + {}, nullptr, replay_flags, data_dir.toStdString(), auto_source)); replay->setSegmentCacheLimit(settings.max_cached_minutes); replay->installEventFilter([this](const Event *event) { return eventFilter(event); }); diff --git a/tools/cabana/streams/replaystream.h b/tools/cabana/streams/replaystream.h index df1f2526a5..d429ed1f95 100644 --- a/tools/cabana/streams/replaystream.h +++ b/tools/cabana/streams/replaystream.h @@ -18,7 +18,7 @@ class ReplayStream : public AbstractStream { public: ReplayStream(QObject *parent); void start() override { replay->start(); } - bool loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags = REPLAY_FLAG_NONE); + bool loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags = REPLAY_FLAG_NONE, bool auto_source = false); bool eventFilter(const Event *event); void seekTo(double ts) override { replay->seekTo(std::max(double(0), ts), false); } bool liveStreaming() const override { return false; } diff --git a/tools/cabana/tools/routeinfo.cc b/tools/cabana/tools/routeinfo.cc new file mode 100644 index 0000000000..77a0e065cd --- /dev/null +++ b/tools/cabana/tools/routeinfo.cc @@ -0,0 +1,40 @@ +#include "tools/cabana/tools/routeinfo.h" +#include +#include +#include +#include +#include "tools/cabana/streams/replaystream.h" + +RouteInfoDlg::RouteInfoDlg(QWidget *parent) : QDialog(parent) { + auto *replay = qobject_cast(can)->getReplay(); + setWindowTitle(tr("Route: %1").arg(QString::fromStdString(replay->route().name()))); + + auto *table = new QTableWidget(replay->route().segments().size(), 7, this); + table->setToolTip(tr("Click on a row to seek to the corresponding segment.")); + table->setEditTriggers(QAbstractItemView::NoEditTriggers); + table->setSelectionBehavior(QAbstractItemView::SelectRows); + table->setSelectionMode(QAbstractItemView::SingleSelection); + table->setHorizontalHeaderLabels({"", "rlog", "fcam", "ecam", "dcam", "qlog", "qcam"}); + table->horizontalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); + table->verticalHeader()->setVisible(false); + table->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + + int row = 0; + for (const auto &[seg_num, seg] : replay->route().segments()) { + table->setItem(row, 0, new QTableWidgetItem(QString::number(seg_num))); + table->setItem(row, 1, new QTableWidgetItem(seg.rlog.empty() ? "--" : "Yes")); + table->setItem(row, 2, new QTableWidgetItem(seg.road_cam.empty() ? "--" : "Yes")); + table->setItem(row, 3, new QTableWidgetItem(seg.wide_road_cam.empty() ? "--" : "Yes")); + table->setItem(row, 4, new QTableWidgetItem(seg.driver_cam.empty() ? "--" : "Yes")); + table->setItem(row, 5, new QTableWidgetItem(seg.qlog.empty() ? "--" : "Yes")); + table->setItem(row, 6, new QTableWidgetItem(seg.qcamera.empty() ? "--" : "Yes")); + ++row; + } + table->setMinimumWidth(table->horizontalHeader()->length() + table->verticalScrollBar()->sizeHint().width()); + table->setMinimumHeight(table->rowHeight(0) * std::min(table->rowCount(), 13) + table->horizontalHeader()->height() + table->frameWidth() * 2); + + connect(table, &QTableWidget::itemClicked, [](QTableWidgetItem *item) { can->seekTo(item->row() * 60.0); }); + + QVBoxLayout *layout = new QVBoxLayout(this); + layout->addWidget(table); +} diff --git a/tools/cabana/tools/routeinfo.h b/tools/cabana/tools/routeinfo.h new file mode 100644 index 0000000000..36f32b4bf4 --- /dev/null +++ b/tools/cabana/tools/routeinfo.h @@ -0,0 +1,8 @@ +#pragma once +#include + +class RouteInfoDlg : public QDialog { + Q_OBJECT +public: + RouteInfoDlg(QWidget *parent = nullptr); +}; diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index e792f80a41..3d715b0319 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -11,6 +11,8 @@ #include #include +#include "tools/cabana/tools/routeinfo.h" + const int MIN_VIDEO_HEIGHT = 100; const int THUMBNAIL_MARGIN = 3; @@ -100,9 +102,12 @@ void VideoWidget::createPlaybackController() { if (!can->liveStreaming()) { toolbar->addAction(utils::icon("repeat"), tr("Loop playback"), this, &VideoWidget::loopPlaybackClicked); + createSpeedDropdown(toolbar); + toolbar->addSeparator(); + toolbar->addAction(utils::icon("info-circle"), tr("View route details"), this, &VideoWidget::showRouteInfo); + } else { + createSpeedDropdown(toolbar); } - - createSpeedDropdown(toolbar); } void VideoWidget::createSpeedDropdown(QToolBar *toolbar) { @@ -230,6 +235,12 @@ void VideoWidget::showThumbnail(double seconds) { slider->update(); } +void VideoWidget::showRouteInfo() { + RouteInfoDlg *route_info = new RouteInfoDlg(this); + route_info->setAttribute(Qt::WA_DeleteOnClose); + route_info->show(); +} + bool VideoWidget::eventFilter(QObject *obj, QEvent *event) { if (event->type() == QEvent::MouseMove) { auto [min_sec, max_sec] = can->timeRange().value_or(std::make_pair(can->minSeconds(), can->maxSeconds())); diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index 1d87a5cfa0..6f756448c0 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -71,6 +71,7 @@ protected: void createSpeedDropdown(QToolBar *toolbar); void loopPlaybackClicked(); void vipcAvailableStreamsUpdated(std::set streams); + void showRouteInfo(); StreamCameraView *cam_widget; QAction *time_display_action = nullptr; diff --git a/tools/clip/run.py b/tools/clip/run.py new file mode 100755 index 0000000000..a84290f9c4 --- /dev/null +++ b/tools/clip/run.py @@ -0,0 +1,320 @@ +#!/usr/bin/env python3 + +import atexit +import logging +import os +import platform +import shutil +import sys +import time +from argparse import ArgumentParser, ArgumentTypeError +from collections.abc import Sequence +from pathlib import Path +from random import randint +from subprocess import Popen, PIPE +from typing import Literal + +from cereal.messaging import SubMaster +from openpilot.common.basedir import BASEDIR +from openpilot.common.params import Params, UnknownKeyName +from openpilot.common.prefix import OpenpilotPrefix +from openpilot.tools.lib.route import Route +from openpilot.tools.lib.logreader import LogReader + +DEFAULT_OUTPUT = 'output.mp4' +DEMO_START = 90 +DEMO_END = 105 +DEMO_ROUTE = 'a2a0ccea32023010/2023-07-27--13-01-19' +FRAMERATE = 20 +PIXEL_DEPTH = '24' +RESOLUTION = '2160x1080' +SECONDS_TO_WARM = 2 +PROC_WAIT_SECONDS = 30 + +OPENPILOT_FONT = str(Path(BASEDIR, 'selfdrive/assets/fonts/Inter-Regular.ttf').resolve()) +REPLAY = str(Path(BASEDIR, 'tools/replay/replay').resolve()) +UI = str(Path(BASEDIR, 'selfdrive/ui/ui').resolve()) + +logger = logging.getLogger('clip.py') + + +def check_for_failure(proc: Popen): + exit_code = proc.poll() + if exit_code is not None and exit_code != 0: + cmd = str(proc.args) + if isinstance(proc.args, str): + cmd = proc.args + elif isinstance(proc.args, Sequence): + cmd = str(proc.args[0]) + msg = f'{cmd} failed, exit code {exit_code}' + logger.error(msg) + stdout, stderr = proc.communicate() + if stdout: + logger.error(stdout.decode()) + if stderr: + logger.error(stderr.decode()) + raise ChildProcessError(msg) + + +def escape_ffmpeg_text(value: str): + special_chars = {',': '\\,', ':': '\\:', '=': '\\=', '[': '\\[', ']': '\\]'} + value = value.replace('\\', '\\\\\\\\\\\\\\\\') + for char, escaped in special_chars.items(): + value = value.replace(char, escaped) + return value + + +def get_logreader(route: Route): + return LogReader(route.qlog_paths()[0] if len(route.qlog_paths()) else route.name.canonical_name) + + +def get_meta_text(lr: LogReader, route: Route): + init_data = lr.first('initData') + car_params = lr.first('carParams') + origin_parts = init_data.gitRemote.split('/') + origin = origin_parts[3] if len(origin_parts) > 3 else 'unknown' + return ', '.join([ + f"openpilot v{init_data.version}", + f"route: {route.name.canonical_name}", + f"car: {car_params.carFingerprint}", + f"origin: {origin}", + f"branch: {init_data.gitBranch}", + f"commit: {init_data.gitCommit[:7]}", + f"modified: {str(init_data.dirty).lower()}", + ]) + + +def parse_args(parser: ArgumentParser): + args = parser.parse_args() + if args.demo: + args.route = DEMO_ROUTE + if args.start is None or args.end is None: + args.start = DEMO_START + args.end = DEMO_END + elif args.route.count('/') == 1: + if args.start is None or args.end is None: + parser.error('must provide both start and end if timing is not in the route ID') + elif args.route.count('/') == 3: + if args.start is not None or args.end is not None: + parser.error('don\'t provide timing when including it in the route ID') + parts = args.route.split('/') + args.route = '/'.join(parts[:2]) + args.start = int(parts[2]) + args.end = int(parts[3]) + if args.end <= args.start: + parser.error(f'end ({args.end}) must be greater than start ({args.start})') + if args.start < SECONDS_TO_WARM: + parser.error(f'start must be greater than {SECONDS_TO_WARM}s to allow the UI time to warm up') + + try: + args.route = Route(args.route, data_dir=args.data_dir) + except Exception as e: + parser.error(f'failed to get route: {e}') + + # FIXME: length isn't exactly max segment seconds, simplify to replay exiting at end of data + length = round(args.route.max_seg_number * 60) + if args.start >= length: + parser.error(f'start ({args.start}s) cannot be after end of route ({length}s)') + if args.end > length: + parser.error(f'end ({args.end}s) cannot be after end of route ({length}s)') + + return args + + +def populate_car_params(lr: LogReader): + init_data = lr.first('initData') + assert init_data is not None + + params = Params() + entries = init_data.params.entries + for cp in entries: + key, value = cp.key, cp.value + try: + params.put(key, value) + except UnknownKeyName: + # forks of openpilot may have other Params keys configured. ignore these + logger.warning(f"unknown Params key '{key}', skipping") + logger.debug('persisted CarParams') + + +def start_proc(args: list[str], env: dict[str, str]): + return Popen(args, env=env, stdout=PIPE, stderr=PIPE) + + +def validate_env(parser: ArgumentParser): + if platform.system() not in ['Linux']: + parser.exit(1, f'clip.py: error: {platform.system()} is not a supported operating system\n') + for proc in ['Xvfb', 'ffmpeg']: + if shutil.which(proc) is None: + parser.exit(1, f'clip.py: error: missing {proc} command, is it installed?\n') + for proc in [REPLAY, UI]: + if shutil.which(proc) is None: + parser.exit(1, f'clip.py: error: missing {proc} command, did you build openpilot yet?\n') + + +def validate_output_file(output_file: str): + if not output_file.endswith('.mp4'): + raise ArgumentTypeError('output must be an mp4') + return output_file + + +def validate_route(route: str): + if route.count('/') not in (1, 3): + raise ArgumentTypeError(f'route must include or exclude timing, example: {DEMO_ROUTE}') + return route + + +def validate_title(title: str): + if len(title) > 80: + raise ArgumentTypeError('title must be no longer than 80 chars') + return title + + +def wait_for_frames(procs: list[Popen]): + sm = SubMaster(['uiDebug']) + no_frames_drawn = True + while no_frames_drawn: + sm.update() + no_frames_drawn = sm['uiDebug'].drawTimeMillis == 0. + for proc in procs: + check_for_failure(proc) + + +def clip( + data_dir: str | None, + quality: Literal['low', 'high'], + prefix: str, + route: Route, + out: str, + start: int, + end: int, + target_mb: int, + title: str | None, +): + logger.info(f'clipping route {route.name.canonical_name}, start={start} end={end} quality={quality} target_filesize={target_mb}MB') + lr = get_logreader(route) + + begin_at = max(start - SECONDS_TO_WARM, 0) + duration = end - start + bit_rate_kbps = int(round(target_mb * 8 * 1024 * 1024 / duration / 1000)) + + # TODO: evaluate creating fn that inspects /tmp/.X11-unix and creates unused display to avoid possibility of collision + display = f':{randint(99, 999)}' + + box_style = 'box=1:boxcolor=black@0.33:boxborderw=7' + meta_text = get_meta_text(lr, route) + overlays = [ + # metadata overlay + f"drawtext=text='{escape_ffmpeg_text(meta_text)}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=15:{box_style}:x=(w-text_w)/2:y=5.5:enable='between(t,1,5)'", + # route time overlay + f"drawtext=text='%{{eif\\:floor(({start}+t)/60)\\:d\\:2}}\\:%{{eif\\:mod({start}+t\\,60)\\:d\\:2}}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=24:{box_style}:x=w-text_w-38:y=38" + ] + if title: + overlays.append(f"drawtext=text='{escape_ffmpeg_text(title)}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=32:{box_style}:x=(w-text_w)/2:y=53") + + ffmpeg_cmd = [ + 'ffmpeg', '-y', + '-video_size', RESOLUTION, + '-framerate', str(FRAMERATE), + '-f', 'x11grab', + '-rtbufsize', '100M', + '-draw_mouse', '0', + '-i', display, + '-c:v', 'libx264', + '-maxrate', f'{bit_rate_kbps}k', + '-bufsize', f'{bit_rate_kbps*2}k', + '-crf', '23', + '-filter:v', ','.join(overlays), + '-preset', 'ultrafast', + '-tune', 'zerolatency', + '-pix_fmt', 'yuv420p', + '-movflags', '+faststart', + '-f', 'mp4', + '-t', str(duration), + out, + ] + + replay_cmd = [REPLAY, '--ecam', '-c', '1', '-s', str(begin_at), '--prefix', prefix] + if data_dir: + replay_cmd.extend(['--data_dir', data_dir]) + if quality == 'low': + replay_cmd.append('--qcam') + replay_cmd.append(route.name.canonical_name) + + ui_cmd = [UI, '-platform', 'xcb'] + xvfb_cmd = ['Xvfb', display, '-terminate', '-screen', '0', f'{RESOLUTION}x{PIXEL_DEPTH}'] + + with OpenpilotPrefix(prefix, shared_download_cache=True): + populate_car_params(lr) + + env = os.environ.copy() + env['DISPLAY'] = display + + xvfb_proc = start_proc(xvfb_cmd, env) + atexit.register(lambda: xvfb_proc.terminate()) + ui_proc = start_proc(ui_cmd, env) + atexit.register(lambda: ui_proc.terminate()) + replay_proc = start_proc(replay_cmd, env) + atexit.register(lambda: replay_proc.terminate()) + procs = [replay_proc, ui_proc, xvfb_proc] + + logger.info('waiting for replay to begin (loading segments, may take a while)...') + wait_for_frames(procs) + + logger.debug(f'letting UI warm up ({SECONDS_TO_WARM}s)...') + time.sleep(SECONDS_TO_WARM) + for proc in procs: + check_for_failure(proc) + + ffmpeg_proc = start_proc(ffmpeg_cmd, env) + procs.append(ffmpeg_proc) + atexit.register(lambda: ffmpeg_proc.terminate()) + + logger.info(f'recording in progress ({duration}s)...') + ffmpeg_proc.wait(duration + PROC_WAIT_SECONDS) + for proc in procs: + check_for_failure(proc) + logger.info(f'recording complete: {Path(out).resolve()}') + + +def main(): + p = ArgumentParser(prog='clip.py', description='clip your openpilot route.', epilog='comma.ai') + validate_env(p) + route_group = p.add_mutually_exclusive_group(required=True) + route_group.add_argument('route', nargs='?', type=validate_route, help=f'The route (e.g. {DEMO_ROUTE} or {DEMO_ROUTE}/{DEMO_START}/{DEMO_END})') + route_group.add_argument('--demo', help='use the demo route', action='store_true') + p.add_argument('-d', '--data-dir', help='local directory where route data is stored') + p.add_argument('-e', '--end', help='stop clipping at seconds', type=int) + p.add_argument('-f', '--file-size', help='target file size (Discord/GitHub support max 10MB, default is 9MB)', type=float, default=9.) + p.add_argument('-o', '--output', help='output clip to (.mp4)', type=validate_output_file, default=DEFAULT_OUTPUT) + p.add_argument('-p', '--prefix', help='openpilot prefix', default=f'clip_{randint(100, 99999)}') + p.add_argument('-q', '--quality', help='quality of camera (low = qcam, high = hevc)', choices=['low', 'high'], default='high') + p.add_argument('-s', '--start', help='start clipping at seconds', type=int) + p.add_argument('-t', '--title', help='overlay this title on the video (e.g. "Chill driving across the Golden Gate Bridge")', type=validate_title) + args = parse_args(p) + exit_code = 1 + try: + clip( + data_dir=args.data_dir, + quality=args.quality, + prefix=args.prefix, + route=args.route, + out=args.output, + start=args.start, + end=args.end, + target_mb=args.file_size, + title=args.title, + ) + exit_code = 0 + except KeyboardInterrupt as e: + logger.exception('interrupted by user', exc_info=e) + except Exception as e: + logger.exception('encountered error', exc_info=e) + finally: + atexit._run_exitfuncs() + sys.exit(exit_code) + + +if __name__ == '__main__': + logging.basicConfig(level=logging.INFO, format='%(asctime)s %(name)s %(levelname)s\t%(message)s') + main() diff --git a/tools/install_ubuntu_dependencies.sh b/tools/install_ubuntu_dependencies.sh index 03302364e9..f33569704a 100755 --- a/tools/install_ubuntu_dependencies.sh +++ b/tools/install_ubuntu_dependencies.sh @@ -63,7 +63,8 @@ function install_ubuntu_common_requirements() { libqt5svg5-dev \ libqt5serialbus5-dev \ libqt5x11extras5-dev \ - libqt5opengl5-dev + libqt5opengl5-dev \ + xvfb } # Install Ubuntu 24.04 LTS packages diff --git a/tools/joystick/joystick_control.py b/tools/joystick/joystick_control.py index 74d034d505..11d17e587e 100755 --- a/tools/joystick/joystick_control.py +++ b/tools/joystick/joystick_control.py @@ -28,7 +28,7 @@ class Keyboard: key = self.kb.getch().lower() self.cancel = False if key == 'r': - self.axes_values = {ax: 0. for ax in self.axes_values} + self.axes_values = dict.fromkeys(self.axes_values, 0.) elif key == 'c': self.cancel = True elif key in self.axes_map: @@ -65,7 +65,7 @@ class Joystick: try: joystick_event = get_gamepad()[0] except (OSError, UnpluggedError): - self.axes_values = {ax: 0. for ax in self.axes_values} + self.axes_values = dict.fromkeys(self.axes_values, 0.) return False event = (joystick_event.code, joystick_event.state) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index b775f18f70..673a5bc1d0 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -10,7 +10,7 @@ from openpilot.common.params import Params from openpilot.common.swaglog import cloudlog LongCtrlState = car.CarControl.Actuators.LongControlState -MAX_LAT_ACCEL = 2.5 +MAX_LAT_ACCEL = 3.0 def joystickd_thread(): diff --git a/tools/lib/github_utils.py b/tools/lib/github_utils.py index 4dc22b9524..46a0dcf3cb 100644 --- a/tools/lib/github_utils.py +++ b/tools/lib/github_utils.py @@ -87,8 +87,8 @@ class GithubUtils: def comment_on_pr(self, comment, pr_branch, commenter="", overwrite=False): pr_number = self.get_pr_number(pr_branch) data = f'{{"body": "{comment}"}}' + github_path = f'issues/{pr_number}/comments' if overwrite: - github_path = f'issues/{pr_number}/comments' r = self.api_call(github_path) comments = [x['id'] for x in r.json() if x['user']['login'] == commenter] if comments: @@ -96,7 +96,6 @@ class GithubUtils: self.api_call(github_path, data=data, method=HTTPMethod.PATCH) return - github_path=f'issues/{pr_number}/comments' self.api_call(github_path, data=data, method=HTTPMethod.POST) # upload files to github and comment them on the pr diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 9fe73825a8..34d3e5ea9f 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -300,11 +300,11 @@ class LogReader: def _run_on_segment(self, func, i): return func(self._get_lr(i)) - def run_across_segments(self, num_processes, func, desc=None): + def run_across_segments(self, num_processes, func, disable_tqdm=False, desc=None): with multiprocessing.Pool(num_processes) as pool: ret = [] num_segs = len(self.logreader_identifiers) - for p in tqdm.tqdm(pool.imap(partial(self._run_on_segment, func), range(num_segs)), total=num_segs, desc=desc): + for p in tqdm.tqdm(pool.imap(partial(self._run_on_segment, func), range(num_segs)), total=num_segs, disable=disable_tqdm, desc=desc): ret.extend(p) return ret diff --git a/tools/lib/route.py b/tools/lib/route.py index ddb8b0486e..0a4700f083 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -1,12 +1,13 @@ import os import re +import requests from functools import cache from urllib.parse import urlparse from collections import defaultdict from itertools import chain from openpilot.tools.lib.auth_config import get_token -from openpilot.tools.lib.api import CommaApi +from openpilot.tools.lib.api import APIError, CommaApi from openpilot.tools.lib.helpers import RE QLOG_FILENAMES = ['qlog', 'qlog.bz2', 'qlog.zst'] @@ -19,6 +20,7 @@ ECAMERA_FILENAMES = ['ecamera.hevc'] class Route: def __init__(self, name, data_dir=None): + self._metadata = None self._name = RouteName(name) self.files = None if data_dir is not None: @@ -27,6 +29,13 @@ class Route: self._segments = self._get_segments_remote() self.max_seg_number = self._segments[-1].name.segment_num + @property + def metadata(self): + if not self._metadata: + api = CommaApi(get_token()) + self._metadata = api.get('v1/route/' + self.name.canonical_name) + return self._metadata + @property def name(self): return self._name @@ -78,6 +87,7 @@ class Route: url if fn in DCAMERA_FILENAMES else segments[segment_name].dcamera_path, url if fn in ECAMERA_FILENAMES else segments[segment_name].ecamera_path, url if fn in QCAMERA_FILENAMES else segments[segment_name].qcamera_path, + self.metadata['url'], ) else: segments[segment_name] = Segment( @@ -88,6 +98,7 @@ class Route: url if fn in DCAMERA_FILENAMES else None, url if fn in ECAMERA_FILENAMES else None, url if fn in QCAMERA_FILENAMES else None, + self.metadata['url'], ) return sorted(segments.values(), key=lambda seg: seg.name.segment_num) @@ -153,7 +164,7 @@ class Route: except StopIteration: qcamera_path = None - segments.append(Segment(segment, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path)) + segments.append(Segment(segment, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path, self.metadata['url'])) if len(segments) == 0: raise ValueError(f'Could not find segments for route {self.name.canonical_name} in data directory {data_dir}') @@ -161,8 +172,10 @@ class Route: class Segment: - def __init__(self, name, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path): + def __init__(self, name, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path, url): + self._events = None self._name = SegmentName(name) + self.url = f'{url}/{self._name.segment_num}' self.log_path = log_path self.qlog_path = qlog_path self.camera_path = camera_path @@ -174,6 +187,17 @@ class Segment: def name(self): return self._name + @property + def events(self): + if not self._events: + try: + resp = requests.get(f'{self.url}/events.json') + resp.raise_for_status() + self._events = resp.json() + except Exception as e: + raise APIError(f'error getting events for segment {self._name}') from e + return self._events + class RouteName: def __init__(self, name_str: str): diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index fe8bd3ea84..b2a11dc77b 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -16,8 +16,7 @@ CHUNK_SIZE = 1000 * K logging.getLogger("urllib3").setLevel(logging.WARNING) def hash_256(link: str) -> str: - hsh = str(sha256((link.split("?")[0]).encode('utf-8')).hexdigest()) - return hsh + return sha256((link.split("?")[0]).encode('utf-8')).hexdigest() class URLFileException(Exception): diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh index c626ec4561..d23052d0f0 100755 --- a/tools/mac_setup.sh +++ b/tools/mac_setup.sh @@ -28,6 +28,8 @@ if [[ $(command -v brew) == "" ]]; then echo 'eval "$(/opt/homebrew/bin/brew shellenv)"' >> $RC_FILE eval "$(/opt/homebrew/bin/brew shellenv)" fi +else + brew up fi brew bundle --file=- <<-EOS diff --git a/tools/op.sh b/tools/op.sh index b4508f7ef7..7c17c949e4 100755 --- a/tools/op.sh +++ b/tools/op.sh @@ -52,6 +52,7 @@ function op_run_command() { # be default, assume openpilot dir is in current directory OPENPILOT_ROOT=$(pwd) function op_get_openpilot_dir() { + # First try traversing up the directory tree while [[ "$OPENPILOT_ROOT" != '/' ]]; do if find "$OPENPILOT_ROOT/launch_openpilot.sh" -maxdepth 1 -mindepth 1 &> /dev/null; then @@ -59,6 +60,14 @@ function op_get_openpilot_dir() { fi OPENPILOT_ROOT="$(readlink -f "$OPENPILOT_ROOT/"..)" done + + # Fallback to hardcoded directories if not found + for dir in "$HOME/openpilot" "/data/openpilot"; do + if [[ -f "$dir/launch_openpilot.sh" ]]; then + OPENPILOT_ROOT="$dir" + return 0 + fi + done } function op_install_post_commit() { @@ -245,7 +254,7 @@ function op_setup() { function op_auth() { op_before_cmd - op_run_command tools/lib/auth.py + op_run_command tools/lib/auth.py "$@" } function op_activate_venv() { @@ -275,7 +284,7 @@ function op_venv() { function op_adb() { op_before_cmd - op_run_command tools/adb_shell.sh + op_run_command tools/scripts/adb_ssh.sh } function op_check() { @@ -284,6 +293,11 @@ function op_check() { unset VERBOSE } +function op_esim() { + op_before_cmd + op_run_command system/hardware/tici/esim.py "$@" +} + function op_build() { CDIR=$(pwd) op_before_cmd @@ -328,6 +342,11 @@ function op_sim() { op_run_command exec tools/sim/launch_openpilot.sh } +function op_clip() { + op_before_cmd + op_run_command tools/clip/run.py $@ +} + function op_switch() { REMOTE="origin" if [ "$#" -gt 1 ]; then @@ -373,16 +392,12 @@ function op_default() { echo " op is only a wrapper for existing scripts, tools, and commands." echo " op will always show you what it will run on your system." echo "" - echo " op will try to find your openpilot directory in the following order:" - echo " 1: use the directory specified with the --dir option" - echo " 2: use the current working directory" - echo " 3: go up the file tree non-recursively" - echo "" echo -e "${BOLD}${UNDERLINE}Usage:${NC} op [OPTIONS] " echo "" echo -e "${BOLD}${UNDERLINE}Commands [System]:${NC}" echo -e " ${BOLD}auth${NC} Authenticate yourself for API use" echo -e " ${BOLD}check${NC} Check the development environment (git, os, python) to start using openpilot" + echo -e " ${BOLD}esim${NC} Manage eSIM profiles on your comma device" echo -e " ${BOLD}venv${NC} Activate the python virtual environment" echo -e " ${BOLD}setup${NC} Install openpilot dependencies" echo -e " ${BOLD}build${NC} Run the openpilot build system in the current working directory" @@ -395,6 +410,7 @@ function op_default() { echo -e " ${BOLD}juggle${NC} Run PlotJuggler" echo -e " ${BOLD}replay${NC} Run Replay" echo -e " ${BOLD}cabana${NC} Run Cabana" + echo -e " ${BOLD}clip${NC} Run clip (linux only)" echo -e " ${BOLD}adb${NC} Run adb shell" echo "" echo -e "${BOLD}${UNDERLINE}Commands [Testing]:${NC}" @@ -438,6 +454,7 @@ function _op() { auth ) shift 1; op_auth "$@" ;; venv ) shift 1; op_venv "$@" ;; check ) shift 1; op_check "$@" ;; + esim ) shift 1; op_esim "$@" ;; setup ) shift 1; op_setup "$@" ;; build ) shift 1; op_build "$@" ;; juggle ) shift 1; op_juggle "$@" ;; @@ -445,6 +462,7 @@ function _op() { lint ) shift 1; op_lint "$@" ;; test ) shift 1; op_test "$@" ;; replay ) shift 1; op_replay "$@" ;; + clip ) shift 1; op_clip "$@" ;; sim ) shift 1; op_sim "$@" ;; install ) shift 1; op_install "$@" ;; switch ) shift 1; op_switch "$@" ;; diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index f66782d6f3..34f33d1959 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -61,13 +61,15 @@ def start_juggler(fn=None, dbc=None, layout=None, route_or_segment_name=None, pl env["BASEDIR"] = BASEDIR env["PATH"] = f"{INSTALL_DIR}:{os.getenv('PATH', '')}" if dbc: + if os.path.exists(dbc): + dbc = os.path.abspath(dbc) env["DBC_NAME"] = dbc extra_args = "" if fn is not None: - extra_args += f" -d {fn}" + extra_args += f" -d {os.path.abspath(fn)}" if layout is not None: - extra_args += f" -l {layout}" + extra_args += f" -l {os.path.abspath(layout)}" if route_or_segment_name is not None: extra_args += f" --window_title \"{route_or_segment_name}{f' ({platform})' if platform is not None else ''}\"" diff --git a/tools/plotjuggler/layouts/gps.xml b/tools/plotjuggler/layouts/gps.xml new file mode 100644 index 0000000000..8fd3b53f93 --- /dev/null +++ b/tools/plotjuggler/layouts/gps.xml @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/tools/plotjuggler/layouts/torque-controller.xml b/tools/plotjuggler/layouts/torque-controller.xml index 5a0a7625e0..606df03611 100644 --- a/tools/plotjuggler/layouts/torque-controller.xml +++ b/tools/plotjuggler/layouts/torque-controller.xml @@ -150,44 +150,44 @@ - - + + - + - + - + - + - + - + diff --git a/tools/replay/README.md b/tools/replay/README.md index f02090c58e..8b4afb0acc 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -64,6 +64,8 @@ Options: -s, --start start from -x playback . between 0.2 - 3 --demo use a demo route instead of providing your own + --auto Auto load the route from the best available source (no video): + internal, openpilotci, comma_api, car_segments, testing_closet --data_dir local directory with routes --prefix set OPENPILOT_PREFIX --dcam load driver camera @@ -81,7 +83,7 @@ Arguments: connect.comma.ai ``` -## Visualize the Replay in the Openpilot UI +## Visualize the Replay in the openpilot UI To visualize the replay within the openpilot UI, run the following commands: ```bash diff --git a/tools/replay/consoleui.h b/tools/replay/consoleui.h index 3d4abeb458..7731f8017f 100644 --- a/tools/replay/consoleui.h +++ b/tools/replay/consoleui.h @@ -12,7 +12,7 @@ public: ConsoleUI(Replay *replay); ~ConsoleUI(); int exec(); - inline static const std::array speed_array = {0.2f, 0.5f, 1.0f, 2.0f, 3.0f}; + inline static const std::array speed_array = {0.2f, 0.5f, 1.0f, 2.0f, 4.0f, 8.0f}; private: void initWindows(); diff --git a/tools/replay/main.cc b/tools/replay/main.cc index b33b7fa263..38a1da292a 100644 --- a/tools/replay/main.cc +++ b/tools/replay/main.cc @@ -19,6 +19,8 @@ Options: -s, --start Start from -x, --playback Playback --demo Use a demo route instead of providing your own + --auto Auto load the route from the best available source (no video): + internal, openpilotci, comma_api, car_segments, testing_closet -d, --data_dir Local directory with routes -p, --prefix Set OPENPILOT_PREFIX --dcam Load driver camera @@ -39,6 +41,7 @@ struct ReplayConfig { std::string data_dir; std::string prefix; uint32_t flags = REPLAY_FLAG_NONE; + bool auto_source = false; int start_seconds = 0; int cache_segments = -1; float playback_speed = -1; @@ -52,6 +55,7 @@ bool parseArgs(int argc, char *argv[], ReplayConfig &config) { {"start", required_argument, nullptr, 's'}, {"playback", required_argument, nullptr, 'x'}, {"demo", no_argument, nullptr, 0}, + {"auto", no_argument, nullptr, 0}, {"data_dir", required_argument, nullptr, 'd'}, {"prefix", required_argument, nullptr, 'p'}, {"dcam", no_argument, nullptr, 0}, @@ -94,11 +98,9 @@ bool parseArgs(int argc, char *argv[], ReplayConfig &config) { case 'p': config.prefix = optarg; break; case 0: { std::string name = cli_options[option_index].name; - if (name == "demo") { - config.route = DEMO_ROUTE; - } else { - config.flags |= flag_map.at(name); - } + if (name == "demo") config.route = DEMO_ROUTE; + else if (name == "auto") config.auto_source = true; + else config.flags |= flag_map.at(name); break; } case 'h': std::cout << helpText; return false; @@ -136,7 +138,7 @@ int main(int argc, char *argv[]) { op_prefix = std::make_unique(config.prefix); } - Replay replay(config.route, config.allow, config.block, nullptr, config.flags, config.data_dir); + Replay replay(config.route, config.allow, config.block, nullptr, config.flags, config.data_dir, config.auto_source); if (config.cache_segments > 0) { replay.setSegmentCacheLimit(config.cache_segments); } diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index 80f586daa6..a8e5cd9d43 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -15,8 +15,8 @@ void notifyEvent(Callback &callback, Args &&...args) { } Replay::Replay(const std::string &route, std::vector allow, std::vector block, - SubMaster *sm, uint32_t flags, const std::string &data_dir) - : sm_(sm), flags_(flags), seg_mgr_(std::make_unique(route, flags, data_dir)) { + SubMaster *sm, uint32_t flags, const std::string &data_dir, bool auto_source) + : sm_(sm), flags_(flags), seg_mgr_(std::make_unique(route, flags, data_dir, auto_source)) { std::signal(SIGUSR1, interrupt_sleep_handler); if (!(flags_ & REPLAY_FLAG_ALL_SERVICES)) { diff --git a/tools/replay/replay.h b/tools/replay/replay.h index 6a2c86ff02..5e868d2427 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -29,7 +29,7 @@ enum REPLAY_FLAGS { class Replay { public: Replay(const std::string &route, std::vector allow, std::vector block, SubMaster *sm = nullptr, - uint32_t flags = REPLAY_FLAG_NONE, const std::string &data_dir = ""); + uint32_t flags = REPLAY_FLAG_NONE, const std::string &data_dir = "", bool auto_source = false); ~Replay(); bool load(); RouteLoadError lastRouteError() const { return route().lastError(); } diff --git a/tools/replay/route.cc b/tools/replay/route.cc index 7731d0daf4..ba00828267 100644 --- a/tools/replay/route.cc +++ b/tools/replay/route.cc @@ -10,9 +10,8 @@ #include "tools/replay/replay.h" #include "tools/replay/util.h" -Route::Route(const std::string &route, const std::string &data_dir) : data_dir_(data_dir) { - route_ = parseRoute(route); -} +Route::Route(const std::string &route, const std::string &data_dir, bool auto_source) + : route_string_(route), data_dir_(data_dir), auto_source_(auto_source) {} RouteIdentifier Route::parseRoute(const std::string &str) { RouteIdentifier identifier = {}; @@ -44,27 +43,62 @@ RouteIdentifier Route::parseRoute(const std::string &str) { } bool Route::load() { - err_ = RouteLoadError::None; + route_ = parseRoute(route_string_); if (route_.str.empty() || (data_dir_.empty() && route_.dongle_id.empty())) { rInfo("invalid route format"); return false; } + // Parse the timestamp from the route identifier (only applicable for old route formats). struct tm tm_time = {0}; - strptime(route_.timestamp.c_str(), "%Y-%m-%d--%H-%M-%S", &tm_time); - date_time_ = mktime(&tm_time); - - bool ret = data_dir_.empty() ? loadFromServer() : loadFromLocal(); - if (ret) { - if (route_.begin_segment == -1) route_.begin_segment = segments_.rbegin()->first; - if (route_.end_segment == -1) route_.end_segment = segments_.rbegin()->first; - for (auto it = segments_.begin(); it != segments_.end(); /**/) { - if (it->first < route_.begin_segment || it->first > route_.end_segment) { - it = segments_.erase(it); - } else { - ++it; + if (strptime(route_.timestamp.c_str(), "%Y-%m-%d--%H-%M-%S", &tm_time)) { + date_time_ = mktime(&tm_time); + } + + if (!loadSegments()) { + rInfo("Failed to load segments"); + return false; + } + + return true; +} + +bool Route::loadSegments() { + if (!auto_source_) { + bool ret = data_dir_.empty() ? loadFromServer() : loadFromLocal(); + if (ret) { + // Trim segments + if (route_.begin_segment > 0) { + segments_.erase(segments_.begin(), segments_.lower_bound(route_.begin_segment)); + } + if (route_.end_segment >= 0) { + segments_.erase(segments_.upper_bound(route_.end_segment), segments_.end()); } } + return !segments_.empty(); + } + return loadFromAutoSource(); +} + +bool Route::loadFromAutoSource() { + auto origin_prefix = getenv("OPENPILOT_PREFIX"); + if (origin_prefix) { + setenv("OPENPILOT_PREFIX", "", 1); + } + auto cmd = util::string_format("../auto_source.py \"%s\"", route_string_.c_str()); + auto log_files = split(util::check_output(cmd), '\n'); + if (origin_prefix) { + setenv("OPENPILOT_PREFIX", origin_prefix, 1); + } + + const static std::regex rx(R"(\/(\d+)\/)"); + for (int i = 0; i < log_files.size(); ++i) { + int seg_num = i; + std::smatch match; + if (std::regex_search(log_files[i], match, rx)) { + seg_num = std::stoi(match[1]); + } + addFileToSegment(seg_num, log_files[i]); } return !segments_.empty(); } @@ -121,7 +155,7 @@ bool Route::loadFromJson(const std::string &json) { bool Route::loadFromLocal() { std::string pattern = route_.timestamp + "--"; for (const auto &entry : std::filesystem::directory_iterator(data_dir_)) { - if (entry.is_directory() && entry.path().filename().string().find(pattern) == 0) { + if (entry.is_directory() && entry.path().filename().string().find(pattern) != std::string::npos) { std::string segment = entry.path().string(); int seg_num = std::atoi(segment.substr(segment.rfind("--") + 2).c_str()); diff --git a/tools/replay/route.h b/tools/replay/route.h index 1806be5afa..0375252a19 100644 --- a/tools/replay/route.h +++ b/tools/replay/route.h @@ -40,7 +40,7 @@ struct SegmentFile { class Route { public: - Route(const std::string &route, const std::string &data_dir = {}); + Route(const std::string &route, const std::string &data_dir = {}, bool auto_source = false); bool load(); RouteLoadError lastError() const { return err_; } inline const std::string &name() const { return route_.str; } @@ -52,6 +52,8 @@ public: static RouteIdentifier parseRoute(const std::string &str); protected: + bool loadSegments(); + bool loadFromAutoSource(); bool loadFromLocal(); bool loadFromServer(int retries = 3); bool loadFromJson(const std::string &json); @@ -59,8 +61,10 @@ protected: RouteIdentifier route_ = {}; std::string data_dir_; std::map segments_; - std::time_t date_time_; + std::time_t date_time_ = 0; RouteLoadError err_ = RouteLoadError::None; + bool auto_source_ = false; + std::string route_string_; }; class Segment { diff --git a/tools/replay/seg_mgr.h b/tools/replay/seg_mgr.h index 9158e41618..640169749e 100644 --- a/tools/replay/seg_mgr.h +++ b/tools/replay/seg_mgr.h @@ -20,8 +20,8 @@ public: bool isSegmentLoaded(int n) const { return segments.find(n) != segments.end(); } }; - SegmentManager(const std::string &route_name, uint32_t flags, const std::string &data_dir = "") - : flags_(flags), route_(route_name, data_dir), event_data_(std::make_shared()) {} + SegmentManager(const std::string &route_name, uint32_t flags, const std::string &data_dir = "", bool auto_source = false) + : flags_(flags), route_(route_name, data_dir, auto_source), event_data_(std::make_shared()) {} ~SegmentManager(); bool load(); diff --git a/tools/scripts/adb_ssh.sh b/tools/scripts/adb_ssh.sh new file mode 100755 index 0000000000..43c8e07de6 --- /dev/null +++ b/tools/scripts/adb_ssh.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env bash +set -e + +# this is a little nicer than "adb shell" since +# "adb shell" doesn't do full terminal emulation +adb forward tcp:2222 tcp:22 +ssh comma@localhost -p 2222 diff --git a/tools/scripts/setup_ssh_keys.py b/tools/scripts/setup_ssh_keys.py index 699765eee1..45dc0aa977 100755 --- a/tools/scripts/setup_ssh_keys.py +++ b/tools/scripts/setup_ssh_keys.py @@ -18,6 +18,6 @@ if __name__ == "__main__": params.put_bool("SshEnabled", True) params.put("GithubSshKeys", keys.text) params.put("GithubUsername", username) - print("Setup ssh keys successfully") + print("Set up ssh keys successfully") else: print("Error getting public keys from github") diff --git a/tools/sim/bridge/common.py b/tools/sim/bridge/common.py index bf3be5193d..69dec173ca 100644 --- a/tools/sim/bridge/common.py +++ b/tools/sim/bridge/common.py @@ -40,7 +40,7 @@ class SimulatorBridge(ABC): def __init__(self, dual_camera, high_quality): set_params_enabled() self.params = Params() - self.params.put_bool("ExperimentalLongitudinalEnabled", True) + self.params.put_bool("AlphaLongitudinalEnabled", True) self.rk = Ratekeeper(100, None) diff --git a/uv.lock b/uv.lock index fe95157eb2..2f8cf68094 100644 --- a/uv.lock +++ b/uv.lock @@ -1,5 +1,5 @@ version = 1 -revision = 1 +revision = 2 requires-python = ">=3.11, <3.13" resolution-markers = [ "python_full_version >= '3.12' and sys_platform == 'darwin'", @@ -12,16 +12,16 @@ resolution-markers = [ [[package]] name = "aiohappyeyeballs" -version = "2.5.0" +version = "2.6.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a2/0c/458958007041f4b4de2d307e6b75d9e7554dad0baf26fe7a48b741aac126/aiohappyeyeballs-2.5.0.tar.gz", hash = "sha256:18fde6204a76deeabc97c48bdd01d5801cfda5d6b9c8bbeb1aaaee9d648ca191", size = 22494 } +sdist = { url = "https://files.pythonhosted.org/packages/26/30/f84a107a9c4331c14b2b586036f40965c128aa4fee4dda5d3d51cb14ad54/aiohappyeyeballs-2.6.1.tar.gz", hash = "sha256:c3f9d0113123803ccadfdf3f0faa505bc78e6a72d1cc4806cbd719826e943558", size = 22760, upload-time = "2025-03-12T01:42:48.764Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1b/9a/e4886864ce06e1579bd428208127fbdc0d62049c751e4e9e3b509c0059dc/aiohappyeyeballs-2.5.0-py3-none-any.whl", hash = "sha256:0850b580748c7071db98bffff6d4c94028d0d3035acc20fd721a0ce7e8cac35d", size = 15128 }, + { url = "https://files.pythonhosted.org/packages/0f/15/5bf3b99495fb160b63f95972b81750f18f7f4e02ad051373b669d17d44f2/aiohappyeyeballs-2.6.1-py3-none-any.whl", hash = "sha256:f349ba8f4b75cb25c99c5c2d84e997e485204d2902a9597802b0371f09331fb8", size = 15265, upload-time = "2025-03-12T01:42:47.083Z" }, ] [[package]] name = "aiohttp" -version = "3.11.13" +version = "3.11.18" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "aiohappyeyeballs" }, @@ -32,53 +32,53 @@ dependencies = [ { name = "propcache" }, { name = "yarl" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b3/3f/c4a667d184c69667b8f16e0704127efc5f1e60577df429382b4d95fd381e/aiohttp-3.11.13.tar.gz", hash = "sha256:8ce789231404ca8fff7f693cdce398abf6d90fd5dae2b1847477196c243b1fbb", size = 7674284 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/3b/93/8e012ae31ff1bda5d43565d6f9e0bad325ba6f3f2d78f298bd39645be8a3/aiohttp-3.11.13-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6b35aab22419ba45f8fc290d0010898de7a6ad131e468ffa3922b1b0b24e9d2e", size = 709013 }, - { url = "https://files.pythonhosted.org/packages/d8/be/fc7c436678ffe547d038319add8e44fd5e33090158752e5c480aed51a8d0/aiohttp-3.11.13-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f81cba651db8795f688c589dd11a4fbb834f2e59bbf9bb50908be36e416dc760", size = 468896 }, - { url = "https://files.pythonhosted.org/packages/d9/1c/56906111ac9d4dab4baab43c89d35d5de1dbb38085150257895005b08bef/aiohttp-3.11.13-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f55d0f242c2d1fcdf802c8fabcff25a9d85550a4cf3a9cf5f2a6b5742c992839", size = 455968 }, - { url = "https://files.pythonhosted.org/packages/ba/16/229d36ed27c2bb350320364efb56f906af194616cc15fc5d87f3ef21dbef/aiohttp-3.11.13-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c4bea08a6aad9195ac9b1be6b0c7e8a702a9cec57ce6b713698b4a5afa9c2e33", size = 1686082 }, - { url = "https://files.pythonhosted.org/packages/3a/44/78fd174509c56028672e5dfef886569cfa1fced0c5fd5c4480426db19ac9/aiohttp-3.11.13-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c6070bcf2173a7146bb9e4735b3c62b2accba459a6eae44deea0eb23e0035a23", size = 1744056 }, - { url = "https://files.pythonhosted.org/packages/a3/11/325145c6dce8124b5caadbf763e908f2779c14bb0bc5868744d1e5cb9cb7/aiohttp-3.11.13-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:718d5deb678bc4b9d575bfe83a59270861417da071ab44542d0fcb6faa686636", size = 1785810 }, - { url = "https://files.pythonhosted.org/packages/95/de/faba18a0af09969e10eb89fdbd4cb968bea95e75449a7fa944d4de7d1d2f/aiohttp-3.11.13-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f6b2c5b4a4d22b8fb2c92ac98e0747f5f195e8e9448bfb7404cd77e7bfa243f", size = 1675540 }, - { url = "https://files.pythonhosted.org/packages/ea/53/0437c46e960b79ae3b1ff74c1ec12f04bf4f425bd349c8807acb38aae3d7/aiohttp-3.11.13-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:747ec46290107a490d21fe1ff4183bef8022b848cf9516970cb31de6d9460088", size = 1620210 }, - { url = "https://files.pythonhosted.org/packages/04/2f/31769ed8e29cc22baaa4005bd2749a7fd0f61ad0f86024d38dff8e394cf6/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:01816f07c9cc9d80f858615b1365f8319d6a5fd079cd668cc58e15aafbc76a54", size = 1654399 }, - { url = "https://files.pythonhosted.org/packages/b0/24/acb24571815b9a86a8261577c920fd84f819178c02a75b05b1a0d7ab83fb/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:a08ad95fcbd595803e0c4280671d808eb170a64ca3f2980dd38e7a72ed8d1fea", size = 1660424 }, - { url = "https://files.pythonhosted.org/packages/91/45/30ca0c3ba5bbf7592eee7489eae30437736f7ff912eaa04cfdcf74edca8c/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:c97be90d70f7db3aa041d720bfb95f4869d6063fcdf2bb8333764d97e319b7d0", size = 1650415 }, - { url = "https://files.pythonhosted.org/packages/86/8d/4d887df5e732cc70349243c2c9784911979e7bd71c06f9e7717b8a896f75/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:ab915a57c65f7a29353c8014ac4be685c8e4a19e792a79fe133a8e101111438e", size = 1733292 }, - { url = "https://files.pythonhosted.org/packages/40/c9/bd950dac0a4c84d44d8da8d6e0f9c9511d45e02cf908a4e1fca591f46a25/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:35cda4e07f5e058a723436c4d2b7ba2124ab4e0aa49e6325aed5896507a8a42e", size = 1755536 }, - { url = "https://files.pythonhosted.org/packages/32/04/aafeda6b4ed3693a44bb89eae002ebaa74f88b2265a7e68f8a31c33330f5/aiohttp-3.11.13-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:af55314407714fe77a68a9ccaab90fdb5deb57342585fd4a3a8102b6d4370080", size = 1693126 }, - { url = "https://files.pythonhosted.org/packages/a1/4f/67729187e884b0f002a0317d2cc7962a5a0416cadc95ea88ba92477290d9/aiohttp-3.11.13-cp311-cp311-win32.whl", hash = "sha256:42d689a5c0a0c357018993e471893e939f555e302313d5c61dfc566c2cad6185", size = 416800 }, - { url = "https://files.pythonhosted.org/packages/29/23/d98d491ca073ee92cc6a741be97b6b097fb06dacc5f95c0c9350787db549/aiohttp-3.11.13-cp311-cp311-win_amd64.whl", hash = "sha256:b73a2b139782a07658fbf170fe4bcdf70fc597fae5ffe75e5b67674c27434a9f", size = 442891 }, - { url = "https://files.pythonhosted.org/packages/9a/a9/6657664a55f78db8767e396cc9723782ed3311eb57704b0a5dacfa731916/aiohttp-3.11.13-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2eabb269dc3852537d57589b36d7f7362e57d1ece308842ef44d9830d2dc3c90", size = 705054 }, - { url = "https://files.pythonhosted.org/packages/3b/06/f7df1fe062d16422f70af5065b76264f40b382605cf7477fa70553a9c9c1/aiohttp-3.11.13-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7b77ee42addbb1c36d35aca55e8cc6d0958f8419e458bb70888d8c69a4ca833d", size = 464440 }, - { url = "https://files.pythonhosted.org/packages/22/3a/8773ea866735754004d9f79e501fe988bdd56cfac7fdecbc8de17fc093eb/aiohttp-3.11.13-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:55789e93c5ed71832e7fac868167276beadf9877b85697020c46e9a75471f55f", size = 456394 }, - { url = "https://files.pythonhosted.org/packages/7f/61/8e2f2af2327e8e475a2b0890f15ef0bbfd117e321cce1e1ed210df81bbac/aiohttp-3.11.13-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c929f9a7249a11e4aa5c157091cfad7f49cc6b13f4eecf9b747104befd9f56f2", size = 1682752 }, - { url = "https://files.pythonhosted.org/packages/24/ed/84fce816bc8da39aa3f6c1196fe26e47065fea882b1a67a808282029c079/aiohttp-3.11.13-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d33851d85537bbf0f6291ddc97926a754c8f041af759e0aa0230fe939168852b", size = 1737375 }, - { url = "https://files.pythonhosted.org/packages/d9/de/35a5ba9e3d21ebfda1ebbe66f6cc5cbb4d3ff9bd6a03e5e8a788954f8f27/aiohttp-3.11.13-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9229d8613bd8401182868fe95688f7581673e1c18ff78855671a4b8284f47bcb", size = 1793660 }, - { url = "https://files.pythonhosted.org/packages/ff/fe/0f650a8c7c72c8a07edf8ab164786f936668acd71786dd5885fc4b1ca563/aiohttp-3.11.13-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:669dd33f028e54fe4c96576f406ebb242ba534dd3a981ce009961bf49960f117", size = 1692233 }, - { url = "https://files.pythonhosted.org/packages/a8/20/185378b3483f968c6303aafe1e33b0da0d902db40731b2b2b2680a631131/aiohttp-3.11.13-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7c1b20a1ace54af7db1f95af85da530fe97407d9063b7aaf9ce6a32f44730778", size = 1619708 }, - { url = "https://files.pythonhosted.org/packages/a4/f9/d9c181750980b17e1e13e522d7e82a8d08d3d28a2249f99207ef5d8d738f/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5724cc77f4e648362ebbb49bdecb9e2b86d9b172c68a295263fa072e679ee69d", size = 1641802 }, - { url = "https://files.pythonhosted.org/packages/50/c7/1cb46b72b1788710343b6e59eaab9642bd2422f2d87ede18b1996e0aed8f/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:aa36c35e94ecdb478246dd60db12aba57cfcd0abcad43c927a8876f25734d496", size = 1684678 }, - { url = "https://files.pythonhosted.org/packages/71/87/89b979391de840c5d7c34e78e1148cc731b8aafa84b6a51d02f44b4c66e2/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:9b5b37c863ad5b0892cc7a4ceb1e435e5e6acd3f2f8d3e11fa56f08d3c67b820", size = 1646921 }, - { url = "https://files.pythonhosted.org/packages/a7/db/a463700ac85b72f8cf68093e988538faaf4e865e3150aa165cf80ee29d6e/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:e06cf4852ce8c4442a59bae5a3ea01162b8fcb49ab438d8548b8dc79375dad8a", size = 1702493 }, - { url = "https://files.pythonhosted.org/packages/b8/32/1084e65da3adfb08c7e1b3e94f3e4ded8bd707dee265a412bc377b7cd000/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:5194143927e494616e335d074e77a5dac7cd353a04755330c9adc984ac5a628e", size = 1735004 }, - { url = "https://files.pythonhosted.org/packages/a0/bb/a634cbdd97ce5d05c2054a9a35bfc32792d7e4f69d600ad7e820571d095b/aiohttp-3.11.13-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:afcb6b275c2d2ba5d8418bf30a9654fa978b4f819c2e8db6311b3525c86fe637", size = 1694964 }, - { url = "https://files.pythonhosted.org/packages/fd/cf/7d29db4e5c28ec316e5d2ac9ac9df0e2e278e9ea910e5c4205b9b64c2c42/aiohttp-3.11.13-cp312-cp312-win32.whl", hash = "sha256:7104d5b3943c6351d1ad7027d90bdd0ea002903e9f610735ac99df3b81f102ee", size = 411746 }, - { url = "https://files.pythonhosted.org/packages/65/a9/13e69ad4fd62104ebd94617f9f2be58231b50bb1e6bac114f024303ac23b/aiohttp-3.11.13-cp312-cp312-win_amd64.whl", hash = "sha256:47dc018b1b220c48089b5b9382fbab94db35bef2fa192995be22cbad3c5730c8", size = 438078 }, +sdist = { url = "https://files.pythonhosted.org/packages/63/e7/fa1a8c00e2c54b05dc8cb5d1439f627f7c267874e3f7bb047146116020f9/aiohttp-3.11.18.tar.gz", hash = "sha256:ae856e1138612b7e412db63b7708735cff4d38d0399f6a5435d3dac2669f558a", size = 7678653, upload-time = "2025-04-21T09:43:09.191Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/2f/10/fd9ee4f9e042818c3c2390054c08ccd34556a3cb209d83285616434cf93e/aiohttp-3.11.18-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:427fdc56ccb6901ff8088544bde47084845ea81591deb16f957897f0f0ba1be9", size = 712088, upload-time = "2025-04-21T09:40:55.776Z" }, + { url = "https://files.pythonhosted.org/packages/22/eb/6a77f055ca56f7aae2cd2a5607a3c9e7b9554f1497a069dcfcb52bfc9540/aiohttp-3.11.18-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2c828b6d23b984255b85b9b04a5b963a74278b7356a7de84fda5e3b76866597b", size = 471450, upload-time = "2025-04-21T09:40:57.301Z" }, + { url = "https://files.pythonhosted.org/packages/78/dc/5f3c0d27c91abf0bb5d103e9c9b0ff059f60cf6031a5f06f456c90731f42/aiohttp-3.11.18-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5c2eaa145bb36b33af1ff2860820ba0589e165be4ab63a49aebfd0981c173b66", size = 457836, upload-time = "2025-04-21T09:40:59.322Z" }, + { url = "https://files.pythonhosted.org/packages/49/7b/55b65af9ef48b9b811c91ff8b5b9de9650c71147f10523e278d297750bc8/aiohttp-3.11.18-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3d518ce32179f7e2096bf4e3e8438cf445f05fedd597f252de9f54c728574756", size = 1690978, upload-time = "2025-04-21T09:41:00.795Z" }, + { url = "https://files.pythonhosted.org/packages/a2/5a/3f8938c4f68ae400152b42742653477fc625d6bfe02e764f3521321c8442/aiohttp-3.11.18-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0700055a6e05c2f4711011a44364020d7a10fbbcd02fbf3e30e8f7e7fddc8717", size = 1745307, upload-time = "2025-04-21T09:41:02.89Z" }, + { url = "https://files.pythonhosted.org/packages/b4/42/89b694a293333ef6f771c62da022163bcf44fb03d4824372d88e3dc12530/aiohttp-3.11.18-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8bd1cde83e4684324e6ee19adfc25fd649d04078179890be7b29f76b501de8e4", size = 1780692, upload-time = "2025-04-21T09:41:04.461Z" }, + { url = "https://files.pythonhosted.org/packages/e2/ce/1a75384e01dd1bf546898b6062b1b5f7a59b6692ef802e4dd6db64fed264/aiohttp-3.11.18-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:73b8870fe1c9a201b8c0d12c94fe781b918664766728783241a79e0468427e4f", size = 1676934, upload-time = "2025-04-21T09:41:06.728Z" }, + { url = "https://files.pythonhosted.org/packages/a5/31/442483276e6c368ab5169797d9873b5875213cbcf7e74b95ad1c5003098a/aiohttp-3.11.18-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:25557982dd36b9e32c0a3357f30804e80790ec2c4d20ac6bcc598533e04c6361", size = 1621190, upload-time = "2025-04-21T09:41:08.293Z" }, + { url = "https://files.pythonhosted.org/packages/7b/83/90274bf12c079457966008a58831a99675265b6a34b505243e004b408934/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:7e889c9df381a2433802991288a61e5a19ceb4f61bd14f5c9fa165655dcb1fd1", size = 1658947, upload-time = "2025-04-21T09:41:11.054Z" }, + { url = "https://files.pythonhosted.org/packages/91/c1/da9cee47a0350b78fdc93670ebe7ad74103011d7778ab4c382ca4883098d/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:9ea345fda05bae217b6cce2acf3682ce3b13d0d16dd47d0de7080e5e21362421", size = 1654443, upload-time = "2025-04-21T09:41:13.213Z" }, + { url = "https://files.pythonhosted.org/packages/c9/f2/73cbe18dc25d624f79a09448adfc4972f82ed6088759ddcf783cd201956c/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:9f26545b9940c4b46f0a9388fd04ee3ad7064c4017b5a334dd450f616396590e", size = 1644169, upload-time = "2025-04-21T09:41:14.827Z" }, + { url = "https://files.pythonhosted.org/packages/5b/32/970b0a196c4dccb1b0cfa5b4dc3b20f63d76f1c608f41001a84b2fd23c3d/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:3a621d85e85dccabd700294494d7179ed1590b6d07a35709bb9bd608c7f5dd1d", size = 1728532, upload-time = "2025-04-21T09:41:17.168Z" }, + { url = "https://files.pythonhosted.org/packages/0b/50/b1dc810a41918d2ea9574e74125eb053063bc5e14aba2d98966f7d734da0/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:9c23fd8d08eb9c2af3faeedc8c56e134acdaf36e2117ee059d7defa655130e5f", size = 1750310, upload-time = "2025-04-21T09:41:19.353Z" }, + { url = "https://files.pythonhosted.org/packages/95/24/39271f5990b35ff32179cc95537e92499d3791ae82af7dcf562be785cd15/aiohttp-3.11.18-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d9e6b0e519067caa4fd7fb72e3e8002d16a68e84e62e7291092a5433763dc0dd", size = 1691580, upload-time = "2025-04-21T09:41:21.868Z" }, + { url = "https://files.pythonhosted.org/packages/6b/78/75d0353feb77f041460564f12fe58e456436bbc00cbbf5d676dbf0038cc2/aiohttp-3.11.18-cp311-cp311-win32.whl", hash = "sha256:122f3e739f6607e5e4c6a2f8562a6f476192a682a52bda8b4c6d4254e1138f4d", size = 417565, upload-time = "2025-04-21T09:41:24.78Z" }, + { url = "https://files.pythonhosted.org/packages/ed/97/b912dcb654634a813f8518de359364dfc45976f822116e725dc80a688eee/aiohttp-3.11.18-cp311-cp311-win_amd64.whl", hash = "sha256:e6f3c0a3a1e73e88af384b2e8a0b9f4fb73245afd47589df2afcab6b638fa0e6", size = 443652, upload-time = "2025-04-21T09:41:26.48Z" }, + { url = "https://files.pythonhosted.org/packages/b5/d2/5bc436f42bf4745c55f33e1e6a2d69e77075d3e768e3d1a34f96ee5298aa/aiohttp-3.11.18-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:63d71eceb9cad35d47d71f78edac41fcd01ff10cacaa64e473d1aec13fa02df2", size = 706671, upload-time = "2025-04-21T09:41:28.021Z" }, + { url = "https://files.pythonhosted.org/packages/fe/d0/2dbabecc4e078c0474abb40536bbde717fb2e39962f41c5fc7a216b18ea7/aiohttp-3.11.18-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d1929da615840969929e8878d7951b31afe0bac883d84418f92e5755d7b49508", size = 466169, upload-time = "2025-04-21T09:41:29.783Z" }, + { url = "https://files.pythonhosted.org/packages/70/84/19edcf0b22933932faa6e0be0d933a27bd173da02dc125b7354dff4d8da4/aiohttp-3.11.18-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:7d0aebeb2392f19b184e3fdd9e651b0e39cd0f195cdb93328bd124a1d455cd0e", size = 457554, upload-time = "2025-04-21T09:41:31.327Z" }, + { url = "https://files.pythonhosted.org/packages/32/d0/e8d1f034ae5624a0f21e4fb3feff79342ce631f3a4d26bd3e58b31ef033b/aiohttp-3.11.18-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3849ead845e8444f7331c284132ab314b4dac43bfae1e3cf350906d4fff4620f", size = 1690154, upload-time = "2025-04-21T09:41:33.541Z" }, + { url = "https://files.pythonhosted.org/packages/16/de/2f9dbe2ac6f38f8495562077131888e0d2897e3798a0ff3adda766b04a34/aiohttp-3.11.18-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5e8452ad6b2863709f8b3d615955aa0807bc093c34b8e25b3b52097fe421cb7f", size = 1733402, upload-time = "2025-04-21T09:41:35.634Z" }, + { url = "https://files.pythonhosted.org/packages/e0/04/bd2870e1e9aef990d14b6df2a695f17807baf5c85a4c187a492bda569571/aiohttp-3.11.18-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3b8d2b42073611c860a37f718b3d61ae8b4c2b124b2e776e2c10619d920350ec", size = 1783958, upload-time = "2025-04-21T09:41:37.456Z" }, + { url = "https://files.pythonhosted.org/packages/23/06/4203ffa2beb5bedb07f0da0f79b7d9039d1c33f522e0d1a2d5b6218e6f2e/aiohttp-3.11.18-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40fbf91f6a0ac317c0a07eb328a1384941872f6761f2e6f7208b63c4cc0a7ff6", size = 1695288, upload-time = "2025-04-21T09:41:39.756Z" }, + { url = "https://files.pythonhosted.org/packages/30/b2/e2285dda065d9f29ab4b23d8bcc81eb881db512afb38a3f5247b191be36c/aiohttp-3.11.18-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:44ff5625413fec55216da5eaa011cf6b0a2ed67a565914a212a51aa3755b0009", size = 1618871, upload-time = "2025-04-21T09:41:41.972Z" }, + { url = "https://files.pythonhosted.org/packages/57/e0/88f2987885d4b646de2036f7296ebea9268fdbf27476da551c1a7c158bc0/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:7f33a92a2fde08e8c6b0c61815521324fc1612f397abf96eed86b8e31618fdb4", size = 1646262, upload-time = "2025-04-21T09:41:44.192Z" }, + { url = "https://files.pythonhosted.org/packages/e0/19/4d2da508b4c587e7472a032290b2981f7caeca82b4354e19ab3df2f51d56/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:11d5391946605f445ddafda5eab11caf310f90cdda1fd99865564e3164f5cff9", size = 1677431, upload-time = "2025-04-21T09:41:46.049Z" }, + { url = "https://files.pythonhosted.org/packages/eb/ae/047473ea50150a41440f3265f53db1738870b5a1e5406ece561ca61a3bf4/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:3cc314245deb311364884e44242e00c18b5896e4fe6d5f942e7ad7e4cb640adb", size = 1637430, upload-time = "2025-04-21T09:41:47.973Z" }, + { url = "https://files.pythonhosted.org/packages/11/32/c6d1e3748077ce7ee13745fae33e5cb1dac3e3b8f8787bf738a93c94a7d2/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:0f421843b0f70740772228b9e8093289924359d306530bcd3926f39acbe1adda", size = 1703342, upload-time = "2025-04-21T09:41:50.323Z" }, + { url = "https://files.pythonhosted.org/packages/c5/1d/a3b57bfdbe285f0d45572d6d8f534fd58761da3e9cbc3098372565005606/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:e220e7562467dc8d589e31c1acd13438d82c03d7f385c9cd41a3f6d1d15807c1", size = 1740600, upload-time = "2025-04-21T09:41:52.111Z" }, + { url = "https://files.pythonhosted.org/packages/a5/71/f9cd2fed33fa2b7ce4d412fb7876547abb821d5b5520787d159d0748321d/aiohttp-3.11.18-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ab2ef72f8605046115bc9aa8e9d14fd49086d405855f40b79ed9e5c1f9f4faea", size = 1695131, upload-time = "2025-04-21T09:41:53.94Z" }, + { url = "https://files.pythonhosted.org/packages/97/97/d1248cd6d02b9de6aa514793d0dcb20099f0ec47ae71a933290116c070c5/aiohttp-3.11.18-cp312-cp312-win32.whl", hash = "sha256:12a62691eb5aac58d65200c7ae94d73e8a65c331c3a86a2e9670927e94339ee8", size = 412442, upload-time = "2025-04-21T09:41:55.689Z" }, + { url = "https://files.pythonhosted.org/packages/33/9a/e34e65506e06427b111e19218a99abf627638a9703f4b8bcc3e3021277ed/aiohttp-3.11.18-cp312-cp312-win_amd64.whl", hash = "sha256:364329f319c499128fd5cd2d1c31c44f234c58f9b96cc57f743d16ec4f3238c8", size = 439444, upload-time = "2025-04-21T09:41:57.977Z" }, ] [[package]] name = "aioice" -version = "0.9.0" +version = "0.10.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "dnspython" }, { name = "ifaddr" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/33/b6/e2b0e48ccb5b04fe29265e93f14a0915f416e359c897ae87d570566c430b/aioice-0.9.0.tar.gz", hash = "sha256:fc2401b1c4b6e19372eaaeaa28fd1bd9cbf6b0e412e48625297c53b495eebd1e", size = 40324 } +sdist = { url = "https://files.pythonhosted.org/packages/95/a2/45dfab1d5a7f96c48595a5770379acf406cdf02a2cd1ac1729b599322b08/aioice-0.10.1.tar.gz", hash = "sha256:5c8e1422103448d171925c678fb39795e5fe13d79108bebb00aa75a899c2094a", size = 44304, upload-time = "2025-04-13T08:15:25.629Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b6/35/d21e48d3ba25d32aba5d142d54c4491376c659dd74d052a30dd25198007b/aioice-0.9.0-py3-none-any.whl", hash = "sha256:b609597a3a5a611e0004ff04772e16aceb881d51c25c0afc4ceac05d5e50024e", size = 24177 }, + { url = "https://files.pythonhosted.org/packages/3b/58/af07dda649c22a1ae954ffb7aaaf4d4a57f1bf00ebdf62307affc0b8552f/aioice-0.10.1-py3-none-any.whl", hash = "sha256:f31ae2abc8608b1283ed5f21aebd7b6bd472b152ff9551e9b559b2d8efed79e9", size = 24872, upload-time = "2025-04-13T08:15:24.044Z" }, ] [[package]] @@ -95,15 +95,15 @@ dependencies = [ { name = "pylibsrtp" }, { name = "pyopenssl" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/8a/f8/408e092748521889c9d33dddcef920afd9891cf6db4615ba6b6bfe114ff8/aiortc-1.10.1.tar.gz", hash = "sha256:64926ad86bde20c1a4dacb7c3a164e57b522606b70febe261fada4acf79641b5", size = 1179406 } +sdist = { url = "https://files.pythonhosted.org/packages/8a/f8/408e092748521889c9d33dddcef920afd9891cf6db4615ba6b6bfe114ff8/aiortc-1.10.1.tar.gz", hash = "sha256:64926ad86bde20c1a4dacb7c3a164e57b522606b70febe261fada4acf79641b5", size = 1179406, upload-time = "2025-02-02T17:36:38.684Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/0a/6b/74547a30d1ddcc81f905ef4ff7fcc2c89b7482cb2045688f2aaa4fa918aa/aiortc-1.10.1-cp39-abi3-macosx_10_9_x86_64.whl", hash = "sha256:3bef536f38394b518aefae9dbf9cdd08f39e4c425f316f9692f0d8dc724810bd", size = 1218457 }, - { url = "https://files.pythonhosted.org/packages/46/92/b4ccf39cd18e366ace2a11dc7d98ed55967b4b325707386b5788149db15e/aiortc-1.10.1-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:8842c02e38513d9432ef22982572833487bb015f23348fa10a690616dbf55143", size = 898855 }, - { url = "https://files.pythonhosted.org/packages/a4/e9/2676de48b493787d8b03129713e6bb2dfbacca2a565090f2a89cbad71f96/aiortc-1.10.1-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:954a420de01c0bf6b07a0c58b662029b1c4204ddbd8f5c4162bbdebd43f882b1", size = 1750403 }, - { url = "https://files.pythonhosted.org/packages/c3/9d/ab6d09183cdaf5df060923d9bd5c9ed5fb1802661d9401dba35f3c85a57b/aiortc-1.10.1-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e7c0d46fb30307a9d7deb4b7d66f0b0e73b77a7221b063fb6dc78821a5d2aa1e", size = 1867886 }, - { url = "https://files.pythonhosted.org/packages/c2/71/0b5666e6b965dbd9a7f331aa827a6c3ab3eb4d582fefb686a7f4227b7954/aiortc-1.10.1-cp39-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:89582f6923046f79f15d9045f432bc78191eacc95f6bed18714e86ec935188d9", size = 1893709 }, - { url = "https://files.pythonhosted.org/packages/9d/0a/8c0c78fad79ef595a0ed6e2ab413900e6bd0eac65fc5c31c9d8736bff909/aiortc-1.10.1-cp39-abi3-win32.whl", hash = "sha256:d1cbe87f740b33ffaa8e905f21092773e74916be338b64b81c8b79af4c3847eb", size = 923265 }, - { url = "https://files.pythonhosted.org/packages/73/12/a27dd588a4988021da88cb4d338d8ee65ac097afc14e9193ab0be4a48790/aiortc-1.10.1-cp39-abi3-win_amd64.whl", hash = "sha256:c9a5a0b23f8a77540068faec8837fa0a65b0396c20f09116bdb874b75e0b6abe", size = 1009488 }, + { url = "https://files.pythonhosted.org/packages/0a/6b/74547a30d1ddcc81f905ef4ff7fcc2c89b7482cb2045688f2aaa4fa918aa/aiortc-1.10.1-cp39-abi3-macosx_10_9_x86_64.whl", hash = "sha256:3bef536f38394b518aefae9dbf9cdd08f39e4c425f316f9692f0d8dc724810bd", size = 1218457, upload-time = "2025-02-02T17:36:23.172Z" }, + { url = "https://files.pythonhosted.org/packages/46/92/b4ccf39cd18e366ace2a11dc7d98ed55967b4b325707386b5788149db15e/aiortc-1.10.1-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:8842c02e38513d9432ef22982572833487bb015f23348fa10a690616dbf55143", size = 898855, upload-time = "2025-02-02T17:36:25.9Z" }, + { url = "https://files.pythonhosted.org/packages/a4/e9/2676de48b493787d8b03129713e6bb2dfbacca2a565090f2a89cbad71f96/aiortc-1.10.1-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:954a420de01c0bf6b07a0c58b662029b1c4204ddbd8f5c4162bbdebd43f882b1", size = 1750403, upload-time = "2025-02-02T17:36:28.446Z" }, + { url = "https://files.pythonhosted.org/packages/c3/9d/ab6d09183cdaf5df060923d9bd5c9ed5fb1802661d9401dba35f3c85a57b/aiortc-1.10.1-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e7c0d46fb30307a9d7deb4b7d66f0b0e73b77a7221b063fb6dc78821a5d2aa1e", size = 1867886, upload-time = "2025-02-02T17:36:30.209Z" }, + { url = "https://files.pythonhosted.org/packages/c2/71/0b5666e6b965dbd9a7f331aa827a6c3ab3eb4d582fefb686a7f4227b7954/aiortc-1.10.1-cp39-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:89582f6923046f79f15d9045f432bc78191eacc95f6bed18714e86ec935188d9", size = 1893709, upload-time = "2025-02-02T17:36:32.342Z" }, + { url = "https://files.pythonhosted.org/packages/9d/0a/8c0c78fad79ef595a0ed6e2ab413900e6bd0eac65fc5c31c9d8736bff909/aiortc-1.10.1-cp39-abi3-win32.whl", hash = "sha256:d1cbe87f740b33ffaa8e905f21092773e74916be338b64b81c8b79af4c3847eb", size = 923265, upload-time = "2025-02-02T17:36:34.685Z" }, + { url = "https://files.pythonhosted.org/packages/73/12/a27dd588a4988021da88cb4d338d8ee65ac097afc14e9193ab0be4a48790/aiortc-1.10.1-cp39-abi3-win_amd64.whl", hash = "sha256:c9a5a0b23f8a77540068faec8837fa0a65b0396c20f09116bdb874b75e0b6abe", size = 1009488, upload-time = "2025-02-02T17:36:36.317Z" }, ] [[package]] @@ -113,57 +113,57 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "frozenlist" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ba/b5/6d55e80f6d8a08ce22b982eafa278d823b541c925f11ee774b0b9c43473d/aiosignal-1.3.2.tar.gz", hash = "sha256:a8c255c66fafb1e499c9351d0bf32ff2d8a0321595ebac3b93713656d2436f54", size = 19424 } +sdist = { url = "https://files.pythonhosted.org/packages/ba/b5/6d55e80f6d8a08ce22b982eafa278d823b541c925f11ee774b0b9c43473d/aiosignal-1.3.2.tar.gz", hash = "sha256:a8c255c66fafb1e499c9351d0bf32ff2d8a0321595ebac3b93713656d2436f54", size = 19424, upload-time = "2024-12-13T17:10:40.86Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ec/6a/bc7e17a3e87a2985d3e8f4da4cd0f481060eb78fb08596c42be62c90a4d9/aiosignal-1.3.2-py2.py3-none-any.whl", hash = "sha256:45cde58e409a301715980c2b01d0c28bdde3770d8290b5eb2173759d9acb31a5", size = 7597 }, + { url = "https://files.pythonhosted.org/packages/ec/6a/bc7e17a3e87a2985d3e8f4da4cd0f481060eb78fb08596c42be62c90a4d9/aiosignal-1.3.2-py2.py3-none-any.whl", hash = "sha256:45cde58e409a301715980c2b01d0c28bdde3770d8290b5eb2173759d9acb31a5", size = 7597, upload-time = "2024-12-13T17:10:38.469Z" }, ] [[package]] name = "attrs" -version = "25.1.0" +version = "25.3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/49/7c/fdf464bcc51d23881d110abd74b512a42b3d5d376a55a831b44c603ae17f/attrs-25.1.0.tar.gz", hash = "sha256:1c97078a80c814273a76b2a298a932eb681c87415c11dee0a6921de7f1b02c3e", size = 810562 } +sdist = { url = "https://files.pythonhosted.org/packages/5a/b0/1367933a8532ee6ff8d63537de4f1177af4bff9f3e829baf7331f595bb24/attrs-25.3.0.tar.gz", hash = "sha256:75d7cefc7fb576747b2c81b4442d4d4a1ce0900973527c011d1030fd3bf4af1b", size = 812032, upload-time = "2025-03-13T11:10:22.779Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fc/30/d4986a882011f9df997a55e6becd864812ccfcd821d64aac8570ee39f719/attrs-25.1.0-py3-none-any.whl", hash = "sha256:c75a69e28a550a7e93789579c22aa26b0f5b83b75dc4e08fe092980051e1090a", size = 63152 }, + { url = "https://files.pythonhosted.org/packages/77/06/bb80f5f86020c4551da315d78b3ab75e8228f89f0162f2c3a819e407941a/attrs-25.3.0-py3-none-any.whl", hash = "sha256:427318ce031701fea540783410126f03899a97ffc6f61596ad581ac2e40e3bc3", size = 63815, upload-time = "2025-03-13T11:10:21.14Z" }, ] [[package]] name = "av" version = "13.1.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/0c/9d/486d31e76784cc0ad943f420c5e05867263b32b37e2f4b0f7f22fdc1ca3a/av-13.1.0.tar.gz", hash = "sha256:d3da736c55847d8596eb8c26c60e036f193001db3bc5c10da8665622d906c17e", size = 3957908 } +sdist = { url = "https://files.pythonhosted.org/packages/0c/9d/486d31e76784cc0ad943f420c5e05867263b32b37e2f4b0f7f22fdc1ca3a/av-13.1.0.tar.gz", hash = "sha256:d3da736c55847d8596eb8c26c60e036f193001db3bc5c10da8665622d906c17e", size = 3957908, upload-time = "2024-10-06T04:54:57.507Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/39/54/c4227080c9700384db90072ace70d89b6a288b3748bd2ec0e32580a49e7f/av-13.1.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:867385e6701464a5c95903e24d2e0df1c7e0dbf211ed91d0ce639cd687373e10", size = 24255112 }, - { url = "https://files.pythonhosted.org/packages/32/4a/eb9348231655ca99b200b380f4edbceff7358c927a285badcc84b18fb1c9/av-13.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:cb7a3f319401a46b0017771268ff4928501e77cf00b1a2aa0721e20b2fd1146e", size = 19467930 }, - { url = "https://files.pythonhosted.org/packages/14/c7/48c80252bdbc3a75a54dd205a7fab8f613914009b9e5416202757208e040/av-13.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ad904f860147bceaca65b0d3174a8153f35c570d465161d210f1879970b15559", size = 32207671 }, - { url = "https://files.pythonhosted.org/packages/f9/66/3332c7fa8c43b65680a94f279ea3e832b5500de3a1392bac6112881e984b/av-13.1.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a906e017b29d0eb80d9ccf7a98d19268122da792dbb68eb741cfebba156e6aed", size = 31520911 }, - { url = "https://files.pythonhosted.org/packages/e5/bb/2e03acb9b27591d97f700a3a6c27cfd1bc53fa148177747eda8a70cca1e9/av-13.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5ce894d7847897da7be63277a0875bd93c51327134ac226c67978de014c7979f", size = 34048399 }, - { url = "https://files.pythonhosted.org/packages/85/44/527aa3b65947d42cfe829326026edf0cd1a8c459390076034be275616c36/av-13.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:384bcdb5fc3238a263a5a25cc9efc690859fa4148cc4b07e00fae927178db22a", size = 25779569 }, - { url = "https://files.pythonhosted.org/packages/9b/aa/4bdd8ce59173574fc6e0c282c71ee6f96fca82643d97bf172bc4cb5a5674/av-13.1.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:261dbc3f4b55f4f8f3375b10b2258fca7f2ab7a6365c01bc65e77a0d5327a195", size = 24268674 }, - { url = "https://files.pythonhosted.org/packages/17/b4/b267dd5bad99eed49ec6731827c6bcb5ab03864bf732a7ebb81e3df79911/av-13.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:83d259ef86b9054eb914bc7c6a7f6092a6d75cb939295e70ee979cfd92a67b99", size = 19475617 }, - { url = "https://files.pythonhosted.org/packages/68/32/4209e51f54d7b54a1feb576d309c671ed1ff437b54fcc4ec68c239199e0a/av-13.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f3b4d3ca159eceab97e3c0fb08fe756520fb95508417f76e48198fda2a5b0806", size = 32468873 }, - { url = "https://files.pythonhosted.org/packages/b6/d8/c174da5f06b24f3c9e36f91fd02a7411c39da9ce792c17964260d4be675e/av-13.1.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:40e8f757e373b73a2dc4640852a00cce4a4a92ef19b2e642a96d6994cd1fffbf", size = 31818484 }, - { url = "https://files.pythonhosted.org/packages/7f/22/0dd8d1d5cad415772bb707d16aea8b81cf75d340d11d3668eea43468c730/av-13.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d8aaec2c0bfd024359db3821d679009d4e637e1bee0321d20f61c54ed6b20f41", size = 34398652 }, - { url = "https://files.pythonhosted.org/packages/7b/ff/48fa68888b8d5bae36d915556ff18f9e5fdc6b5ff5ae23dc4904c9713168/av-13.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:5ea0deab0e6a739cb742fba2a3983d8102f7516a3cdf3c46669f3cac0ed1f351", size = 25781343 }, + { url = "https://files.pythonhosted.org/packages/39/54/c4227080c9700384db90072ace70d89b6a288b3748bd2ec0e32580a49e7f/av-13.1.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:867385e6701464a5c95903e24d2e0df1c7e0dbf211ed91d0ce639cd687373e10", size = 24255112, upload-time = "2024-10-06T04:52:48.49Z" }, + { url = "https://files.pythonhosted.org/packages/32/4a/eb9348231655ca99b200b380f4edbceff7358c927a285badcc84b18fb1c9/av-13.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:cb7a3f319401a46b0017771268ff4928501e77cf00b1a2aa0721e20b2fd1146e", size = 19467930, upload-time = "2024-10-06T04:52:52.118Z" }, + { url = "https://files.pythonhosted.org/packages/14/c7/48c80252bdbc3a75a54dd205a7fab8f613914009b9e5416202757208e040/av-13.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ad904f860147bceaca65b0d3174a8153f35c570d465161d210f1879970b15559", size = 32207671, upload-time = "2024-10-06T04:52:55.82Z" }, + { url = "https://files.pythonhosted.org/packages/f9/66/3332c7fa8c43b65680a94f279ea3e832b5500de3a1392bac6112881e984b/av-13.1.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a906e017b29d0eb80d9ccf7a98d19268122da792dbb68eb741cfebba156e6aed", size = 31520911, upload-time = "2024-10-06T04:52:59.231Z" }, + { url = "https://files.pythonhosted.org/packages/e5/bb/2e03acb9b27591d97f700a3a6c27cfd1bc53fa148177747eda8a70cca1e9/av-13.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5ce894d7847897da7be63277a0875bd93c51327134ac226c67978de014c7979f", size = 34048399, upload-time = "2024-10-06T04:53:03.934Z" }, + { url = "https://files.pythonhosted.org/packages/85/44/527aa3b65947d42cfe829326026edf0cd1a8c459390076034be275616c36/av-13.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:384bcdb5fc3238a263a5a25cc9efc690859fa4148cc4b07e00fae927178db22a", size = 25779569, upload-time = "2024-10-06T04:53:07.582Z" }, + { url = "https://files.pythonhosted.org/packages/9b/aa/4bdd8ce59173574fc6e0c282c71ee6f96fca82643d97bf172bc4cb5a5674/av-13.1.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:261dbc3f4b55f4f8f3375b10b2258fca7f2ab7a6365c01bc65e77a0d5327a195", size = 24268674, upload-time = "2024-10-06T04:53:11.251Z" }, + { url = "https://files.pythonhosted.org/packages/17/b4/b267dd5bad99eed49ec6731827c6bcb5ab03864bf732a7ebb81e3df79911/av-13.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:83d259ef86b9054eb914bc7c6a7f6092a6d75cb939295e70ee979cfd92a67b99", size = 19475617, upload-time = "2024-10-06T04:53:13.832Z" }, + { url = "https://files.pythonhosted.org/packages/68/32/4209e51f54d7b54a1feb576d309c671ed1ff437b54fcc4ec68c239199e0a/av-13.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f3b4d3ca159eceab97e3c0fb08fe756520fb95508417f76e48198fda2a5b0806", size = 32468873, upload-time = "2024-10-06T04:53:17.639Z" }, + { url = "https://files.pythonhosted.org/packages/b6/d8/c174da5f06b24f3c9e36f91fd02a7411c39da9ce792c17964260d4be675e/av-13.1.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:40e8f757e373b73a2dc4640852a00cce4a4a92ef19b2e642a96d6994cd1fffbf", size = 31818484, upload-time = "2024-10-06T04:53:21.509Z" }, + { url = "https://files.pythonhosted.org/packages/7f/22/0dd8d1d5cad415772bb707d16aea8b81cf75d340d11d3668eea43468c730/av-13.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d8aaec2c0bfd024359db3821d679009d4e637e1bee0321d20f61c54ed6b20f41", size = 34398652, upload-time = "2024-10-06T04:53:25.798Z" }, + { url = "https://files.pythonhosted.org/packages/7b/ff/48fa68888b8d5bae36d915556ff18f9e5fdc6b5ff5ae23dc4904c9713168/av-13.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:5ea0deab0e6a739cb742fba2a3983d8102f7516a3cdf3c46669f3cac0ed1f351", size = 25781343, upload-time = "2024-10-06T04:53:29.577Z" }, ] [[package]] name = "azure-core" -version = "1.32.0" +version = "1.34.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "requests" }, { name = "six" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/cc/ee/668328306a9e963a5ad9f152cd98c7adad86c822729fd1d2a01613ad1e67/azure_core-1.32.0.tar.gz", hash = "sha256:22b3c35d6b2dae14990f6c1be2912bf23ffe50b220e708a28ab1bb92b1c730e5", size = 279128 } +sdist = { url = "https://files.pythonhosted.org/packages/c9/29/ff7a519a315e41c85bab92a7478c6acd1cf0b14353139a08caee4c691f77/azure_core-1.34.0.tar.gz", hash = "sha256:bdb544989f246a0ad1c85d72eeb45f2f835afdcbc5b45e43f0dbde7461c81ece", size = 297999, upload-time = "2025-05-01T23:17:27.59Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/39/83/325bf5e02504dbd8b4faa98197a44cdf8a325ef259b48326a2b6f17f8383/azure_core-1.32.0-py3-none-any.whl", hash = "sha256:eac191a0efb23bfa83fddf321b27b122b4ec847befa3091fa736a5c32c50d7b4", size = 198855 }, + { url = "https://files.pythonhosted.org/packages/84/9e/5c87b49f65bb16571599bc789857d0ded2f53014d3392bc88a5d1f3ad779/azure_core-1.34.0-py3-none-any.whl", hash = "sha256:0615d3b756beccdb6624d1c0ae97284f38b78fb59a2a9839bf927c66fbbdddd6", size = 207409, upload-time = "2025-05-01T23:17:29.818Z" }, ] [[package]] name = "azure-identity" -version = "1.20.0" +version = "1.23.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -172,14 +172,14 @@ dependencies = [ { name = "msal-extensions" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ee/89/7d170fab0b85d9650cdb7abda087e849644beb52bd28f6804620dd0cecd9/azure_identity-1.20.0.tar.gz", hash = "sha256:40597210d56c83e15031b0fe2ea3b26420189e1e7f3e20bdbb292315da1ba014", size = 264447 } +sdist = { url = "https://files.pythonhosted.org/packages/41/52/458c1be17a5d3796570ae2ed3c6b7b55b134b22d5ef8132b4f97046a9051/azure_identity-1.23.0.tar.gz", hash = "sha256:d9cdcad39adb49d4bb2953a217f62aec1f65bbb3c63c9076da2be2a47e53dde4", size = 265280, upload-time = "2025-05-14T00:18:30.408Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/de/aa/819513c1dbef990af690bb5eefb5e337f8698d75dfdb7302528f50ce1994/azure_identity-1.20.0-py3-none-any.whl", hash = "sha256:5f23fc4889a66330e840bd78830287e14f3761820fe3c5f77ac875edcb9ec998", size = 188243 }, + { url = "https://files.pythonhosted.org/packages/07/16/a51d47780f41e4b87bb2d454df6aea90a44a346e918ac189d3700f3d728d/azure_identity-1.23.0-py3-none-any.whl", hash = "sha256:dbbeb64b8e5eaa81c44c565f264b519ff2de7ff0e02271c49f3cb492762a50b0", size = 186097, upload-time = "2025-05-14T00:18:32.734Z" }, ] [[package]] name = "azure-storage-blob" -version = "12.24.1" +version = "12.25.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -187,41 +187,41 @@ dependencies = [ { name = "isodate" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/aa/ff/f6e81d15687510d83a06cafba9ac38d17df71a2bb18f35a0fb169aee3af3/azure_storage_blob-12.24.1.tar.gz", hash = "sha256:052b2a1ea41725ba12e2f4f17be85a54df1129e13ea0321f5a2fcc851cbf47d4", size = 570523 } +sdist = { url = "https://files.pythonhosted.org/packages/8b/f3/f764536c25cc3829d36857167f03933ce9aee2262293179075439f3cd3ad/azure_storage_blob-12.25.1.tar.gz", hash = "sha256:4f294ddc9bc47909ac66b8934bd26b50d2000278b10ad82cc109764fdc6e0e3b", size = 570541, upload-time = "2025-03-27T17:13:05.424Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/74/3c/3814aba90a63e84c7de0eb6fdf67bd1a9115ac5f99ec5b7a817a5d5278ec/azure_storage_blob-12.24.1-py3-none-any.whl", hash = "sha256:77fb823fdbac7f3c11f7d86a5892e2f85e161e8440a7489babe2195bf248f09e", size = 408432 }, + { url = "https://files.pythonhosted.org/packages/57/33/085d9352d416e617993821b9d9488222fbb559bc15c3641d6cbd6d16d236/azure_storage_blob-12.25.1-py3-none-any.whl", hash = "sha256:1f337aab12e918ec3f1b638baada97550673911c4ceed892acc8e4e891b74167", size = 406990, upload-time = "2025-03-27T17:13:06.879Z" }, ] [[package]] name = "casadi" -version = "3.6.7" +version = "3.7.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "numpy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/cf/e0/8d2c6a350101b6f73548a1ceba4b93b60e436060ed647e5fb5d5e0b17fed/casadi-3.6.7.tar.gz", hash = "sha256:21cde87288afebb32a2a035bf6b6a91a025e24ee14aba7a0ae5515707b9887c1", size = 5132668 } +sdist = { url = "https://files.pythonhosted.org/packages/b3/49/f8b8eb7c8e98e28e0cca1b41988932025d59a602fb2075f737cbaecf764d/casadi-3.7.0.tar.gz", hash = "sha256:21254f17eb5551c4a938641cc1b815ff3da27271ab2c36e44a3e90ec50ba471f", size = 6027731, upload-time = "2025-03-29T22:31:31.309Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/aa/60/9c1a2492645201e073252107c58bfb029ee703a44c6b9608202ccab01eac/casadi-3.6.7-cp311-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:514b5d2af59c3a60b2a955d9508d5f2c75f05bec1e2f5000043870856e3d41a3", size = 44952900 }, - { url = "https://files.pythonhosted.org/packages/04/84/b8c624aa429a3b3c185f509e7f4152149419085b5087acfcdb3dc4c9e56f/casadi-3.6.7-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:1a7122f3fd4dca0ed9af72bac398de06e225b291b45c3d89b73a19a3247eeeb5", size = 40416205 }, - { url = "https://files.pythonhosted.org/packages/55/07/6aa1b3b258cffee0c100a8339057ad5de338e13dc47518137f72f6e270b2/casadi-3.6.7-cp311-none-manylinux2014_aarch64.whl", hash = "sha256:5c252837354ca9da91bb2c9836921213d3972dad6edf516c9c8ef296e71a4f74", size = 43905544 }, - { url = "https://files.pythonhosted.org/packages/df/8a/9d4301d0968a2f3c743bd2b6a73a2cb28560ff1bcf04b1f65bd8c990f74d/casadi-3.6.7-cp311-none-manylinux2014_i686.whl", hash = "sha256:783976f9016ed2e882f00f3dc81a72abd8424fc6e8d322793d4bd3782a37f96d", size = 70248016 }, - { url = "https://files.pythonhosted.org/packages/44/c6/9579b91b50149e41c3dcc3001027af8a44fcd796a6220968bb214528b18a/casadi-3.6.7-cp311-none-manylinux2014_x86_64.whl", hash = "sha256:971cefbe41e6bde88547c0591ab9424ad1efbe81edc6b0c5a54f125ddffadbf1", size = 73403655 }, - { url = "https://files.pythonhosted.org/packages/b4/71/458735f76f16c7ea24eee326cc8691f642a372fa60f8703228287471bcca/casadi-3.6.7-cp311-none-win_amd64.whl", hash = "sha256:c30904baf2de259979e0e13b99c605cd18c4523aa86170de5940edeb5dd348fa", size = 44689192 }, - { url = "https://files.pythonhosted.org/packages/73/96/1f8323b62c663898179dd0c74edbe09ae94d674eed4ad5eb95c40d3bb49d/casadi-3.6.7-cp312-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:f780e496157ab1caeb6fe19079e4508c2d7a9f5489b298e04c40438a3ba0caf4", size = 44955332 }, - { url = "https://files.pythonhosted.org/packages/9c/49/8a1ff97a94e219142d36c7c0b70d6ad7c79c4927efa53d5a8be29a51a32b/casadi-3.6.7-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:c02a304f5e8b147bca343e84b4de39629e2b761901c1fe99ecffa66c99875b80", size = 40416554 }, - { url = "https://files.pythonhosted.org/packages/5c/dd/242806ccb9d36f6c006d43ad844c752566ed8cc0c0f026a86b3c8c7c2ecb/casadi-3.6.7-cp312-none-manylinux2014_aarch64.whl", hash = "sha256:290e92a7e2f4cecffc229dc196a85855e7dbedf6929eed1850b27e4ad8ad67f0", size = 43904952 }, - { url = "https://files.pythonhosted.org/packages/4e/4c/d6547e51d066df4225a11770360ebcf38532d218fafc07824683ce5253fa/casadi-3.6.7-cp312-none-manylinux2014_i686.whl", hash = "sha256:c7c1502a042efb321da1556e94cc8ef6a035785b9ebcb5ddd4676b32e58d09f8", size = 70246100 }, - { url = "https://files.pythonhosted.org/packages/b5/21/d4bc8c6a492fadecd68128de97595aa8038a6f31fb57159d52a8013e2f06/casadi-3.6.7-cp312-none-manylinux2014_x86_64.whl", hash = "sha256:16042ef095117704312be53389a0f22ab7a0968131db2bf785663d8003957a95", size = 73408033 }, - { url = "https://files.pythonhosted.org/packages/d1/7c/ef71d5988bf4588d298a3b5cbf6ae50621dad4e291f471b5c653ef95b4b8/casadi-3.6.7-cp312-none-win_amd64.whl", hash = "sha256:7f65e7444ddb15f521e0dc5d61b2557054e264de1dea8d9990235336d3e80247", size = 44690057 }, + { url = "https://files.pythonhosted.org/packages/83/cf/7d1dc6b16f690f1fac22a0a43684de3a03b3f631a1d8c25393f320b5f971/casadi-3.7.0-cp311-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:50bba75bb9575baa09a2e25ce3c1968803320c49b9dcc218139321dab02f0400", size = 48302536, upload-time = "2025-03-30T07:31:37.067Z" }, + { url = "https://files.pythonhosted.org/packages/74/d2/f69156aaf4545543995c791a0f97551b66f9c9bc8d92361973ee6378ad25/casadi-3.7.0-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:8f138bf370603f6f820385d78882f840168e8e0866bea5de08b6b54a6e22c093", size = 44713683, upload-time = "2025-03-30T07:33:37.446Z" }, + { url = "https://files.pythonhosted.org/packages/2e/3b/13a7d92c27543e0a2eb559f2a5acc7278f1a2ef0217772b09df50ac1c2dc/casadi-3.7.0-cp311-none-manylinux2014_aarch64.whl", hash = "sha256:4d844a1281c7ff527115d27ee8f2c58315d0008cac835656323a6d502de27010", size = 45518255, upload-time = "2025-03-30T07:36:03.844Z" }, + { url = "https://files.pythonhosted.org/packages/bb/88/00adcb26a0c313ebeaa2db8b2691e37418d6b7c3e06b4a90a3ac9380b91b/casadi-3.7.0-cp311-none-manylinux2014_i686.whl", hash = "sha256:b8640486db98b75a75eb05b6191d5a7f0d44774c36c07c7da327d4d740914284", size = 74329105, upload-time = "2025-03-30T07:39:19.069Z" }, + { url = "https://files.pythonhosted.org/packages/60/64/b31fd4ce5b93f97fd16a9ba7ce8d4a8d36334a518f1ad00525340db31ff4/casadi-3.7.0-cp311-none-manylinux2014_x86_64.whl", hash = "sha256:65d9a61660c75ff8f0c30abf52e2f9cefcdee1cbb9301e26678f64116f509ee7", size = 77330636, upload-time = "2025-03-30T07:46:55.954Z" }, + { url = "https://files.pythonhosted.org/packages/c4/25/79bb6b866a7005186ccdfcb89e01032885a9efa90acfe2d079253685622b/casadi-3.7.0-cp311-none-win_amd64.whl", hash = "sha256:391b5ee886cde28bf813e820958bfcdef98314bd367a93c95e7bef1bf713b886", size = 50949252, upload-time = "2025-03-30T07:49:05.348Z" }, + { url = "https://files.pythonhosted.org/packages/b8/27/6ca4c831d9131eb15ca34346398c1379a577363c264ad47983c1be65b3e1/casadi-3.7.0-cp312-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:ceb4d67c1c5cdf80f233866fcdcaf7d77523115983081fe909b70fe89fd7b708", size = 48303214, upload-time = "2025-03-30T07:51:05.246Z" }, + { url = "https://files.pythonhosted.org/packages/b2/cb/cd8be8aeac6453e2aad96793101fa287f54f86b643d542375969738930c3/casadi-3.7.0-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:83dbc27125044e7600b04af648f24e6924d46e81afe6ff088218e4b7e9a37f08", size = 44713758, upload-time = "2025-03-30T07:52:44.766Z" }, + { url = "https://files.pythonhosted.org/packages/a4/3d/c8a392eac772b1537f63ee16b57be87bcdef9d9bc9530b54c95b1a122960/casadi-3.7.0-cp312-none-manylinux2014_aarch64.whl", hash = "sha256:53731171b41ca0640b76657d2320b929634a137ff30f12f985196df35411885b", size = 45517623, upload-time = "2025-03-30T07:54:25.318Z" }, + { url = "https://files.pythonhosted.org/packages/68/d2/2acd3b8cf8fa25bca342cd539f69dc94b0fa1bf3acaa30f13848fa0f31ee/casadi-3.7.0-cp312-none-manylinux2014_i686.whl", hash = "sha256:6b30fb73d8c140fbbe51e60d00412aaefe5a7b775257a422ea244f423bd2351c", size = 74319729, upload-time = "2025-03-30T07:57:18.329Z" }, + { url = "https://files.pythonhosted.org/packages/0f/35/ec351423c854a74884218501a431e018c6eee79461dde8e91f9ce6b4e2b5/casadi-3.7.0-cp312-none-manylinux2014_x86_64.whl", hash = "sha256:b795371bf09ec0bfd22eaa0a1e81ce2cd3ecd811c9d370b98f6853b87e8397c9", size = 77323153, upload-time = "2025-03-30T08:00:32.507Z" }, + { url = "https://files.pythonhosted.org/packages/d5/4b/ab605b5948795fe15b5930ecc5ac7ba72ebad116a9003c0117421cbe34a8/casadi-3.7.0-cp312-none-win_amd64.whl", hash = "sha256:e77173aad67b817ebf4320c31cef37c7d666f9895bc5970f3370b2ae6fdad587", size = 50946897, upload-time = "2025-03-30T08:02:37.836Z" }, ] [[package]] name = "certifi" -version = "2025.1.31" +version = "2025.4.26" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1c/ab/c9f1e32b7b1bf505bf26f0ef697775960db7932abeb7b516de930ba2705f/certifi-2025.1.31.tar.gz", hash = "sha256:3d5da6925056f6f18f119200434a4780a94263f10d1c21d032a6f6b2baa20651", size = 167577 } +sdist = { url = "https://files.pythonhosted.org/packages/e8/9e/c05b3920a3b7d20d3d3310465f50348e5b3694f4f88c6daf736eef3024c4/certifi-2025.4.26.tar.gz", hash = "sha256:0a816057ea3cdefcef70270d2c515e4506bbc954f417fa5ade2021213bb8f0c6", size = 160705, upload-time = "2025-04-26T02:12:29.51Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/38/fc/bce832fd4fd99766c04d1ee0eead6b0ec6486fb100ae5e74c1d91292b982/certifi-2025.1.31-py3-none-any.whl", hash = "sha256:ca78db4565a652026a4db2bcdf68f2fb589ea80d0be70e03929ed730746b84fe", size = 166393 }, + { url = "https://files.pythonhosted.org/packages/4a/7e/3db2bd1b1f9e95f7cddca6d6e75e2f2bd9f51b1246e546d88addca0106bd/certifi-2025.4.26-py3-none-any.whl", hash = "sha256:30350364dfe371162649852c63336a15c70c6510c2ad5015b21c2345311805f3", size = 159618, upload-time = "2025-04-26T02:12:27.662Z" }, ] [[package]] @@ -231,165 +231,169 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pycparser" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fc/97/c783634659c2920c3fc70419e3af40972dbaf758daa229a7d6ea6135c90d/cffi-1.17.1.tar.gz", hash = "sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824", size = 516621 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/6b/f4/927e3a8899e52a27fa57a48607ff7dc91a9ebe97399b357b85a0c7892e00/cffi-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401", size = 182264 }, - { url = "https://files.pythonhosted.org/packages/6c/f5/6c3a8efe5f503175aaddcbea6ad0d2c96dad6f5abb205750d1b3df44ef29/cffi-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf", size = 178651 }, - { url = "https://files.pythonhosted.org/packages/94/dd/a3f0118e688d1b1a57553da23b16bdade96d2f9bcda4d32e7d2838047ff7/cffi-1.17.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4", size = 445259 }, - { url = "https://files.pythonhosted.org/packages/2e/ea/70ce63780f096e16ce8588efe039d3c4f91deb1dc01e9c73a287939c79a6/cffi-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41", size = 469200 }, - { url = "https://files.pythonhosted.org/packages/1c/a0/a4fa9f4f781bda074c3ddd57a572b060fa0df7655d2a4247bbe277200146/cffi-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1", size = 477235 }, - { url = "https://files.pythonhosted.org/packages/62/12/ce8710b5b8affbcdd5c6e367217c242524ad17a02fe5beec3ee339f69f85/cffi-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6", size = 459721 }, - { url = "https://files.pythonhosted.org/packages/ff/6b/d45873c5e0242196f042d555526f92aa9e0c32355a1be1ff8c27f077fd37/cffi-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d", size = 467242 }, - { url = "https://files.pythonhosted.org/packages/1a/52/d9a0e523a572fbccf2955f5abe883cfa8bcc570d7faeee06336fbd50c9fc/cffi-1.17.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6", size = 477999 }, - { url = "https://files.pythonhosted.org/packages/44/74/f2a2460684a1a2d00ca799ad880d54652841a780c4c97b87754f660c7603/cffi-1.17.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f", size = 454242 }, - { url = "https://files.pythonhosted.org/packages/f8/4a/34599cac7dfcd888ff54e801afe06a19c17787dfd94495ab0c8d35fe99fb/cffi-1.17.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b", size = 478604 }, - { url = "https://files.pythonhosted.org/packages/34/33/e1b8a1ba29025adbdcda5fb3a36f94c03d771c1b7b12f726ff7fef2ebe36/cffi-1.17.1-cp311-cp311-win32.whl", hash = "sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655", size = 171727 }, - { url = "https://files.pythonhosted.org/packages/3d/97/50228be003bb2802627d28ec0627837ac0bf35c90cf769812056f235b2d1/cffi-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0", size = 181400 }, - { url = "https://files.pythonhosted.org/packages/5a/84/e94227139ee5fb4d600a7a4927f322e1d4aea6fdc50bd3fca8493caba23f/cffi-1.17.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4", size = 183178 }, - { url = "https://files.pythonhosted.org/packages/da/ee/fb72c2b48656111c4ef27f0f91da355e130a923473bf5ee75c5643d00cca/cffi-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c", size = 178840 }, - { url = "https://files.pythonhosted.org/packages/cc/b6/db007700f67d151abadf508cbfd6a1884f57eab90b1bb985c4c8c02b0f28/cffi-1.17.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36", size = 454803 }, - { url = "https://files.pythonhosted.org/packages/1a/df/f8d151540d8c200eb1c6fba8cd0dfd40904f1b0682ea705c36e6c2e97ab3/cffi-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5", size = 478850 }, - { url = "https://files.pythonhosted.org/packages/28/c0/b31116332a547fd2677ae5b78a2ef662dfc8023d67f41b2a83f7c2aa78b1/cffi-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff", size = 485729 }, - { url = "https://files.pythonhosted.org/packages/91/2b/9a1ddfa5c7f13cab007a2c9cc295b70fbbda7cb10a286aa6810338e60ea1/cffi-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99", size = 471256 }, - { url = "https://files.pythonhosted.org/packages/b2/d5/da47df7004cb17e4955df6a43d14b3b4ae77737dff8bf7f8f333196717bf/cffi-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93", size = 479424 }, - { url = "https://files.pythonhosted.org/packages/0b/ac/2a28bcf513e93a219c8a4e8e125534f4f6db03e3179ba1c45e949b76212c/cffi-1.17.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3", size = 484568 }, - { url = "https://files.pythonhosted.org/packages/d4/38/ca8a4f639065f14ae0f1d9751e70447a261f1a30fa7547a828ae08142465/cffi-1.17.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8", size = 488736 }, - { url = "https://files.pythonhosted.org/packages/86/c5/28b2d6f799ec0bdecf44dced2ec5ed43e0eb63097b0f58c293583b406582/cffi-1.17.1-cp312-cp312-win32.whl", hash = "sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65", size = 172448 }, - { url = "https://files.pythonhosted.org/packages/50/b9/db34c4755a7bd1cb2d1603ac3863f22bcecbd1ba29e5ee841a4bc510b294/cffi-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903", size = 181976 }, +sdist = { url = "https://files.pythonhosted.org/packages/fc/97/c783634659c2920c3fc70419e3af40972dbaf758daa229a7d6ea6135c90d/cffi-1.17.1.tar.gz", hash = "sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824", size = 516621, upload-time = "2024-09-04T20:45:21.852Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/f4/927e3a8899e52a27fa57a48607ff7dc91a9ebe97399b357b85a0c7892e00/cffi-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401", size = 182264, upload-time = "2024-09-04T20:43:51.124Z" }, + { url = "https://files.pythonhosted.org/packages/6c/f5/6c3a8efe5f503175aaddcbea6ad0d2c96dad6f5abb205750d1b3df44ef29/cffi-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf", size = 178651, upload-time = "2024-09-04T20:43:52.872Z" }, + { url = "https://files.pythonhosted.org/packages/94/dd/a3f0118e688d1b1a57553da23b16bdade96d2f9bcda4d32e7d2838047ff7/cffi-1.17.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4", size = 445259, upload-time = "2024-09-04T20:43:56.123Z" }, + { url = "https://files.pythonhosted.org/packages/2e/ea/70ce63780f096e16ce8588efe039d3c4f91deb1dc01e9c73a287939c79a6/cffi-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41", size = 469200, upload-time = "2024-09-04T20:43:57.891Z" }, + { url = "https://files.pythonhosted.org/packages/1c/a0/a4fa9f4f781bda074c3ddd57a572b060fa0df7655d2a4247bbe277200146/cffi-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1", size = 477235, upload-time = "2024-09-04T20:44:00.18Z" }, + { url = "https://files.pythonhosted.org/packages/62/12/ce8710b5b8affbcdd5c6e367217c242524ad17a02fe5beec3ee339f69f85/cffi-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6", size = 459721, upload-time = "2024-09-04T20:44:01.585Z" }, + { url = "https://files.pythonhosted.org/packages/ff/6b/d45873c5e0242196f042d555526f92aa9e0c32355a1be1ff8c27f077fd37/cffi-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d", size = 467242, upload-time = "2024-09-04T20:44:03.467Z" }, + { url = "https://files.pythonhosted.org/packages/1a/52/d9a0e523a572fbccf2955f5abe883cfa8bcc570d7faeee06336fbd50c9fc/cffi-1.17.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6", size = 477999, upload-time = "2024-09-04T20:44:05.023Z" }, + { url = "https://files.pythonhosted.org/packages/44/74/f2a2460684a1a2d00ca799ad880d54652841a780c4c97b87754f660c7603/cffi-1.17.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f", size = 454242, upload-time = "2024-09-04T20:44:06.444Z" }, + { url = "https://files.pythonhosted.org/packages/f8/4a/34599cac7dfcd888ff54e801afe06a19c17787dfd94495ab0c8d35fe99fb/cffi-1.17.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b", size = 478604, upload-time = "2024-09-04T20:44:08.206Z" }, + { url = "https://files.pythonhosted.org/packages/34/33/e1b8a1ba29025adbdcda5fb3a36f94c03d771c1b7b12f726ff7fef2ebe36/cffi-1.17.1-cp311-cp311-win32.whl", hash = "sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655", size = 171727, upload-time = "2024-09-04T20:44:09.481Z" }, + { url = "https://files.pythonhosted.org/packages/3d/97/50228be003bb2802627d28ec0627837ac0bf35c90cf769812056f235b2d1/cffi-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0", size = 181400, upload-time = "2024-09-04T20:44:10.873Z" }, + { url = "https://files.pythonhosted.org/packages/5a/84/e94227139ee5fb4d600a7a4927f322e1d4aea6fdc50bd3fca8493caba23f/cffi-1.17.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4", size = 183178, upload-time = "2024-09-04T20:44:12.232Z" }, + { url = "https://files.pythonhosted.org/packages/da/ee/fb72c2b48656111c4ef27f0f91da355e130a923473bf5ee75c5643d00cca/cffi-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c", size = 178840, upload-time = "2024-09-04T20:44:13.739Z" }, + { url = "https://files.pythonhosted.org/packages/cc/b6/db007700f67d151abadf508cbfd6a1884f57eab90b1bb985c4c8c02b0f28/cffi-1.17.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36", size = 454803, upload-time = "2024-09-04T20:44:15.231Z" }, + { url = "https://files.pythonhosted.org/packages/1a/df/f8d151540d8c200eb1c6fba8cd0dfd40904f1b0682ea705c36e6c2e97ab3/cffi-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5", size = 478850, upload-time = "2024-09-04T20:44:17.188Z" }, + { url = "https://files.pythonhosted.org/packages/28/c0/b31116332a547fd2677ae5b78a2ef662dfc8023d67f41b2a83f7c2aa78b1/cffi-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff", size = 485729, upload-time = "2024-09-04T20:44:18.688Z" }, + { url = "https://files.pythonhosted.org/packages/91/2b/9a1ddfa5c7f13cab007a2c9cc295b70fbbda7cb10a286aa6810338e60ea1/cffi-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99", size = 471256, upload-time = "2024-09-04T20:44:20.248Z" }, + { url = "https://files.pythonhosted.org/packages/b2/d5/da47df7004cb17e4955df6a43d14b3b4ae77737dff8bf7f8f333196717bf/cffi-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93", size = 479424, upload-time = "2024-09-04T20:44:21.673Z" }, + { url = "https://files.pythonhosted.org/packages/0b/ac/2a28bcf513e93a219c8a4e8e125534f4f6db03e3179ba1c45e949b76212c/cffi-1.17.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3", size = 484568, upload-time = "2024-09-04T20:44:23.245Z" }, + { url = "https://files.pythonhosted.org/packages/d4/38/ca8a4f639065f14ae0f1d9751e70447a261f1a30fa7547a828ae08142465/cffi-1.17.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8", size = 488736, upload-time = "2024-09-04T20:44:24.757Z" }, + { url = "https://files.pythonhosted.org/packages/86/c5/28b2d6f799ec0bdecf44dced2ec5ed43e0eb63097b0f58c293583b406582/cffi-1.17.1-cp312-cp312-win32.whl", hash = "sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65", size = 172448, upload-time = "2024-09-04T20:44:26.208Z" }, + { url = "https://files.pythonhosted.org/packages/50/b9/db34c4755a7bd1cb2d1603ac3863f22bcecbd1ba29e5ee841a4bc510b294/cffi-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903", size = 181976, upload-time = "2024-09-04T20:44:27.578Z" }, ] [[package]] name = "charset-normalizer" -version = "3.4.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/16/b0/572805e227f01586461c80e0fd25d65a2115599cc9dad142fee4b747c357/charset_normalizer-3.4.1.tar.gz", hash = "sha256:44251f18cd68a75b56585dd00dae26183e102cd5e0f9f1466e6df5da2ed64ea3", size = 123188 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/72/80/41ef5d5a7935d2d3a773e3eaebf0a9350542f2cab4eac59a7a4741fbbbbe/charset_normalizer-3.4.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8bfa33f4f2672964266e940dd22a195989ba31669bd84629f05fab3ef4e2d125", size = 194995 }, - { url = "https://files.pythonhosted.org/packages/7a/28/0b9fefa7b8b080ec492110af6d88aa3dea91c464b17d53474b6e9ba5d2c5/charset_normalizer-3.4.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:28bf57629c75e810b6ae989f03c0828d64d6b26a5e205535585f96093e405ed1", size = 139471 }, - { url = "https://files.pythonhosted.org/packages/71/64/d24ab1a997efb06402e3fc07317e94da358e2585165930d9d59ad45fcae2/charset_normalizer-3.4.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f08ff5e948271dc7e18a35641d2f11a4cd8dfd5634f55228b691e62b37125eb3", size = 149831 }, - { url = "https://files.pythonhosted.org/packages/37/ed/be39e5258e198655240db5e19e0b11379163ad7070962d6b0c87ed2c4d39/charset_normalizer-3.4.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:234ac59ea147c59ee4da87a0c0f098e9c8d169f4dc2a159ef720f1a61bbe27cd", size = 142335 }, - { url = "https://files.pythonhosted.org/packages/88/83/489e9504711fa05d8dde1574996408026bdbdbd938f23be67deebb5eca92/charset_normalizer-3.4.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd4ec41f914fa74ad1b8304bbc634b3de73d2a0889bd32076342a573e0779e00", size = 143862 }, - { url = "https://files.pythonhosted.org/packages/c6/c7/32da20821cf387b759ad24627a9aca289d2822de929b8a41b6241767b461/charset_normalizer-3.4.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:eea6ee1db730b3483adf394ea72f808b6e18cf3cb6454b4d86e04fa8c4327a12", size = 145673 }, - { url = "https://files.pythonhosted.org/packages/68/85/f4288e96039abdd5aeb5c546fa20a37b50da71b5cf01e75e87f16cd43304/charset_normalizer-3.4.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c96836c97b1238e9c9e3fe90844c947d5afbf4f4c92762679acfe19927d81d77", size = 140211 }, - { url = "https://files.pythonhosted.org/packages/28/a3/a42e70d03cbdabc18997baf4f0227c73591a08041c149e710045c281f97b/charset_normalizer-3.4.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:4d86f7aff21ee58f26dcf5ae81a9addbd914115cdebcbb2217e4f0ed8982e146", size = 148039 }, - { url = "https://files.pythonhosted.org/packages/85/e4/65699e8ab3014ecbe6f5c71d1a55d810fb716bbfd74f6283d5c2aa87febf/charset_normalizer-3.4.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:09b5e6733cbd160dcc09589227187e242a30a49ca5cefa5a7edd3f9d19ed53fd", size = 151939 }, - { url = "https://files.pythonhosted.org/packages/b1/82/8e9fe624cc5374193de6860aba3ea8070f584c8565ee77c168ec13274bd2/charset_normalizer-3.4.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:5777ee0881f9499ed0f71cc82cf873d9a0ca8af166dfa0af8ec4e675b7df48e6", size = 149075 }, - { url = "https://files.pythonhosted.org/packages/3d/7b/82865ba54c765560c8433f65e8acb9217cb839a9e32b42af4aa8e945870f/charset_normalizer-3.4.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:237bdbe6159cff53b4f24f397d43c6336c6b0b42affbe857970cefbb620911c8", size = 144340 }, - { url = "https://files.pythonhosted.org/packages/b5/b6/9674a4b7d4d99a0d2df9b215da766ee682718f88055751e1e5e753c82db0/charset_normalizer-3.4.1-cp311-cp311-win32.whl", hash = "sha256:8417cb1f36cc0bc7eaba8ccb0e04d55f0ee52df06df3ad55259b9a323555fc8b", size = 95205 }, - { url = "https://files.pythonhosted.org/packages/1e/ab/45b180e175de4402dcf7547e4fb617283bae54ce35c27930a6f35b6bef15/charset_normalizer-3.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:d7f50a1f8c450f3925cb367d011448c39239bb3eb4117c36a6d354794de4ce76", size = 102441 }, - { url = "https://files.pythonhosted.org/packages/0a/9a/dd1e1cdceb841925b7798369a09279bd1cf183cef0f9ddf15a3a6502ee45/charset_normalizer-3.4.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:73d94b58ec7fecbc7366247d3b0b10a21681004153238750bb67bd9012414545", size = 196105 }, - { url = "https://files.pythonhosted.org/packages/d3/8c/90bfabf8c4809ecb648f39794cf2a84ff2e7d2a6cf159fe68d9a26160467/charset_normalizer-3.4.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dad3e487649f498dd991eeb901125411559b22e8d7ab25d3aeb1af367df5efd7", size = 140404 }, - { url = "https://files.pythonhosted.org/packages/ad/8f/e410d57c721945ea3b4f1a04b74f70ce8fa800d393d72899f0a40526401f/charset_normalizer-3.4.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c30197aa96e8eed02200a83fba2657b4c3acd0f0aa4bdc9f6c1af8e8962e0757", size = 150423 }, - { url = "https://files.pythonhosted.org/packages/f0/b8/e6825e25deb691ff98cf5c9072ee0605dc2acfca98af70c2d1b1bc75190d/charset_normalizer-3.4.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2369eea1ee4a7610a860d88f268eb39b95cb588acd7235e02fd5a5601773d4fa", size = 143184 }, - { url = "https://files.pythonhosted.org/packages/3e/a2/513f6cbe752421f16d969e32f3583762bfd583848b763913ddab8d9bfd4f/charset_normalizer-3.4.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bc2722592d8998c870fa4e290c2eec2c1569b87fe58618e67d38b4665dfa680d", size = 145268 }, - { url = "https://files.pythonhosted.org/packages/74/94/8a5277664f27c3c438546f3eb53b33f5b19568eb7424736bdc440a88a31f/charset_normalizer-3.4.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ffc9202a29ab3920fa812879e95a9e78b2465fd10be7fcbd042899695d75e616", size = 147601 }, - { url = "https://files.pythonhosted.org/packages/7c/5f/6d352c51ee763623a98e31194823518e09bfa48be2a7e8383cf691bbb3d0/charset_normalizer-3.4.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:804a4d582ba6e5b747c625bf1255e6b1507465494a40a2130978bda7b932c90b", size = 141098 }, - { url = "https://files.pythonhosted.org/packages/78/d4/f5704cb629ba5ab16d1d3d741396aec6dc3ca2b67757c45b0599bb010478/charset_normalizer-3.4.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:0f55e69f030f7163dffe9fd0752b32f070566451afe180f99dbeeb81f511ad8d", size = 149520 }, - { url = "https://files.pythonhosted.org/packages/c5/96/64120b1d02b81785f222b976c0fb79a35875457fa9bb40827678e54d1bc8/charset_normalizer-3.4.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:c4c3e6da02df6fa1410a7680bd3f63d4f710232d3139089536310d027950696a", size = 152852 }, - { url = "https://files.pythonhosted.org/packages/84/c9/98e3732278a99f47d487fd3468bc60b882920cef29d1fa6ca460a1fdf4e6/charset_normalizer-3.4.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:5df196eb874dae23dcfb968c83d4f8fdccb333330fe1fc278ac5ceeb101003a9", size = 150488 }, - { url = "https://files.pythonhosted.org/packages/13/0e/9c8d4cb99c98c1007cc11eda969ebfe837bbbd0acdb4736d228ccaabcd22/charset_normalizer-3.4.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:e358e64305fe12299a08e08978f51fc21fac060dcfcddd95453eabe5b93ed0e1", size = 146192 }, - { url = "https://files.pythonhosted.org/packages/b2/21/2b6b5b860781a0b49427309cb8670785aa543fb2178de875b87b9cc97746/charset_normalizer-3.4.1-cp312-cp312-win32.whl", hash = "sha256:9b23ca7ef998bc739bf6ffc077c2116917eabcc901f88da1b9856b210ef63f35", size = 95550 }, - { url = "https://files.pythonhosted.org/packages/21/5b/1b390b03b1d16c7e382b561c5329f83cc06623916aab983e8ab9239c7d5c/charset_normalizer-3.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:6ff8a4a60c227ad87030d76e99cd1698345d4491638dfa6673027c48b3cd395f", size = 102785 }, - { url = "https://files.pythonhosted.org/packages/0e/f6/65ecc6878a89bb1c23a086ea335ad4bf21a588990c3f535a227b9eea9108/charset_normalizer-3.4.1-py3-none-any.whl", hash = "sha256:d98b1668f06378c6dbefec3b92299716b931cd4e6061f3c875a71ced1780ab85", size = 49767 }, +version = "3.4.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e4/33/89c2ced2b67d1c2a61c19c6751aa8902d46ce3dacb23600a283619f5a12d/charset_normalizer-3.4.2.tar.gz", hash = "sha256:5baececa9ecba31eff645232d59845c07aa030f0c81ee70184a90d35099a0e63", size = 126367, upload-time = "2025-05-02T08:34:42.01Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/05/85/4c40d00dcc6284a1c1ad5de5e0996b06f39d8232f1031cd23c2f5c07ee86/charset_normalizer-3.4.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:be1e352acbe3c78727a16a455126d9ff83ea2dfdcbc83148d2982305a04714c2", size = 198794, upload-time = "2025-05-02T08:32:11.945Z" }, + { url = "https://files.pythonhosted.org/packages/41/d9/7a6c0b9db952598e97e93cbdfcb91bacd89b9b88c7c983250a77c008703c/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aa88ca0b1932e93f2d961bf3addbb2db902198dca337d88c89e1559e066e7645", size = 142846, upload-time = "2025-05-02T08:32:13.946Z" }, + { url = "https://files.pythonhosted.org/packages/66/82/a37989cda2ace7e37f36c1a8ed16c58cf48965a79c2142713244bf945c89/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d524ba3f1581b35c03cb42beebab4a13e6cdad7b36246bd22541fa585a56cccd", size = 153350, upload-time = "2025-05-02T08:32:15.873Z" }, + { url = "https://files.pythonhosted.org/packages/df/68/a576b31b694d07b53807269d05ec3f6f1093e9545e8607121995ba7a8313/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:28a1005facc94196e1fb3e82a3d442a9d9110b8434fc1ded7a24a2983c9888d8", size = 145657, upload-time = "2025-05-02T08:32:17.283Z" }, + { url = "https://files.pythonhosted.org/packages/92/9b/ad67f03d74554bed3aefd56fe836e1623a50780f7c998d00ca128924a499/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fdb20a30fe1175ecabed17cbf7812f7b804b8a315a25f24678bcdf120a90077f", size = 147260, upload-time = "2025-05-02T08:32:18.807Z" }, + { url = "https://files.pythonhosted.org/packages/a6/e6/8aebae25e328160b20e31a7e9929b1578bbdc7f42e66f46595a432f8539e/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0f5d9ed7f254402c9e7d35d2f5972c9bbea9040e99cd2861bd77dc68263277c7", size = 149164, upload-time = "2025-05-02T08:32:20.333Z" }, + { url = "https://files.pythonhosted.org/packages/8b/f2/b3c2f07dbcc248805f10e67a0262c93308cfa149a4cd3d1fe01f593e5fd2/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:efd387a49825780ff861998cd959767800d54f8308936b21025326de4b5a42b9", size = 144571, upload-time = "2025-05-02T08:32:21.86Z" }, + { url = "https://files.pythonhosted.org/packages/60/5b/c3f3a94bc345bc211622ea59b4bed9ae63c00920e2e8f11824aa5708e8b7/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f0aa37f3c979cf2546b73e8222bbfa3dc07a641585340179d768068e3455e544", size = 151952, upload-time = "2025-05-02T08:32:23.434Z" }, + { url = "https://files.pythonhosted.org/packages/e2/4d/ff460c8b474122334c2fa394a3f99a04cf11c646da895f81402ae54f5c42/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:e70e990b2137b29dc5564715de1e12701815dacc1d056308e2b17e9095372a82", size = 155959, upload-time = "2025-05-02T08:32:24.993Z" }, + { url = "https://files.pythonhosted.org/packages/a2/2b/b964c6a2fda88611a1fe3d4c400d39c66a42d6c169c924818c848f922415/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:0c8c57f84ccfc871a48a47321cfa49ae1df56cd1d965a09abe84066f6853b9c0", size = 153030, upload-time = "2025-05-02T08:32:26.435Z" }, + { url = "https://files.pythonhosted.org/packages/59/2e/d3b9811db26a5ebf444bc0fa4f4be5aa6d76fc6e1c0fd537b16c14e849b6/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6b66f92b17849b85cad91259efc341dce9c1af48e2173bf38a85c6329f1033e5", size = 148015, upload-time = "2025-05-02T08:32:28.376Z" }, + { url = "https://files.pythonhosted.org/packages/90/07/c5fd7c11eafd561bb51220d600a788f1c8d77c5eef37ee49454cc5c35575/charset_normalizer-3.4.2-cp311-cp311-win32.whl", hash = "sha256:daac4765328a919a805fa5e2720f3e94767abd632ae410a9062dff5412bae65a", size = 98106, upload-time = "2025-05-02T08:32:30.281Z" }, + { url = "https://files.pythonhosted.org/packages/a8/05/5e33dbef7e2f773d672b6d79f10ec633d4a71cd96db6673625838a4fd532/charset_normalizer-3.4.2-cp311-cp311-win_amd64.whl", hash = "sha256:e53efc7c7cee4c1e70661e2e112ca46a575f90ed9ae3fef200f2a25e954f4b28", size = 105402, upload-time = "2025-05-02T08:32:32.191Z" }, + { url = "https://files.pythonhosted.org/packages/d7/a4/37f4d6035c89cac7930395a35cc0f1b872e652eaafb76a6075943754f095/charset_normalizer-3.4.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0c29de6a1a95f24b9a1aa7aefd27d2487263f00dfd55a77719b530788f75cff7", size = 199936, upload-time = "2025-05-02T08:32:33.712Z" }, + { url = "https://files.pythonhosted.org/packages/ee/8a/1a5e33b73e0d9287274f899d967907cd0bf9c343e651755d9307e0dbf2b3/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cddf7bd982eaa998934a91f69d182aec997c6c468898efe6679af88283b498d3", size = 143790, upload-time = "2025-05-02T08:32:35.768Z" }, + { url = "https://files.pythonhosted.org/packages/66/52/59521f1d8e6ab1482164fa21409c5ef44da3e9f653c13ba71becdd98dec3/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcbe676a55d7445b22c10967bceaaf0ee69407fbe0ece4d032b6eb8d4565982a", size = 153924, upload-time = "2025-05-02T08:32:37.284Z" }, + { url = "https://files.pythonhosted.org/packages/86/2d/fb55fdf41964ec782febbf33cb64be480a6b8f16ded2dbe8db27a405c09f/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d41c4d287cfc69060fa91cae9683eacffad989f1a10811995fa309df656ec214", size = 146626, upload-time = "2025-05-02T08:32:38.803Z" }, + { url = "https://files.pythonhosted.org/packages/8c/73/6ede2ec59bce19b3edf4209d70004253ec5f4e319f9a2e3f2f15601ed5f7/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4e594135de17ab3866138f496755f302b72157d115086d100c3f19370839dd3a", size = 148567, upload-time = "2025-05-02T08:32:40.251Z" }, + { url = "https://files.pythonhosted.org/packages/09/14/957d03c6dc343c04904530b6bef4e5efae5ec7d7990a7cbb868e4595ee30/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:cf713fe9a71ef6fd5adf7a79670135081cd4431c2943864757f0fa3a65b1fafd", size = 150957, upload-time = "2025-05-02T08:32:41.705Z" }, + { url = "https://files.pythonhosted.org/packages/0d/c8/8174d0e5c10ccebdcb1b53cc959591c4c722a3ad92461a273e86b9f5a302/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a370b3e078e418187da8c3674eddb9d983ec09445c99a3a263c2011993522981", size = 145408, upload-time = "2025-05-02T08:32:43.709Z" }, + { url = "https://files.pythonhosted.org/packages/58/aa/8904b84bc8084ac19dc52feb4f5952c6df03ffb460a887b42615ee1382e8/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:a955b438e62efdf7e0b7b52a64dc5c3396e2634baa62471768a64bc2adb73d5c", size = 153399, upload-time = "2025-05-02T08:32:46.197Z" }, + { url = "https://files.pythonhosted.org/packages/c2/26/89ee1f0e264d201cb65cf054aca6038c03b1a0c6b4ae998070392a3ce605/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:7222ffd5e4de8e57e03ce2cef95a4c43c98fcb72ad86909abdfc2c17d227fc1b", size = 156815, upload-time = "2025-05-02T08:32:48.105Z" }, + { url = "https://files.pythonhosted.org/packages/fd/07/68e95b4b345bad3dbbd3a8681737b4338ff2c9df29856a6d6d23ac4c73cb/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:bee093bf902e1d8fc0ac143c88902c3dfc8941f7ea1d6a8dd2bcb786d33db03d", size = 154537, upload-time = "2025-05-02T08:32:49.719Z" }, + { url = "https://files.pythonhosted.org/packages/77/1a/5eefc0ce04affb98af07bc05f3bac9094513c0e23b0562d64af46a06aae4/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:dedb8adb91d11846ee08bec4c8236c8549ac721c245678282dcb06b221aab59f", size = 149565, upload-time = "2025-05-02T08:32:51.404Z" }, + { url = "https://files.pythonhosted.org/packages/37/a0/2410e5e6032a174c95e0806b1a6585eb21e12f445ebe239fac441995226a/charset_normalizer-3.4.2-cp312-cp312-win32.whl", hash = "sha256:db4c7bf0e07fc3b7d89ac2a5880a6a8062056801b83ff56d8464b70f65482b6c", size = 98357, upload-time = "2025-05-02T08:32:53.079Z" }, + { url = "https://files.pythonhosted.org/packages/6c/4f/c02d5c493967af3eda9c771ad4d2bbc8df6f99ddbeb37ceea6e8716a32bc/charset_normalizer-3.4.2-cp312-cp312-win_amd64.whl", hash = "sha256:5a9979887252a82fefd3d3ed2a8e3b937a7a809f65dcb1e068b090e165bbe99e", size = 105776, upload-time = "2025-05-02T08:32:54.573Z" }, + { url = "https://files.pythonhosted.org/packages/20/94/c5790835a017658cbfabd07f3bfb549140c3ac458cfc196323996b10095a/charset_normalizer-3.4.2-py3-none-any.whl", hash = "sha256:7f56930ab0abd1c45cd15be65cc741c28b1c9a34876ce8c17a2fa107810c0af0", size = 52626, upload-time = "2025-05-02T08:34:40.053Z" }, ] [[package]] name = "click" -version = "8.1.8" +version = "8.2.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "sys_platform == 'win32'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b9/2e/0090cbf739cee7d23781ad4b89a9894a41538e4fcf4c31dcdd705b78eb8b/click-8.1.8.tar.gz", hash = "sha256:ed53c9d8990d83c2a27deae68e4ee337473f6330c040a31d4225c9574d16096a", size = 226593 } +sdist = { url = "https://files.pythonhosted.org/packages/cd/0f/62ca20172d4f87d93cf89665fbaedcd560ac48b465bd1d92bfc7ea6b0a41/click-8.2.0.tar.gz", hash = "sha256:f5452aeddd9988eefa20f90f05ab66f17fce1ee2a36907fd30b05bbb5953814d", size = 235857, upload-time = "2025-05-10T22:21:03.111Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7e/d4/7ebdbd03970677812aac39c869717059dbb71a4cfc033ca6e5221787892c/click-8.1.8-py3-none-any.whl", hash = "sha256:63c132bbbed01578a06712a2d1f497bb62d9c1c0d329b7903a866228027263b2", size = 98188 }, + { url = "https://files.pythonhosted.org/packages/a2/58/1f37bf81e3c689cc74ffa42102fa8915b59085f54a6e4a80bc6265c0f6bf/click-8.2.0-py3-none-any.whl", hash = "sha256:6b303f0b2aa85f1cb4e5303078fadcbcd4e476f114fab9b5007005711839325c", size = 102156, upload-time = "2025-05-10T22:21:01.352Z" }, ] [[package]] name = "cloudpickle" version = "3.1.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/52/39/069100b84d7418bc358d81669d5748efb14b9cceacd2f9c75f550424132f/cloudpickle-3.1.1.tar.gz", hash = "sha256:b216fa8ae4019d5482a8ac3c95d8f6346115d8835911fd4aefd1a445e4242c64", size = 22113 } +sdist = { url = "https://files.pythonhosted.org/packages/52/39/069100b84d7418bc358d81669d5748efb14b9cceacd2f9c75f550424132f/cloudpickle-3.1.1.tar.gz", hash = "sha256:b216fa8ae4019d5482a8ac3c95d8f6346115d8835911fd4aefd1a445e4242c64", size = 22113, upload-time = "2025-01-14T17:02:05.085Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7e/e8/64c37fadfc2816a7701fa8a6ed8d87327c7d54eacfbfb6edab14a2f2be75/cloudpickle-3.1.1-py3-none-any.whl", hash = "sha256:c8c5a44295039331ee9dad40ba100a9c7297b6f988e50e87ccdf3765a668350e", size = 20992 }, + { url = "https://files.pythonhosted.org/packages/7e/e8/64c37fadfc2816a7701fa8a6ed8d87327c7d54eacfbfb6edab14a2f2be75/cloudpickle-3.1.1-py3-none-any.whl", hash = "sha256:c8c5a44295039331ee9dad40ba100a9c7297b6f988e50e87ccdf3765a668350e", size = 20992, upload-time = "2025-01-14T17:02:02.417Z" }, ] [[package]] name = "codespell" version = "2.4.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/15/e0/709453393c0ea77d007d907dd436b3ee262e28b30995ea1aa36c6ffbccaf/codespell-2.4.1.tar.gz", hash = "sha256:299fcdcb09d23e81e35a671bbe746d5ad7e8385972e65dbb833a2eaac33c01e5", size = 344740 } +sdist = { url = "https://files.pythonhosted.org/packages/15/e0/709453393c0ea77d007d907dd436b3ee262e28b30995ea1aa36c6ffbccaf/codespell-2.4.1.tar.gz", hash = "sha256:299fcdcb09d23e81e35a671bbe746d5ad7e8385972e65dbb833a2eaac33c01e5", size = 344740, upload-time = "2025-01-28T18:52:39.411Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/20/01/b394922252051e97aab231d416c86da3d8a6d781eeadcdca1082867de64e/codespell-2.4.1-py3-none-any.whl", hash = "sha256:3dadafa67df7e4a3dbf51e0d7315061b80d265f9552ebd699b3dd6834b47e425", size = 344501 }, + { url = "https://files.pythonhosted.org/packages/20/01/b394922252051e97aab231d416c86da3d8a6d781eeadcdca1082867de64e/codespell-2.4.1-py3-none-any.whl", hash = "sha256:3dadafa67df7e4a3dbf51e0d7315061b80d265f9552ebd699b3dd6834b47e425", size = 344501, upload-time = "2025-01-28T18:52:37.057Z" }, ] [[package]] name = "colorama" version = "0.4.6" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d8/53/6f443c9a4a8358a93a6792e2acffb9d9d5cb0a5cfd8802644b7b1c9a02e4/colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44", size = 27697 } +sdist = { url = "https://files.pythonhosted.org/packages/d8/53/6f443c9a4a8358a93a6792e2acffb9d9d5cb0a5cfd8802644b7b1c9a02e4/colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44", size = 27697, upload-time = "2022-10-25T02:36:22.414Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d1/d6/3965ed04c63042e047cb6a3e6ed1a63a35087b6a609aa3a15ed8ac56c221/colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6", size = 25335 }, + { url = "https://files.pythonhosted.org/packages/d1/d6/3965ed04c63042e047cb6a3e6ed1a63a35087b6a609aa3a15ed8ac56c221/colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6", size = 25335, upload-time = "2022-10-25T02:36:20.889Z" }, ] [[package]] name = "contourpy" -version = "1.3.1" +version = "1.3.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "numpy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/25/c2/fc7193cc5383637ff390a712e88e4ded0452c9fbcf84abe3de5ea3df1866/contourpy-1.3.1.tar.gz", hash = "sha256:dfd97abd83335045a913e3bcc4a09c0ceadbe66580cf573fe961f4a825efa699", size = 13465753 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/12/bb/11250d2906ee2e8b466b5f93e6b19d525f3e0254ac8b445b56e618527718/contourpy-1.3.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3e8b974d8db2c5610fb4e76307e265de0edb655ae8169e8b21f41807ccbeec4b", size = 269555 }, - { url = "https://files.pythonhosted.org/packages/67/71/1e6e95aee21a500415f5d2dbf037bf4567529b6a4e986594d7026ec5ae90/contourpy-1.3.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:20914c8c973f41456337652a6eeca26d2148aa96dd7ac323b74516988bea89fc", size = 254549 }, - { url = "https://files.pythonhosted.org/packages/31/2c/b88986e8d79ac45efe9d8801ae341525f38e087449b6c2f2e6050468a42c/contourpy-1.3.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:19d40d37c1c3a4961b4619dd9d77b12124a453cc3d02bb31a07d58ef684d3d86", size = 313000 }, - { url = "https://files.pythonhosted.org/packages/c4/18/65280989b151fcf33a8352f992eff71e61b968bef7432fbfde3a364f0730/contourpy-1.3.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:113231fe3825ebf6f15eaa8bc1f5b0ddc19d42b733345eae0934cb291beb88b6", size = 352925 }, - { url = "https://files.pythonhosted.org/packages/f5/c7/5fd0146c93220dbfe1a2e0f98969293b86ca9bc041d6c90c0e065f4619ad/contourpy-1.3.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4dbbc03a40f916a8420e420d63e96a1258d3d1b58cbdfd8d1f07b49fcbd38e85", size = 323693 }, - { url = "https://files.pythonhosted.org/packages/85/fc/7fa5d17daf77306840a4e84668a48ddff09e6bc09ba4e37e85ffc8e4faa3/contourpy-1.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a04ecd68acbd77fa2d39723ceca4c3197cb2969633836ced1bea14e219d077c", size = 326184 }, - { url = "https://files.pythonhosted.org/packages/ef/e7/104065c8270c7397c9571620d3ab880558957216f2b5ebb7e040f85eeb22/contourpy-1.3.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c414fc1ed8ee1dbd5da626cf3710c6013d3d27456651d156711fa24f24bd1291", size = 1268031 }, - { url = "https://files.pythonhosted.org/packages/e2/4a/c788d0bdbf32c8113c2354493ed291f924d4793c4a2e85b69e737a21a658/contourpy-1.3.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:31c1b55c1f34f80557d3830d3dd93ba722ce7e33a0b472cba0ec3b6535684d8f", size = 1325995 }, - { url = "https://files.pythonhosted.org/packages/a6/e6/a2f351a90d955f8b0564caf1ebe4b1451a3f01f83e5e3a414055a5b8bccb/contourpy-1.3.1-cp311-cp311-win32.whl", hash = "sha256:f611e628ef06670df83fce17805c344710ca5cde01edfdc72751311da8585375", size = 174396 }, - { url = "https://files.pythonhosted.org/packages/a8/7e/cd93cab453720a5d6cb75588cc17dcdc08fc3484b9de98b885924ff61900/contourpy-1.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:b2bdca22a27e35f16794cf585832e542123296b4687f9fd96822db6bae17bfc9", size = 219787 }, - { url = "https://files.pythonhosted.org/packages/37/6b/175f60227d3e7f5f1549fcb374592be311293132207e451c3d7c654c25fb/contourpy-1.3.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:0ffa84be8e0bd33410b17189f7164c3589c229ce5db85798076a3fa136d0e509", size = 271494 }, - { url = "https://files.pythonhosted.org/packages/6b/6a/7833cfae2c1e63d1d8875a50fd23371394f540ce809d7383550681a1fa64/contourpy-1.3.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:805617228ba7e2cbbfb6c503858e626ab528ac2a32a04a2fe88ffaf6b02c32bc", size = 255444 }, - { url = "https://files.pythonhosted.org/packages/7f/b3/7859efce66eaca5c14ba7619791b084ed02d868d76b928ff56890d2d059d/contourpy-1.3.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ade08d343436a94e633db932e7e8407fe7de8083967962b46bdfc1b0ced39454", size = 307628 }, - { url = "https://files.pythonhosted.org/packages/48/b2/011415f5e3f0a50b1e285a0bf78eb5d92a4df000553570f0851b6e309076/contourpy-1.3.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:47734d7073fb4590b4a40122b35917cd77be5722d80683b249dac1de266aac80", size = 347271 }, - { url = "https://files.pythonhosted.org/packages/84/7d/ef19b1db0f45b151ac78c65127235239a8cf21a59d1ce8507ce03e89a30b/contourpy-1.3.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2ba94a401342fc0f8b948e57d977557fbf4d515f03c67682dd5c6191cb2d16ec", size = 318906 }, - { url = "https://files.pythonhosted.org/packages/ba/99/6794142b90b853a9155316c8f470d2e4821fe6f086b03e372aca848227dd/contourpy-1.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:efa874e87e4a647fd2e4f514d5e91c7d493697127beb95e77d2f7561f6905bd9", size = 323622 }, - { url = "https://files.pythonhosted.org/packages/3c/0f/37d2c84a900cd8eb54e105f4fa9aebd275e14e266736778bb5dccbf3bbbb/contourpy-1.3.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1bf98051f1045b15c87868dbaea84f92408337d4f81d0e449ee41920ea121d3b", size = 1266699 }, - { url = "https://files.pythonhosted.org/packages/3a/8a/deb5e11dc7d9cc8f0f9c8b29d4f062203f3af230ba83c30a6b161a6effc9/contourpy-1.3.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:61332c87493b00091423e747ea78200659dc09bdf7fd69edd5e98cef5d3e9a8d", size = 1326395 }, - { url = "https://files.pythonhosted.org/packages/1a/35/7e267ae7c13aaf12322ccc493531f1e7f2eb8fba2927b9d7a05ff615df7a/contourpy-1.3.1-cp312-cp312-win32.whl", hash = "sha256:e914a8cb05ce5c809dd0fe350cfbb4e881bde5e2a38dc04e3afe1b3e58bd158e", size = 175354 }, - { url = "https://files.pythonhosted.org/packages/a1/35/c2de8823211d07e8a79ab018ef03960716c5dff6f4d5bff5af87fd682992/contourpy-1.3.1-cp312-cp312-win_amd64.whl", hash = "sha256:08d9d449a61cf53033612cb368f3a1b26cd7835d9b8cd326647efe43bca7568d", size = 220971 }, +sdist = { url = "https://files.pythonhosted.org/packages/66/54/eb9bfc647b19f2009dd5c7f5ec51c4e6ca831725f1aea7a993034f483147/contourpy-1.3.2.tar.gz", hash = "sha256:b6945942715a034c671b7fc54f9588126b0b8bf23db2696e3ca8328f3ff0ab54", size = 13466130, upload-time = "2025-04-15T17:47:53.79Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/b3/b9/ede788a0b56fc5b071639d06c33cb893f68b1178938f3425debebe2dab78/contourpy-1.3.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6a37a2fb93d4df3fc4c0e363ea4d16f83195fc09c891bc8ce072b9d084853445", size = 269636, upload-time = "2025-04-15T17:35:54.473Z" }, + { url = "https://files.pythonhosted.org/packages/e6/75/3469f011d64b8bbfa04f709bfc23e1dd71be54d05b1b083be9f5b22750d1/contourpy-1.3.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b7cd50c38f500bbcc9b6a46643a40e0913673f869315d8e70de0438817cb7773", size = 254636, upload-time = "2025-04-15T17:35:58.283Z" }, + { url = "https://files.pythonhosted.org/packages/8d/2f/95adb8dae08ce0ebca4fd8e7ad653159565d9739128b2d5977806656fcd2/contourpy-1.3.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d6658ccc7251a4433eebd89ed2672c2ed96fba367fd25ca9512aa92a4b46c4f1", size = 313053, upload-time = "2025-04-15T17:36:03.235Z" }, + { url = "https://files.pythonhosted.org/packages/c3/a6/8ccf97a50f31adfa36917707fe39c9a0cbc24b3bbb58185577f119736cc9/contourpy-1.3.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:70771a461aaeb335df14deb6c97439973d253ae70660ca085eec25241137ef43", size = 352985, upload-time = "2025-04-15T17:36:08.275Z" }, + { url = "https://files.pythonhosted.org/packages/1d/b6/7925ab9b77386143f39d9c3243fdd101621b4532eb126743201160ffa7e6/contourpy-1.3.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:65a887a6e8c4cd0897507d814b14c54a8c2e2aa4ac9f7686292f9769fcf9a6ab", size = 323750, upload-time = "2025-04-15T17:36:13.29Z" }, + { url = "https://files.pythonhosted.org/packages/c2/f3/20c5d1ef4f4748e52d60771b8560cf00b69d5c6368b5c2e9311bcfa2a08b/contourpy-1.3.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3859783aefa2b8355697f16642695a5b9792e7a46ab86da1118a4a23a51a33d7", size = 326246, upload-time = "2025-04-15T17:36:18.329Z" }, + { url = "https://files.pythonhosted.org/packages/8c/e5/9dae809e7e0b2d9d70c52b3d24cba134dd3dad979eb3e5e71f5df22ed1f5/contourpy-1.3.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:eab0f6db315fa4d70f1d8ab514e527f0366ec021ff853d7ed6a2d33605cf4b83", size = 1308728, upload-time = "2025-04-15T17:36:33.878Z" }, + { url = "https://files.pythonhosted.org/packages/e2/4a/0058ba34aeea35c0b442ae61a4f4d4ca84d6df8f91309bc2d43bb8dd248f/contourpy-1.3.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d91a3ccc7fea94ca0acab82ceb77f396d50a1f67412efe4c526f5d20264e6ecd", size = 1375762, upload-time = "2025-04-15T17:36:51.295Z" }, + { url = "https://files.pythonhosted.org/packages/09/33/7174bdfc8b7767ef2c08ed81244762d93d5c579336fc0b51ca57b33d1b80/contourpy-1.3.2-cp311-cp311-win32.whl", hash = "sha256:1c48188778d4d2f3d48e4643fb15d8608b1d01e4b4d6b0548d9b336c28fc9b6f", size = 178196, upload-time = "2025-04-15T17:36:55.002Z" }, + { url = "https://files.pythonhosted.org/packages/5e/fe/4029038b4e1c4485cef18e480b0e2cd2d755448bb071eb9977caac80b77b/contourpy-1.3.2-cp311-cp311-win_amd64.whl", hash = "sha256:5ebac872ba09cb8f2131c46b8739a7ff71de28a24c869bcad554477eb089a878", size = 222017, upload-time = "2025-04-15T17:36:58.576Z" }, + { url = "https://files.pythonhosted.org/packages/34/f7/44785876384eff370c251d58fd65f6ad7f39adce4a093c934d4a67a7c6b6/contourpy-1.3.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4caf2bcd2969402bf77edc4cb6034c7dd7c0803213b3523f111eb7460a51b8d2", size = 271580, upload-time = "2025-04-15T17:37:03.105Z" }, + { url = "https://files.pythonhosted.org/packages/93/3b/0004767622a9826ea3d95f0e9d98cd8729015768075d61f9fea8eeca42a8/contourpy-1.3.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:82199cb78276249796419fe36b7386bd8d2cc3f28b3bc19fe2454fe2e26c4c15", size = 255530, upload-time = "2025-04-15T17:37:07.026Z" }, + { url = "https://files.pythonhosted.org/packages/e7/bb/7bd49e1f4fa805772d9fd130e0d375554ebc771ed7172f48dfcd4ca61549/contourpy-1.3.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:106fab697af11456fcba3e352ad50effe493a90f893fca6c2ca5c033820cea92", size = 307688, upload-time = "2025-04-15T17:37:11.481Z" }, + { url = "https://files.pythonhosted.org/packages/fc/97/e1d5dbbfa170725ef78357a9a0edc996b09ae4af170927ba8ce977e60a5f/contourpy-1.3.2-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d14f12932a8d620e307f715857107b1d1845cc44fdb5da2bc8e850f5ceba9f87", size = 347331, upload-time = "2025-04-15T17:37:18.212Z" }, + { url = "https://files.pythonhosted.org/packages/6f/66/e69e6e904f5ecf6901be3dd16e7e54d41b6ec6ae3405a535286d4418ffb4/contourpy-1.3.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:532fd26e715560721bb0d5fc7610fce279b3699b018600ab999d1be895b09415", size = 318963, upload-time = "2025-04-15T17:37:22.76Z" }, + { url = "https://files.pythonhosted.org/packages/a8/32/b8a1c8965e4f72482ff2d1ac2cd670ce0b542f203c8e1d34e7c3e6925da7/contourpy-1.3.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f26b383144cf2d2c29f01a1e8170f50dacf0eac02d64139dcd709a8ac4eb3cfe", size = 323681, upload-time = "2025-04-15T17:37:33.001Z" }, + { url = "https://files.pythonhosted.org/packages/30/c6/12a7e6811d08757c7162a541ca4c5c6a34c0f4e98ef2b338791093518e40/contourpy-1.3.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:c49f73e61f1f774650a55d221803b101d966ca0c5a2d6d5e4320ec3997489441", size = 1308674, upload-time = "2025-04-15T17:37:48.64Z" }, + { url = "https://files.pythonhosted.org/packages/2a/8a/bebe5a3f68b484d3a2b8ffaf84704b3e343ef1addea528132ef148e22b3b/contourpy-1.3.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3d80b2c0300583228ac98d0a927a1ba6a2ba6b8a742463c564f1d419ee5b211e", size = 1380480, upload-time = "2025-04-15T17:38:06.7Z" }, + { url = "https://files.pythonhosted.org/packages/34/db/fcd325f19b5978fb509a7d55e06d99f5f856294c1991097534360b307cf1/contourpy-1.3.2-cp312-cp312-win32.whl", hash = "sha256:90df94c89a91b7362e1142cbee7568f86514412ab8a2c0d0fca72d7e91b62912", size = 178489, upload-time = "2025-04-15T17:38:10.338Z" }, + { url = "https://files.pythonhosted.org/packages/01/c8/fadd0b92ffa7b5eb5949bf340a63a4a496a6930a6c37a7ba0f12acb076d6/contourpy-1.3.2-cp312-cp312-win_amd64.whl", hash = "sha256:8c942a01d9163e2e5cfb05cb66110121b8d07ad438a17f9e766317bcb62abf73", size = 223042, upload-time = "2025-04-15T17:38:14.239Z" }, + { url = "https://files.pythonhosted.org/packages/ff/c0/91f1215d0d9f9f343e4773ba6c9b89e8c0cc7a64a6263f21139da639d848/contourpy-1.3.2-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:5f5964cdad279256c084b69c3f412b7801e15356b16efa9d78aa974041903da0", size = 266807, upload-time = "2025-04-15T17:45:15.535Z" }, + { url = "https://files.pythonhosted.org/packages/d4/79/6be7e90c955c0487e7712660d6cead01fa17bff98e0ea275737cc2bc8e71/contourpy-1.3.2-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:49b65a95d642d4efa8f64ba12558fcb83407e58a2dfba9d796d77b63ccfcaff5", size = 318729, upload-time = "2025-04-15T17:45:20.166Z" }, + { url = "https://files.pythonhosted.org/packages/87/68/7f46fb537958e87427d98a4074bcde4b67a70b04900cfc5ce29bc2f556c1/contourpy-1.3.2-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:8c5acb8dddb0752bf252e01a3035b21443158910ac16a3b0d20e7fed7d534ce5", size = 221791, upload-time = "2025-04-15T17:45:24.794Z" }, ] [[package]] name = "coverage" -version = "7.6.12" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/0c/d6/2b53ab3ee99f2262e6f0b8369a43f6d66658eab45510331c0b3d5c8c4272/coverage-7.6.12.tar.gz", hash = "sha256:48cfc4641d95d34766ad41d9573cc0f22a48aa88d22657a1fe01dca0dbae4de2", size = 805941 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/64/2d/da78abbfff98468c91fd63a73cccdfa0e99051676ded8dd36123e3a2d4d5/coverage-7.6.12-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:e18aafdfb3e9ec0d261c942d35bd7c28d031c5855dadb491d2723ba54f4c3015", size = 208464 }, - { url = "https://files.pythonhosted.org/packages/31/f2/c269f46c470bdabe83a69e860c80a82e5e76840e9f4bbd7f38f8cebbee2f/coverage-7.6.12-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:66fe626fd7aa5982cdebad23e49e78ef7dbb3e3c2a5960a2b53632f1f703ea45", size = 208893 }, - { url = "https://files.pythonhosted.org/packages/47/63/5682bf14d2ce20819998a49c0deadb81e608a59eed64d6bc2191bc8046b9/coverage-7.6.12-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ef01d70198431719af0b1f5dcbefc557d44a190e749004042927b2a3fed0702", size = 241545 }, - { url = "https://files.pythonhosted.org/packages/6a/b6/6b6631f1172d437e11067e1c2edfdb7238b65dff965a12bce3b6d1bf2be2/coverage-7.6.12-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:07e92ae5a289a4bc4c0aae710c0948d3c7892e20fd3588224ebe242039573bf0", size = 239230 }, - { url = "https://files.pythonhosted.org/packages/c7/01/9cd06cbb1be53e837e16f1b4309f6357e2dfcbdab0dd7cd3b1a50589e4e1/coverage-7.6.12-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e695df2c58ce526eeab11a2e915448d3eb76f75dffe338ea613c1201b33bab2f", size = 241013 }, - { url = "https://files.pythonhosted.org/packages/4b/26/56afefc03c30871326e3d99709a70d327ac1f33da383cba108c79bd71563/coverage-7.6.12-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d74c08e9aaef995f8c4ef6d202dbd219c318450fe2a76da624f2ebb9c8ec5d9f", size = 239750 }, - { url = "https://files.pythonhosted.org/packages/dd/ea/88a1ff951ed288f56aa561558ebe380107cf9132facd0b50bced63ba7238/coverage-7.6.12-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:e995b3b76ccedc27fe4f477b349b7d64597e53a43fc2961db9d3fbace085d69d", size = 238462 }, - { url = "https://files.pythonhosted.org/packages/6e/d4/1d9404566f553728889409eff82151d515fbb46dc92cbd13b5337fa0de8c/coverage-7.6.12-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b1f097878d74fe51e1ddd1be62d8e3682748875b461232cf4b52ddc6e6db0bba", size = 239307 }, - { url = "https://files.pythonhosted.org/packages/12/c1/e453d3b794cde1e232ee8ac1d194fde8e2ba329c18bbf1b93f6f5eef606b/coverage-7.6.12-cp311-cp311-win32.whl", hash = "sha256:1f7ffa05da41754e20512202c866d0ebfc440bba3b0ed15133070e20bf5aeb5f", size = 211117 }, - { url = "https://files.pythonhosted.org/packages/d5/db/829185120c1686fa297294f8fcd23e0422f71070bf85ef1cc1a72ecb2930/coverage-7.6.12-cp311-cp311-win_amd64.whl", hash = "sha256:e216c5c45f89ef8971373fd1c5d8d1164b81f7f5f06bbf23c37e7908d19e8558", size = 212019 }, - { url = "https://files.pythonhosted.org/packages/e2/7f/4af2ed1d06ce6bee7eafc03b2ef748b14132b0bdae04388e451e4b2c529b/coverage-7.6.12-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:b172f8e030e8ef247b3104902cc671e20df80163b60a203653150d2fc204d1ad", size = 208645 }, - { url = "https://files.pythonhosted.org/packages/dc/60/d19df912989117caa95123524d26fc973f56dc14aecdec5ccd7d0084e131/coverage-7.6.12-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:641dfe0ab73deb7069fb972d4d9725bf11c239c309ce694dd50b1473c0f641c3", size = 208898 }, - { url = "https://files.pythonhosted.org/packages/bd/10/fecabcf438ba676f706bf90186ccf6ff9f6158cc494286965c76e58742fa/coverage-7.6.12-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0e549f54ac5f301e8e04c569dfdb907f7be71b06b88b5063ce9d6953d2d58574", size = 242987 }, - { url = "https://files.pythonhosted.org/packages/4c/53/4e208440389e8ea936f5f2b0762dcd4cb03281a7722def8e2bf9dc9c3d68/coverage-7.6.12-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:959244a17184515f8c52dcb65fb662808767c0bd233c1d8a166e7cf74c9ea985", size = 239881 }, - { url = "https://files.pythonhosted.org/packages/c4/47/2ba744af8d2f0caa1f17e7746147e34dfc5f811fb65fc153153722d58835/coverage-7.6.12-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bda1c5f347550c359f841d6614fb8ca42ae5cb0b74d39f8a1e204815ebe25750", size = 242142 }, - { url = "https://files.pythonhosted.org/packages/e9/90/df726af8ee74d92ee7e3bf113bf101ea4315d71508952bd21abc3fae471e/coverage-7.6.12-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1ceeb90c3eda1f2d8c4c578c14167dbd8c674ecd7d38e45647543f19839dd6ea", size = 241437 }, - { url = "https://files.pythonhosted.org/packages/f6/af/995263fd04ae5f9cf12521150295bf03b6ba940d0aea97953bb4a6db3e2b/coverage-7.6.12-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:0f16f44025c06792e0fb09571ae454bcc7a3ec75eeb3c36b025eccf501b1a4c3", size = 239724 }, - { url = "https://files.pythonhosted.org/packages/1c/8e/5bb04f0318805e190984c6ce106b4c3968a9562a400180e549855d8211bd/coverage-7.6.12-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:b076e625396e787448d27a411aefff867db2bffac8ed04e8f7056b07024eed5a", size = 241329 }, - { url = "https://files.pythonhosted.org/packages/9e/9d/fa04d9e6c3f6459f4e0b231925277cfc33d72dfab7fa19c312c03e59da99/coverage-7.6.12-cp312-cp312-win32.whl", hash = "sha256:00b2086892cf06c7c2d74983c9595dc511acca00665480b3ddff749ec4fb2a95", size = 211289 }, - { url = "https://files.pythonhosted.org/packages/53/40/53c7ffe3c0c3fff4d708bc99e65f3d78c129110d6629736faf2dbd60ad57/coverage-7.6.12-cp312-cp312-win_amd64.whl", hash = "sha256:7ae6eabf519bc7871ce117fb18bf14e0e343eeb96c377667e3e5dd12095e0288", size = 212079 }, - { url = "https://files.pythonhosted.org/packages/fb/b2/f655700e1024dec98b10ebaafd0cedbc25e40e4abe62a3c8e2ceef4f8f0a/coverage-7.6.12-py3-none-any.whl", hash = "sha256:eb8668cfbc279a536c633137deeb9435d2962caec279c3f8cf8b91fff6ff8953", size = 200552 }, +version = "7.8.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/19/4f/2251e65033ed2ce1e68f00f91a0294e0f80c80ae8c3ebbe2f12828c4cd53/coverage-7.8.0.tar.gz", hash = "sha256:7a3d62b3b03b4b6fd41a085f3574874cf946cb4604d2b4d3e8dca8cd570ca501", size = 811872, upload-time = "2025-03-30T20:36:45.376Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/2b/77/074d201adb8383addae5784cb8e2dac60bb62bfdf28b2b10f3a3af2fda47/coverage-7.8.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:e7ac22a0bb2c7c49f441f7a6d46c9c80d96e56f5a8bc6972529ed43c8b694e27", size = 211493, upload-time = "2025-03-30T20:35:12.286Z" }, + { url = "https://files.pythonhosted.org/packages/a9/89/7a8efe585750fe59b48d09f871f0e0c028a7b10722b2172dfe021fa2fdd4/coverage-7.8.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bf13d564d310c156d1c8e53877baf2993fb3073b2fc9f69790ca6a732eb4bfea", size = 211921, upload-time = "2025-03-30T20:35:14.18Z" }, + { url = "https://files.pythonhosted.org/packages/e9/ef/96a90c31d08a3f40c49dbe897df4f1fd51fb6583821a1a1c5ee30cc8f680/coverage-7.8.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a5761c70c017c1b0d21b0815a920ffb94a670c8d5d409d9b38857874c21f70d7", size = 244556, upload-time = "2025-03-30T20:35:15.616Z" }, + { url = "https://files.pythonhosted.org/packages/89/97/dcd5c2ce72cee9d7b0ee8c89162c24972fb987a111b92d1a3d1d19100c61/coverage-7.8.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e5ff52d790c7e1628241ffbcaeb33e07d14b007b6eb00a19320c7b8a7024c040", size = 242245, upload-time = "2025-03-30T20:35:18.648Z" }, + { url = "https://files.pythonhosted.org/packages/b2/7b/b63cbb44096141ed435843bbb251558c8e05cc835c8da31ca6ffb26d44c0/coverage-7.8.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d39fc4817fd67b3915256af5dda75fd4ee10621a3d484524487e33416c6f3543", size = 244032, upload-time = "2025-03-30T20:35:20.131Z" }, + { url = "https://files.pythonhosted.org/packages/97/e3/7fa8c2c00a1ef530c2a42fa5df25a6971391f92739d83d67a4ee6dcf7a02/coverage-7.8.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b44674870709017e4b4036e3d0d6c17f06a0e6d4436422e0ad29b882c40697d2", size = 243679, upload-time = "2025-03-30T20:35:21.636Z" }, + { url = "https://files.pythonhosted.org/packages/4f/b3/e0a59d8df9150c8a0c0841d55d6568f0a9195692136c44f3d21f1842c8f6/coverage-7.8.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:8f99eb72bf27cbb167b636eb1726f590c00e1ad375002230607a844d9e9a2318", size = 241852, upload-time = "2025-03-30T20:35:23.525Z" }, + { url = "https://files.pythonhosted.org/packages/9b/82/db347ccd57bcef150c173df2ade97976a8367a3be7160e303e43dd0c795f/coverage-7.8.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b571bf5341ba8c6bc02e0baeaf3b061ab993bf372d982ae509807e7f112554e9", size = 242389, upload-time = "2025-03-30T20:35:25.09Z" }, + { url = "https://files.pythonhosted.org/packages/21/f6/3f7d7879ceb03923195d9ff294456241ed05815281f5254bc16ef71d6a20/coverage-7.8.0-cp311-cp311-win32.whl", hash = "sha256:e75a2ad7b647fd8046d58c3132d7eaf31b12d8a53c0e4b21fa9c4d23d6ee6d3c", size = 213997, upload-time = "2025-03-30T20:35:26.914Z" }, + { url = "https://files.pythonhosted.org/packages/28/87/021189643e18ecf045dbe1e2071b2747901f229df302de01c998eeadf146/coverage-7.8.0-cp311-cp311-win_amd64.whl", hash = "sha256:3043ba1c88b2139126fc72cb48574b90e2e0546d4c78b5299317f61b7f718b78", size = 214911, upload-time = "2025-03-30T20:35:28.498Z" }, + { url = "https://files.pythonhosted.org/packages/aa/12/4792669473297f7973518bec373a955e267deb4339286f882439b8535b39/coverage-7.8.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:bbb5cc845a0292e0c520656d19d7ce40e18d0e19b22cb3e0409135a575bf79fc", size = 211684, upload-time = "2025-03-30T20:35:29.959Z" }, + { url = "https://files.pythonhosted.org/packages/be/e1/2a4ec273894000ebedd789e8f2fc3813fcaf486074f87fd1c5b2cb1c0a2b/coverage-7.8.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4dfd9a93db9e78666d178d4f08a5408aa3f2474ad4d0e0378ed5f2ef71640cb6", size = 211935, upload-time = "2025-03-30T20:35:31.912Z" }, + { url = "https://files.pythonhosted.org/packages/f8/3a/7b14f6e4372786709a361729164125f6b7caf4024ce02e596c4a69bccb89/coverage-7.8.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f017a61399f13aa6d1039f75cd467be388d157cd81f1a119b9d9a68ba6f2830d", size = 245994, upload-time = "2025-03-30T20:35:33.455Z" }, + { url = "https://files.pythonhosted.org/packages/54/80/039cc7f1f81dcbd01ea796d36d3797e60c106077e31fd1f526b85337d6a1/coverage-7.8.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0915742f4c82208ebf47a2b154a5334155ed9ef9fe6190674b8a46c2fb89cb05", size = 242885, upload-time = "2025-03-30T20:35:35.354Z" }, + { url = "https://files.pythonhosted.org/packages/10/e0/dc8355f992b6cc2f9dcd5ef6242b62a3f73264893bc09fbb08bfcab18eb4/coverage-7.8.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8a40fcf208e021eb14b0fac6bdb045c0e0cab53105f93ba0d03fd934c956143a", size = 245142, upload-time = "2025-03-30T20:35:37.121Z" }, + { url = "https://files.pythonhosted.org/packages/43/1b/33e313b22cf50f652becb94c6e7dae25d8f02e52e44db37a82de9ac357e8/coverage-7.8.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a1f406a8e0995d654b2ad87c62caf6befa767885301f3b8f6f73e6f3c31ec3a6", size = 244906, upload-time = "2025-03-30T20:35:39.07Z" }, + { url = "https://files.pythonhosted.org/packages/05/08/c0a8048e942e7f918764ccc99503e2bccffba1c42568693ce6955860365e/coverage-7.8.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:77af0f6447a582fdc7de5e06fa3757a3ef87769fbb0fdbdeba78c23049140a47", size = 243124, upload-time = "2025-03-30T20:35:40.598Z" }, + { url = "https://files.pythonhosted.org/packages/5b/62/ea625b30623083c2aad645c9a6288ad9fc83d570f9adb913a2abdba562dd/coverage-7.8.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f2d32f95922927186c6dbc8bc60df0d186b6edb828d299ab10898ef3f40052fe", size = 244317, upload-time = "2025-03-30T20:35:42.204Z" }, + { url = "https://files.pythonhosted.org/packages/62/cb/3871f13ee1130a6c8f020e2f71d9ed269e1e2124aa3374d2180ee451cee9/coverage-7.8.0-cp312-cp312-win32.whl", hash = "sha256:769773614e676f9d8e8a0980dd7740f09a6ea386d0f383db6821df07d0f08545", size = 214170, upload-time = "2025-03-30T20:35:44.216Z" }, + { url = "https://files.pythonhosted.org/packages/88/26/69fe1193ab0bfa1eb7a7c0149a066123611baba029ebb448500abd8143f9/coverage-7.8.0-cp312-cp312-win_amd64.whl", hash = "sha256:e5d2b9be5b0693cf21eb4ce0ec8d211efb43966f6657807f6859aab3814f946b", size = 214969, upload-time = "2025-03-30T20:35:45.797Z" }, + { url = "https://files.pythonhosted.org/packages/c4/f1/1da77bb4c920aa30e82fa9b6ea065da3467977c2e5e032e38e66f1c57ffd/coverage-7.8.0-pp39.pp310.pp311-none-any.whl", hash = "sha256:b8194fb8e50d556d5849753de991d390c5a1edeeba50f68e3a9253fbd8bf8ccd", size = 203443, upload-time = "2025-03-30T20:36:41.959Z" }, + { url = "https://files.pythonhosted.org/packages/59/f1/4da7717f0063a222db253e7121bd6a56f6fb1ba439dcc36659088793347c/coverage-7.8.0-py3-none-any.whl", hash = "sha256:dbf364b4c5e7bae9250528167dfe40219b62e2d573c854d74be213e1e52069f7", size = 203435, upload-time = "2025-03-30T20:36:43.61Z" }, ] [package.optional-dependencies] @@ -401,7 +405,7 @@ toml = [ name = "crcmod" version = "1.7" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/6b/b0/e595ce2a2527e169c3bcd6c33d2473c1918e0b7f6826a043ca1245dd4e5b/crcmod-1.7.tar.gz", hash = "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e", size = 89670 } +sdist = { url = "https://files.pythonhosted.org/packages/6b/b0/e595ce2a2527e169c3bcd6c33d2473c1918e0b7f6826a043ca1245dd4e5b/crcmod-1.7.tar.gz", hash = "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e", size = 89670, upload-time = "2010-06-27T14:35:29.538Z" } [[package]] name = "cryptography" @@ -410,87 +414,91 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi", marker = "platform_python_implementation != 'PyPy'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0d/05/07b55d1fa21ac18c3a8c79f764e2514e6f6a9698f1be44994f5adf0d29db/cryptography-43.0.3.tar.gz", hash = "sha256:315b9001266a492a6ff443b61238f956b214dbec9910a081ba5b6646a055a805", size = 686989 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1f/f3/01fdf26701a26f4b4dbc337a26883ad5bccaa6f1bbbdd29cd89e22f18a1c/cryptography-43.0.3-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:bf7a1932ac4176486eab36a19ed4c0492da5d97123f1406cf15e41b05e787d2e", size = 6225303 }, - { url = "https://files.pythonhosted.org/packages/a3/01/4896f3d1b392025d4fcbecf40fdea92d3df8662123f6835d0af828d148fd/cryptography-43.0.3-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:63efa177ff54aec6e1c0aefaa1a241232dcd37413835a9b674b6e3f0ae2bfd3e", size = 3760905 }, - { url = "https://files.pythonhosted.org/packages/0a/be/f9a1f673f0ed4b7f6c643164e513dbad28dd4f2dcdf5715004f172ef24b6/cryptography-43.0.3-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e1ce50266f4f70bf41a2c6dc4358afadae90e2a1e5342d3c08883df1675374f", size = 3977271 }, - { url = "https://files.pythonhosted.org/packages/4e/49/80c3a7b5514d1b416d7350830e8c422a4d667b6d9b16a9392ebfd4a5388a/cryptography-43.0.3-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:443c4a81bb10daed9a8f334365fe52542771f25aedaf889fd323a853ce7377d6", size = 3746606 }, - { url = "https://files.pythonhosted.org/packages/0e/16/a28ddf78ac6e7e3f25ebcef69ab15c2c6be5ff9743dd0709a69a4f968472/cryptography-43.0.3-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:74f57f24754fe349223792466a709f8e0c093205ff0dca557af51072ff47ab18", size = 3986484 }, - { url = "https://files.pythonhosted.org/packages/01/f5/69ae8da70c19864a32b0315049866c4d411cce423ec169993d0434218762/cryptography-43.0.3-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:9762ea51a8fc2a88b70cf2995e5675b38d93bf36bd67d91721c309df184f49bd", size = 3852131 }, - { url = "https://files.pythonhosted.org/packages/fd/db/e74911d95c040f9afd3612b1f732e52b3e517cb80de8bf183be0b7d413c6/cryptography-43.0.3-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:81ef806b1fef6b06dcebad789f988d3b37ccaee225695cf3e07648eee0fc6b73", size = 4075647 }, - { url = "https://files.pythonhosted.org/packages/56/48/7b6b190f1462818b324e674fa20d1d5ef3e24f2328675b9b16189cbf0b3c/cryptography-43.0.3-cp37-abi3-win32.whl", hash = "sha256:cbeb489927bd7af4aa98d4b261af9a5bc025bd87f0e3547e11584be9e9427be2", size = 2623873 }, - { url = "https://files.pythonhosted.org/packages/eb/b1/0ebff61a004f7f89e7b65ca95f2f2375679d43d0290672f7713ee3162aff/cryptography-43.0.3-cp37-abi3-win_amd64.whl", hash = "sha256:f46304d6f0c6ab8e52770addfa2fc41e6629495548862279641972b6215451cd", size = 3068039 }, - { url = "https://files.pythonhosted.org/packages/30/d5/c8b32c047e2e81dd172138f772e81d852c51f0f2ad2ae8a24f1122e9e9a7/cryptography-43.0.3-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:8ac43ae87929a5982f5948ceda07001ee5e83227fd69cf55b109144938d96984", size = 6222984 }, - { url = "https://files.pythonhosted.org/packages/2f/78/55356eb9075d0be6e81b59f45c7b48df87f76a20e73893872170471f3ee8/cryptography-43.0.3-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:846da004a5804145a5f441b8530b4bf35afbf7da70f82409f151695b127213d5", size = 3762968 }, - { url = "https://files.pythonhosted.org/packages/2a/2c/488776a3dc843f95f86d2f957ca0fc3407d0242b50bede7fad1e339be03f/cryptography-43.0.3-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f996e7268af62598f2fc1204afa98a3b5712313a55c4c9d434aef49cadc91d4", size = 3977754 }, - { url = "https://files.pythonhosted.org/packages/7c/04/2345ca92f7a22f601a9c62961741ef7dd0127c39f7310dffa0041c80f16f/cryptography-43.0.3-cp39-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:f7b178f11ed3664fd0e995a47ed2b5ff0a12d893e41dd0494f406d1cf555cab7", size = 3749458 }, - { url = "https://files.pythonhosted.org/packages/ac/25/e715fa0bc24ac2114ed69da33adf451a38abb6f3f24ec207908112e9ba53/cryptography-43.0.3-cp39-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:c2e6fc39c4ab499049df3bdf567f768a723a5e8464816e8f009f121a5a9f4405", size = 3988220 }, - { url = "https://files.pythonhosted.org/packages/21/ce/b9c9ff56c7164d8e2edfb6c9305045fbc0df4508ccfdb13ee66eb8c95b0e/cryptography-43.0.3-cp39-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:e1be4655c7ef6e1bbe6b5d0403526601323420bcf414598955968c9ef3eb7d16", size = 3853898 }, - { url = "https://files.pythonhosted.org/packages/2a/33/b3682992ab2e9476b9c81fff22f02c8b0a1e6e1d49ee1750a67d85fd7ed2/cryptography-43.0.3-cp39-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:df6b6c6d742395dd77a23ea3728ab62f98379eff8fb61be2744d4679ab678f73", size = 4076592 }, - { url = "https://files.pythonhosted.org/packages/81/1e/ffcc41b3cebd64ca90b28fd58141c5f68c83d48563c88333ab660e002cd3/cryptography-43.0.3-cp39-abi3-win32.whl", hash = "sha256:d56e96520b1020449bbace2b78b603442e7e378a9b3bd68de65c782db1507995", size = 2623145 }, - { url = "https://files.pythonhosted.org/packages/87/5c/3dab83cc4aba1f4b0e733e3f0c3e7d4386440d660ba5b1e3ff995feb734d/cryptography-43.0.3-cp39-abi3-win_amd64.whl", hash = "sha256:0c580952eef9bf68c4747774cde7ec1d85a6e61de97281f2dba83c7d2c806362", size = 3068026 }, +sdist = { url = "https://files.pythonhosted.org/packages/0d/05/07b55d1fa21ac18c3a8c79f764e2514e6f6a9698f1be44994f5adf0d29db/cryptography-43.0.3.tar.gz", hash = "sha256:315b9001266a492a6ff443b61238f956b214dbec9910a081ba5b6646a055a805", size = 686989, upload-time = "2024-10-18T15:58:32.918Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1f/f3/01fdf26701a26f4b4dbc337a26883ad5bccaa6f1bbbdd29cd89e22f18a1c/cryptography-43.0.3-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:bf7a1932ac4176486eab36a19ed4c0492da5d97123f1406cf15e41b05e787d2e", size = 6225303, upload-time = "2024-10-18T15:57:36.753Z" }, + { url = "https://files.pythonhosted.org/packages/a3/01/4896f3d1b392025d4fcbecf40fdea92d3df8662123f6835d0af828d148fd/cryptography-43.0.3-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:63efa177ff54aec6e1c0aefaa1a241232dcd37413835a9b674b6e3f0ae2bfd3e", size = 3760905, upload-time = "2024-10-18T15:57:39.166Z" }, + { url = "https://files.pythonhosted.org/packages/0a/be/f9a1f673f0ed4b7f6c643164e513dbad28dd4f2dcdf5715004f172ef24b6/cryptography-43.0.3-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e1ce50266f4f70bf41a2c6dc4358afadae90e2a1e5342d3c08883df1675374f", size = 3977271, upload-time = "2024-10-18T15:57:41.227Z" }, + { url = "https://files.pythonhosted.org/packages/4e/49/80c3a7b5514d1b416d7350830e8c422a4d667b6d9b16a9392ebfd4a5388a/cryptography-43.0.3-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:443c4a81bb10daed9a8f334365fe52542771f25aedaf889fd323a853ce7377d6", size = 3746606, upload-time = "2024-10-18T15:57:42.903Z" }, + { url = "https://files.pythonhosted.org/packages/0e/16/a28ddf78ac6e7e3f25ebcef69ab15c2c6be5ff9743dd0709a69a4f968472/cryptography-43.0.3-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:74f57f24754fe349223792466a709f8e0c093205ff0dca557af51072ff47ab18", size = 3986484, upload-time = "2024-10-18T15:57:45.434Z" }, + { url = "https://files.pythonhosted.org/packages/01/f5/69ae8da70c19864a32b0315049866c4d411cce423ec169993d0434218762/cryptography-43.0.3-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:9762ea51a8fc2a88b70cf2995e5675b38d93bf36bd67d91721c309df184f49bd", size = 3852131, upload-time = "2024-10-18T15:57:47.267Z" }, + { url = "https://files.pythonhosted.org/packages/fd/db/e74911d95c040f9afd3612b1f732e52b3e517cb80de8bf183be0b7d413c6/cryptography-43.0.3-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:81ef806b1fef6b06dcebad789f988d3b37ccaee225695cf3e07648eee0fc6b73", size = 4075647, upload-time = "2024-10-18T15:57:49.684Z" }, + { url = "https://files.pythonhosted.org/packages/56/48/7b6b190f1462818b324e674fa20d1d5ef3e24f2328675b9b16189cbf0b3c/cryptography-43.0.3-cp37-abi3-win32.whl", hash = "sha256:cbeb489927bd7af4aa98d4b261af9a5bc025bd87f0e3547e11584be9e9427be2", size = 2623873, upload-time = "2024-10-18T15:57:51.822Z" }, + { url = "https://files.pythonhosted.org/packages/eb/b1/0ebff61a004f7f89e7b65ca95f2f2375679d43d0290672f7713ee3162aff/cryptography-43.0.3-cp37-abi3-win_amd64.whl", hash = "sha256:f46304d6f0c6ab8e52770addfa2fc41e6629495548862279641972b6215451cd", size = 3068039, upload-time = "2024-10-18T15:57:54.426Z" }, + { url = "https://files.pythonhosted.org/packages/30/d5/c8b32c047e2e81dd172138f772e81d852c51f0f2ad2ae8a24f1122e9e9a7/cryptography-43.0.3-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:8ac43ae87929a5982f5948ceda07001ee5e83227fd69cf55b109144938d96984", size = 6222984, upload-time = "2024-10-18T15:57:56.174Z" }, + { url = "https://files.pythonhosted.org/packages/2f/78/55356eb9075d0be6e81b59f45c7b48df87f76a20e73893872170471f3ee8/cryptography-43.0.3-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:846da004a5804145a5f441b8530b4bf35afbf7da70f82409f151695b127213d5", size = 3762968, upload-time = "2024-10-18T15:57:58.206Z" }, + { url = "https://files.pythonhosted.org/packages/2a/2c/488776a3dc843f95f86d2f957ca0fc3407d0242b50bede7fad1e339be03f/cryptography-43.0.3-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f996e7268af62598f2fc1204afa98a3b5712313a55c4c9d434aef49cadc91d4", size = 3977754, upload-time = "2024-10-18T15:58:00.683Z" }, + { url = "https://files.pythonhosted.org/packages/7c/04/2345ca92f7a22f601a9c62961741ef7dd0127c39f7310dffa0041c80f16f/cryptography-43.0.3-cp39-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:f7b178f11ed3664fd0e995a47ed2b5ff0a12d893e41dd0494f406d1cf555cab7", size = 3749458, upload-time = "2024-10-18T15:58:02.225Z" }, + { url = "https://files.pythonhosted.org/packages/ac/25/e715fa0bc24ac2114ed69da33adf451a38abb6f3f24ec207908112e9ba53/cryptography-43.0.3-cp39-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:c2e6fc39c4ab499049df3bdf567f768a723a5e8464816e8f009f121a5a9f4405", size = 3988220, upload-time = "2024-10-18T15:58:04.331Z" }, + { url = "https://files.pythonhosted.org/packages/21/ce/b9c9ff56c7164d8e2edfb6c9305045fbc0df4508ccfdb13ee66eb8c95b0e/cryptography-43.0.3-cp39-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:e1be4655c7ef6e1bbe6b5d0403526601323420bcf414598955968c9ef3eb7d16", size = 3853898, upload-time = "2024-10-18T15:58:06.113Z" }, + { url = "https://files.pythonhosted.org/packages/2a/33/b3682992ab2e9476b9c81fff22f02c8b0a1e6e1d49ee1750a67d85fd7ed2/cryptography-43.0.3-cp39-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:df6b6c6d742395dd77a23ea3728ab62f98379eff8fb61be2744d4679ab678f73", size = 4076592, upload-time = "2024-10-18T15:58:08.673Z" }, + { url = "https://files.pythonhosted.org/packages/81/1e/ffcc41b3cebd64ca90b28fd58141c5f68c83d48563c88333ab660e002cd3/cryptography-43.0.3-cp39-abi3-win32.whl", hash = "sha256:d56e96520b1020449bbace2b78b603442e7e378a9b3bd68de65c782db1507995", size = 2623145, upload-time = "2024-10-18T15:58:10.264Z" }, + { url = "https://files.pythonhosted.org/packages/87/5c/3dab83cc4aba1f4b0e733e3f0c3e7d4386440d660ba5b1e3ff995feb734d/cryptography-43.0.3-cp39-abi3-win_amd64.whl", hash = "sha256:0c580952eef9bf68c4747774cde7ec1d85a6e61de97281f2dba83c7d2c806362", size = 3068026, upload-time = "2024-10-18T15:58:11.916Z" }, ] [[package]] name = "cycler" version = "0.12.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a9/95/a3dbbb5028f35eafb79008e7522a75244477d2838f38cbb722248dabc2a8/cycler-0.12.1.tar.gz", hash = "sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c", size = 7615 } +sdist = { url = "https://files.pythonhosted.org/packages/a9/95/a3dbbb5028f35eafb79008e7522a75244477d2838f38cbb722248dabc2a8/cycler-0.12.1.tar.gz", hash = "sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c", size = 7615, upload-time = "2023-10-07T05:32:18.335Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e7/05/c19819d5e3d95294a6f5947fb9b9629efb316b96de511b418c53d245aae6/cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30", size = 8321 }, + { url = "https://files.pythonhosted.org/packages/e7/05/c19819d5e3d95294a6f5947fb9b9629efb316b96de511b418c53d245aae6/cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30", size = 8321, upload-time = "2023-10-07T05:32:16.783Z" }, ] [[package]] name = "cython" -version = "3.0.12" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5a/25/886e197c97a4b8e254173002cdc141441e878ff29aaa7d9ba560cd6e4866/cython-3.0.12.tar.gz", hash = "sha256:b988bb297ce76c671e28c97d017b95411010f7c77fa6623dd0bb47eed1aee1bc", size = 2757617 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/7e/60/3d27abd940f7b80a6aeb69dc093a892f04828e1dd0b243dd81ff87d7b0e9/Cython-3.0.12-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:feb86122a823937cc06e4c029d80ff69f082ebb0b959ab52a5af6cdd271c5dc3", size = 3277430 }, - { url = "https://files.pythonhosted.org/packages/c7/49/f17b0541b317d11f1d021a580643ee2481685157cded92efb32e2fb4daef/Cython-3.0.12-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dfdbea486e702c328338314adb8e80f5f9741f06a0ae83aaec7463bc166d12e8", size = 3444055 }, - { url = "https://files.pythonhosted.org/packages/6b/7f/c57791ba6a1c934b6f1ab51371e894e3b4bfde0bc35e50046c8754a9d215/Cython-3.0.12-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:563de1728c8e48869d2380a1b76bbc1b1b1d01aba948480d68c1d05e52d20c92", size = 3597874 }, - { url = "https://files.pythonhosted.org/packages/23/24/803a0db3681b3a2ef65a4bebab201e5ae4aef5e6127ae03683476a573aa9/Cython-3.0.12-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:398d4576c1e1f6316282aa0b4a55139254fbed965cba7813e6d9900d3092b128", size = 3644129 }, - { url = "https://files.pythonhosted.org/packages/27/13/9b53ba8336e083ece441af8d6d182b8ca83ad523e87c07b3190af379ebc3/Cython-3.0.12-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1e5eadef80143026944ea8f9904715a008f5108d1d644a89f63094cc37351e73", size = 3504936 }, - { url = "https://files.pythonhosted.org/packages/a9/d2/d11104be6992a9fe256860cae6d1a79f7dcf3bdb12ae00116fac591f677d/Cython-3.0.12-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:5a93cbda00a5451175b97dea5a9440a3fcee9e54b4cba7a7dbcba9a764b22aec", size = 3713066 }, - { url = "https://files.pythonhosted.org/packages/d9/8c/1fe49135296efa3f460c760a4297f6a5b387f3e69ac5c9dcdbd620295ab3/Cython-3.0.12-cp311-cp311-win32.whl", hash = "sha256:3109e1d44425a2639e9a677b66cd7711721a5b606b65867cb2d8ef7a97e2237b", size = 2579935 }, - { url = "https://files.pythonhosted.org/packages/02/4e/5ac0b5b9a239cd3fdae187dda8ff06b0b812f671e2501bf253712278f0ac/Cython-3.0.12-cp311-cp311-win_amd64.whl", hash = "sha256:d4b70fc339adba1e2111b074ee6119fe9fd6072c957d8597bce9a0dd1c3c6784", size = 2787337 }, - { url = "https://files.pythonhosted.org/packages/e6/6c/3be501a6520a93449b1e7e6f63e598ec56f3b5d1bc7ad14167c72a22ddf7/Cython-3.0.12-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:fe030d4a00afb2844f5f70896b7f2a1a0d7da09bf3aa3d884cbe5f73fff5d310", size = 3311717 }, - { url = "https://files.pythonhosted.org/packages/ee/ab/adfeb22c85491de18ae10932165edd5b6f01e4c5e3e363638759d1235015/Cython-3.0.12-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a7fec4f052b8fe173fe70eae75091389955b9a23d5cec3d576d21c5913b49d47", size = 3344337 }, - { url = "https://files.pythonhosted.org/packages/0d/72/743730d7c46b4c85abefb93187cbbcb7aae8de288d7722b990db3d13499e/Cython-3.0.12-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0faa5e39e5c8cdf6f9c3b1c3f24972826e45911e7f5b99cf99453fca5432f45e", size = 3517692 }, - { url = "https://files.pythonhosted.org/packages/09/a1/29a4759a02661f8c8e6b703f62bfbc8285337e6918cc90f55dc0fadb5eb3/Cython-3.0.12-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2d53de996ed340e9ab0fc85a88aaa8932f2591a2746e1ab1c06e262bd4ec4be7", size = 3577057 }, - { url = "https://files.pythonhosted.org/packages/d6/f8/03d74e98901a7cc2f21f95231b07dd54ec2f69477319bac268b3816fc3a8/Cython-3.0.12-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:ea3a0e19ab77266c738aa110684a753a04da4e709472cadeff487133354d6ab8", size = 3396493 }, - { url = "https://files.pythonhosted.org/packages/50/ea/ac33c5f54f980dbc23dd8f1d5c51afeef26e15ac1a66388e4b8195af83b7/Cython-3.0.12-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c151082884be468f2f405645858a857298ac7f7592729e5b54788b5c572717ba", size = 3603859 }, - { url = "https://files.pythonhosted.org/packages/a2/4e/91fc1d6b5e678dcf2d1ecd8dce45b014b4b60d2044d376355c605831c873/Cython-3.0.12-cp312-cp312-win32.whl", hash = "sha256:3083465749911ac3b2ce001b6bf17f404ac9dd35d8b08469d19dc7e717f5877a", size = 2610428 }, - { url = "https://files.pythonhosted.org/packages/ff/c3/a7fdec227b9f0bb07edbeb016c7b18ed6a8e6ce884d08b2e397cda2c0168/Cython-3.0.12-cp312-cp312-win_amd64.whl", hash = "sha256:c0b91c7ebace030dd558ea28730de8c580680b50768e5af66db2904a3716c3e3", size = 2794755 }, - { url = "https://files.pythonhosted.org/packages/27/6b/7c87867d255cbce8167ed99fc65635e9395d2af0f0c915428f5b17ec412d/Cython-3.0.12-py2.py3-none-any.whl", hash = "sha256:0038c9bae46c459669390e53a1ec115f8096b2e4647ae007ff1bf4e6dee92806", size = 1171640 }, +version = "3.1.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/5b/d3/bb000603e46144db2e5055219bbddcf7ab3b10012fcb342695694fb88141/cython-3.1.1.tar.gz", hash = "sha256:505ccd413669d5132a53834d792c707974248088c4f60c497deb1b416e366397", size = 3175446, upload-time = "2025-05-19T09:44:54.347Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/35/b3/bc75c0352214b5ced31ce5e0d051d0ad4ad916aa7a1d669d1876ad1e59aa/cython-3.1.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c360823e1063784efc2335617e0f28573d7a594c5a8a05d85e850a9621cccb1f", size = 2998590, upload-time = "2025-05-19T09:56:51.148Z" }, + { url = "https://files.pythonhosted.org/packages/bf/0a/5840cdd7a1e8c0d2ffeb5e09afd32b8d10321cce33a2554ef10ea832a200/cython-3.1.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:12e00b88147b03c148a95365f89dc1c45a0fc52f9c35aa75ff770ef65b615839", size = 2860818, upload-time = "2025-05-19T09:56:53.694Z" }, + { url = "https://files.pythonhosted.org/packages/63/2e/0fac02ce46f208af54d76c6c786b8dddeb207ca94aa85b0455f6cbaa472c/cython-3.1.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ab644415458d782c16ba7252de9cec1e3125371641cafea2e53a8c1cf85dd58d", size = 3124262, upload-time = "2025-05-19T09:56:56.277Z" }, + { url = "https://files.pythonhosted.org/packages/23/04/b7ae247b83b3f98966184c1a787001964132ae2e05a989769b1a5e7325da/cython-3.1.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c5cb6c054daadaf01a88c8f49f3edd9e829c9b76a82cbb4269e3f9878254540b", size = 3215216, upload-time = "2025-05-19T09:56:58.674Z" }, + { url = "https://files.pythonhosted.org/packages/b5/3b/c4e6c16b099a592dbd6cd615c4de901eb8cc2795d5445d77b8cd378de7da/cython-3.1.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:af8f62cc9339b75fe8434325083e6a7cae88c9c21efd74bbb6ba4e3623219469", size = 3282597, upload-time = "2025-05-19T09:57:00.85Z" }, + { url = "https://files.pythonhosted.org/packages/06/dd/90a8fd8508298f1f16e2cbc665774047fbc81f0370125b6e32f0a182fc10/cython-3.1.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:689c1aad373556bd2ab1aa1c2dad8939a2891465a1fbd2cbbdd42b488fb40ec8", size = 3175592, upload-time = "2025-05-19T09:57:03.1Z" }, + { url = "https://files.pythonhosted.org/packages/af/ab/2cd4e8d5c46499ea2ca5b7c3ae4053db86465b35a8870ce5e847fee06aff/cython-3.1.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:953046c190fa9ab9a09a546a909b847cdbb4c1fe34e9bfa4a15b6ee1585a86aa", size = 3378435, upload-time = "2025-05-19T09:57:05.535Z" }, + { url = "https://files.pythonhosted.org/packages/b2/99/250fb399af2edd9861774f0c8b6c4b7d862aa52d966a07b860bcd723842a/cython-3.1.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:755a991601b27dd3555310d0f95b19a05e622a80d7b4e7a91fa6f5f3ef3f3b80", size = 3300519, upload-time = "2025-05-19T09:57:07.512Z" }, + { url = "https://files.pythonhosted.org/packages/37/09/1c5d470580d9b92107cadedc848f43e2f2102284f8b666ea9ab82f6fc101/cython-3.1.1-cp311-cp311-win32.whl", hash = "sha256:83b2af5c327f7da4f08afc34fddfaf6d24fa0c000b6b70a527c8125e493b6080", size = 2447287, upload-time = "2025-05-19T09:57:09.958Z" }, + { url = "https://files.pythonhosted.org/packages/30/67/c99ec81380cd9d2c798eb1572f61dbe50318958925049b39029f73fe6b52/cython-3.1.1-cp311-cp311-win_amd64.whl", hash = "sha256:141ffd6279411c562f6b707adc56b63e965a4fd7f21db83f5d4fcbd8c50ac546", size = 2655739, upload-time = "2025-05-19T09:57:11.938Z" }, + { url = "https://files.pythonhosted.org/packages/78/06/83ff82381319ff68ae46f9dd3024b1d5101997e81a8e955811525b6f934b/cython-3.1.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:9d7dc0e4d0cd491fac679a61e9ede348c64ca449f99a284f9a01851aa1dbc7f6", size = 3006334, upload-time = "2025-05-19T09:57:14.284Z" }, + { url = "https://files.pythonhosted.org/packages/c3/01/b4c46c6a27cd2da642bc987c1f9087265defbc96a1929d326b9034953f15/cython-3.1.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:fd689910002adfac8734f237cdea1573e38345f27ed7fd445482813b65a29457", size = 2836861, upload-time = "2025-05-19T09:57:16.129Z" }, + { url = "https://files.pythonhosted.org/packages/96/51/7936c5d01ec3c89be8de1756f284878d4a567627b7b1790455ac627fb833/cython-3.1.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10f0434916994fe213ea7749268b88d77e3ebcbd1b99542cf64bb7d180f45470", size = 3074560, upload-time = "2025-05-19T09:57:18.797Z" }, + { url = "https://files.pythonhosted.org/packages/0d/81/34aeb787dcb2624a82a33e60276ed28d2da8a08c79660cf674b19be82248/cython-3.1.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:873aac4ac0b0fb197557c0ac15458b780b9221daa4a716881cbd1a9016c8459f", size = 3192645, upload-time = "2025-05-19T09:57:21.002Z" }, + { url = "https://files.pythonhosted.org/packages/e8/bf/1350ed6cb48158a4f096306a12bc4c26c6d20d3314f1f1978ea23afe0220/cython-3.1.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:23b886a6c8a50b1101ccef2f2f3dc9c699b77633ef5bb5007090226c2ad3f9c2", size = 3241751, upload-time = "2025-05-19T09:57:23.118Z" }, + { url = "https://files.pythonhosted.org/packages/1e/f5/9ed5a898c41723e3da2317fd1f082d963ff08571caeded31cb945be589b5/cython-3.1.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:dff0e7dd53a0ca35b64cda843253d5cac944db26663dc097b3a1adf2c49514ad", size = 3123562, upload-time = "2025-05-19T09:57:25.492Z" }, + { url = "https://files.pythonhosted.org/packages/c3/81/b5ce4393d3a0a75a8c6d9ad0b80a62263d892260b816eb3d569ef144511a/cython-3.1.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:0f7954b0b4b3302655d3caa6924261de5907a4e129bc22ace52fe9ae0cd5a758", size = 3333555, upload-time = "2025-05-19T09:57:29.232Z" }, + { url = "https://files.pythonhosted.org/packages/db/47/2c1fa4b4901f10d00e666931dd68d4bd7954d3caa900544d135424ef6178/cython-3.1.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:dfa500fd7ae95ca152a5f8062b870532fa3e27efcef6d00612e1f28b9f72615f", size = 3282112, upload-time = "2025-05-19T09:57:31.904Z" }, + { url = "https://files.pythonhosted.org/packages/ed/5b/b000d3ebff79429419d846e06c5c09f33fd010e1f6158d7ba553e1082253/cython-3.1.1-cp312-cp312-win32.whl", hash = "sha256:cd748fab8e4426dbcb2e0fa2979558333934d24365e0de5672fbabfe337d880c", size = 2462293, upload-time = "2025-05-19T09:57:34.964Z" }, + { url = "https://files.pythonhosted.org/packages/45/0e/e1370ed3216e4e164232d1891c2a2932a3874d1a8681f8c3565cafd98579/cython-3.1.1-cp312-cp312-win_amd64.whl", hash = "sha256:307f216ed319ea07644f2ef9974406c830f01bc8e677e2147e9bfcdf9e3ca8ad", size = 2666710, upload-time = "2025-05-19T09:57:37.528Z" }, + { url = "https://files.pythonhosted.org/packages/a7/97/8e8637e67afc09f1b51a617b15a0d1caf0b5159b0f79d47ab101e620e491/cython-3.1.1-py3-none-any.whl", hash = "sha256:07621e044f332d18139df2ccfcc930151fd323c2f61a58c82f304cffc9eb5280", size = 1220898, upload-time = "2025-05-19T09:44:50.614Z" }, ] [[package]] name = "dbus-next" version = "0.2.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ce/45/6a40fbe886d60a8c26f480e7d12535502b5ba123814b3b9a0b002ebca198/dbus_next-0.2.3.tar.gz", hash = "sha256:f4eae26909332ada528c0a3549dda8d4f088f9b365153952a408e28023a626a5", size = 71112 } +sdist = { url = "https://files.pythonhosted.org/packages/ce/45/6a40fbe886d60a8c26f480e7d12535502b5ba123814b3b9a0b002ebca198/dbus_next-0.2.3.tar.gz", hash = "sha256:f4eae26909332ada528c0a3549dda8d4f088f9b365153952a408e28023a626a5", size = 71112, upload-time = "2021-07-25T22:11:28.398Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d2/fc/c0a3f4c4eaa5a22fbef91713474666e13d0ea2a69c84532579490a9f2cc8/dbus_next-0.2.3-py3-none-any.whl", hash = "sha256:58948f9aff9db08316734c0be2a120f6dc502124d9642f55e90ac82ffb16a18b", size = 57885 }, + { url = "https://files.pythonhosted.org/packages/d2/fc/c0a3f4c4eaa5a22fbef91713474666e13d0ea2a69c84532579490a9f2cc8/dbus_next-0.2.3-py3-none-any.whl", hash = "sha256:58948f9aff9db08316734c0be2a120f6dc502124d9642f55e90ac82ffb16a18b", size = 57885, upload-time = "2021-07-25T22:11:25.466Z" }, ] [[package]] name = "dictdiffer" version = "0.9.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/61/7b/35cbccb7effc5d7e40f4c55e2b79399e1853041997fcda15c9ff160abba0/dictdiffer-0.9.0.tar.gz", hash = "sha256:17bacf5fbfe613ccf1b6d512bd766e6b21fb798822a133aa86098b8ac9997578", size = 31513 } +sdist = { url = "https://files.pythonhosted.org/packages/61/7b/35cbccb7effc5d7e40f4c55e2b79399e1853041997fcda15c9ff160abba0/dictdiffer-0.9.0.tar.gz", hash = "sha256:17bacf5fbfe613ccf1b6d512bd766e6b21fb798822a133aa86098b8ac9997578", size = 31513, upload-time = "2021-07-22T13:24:29.276Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/47/ef/4cb333825d10317a36a1154341ba37e6e9c087bac99c1990ef07ffdb376f/dictdiffer-0.9.0-py2.py3-none-any.whl", hash = "sha256:442bfc693cfcadaf46674575d2eba1c53b42f5e404218ca2c2ff549f2df56595", size = 16754 }, + { url = "https://files.pythonhosted.org/packages/47/ef/4cb333825d10317a36a1154341ba37e6e9c087bac99c1990ef07ffdb376f/dictdiffer-0.9.0-py2.py3-none-any.whl", hash = "sha256:442bfc693cfcadaf46674575d2eba1c53b42f5e404218ca2c2ff549f2df56595", size = 16754, upload-time = "2021-07-22T13:24:26.783Z" }, ] [[package]] name = "dnspython" version = "2.7.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/b5/4a/263763cb2ba3816dd94b08ad3a33d5fdae34ecb856678773cc40a3605829/dnspython-2.7.0.tar.gz", hash = "sha256:ce9c432eda0dc91cf618a5cedf1a4e142651196bbcd2c80e89ed5a907e5cfaf1", size = 345197 } +sdist = { url = "https://files.pythonhosted.org/packages/b5/4a/263763cb2ba3816dd94b08ad3a33d5fdae34ecb856678773cc40a3605829/dnspython-2.7.0.tar.gz", hash = "sha256:ce9c432eda0dc91cf618a5cedf1a4e142651196bbcd2c80e89ed5a907e5cfaf1", size = 345197, upload-time = "2024-10-05T20:14:59.362Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/68/1b/e0a87d256e40e8c888847551b20a017a6b98139178505dc7ffb96f04e954/dnspython-2.7.0-py3-none-any.whl", hash = "sha256:b4c34b7d10b51bcc3a5071e7b8dee77939f1e878477eeecc965e9835f63c6c86", size = 313632 }, + { url = "https://files.pythonhosted.org/packages/68/1b/e0a87d256e40e8c888847551b20a017a6b98139178505dc7ffb96f04e954/dnspython-2.7.0-py3-none-any.whl", hash = "sha256:b4c34b7d10b51bcc3a5071e7b8dee77939f1e878477eeecc965e9835f63c6c86", size = 313632, upload-time = "2024-10-05T20:14:57.687Z" }, ] [[package]] @@ -499,110 +507,114 @@ version = "0.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "python-xlib", marker = "sys_platform == 'linux'" }, - { name = "typing-extensions", marker = "sys_platform != 'darwin'" }, + { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/2f/3a/46ca34abf0725a754bc44ef474ad34aedcc3ea23b052d97b18b76715a6a9/EWMHlib-0.2-py3-none-any.whl", hash = "sha256:f5b07d8cfd4c7734462ee744c32d490f2f3233fa7ab354240069344208d2f6f5", size = 46657 }, + { url = "https://files.pythonhosted.org/packages/2f/3a/46ca34abf0725a754bc44ef474ad34aedcc3ea23b052d97b18b76715a6a9/EWMHlib-0.2-py3-none-any.whl", hash = "sha256:f5b07d8cfd4c7734462ee744c32d490f2f3233fa7ab354240069344208d2f6f5", size = 46657, upload-time = "2024-04-17T08:15:56.338Z" }, ] [[package]] name = "execnet" version = "2.1.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/bb/ff/b4c0dc78fbe20c3e59c0c7334de0c27eb4001a2b2017999af398bf730817/execnet-2.1.1.tar.gz", hash = "sha256:5189b52c6121c24feae288166ab41b32549c7e2348652736540b9e6e7d4e72e3", size = 166524 } +sdist = { url = "https://files.pythonhosted.org/packages/bb/ff/b4c0dc78fbe20c3e59c0c7334de0c27eb4001a2b2017999af398bf730817/execnet-2.1.1.tar.gz", hash = "sha256:5189b52c6121c24feae288166ab41b32549c7e2348652736540b9e6e7d4e72e3", size = 166524, upload-time = "2024-04-08T09:04:19.245Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/43/09/2aea36ff60d16dd8879bdb2f5b3ee0ba8d08cbbdcdfe870e695ce3784385/execnet-2.1.1-py3-none-any.whl", hash = "sha256:26dee51f1b80cebd6d0ca8e74dd8745419761d3bef34163928cbebbdc4749fdc", size = 40612 }, + { url = "https://files.pythonhosted.org/packages/43/09/2aea36ff60d16dd8879bdb2f5b3ee0ba8d08cbbdcdfe870e695ce3784385/execnet-2.1.1-py3-none-any.whl", hash = "sha256:26dee51f1b80cebd6d0ca8e74dd8745419761d3bef34163928cbebbdc4749fdc", size = 40612, upload-time = "2024-04-08T09:04:17.414Z" }, ] [[package]] name = "farama-notifications" version = "0.0.4" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/2e/2c/8384832b7a6b1fd6ba95bbdcae26e7137bb3eedc955c42fd5cdcc086cfbf/Farama-Notifications-0.0.4.tar.gz", hash = "sha256:13fceff2d14314cf80703c8266462ebf3733c7d165336eee998fc58e545efd18", size = 2131 } +sdist = { url = "https://files.pythonhosted.org/packages/2e/2c/8384832b7a6b1fd6ba95bbdcae26e7137bb3eedc955c42fd5cdcc086cfbf/Farama-Notifications-0.0.4.tar.gz", hash = "sha256:13fceff2d14314cf80703c8266462ebf3733c7d165336eee998fc58e545efd18", size = 2131, upload-time = "2023-02-27T18:28:41.047Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/05/2c/ffc08c54c05cdce6fbed2aeebc46348dbe180c6d2c541c7af7ba0aa5f5f8/Farama_Notifications-0.0.4-py3-none-any.whl", hash = "sha256:14de931035a41961f7c056361dc7f980762a143d05791ef5794a751a2caf05ae", size = 2511 }, + { url = "https://files.pythonhosted.org/packages/05/2c/ffc08c54c05cdce6fbed2aeebc46348dbe180c6d2c541c7af7ba0aa5f5f8/Farama_Notifications-0.0.4-py3-none-any.whl", hash = "sha256:14de931035a41961f7c056361dc7f980762a143d05791ef5794a751a2caf05ae", size = 2511, upload-time = "2023-02-27T18:28:39.447Z" }, ] [[package]] name = "filelock" -version = "3.17.0" +version = "3.18.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/dc/9c/0b15fb47b464e1b663b1acd1253a062aa5feecb07d4e597daea542ebd2b5/filelock-3.17.0.tar.gz", hash = "sha256:ee4e77401ef576ebb38cd7f13b9b28893194acc20a8e68e18730ba9c0e54660e", size = 18027 } +sdist = { url = "https://files.pythonhosted.org/packages/0a/10/c23352565a6544bdc5353e0b15fc1c563352101f30e24bf500207a54df9a/filelock-3.18.0.tar.gz", hash = "sha256:adbc88eabb99d2fec8c9c1b229b171f18afa655400173ddc653d5d01501fb9f2", size = 18075, upload-time = "2025-03-14T07:11:40.47Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/89/ec/00d68c4ddfedfe64159999e5f8a98fb8442729a63e2077eb9dcd89623d27/filelock-3.17.0-py3-none-any.whl", hash = "sha256:533dc2f7ba78dc2f0f531fc6c4940addf7b70a481e269a5a3b93be94ffbe8338", size = 16164 }, + { url = "https://files.pythonhosted.org/packages/4d/36/2a115987e2d8c300a974597416d9de88f2444426de9571f4b59b2cca3acc/filelock-3.18.0-py3-none-any.whl", hash = "sha256:c401f4f8377c4464e6db25fff06205fd89bdd83b65eb0488ed1b160f780e21de", size = 16215, upload-time = "2025-03-14T07:11:39.145Z" }, ] [[package]] name = "fonttools" -version = "4.56.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1c/8c/9ffa2a555af0e5e5d0e2ed7fdd8c9bef474ed676995bb4c57c9cd0014248/fonttools-4.56.0.tar.gz", hash = "sha256:a114d1567e1a1586b7e9e7fc2ff686ca542a82769a296cef131e4c4af51e58f4", size = 3462892 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/35/56/a2f3e777d48fcae7ecd29de4d96352d84e5ea9871e5f3fc88241521572cf/fonttools-4.56.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7ef04bc7827adb7532be3d14462390dd71287644516af3f1e67f1e6ff9c6d6df", size = 2753325 }, - { url = "https://files.pythonhosted.org/packages/71/85/d483e9c4e5ed586b183bf037a353e8d766366b54fd15519b30e6178a6a6e/fonttools-4.56.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ffda9b8cd9cb8b301cae2602ec62375b59e2e2108a117746f12215145e3f786c", size = 2281554 }, - { url = "https://files.pythonhosted.org/packages/09/67/060473b832b2fade03c127019794df6dc02d9bc66fa4210b8e0d8a99d1e5/fonttools-4.56.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e2e993e8db36306cc3f1734edc8ea67906c55f98683d6fd34c3fc5593fdbba4c", size = 4869260 }, - { url = "https://files.pythonhosted.org/packages/28/e9/47c02d5a7027e8ed841ab6a10ca00c93dadd5f16742f1af1fa3f9978adf4/fonttools-4.56.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:003548eadd674175510773f73fb2060bb46adb77c94854af3e0cc5bc70260049", size = 4898508 }, - { url = "https://files.pythonhosted.org/packages/bf/8a/221d456d1afb8ca043cfd078f59f187ee5d0a580f4b49351b9ce95121f57/fonttools-4.56.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:bd9825822e7bb243f285013e653f6741954d8147427aaa0324a862cdbf4cbf62", size = 4877700 }, - { url = "https://files.pythonhosted.org/packages/a4/8c/e503863adf7a6aeff7b960e2f66fa44dd0c29a7a8b79765b2821950d7b05/fonttools-4.56.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b23d30a2c0b992fb1c4f8ac9bfde44b5586d23457759b6cf9a787f1a35179ee0", size = 5045817 }, - { url = "https://files.pythonhosted.org/packages/2b/50/79ba3b7e42f4eaa70b82b9e79155f0f6797858dc8a97862428b6852c6aee/fonttools-4.56.0-cp311-cp311-win32.whl", hash = "sha256:47b5e4680002ae1756d3ae3b6114e20aaee6cc5c69d1e5911f5ffffd3ee46c6b", size = 2154426 }, - { url = "https://files.pythonhosted.org/packages/3b/90/4926e653041c4116ecd43e50e3c79f5daae6dcafc58ceb64bc4f71dd4924/fonttools-4.56.0-cp311-cp311-win_amd64.whl", hash = "sha256:14a3e3e6b211660db54ca1ef7006401e4a694e53ffd4553ab9bc87ead01d0f05", size = 2200937 }, - { url = "https://files.pythonhosted.org/packages/39/32/71cfd6877999576a11824a7fe7bc0bb57c5c72b1f4536fa56a3e39552643/fonttools-4.56.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d6f195c14c01bd057bc9b4f70756b510e009c83c5ea67b25ced3e2c38e6ee6e9", size = 2747757 }, - { url = "https://files.pythonhosted.org/packages/15/52/d9f716b072c5061a0b915dd4c387f74bef44c68c069e2195c753905bd9b7/fonttools-4.56.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:fa760e5fe8b50cbc2d71884a1eff2ed2b95a005f02dda2fa431560db0ddd927f", size = 2279007 }, - { url = "https://files.pythonhosted.org/packages/d1/97/f1b3a8afa9a0d814a092a25cd42f59ccb98a0bb7a295e6e02fc9ba744214/fonttools-4.56.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d54a45d30251f1d729e69e5b675f9a08b7da413391a1227781e2a297fa37f6d2", size = 4783991 }, - { url = "https://files.pythonhosted.org/packages/95/70/2a781bedc1c45a0c61d29c56425609b22ed7f971da5d7e5df2679488741b/fonttools-4.56.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:661a8995d11e6e4914a44ca7d52d1286e2d9b154f685a4d1f69add8418961563", size = 4855109 }, - { url = "https://files.pythonhosted.org/packages/0c/02/a2597858e61a5e3fb6a14d5f6be9e6eb4eaf090da56ad70cedcbdd201685/fonttools-4.56.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9d94449ad0a5f2a8bf5d2f8d71d65088aee48adbe45f3c5f8e00e3ad861ed81a", size = 4762496 }, - { url = "https://files.pythonhosted.org/packages/f2/00/aaf00100d6078fdc73f7352b44589804af9dc12b182a2540b16002152ba4/fonttools-4.56.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f59746f7953f69cc3290ce2f971ab01056e55ddd0fb8b792c31a8acd7fee2d28", size = 4990094 }, - { url = "https://files.pythonhosted.org/packages/bf/dc/3ff1db522460db60cf3adaf1b64e0c72b43406717d139786d3fa1eb20709/fonttools-4.56.0-cp312-cp312-win32.whl", hash = "sha256:bce60f9a977c9d3d51de475af3f3581d9b36952e1f8fc19a1f2254f1dda7ce9c", size = 2142888 }, - { url = "https://files.pythonhosted.org/packages/6f/e3/5a181a85777f7809076e51f7422e0dc77eb04676c40ec8bf6a49d390d1ff/fonttools-4.56.0-cp312-cp312-win_amd64.whl", hash = "sha256:300c310bb725b2bdb4f5fc7e148e190bd69f01925c7ab437b9c0ca3e1c7cd9ba", size = 2189734 }, - { url = "https://files.pythonhosted.org/packages/bf/ff/44934a031ce5a39125415eb405b9efb76fe7f9586b75291d66ae5cbfc4e6/fonttools-4.56.0-py3-none-any.whl", hash = "sha256:1088182f68c303b50ca4dc0c82d42083d176cba37af1937e1a976a31149d4d14", size = 1089800 }, +version = "4.58.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/9a/cf/4d037663e2a1fe30fddb655d755d76e18624be44ad467c07412c2319ab97/fonttools-4.58.0.tar.gz", hash = "sha256:27423d0606a2c7b336913254bf0b1193ebd471d5f725d665e875c5e88a011a43", size = 3514522, upload-time = "2025-05-10T17:36:35.886Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/76/2e/9b9bd943872a50cb182382f8f4a99af92d76e800603d5f73e4343fdce61a/fonttools-4.58.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9345b1bb994476d6034996b31891c0c728c1059c05daa59f9ab57d2a4dce0f84", size = 2751920, upload-time = "2025-05-10T17:35:16.487Z" }, + { url = "https://files.pythonhosted.org/packages/9b/8c/e8d6375da893125f610826c2e30e6d2597dfb8dad256f8ff5a54f3089fda/fonttools-4.58.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:1d93119ace1e2d39ff1340deb71097932f72b21c054bd3da727a3859825e24e5", size = 2313957, upload-time = "2025-05-10T17:35:18.906Z" }, + { url = "https://files.pythonhosted.org/packages/4f/1b/a29cb00c8c20164b24f88780e298fafd0bbfb25cf8bc7b10c4b69331ad5d/fonttools-4.58.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79c9e4f01bb04f19df272ae35314eb6349fdb2e9497a163cd22a21be999694bd", size = 4913808, upload-time = "2025-05-10T17:35:21.394Z" }, + { url = "https://files.pythonhosted.org/packages/d1/ab/9b9507b65b15190cbfe1ccd3c08067d79268d8312ef20948b16d9f5aa905/fonttools-4.58.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:62ecda1465d38248aaf9bee1c17a21cf0b16aef7d121d7d303dbb320a6fd49c2", size = 4935876, upload-time = "2025-05-10T17:35:23.849Z" }, + { url = "https://files.pythonhosted.org/packages/15/e4/1395853bc775b0ab06a1c61cf261779afda7baff3f65cf1197bbd21aa149/fonttools-4.58.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:29d0499bff12a26733c05c1bfd07e68465158201624b2fba4a40b23d96c43f94", size = 4974798, upload-time = "2025-05-10T17:35:26.189Z" }, + { url = "https://files.pythonhosted.org/packages/3c/b9/0358368ef5462f4653a198207b29885bee8d5e23c870f6125450ed88e693/fonttools-4.58.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1871abdb0af582e2d96cc12d88889e3bfa796928f491ec14d34a2e58ca298c7e", size = 5093560, upload-time = "2025-05-10T17:35:28.577Z" }, + { url = "https://files.pythonhosted.org/packages/11/00/f64bc3659980c41eccf2c371e62eb15b40858f02a41a0e9c6258ef094388/fonttools-4.58.0-cp311-cp311-win32.whl", hash = "sha256:e292485d70402093eb94f6ab7669221743838b8bd4c1f45c84ca76b63338e7bf", size = 2186330, upload-time = "2025-05-10T17:35:31.733Z" }, + { url = "https://files.pythonhosted.org/packages/c8/a0/0287be13a1ec7733abf292ffbd76417cea78752d4ce10fecf92d8b1252d6/fonttools-4.58.0-cp311-cp311-win_amd64.whl", hash = "sha256:6df3755fcf9ad70a74ad3134bd5c9738f73c9bb701a304b1c809877b11fe701c", size = 2234687, upload-time = "2025-05-10T17:35:34.015Z" }, + { url = "https://files.pythonhosted.org/packages/6a/4e/1c6b35ec7c04d739df4cf5aace4b7ec284d6af2533a65de21972e2f237d9/fonttools-4.58.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:aa8316798f982c751d71f0025b372151ea36405733b62d0d94d5e7b8dd674fa6", size = 2737502, upload-time = "2025-05-10T17:35:36.436Z" }, + { url = "https://files.pythonhosted.org/packages/fc/72/c6fcafa3c9ed2b69991ae25a1ba7a3fec8bf74928a96e8229c37faa8eda2/fonttools-4.58.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:c6db489511e867633b859b11aefe1b7c0d90281c5bdb903413edbb2ba77b97f1", size = 2307214, upload-time = "2025-05-10T17:35:38.939Z" }, + { url = "https://files.pythonhosted.org/packages/52/11/1015cedc9878da6d8d1758049749eef857b693e5828d477287a959c8650f/fonttools-4.58.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:107bdb2dacb1f627db3c4b77fb16d065a10fe88978d02b4fc327b9ecf8a62060", size = 4811136, upload-time = "2025-05-10T17:35:41.491Z" }, + { url = "https://files.pythonhosted.org/packages/32/b9/6a1bc1af6ec17eead5d32e87075e22d0dab001eace0b5a1542d38c6a9483/fonttools-4.58.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ba7212068ab20f1128a0475f169068ba8e5b6e35a39ba1980b9f53f6ac9720ac", size = 4876598, upload-time = "2025-05-10T17:35:43.986Z" }, + { url = "https://files.pythonhosted.org/packages/d8/46/b14584c7ea65ad1609fb9632251016cda8a2cd66b15606753b9f888d3677/fonttools-4.58.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:f95ea3b6a3b9962da3c82db73f46d6a6845a6c3f3f968f5293b3ac1864e771c2", size = 4872256, upload-time = "2025-05-10T17:35:46.617Z" }, + { url = "https://files.pythonhosted.org/packages/05/78/b2105a7812ca4ef9bf180cd741c82f4522316c652ce2a56f788e2eb54b62/fonttools-4.58.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:874f1225cc4ccfeac32009887f722d7f8b107ca5e867dcee067597eef9d4c80b", size = 5028710, upload-time = "2025-05-10T17:35:49.227Z" }, + { url = "https://files.pythonhosted.org/packages/8c/a9/a38c85ffd30d1f2c7a5460c8abfd1aa66e00c198df3ff0b08117f5c6fcd9/fonttools-4.58.0-cp312-cp312-win32.whl", hash = "sha256:5f3cde64ec99c43260e2e6c4fa70dfb0a5e2c1c1d27a4f4fe4618c16f6c9ff71", size = 2173593, upload-time = "2025-05-10T17:35:51.226Z" }, + { url = "https://files.pythonhosted.org/packages/66/48/29752962a74b7ed95da976b5a968bba1fe611a4a7e50b9fefa345e6e7025/fonttools-4.58.0-cp312-cp312-win_amd64.whl", hash = "sha256:2aee08e2818de45067109a207cbd1b3072939f77751ef05904d506111df5d824", size = 2223230, upload-time = "2025-05-10T17:35:53.653Z" }, + { url = "https://files.pythonhosted.org/packages/9b/1f/4417c26e26a1feab85a27e927f7a73d8aabc84544be8ba108ce4aa90eb1e/fonttools-4.58.0-py3-none-any.whl", hash = "sha256:c96c36880be2268be409df7b08c5b5dacac1827083461a6bc2cb07b8cbcec1d7", size = 1111440, upload-time = "2025-05-10T17:36:33.607Z" }, ] [[package]] name = "frozenlist" -version = "1.5.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/8f/ed/0f4cec13a93c02c47ec32d81d11c0c1efbadf4a471e3f3ce7cad366cbbd3/frozenlist-1.5.0.tar.gz", hash = "sha256:81d5af29e61b9c8348e876d442253723928dce6433e0e76cd925cd83f1b4b817", size = 39930 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/79/43/0bed28bf5eb1c9e4301003b74453b8e7aa85fb293b31dde352aac528dafc/frozenlist-1.5.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:fd74520371c3c4175142d02a976aee0b4cb4a7cc912a60586ffd8d5929979b30", size = 94987 }, - { url = "https://files.pythonhosted.org/packages/bb/bf/b74e38f09a246e8abbe1e90eb65787ed745ccab6eaa58b9c9308e052323d/frozenlist-1.5.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2f3f7a0fbc219fb4455264cae4d9f01ad41ae6ee8524500f381de64ffaa077d5", size = 54584 }, - { url = "https://files.pythonhosted.org/packages/2c/31/ab01375682f14f7613a1ade30149f684c84f9b8823a4391ed950c8285656/frozenlist-1.5.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f47c9c9028f55a04ac254346e92977bf0f166c483c74b4232bee19a6697e4778", size = 52499 }, - { url = "https://files.pythonhosted.org/packages/98/a8/d0ac0b9276e1404f58fec3ab6e90a4f76b778a49373ccaf6a563f100dfbc/frozenlist-1.5.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0996c66760924da6e88922756d99b47512a71cfd45215f3570bf1e0b694c206a", size = 276357 }, - { url = "https://files.pythonhosted.org/packages/ad/c9/c7761084fa822f07dac38ac29f841d4587570dd211e2262544aa0b791d21/frozenlist-1.5.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a2fe128eb4edeabe11896cb6af88fca5346059f6c8d807e3b910069f39157869", size = 287516 }, - { url = "https://files.pythonhosted.org/packages/a1/ff/cd7479e703c39df7bdab431798cef89dc75010d8aa0ca2514c5b9321db27/frozenlist-1.5.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1a8ea951bbb6cacd492e3948b8da8c502a3f814f5d20935aae74b5df2b19cf3d", size = 283131 }, - { url = "https://files.pythonhosted.org/packages/59/a0/370941beb47d237eca4fbf27e4e91389fd68699e6f4b0ebcc95da463835b/frozenlist-1.5.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:de537c11e4aa01d37db0d403b57bd6f0546e71a82347a97c6a9f0dcc532b3a45", size = 261320 }, - { url = "https://files.pythonhosted.org/packages/b8/5f/c10123e8d64867bc9b4f2f510a32042a306ff5fcd7e2e09e5ae5100ee333/frozenlist-1.5.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9c2623347b933fcb9095841f1cc5d4ff0b278addd743e0e966cb3d460278840d", size = 274877 }, - { url = "https://files.pythonhosted.org/packages/fa/79/38c505601ae29d4348f21706c5d89755ceded02a745016ba2f58bd5f1ea6/frozenlist-1.5.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:cee6798eaf8b1416ef6909b06f7dc04b60755206bddc599f52232606e18179d3", size = 269592 }, - { url = "https://files.pythonhosted.org/packages/19/e2/39f3a53191b8204ba9f0bb574b926b73dd2efba2a2b9d2d730517e8f7622/frozenlist-1.5.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f5f9da7f5dbc00a604fe74aa02ae7c98bcede8a3b8b9666f9f86fc13993bc71a", size = 265934 }, - { url = "https://files.pythonhosted.org/packages/d5/c9/3075eb7f7f3a91f1a6b00284af4de0a65a9ae47084930916f5528144c9dd/frozenlist-1.5.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:90646abbc7a5d5c7c19461d2e3eeb76eb0b204919e6ece342feb6032c9325ae9", size = 283859 }, - { url = "https://files.pythonhosted.org/packages/05/f5/549f44d314c29408b962fa2b0e69a1a67c59379fb143b92a0a065ffd1f0f/frozenlist-1.5.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:bdac3c7d9b705d253b2ce370fde941836a5f8b3c5c2b8fd70940a3ea3af7f4f2", size = 287560 }, - { url = "https://files.pythonhosted.org/packages/9d/f8/cb09b3c24a3eac02c4c07a9558e11e9e244fb02bf62c85ac2106d1eb0c0b/frozenlist-1.5.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:03d33c2ddbc1816237a67f66336616416e2bbb6beb306e5f890f2eb22b959cdf", size = 277150 }, - { url = "https://files.pythonhosted.org/packages/37/48/38c2db3f54d1501e692d6fe058f45b6ad1b358d82cd19436efab80cfc965/frozenlist-1.5.0-cp311-cp311-win32.whl", hash = "sha256:237f6b23ee0f44066219dae14c70ae38a63f0440ce6750f868ee08775073f942", size = 45244 }, - { url = "https://files.pythonhosted.org/packages/ca/8c/2ddffeb8b60a4bce3b196c32fcc30d8830d4615e7b492ec2071da801b8ad/frozenlist-1.5.0-cp311-cp311-win_amd64.whl", hash = "sha256:0cc974cc93d32c42e7b0f6cf242a6bd941c57c61b618e78b6c0a96cb72788c1d", size = 51634 }, - { url = "https://files.pythonhosted.org/packages/79/73/fa6d1a96ab7fd6e6d1c3500700963eab46813847f01ef0ccbaa726181dd5/frozenlist-1.5.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:31115ba75889723431aa9a4e77d5f398f5cf976eea3bdf61749731f62d4a4a21", size = 94026 }, - { url = "https://files.pythonhosted.org/packages/ab/04/ea8bf62c8868b8eada363f20ff1b647cf2e93377a7b284d36062d21d81d1/frozenlist-1.5.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7437601c4d89d070eac8323f121fcf25f88674627505334654fd027b091db09d", size = 54150 }, - { url = "https://files.pythonhosted.org/packages/d0/9a/8e479b482a6f2070b26bda572c5e6889bb3ba48977e81beea35b5ae13ece/frozenlist-1.5.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:7948140d9f8ece1745be806f2bfdf390127cf1a763b925c4a805c603df5e697e", size = 51927 }, - { url = "https://files.pythonhosted.org/packages/e3/12/2aad87deb08a4e7ccfb33600871bbe8f0e08cb6d8224371387f3303654d7/frozenlist-1.5.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:feeb64bc9bcc6b45c6311c9e9b99406660a9c05ca8a5b30d14a78555088b0b3a", size = 282647 }, - { url = "https://files.pythonhosted.org/packages/77/f2/07f06b05d8a427ea0060a9cef6e63405ea9e0d761846b95ef3fb3be57111/frozenlist-1.5.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:683173d371daad49cffb8309779e886e59c2f369430ad28fe715f66d08d4ab1a", size = 289052 }, - { url = "https://files.pythonhosted.org/packages/bd/9f/8bf45a2f1cd4aa401acd271b077989c9267ae8463e7c8b1eb0d3f561b65e/frozenlist-1.5.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7d57d8f702221405a9d9b40f9da8ac2e4a1a8b5285aac6100f3393675f0a85ee", size = 291719 }, - { url = "https://files.pythonhosted.org/packages/41/d1/1f20fd05a6c42d3868709b7604c9f15538a29e4f734c694c6bcfc3d3b935/frozenlist-1.5.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:30c72000fbcc35b129cb09956836c7d7abf78ab5416595e4857d1cae8d6251a6", size = 267433 }, - { url = "https://files.pythonhosted.org/packages/af/f2/64b73a9bb86f5a89fb55450e97cd5c1f84a862d4ff90d9fd1a73ab0f64a5/frozenlist-1.5.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:000a77d6034fbad9b6bb880f7ec073027908f1b40254b5d6f26210d2dab1240e", size = 283591 }, - { url = "https://files.pythonhosted.org/packages/29/e2/ffbb1fae55a791fd6c2938dd9ea779509c977435ba3940b9f2e8dc9d5316/frozenlist-1.5.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5d7f5a50342475962eb18b740f3beecc685a15b52c91f7d975257e13e029eca9", size = 273249 }, - { url = "https://files.pythonhosted.org/packages/2e/6e/008136a30798bb63618a114b9321b5971172a5abddff44a100c7edc5ad4f/frozenlist-1.5.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:87f724d055eb4785d9be84e9ebf0f24e392ddfad00b3fe036e43f489fafc9039", size = 271075 }, - { url = "https://files.pythonhosted.org/packages/ae/f0/4e71e54a026b06724cec9b6c54f0b13a4e9e298cc8db0f82ec70e151f5ce/frozenlist-1.5.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:6e9080bb2fb195a046e5177f10d9d82b8a204c0736a97a153c2466127de87784", size = 285398 }, - { url = "https://files.pythonhosted.org/packages/4d/36/70ec246851478b1c0b59f11ef8ade9c482ff447c1363c2bd5fad45098b12/frozenlist-1.5.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9b93d7aaa36c966fa42efcaf716e6b3900438632a626fb09c049f6a2f09fc631", size = 294445 }, - { url = "https://files.pythonhosted.org/packages/37/e0/47f87544055b3349b633a03c4d94b405956cf2437f4ab46d0928b74b7526/frozenlist-1.5.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:52ef692a4bc60a6dd57f507429636c2af8b6046db8b31b18dac02cbc8f507f7f", size = 280569 }, - { url = "https://files.pythonhosted.org/packages/f9/7c/490133c160fb6b84ed374c266f42800e33b50c3bbab1652764e6e1fc498a/frozenlist-1.5.0-cp312-cp312-win32.whl", hash = "sha256:29d94c256679247b33a3dc96cce0f93cbc69c23bf75ff715919332fdbb6a32b8", size = 44721 }, - { url = "https://files.pythonhosted.org/packages/b1/56/4e45136ffc6bdbfa68c29ca56ef53783ef4c2fd395f7cbf99a2624aa9aaa/frozenlist-1.5.0-cp312-cp312-win_amd64.whl", hash = "sha256:8969190d709e7c48ea386db202d708eb94bdb29207a1f269bab1196ce0dcca1f", size = 51329 }, - { url = "https://files.pythonhosted.org/packages/c6/c8/a5be5b7550c10858fcf9b0ea054baccab474da77d37f1e828ce043a3a5d4/frozenlist-1.5.0-py3-none-any.whl", hash = "sha256:d994863bba198a4a518b467bb971c56e1db3f180a25c6cf7bb1949c267f748c3", size = 11901 }, +version = "1.6.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/ee/f4/d744cba2da59b5c1d88823cf9e8a6c74e4659e2b27604ed973be2a0bf5ab/frozenlist-1.6.0.tar.gz", hash = "sha256:b99655c32c1c8e06d111e7f41c06c29a5318cb1835df23a45518e02a47c63b68", size = 42831, upload-time = "2025-04-17T22:38:53.099Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/53/b5/bc883b5296ec902115c00be161da93bf661199c465ec4c483feec6ea4c32/frozenlist-1.6.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ae8337990e7a45683548ffb2fee1af2f1ed08169284cd829cdd9a7fa7470530d", size = 160912, upload-time = "2025-04-17T22:36:17.235Z" }, + { url = "https://files.pythonhosted.org/packages/6f/93/51b058b563d0704b39c56baa222828043aafcac17fd3734bec5dbeb619b1/frozenlist-1.6.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8c952f69dd524558694818a461855f35d36cc7f5c0adddce37e962c85d06eac0", size = 124315, upload-time = "2025-04-17T22:36:18.735Z" }, + { url = "https://files.pythonhosted.org/packages/c9/e0/46cd35219428d350558b874d595e132d1c17a9471a1bd0d01d518a261e7c/frozenlist-1.6.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:8f5fef13136c4e2dee91bfb9a44e236fff78fc2cd9f838eddfc470c3d7d90afe", size = 122230, upload-time = "2025-04-17T22:36:20.6Z" }, + { url = "https://files.pythonhosted.org/packages/d1/0f/7ad2ce928ad06d6dd26a61812b959ded573d3e9d0ee6109d96c2be7172e9/frozenlist-1.6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:716bbba09611b4663ecbb7cd022f640759af8259e12a6ca939c0a6acd49eedba", size = 314842, upload-time = "2025-04-17T22:36:22.088Z" }, + { url = "https://files.pythonhosted.org/packages/34/76/98cbbd8a20a5c3359a2004ae5e5b216af84a150ccbad67c8f8f30fb2ea91/frozenlist-1.6.0-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:7b8c4dc422c1a3ffc550b465090e53b0bf4839047f3e436a34172ac67c45d595", size = 304919, upload-time = "2025-04-17T22:36:24.247Z" }, + { url = "https://files.pythonhosted.org/packages/9a/fa/258e771ce3a44348c05e6b01dffc2bc67603fba95761458c238cd09a2c77/frozenlist-1.6.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b11534872256e1666116f6587a1592ef395a98b54476addb5e8d352925cb5d4a", size = 324074, upload-time = "2025-04-17T22:36:26.291Z" }, + { url = "https://files.pythonhosted.org/packages/d5/a4/047d861fd8c538210e12b208c0479912273f991356b6bdee7ea8356b07c9/frozenlist-1.6.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1c6eceb88aaf7221f75be6ab498dc622a151f5f88d536661af3ffc486245a626", size = 321292, upload-time = "2025-04-17T22:36:27.909Z" }, + { url = "https://files.pythonhosted.org/packages/c0/25/cfec8af758b4525676cabd36efcaf7102c1348a776c0d1ad046b8a7cdc65/frozenlist-1.6.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:62c828a5b195570eb4b37369fcbbd58e96c905768d53a44d13044355647838ff", size = 301569, upload-time = "2025-04-17T22:36:29.448Z" }, + { url = "https://files.pythonhosted.org/packages/87/2f/0c819372fa9f0c07b153124bf58683b8d0ca7bb73ea5ccde9b9ef1745beb/frozenlist-1.6.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e1c6bd2c6399920c9622362ce95a7d74e7f9af9bfec05fff91b8ce4b9647845a", size = 313625, upload-time = "2025-04-17T22:36:31.55Z" }, + { url = "https://files.pythonhosted.org/packages/50/5f/f0cf8b0fdedffdb76b3745aa13d5dbe404d63493cc211ce8250f2025307f/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:49ba23817781e22fcbd45fd9ff2b9b8cdb7b16a42a4851ab8025cae7b22e96d0", size = 312523, upload-time = "2025-04-17T22:36:33.078Z" }, + { url = "https://files.pythonhosted.org/packages/e1/6c/38c49108491272d3e84125bbabf2c2d0b304899b52f49f0539deb26ad18d/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:431ef6937ae0f853143e2ca67d6da76c083e8b1fe3df0e96f3802fd37626e606", size = 322657, upload-time = "2025-04-17T22:36:34.688Z" }, + { url = "https://files.pythonhosted.org/packages/bd/4b/3bd3bad5be06a9d1b04b1c22be80b5fe65b502992d62fab4bdb25d9366ee/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:9d124b38b3c299ca68433597ee26b7819209cb8a3a9ea761dfe9db3a04bba584", size = 303414, upload-time = "2025-04-17T22:36:36.363Z" }, + { url = "https://files.pythonhosted.org/packages/5b/89/7e225a30bef6e85dbfe22622c24afe932e9444de3b40d58b1ea589a14ef8/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:118e97556306402e2b010da1ef21ea70cb6d6122e580da64c056b96f524fbd6a", size = 320321, upload-time = "2025-04-17T22:36:38.16Z" }, + { url = "https://files.pythonhosted.org/packages/22/72/7e3acef4dd9e86366cb8f4d8f28e852c2b7e116927e9722b31a6f71ea4b0/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:fb3b309f1d4086b5533cf7bbcf3f956f0ae6469664522f1bde4feed26fba60f1", size = 323975, upload-time = "2025-04-17T22:36:40.289Z" }, + { url = "https://files.pythonhosted.org/packages/d8/85/e5da03d20507e13c66ce612c9792b76811b7a43e3320cce42d95b85ac755/frozenlist-1.6.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:54dece0d21dce4fdb188a1ffc555926adf1d1c516e493c2914d7c370e454bc9e", size = 316553, upload-time = "2025-04-17T22:36:42.045Z" }, + { url = "https://files.pythonhosted.org/packages/ac/8e/6c609cbd0580ae8a0661c408149f196aade7d325b1ae7adc930501b81acb/frozenlist-1.6.0-cp311-cp311-win32.whl", hash = "sha256:654e4ba1d0b2154ca2f096bed27461cf6160bc7f504a7f9a9ef447c293caf860", size = 115511, upload-time = "2025-04-17T22:36:44.067Z" }, + { url = "https://files.pythonhosted.org/packages/f2/13/a84804cfde6de12d44ed48ecbf777ba62b12ff09e761f76cdd1ff9e14bb1/frozenlist-1.6.0-cp311-cp311-win_amd64.whl", hash = "sha256:3e911391bffdb806001002c1f860787542f45916c3baf764264a52765d5a5603", size = 120863, upload-time = "2025-04-17T22:36:45.465Z" }, + { url = "https://files.pythonhosted.org/packages/9c/8a/289b7d0de2fbac832ea80944d809759976f661557a38bb8e77db5d9f79b7/frozenlist-1.6.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c5b9e42ace7d95bf41e19b87cec8f262c41d3510d8ad7514ab3862ea2197bfb1", size = 160193, upload-time = "2025-04-17T22:36:47.382Z" }, + { url = "https://files.pythonhosted.org/packages/19/80/2fd17d322aec7f430549f0669f599997174f93ee17929ea5b92781ec902c/frozenlist-1.6.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:ca9973735ce9f770d24d5484dcb42f68f135351c2fc81a7a9369e48cf2998a29", size = 123831, upload-time = "2025-04-17T22:36:49.401Z" }, + { url = "https://files.pythonhosted.org/packages/99/06/f5812da431273f78c6543e0b2f7de67dfd65eb0a433978b2c9c63d2205e4/frozenlist-1.6.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6ac40ec76041c67b928ca8aaffba15c2b2ee3f5ae8d0cb0617b5e63ec119ca25", size = 121862, upload-time = "2025-04-17T22:36:51.899Z" }, + { url = "https://files.pythonhosted.org/packages/d0/31/9e61c6b5fc493cf24d54881731204d27105234d09878be1a5983182cc4a5/frozenlist-1.6.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:95b7a8a3180dfb280eb044fdec562f9b461614c0ef21669aea6f1d3dac6ee576", size = 316361, upload-time = "2025-04-17T22:36:53.402Z" }, + { url = "https://files.pythonhosted.org/packages/9d/55/22ca9362d4f0222324981470fd50192be200154d51509ee6eb9baa148e96/frozenlist-1.6.0-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:c444d824e22da6c9291886d80c7d00c444981a72686e2b59d38b285617cb52c8", size = 307115, upload-time = "2025-04-17T22:36:55.016Z" }, + { url = "https://files.pythonhosted.org/packages/ae/39/4fff42920a57794881e7bb3898dc7f5f539261711ea411b43bba3cde8b79/frozenlist-1.6.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:bb52c8166499a8150bfd38478248572c924c003cbb45fe3bcd348e5ac7c000f9", size = 322505, upload-time = "2025-04-17T22:36:57.12Z" }, + { url = "https://files.pythonhosted.org/packages/55/f2/88c41f374c1e4cf0092a5459e5f3d6a1e17ed274c98087a76487783df90c/frozenlist-1.6.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b35298b2db9c2468106278537ee529719228950a5fdda686582f68f247d1dc6e", size = 322666, upload-time = "2025-04-17T22:36:58.735Z" }, + { url = "https://files.pythonhosted.org/packages/75/51/034eeb75afdf3fd03997856195b500722c0b1a50716664cde64e28299c4b/frozenlist-1.6.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d108e2d070034f9d57210f22fefd22ea0d04609fc97c5f7f5a686b3471028590", size = 302119, upload-time = "2025-04-17T22:37:00.512Z" }, + { url = "https://files.pythonhosted.org/packages/2b/a6/564ecde55ee633270a793999ef4fd1d2c2b32b5a7eec903b1012cb7c5143/frozenlist-1.6.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4e1be9111cb6756868ac242b3c2bd1f09d9aea09846e4f5c23715e7afb647103", size = 316226, upload-time = "2025-04-17T22:37:02.102Z" }, + { url = "https://files.pythonhosted.org/packages/f1/c8/6c0682c32377f402b8a6174fb16378b683cf6379ab4d2827c580892ab3c7/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:94bb451c664415f02f07eef4ece976a2c65dcbab9c2f1705b7031a3a75349d8c", size = 312788, upload-time = "2025-04-17T22:37:03.578Z" }, + { url = "https://files.pythonhosted.org/packages/b6/b8/10fbec38f82c5d163ca1750bfff4ede69713badf236a016781cf1f10a0f0/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:d1a686d0b0949182b8faddea596f3fc11f44768d1f74d4cad70213b2e139d821", size = 325914, upload-time = "2025-04-17T22:37:05.213Z" }, + { url = "https://files.pythonhosted.org/packages/62/ca/2bf4f3a1bd40cdedd301e6ecfdbb291080d5afc5f9ce350c0739f773d6b9/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:ea8e59105d802c5a38bdbe7362822c522230b3faba2aa35c0fa1765239b7dd70", size = 305283, upload-time = "2025-04-17T22:37:06.985Z" }, + { url = "https://files.pythonhosted.org/packages/09/64/20cc13ccf94abc2a1f482f74ad210703dc78a590d0b805af1c9aa67f76f9/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:abc4e880a9b920bc5020bf6a431a6bb40589d9bca3975c980495f63632e8382f", size = 319264, upload-time = "2025-04-17T22:37:08.618Z" }, + { url = "https://files.pythonhosted.org/packages/20/ff/86c6a2bbe98cfc231519f5e6d712a0898488ceac804a917ce014f32e68f6/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9a79713adfe28830f27a3c62f6b5406c37376c892b05ae070906f07ae4487046", size = 326482, upload-time = "2025-04-17T22:37:10.196Z" }, + { url = "https://files.pythonhosted.org/packages/2f/da/8e381f66367d79adca245d1d71527aac774e30e291d41ef161ce2d80c38e/frozenlist-1.6.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:9a0318c2068e217a8f5e3b85e35899f5a19e97141a45bb925bb357cfe1daf770", size = 318248, upload-time = "2025-04-17T22:37:12.284Z" }, + { url = "https://files.pythonhosted.org/packages/39/24/1a1976563fb476ab6f0fa9fefaac7616a4361dbe0461324f9fd7bf425dbe/frozenlist-1.6.0-cp312-cp312-win32.whl", hash = "sha256:853ac025092a24bb3bf09ae87f9127de9fe6e0c345614ac92536577cf956dfcc", size = 115161, upload-time = "2025-04-17T22:37:13.902Z" }, + { url = "https://files.pythonhosted.org/packages/80/2e/fb4ed62a65f8cd66044706b1013f0010930d8cbb0729a2219561ea075434/frozenlist-1.6.0-cp312-cp312-win_amd64.whl", hash = "sha256:2bdfe2d7e6c9281c6e55523acd6c2bf77963cb422fdc7d142fb0cb6621b66878", size = 120548, upload-time = "2025-04-17T22:37:15.326Z" }, + { url = "https://files.pythonhosted.org/packages/71/3e/b04a0adda73bd52b390d730071c0d577073d3d26740ee1bad25c3ad0f37b/frozenlist-1.6.0-py3-none-any.whl", hash = "sha256:535eec9987adb04701266b92745d6cdcef2e77669299359c3009c3404dd5d191", size = 12404, upload-time = "2025-04-17T22:38:51.668Z" }, ] [[package]] name = "future-fstrings" version = "1.2.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5d/e2/3874574cce18a2e3608abfe5b4b5b3c9765653c464f5da18df8971cf501d/future_fstrings-1.2.0.tar.gz", hash = "sha256:6cf41cbe97c398ab5a81168ce0dbb8ad95862d3caf23c21e4430627b90844089", size = 5786 } +sdist = { url = "https://files.pythonhosted.org/packages/5d/e2/3874574cce18a2e3608abfe5b4b5b3c9765653c464f5da18df8971cf501d/future_fstrings-1.2.0.tar.gz", hash = "sha256:6cf41cbe97c398ab5a81168ce0dbb8ad95862d3caf23c21e4430627b90844089", size = 5786, upload-time = "2019-06-16T03:04:42.651Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/6d/ea1d52e9038558dd37f5d30647eb9f07888c164960a5d4daa5f970c6da25/future_fstrings-1.2.0-py2.py3-none-any.whl", hash = "sha256:90e49598b553d8746c4dc7d9442e0359d038c3039d802c91c0a55505da318c63", size = 6138 }, + { url = "https://files.pythonhosted.org/packages/ab/6d/ea1d52e9038558dd37f5d30647eb9f07888c164960a5d4daa5f970c6da25/future_fstrings-1.2.0-py2.py3-none-any.whl", hash = "sha256:90e49598b553d8746c4dc7d9442e0359d038c3039d802c91c0a55505da318c63", size = 6138, upload-time = "2019-06-16T03:04:40.395Z" }, ] [[package]] @@ -612,27 +624,29 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "python-dateutil" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d9/29/d40217cbe2f6b1359e00c6c307bb3fc876ba74068cbab3dde77f03ca0dc4/ghp-import-2.1.0.tar.gz", hash = "sha256:9c535c4c61193c2df8871222567d7fd7e5014d835f97dc7b7439069e2413d343", size = 10943 } +sdist = { url = "https://files.pythonhosted.org/packages/d9/29/d40217cbe2f6b1359e00c6c307bb3fc876ba74068cbab3dde77f03ca0dc4/ghp-import-2.1.0.tar.gz", hash = "sha256:9c535c4c61193c2df8871222567d7fd7e5014d835f97dc7b7439069e2413d343", size = 10943, upload-time = "2022-05-02T15:47:16.11Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f7/ec/67fbef5d497f86283db54c22eec6f6140243aae73265799baaaa19cd17fb/ghp_import-2.1.0-py3-none-any.whl", hash = "sha256:8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619", size = 11034 }, + { url = "https://files.pythonhosted.org/packages/f7/ec/67fbef5d497f86283db54c22eec6f6140243aae73265799baaaa19cd17fb/ghp_import-2.1.0-py3-none-any.whl", hash = "sha256:8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619", size = 11034, upload-time = "2022-05-02T15:47:14.552Z" }, ] [[package]] name = "google-crc32c" -version = "1.6.0" +version = "1.7.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/67/72/c3298da1a3773102359c5a78f20dae8925f5ea876e37354415f68594a6fb/google_crc32c-1.6.0.tar.gz", hash = "sha256:6eceb6ad197656a1ff49ebfbbfa870678c75be4344feb35ac1edf694309413dc", size = 14472 } +sdist = { url = "https://files.pythonhosted.org/packages/19/ae/87802e6d9f9d69adfaedfcfd599266bf386a54d0be058b532d04c794f76d/google_crc32c-1.7.1.tar.gz", hash = "sha256:2bff2305f98846f3e825dbeec9ee406f89da7962accdb29356e4eadc251bd472", size = 14495, upload-time = "2025-03-26T14:29:13.32Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7d/14/ab47972ac79b6e7b03c8be3a7ef44b530a60e69555668dbbf08fc5692a98/google_crc32c-1.6.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:f7a1fc29803712f80879b0806cb83ab24ce62fc8daf0569f2204a0cfd7f68ed4", size = 30267 }, - { url = "https://files.pythonhosted.org/packages/54/7d/738cb0d25ee55629e7d07da686decf03864a366e5e863091a97b7bd2b8aa/google_crc32c-1.6.0-cp311-cp311-macosx_12_0_x86_64.whl", hash = "sha256:40b05ab32a5067525670880eb5d169529089a26fe35dce8891127aeddc1950e8", size = 30112 }, - { url = "https://files.pythonhosted.org/packages/3e/6d/33ca50cbdeec09c31bb5dac277c90994edee975662a4c890bda7ffac90ef/google_crc32c-1.6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a9e4b426c3702f3cd23b933436487eb34e01e00327fac20c9aebb68ccf34117d", size = 32861 }, - { url = "https://files.pythonhosted.org/packages/67/1e/4870896fc81ec77b1b5ebae7fdd680d5a4d40e19a4b6d724032f996ca77a/google_crc32c-1.6.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:51c4f54dd8c6dfeb58d1df5e4f7f97df8abf17a36626a217f169893d1d7f3e9f", size = 32490 }, - { url = "https://files.pythonhosted.org/packages/00/9c/f5f5af3ddaa7a639d915f8f58b09bbb8d1db90ecd0459b62cd430eb9a4b6/google_crc32c-1.6.0-cp311-cp311-win_amd64.whl", hash = "sha256:bb8b3c75bd157010459b15222c3fd30577042a7060e29d42dabce449c087f2b3", size = 33446 }, - { url = "https://files.pythonhosted.org/packages/cf/41/65a91657d6a8123c6c12f9aac72127b6ac76dda9e2ba1834026a842eb77c/google_crc32c-1.6.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:ed767bf4ba90104c1216b68111613f0d5926fb3780660ea1198fc469af410e9d", size = 30268 }, - { url = "https://files.pythonhosted.org/packages/59/d0/ee743a267c7d5c4bb8bd865f7d4c039505f1c8a4b439df047fdc17be9769/google_crc32c-1.6.0-cp312-cp312-macosx_12_0_x86_64.whl", hash = "sha256:62f6d4a29fea082ac4a3c9be5e415218255cf11684ac6ef5488eea0c9132689b", size = 30113 }, - { url = "https://files.pythonhosted.org/packages/25/53/e5e449c368dd26ade5fb2bb209e046d4309ed0623be65b13f0ce026cb520/google_crc32c-1.6.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c87d98c7c4a69066fd31701c4e10d178a648c2cac3452e62c6b24dc51f9fcc00", size = 32995 }, - { url = "https://files.pythonhosted.org/packages/52/12/9bf6042d5b0ac8c25afed562fb78e51b0641474097e4139e858b45de40a5/google_crc32c-1.6.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bd5e7d2445d1a958c266bfa5d04c39932dc54093fa391736dbfdb0f1929c1fb3", size = 32614 }, - { url = "https://files.pythonhosted.org/packages/76/29/fc20f5ec36eac1eea0d0b2de4118c774c5f59c513f2a8630d4db6991f3e0/google_crc32c-1.6.0-cp312-cp312-win_amd64.whl", hash = "sha256:7aec8e88a3583515f9e0957fe4f5f6d8d4997e36d0f61624e70469771584c760", size = 33445 }, + { url = "https://files.pythonhosted.org/packages/f7/94/220139ea87822b6fdfdab4fb9ba81b3fff7ea2c82e2af34adc726085bffc/google_crc32c-1.7.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:6fbab4b935989e2c3610371963ba1b86afb09537fd0c633049be82afe153ac06", size = 30468, upload-time = "2025-03-26T14:32:52.215Z" }, + { url = "https://files.pythonhosted.org/packages/94/97/789b23bdeeb9d15dc2904660463ad539d0318286d7633fe2760c10ed0c1c/google_crc32c-1.7.1-cp311-cp311-macosx_12_0_x86_64.whl", hash = "sha256:ed66cbe1ed9cbaaad9392b5259b3eba4a9e565420d734e6238813c428c3336c9", size = 30313, upload-time = "2025-03-26T14:57:38.758Z" }, + { url = "https://files.pythonhosted.org/packages/81/b8/976a2b843610c211e7ccb3e248996a61e87dbb2c09b1499847e295080aec/google_crc32c-1.7.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ee6547b657621b6cbed3562ea7826c3e11cab01cd33b74e1f677690652883e77", size = 33048, upload-time = "2025-03-26T14:41:30.679Z" }, + { url = "https://files.pythonhosted.org/packages/c9/16/a3842c2cf591093b111d4a5e2bfb478ac6692d02f1b386d2a33283a19dc9/google_crc32c-1.7.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d68e17bad8f7dd9a49181a1f5a8f4b251c6dbc8cc96fb79f1d321dfd57d66f53", size = 32669, upload-time = "2025-03-26T14:41:31.432Z" }, + { url = "https://files.pythonhosted.org/packages/04/17/ed9aba495916fcf5fe4ecb2267ceb851fc5f273c4e4625ae453350cfd564/google_crc32c-1.7.1-cp311-cp311-win_amd64.whl", hash = "sha256:6335de12921f06e1f774d0dd1fbea6bf610abe0887a1638f64d694013138be5d", size = 33476, upload-time = "2025-03-26T14:29:10.211Z" }, + { url = "https://files.pythonhosted.org/packages/dd/b7/787e2453cf8639c94b3d06c9d61f512234a82e1d12d13d18584bd3049904/google_crc32c-1.7.1-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:2d73a68a653c57281401871dd4aeebbb6af3191dcac751a76ce430df4d403194", size = 30470, upload-time = "2025-03-26T14:34:31.655Z" }, + { url = "https://files.pythonhosted.org/packages/ed/b4/6042c2b0cbac3ec3a69bb4c49b28d2f517b7a0f4a0232603c42c58e22b44/google_crc32c-1.7.1-cp312-cp312-macosx_12_0_x86_64.whl", hash = "sha256:22beacf83baaf59f9d3ab2bbb4db0fb018da8e5aebdce07ef9f09fce8220285e", size = 30315, upload-time = "2025-03-26T15:01:54.634Z" }, + { url = "https://files.pythonhosted.org/packages/29/ad/01e7a61a5d059bc57b702d9ff6a18b2585ad97f720bd0a0dbe215df1ab0e/google_crc32c-1.7.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:19eafa0e4af11b0a4eb3974483d55d2d77ad1911e6cf6f832e1574f6781fd337", size = 33180, upload-time = "2025-03-26T14:41:32.168Z" }, + { url = "https://files.pythonhosted.org/packages/3b/a5/7279055cf004561894ed3a7bfdf5bf90a53f28fadd01af7cd166e88ddf16/google_crc32c-1.7.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b6d86616faaea68101195c6bdc40c494e4d76f41e07a37ffdef270879c15fb65", size = 32794, upload-time = "2025-03-26T14:41:33.264Z" }, + { url = "https://files.pythonhosted.org/packages/0f/d6/77060dbd140c624e42ae3ece3df53b9d811000729a5c821b9fd671ceaac6/google_crc32c-1.7.1-cp312-cp312-win_amd64.whl", hash = "sha256:b7491bdc0c7564fcf48c0179d2048ab2f7c7ba36b84ccd3a3e1c3f7a72d3bba6", size = 33477, upload-time = "2025-03-26T14:29:10.94Z" }, + { url = "https://files.pythonhosted.org/packages/16/1b/1693372bf423ada422f80fd88260dbfd140754adb15cbc4d7e9a68b1cb8e/google_crc32c-1.7.1-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:85fef7fae11494e747c9fd1359a527e5970fc9603c90764843caabd3a16a0a48", size = 28241, upload-time = "2025-03-26T14:41:45.898Z" }, + { url = "https://files.pythonhosted.org/packages/fd/3c/2a19a60a473de48717b4efb19398c3f914795b64a96cf3fbe82588044f78/google_crc32c-1.7.1-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6efb97eb4369d52593ad6f75e7e10d053cf00c48983f7a973105bc70b0ac4d82", size = 28048, upload-time = "2025-03-26T14:41:46.696Z" }, ] [[package]] @@ -640,14 +654,14 @@ name = "gymnasium" version = "1.1.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cloudpickle", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "farama-notifications", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "numpy", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "typing-extensions", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "cloudpickle" }, + { name = "farama-notifications" }, + { name = "numpy" }, + { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/90/69/70cd29e9fc4953d013b15981ee71d4c9ef4d8b2183e6ef2fe89756746dce/gymnasium-1.1.1.tar.gz", hash = "sha256:8bd9ea9bdef32c950a444ff36afc785e1d81051ec32d30435058953c20d2456d", size = 829326 } +sdist = { url = "https://files.pythonhosted.org/packages/90/69/70cd29e9fc4953d013b15981ee71d4c9ef4d8b2183e6ef2fe89756746dce/gymnasium-1.1.1.tar.gz", hash = "sha256:8bd9ea9bdef32c950a444ff36afc785e1d81051ec32d30435058953c20d2456d", size = 829326, upload-time = "2025-03-06T16:30:36.428Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f9/68/2bdc7b46b5f543dd865575f9d19716866bdb76e50dd33b71ed1a3dd8bb42/gymnasium-1.1.1-py3-none-any.whl", hash = "sha256:9c167ec0a2b388666e37f63b2849cd2552f7f5b71938574c637bb36487eb928a", size = 965410 }, + { url = "https://files.pythonhosted.org/packages/f9/68/2bdc7b46b5f543dd865575f9d19716866bdb76e50dd33b71ed1a3dd8bb42/gymnasium-1.1.1-py3-none-any.whl", hash = "sha256:9c167ec0a2b388666e37f63b2849cd2552f7f5b71938574c637bb36487eb928a", size = 965410, upload-time = "2025-03-06T16:30:34.443Z" }, ] [[package]] @@ -658,54 +672,54 @@ dependencies = [ { name = "attrs" }, { name = "sortedcontainers" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/45/f2/f77da8271b1abb630cb2090ead2f5aa4acc9639d632e8e68187f52527e4b/hypothesis-6.47.5.tar.gz", hash = "sha256:e0c1e253fc97e7ecdb9e2bbff2cf815d8739e0d1d3d093d67c3af5bb6a7211b0", size = 326641 } +sdist = { url = "https://files.pythonhosted.org/packages/45/f2/f77da8271b1abb630cb2090ead2f5aa4acc9639d632e8e68187f52527e4b/hypothesis-6.47.5.tar.gz", hash = "sha256:e0c1e253fc97e7ecdb9e2bbff2cf815d8739e0d1d3d093d67c3af5bb6a7211b0", size = 326641, upload-time = "2022-06-25T20:58:48.926Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d3/a7/389bbaade2cbbb2534cb2715986041ed01c6d792152c527e71f7f68e93b5/hypothesis-6.47.5-py3-none-any.whl", hash = "sha256:87049b781ee11ec1c7948565b889ab02e428a1e32d427ab4de8fdb3649242d06", size = 387311 }, + { url = "https://files.pythonhosted.org/packages/d3/a7/389bbaade2cbbb2534cb2715986041ed01c6d792152c527e71f7f68e93b5/hypothesis-6.47.5-py3-none-any.whl", hash = "sha256:87049b781ee11ec1c7948565b889ab02e428a1e32d427ab4de8fdb3649242d06", size = 387311, upload-time = "2022-06-25T20:58:45.281Z" }, ] [[package]] name = "idna" version = "3.10" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f1/70/7703c29685631f5a7590aa73f1f1d3fa9a380e654b86af429e0934a32f7d/idna-3.10.tar.gz", hash = "sha256:12f65c9b470abda6dc35cf8e63cc574b1c52b11df2c86030af0ac09b01b13ea9", size = 190490 } +sdist = { url = "https://files.pythonhosted.org/packages/f1/70/7703c29685631f5a7590aa73f1f1d3fa9a380e654b86af429e0934a32f7d/idna-3.10.tar.gz", hash = "sha256:12f65c9b470abda6dc35cf8e63cc574b1c52b11df2c86030af0ac09b01b13ea9", size = 190490, upload-time = "2024-09-15T18:07:39.745Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/76/c6/c88e154df9c4e1a2a66ccf0005a88dfb2650c1dffb6f5ce603dfbd452ce3/idna-3.10-py3-none-any.whl", hash = "sha256:946d195a0d259cbba61165e88e65941f16e9b36ea6ddb97f00452bae8b1287d3", size = 70442 }, + { url = "https://files.pythonhosted.org/packages/76/c6/c88e154df9c4e1a2a66ccf0005a88dfb2650c1dffb6f5ce603dfbd452ce3/idna-3.10-py3-none-any.whl", hash = "sha256:946d195a0d259cbba61165e88e65941f16e9b36ea6ddb97f00452bae8b1287d3", size = 70442, upload-time = "2024-09-15T18:07:37.964Z" }, ] [[package]] name = "ifaddr" version = "0.2.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e8/ac/fb4c578f4a3256561548cd825646680edcadb9440f3f68add95ade1eb791/ifaddr-0.2.0.tar.gz", hash = "sha256:cc0cbfcaabf765d44595825fb96a99bb12c79716b73b44330ea38ee2b0c4aed4", size = 10485 } +sdist = { url = "https://files.pythonhosted.org/packages/e8/ac/fb4c578f4a3256561548cd825646680edcadb9440f3f68add95ade1eb791/ifaddr-0.2.0.tar.gz", hash = "sha256:cc0cbfcaabf765d44595825fb96a99bb12c79716b73b44330ea38ee2b0c4aed4", size = 10485, upload-time = "2022-06-15T21:40:27.561Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9c/1f/19ebc343cc71a7ffa78f17018535adc5cbdd87afb31d7c34874680148b32/ifaddr-0.2.0-py3-none-any.whl", hash = "sha256:085e0305cfe6f16ab12d72e2024030f5d52674afad6911bb1eee207177b8a748", size = 12314 }, + { url = "https://files.pythonhosted.org/packages/9c/1f/19ebc343cc71a7ffa78f17018535adc5cbdd87afb31d7c34874680148b32/ifaddr-0.2.0-py3-none-any.whl", hash = "sha256:085e0305cfe6f16ab12d72e2024030f5d52674afad6911bb1eee207177b8a748", size = 12314, upload-time = "2022-06-15T21:40:25.756Z" }, ] [[package]] name = "iniconfig" -version = "2.0.0" +version = "2.1.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d7/4b/cbd8e699e64a6f16ca3a8220661b5f83792b3017d0f79807cb8708d33913/iniconfig-2.0.0.tar.gz", hash = "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3", size = 4646 } +sdist = { url = "https://files.pythonhosted.org/packages/f2/97/ebf4da567aa6827c909642694d71c9fcf53e5b504f2d96afea02718862f3/iniconfig-2.1.0.tar.gz", hash = "sha256:3abbd2e30b36733fee78f9c7f7308f2d0050e88f0087fd25c2645f63c773e1c7", size = 4793, upload-time = "2025-03-19T20:09:59.721Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ef/a6/62565a6e1cf69e10f5727360368e451d4b7f58beeac6173dc9db836a5b46/iniconfig-2.0.0-py3-none-any.whl", hash = "sha256:b6a85871a79d2e3b22d2d1b94ac2824226a63c6b741c88f7ae975f18b6778374", size = 5892 }, + { url = "https://files.pythonhosted.org/packages/2c/e1/e6716421ea10d38022b952c159d5161ca1193197fb744506875fbb87ea7b/iniconfig-2.1.0-py3-none-any.whl", hash = "sha256:9deba5723312380e77435581c6bf4935c94cbfab9b1ed33ef8d238ea168eb760", size = 6050, upload-time = "2025-03-19T20:10:01.071Z" }, ] [[package]] name = "inputs" version = "0.5" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d1/cd/5f434220920f76eb73d19bb7aab8d857445f40aa642718e6e51e850cd663/inputs-0.5.tar.gz", hash = "sha256:a31d5b96a3525f1232f326be9e7ce8ccaf873c6b1fb84d9f3c9bc3d79b23eae4", size = 33393 } +sdist = { url = "https://files.pythonhosted.org/packages/d1/cd/5f434220920f76eb73d19bb7aab8d857445f40aa642718e6e51e850cd663/inputs-0.5.tar.gz", hash = "sha256:a31d5b96a3525f1232f326be9e7ce8ccaf873c6b1fb84d9f3c9bc3d79b23eae4", size = 33393, upload-time = "2018-10-05T22:38:14.206Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d0/94/040a0d9c81f018c39bd887b7b825013b024deb0a6c795f9524797e2cd41b/inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec", size = 33630 }, + { url = "https://files.pythonhosted.org/packages/d0/94/040a0d9c81f018c39bd887b7b825013b024deb0a6c795f9524797e2cd41b/inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec", size = 33630, upload-time = "2018-10-05T22:38:28.28Z" }, ] [[package]] name = "isodate" version = "0.7.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/54/4d/e940025e2ce31a8ce1202635910747e5a87cc3a6a6bb2d00973375014749/isodate-0.7.2.tar.gz", hash = "sha256:4cd1aa0f43ca76f4a6c6c0292a85f40b35ec2e43e315b59f06e6d32171a953e6", size = 29705 } +sdist = { url = "https://files.pythonhosted.org/packages/54/4d/e940025e2ce31a8ce1202635910747e5a87cc3a6a6bb2d00973375014749/isodate-0.7.2.tar.gz", hash = "sha256:4cd1aa0f43ca76f4a6c6c0292a85f40b35ec2e43e315b59f06e6d32171a953e6", size = 29705, upload-time = "2024-10-08T23:04:11.5Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/15/aa/0aca39a37d3c7eb941ba736ede56d689e7be91cab5d9ca846bde3999eba6/isodate-0.7.2-py3-none-any.whl", hash = "sha256:28009937d8031054830160fce6d409ed342816b543597cece116d966c6d99e15", size = 22320 }, + { url = "https://files.pythonhosted.org/packages/15/aa/0aca39a37d3c7eb941ba736ede56d689e7be91cab5d9ca846bde3999eba6/isodate-0.7.2-py3-none-any.whl", hash = "sha256:28009937d8031054830160fce6d409ed342816b543597cece116d966c6d99e15", size = 22320, upload-time = "2024-10-08T23:04:09.501Z" }, ] [[package]] @@ -715,203 +729,203 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "markupsafe" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/df/bf/f7da0350254c0ed7c72f3e33cef02e048281fec7ecec5f032d4aac52226b/jinja2-3.1.6.tar.gz", hash = "sha256:0137fb05990d35f1275a587e9aee6d56da821fc83491a0fb838183be43f66d6d", size = 245115 } +sdist = { url = "https://files.pythonhosted.org/packages/df/bf/f7da0350254c0ed7c72f3e33cef02e048281fec7ecec5f032d4aac52226b/jinja2-3.1.6.tar.gz", hash = "sha256:0137fb05990d35f1275a587e9aee6d56da821fc83491a0fb838183be43f66d6d", size = 245115, upload-time = "2025-03-05T20:05:02.478Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl", hash = "sha256:85ece4451f492d0c13c5dd7c13a64681a86afae63a5f347908daf103ce6d2f67", size = 134899 }, + { url = "https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl", hash = "sha256:85ece4451f492d0c13c5dd7c13a64681a86afae63a5f347908daf103ce6d2f67", size = 134899, upload-time = "2025-03-05T20:05:00.369Z" }, ] [[package]] name = "json-rpc" version = "1.15.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/6d/9e/59f4a5b7855ced7346ebf40a2e9a8942863f644378d956f68bcef2c88b90/json-rpc-1.15.0.tar.gz", hash = "sha256:e6441d56c1dcd54241c937d0a2dcd193bdf0bdc539b5316524713f554b7f85b9", size = 28854 } +sdist = { url = "https://files.pythonhosted.org/packages/6d/9e/59f4a5b7855ced7346ebf40a2e9a8942863f644378d956f68bcef2c88b90/json-rpc-1.15.0.tar.gz", hash = "sha256:e6441d56c1dcd54241c937d0a2dcd193bdf0bdc539b5316524713f554b7f85b9", size = 28854, upload-time = "2023-06-11T09:45:49.078Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/94/9e/820c4b086ad01ba7d77369fb8b11470a01fac9b4977f02e18659cf378b6b/json_rpc-1.15.0-py2.py3-none-any.whl", hash = "sha256:4a4668bbbe7116feb4abbd0f54e64a4adcf4b8f648f19ffa0848ad0f6606a9bf", size = 39450 }, + { url = "https://files.pythonhosted.org/packages/94/9e/820c4b086ad01ba7d77369fb8b11470a01fac9b4977f02e18659cf378b6b/json_rpc-1.15.0-py2.py3-none-any.whl", hash = "sha256:4a4668bbbe7116feb4abbd0f54e64a4adcf4b8f648f19ffa0848ad0f6606a9bf", size = 39450, upload-time = "2023-06-11T09:45:47.136Z" }, ] [[package]] name = "kiwisolver" version = "1.4.8" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/82/59/7c91426a8ac292e1cdd53a63b6d9439abd573c875c3f92c146767dd33faf/kiwisolver-1.4.8.tar.gz", hash = "sha256:23d5f023bdc8c7e54eb65f03ca5d5bb25b601eac4d7f1a042888a1f45237987e", size = 97538 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/da/ed/c913ee28936c371418cb167b128066ffb20bbf37771eecc2c97edf8a6e4c/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a4d3601908c560bdf880f07d94f31d734afd1bb71e96585cace0e38ef44c6d84", size = 124635 }, - { url = "https://files.pythonhosted.org/packages/4c/45/4a7f896f7467aaf5f56ef093d1f329346f3b594e77c6a3c327b2d415f521/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:856b269c4d28a5c0d5e6c1955ec36ebfd1651ac00e1ce0afa3e28da95293b561", size = 66717 }, - { url = "https://files.pythonhosted.org/packages/5f/b4/c12b3ac0852a3a68f94598d4c8d569f55361beef6159dce4e7b624160da2/kiwisolver-1.4.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c2b9a96e0f326205af81a15718a9073328df1173a2619a68553decb7097fd5d7", size = 65413 }, - { url = "https://files.pythonhosted.org/packages/a9/98/1df4089b1ed23d83d410adfdc5947245c753bddfbe06541c4aae330e9e70/kiwisolver-1.4.8-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c5020c83e8553f770cb3b5fc13faac40f17e0b205bd237aebd21d53d733adb03", size = 1343994 }, - { url = "https://files.pythonhosted.org/packages/8d/bf/b4b169b050c8421a7c53ea1ea74e4ef9c335ee9013216c558a047f162d20/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dace81d28c787956bfbfbbfd72fdcef014f37d9b48830829e488fdb32b49d954", size = 1434804 }, - { url = "https://files.pythonhosted.org/packages/66/5a/e13bd341fbcf73325ea60fdc8af752addf75c5079867af2e04cc41f34434/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:11e1022b524bd48ae56c9b4f9296bce77e15a2e42a502cceba602f804b32bb79", size = 1450690 }, - { url = "https://files.pythonhosted.org/packages/9b/4f/5955dcb376ba4a830384cc6fab7d7547bd6759fe75a09564910e9e3bb8ea/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3b9b4d2892fefc886f30301cdd80debd8bb01ecdf165a449eb6e78f79f0fabd6", size = 1376839 }, - { url = "https://files.pythonhosted.org/packages/3a/97/5edbed69a9d0caa2e4aa616ae7df8127e10f6586940aa683a496c2c280b9/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a96c0e790ee875d65e340ab383700e2b4891677b7fcd30a699146f9384a2bb0", size = 1435109 }, - { url = "https://files.pythonhosted.org/packages/13/fc/e756382cb64e556af6c1809a1bbb22c141bbc2445049f2da06b420fe52bf/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23454ff084b07ac54ca8be535f4174170c1094a4cff78fbae4f73a4bcc0d4dab", size = 2245269 }, - { url = "https://files.pythonhosted.org/packages/76/15/e59e45829d7f41c776d138245cabae6515cb4eb44b418f6d4109c478b481/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:87b287251ad6488e95b4f0b4a79a6d04d3ea35fde6340eb38fbd1ca9cd35bbbc", size = 2393468 }, - { url = "https://files.pythonhosted.org/packages/e9/39/483558c2a913ab8384d6e4b66a932406f87c95a6080112433da5ed668559/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:b21dbe165081142b1232a240fc6383fd32cdd877ca6cc89eab93e5f5883e1c25", size = 2355394 }, - { url = "https://files.pythonhosted.org/packages/01/aa/efad1fbca6570a161d29224f14b082960c7e08268a133fe5dc0f6906820e/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:768cade2c2df13db52475bd28d3a3fac8c9eff04b0e9e2fda0f3760f20b3f7fc", size = 2490901 }, - { url = "https://files.pythonhosted.org/packages/c9/4f/15988966ba46bcd5ab9d0c8296914436720dd67fca689ae1a75b4ec1c72f/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d47cfb2650f0e103d4bf68b0b5804c68da97272c84bb12850d877a95c056bd67", size = 2312306 }, - { url = "https://files.pythonhosted.org/packages/2d/27/bdf1c769c83f74d98cbc34483a972f221440703054894a37d174fba8aa68/kiwisolver-1.4.8-cp311-cp311-win_amd64.whl", hash = "sha256:ed33ca2002a779a2e20eeb06aea7721b6e47f2d4b8a8ece979d8ba9e2a167e34", size = 71966 }, - { url = "https://files.pythonhosted.org/packages/4a/c9/9642ea855604aeb2968a8e145fc662edf61db7632ad2e4fb92424be6b6c0/kiwisolver-1.4.8-cp311-cp311-win_arm64.whl", hash = "sha256:16523b40aab60426ffdebe33ac374457cf62863e330a90a0383639ce14bf44b2", size = 65311 }, - { url = "https://files.pythonhosted.org/packages/fc/aa/cea685c4ab647f349c3bc92d2daf7ae34c8e8cf405a6dcd3a497f58a2ac3/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d6af5e8815fd02997cb6ad9bbed0ee1e60014438ee1a5c2444c96f87b8843502", size = 124152 }, - { url = "https://files.pythonhosted.org/packages/c5/0b/8db6d2e2452d60d5ebc4ce4b204feeb16176a851fd42462f66ade6808084/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:bade438f86e21d91e0cf5dd7c0ed00cda0f77c8c1616bd83f9fc157fa6760d31", size = 66555 }, - { url = "https://files.pythonhosted.org/packages/60/26/d6a0db6785dd35d3ba5bf2b2df0aedc5af089962c6eb2cbf67a15b81369e/kiwisolver-1.4.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b83dc6769ddbc57613280118fb4ce3cd08899cc3369f7d0e0fab518a7cf37fdb", size = 65067 }, - { url = "https://files.pythonhosted.org/packages/c9/ed/1d97f7e3561e09757a196231edccc1bcf59d55ddccefa2afc9c615abd8e0/kiwisolver-1.4.8-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:111793b232842991be367ed828076b03d96202c19221b5ebab421ce8bcad016f", size = 1378443 }, - { url = "https://files.pythonhosted.org/packages/29/61/39d30b99954e6b46f760e6289c12fede2ab96a254c443639052d1b573fbc/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:257af1622860e51b1a9d0ce387bf5c2c4f36a90594cb9514f55b074bcc787cfc", size = 1472728 }, - { url = "https://files.pythonhosted.org/packages/0c/3e/804163b932f7603ef256e4a715e5843a9600802bb23a68b4e08c8c0ff61d/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:69b5637c3f316cab1ec1c9a12b8c5f4750a4c4b71af9157645bf32830e39c03a", size = 1478388 }, - { url = "https://files.pythonhosted.org/packages/8a/9e/60eaa75169a154700be74f875a4d9961b11ba048bef315fbe89cb6999056/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:782bb86f245ec18009890e7cb8d13a5ef54dcf2ebe18ed65f795e635a96a1c6a", size = 1413849 }, - { url = "https://files.pythonhosted.org/packages/bc/b3/9458adb9472e61a998c8c4d95cfdfec91c73c53a375b30b1428310f923e4/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cc978a80a0db3a66d25767b03688f1147a69e6237175c0f4ffffaaedf744055a", size = 1475533 }, - { url = "https://files.pythonhosted.org/packages/e4/7a/0a42d9571e35798de80aef4bb43a9b672aa7f8e58643d7bd1950398ffb0a/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:36dbbfd34838500a31f52c9786990d00150860e46cd5041386f217101350f0d3", size = 2268898 }, - { url = "https://files.pythonhosted.org/packages/d9/07/1255dc8d80271400126ed8db35a1795b1a2c098ac3a72645075d06fe5c5d/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:eaa973f1e05131de5ff3569bbba7f5fd07ea0595d3870ed4a526d486fe57fa1b", size = 2425605 }, - { url = "https://files.pythonhosted.org/packages/84/df/5a3b4cf13780ef6f6942df67b138b03b7e79e9f1f08f57c49957d5867f6e/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:a66f60f8d0c87ab7f59b6fb80e642ebb29fec354a4dfad687ca4092ae69d04f4", size = 2375801 }, - { url = "https://files.pythonhosted.org/packages/8f/10/2348d068e8b0f635c8c86892788dac7a6b5c0cb12356620ab575775aad89/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:858416b7fb777a53f0c59ca08190ce24e9abbd3cffa18886a5781b8e3e26f65d", size = 2520077 }, - { url = "https://files.pythonhosted.org/packages/32/d8/014b89fee5d4dce157d814303b0fce4d31385a2af4c41fed194b173b81ac/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:085940635c62697391baafaaeabdf3dd7a6c3643577dde337f4d66eba021b2b8", size = 2338410 }, - { url = "https://files.pythonhosted.org/packages/bd/72/dfff0cc97f2a0776e1c9eb5bef1ddfd45f46246c6533b0191887a427bca5/kiwisolver-1.4.8-cp312-cp312-win_amd64.whl", hash = "sha256:01c3d31902c7db5fb6182832713d3b4122ad9317c2c5877d0539227d96bb2e50", size = 71853 }, - { url = "https://files.pythonhosted.org/packages/dc/85/220d13d914485c0948a00f0b9eb419efaf6da81b7d72e88ce2391f7aed8d/kiwisolver-1.4.8-cp312-cp312-win_arm64.whl", hash = "sha256:a3c44cb68861de93f0c4a8175fbaa691f0aa22550c331fefef02b618a9dcb476", size = 65424 }, +sdist = { url = "https://files.pythonhosted.org/packages/82/59/7c91426a8ac292e1cdd53a63b6d9439abd573c875c3f92c146767dd33faf/kiwisolver-1.4.8.tar.gz", hash = "sha256:23d5f023bdc8c7e54eb65f03ca5d5bb25b601eac4d7f1a042888a1f45237987e", size = 97538, upload-time = "2024-12-24T18:30:51.519Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/da/ed/c913ee28936c371418cb167b128066ffb20bbf37771eecc2c97edf8a6e4c/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a4d3601908c560bdf880f07d94f31d734afd1bb71e96585cace0e38ef44c6d84", size = 124635, upload-time = "2024-12-24T18:28:51.826Z" }, + { url = "https://files.pythonhosted.org/packages/4c/45/4a7f896f7467aaf5f56ef093d1f329346f3b594e77c6a3c327b2d415f521/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:856b269c4d28a5c0d5e6c1955ec36ebfd1651ac00e1ce0afa3e28da95293b561", size = 66717, upload-time = "2024-12-24T18:28:54.256Z" }, + { url = "https://files.pythonhosted.org/packages/5f/b4/c12b3ac0852a3a68f94598d4c8d569f55361beef6159dce4e7b624160da2/kiwisolver-1.4.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c2b9a96e0f326205af81a15718a9073328df1173a2619a68553decb7097fd5d7", size = 65413, upload-time = "2024-12-24T18:28:55.184Z" }, + { url = "https://files.pythonhosted.org/packages/a9/98/1df4089b1ed23d83d410adfdc5947245c753bddfbe06541c4aae330e9e70/kiwisolver-1.4.8-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c5020c83e8553f770cb3b5fc13faac40f17e0b205bd237aebd21d53d733adb03", size = 1343994, upload-time = "2024-12-24T18:28:57.493Z" }, + { url = "https://files.pythonhosted.org/packages/8d/bf/b4b169b050c8421a7c53ea1ea74e4ef9c335ee9013216c558a047f162d20/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dace81d28c787956bfbfbbfd72fdcef014f37d9b48830829e488fdb32b49d954", size = 1434804, upload-time = "2024-12-24T18:29:00.077Z" }, + { url = "https://files.pythonhosted.org/packages/66/5a/e13bd341fbcf73325ea60fdc8af752addf75c5079867af2e04cc41f34434/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:11e1022b524bd48ae56c9b4f9296bce77e15a2e42a502cceba602f804b32bb79", size = 1450690, upload-time = "2024-12-24T18:29:01.401Z" }, + { url = "https://files.pythonhosted.org/packages/9b/4f/5955dcb376ba4a830384cc6fab7d7547bd6759fe75a09564910e9e3bb8ea/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3b9b4d2892fefc886f30301cdd80debd8bb01ecdf165a449eb6e78f79f0fabd6", size = 1376839, upload-time = "2024-12-24T18:29:02.685Z" }, + { url = "https://files.pythonhosted.org/packages/3a/97/5edbed69a9d0caa2e4aa616ae7df8127e10f6586940aa683a496c2c280b9/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a96c0e790ee875d65e340ab383700e2b4891677b7fcd30a699146f9384a2bb0", size = 1435109, upload-time = "2024-12-24T18:29:04.113Z" }, + { url = "https://files.pythonhosted.org/packages/13/fc/e756382cb64e556af6c1809a1bbb22c141bbc2445049f2da06b420fe52bf/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23454ff084b07ac54ca8be535f4174170c1094a4cff78fbae4f73a4bcc0d4dab", size = 2245269, upload-time = "2024-12-24T18:29:05.488Z" }, + { url = "https://files.pythonhosted.org/packages/76/15/e59e45829d7f41c776d138245cabae6515cb4eb44b418f6d4109c478b481/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:87b287251ad6488e95b4f0b4a79a6d04d3ea35fde6340eb38fbd1ca9cd35bbbc", size = 2393468, upload-time = "2024-12-24T18:29:06.79Z" }, + { url = "https://files.pythonhosted.org/packages/e9/39/483558c2a913ab8384d6e4b66a932406f87c95a6080112433da5ed668559/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:b21dbe165081142b1232a240fc6383fd32cdd877ca6cc89eab93e5f5883e1c25", size = 2355394, upload-time = "2024-12-24T18:29:08.24Z" }, + { url = "https://files.pythonhosted.org/packages/01/aa/efad1fbca6570a161d29224f14b082960c7e08268a133fe5dc0f6906820e/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:768cade2c2df13db52475bd28d3a3fac8c9eff04b0e9e2fda0f3760f20b3f7fc", size = 2490901, upload-time = "2024-12-24T18:29:09.653Z" }, + { url = "https://files.pythonhosted.org/packages/c9/4f/15988966ba46bcd5ab9d0c8296914436720dd67fca689ae1a75b4ec1c72f/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d47cfb2650f0e103d4bf68b0b5804c68da97272c84bb12850d877a95c056bd67", size = 2312306, upload-time = "2024-12-24T18:29:12.644Z" }, + { url = "https://files.pythonhosted.org/packages/2d/27/bdf1c769c83f74d98cbc34483a972f221440703054894a37d174fba8aa68/kiwisolver-1.4.8-cp311-cp311-win_amd64.whl", hash = "sha256:ed33ca2002a779a2e20eeb06aea7721b6e47f2d4b8a8ece979d8ba9e2a167e34", size = 71966, upload-time = "2024-12-24T18:29:14.089Z" }, + { url = "https://files.pythonhosted.org/packages/4a/c9/9642ea855604aeb2968a8e145fc662edf61db7632ad2e4fb92424be6b6c0/kiwisolver-1.4.8-cp311-cp311-win_arm64.whl", hash = "sha256:16523b40aab60426ffdebe33ac374457cf62863e330a90a0383639ce14bf44b2", size = 65311, upload-time = "2024-12-24T18:29:15.892Z" }, + { url = "https://files.pythonhosted.org/packages/fc/aa/cea685c4ab647f349c3bc92d2daf7ae34c8e8cf405a6dcd3a497f58a2ac3/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d6af5e8815fd02997cb6ad9bbed0ee1e60014438ee1a5c2444c96f87b8843502", size = 124152, upload-time = "2024-12-24T18:29:16.85Z" }, + { url = "https://files.pythonhosted.org/packages/c5/0b/8db6d2e2452d60d5ebc4ce4b204feeb16176a851fd42462f66ade6808084/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:bade438f86e21d91e0cf5dd7c0ed00cda0f77c8c1616bd83f9fc157fa6760d31", size = 66555, upload-time = "2024-12-24T18:29:19.146Z" }, + { url = "https://files.pythonhosted.org/packages/60/26/d6a0db6785dd35d3ba5bf2b2df0aedc5af089962c6eb2cbf67a15b81369e/kiwisolver-1.4.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b83dc6769ddbc57613280118fb4ce3cd08899cc3369f7d0e0fab518a7cf37fdb", size = 65067, upload-time = "2024-12-24T18:29:20.096Z" }, + { url = "https://files.pythonhosted.org/packages/c9/ed/1d97f7e3561e09757a196231edccc1bcf59d55ddccefa2afc9c615abd8e0/kiwisolver-1.4.8-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:111793b232842991be367ed828076b03d96202c19221b5ebab421ce8bcad016f", size = 1378443, upload-time = "2024-12-24T18:29:22.843Z" }, + { url = "https://files.pythonhosted.org/packages/29/61/39d30b99954e6b46f760e6289c12fede2ab96a254c443639052d1b573fbc/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:257af1622860e51b1a9d0ce387bf5c2c4f36a90594cb9514f55b074bcc787cfc", size = 1472728, upload-time = "2024-12-24T18:29:24.463Z" }, + { url = "https://files.pythonhosted.org/packages/0c/3e/804163b932f7603ef256e4a715e5843a9600802bb23a68b4e08c8c0ff61d/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:69b5637c3f316cab1ec1c9a12b8c5f4750a4c4b71af9157645bf32830e39c03a", size = 1478388, upload-time = "2024-12-24T18:29:25.776Z" }, + { url = "https://files.pythonhosted.org/packages/8a/9e/60eaa75169a154700be74f875a4d9961b11ba048bef315fbe89cb6999056/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:782bb86f245ec18009890e7cb8d13a5ef54dcf2ebe18ed65f795e635a96a1c6a", size = 1413849, upload-time = "2024-12-24T18:29:27.202Z" }, + { url = "https://files.pythonhosted.org/packages/bc/b3/9458adb9472e61a998c8c4d95cfdfec91c73c53a375b30b1428310f923e4/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cc978a80a0db3a66d25767b03688f1147a69e6237175c0f4ffffaaedf744055a", size = 1475533, upload-time = "2024-12-24T18:29:28.638Z" }, + { url = "https://files.pythonhosted.org/packages/e4/7a/0a42d9571e35798de80aef4bb43a9b672aa7f8e58643d7bd1950398ffb0a/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:36dbbfd34838500a31f52c9786990d00150860e46cd5041386f217101350f0d3", size = 2268898, upload-time = "2024-12-24T18:29:30.368Z" }, + { url = "https://files.pythonhosted.org/packages/d9/07/1255dc8d80271400126ed8db35a1795b1a2c098ac3a72645075d06fe5c5d/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:eaa973f1e05131de5ff3569bbba7f5fd07ea0595d3870ed4a526d486fe57fa1b", size = 2425605, upload-time = "2024-12-24T18:29:33.151Z" }, + { url = "https://files.pythonhosted.org/packages/84/df/5a3b4cf13780ef6f6942df67b138b03b7e79e9f1f08f57c49957d5867f6e/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:a66f60f8d0c87ab7f59b6fb80e642ebb29fec354a4dfad687ca4092ae69d04f4", size = 2375801, upload-time = "2024-12-24T18:29:34.584Z" }, + { url = "https://files.pythonhosted.org/packages/8f/10/2348d068e8b0f635c8c86892788dac7a6b5c0cb12356620ab575775aad89/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:858416b7fb777a53f0c59ca08190ce24e9abbd3cffa18886a5781b8e3e26f65d", size = 2520077, upload-time = "2024-12-24T18:29:36.138Z" }, + { url = "https://files.pythonhosted.org/packages/32/d8/014b89fee5d4dce157d814303b0fce4d31385a2af4c41fed194b173b81ac/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:085940635c62697391baafaaeabdf3dd7a6c3643577dde337f4d66eba021b2b8", size = 2338410, upload-time = "2024-12-24T18:29:39.991Z" }, + { url = "https://files.pythonhosted.org/packages/bd/72/dfff0cc97f2a0776e1c9eb5bef1ddfd45f46246c6533b0191887a427bca5/kiwisolver-1.4.8-cp312-cp312-win_amd64.whl", hash = "sha256:01c3d31902c7db5fb6182832713d3b4122ad9317c2c5877d0539227d96bb2e50", size = 71853, upload-time = "2024-12-24T18:29:42.006Z" }, + { url = "https://files.pythonhosted.org/packages/dc/85/220d13d914485c0948a00f0b9eb419efaf6da81b7d72e88ce2391f7aed8d/kiwisolver-1.4.8-cp312-cp312-win_arm64.whl", hash = "sha256:a3c44cb68861de93f0c4a8175fbaa691f0aa22550c331fefef02b618a9dcb476", size = 65424, upload-time = "2024-12-24T18:29:44.38Z" }, ] [[package]] name = "libusb1" -version = "3.3.0" +version = "3.3.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/69/c7/3c441fb0628b5afdfe68768f90f8d6ce74dc08e72691fb78d0875db06c48/libusb1-3.3.0.tar.gz", hash = "sha256:b642aa518689f8e053f61955cba274e72bc8d0794c65d7990745aaae90dfc8a1", size = 107253 } +sdist = { url = "https://files.pythonhosted.org/packages/a2/7f/c59ad56d1bca8fa4321d1bb77ba4687775751a4deceec14943a44da18ca0/libusb1-3.3.1.tar.gz", hash = "sha256:3951d360f2daf0e0eacf839e15d2d1d2f4f5e7830231eb3188eeffef2dd17bad", size = 107600, upload-time = "2025-03-24T05:36:47.834Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c7/48/b24b810b14595bd4680030f73a31119120069a8857f41554f00e00b57229/libusb1-3.3.0-py3-none-any.whl", hash = "sha256:7923ff2bbe43878e1c7cf733fde49cca844ecada29dbc436033bca6171cda41f", size = 67044 }, - { url = "https://files.pythonhosted.org/packages/3f/45/52980eedf3fb78711960a558465b3d998beed327fcd2b8483119527adc44/libusb1-3.3.0-py3-none-win32.whl", hash = "sha256:270f35b3a8faddd63d78de9b2341e49f6aed6083dceb4b04f47b95fd944e8d00", size = 128992 }, - { url = "https://files.pythonhosted.org/packages/af/d3/992bfd5bcd9d7a978563d3dabb11d0fce5cf7ceea73d9633fbadba93df4e/libusb1-3.3.0-py3-none-win_amd64.whl", hash = "sha256:61e2b4efdbacdd689bf4eab6b9afa2d6ee8a4bae20ffbf7c5785024d25fa3258", size = 140624 }, + { url = "https://files.pythonhosted.org/packages/10/f7/4577cfc55c9520ecab5563173e83235382ac7980c8c2c08d6c9f7ef9e615/libusb1-3.3.1-py3-none-any.whl", hash = "sha256:808c9362299dcee01651aa87e71e9d681ccedb27fc4dbd70aaf14e245fb855f1", size = 67243, upload-time = "2025-03-24T05:36:42.312Z" }, + { url = "https://files.pythonhosted.org/packages/6a/60/d3fd4831c601f063a16fc59f465ef4c1108247b07fbff371a982bd1bac45/libusb1-3.3.1-py3-none-win32.whl", hash = "sha256:0ef69825173ce74af34444754c081cc324233edc6acc405658b3ad784833e076", size = 129576, upload-time = "2025-03-24T05:36:45.202Z" }, + { url = "https://files.pythonhosted.org/packages/94/6d/344a164d32d65d503ffe9201cd74cf13a020099dc446554d1e50b07f167b/libusb1-3.3.1-py3-none-win_amd64.whl", hash = "sha256:6e21b772d80d6487fbb55d3d2141218536db302da82f1983754e96c72781c102", size = 141080, upload-time = "2025-03-24T05:36:46.594Z" }, ] [[package]] name = "llvmlite" version = "0.44.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/89/6a/95a3d3610d5c75293d5dbbb2a76480d5d4eeba641557b69fe90af6c5b84e/llvmlite-0.44.0.tar.gz", hash = "sha256:07667d66a5d150abed9157ab6c0b9393c9356f229784a4385c02f99e94fc94d4", size = 171880 } +sdist = { url = "https://files.pythonhosted.org/packages/89/6a/95a3d3610d5c75293d5dbbb2a76480d5d4eeba641557b69fe90af6c5b84e/llvmlite-0.44.0.tar.gz", hash = "sha256:07667d66a5d150abed9157ab6c0b9393c9356f229784a4385c02f99e94fc94d4", size = 171880, upload-time = "2025-01-20T11:14:41.342Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b5/e2/86b245397052386595ad726f9742e5223d7aea999b18c518a50e96c3aca4/llvmlite-0.44.0-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:eed7d5f29136bda63b6d7804c279e2b72e08c952b7c5df61f45db408e0ee52f3", size = 28132305 }, - { url = "https://files.pythonhosted.org/packages/ff/ec/506902dc6870249fbe2466d9cf66d531265d0f3a1157213c8f986250c033/llvmlite-0.44.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ace564d9fa44bb91eb6e6d8e7754977783c68e90a471ea7ce913bff30bd62427", size = 26201090 }, - { url = "https://files.pythonhosted.org/packages/99/fe/d030f1849ebb1f394bb3f7adad5e729b634fb100515594aca25c354ffc62/llvmlite-0.44.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c5d22c3bfc842668168a786af4205ec8e3ad29fb1bc03fd11fd48460d0df64c1", size = 42361858 }, - { url = "https://files.pythonhosted.org/packages/d7/7a/ce6174664b9077fc673d172e4c888cb0b128e707e306bc33fff8c2035f0d/llvmlite-0.44.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f01a394e9c9b7b1d4e63c327b096d10f6f0ed149ef53d38a09b3749dcf8c9610", size = 41184200 }, - { url = "https://files.pythonhosted.org/packages/5f/c6/258801143975a6d09a373f2641237992496e15567b907a4d401839d671b8/llvmlite-0.44.0-cp311-cp311-win_amd64.whl", hash = "sha256:d8489634d43c20cd0ad71330dde1d5bc7b9966937a263ff1ec1cebb90dc50955", size = 30331193 }, - { url = "https://files.pythonhosted.org/packages/15/86/e3c3195b92e6e492458f16d233e58a1a812aa2bfbef9bdd0fbafcec85c60/llvmlite-0.44.0-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:1d671a56acf725bf1b531d5ef76b86660a5ab8ef19bb6a46064a705c6ca80aad", size = 28132297 }, - { url = "https://files.pythonhosted.org/packages/d6/53/373b6b8be67b9221d12b24125fd0ec56b1078b660eeae266ec388a6ac9a0/llvmlite-0.44.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5f79a728e0435493611c9f405168682bb75ffd1fbe6fc360733b850c80a026db", size = 26201105 }, - { url = "https://files.pythonhosted.org/packages/cb/da/8341fd3056419441286c8e26bf436923021005ece0bff5f41906476ae514/llvmlite-0.44.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0143a5ef336da14deaa8ec26c5449ad5b6a2b564df82fcef4be040b9cacfea9", size = 42361901 }, - { url = "https://files.pythonhosted.org/packages/53/ad/d79349dc07b8a395a99153d7ce8b01d6fcdc9f8231355a5df55ded649b61/llvmlite-0.44.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d752f89e31b66db6f8da06df8b39f9b91e78c5feea1bf9e8c1fba1d1c24c065d", size = 41184247 }, - { url = "https://files.pythonhosted.org/packages/e2/3b/a9a17366af80127bd09decbe2a54d8974b6d8b274b39bf47fbaedeec6307/llvmlite-0.44.0-cp312-cp312-win_amd64.whl", hash = "sha256:eae7e2d4ca8f88f89d315b48c6b741dcb925d6a1042da694aa16ab3dd4cbd3a1", size = 30332380 }, + { url = "https://files.pythonhosted.org/packages/b5/e2/86b245397052386595ad726f9742e5223d7aea999b18c518a50e96c3aca4/llvmlite-0.44.0-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:eed7d5f29136bda63b6d7804c279e2b72e08c952b7c5df61f45db408e0ee52f3", size = 28132305, upload-time = "2025-01-20T11:12:53.936Z" }, + { url = "https://files.pythonhosted.org/packages/ff/ec/506902dc6870249fbe2466d9cf66d531265d0f3a1157213c8f986250c033/llvmlite-0.44.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ace564d9fa44bb91eb6e6d8e7754977783c68e90a471ea7ce913bff30bd62427", size = 26201090, upload-time = "2025-01-20T11:12:59.847Z" }, + { url = "https://files.pythonhosted.org/packages/99/fe/d030f1849ebb1f394bb3f7adad5e729b634fb100515594aca25c354ffc62/llvmlite-0.44.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c5d22c3bfc842668168a786af4205ec8e3ad29fb1bc03fd11fd48460d0df64c1", size = 42361858, upload-time = "2025-01-20T11:13:07.623Z" }, + { url = "https://files.pythonhosted.org/packages/d7/7a/ce6174664b9077fc673d172e4c888cb0b128e707e306bc33fff8c2035f0d/llvmlite-0.44.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f01a394e9c9b7b1d4e63c327b096d10f6f0ed149ef53d38a09b3749dcf8c9610", size = 41184200, upload-time = "2025-01-20T11:13:20.058Z" }, + { url = "https://files.pythonhosted.org/packages/5f/c6/258801143975a6d09a373f2641237992496e15567b907a4d401839d671b8/llvmlite-0.44.0-cp311-cp311-win_amd64.whl", hash = "sha256:d8489634d43c20cd0ad71330dde1d5bc7b9966937a263ff1ec1cebb90dc50955", size = 30331193, upload-time = "2025-01-20T11:13:26.976Z" }, + { url = "https://files.pythonhosted.org/packages/15/86/e3c3195b92e6e492458f16d233e58a1a812aa2bfbef9bdd0fbafcec85c60/llvmlite-0.44.0-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:1d671a56acf725bf1b531d5ef76b86660a5ab8ef19bb6a46064a705c6ca80aad", size = 28132297, upload-time = "2025-01-20T11:13:32.57Z" }, + { url = "https://files.pythonhosted.org/packages/d6/53/373b6b8be67b9221d12b24125fd0ec56b1078b660eeae266ec388a6ac9a0/llvmlite-0.44.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5f79a728e0435493611c9f405168682bb75ffd1fbe6fc360733b850c80a026db", size = 26201105, upload-time = "2025-01-20T11:13:38.744Z" }, + { url = "https://files.pythonhosted.org/packages/cb/da/8341fd3056419441286c8e26bf436923021005ece0bff5f41906476ae514/llvmlite-0.44.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0143a5ef336da14deaa8ec26c5449ad5b6a2b564df82fcef4be040b9cacfea9", size = 42361901, upload-time = "2025-01-20T11:13:46.711Z" }, + { url = "https://files.pythonhosted.org/packages/53/ad/d79349dc07b8a395a99153d7ce8b01d6fcdc9f8231355a5df55ded649b61/llvmlite-0.44.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d752f89e31b66db6f8da06df8b39f9b91e78c5feea1bf9e8c1fba1d1c24c065d", size = 41184247, upload-time = "2025-01-20T11:13:56.159Z" }, + { url = "https://files.pythonhosted.org/packages/e2/3b/a9a17366af80127bd09decbe2a54d8974b6d8b274b39bf47fbaedeec6307/llvmlite-0.44.0-cp312-cp312-win_amd64.whl", hash = "sha256:eae7e2d4ca8f88f89d315b48c6b741dcb925d6a1042da694aa16ab3dd4cbd3a1", size = 30332380, upload-time = "2025-01-20T11:14:02.442Z" }, ] [[package]] name = "lru-dict" version = "1.3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/96/e3/42c87871920602a3c8300915bd0292f76eccc66c38f782397acbf8a62088/lru-dict-1.3.0.tar.gz", hash = "sha256:54fd1966d6bd1fcde781596cb86068214edeebff1db13a2cea11079e3fd07b6b", size = 13123 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/a8/c9/6fac0cb67160f0efa3cc76a6a7d04d5e21a516eeb991ebba08f4f8f01ec5/lru_dict-1.3.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:20c595764695d20bdc3ab9b582e0cc99814da183544afb83783a36d6741a0dac", size = 17750 }, - { url = "https://files.pythonhosted.org/packages/61/14/f90dee4bc547ae266dbeffd4e11611234bb6af511dea48f3bc8dac1de478/lru_dict-1.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d9b30a8f50c3fa72a494eca6be5810a1b5c89e4f0fda89374f0d1c5ad8d37d51", size = 11055 }, - { url = "https://files.pythonhosted.org/packages/4e/63/a0ae20525f9d52f62ac0def47935f8a2b3b6fcd2c145218b9a27fc1fb910/lru_dict-1.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9710737584650a4251b9a566cbb1a86f83437adb209c9ba43a4e756d12faf0d7", size = 11330 }, - { url = "https://files.pythonhosted.org/packages/e9/c6/8c2b81b61e5206910c81b712500736227289aefe4ccfb36137aa21807003/lru_dict-1.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b84c321ae34f2f40aae80e18b6fa08b31c90095792ab64bb99d2e385143effaa", size = 31793 }, - { url = "https://files.pythonhosted.org/packages/f9/d7/af9733f94df67a2e9e31ef47d4c41aff1836024f135cdbda4743eb628452/lru_dict-1.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:eed24272b4121b7c22f234daed99899817d81d671b3ed030c876ac88bc9dc890", size = 33090 }, - { url = "https://files.pythonhosted.org/packages/5b/6e/5b09b069a70028bcf05dbdc57a301fbe8b3bafecf916f2ed5a3065c79a71/lru_dict-1.3.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9bd13af06dab7c6ee92284fd02ed9a5613a07d5c1b41948dc8886e7207f86dfd", size = 29795 }, - { url = "https://files.pythonhosted.org/packages/21/92/4690daefc2602f7c3429ecf54572d37a9e3c372d370344d2185daa4d5ecc/lru_dict-1.3.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a1efc59bfba6aac33684d87b9e02813b0e2445b2f1c444dae2a0b396ad0ed60c", size = 31586 }, - { url = "https://files.pythonhosted.org/packages/3c/67/0a29a91087196b02f278d8765120ee4e7486f1f72a4c505fd1cd3109e627/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:cfaf75ac574447afcf8ad998789071af11d2bcf6f947643231f692948839bd98", size = 36662 }, - { url = "https://files.pythonhosted.org/packages/36/54/8d56c514cd2333b652bd44c8f1962ab986cbe68e8ad7258c9e0f360cddb6/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c95f8751e2abd6f778da0399c8e0239321d560dbc58cb063827123137d213242", size = 35118 }, - { url = "https://files.pythonhosted.org/packages/f5/9a/c7a175d10d503b86974cb07141ca175947145dd1c7370fcda86fbbcaf326/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:abd0c284b26b5c4ee806ca4f33ab5e16b4bf4d5ec9e093e75a6f6287acdde78e", size = 38198 }, - { url = "https://files.pythonhosted.org/packages/fd/59/2e5086c8e8a05a7282a824a2a37e3c45cd5714e7b83d8bc0267cb3bb5b4f/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:2a47740652b25900ac5ce52667b2eade28d8b5fdca0ccd3323459df710e8210a", size = 36542 }, - { url = "https://files.pythonhosted.org/packages/12/52/80d0a06e5f45fe7c278dd662da6ea5b39f2ff003248f448189932f6b71c2/lru_dict-1.3.0-cp311-cp311-win32.whl", hash = "sha256:a690c23fc353681ed8042d9fe8f48f0fb79a57b9a45daea2f0be1eef8a1a4aa4", size = 12533 }, - { url = "https://files.pythonhosted.org/packages/ce/fe/1f12f33513310860ec6d722709ec4ad8256d9dcc3385f6ae2a244e6e66f5/lru_dict-1.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:efd3f4e0385d18f20f7ea6b08af2574c1bfaa5cb590102ef1bee781bdfba84bc", size = 13651 }, - { url = "https://files.pythonhosted.org/packages/fc/5c/385f080747eb3083af87d8e4c9068f3c4cab89035f6982134889940dafd8/lru_dict-1.3.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:c279068f68af3b46a5d649855e1fb87f5705fe1f744a529d82b2885c0e1fc69d", size = 17174 }, - { url = "https://files.pythonhosted.org/packages/3c/de/5ef2ed75ce55d7059d1b96177ba04fa7ee1f35564f97bdfcd28fccfbe9d2/lru_dict-1.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:350e2233cfee9f326a0d7a08e309372d87186565e43a691b120006285a0ac549", size = 10742 }, - { url = "https://files.pythonhosted.org/packages/ca/05/f69a6abb0062d2cf2ce0aaf0284b105b97d1da024ca6d3d0730e6151242e/lru_dict-1.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4eafb188a84483b3231259bf19030859f070321b00326dcb8e8c6cbf7db4b12f", size = 11079 }, - { url = "https://files.pythonhosted.org/packages/ea/59/cf891143abe58a455b8eaa9175f0e80f624a146a2bf9a1ca842ee0ef930a/lru_dict-1.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73593791047e36b37fdc0b67b76aeed439fcea80959c7d46201240f9ec3b2563", size = 32469 }, - { url = "https://files.pythonhosted.org/packages/59/88/d5976e9f70107ce11e45d93c6f0c2d5eaa1fc30bb3c8f57525eda4510dff/lru_dict-1.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1958cb70b9542773d6241974646e5410e41ef32e5c9e437d44040d59bd80daf2", size = 33496 }, - { url = "https://files.pythonhosted.org/packages/6c/f8/94d6e910d54fc1fa05c0ee1cd608c39401866a18cf5e5aff238449b33c11/lru_dict-1.3.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bc1cd3ed2cee78a47f11f3b70be053903bda197a873fd146e25c60c8e5a32cd6", size = 29914 }, - { url = "https://files.pythonhosted.org/packages/ca/b9/9db79780c8a3cfd66bba6847773061e5cf8a3746950273b9985d47bbfe53/lru_dict-1.3.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82eb230d48eaebd6977a92ddaa6d788f14cf4f4bcf5bbffa4ddfd60d051aa9d4", size = 32241 }, - { url = "https://files.pythonhosted.org/packages/9b/b6/08a623019daec22a40c4d6d2c40851dfa3d129a53b2f9469db8eb13666c1/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:5ad659cbc349d0c9ba8e536b5f40f96a70c360f43323c29f4257f340d891531c", size = 37320 }, - { url = "https://files.pythonhosted.org/packages/70/0b/d3717159c26155ff77679cee1b077d22e1008bf45f19921e193319cd8e46/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:ba490b8972531d153ac0d4e421f60d793d71a2f4adbe2f7740b3c55dce0a12f1", size = 35054 }, - { url = "https://files.pythonhosted.org/packages/04/74/f2ae00de7c27984a19b88d2b09ac877031c525b01199d7841ec8fa657fd6/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:c0131351b8a7226c69f1eba5814cbc9d1d8daaf0fdec1ae3f30508e3de5262d4", size = 38613 }, - { url = "https://files.pythonhosted.org/packages/5a/0b/e30236aafe31b4247aa9ae61ba8aac6dde75c3ea0e47a8fb7eef53f6d5ce/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:0e88dba16695f17f41701269fa046197a3fd7b34a8dba744c8749303ddaa18df", size = 37143 }, - { url = "https://files.pythonhosted.org/packages/1c/28/b59bcebb8d76ba8147a784a8be7eab6a4ad3395b9236e73740ff675a5a52/lru_dict-1.3.0-cp312-cp312-win32.whl", hash = "sha256:6ffaf595e625b388babc8e7d79b40f26c7485f61f16efe76764e32dce9ea17fc", size = 12653 }, - { url = "https://files.pythonhosted.org/packages/bd/18/06d9710cb0a0d3634f8501e4bdcc07abe64a32e404d82895a6a36fab97f6/lru_dict-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:cf9da32ef2582434842ab6ba6e67290debfae72771255a8e8ab16f3e006de0aa", size = 13811 }, +sdist = { url = "https://files.pythonhosted.org/packages/96/e3/42c87871920602a3c8300915bd0292f76eccc66c38f782397acbf8a62088/lru-dict-1.3.0.tar.gz", hash = "sha256:54fd1966d6bd1fcde781596cb86068214edeebff1db13a2cea11079e3fd07b6b", size = 13123, upload-time = "2023-11-06T01:40:12.951Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a8/c9/6fac0cb67160f0efa3cc76a6a7d04d5e21a516eeb991ebba08f4f8f01ec5/lru_dict-1.3.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:20c595764695d20bdc3ab9b582e0cc99814da183544afb83783a36d6741a0dac", size = 17750, upload-time = "2023-11-06T01:38:52.667Z" }, + { url = "https://files.pythonhosted.org/packages/61/14/f90dee4bc547ae266dbeffd4e11611234bb6af511dea48f3bc8dac1de478/lru_dict-1.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d9b30a8f50c3fa72a494eca6be5810a1b5c89e4f0fda89374f0d1c5ad8d37d51", size = 11055, upload-time = "2023-11-06T01:38:53.798Z" }, + { url = "https://files.pythonhosted.org/packages/4e/63/a0ae20525f9d52f62ac0def47935f8a2b3b6fcd2c145218b9a27fc1fb910/lru_dict-1.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9710737584650a4251b9a566cbb1a86f83437adb209c9ba43a4e756d12faf0d7", size = 11330, upload-time = "2023-11-06T01:38:54.847Z" }, + { url = "https://files.pythonhosted.org/packages/e9/c6/8c2b81b61e5206910c81b712500736227289aefe4ccfb36137aa21807003/lru_dict-1.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b84c321ae34f2f40aae80e18b6fa08b31c90095792ab64bb99d2e385143effaa", size = 31793, upload-time = "2023-11-06T01:38:56.163Z" }, + { url = "https://files.pythonhosted.org/packages/f9/d7/af9733f94df67a2e9e31ef47d4c41aff1836024f135cdbda4743eb628452/lru_dict-1.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:eed24272b4121b7c22f234daed99899817d81d671b3ed030c876ac88bc9dc890", size = 33090, upload-time = "2023-11-06T01:38:57.091Z" }, + { url = "https://files.pythonhosted.org/packages/5b/6e/5b09b069a70028bcf05dbdc57a301fbe8b3bafecf916f2ed5a3065c79a71/lru_dict-1.3.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9bd13af06dab7c6ee92284fd02ed9a5613a07d5c1b41948dc8886e7207f86dfd", size = 29795, upload-time = "2023-11-06T01:38:58.278Z" }, + { url = "https://files.pythonhosted.org/packages/21/92/4690daefc2602f7c3429ecf54572d37a9e3c372d370344d2185daa4d5ecc/lru_dict-1.3.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a1efc59bfba6aac33684d87b9e02813b0e2445b2f1c444dae2a0b396ad0ed60c", size = 31586, upload-time = "2023-11-06T01:38:59.363Z" }, + { url = "https://files.pythonhosted.org/packages/3c/67/0a29a91087196b02f278d8765120ee4e7486f1f72a4c505fd1cd3109e627/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:cfaf75ac574447afcf8ad998789071af11d2bcf6f947643231f692948839bd98", size = 36662, upload-time = "2023-11-06T01:39:00.795Z" }, + { url = "https://files.pythonhosted.org/packages/36/54/8d56c514cd2333b652bd44c8f1962ab986cbe68e8ad7258c9e0f360cddb6/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c95f8751e2abd6f778da0399c8e0239321d560dbc58cb063827123137d213242", size = 35118, upload-time = "2023-11-06T01:39:01.883Z" }, + { url = "https://files.pythonhosted.org/packages/f5/9a/c7a175d10d503b86974cb07141ca175947145dd1c7370fcda86fbbcaf326/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:abd0c284b26b5c4ee806ca4f33ab5e16b4bf4d5ec9e093e75a6f6287acdde78e", size = 38198, upload-time = "2023-11-06T01:39:03.306Z" }, + { url = "https://files.pythonhosted.org/packages/fd/59/2e5086c8e8a05a7282a824a2a37e3c45cd5714e7b83d8bc0267cb3bb5b4f/lru_dict-1.3.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:2a47740652b25900ac5ce52667b2eade28d8b5fdca0ccd3323459df710e8210a", size = 36542, upload-time = "2023-11-06T01:39:04.751Z" }, + { url = "https://files.pythonhosted.org/packages/12/52/80d0a06e5f45fe7c278dd662da6ea5b39f2ff003248f448189932f6b71c2/lru_dict-1.3.0-cp311-cp311-win32.whl", hash = "sha256:a690c23fc353681ed8042d9fe8f48f0fb79a57b9a45daea2f0be1eef8a1a4aa4", size = 12533, upload-time = "2023-11-06T01:39:05.838Z" }, + { url = "https://files.pythonhosted.org/packages/ce/fe/1f12f33513310860ec6d722709ec4ad8256d9dcc3385f6ae2a244e6e66f5/lru_dict-1.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:efd3f4e0385d18f20f7ea6b08af2574c1bfaa5cb590102ef1bee781bdfba84bc", size = 13651, upload-time = "2023-11-06T01:39:06.871Z" }, + { url = "https://files.pythonhosted.org/packages/fc/5c/385f080747eb3083af87d8e4c9068f3c4cab89035f6982134889940dafd8/lru_dict-1.3.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:c279068f68af3b46a5d649855e1fb87f5705fe1f744a529d82b2885c0e1fc69d", size = 17174, upload-time = "2023-11-06T01:39:07.923Z" }, + { url = "https://files.pythonhosted.org/packages/3c/de/5ef2ed75ce55d7059d1b96177ba04fa7ee1f35564f97bdfcd28fccfbe9d2/lru_dict-1.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:350e2233cfee9f326a0d7a08e309372d87186565e43a691b120006285a0ac549", size = 10742, upload-time = "2023-11-06T01:39:08.871Z" }, + { url = "https://files.pythonhosted.org/packages/ca/05/f69a6abb0062d2cf2ce0aaf0284b105b97d1da024ca6d3d0730e6151242e/lru_dict-1.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4eafb188a84483b3231259bf19030859f070321b00326dcb8e8c6cbf7db4b12f", size = 11079, upload-time = "2023-11-06T01:39:09.766Z" }, + { url = "https://files.pythonhosted.org/packages/ea/59/cf891143abe58a455b8eaa9175f0e80f624a146a2bf9a1ca842ee0ef930a/lru_dict-1.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73593791047e36b37fdc0b67b76aeed439fcea80959c7d46201240f9ec3b2563", size = 32469, upload-time = "2023-11-06T01:39:11.091Z" }, + { url = "https://files.pythonhosted.org/packages/59/88/d5976e9f70107ce11e45d93c6f0c2d5eaa1fc30bb3c8f57525eda4510dff/lru_dict-1.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1958cb70b9542773d6241974646e5410e41ef32e5c9e437d44040d59bd80daf2", size = 33496, upload-time = "2023-11-06T01:39:12.463Z" }, + { url = "https://files.pythonhosted.org/packages/6c/f8/94d6e910d54fc1fa05c0ee1cd608c39401866a18cf5e5aff238449b33c11/lru_dict-1.3.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bc1cd3ed2cee78a47f11f3b70be053903bda197a873fd146e25c60c8e5a32cd6", size = 29914, upload-time = "2023-11-06T01:39:13.395Z" }, + { url = "https://files.pythonhosted.org/packages/ca/b9/9db79780c8a3cfd66bba6847773061e5cf8a3746950273b9985d47bbfe53/lru_dict-1.3.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82eb230d48eaebd6977a92ddaa6d788f14cf4f4bcf5bbffa4ddfd60d051aa9d4", size = 32241, upload-time = "2023-11-06T01:39:14.612Z" }, + { url = "https://files.pythonhosted.org/packages/9b/b6/08a623019daec22a40c4d6d2c40851dfa3d129a53b2f9469db8eb13666c1/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:5ad659cbc349d0c9ba8e536b5f40f96a70c360f43323c29f4257f340d891531c", size = 37320, upload-time = "2023-11-06T01:39:15.875Z" }, + { url = "https://files.pythonhosted.org/packages/70/0b/d3717159c26155ff77679cee1b077d22e1008bf45f19921e193319cd8e46/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:ba490b8972531d153ac0d4e421f60d793d71a2f4adbe2f7740b3c55dce0a12f1", size = 35054, upload-time = "2023-11-06T01:39:17.063Z" }, + { url = "https://files.pythonhosted.org/packages/04/74/f2ae00de7c27984a19b88d2b09ac877031c525b01199d7841ec8fa657fd6/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:c0131351b8a7226c69f1eba5814cbc9d1d8daaf0fdec1ae3f30508e3de5262d4", size = 38613, upload-time = "2023-11-06T01:39:18.136Z" }, + { url = "https://files.pythonhosted.org/packages/5a/0b/e30236aafe31b4247aa9ae61ba8aac6dde75c3ea0e47a8fb7eef53f6d5ce/lru_dict-1.3.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:0e88dba16695f17f41701269fa046197a3fd7b34a8dba744c8749303ddaa18df", size = 37143, upload-time = "2023-11-06T01:39:19.571Z" }, + { url = "https://files.pythonhosted.org/packages/1c/28/b59bcebb8d76ba8147a784a8be7eab6a4ad3395b9236e73740ff675a5a52/lru_dict-1.3.0-cp312-cp312-win32.whl", hash = "sha256:6ffaf595e625b388babc8e7d79b40f26c7485f61f16efe76764e32dce9ea17fc", size = 12653, upload-time = "2023-11-06T01:39:20.574Z" }, + { url = "https://files.pythonhosted.org/packages/bd/18/06d9710cb0a0d3634f8501e4bdcc07abe64a32e404d82895a6a36fab97f6/lru_dict-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:cf9da32ef2582434842ab6ba6e67290debfae72771255a8e8ab16f3e006de0aa", size = 13811, upload-time = "2023-11-06T01:39:21.599Z" }, ] [[package]] name = "lxml" -version = "5.3.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ef/f6/c15ca8e5646e937c148e147244817672cf920b56ac0bf2cc1512ae674be8/lxml-5.3.1.tar.gz", hash = "sha256:106b7b5d2977b339f1e97efe2778e2ab20e99994cbb0ec5e55771ed0795920c8", size = 3678591 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/57/bb/2faea15df82114fa27f2a86eec220506c532ee8ce211dff22f48881b353a/lxml-5.3.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e220f7b3e8656ab063d2eb0cd536fafef396829cafe04cb314e734f87649058f", size = 8161781 }, - { url = "https://files.pythonhosted.org/packages/9f/d3/374114084abb1f96026eccb6cd48b070f85de82fdabae6c2f1e198fa64e5/lxml-5.3.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0f2cfae0688fd01f7056a17367e3b84f37c545fb447d7282cf2c242b16262607", size = 4432571 }, - { url = "https://files.pythonhosted.org/packages/0f/fb/44a46efdc235c2dd763c1e929611d8ff3b920c32b8fcd9051d38f4d04633/lxml-5.3.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:67d2f8ad9dcc3a9e826bdc7802ed541a44e124c29b7d95a679eeb58c1c14ade8", size = 5028919 }, - { url = "https://files.pythonhosted.org/packages/3b/e5/168ddf9f16a90b590df509858ae97a8219d6999d5a132ad9f72427454bed/lxml-5.3.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:db0c742aad702fd5d0c6611a73f9602f20aec2007c102630c06d7633d9c8f09a", size = 4769599 }, - { url = "https://files.pythonhosted.org/packages/f9/0e/3e2742c6f4854b202eb8587c1f7ed760179f6a9fcb34a460497c8c8f3078/lxml-5.3.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:198bb4b4dd888e8390afa4f170d4fa28467a7eaf857f1952589f16cfbb67af27", size = 5369260 }, - { url = "https://files.pythonhosted.org/packages/b8/03/b2f2ab9e33c47609c80665e75efed258b030717e06693835413b34e797cb/lxml-5.3.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d2a3e412ce1849be34b45922bfef03df32d1410a06d1cdeb793a343c2f1fd666", size = 4842798 }, - { url = "https://files.pythonhosted.org/packages/93/ad/0ecfb082b842358c8a9e3115ec944b7240f89821baa8cd7c0cb8a38e05cb/lxml-5.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2b8969dbc8d09d9cd2ae06362c3bad27d03f433252601ef658a49bd9f2b22d79", size = 4917531 }, - { url = "https://files.pythonhosted.org/packages/64/5b/3e93d8ebd2b7eb984c2ad74dfff75493ce96e7b954b12e4f5fc34a700414/lxml-5.3.1-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:5be8f5e4044146a69c96077c7e08f0709c13a314aa5315981185c1f00235fe65", size = 4791500 }, - { url = "https://files.pythonhosted.org/packages/91/83/7dc412362ee7a0259c7f64349393262525061fad551a1340ef92c59d9732/lxml-5.3.1-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:133f3493253a00db2c870d3740bc458ebb7d937bd0a6a4f9328373e0db305709", size = 5404557 }, - { url = "https://files.pythonhosted.org/packages/1e/41/c337f121d9dca148431f246825e021fa1a3f66a6b975deab1950530fdb04/lxml-5.3.1-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:52d82b0d436edd6a1d22d94a344b9a58abd6c68c357ed44f22d4ba8179b37629", size = 4931386 }, - { url = "https://files.pythonhosted.org/packages/a5/73/762c319c4906b3db67e4abc7cfe7d66c34996edb6d0e8cb60f462954d662/lxml-5.3.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:1b6f92e35e2658a5ed51c6634ceb5ddae32053182851d8cad2a5bc102a359b33", size = 4982124 }, - { url = "https://files.pythonhosted.org/packages/c1/e7/d1e296cb3b3b46371220a31350730948d7bea41cc9123c5fd219dea33c29/lxml-5.3.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:203b1d3eaebd34277be06a3eb880050f18a4e4d60861efba4fb946e31071a295", size = 4852742 }, - { url = "https://files.pythonhosted.org/packages/df/90/4adc854475105b93ead6c0c736f762d29371751340dcf5588cfcf8191b8a/lxml-5.3.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:155e1a5693cf4b55af652f5c0f78ef36596c7f680ff3ec6eb4d7d85367259b2c", size = 5457004 }, - { url = "https://files.pythonhosted.org/packages/f0/0d/39864efbd231c13eb53edee2ab91c742c24d2f93efe2af7d3fe4343e42c1/lxml-5.3.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:22ec2b3c191f43ed21f9545e9df94c37c6b49a5af0a874008ddc9132d49a2d9c", size = 5298185 }, - { url = "https://files.pythonhosted.org/packages/8d/7a/630a64ceb1088196de182e2e33b5899691c3e1ae21af688e394208bd6810/lxml-5.3.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7eda194dd46e40ec745bf76795a7cccb02a6a41f445ad49d3cf66518b0bd9cff", size = 5032707 }, - { url = "https://files.pythonhosted.org/packages/b2/3d/091bc7b592333754cb346c1507ca948ab39bc89d83577ac8f1da3be4dece/lxml-5.3.1-cp311-cp311-win32.whl", hash = "sha256:fb7c61d4be18e930f75948705e9718618862e6fc2ed0d7159b2262be73f167a2", size = 3474288 }, - { url = "https://files.pythonhosted.org/packages/12/8c/7d47cfc0d04fd4e3639ec7e1c96c2561d5e890eb900de8f76eea75e0964a/lxml-5.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:c809eef167bf4a57af4b03007004896f5c60bd38dc3852fcd97a26eae3d4c9e6", size = 3815031 }, - { url = "https://files.pythonhosted.org/packages/3b/f4/5121aa9ee8e09b8b8a28cf3709552efe3d206ca51a20d6fa471b60bb3447/lxml-5.3.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:e69add9b6b7b08c60d7ff0152c7c9a6c45b4a71a919be5abde6f98f1ea16421c", size = 8191889 }, - { url = "https://files.pythonhosted.org/packages/0a/ca/8e9aa01edddc74878f4aea85aa9ab64372f46aa804d1c36dda861bf9eabf/lxml-5.3.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4e52e1b148867b01c05e21837586ee307a01e793b94072d7c7b91d2c2da02ffe", size = 4450685 }, - { url = "https://files.pythonhosted.org/packages/b2/b3/ea40a5c98619fbd7e9349df7007994506d396b97620ced34e4e5053d3734/lxml-5.3.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a4b382e0e636ed54cd278791d93fe2c4f370772743f02bcbe431a160089025c9", size = 5051722 }, - { url = "https://files.pythonhosted.org/packages/3a/5e/375418be35f8a695cadfe7e7412f16520e62e24952ed93c64c9554755464/lxml-5.3.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c2e49dc23a10a1296b04ca9db200c44d3eb32c8d8ec532e8c1fd24792276522a", size = 4786661 }, - { url = "https://files.pythonhosted.org/packages/79/7c/d258eaaa9560f6664f9b426a5165103015bee6512d8931e17342278bad0a/lxml-5.3.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4399b4226c4785575fb20998dc571bc48125dc92c367ce2602d0d70e0c455eb0", size = 5311766 }, - { url = "https://files.pythonhosted.org/packages/03/bc/a041415be4135a1b3fdf017a5d873244cc16689456166fbdec4b27fba153/lxml-5.3.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5412500e0dc5481b1ee9cf6b38bb3b473f6e411eb62b83dc9b62699c3b7b79f7", size = 4836014 }, - { url = "https://files.pythonhosted.org/packages/32/88/047f24967d5e3fc97848ea2c207eeef0f16239cdc47368c8b95a8dc93a33/lxml-5.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1c93ed3c998ea8472be98fb55aed65b5198740bfceaec07b2eba551e55b7b9ae", size = 4961064 }, - { url = "https://files.pythonhosted.org/packages/3d/b5/ecf5a20937ecd21af02c5374020f4e3a3538e10a32379a7553fca3d77094/lxml-5.3.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:63d57fc94eb0bbb4735e45517afc21ef262991d8758a8f2f05dd6e4174944519", size = 4778341 }, - { url = "https://files.pythonhosted.org/packages/a4/05/56c359e07275911ed5f35ab1d63c8cd3360d395fb91e43927a2ae90b0322/lxml-5.3.1-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:b450d7cabcd49aa7ab46a3c6aa3ac7e1593600a1a0605ba536ec0f1b99a04322", size = 5345450 }, - { url = "https://files.pythonhosted.org/packages/b7/f4/f95e3ae12e9f32fbcde00f9affa6b0df07f495117f62dbb796a9a31c84d6/lxml-5.3.1-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:4df0ec814b50275ad6a99bc82a38b59f90e10e47714ac9871e1b223895825468", size = 4908336 }, - { url = "https://files.pythonhosted.org/packages/c5/f8/309546aec092434166a6e11c7dcecb5c2d0a787c18c072d61e18da9eba57/lxml-5.3.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:d184f85ad2bb1f261eac55cddfcf62a70dee89982c978e92b9a74a1bfef2e367", size = 4986049 }, - { url = "https://files.pythonhosted.org/packages/71/1c/b951817cb5058ca7c332d012dfe8bc59dabd0f0a8911ddd7b7ea8e41cfbd/lxml-5.3.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b725e70d15906d24615201e650d5b0388b08a5187a55f119f25874d0103f90dd", size = 4860351 }, - { url = "https://files.pythonhosted.org/packages/31/23/45feba8dae1d35fcca1e51b051f59dc4223cbd23e071a31e25f3f73938a8/lxml-5.3.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:a31fa7536ec1fb7155a0cd3a4e3d956c835ad0a43e3610ca32384d01f079ea1c", size = 5421580 }, - { url = "https://files.pythonhosted.org/packages/61/69/be245d7b2dbef81c542af59c97fcd641fbf45accf2dc1c325bae7d0d014c/lxml-5.3.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:3c3c8b55c7fc7b7e8877b9366568cc73d68b82da7fe33d8b98527b73857a225f", size = 5285778 }, - { url = "https://files.pythonhosted.org/packages/69/06/128af2ed04bac99b8f83becfb74c480f1aa18407b5c329fad457e08a1bf4/lxml-5.3.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:d61ec60945d694df806a9aec88e8f29a27293c6e424f8ff91c80416e3c617645", size = 5054455 }, - { url = "https://files.pythonhosted.org/packages/8a/2d/f03a21cf6cc75cdd083563e509c7b6b159d761115c4142abb5481094ed8c/lxml-5.3.1-cp312-cp312-win32.whl", hash = "sha256:f4eac0584cdc3285ef2e74eee1513a6001681fd9753b259e8159421ed28a72e5", size = 3486315 }, - { url = "https://files.pythonhosted.org/packages/2b/9c/8abe21585d20ef70ad9cec7562da4332b764ed69ec29b7389d23dfabcea0/lxml-5.3.1-cp312-cp312-win_amd64.whl", hash = "sha256:29bfc8d3d88e56ea0a27e7c4897b642706840247f59f4377d81be8f32aa0cfbf", size = 3816925 }, +version = "5.4.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/76/3d/14e82fc7c8fb1b7761f7e748fd47e2ec8276d137b6acfe5a4bb73853e08f/lxml-5.4.0.tar.gz", hash = "sha256:d12832e1dbea4be280b22fd0ea7c9b87f0d8fc51ba06e92dc62d52f804f78ebd", size = 3679479, upload-time = "2025-04-23T01:50:29.322Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/81/2d/67693cc8a605a12e5975380d7ff83020dcc759351b5a066e1cced04f797b/lxml-5.4.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:98a3912194c079ef37e716ed228ae0dcb960992100461b704aea4e93af6b0bb9", size = 8083240, upload-time = "2025-04-23T01:45:18.566Z" }, + { url = "https://files.pythonhosted.org/packages/73/53/b5a05ab300a808b72e848efd152fe9c022c0181b0a70b8bca1199f1bed26/lxml-5.4.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0ea0252b51d296a75f6118ed0d8696888e7403408ad42345d7dfd0d1e93309a7", size = 4387685, upload-time = "2025-04-23T01:45:21.387Z" }, + { url = "https://files.pythonhosted.org/packages/d8/cb/1a3879c5f512bdcd32995c301886fe082b2edd83c87d41b6d42d89b4ea4d/lxml-5.4.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b92b69441d1bd39f4940f9eadfa417a25862242ca2c396b406f9272ef09cdcaa", size = 4991164, upload-time = "2025-04-23T01:45:23.849Z" }, + { url = "https://files.pythonhosted.org/packages/f9/94/bbc66e42559f9d04857071e3b3d0c9abd88579367fd2588a4042f641f57e/lxml-5.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:20e16c08254b9b6466526bc1828d9370ee6c0d60a4b64836bc3ac2917d1e16df", size = 4746206, upload-time = "2025-04-23T01:45:26.361Z" }, + { url = "https://files.pythonhosted.org/packages/66/95/34b0679bee435da2d7cae895731700e519a8dfcab499c21662ebe671603e/lxml-5.4.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7605c1c32c3d6e8c990dd28a0970a3cbbf1429d5b92279e37fda05fb0c92190e", size = 5342144, upload-time = "2025-04-23T01:45:28.939Z" }, + { url = "https://files.pythonhosted.org/packages/e0/5d/abfcc6ab2fa0be72b2ba938abdae1f7cad4c632f8d552683ea295d55adfb/lxml-5.4.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ecf4c4b83f1ab3d5a7ace10bafcb6f11df6156857a3c418244cef41ca9fa3e44", size = 4825124, upload-time = "2025-04-23T01:45:31.361Z" }, + { url = "https://files.pythonhosted.org/packages/5a/78/6bd33186c8863b36e084f294fc0a5e5eefe77af95f0663ef33809cc1c8aa/lxml-5.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0cef4feae82709eed352cd7e97ae062ef6ae9c7b5dbe3663f104cd2c0e8d94ba", size = 4876520, upload-time = "2025-04-23T01:45:34.191Z" }, + { url = "https://files.pythonhosted.org/packages/3b/74/4d7ad4839bd0fc64e3d12da74fc9a193febb0fae0ba6ebd5149d4c23176a/lxml-5.4.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:df53330a3bff250f10472ce96a9af28628ff1f4efc51ccba351a8820bca2a8ba", size = 4765016, upload-time = "2025-04-23T01:45:36.7Z" }, + { url = "https://files.pythonhosted.org/packages/24/0d/0a98ed1f2471911dadfc541003ac6dd6879fc87b15e1143743ca20f3e973/lxml-5.4.0-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:aefe1a7cb852fa61150fcb21a8c8fcea7b58c4cb11fbe59c97a0a4b31cae3c8c", size = 5362884, upload-time = "2025-04-23T01:45:39.291Z" }, + { url = "https://files.pythonhosted.org/packages/48/de/d4f7e4c39740a6610f0f6959052b547478107967362e8424e1163ec37ae8/lxml-5.4.0-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:ef5a7178fcc73b7d8c07229e89f8eb45b2908a9238eb90dcfc46571ccf0383b8", size = 4902690, upload-time = "2025-04-23T01:45:42.386Z" }, + { url = "https://files.pythonhosted.org/packages/07/8c/61763abd242af84f355ca4ef1ee096d3c1b7514819564cce70fd18c22e9a/lxml-5.4.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:d2ed1b3cb9ff1c10e6e8b00941bb2e5bb568b307bfc6b17dffbbe8be5eecba86", size = 4944418, upload-time = "2025-04-23T01:45:46.051Z" }, + { url = "https://files.pythonhosted.org/packages/f9/c5/6d7e3b63e7e282619193961a570c0a4c8a57fe820f07ca3fe2f6bd86608a/lxml-5.4.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:72ac9762a9f8ce74c9eed4a4e74306f2f18613a6b71fa065495a67ac227b3056", size = 4827092, upload-time = "2025-04-23T01:45:48.943Z" }, + { url = "https://files.pythonhosted.org/packages/71/4a/e60a306df54680b103348545706a98a7514a42c8b4fbfdcaa608567bb065/lxml-5.4.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:f5cb182f6396706dc6cc1896dd02b1c889d644c081b0cdec38747573db88a7d7", size = 5418231, upload-time = "2025-04-23T01:45:51.481Z" }, + { url = "https://files.pythonhosted.org/packages/27/f2/9754aacd6016c930875854f08ac4b192a47fe19565f776a64004aa167521/lxml-5.4.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:3a3178b4873df8ef9457a4875703488eb1622632a9cee6d76464b60e90adbfcd", size = 5261798, upload-time = "2025-04-23T01:45:54.146Z" }, + { url = "https://files.pythonhosted.org/packages/38/a2/0c49ec6941428b1bd4f280650d7b11a0f91ace9db7de32eb7aa23bcb39ff/lxml-5.4.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e094ec83694b59d263802ed03a8384594fcce477ce484b0cbcd0008a211ca751", size = 4988195, upload-time = "2025-04-23T01:45:56.685Z" }, + { url = "https://files.pythonhosted.org/packages/7a/75/87a3963a08eafc46a86c1131c6e28a4de103ba30b5ae903114177352a3d7/lxml-5.4.0-cp311-cp311-win32.whl", hash = "sha256:4329422de653cdb2b72afa39b0aa04252fca9071550044904b2e7036d9d97fe4", size = 3474243, upload-time = "2025-04-23T01:45:58.863Z" }, + { url = "https://files.pythonhosted.org/packages/fa/f9/1f0964c4f6c2be861c50db380c554fb8befbea98c6404744ce243a3c87ef/lxml-5.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:fd3be6481ef54b8cfd0e1e953323b7aa9d9789b94842d0e5b142ef4bb7999539", size = 3815197, upload-time = "2025-04-23T01:46:01.096Z" }, + { url = "https://files.pythonhosted.org/packages/f8/4c/d101ace719ca6a4ec043eb516fcfcb1b396a9fccc4fcd9ef593df34ba0d5/lxml-5.4.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:b5aff6f3e818e6bdbbb38e5967520f174b18f539c2b9de867b1e7fde6f8d95a4", size = 8127392, upload-time = "2025-04-23T01:46:04.09Z" }, + { url = "https://files.pythonhosted.org/packages/11/84/beddae0cec4dd9ddf46abf156f0af451c13019a0fa25d7445b655ba5ccb7/lxml-5.4.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:942a5d73f739ad7c452bf739a62a0f83e2578afd6b8e5406308731f4ce78b16d", size = 4415103, upload-time = "2025-04-23T01:46:07.227Z" }, + { url = "https://files.pythonhosted.org/packages/d0/25/d0d93a4e763f0462cccd2b8a665bf1e4343dd788c76dcfefa289d46a38a9/lxml-5.4.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:460508a4b07364d6abf53acaa0a90b6d370fafde5693ef37602566613a9b0779", size = 5024224, upload-time = "2025-04-23T01:46:10.237Z" }, + { url = "https://files.pythonhosted.org/packages/31/ce/1df18fb8f7946e7f3388af378b1f34fcf253b94b9feedb2cec5969da8012/lxml-5.4.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:529024ab3a505fed78fe3cc5ddc079464e709f6c892733e3f5842007cec8ac6e", size = 4769913, upload-time = "2025-04-23T01:46:12.757Z" }, + { url = "https://files.pythonhosted.org/packages/4e/62/f4a6c60ae7c40d43657f552f3045df05118636be1165b906d3423790447f/lxml-5.4.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7ca56ebc2c474e8f3d5761debfd9283b8b18c76c4fc0967b74aeafba1f5647f9", size = 5290441, upload-time = "2025-04-23T01:46:16.037Z" }, + { url = "https://files.pythonhosted.org/packages/9e/aa/04f00009e1e3a77838c7fc948f161b5d2d5de1136b2b81c712a263829ea4/lxml-5.4.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a81e1196f0a5b4167a8dafe3a66aa67c4addac1b22dc47947abd5d5c7a3f24b5", size = 4820165, upload-time = "2025-04-23T01:46:19.137Z" }, + { url = "https://files.pythonhosted.org/packages/c9/1f/e0b2f61fa2404bf0f1fdf1898377e5bd1b74cc9b2cf2c6ba8509b8f27990/lxml-5.4.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:00b8686694423ddae324cf614e1b9659c2edb754de617703c3d29ff568448df5", size = 4932580, upload-time = "2025-04-23T01:46:21.963Z" }, + { url = "https://files.pythonhosted.org/packages/24/a2/8263f351b4ffe0ed3e32ea7b7830f845c795349034f912f490180d88a877/lxml-5.4.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:c5681160758d3f6ac5b4fea370495c48aac0989d6a0f01bb9a72ad8ef5ab75c4", size = 4759493, upload-time = "2025-04-23T01:46:24.316Z" }, + { url = "https://files.pythonhosted.org/packages/05/00/41db052f279995c0e35c79d0f0fc9f8122d5b5e9630139c592a0b58c71b4/lxml-5.4.0-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:2dc191e60425ad70e75a68c9fd90ab284df64d9cd410ba8d2b641c0c45bc006e", size = 5324679, upload-time = "2025-04-23T01:46:27.097Z" }, + { url = "https://files.pythonhosted.org/packages/1d/be/ee99e6314cdef4587617d3b3b745f9356d9b7dd12a9663c5f3b5734b64ba/lxml-5.4.0-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:67f779374c6b9753ae0a0195a892a1c234ce8416e4448fe1e9f34746482070a7", size = 4890691, upload-time = "2025-04-23T01:46:30.009Z" }, + { url = "https://files.pythonhosted.org/packages/ad/36/239820114bf1d71f38f12208b9c58dec033cbcf80101cde006b9bde5cffd/lxml-5.4.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:79d5bfa9c1b455336f52343130b2067164040604e41f6dc4d8313867ed540079", size = 4955075, upload-time = "2025-04-23T01:46:32.33Z" }, + { url = "https://files.pythonhosted.org/packages/d4/e1/1b795cc0b174efc9e13dbd078a9ff79a58728a033142bc6d70a1ee8fc34d/lxml-5.4.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:3d3c30ba1c9b48c68489dc1829a6eede9873f52edca1dda900066542528d6b20", size = 4838680, upload-time = "2025-04-23T01:46:34.852Z" }, + { url = "https://files.pythonhosted.org/packages/72/48/3c198455ca108cec5ae3662ae8acd7fd99476812fd712bb17f1b39a0b589/lxml-5.4.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:1af80c6316ae68aded77e91cd9d80648f7dd40406cef73df841aa3c36f6907c8", size = 5391253, upload-time = "2025-04-23T01:46:37.608Z" }, + { url = "https://files.pythonhosted.org/packages/d6/10/5bf51858971c51ec96cfc13e800a9951f3fd501686f4c18d7d84fe2d6352/lxml-5.4.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:4d885698f5019abe0de3d352caf9466d5de2baded00a06ef3f1216c1a58ae78f", size = 5261651, upload-time = "2025-04-23T01:46:40.183Z" }, + { url = "https://files.pythonhosted.org/packages/2b/11/06710dd809205377da380546f91d2ac94bad9ff735a72b64ec029f706c85/lxml-5.4.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:aea53d51859b6c64e7c51d522c03cc2c48b9b5d6172126854cc7f01aa11f52bc", size = 5024315, upload-time = "2025-04-23T01:46:43.333Z" }, + { url = "https://files.pythonhosted.org/packages/f5/b0/15b6217834b5e3a59ebf7f53125e08e318030e8cc0d7310355e6edac98ef/lxml-5.4.0-cp312-cp312-win32.whl", hash = "sha256:d90b729fd2732df28130c064aac9bb8aff14ba20baa4aee7bd0795ff1187545f", size = 3486149, upload-time = "2025-04-23T01:46:45.684Z" }, + { url = "https://files.pythonhosted.org/packages/91/1e/05ddcb57ad2f3069101611bd5f5084157d90861a2ef460bf42f45cced944/lxml-5.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:1dc4ca99e89c335a7ed47d38964abcb36c5910790f9bd106f2a8fa2ee0b909d2", size = 3817095, upload-time = "2025-04-23T01:46:48.521Z" }, ] [[package]] name = "markdown" -version = "3.7" +version = "3.8" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/54/28/3af612670f82f4c056911fbbbb42760255801b3068c48de792d354ff4472/markdown-3.7.tar.gz", hash = "sha256:2ae2471477cfd02dbbf038d5d9bc226d40def84b4fe2986e49b59b6b472bbed2", size = 357086 } +sdist = { url = "https://files.pythonhosted.org/packages/2f/15/222b423b0b88689c266d9eac4e61396fe2cc53464459d6a37618ac863b24/markdown-3.8.tar.gz", hash = "sha256:7df81e63f0df5c4b24b7d156eb81e4690595239b7d70937d0409f1b0de319c6f", size = 360906, upload-time = "2025-04-11T14:42:50.928Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3f/08/83871f3c50fc983b88547c196d11cf8c3340e37c32d2e9d6152abe2c61f7/Markdown-3.7-py3-none-any.whl", hash = "sha256:7eb6df5690b81a1d7942992c97fad2938e956e79df20cbc6186e9c3a77b1c803", size = 106349 }, + { url = "https://files.pythonhosted.org/packages/51/3f/afe76f8e2246ffbc867440cbcf90525264df0e658f8a5ca1f872b3f6192a/markdown-3.8-py3-none-any.whl", hash = "sha256:794a929b79c5af141ef5ab0f2f642d0f7b1872981250230e72682346f7cc90dc", size = 106210, upload-time = "2025-04-11T14:42:49.178Z" }, ] [[package]] name = "markupsafe" version = "3.0.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/b2/97/5d42485e71dfc078108a86d6de8fa46db44a1a9295e89c5d6d4a06e23a62/markupsafe-3.0.2.tar.gz", hash = "sha256:ee55d3edf80167e48ea11a923c7386f4669df67d7994554387f84e7d8b0a2bf0", size = 20537 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/6b/28/bbf83e3f76936960b850435576dd5e67034e200469571be53f69174a2dfd/MarkupSafe-3.0.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9025b4018f3a1314059769c7bf15441064b2207cb3f065e6ea1e7359cb46db9d", size = 14353 }, - { url = "https://files.pythonhosted.org/packages/6c/30/316d194b093cde57d448a4c3209f22e3046c5bb2fb0820b118292b334be7/MarkupSafe-3.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:93335ca3812df2f366e80509ae119189886b0f3c2b81325d39efdb84a1e2ae93", size = 12392 }, - { url = "https://files.pythonhosted.org/packages/f2/96/9cdafba8445d3a53cae530aaf83c38ec64c4d5427d975c974084af5bc5d2/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2cb8438c3cbb25e220c2ab33bb226559e7afb3baec11c4f218ffa7308603c832", size = 23984 }, - { url = "https://files.pythonhosted.org/packages/f1/a4/aefb044a2cd8d7334c8a47d3fb2c9f328ac48cb349468cc31c20b539305f/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a123e330ef0853c6e822384873bef7507557d8e4a082961e1defa947aa59ba84", size = 23120 }, - { url = "https://files.pythonhosted.org/packages/8d/21/5e4851379f88f3fad1de30361db501300d4f07bcad047d3cb0449fc51f8c/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1e084f686b92e5b83186b07e8a17fc09e38fff551f3602b249881fec658d3eca", size = 23032 }, - { url = "https://files.pythonhosted.org/packages/00/7b/e92c64e079b2d0d7ddf69899c98842f3f9a60a1ae72657c89ce2655c999d/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d8213e09c917a951de9d09ecee036d5c7d36cb6cb7dbaece4c71a60d79fb9798", size = 24057 }, - { url = "https://files.pythonhosted.org/packages/f9/ac/46f960ca323037caa0a10662ef97d0a4728e890334fc156b9f9e52bcc4ca/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:5b02fb34468b6aaa40dfc198d813a641e3a63b98c2b05a16b9f80b7ec314185e", size = 23359 }, - { url = "https://files.pythonhosted.org/packages/69/84/83439e16197337b8b14b6a5b9c2105fff81d42c2a7c5b58ac7b62ee2c3b1/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0bff5e0ae4ef2e1ae4fdf2dfd5b76c75e5c2fa4132d05fc1b0dabcd20c7e28c4", size = 23306 }, - { url = "https://files.pythonhosted.org/packages/9a/34/a15aa69f01e2181ed8d2b685c0d2f6655d5cca2c4db0ddea775e631918cd/MarkupSafe-3.0.2-cp311-cp311-win32.whl", hash = "sha256:6c89876f41da747c8d3677a2b540fb32ef5715f97b66eeb0c6b66f5e3ef6f59d", size = 15094 }, - { url = "https://files.pythonhosted.org/packages/da/b8/3a3bd761922d416f3dc5d00bfbed11f66b1ab89a0c2b6e887240a30b0f6b/MarkupSafe-3.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:70a87b411535ccad5ef2f1df5136506a10775d267e197e4cf531ced10537bd6b", size = 15521 }, - { url = "https://files.pythonhosted.org/packages/22/09/d1f21434c97fc42f09d290cbb6350d44eb12f09cc62c9476effdb33a18aa/MarkupSafe-3.0.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9778bd8ab0a994ebf6f84c2b949e65736d5575320a17ae8984a77fab08db94cf", size = 14274 }, - { url = "https://files.pythonhosted.org/packages/6b/b0/18f76bba336fa5aecf79d45dcd6c806c280ec44538b3c13671d49099fdd0/MarkupSafe-3.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:846ade7b71e3536c4e56b386c2a47adf5741d2d8b94ec9dc3e92e5e1ee1e2225", size = 12348 }, - { url = "https://files.pythonhosted.org/packages/e0/25/dd5c0f6ac1311e9b40f4af06c78efde0f3b5cbf02502f8ef9501294c425b/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1c99d261bd2d5f6b59325c92c73df481e05e57f19837bdca8413b9eac4bd8028", size = 24149 }, - { url = "https://files.pythonhosted.org/packages/f3/f0/89e7aadfb3749d0f52234a0c8c7867877876e0a20b60e2188e9850794c17/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e17c96c14e19278594aa4841ec148115f9c7615a47382ecb6b82bd8fea3ab0c8", size = 23118 }, - { url = "https://files.pythonhosted.org/packages/d5/da/f2eeb64c723f5e3777bc081da884b414671982008c47dcc1873d81f625b6/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:88416bd1e65dcea10bc7569faacb2c20ce071dd1f87539ca2ab364bf6231393c", size = 22993 }, - { url = "https://files.pythonhosted.org/packages/da/0e/1f32af846df486dce7c227fe0f2398dc7e2e51d4a370508281f3c1c5cddc/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:2181e67807fc2fa785d0592dc2d6206c019b9502410671cc905d132a92866557", size = 24178 }, - { url = "https://files.pythonhosted.org/packages/c4/f6/bb3ca0532de8086cbff5f06d137064c8410d10779c4c127e0e47d17c0b71/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:52305740fe773d09cffb16f8ed0427942901f00adedac82ec8b67752f58a1b22", size = 23319 }, - { url = "https://files.pythonhosted.org/packages/a2/82/8be4c96ffee03c5b4a034e60a31294daf481e12c7c43ab8e34a1453ee48b/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ad10d3ded218f1039f11a75f8091880239651b52e9bb592ca27de44eed242a48", size = 23352 }, - { url = "https://files.pythonhosted.org/packages/51/ae/97827349d3fcffee7e184bdf7f41cd6b88d9919c80f0263ba7acd1bbcb18/MarkupSafe-3.0.2-cp312-cp312-win32.whl", hash = "sha256:0f4ca02bea9a23221c0182836703cbf8930c5e9454bacce27e767509fa286a30", size = 15097 }, - { url = "https://files.pythonhosted.org/packages/c1/80/a61f99dc3a936413c3ee4e1eecac96c0da5ed07ad56fd975f1a9da5bc630/MarkupSafe-3.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:8e06879fc22a25ca47312fbe7c8264eb0b662f6db27cb2d3bbbc74b1df4b9b87", size = 15601 }, +sdist = { url = "https://files.pythonhosted.org/packages/b2/97/5d42485e71dfc078108a86d6de8fa46db44a1a9295e89c5d6d4a06e23a62/markupsafe-3.0.2.tar.gz", hash = "sha256:ee55d3edf80167e48ea11a923c7386f4669df67d7994554387f84e7d8b0a2bf0", size = 20537, upload-time = "2024-10-18T15:21:54.129Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/28/bbf83e3f76936960b850435576dd5e67034e200469571be53f69174a2dfd/MarkupSafe-3.0.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9025b4018f3a1314059769c7bf15441064b2207cb3f065e6ea1e7359cb46db9d", size = 14353, upload-time = "2024-10-18T15:21:02.187Z" }, + { url = "https://files.pythonhosted.org/packages/6c/30/316d194b093cde57d448a4c3209f22e3046c5bb2fb0820b118292b334be7/MarkupSafe-3.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:93335ca3812df2f366e80509ae119189886b0f3c2b81325d39efdb84a1e2ae93", size = 12392, upload-time = "2024-10-18T15:21:02.941Z" }, + { url = "https://files.pythonhosted.org/packages/f2/96/9cdafba8445d3a53cae530aaf83c38ec64c4d5427d975c974084af5bc5d2/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2cb8438c3cbb25e220c2ab33bb226559e7afb3baec11c4f218ffa7308603c832", size = 23984, upload-time = "2024-10-18T15:21:03.953Z" }, + { url = "https://files.pythonhosted.org/packages/f1/a4/aefb044a2cd8d7334c8a47d3fb2c9f328ac48cb349468cc31c20b539305f/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a123e330ef0853c6e822384873bef7507557d8e4a082961e1defa947aa59ba84", size = 23120, upload-time = "2024-10-18T15:21:06.495Z" }, + { url = "https://files.pythonhosted.org/packages/8d/21/5e4851379f88f3fad1de30361db501300d4f07bcad047d3cb0449fc51f8c/MarkupSafe-3.0.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1e084f686b92e5b83186b07e8a17fc09e38fff551f3602b249881fec658d3eca", size = 23032, upload-time = "2024-10-18T15:21:07.295Z" }, + { url = "https://files.pythonhosted.org/packages/00/7b/e92c64e079b2d0d7ddf69899c98842f3f9a60a1ae72657c89ce2655c999d/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d8213e09c917a951de9d09ecee036d5c7d36cb6cb7dbaece4c71a60d79fb9798", size = 24057, upload-time = "2024-10-18T15:21:08.073Z" }, + { url = "https://files.pythonhosted.org/packages/f9/ac/46f960ca323037caa0a10662ef97d0a4728e890334fc156b9f9e52bcc4ca/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:5b02fb34468b6aaa40dfc198d813a641e3a63b98c2b05a16b9f80b7ec314185e", size = 23359, upload-time = "2024-10-18T15:21:09.318Z" }, + { url = "https://files.pythonhosted.org/packages/69/84/83439e16197337b8b14b6a5b9c2105fff81d42c2a7c5b58ac7b62ee2c3b1/MarkupSafe-3.0.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0bff5e0ae4ef2e1ae4fdf2dfd5b76c75e5c2fa4132d05fc1b0dabcd20c7e28c4", size = 23306, upload-time = "2024-10-18T15:21:10.185Z" }, + { url = "https://files.pythonhosted.org/packages/9a/34/a15aa69f01e2181ed8d2b685c0d2f6655d5cca2c4db0ddea775e631918cd/MarkupSafe-3.0.2-cp311-cp311-win32.whl", hash = "sha256:6c89876f41da747c8d3677a2b540fb32ef5715f97b66eeb0c6b66f5e3ef6f59d", size = 15094, upload-time = "2024-10-18T15:21:11.005Z" }, + { url = "https://files.pythonhosted.org/packages/da/b8/3a3bd761922d416f3dc5d00bfbed11f66b1ab89a0c2b6e887240a30b0f6b/MarkupSafe-3.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:70a87b411535ccad5ef2f1df5136506a10775d267e197e4cf531ced10537bd6b", size = 15521, upload-time = "2024-10-18T15:21:12.911Z" }, + { url = "https://files.pythonhosted.org/packages/22/09/d1f21434c97fc42f09d290cbb6350d44eb12f09cc62c9476effdb33a18aa/MarkupSafe-3.0.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9778bd8ab0a994ebf6f84c2b949e65736d5575320a17ae8984a77fab08db94cf", size = 14274, upload-time = "2024-10-18T15:21:13.777Z" }, + { url = "https://files.pythonhosted.org/packages/6b/b0/18f76bba336fa5aecf79d45dcd6c806c280ec44538b3c13671d49099fdd0/MarkupSafe-3.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:846ade7b71e3536c4e56b386c2a47adf5741d2d8b94ec9dc3e92e5e1ee1e2225", size = 12348, upload-time = "2024-10-18T15:21:14.822Z" }, + { url = "https://files.pythonhosted.org/packages/e0/25/dd5c0f6ac1311e9b40f4af06c78efde0f3b5cbf02502f8ef9501294c425b/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1c99d261bd2d5f6b59325c92c73df481e05e57f19837bdca8413b9eac4bd8028", size = 24149, upload-time = "2024-10-18T15:21:15.642Z" }, + { url = "https://files.pythonhosted.org/packages/f3/f0/89e7aadfb3749d0f52234a0c8c7867877876e0a20b60e2188e9850794c17/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e17c96c14e19278594aa4841ec148115f9c7615a47382ecb6b82bd8fea3ab0c8", size = 23118, upload-time = "2024-10-18T15:21:17.133Z" }, + { url = "https://files.pythonhosted.org/packages/d5/da/f2eeb64c723f5e3777bc081da884b414671982008c47dcc1873d81f625b6/MarkupSafe-3.0.2-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:88416bd1e65dcea10bc7569faacb2c20ce071dd1f87539ca2ab364bf6231393c", size = 22993, upload-time = "2024-10-18T15:21:18.064Z" }, + { url = "https://files.pythonhosted.org/packages/da/0e/1f32af846df486dce7c227fe0f2398dc7e2e51d4a370508281f3c1c5cddc/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:2181e67807fc2fa785d0592dc2d6206c019b9502410671cc905d132a92866557", size = 24178, upload-time = "2024-10-18T15:21:18.859Z" }, + { url = "https://files.pythonhosted.org/packages/c4/f6/bb3ca0532de8086cbff5f06d137064c8410d10779c4c127e0e47d17c0b71/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:52305740fe773d09cffb16f8ed0427942901f00adedac82ec8b67752f58a1b22", size = 23319, upload-time = "2024-10-18T15:21:19.671Z" }, + { url = "https://files.pythonhosted.org/packages/a2/82/8be4c96ffee03c5b4a034e60a31294daf481e12c7c43ab8e34a1453ee48b/MarkupSafe-3.0.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ad10d3ded218f1039f11a75f8091880239651b52e9bb592ca27de44eed242a48", size = 23352, upload-time = "2024-10-18T15:21:20.971Z" }, + { url = "https://files.pythonhosted.org/packages/51/ae/97827349d3fcffee7e184bdf7f41cd6b88d9919c80f0263ba7acd1bbcb18/MarkupSafe-3.0.2-cp312-cp312-win32.whl", hash = "sha256:0f4ca02bea9a23221c0182836703cbf8930c5e9454bacce27e767509fa286a30", size = 15097, upload-time = "2024-10-18T15:21:22.646Z" }, + { url = "https://files.pythonhosted.org/packages/c1/80/a61f99dc3a936413c3ee4e1eecac96c0da5ed07ad56fd975f1a9da5bc630/MarkupSafe-3.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:8e06879fc22a25ca47312fbe7c8264eb0b662f6db27cb2d3bbbc74b1df4b9b87", size = 15601, upload-time = "2024-10-18T15:21:23.499Z" }, ] [[package]] name = "matplotlib" -version = "3.10.1" +version = "3.10.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "contourpy" }, @@ -924,29 +938,29 @@ dependencies = [ { name = "pyparsing" }, { name = "python-dateutil" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2f/08/b89867ecea2e305f408fbb417139a8dd941ecf7b23a2e02157c36da546f0/matplotlib-3.10.1.tar.gz", hash = "sha256:e8d2d0e3881b129268585bf4765ad3ee73a4591d77b9a18c214ac7e3a79fb2ba", size = 36743335 } +sdist = { url = "https://files.pythonhosted.org/packages/26/91/d49359a21893183ed2a5b6c76bec40e0b1dcbf8ca148f864d134897cfc75/matplotlib-3.10.3.tar.gz", hash = "sha256:2f82d2c5bb7ae93aaaa4cd42aca65d76ce6376f83304fa3a630b569aca274df0", size = 34799811, upload-time = "2025-05-08T19:10:54.39Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a5/14/a1b840075be247bb1834b22c1e1d558740b0f618fe3a823740181ca557a1/matplotlib-3.10.1-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:057206ff2d6ab82ff3e94ebd94463d084760ca682ed5f150817b859372ec4401", size = 8174669 }, - { url = "https://files.pythonhosted.org/packages/0a/e4/300b08e3e08f9c98b0d5635f42edabf2f7a1d634e64cb0318a71a44ff720/matplotlib-3.10.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a144867dd6bf8ba8cb5fc81a158b645037e11b3e5cf8a50bd5f9917cb863adfe", size = 8047996 }, - { url = "https://files.pythonhosted.org/packages/75/f9/8d99ff5a2498a5f1ccf919fb46fb945109623c6108216f10f96428f388bc/matplotlib-3.10.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:56c5d9fcd9879aa8040f196a235e2dcbdf7dd03ab5b07c0696f80bc6cf04bedd", size = 8461612 }, - { url = "https://files.pythonhosted.org/packages/40/b8/53fa08a5eaf78d3a7213fd6da1feec4bae14a81d9805e567013811ff0e85/matplotlib-3.10.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f69dc9713e4ad2fb21a1c30e37bd445d496524257dfda40ff4a8efb3604ab5c", size = 8602258 }, - { url = "https://files.pythonhosted.org/packages/40/87/4397d2ce808467af86684a622dd112664553e81752ea8bf61bdd89d24a41/matplotlib-3.10.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:4c59af3e8aca75d7744b68e8e78a669e91ccbcf1ac35d0102a7b1b46883f1dd7", size = 9408896 }, - { url = "https://files.pythonhosted.org/packages/d7/68/0d03098b3feb786cbd494df0aac15b571effda7f7cbdec267e8a8d398c16/matplotlib-3.10.1-cp311-cp311-win_amd64.whl", hash = "sha256:11b65088c6f3dae784bc72e8d039a2580186285f87448babb9ddb2ad0082993a", size = 8061281 }, - { url = "https://files.pythonhosted.org/packages/7c/1d/5e0dc3b59c034e43de16f94deb68f4ad8a96b3ea00f4b37c160b7474928e/matplotlib-3.10.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:66e907a06e68cb6cfd652c193311d61a12b54f56809cafbed9736ce5ad92f107", size = 8175488 }, - { url = "https://files.pythonhosted.org/packages/7a/81/dae7e14042e74da658c3336ab9799128e09a1ee03964f2d89630b5d12106/matplotlib-3.10.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:e9b4bb156abb8fa5e5b2b460196f7db7264fc6d62678c03457979e7d5254b7be", size = 8046264 }, - { url = "https://files.pythonhosted.org/packages/21/c4/22516775dcde10fc9c9571d155f90710761b028fc44f660508106c363c97/matplotlib-3.10.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1985ad3d97f51307a2cbfc801a930f120def19ba22864182dacef55277102ba6", size = 8452048 }, - { url = "https://files.pythonhosted.org/packages/63/23/c0615001f67ce7c96b3051d856baedc0c818a2ed84570b9bf9bde200f85d/matplotlib-3.10.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c96f2c2f825d1257e437a1482c5a2cf4fee15db4261bd6fc0750f81ba2b4ba3d", size = 8597111 }, - { url = "https://files.pythonhosted.org/packages/ca/c0/a07939a82aed77770514348f4568177d7dadab9787ebc618a616fe3d665e/matplotlib-3.10.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:35e87384ee9e488d8dd5a2dd7baf471178d38b90618d8ea147aced4ab59c9bea", size = 9402771 }, - { url = "https://files.pythonhosted.org/packages/a6/b6/a9405484fb40746fdc6ae4502b16a9d6e53282ba5baaf9ebe2da579f68c4/matplotlib-3.10.1-cp312-cp312-win_amd64.whl", hash = "sha256:cfd414bce89cc78a7e1d25202e979b3f1af799e416010a20ab2b5ebb3a02425c", size = 8063742 }, + { url = "https://files.pythonhosted.org/packages/f5/bd/af9f655456f60fe1d575f54fb14704ee299b16e999704817a7645dfce6b0/matplotlib-3.10.3-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:0ef061f74cd488586f552d0c336b2f078d43bc00dc473d2c3e7bfee2272f3fa8", size = 8178873, upload-time = "2025-05-08T19:09:53.857Z" }, + { url = "https://files.pythonhosted.org/packages/c2/86/e1c86690610661cd716eda5f9d0b35eaf606ae6c9b6736687cfc8f2d0cd8/matplotlib-3.10.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d96985d14dc5f4a736bbea4b9de9afaa735f8a0fc2ca75be2fa9e96b2097369d", size = 8052205, upload-time = "2025-05-08T19:09:55.684Z" }, + { url = "https://files.pythonhosted.org/packages/54/51/a9f8e49af3883dacddb2da1af5fca1f7468677f1188936452dd9aaaeb9ed/matplotlib-3.10.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7c5f0283da91e9522bdba4d6583ed9d5521566f63729ffb68334f86d0bb98049", size = 8465823, upload-time = "2025-05-08T19:09:57.442Z" }, + { url = "https://files.pythonhosted.org/packages/e7/e3/c82963a3b86d6e6d5874cbeaa390166458a7f1961bab9feb14d3d1a10f02/matplotlib-3.10.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fdfa07c0ec58035242bc8b2c8aae37037c9a886370eef6850703d7583e19964b", size = 8606464, upload-time = "2025-05-08T19:09:59.471Z" }, + { url = "https://files.pythonhosted.org/packages/0e/34/24da1027e7fcdd9e82da3194c470143c551852757a4b473a09a012f5b945/matplotlib-3.10.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c0b9849a17bce080a16ebcb80a7b714b5677d0ec32161a2cc0a8e5a6030ae220", size = 9413103, upload-time = "2025-05-08T19:10:03.208Z" }, + { url = "https://files.pythonhosted.org/packages/a6/da/948a017c3ea13fd4a97afad5fdebe2f5bbc4d28c0654510ce6fd6b06b7bd/matplotlib-3.10.3-cp311-cp311-win_amd64.whl", hash = "sha256:eef6ed6c03717083bc6d69c2d7ee8624205c29a8e6ea5a31cd3492ecdbaee1e1", size = 8065492, upload-time = "2025-05-08T19:10:05.271Z" }, + { url = "https://files.pythonhosted.org/packages/eb/43/6b80eb47d1071f234ef0c96ca370c2ca621f91c12045f1401b5c9b28a639/matplotlib-3.10.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:0ab1affc11d1f495ab9e6362b8174a25afc19c081ba5b0775ef00533a4236eea", size = 8179689, upload-time = "2025-05-08T19:10:07.602Z" }, + { url = "https://files.pythonhosted.org/packages/0f/70/d61a591958325c357204870b5e7b164f93f2a8cca1dc6ce940f563909a13/matplotlib-3.10.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2a818d8bdcafa7ed2eed74487fdb071c09c1ae24152d403952adad11fa3c65b4", size = 8050466, upload-time = "2025-05-08T19:10:09.383Z" }, + { url = "https://files.pythonhosted.org/packages/e7/75/70c9d2306203148cc7902a961240c5927dd8728afedf35e6a77e105a2985/matplotlib-3.10.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:748ebc3470c253e770b17d8b0557f0aa85cf8c63fd52f1a61af5b27ec0b7ffee", size = 8456252, upload-time = "2025-05-08T19:10:11.958Z" }, + { url = "https://files.pythonhosted.org/packages/c4/91/ba0ae1ff4b3f30972ad01cd4a8029e70a0ec3b8ea5be04764b128b66f763/matplotlib-3.10.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ed70453fd99733293ace1aec568255bc51c6361cb0da94fa5ebf0649fdb2150a", size = 8601321, upload-time = "2025-05-08T19:10:14.47Z" }, + { url = "https://files.pythonhosted.org/packages/d2/88/d636041eb54a84b889e11872d91f7cbf036b3b0e194a70fa064eb8b04f7a/matplotlib-3.10.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:dbed9917b44070e55640bd13419de83b4c918e52d97561544814ba463811cbc7", size = 9406972, upload-time = "2025-05-08T19:10:16.569Z" }, + { url = "https://files.pythonhosted.org/packages/b1/79/0d1c165eac44405a86478082e225fce87874f7198300bbebc55faaf6d28d/matplotlib-3.10.3-cp312-cp312-win_amd64.whl", hash = "sha256:cf37d8c6ef1a48829443e8ba5227b44236d7fcaf7647caa3178a4ff9f7a5be05", size = 8067954, upload-time = "2025-05-08T19:10:18.663Z" }, ] [[package]] name = "mergedeep" version = "1.3.4" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3a/41/580bb4006e3ed0361b8151a01d324fb03f420815446c7def45d02f74c270/mergedeep-1.3.4.tar.gz", hash = "sha256:0096d52e9dad9939c3d975a774666af186eda617e6ca84df4c94dec30004f2a8", size = 4661 } +sdist = { url = "https://files.pythonhosted.org/packages/3a/41/580bb4006e3ed0361b8151a01d324fb03f420815446c7def45d02f74c270/mergedeep-1.3.4.tar.gz", hash = "sha256:0096d52e9dad9939c3d975a774666af186eda617e6ca84df4c94dec30004f2a8", size = 4661, upload-time = "2021-02-05T18:55:30.623Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2c/19/04f9b178c2d8a15b076c8b5140708fa6ffc5601fb6f1e975537072df5b2a/mergedeep-1.3.4-py3-none-any.whl", hash = "sha256:70775750742b25c0d8f36c55aed03d24c3384d17c951b3175d898bd778ef0307", size = 6354 }, + { url = "https://files.pythonhosted.org/packages/2c/19/04f9b178c2d8a15b076c8b5140708fa6ffc5601fb6f1e975537072df5b2a/mergedeep-1.3.4-py3-none-any.whl", hash = "sha256:70775750742b25c0d8f36c55aed03d24c3384d17c951b3175d898bd778ef0307", size = 6354, upload-time = "2021-02-05T18:55:29.583Z" }, ] [[package]] @@ -954,22 +968,22 @@ name = "metadrive-simulator" version = "0.4.2.4" source = { url = "https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal-0.4.2.4/metadrive_simulator-0.4.2.4-py3-none-any.whl" } dependencies = [ - { name = "filelock", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "gymnasium", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "lxml", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "matplotlib", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "numpy", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "opencv-python-headless", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "panda3d", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "panda3d-gltf", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "pillow", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "progressbar", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "psutil", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "pygments", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "requests", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "shapely", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "tqdm", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "yapf", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "filelock" }, + { name = "gymnasium" }, + { name = "lxml" }, + { name = "matplotlib" }, + { name = "numpy" }, + { name = "opencv-python-headless" }, + { name = "panda3d" }, + { name = "panda3d-gltf" }, + { name = "pillow" }, + { name = "progressbar" }, + { name = "psutil" }, + { name = "pygments" }, + { name = "requests" }, + { name = "shapely" }, + { name = "tqdm" }, + { name = "yapf" }, ] wheels = [ { url = "https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal-0.4.2.4/metadrive_simulator-0.4.2.4-py3-none-any.whl", hash = "sha256:fbf0ea9be67e65cd45d38ff930e3d49f705dd76c9ddbd1e1482e3f87b61efcef" }, @@ -1022,9 +1036,9 @@ dependencies = [ { name = "pyyaml-env-tag" }, { name = "watchdog" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/bc/c6/bbd4f061bd16b378247f12953ffcb04786a618ce5e904b8c5a01a0309061/mkdocs-1.6.1.tar.gz", hash = "sha256:7b432f01d928c084353ab39c57282f29f92136665bdd6abf7c1ec8d822ef86f2", size = 3889159 } +sdist = { url = "https://files.pythonhosted.org/packages/bc/c6/bbd4f061bd16b378247f12953ffcb04786a618ce5e904b8c5a01a0309061/mkdocs-1.6.1.tar.gz", hash = "sha256:7b432f01d928c084353ab39c57282f29f92136665bdd6abf7c1ec8d822ef86f2", size = 3889159, upload-time = "2024-08-30T12:24:06.899Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/22/5b/dbc6a8cddc9cfa9c4971d59fb12bb8d42e161b7e7f8cc89e49137c5b279c/mkdocs-1.6.1-py3-none-any.whl", hash = "sha256:db91759624d1647f3f34aa0c3f327dd2601beae39a366d6e064c03468d35c20e", size = 3864451 }, + { url = "https://files.pythonhosted.org/packages/22/5b/dbc6a8cddc9cfa9c4971d59fb12bb8d42e161b7e7f8cc89e49137c5b279c/mkdocs-1.6.1-py3-none-any.whl", hash = "sha256:db91759624d1647f3f34aa0c3f327dd2601beae39a366d6e064c03468d35c20e", size = 3864451, upload-time = "2024-08-30T12:24:05.054Z" }, ] [[package]] @@ -1036,9 +1050,9 @@ dependencies = [ { name = "platformdirs" }, { name = "pyyaml" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/98/f5/ed29cd50067784976f25ed0ed6fcd3c2ce9eb90650aa3b2796ddf7b6870b/mkdocs_get_deps-0.2.0.tar.gz", hash = "sha256:162b3d129c7fad9b19abfdcb9c1458a651628e4b1dea628ac68790fb3061c60c", size = 10239 } +sdist = { url = "https://files.pythonhosted.org/packages/98/f5/ed29cd50067784976f25ed0ed6fcd3c2ce9eb90650aa3b2796ddf7b6870b/mkdocs_get_deps-0.2.0.tar.gz", hash = "sha256:162b3d129c7fad9b19abfdcb9c1458a651628e4b1dea628ac68790fb3061c60c", size = 10239, upload-time = "2023-11-20T17:51:09.981Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521 }, + { url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521, upload-time = "2023-11-20T17:51:08.587Z" }, ] [[package]] @@ -1050,81 +1064,84 @@ dependencies = [ { name = "python3-xlib", marker = "sys_platform == 'linux'" }, { name = "rubicon-objc", marker = "sys_platform == 'darwin'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/28/fa/b2ba8229b9381e8f6381c1dcae6f4159a7f72349e414ed19cfbbd1817173/MouseInfo-0.1.3.tar.gz", hash = "sha256:2c62fb8885062b8e520a3cce0a297c657adcc08c60952eb05bc8256ef6f7f6e7", size = 10850 } +sdist = { url = "https://files.pythonhosted.org/packages/28/fa/b2ba8229b9381e8f6381c1dcae6f4159a7f72349e414ed19cfbbd1817173/MouseInfo-0.1.3.tar.gz", hash = "sha256:2c62fb8885062b8e520a3cce0a297c657adcc08c60952eb05bc8256ef6f7f6e7", size = 10850, upload-time = "2020-03-27T21:20:10.136Z" } [[package]] name = "mpmath" version = "1.3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e0/47/dd32fa426cc72114383ac549964eecb20ecfd886d1e5ccf5340b55b02f57/mpmath-1.3.0.tar.gz", hash = "sha256:7a28eb2a9774d00c7bc92411c19a89209d5da7c4c9a9e227be8330a23a25b91f", size = 508106 } +sdist = { url = "https://files.pythonhosted.org/packages/e0/47/dd32fa426cc72114383ac549964eecb20ecfd886d1e5ccf5340b55b02f57/mpmath-1.3.0.tar.gz", hash = "sha256:7a28eb2a9774d00c7bc92411c19a89209d5da7c4c9a9e227be8330a23a25b91f", size = 508106, upload-time = "2023-03-07T16:47:11.061Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/43/e3/7d92a15f894aa0c9c4b49b8ee9ac9850d6e63b03c9c32c0367a13ae62209/mpmath-1.3.0-py3-none-any.whl", hash = "sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c", size = 536198 }, + { url = "https://files.pythonhosted.org/packages/43/e3/7d92a15f894aa0c9c4b49b8ee9ac9850d6e63b03c9c32c0367a13ae62209/mpmath-1.3.0-py3-none-any.whl", hash = "sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c", size = 536198, upload-time = "2023-03-07T16:47:09.197Z" }, ] [[package]] name = "msal" -version = "1.31.1" +version = "1.32.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cryptography" }, { name = "pyjwt", extra = ["crypto"] }, { name = "requests" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3f/f3/cdf2681e83a73c3355883c2884b6ff2f2d2aadfc399c28e9ac4edc3994fd/msal-1.31.1.tar.gz", hash = "sha256:11b5e6a3f802ffd3a72107203e20c4eac6ef53401961b880af2835b723d80578", size = 145362 } +sdist = { url = "https://files.pythonhosted.org/packages/3f/90/81dcc50f0be11a8c4dcbae1a9f761a26e5f905231330a7cacc9f04ec4c61/msal-1.32.3.tar.gz", hash = "sha256:5eea038689c78a5a70ca8ecbe1245458b55a857bd096efb6989c69ba15985d35", size = 151449, upload-time = "2025-04-25T13:12:34.204Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/30/7c/489cd931a752d05753d730e848039f08f65f86237cf1b8724d0a1cbd700b/msal-1.31.1-py3-none-any.whl", hash = "sha256:29d9882de247e96db01386496d59f29035e5e841bcac892e6d7bf4390bf6bd17", size = 113216 }, + { url = "https://files.pythonhosted.org/packages/04/bf/81516b9aac7fd867709984d08eb4db1d2e3fe1df795c8e442cde9b568962/msal-1.32.3-py3-none-any.whl", hash = "sha256:b2798db57760b1961b142f027ffb7c8169536bf77316e99a0df5c4aaebb11569", size = 115358, upload-time = "2025-04-25T13:12:33.034Z" }, ] [[package]] name = "msal-extensions" -version = "1.2.0" +version = "1.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "msal" }, - { name = "portalocker" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2d/38/ad49272d0a5af95f7a0cb64a79bbd75c9c187f3b789385a143d8d537a5eb/msal_extensions-1.2.0.tar.gz", hash = "sha256:6f41b320bfd2933d631a215c91ca0dd3e67d84bd1a2f50ce917d5874ec646bef", size = 22391 } +sdist = { url = "https://files.pythonhosted.org/packages/01/99/5d239b6156eddf761a636bded1118414d161bd6b7b37a9335549ed159396/msal_extensions-1.3.1.tar.gz", hash = "sha256:c5b0fd10f65ef62b5f1d62f4251d51cbcaf003fcedae8c91b040a488614be1a4", size = 23315, upload-time = "2025-03-14T23:51:03.902Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2c/69/314d887a01599669fb330da14e5c6ff5f138609e322812a942a74ef9b765/msal_extensions-1.2.0-py3-none-any.whl", hash = "sha256:cf5ba83a2113fa6dc011a254a72f1c223c88d7dfad74cc30617c4679a417704d", size = 19254 }, + { url = "https://files.pythonhosted.org/packages/5e/75/bd9b7bb966668920f06b200e84454c8f3566b102183bc55c5473d96cb2b9/msal_extensions-1.3.1-py3-none-any.whl", hash = "sha256:96d3de4d034504e969ac5e85bae8106c8373b5c6568e4c8fa7af2eca9dbe6bca", size = 20583, upload-time = "2025-03-14T23:51:03.016Z" }, ] [[package]] name = "multidict" -version = "6.1.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d6/be/504b89a5e9ca731cd47487e91c469064f8ae5af93b7259758dcfc2b9c848/multidict-6.1.0.tar.gz", hash = "sha256:22ae2ebf9b0c69d206c003e2f6a914ea33f0a932d4aa16f236afc049d9958f4a", size = 64002 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/93/13/df3505a46d0cd08428e4c8169a196131d1b0c4b515c3649829258843dde6/multidict-6.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3efe2c2cb5763f2f1b275ad2bf7a287d3f7ebbef35648a9726e3b69284a4f3d6", size = 48570 }, - { url = "https://files.pythonhosted.org/packages/f0/e1/a215908bfae1343cdb72f805366592bdd60487b4232d039c437fe8f5013d/multidict-6.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c7053d3b0353a8b9de430a4f4b4268ac9a4fb3481af37dfe49825bf45ca24156", size = 29316 }, - { url = "https://files.pythonhosted.org/packages/70/0f/6dc70ddf5d442702ed74f298d69977f904960b82368532c88e854b79f72b/multidict-6.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:27e5fc84ccef8dfaabb09d82b7d179c7cf1a3fbc8a966f8274fcb4ab2eb4cadb", size = 29640 }, - { url = "https://files.pythonhosted.org/packages/d8/6d/9c87b73a13d1cdea30b321ef4b3824449866bd7f7127eceed066ccb9b9ff/multidict-6.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0e2b90b43e696f25c62656389d32236e049568b39320e2735d51f08fd362761b", size = 131067 }, - { url = "https://files.pythonhosted.org/packages/cc/1e/1b34154fef373371fd6c65125b3d42ff5f56c7ccc6bfff91b9b3c60ae9e0/multidict-6.1.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d83a047959d38a7ff552ff94be767b7fd79b831ad1cd9920662db05fec24fe72", size = 138507 }, - { url = "https://files.pythonhosted.org/packages/fb/e0/0bc6b2bac6e461822b5f575eae85da6aae76d0e2a79b6665d6206b8e2e48/multidict-6.1.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d1a9dd711d0877a1ece3d2e4fea11a8e75741ca21954c919406b44e7cf971304", size = 133905 }, - { url = "https://files.pythonhosted.org/packages/ba/af/73d13b918071ff9b2205fcf773d316e0f8fefb4ec65354bbcf0b10908cc6/multidict-6.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec2abea24d98246b94913b76a125e855eb5c434f7c46546046372fe60f666351", size = 129004 }, - { url = "https://files.pythonhosted.org/packages/74/21/23960627b00ed39643302d81bcda44c9444ebcdc04ee5bedd0757513f259/multidict-6.1.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4867cafcbc6585e4b678876c489b9273b13e9fff9f6d6d66add5e15d11d926cb", size = 121308 }, - { url = "https://files.pythonhosted.org/packages/8b/5c/cf282263ffce4a596ed0bb2aa1a1dddfe1996d6a62d08842a8d4b33dca13/multidict-6.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b48204e8d955c47c55b72779802b219a39acc3ee3d0116d5080c388970b76e3", size = 132608 }, - { url = "https://files.pythonhosted.org/packages/d7/3e/97e778c041c72063f42b290888daff008d3ab1427f5b09b714f5a8eff294/multidict-6.1.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:d8fff389528cad1618fb4b26b95550327495462cd745d879a8c7c2115248e399", size = 127029 }, - { url = "https://files.pythonhosted.org/packages/47/ac/3efb7bfe2f3aefcf8d103e9a7162572f01936155ab2f7ebcc7c255a23212/multidict-6.1.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a7a9541cd308eed5e30318430a9c74d2132e9a8cb46b901326272d780bf2d423", size = 137594 }, - { url = "https://files.pythonhosted.org/packages/42/9b/6c6e9e8dc4f915fc90a9b7798c44a30773dea2995fdcb619870e705afe2b/multidict-6.1.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:da1758c76f50c39a2efd5e9859ce7d776317eb1dd34317c8152ac9251fc574a3", size = 134556 }, - { url = "https://files.pythonhosted.org/packages/1d/10/8e881743b26aaf718379a14ac58572a240e8293a1c9d68e1418fb11c0f90/multidict-6.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c943a53e9186688b45b323602298ab727d8865d8c9ee0b17f8d62d14b56f0753", size = 130993 }, - { url = "https://files.pythonhosted.org/packages/45/84/3eb91b4b557442802d058a7579e864b329968c8d0ea57d907e7023c677f2/multidict-6.1.0-cp311-cp311-win32.whl", hash = "sha256:90f8717cb649eea3504091e640a1b8568faad18bd4b9fcd692853a04475a4b80", size = 26405 }, - { url = "https://files.pythonhosted.org/packages/9f/0b/ad879847ecbf6d27e90a6eabb7eff6b62c129eefe617ea45eae7c1f0aead/multidict-6.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:82176036e65644a6cc5bd619f65f6f19781e8ec2e5330f51aa9ada7504cc1926", size = 28795 }, - { url = "https://files.pythonhosted.org/packages/fd/16/92057c74ba3b96d5e211b553895cd6dc7cc4d1e43d9ab8fafc727681ef71/multidict-6.1.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:b04772ed465fa3cc947db808fa306d79b43e896beb677a56fb2347ca1a49c1fa", size = 48713 }, - { url = "https://files.pythonhosted.org/packages/94/3d/37d1b8893ae79716179540b89fc6a0ee56b4a65fcc0d63535c6f5d96f217/multidict-6.1.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:6180c0ae073bddeb5a97a38c03f30c233e0a4d39cd86166251617d1bbd0af436", size = 29516 }, - { url = "https://files.pythonhosted.org/packages/a2/12/adb6b3200c363062f805275b4c1e656be2b3681aada66c80129932ff0bae/multidict-6.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:071120490b47aa997cca00666923a83f02c7fbb44f71cf7f136df753f7fa8761", size = 29557 }, - { url = "https://files.pythonhosted.org/packages/47/e9/604bb05e6e5bce1e6a5cf80a474e0f072e80d8ac105f1b994a53e0b28c42/multidict-6.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:50b3a2710631848991d0bf7de077502e8994c804bb805aeb2925a981de58ec2e", size = 130170 }, - { url = "https://files.pythonhosted.org/packages/7e/13/9efa50801785eccbf7086b3c83b71a4fb501a4d43549c2f2f80b8787d69f/multidict-6.1.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b58c621844d55e71c1b7f7c498ce5aa6985d743a1a59034c57a905b3f153c1ef", size = 134836 }, - { url = "https://files.pythonhosted.org/packages/bf/0f/93808b765192780d117814a6dfcc2e75de6dcc610009ad408b8814dca3ba/multidict-6.1.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:55b6d90641869892caa9ca42ff913f7ff1c5ece06474fbd32fb2cf6834726c95", size = 133475 }, - { url = "https://files.pythonhosted.org/packages/d3/c8/529101d7176fe7dfe1d99604e48d69c5dfdcadb4f06561f465c8ef12b4df/multidict-6.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b820514bfc0b98a30e3d85462084779900347e4d49267f747ff54060cc33925", size = 131049 }, - { url = "https://files.pythonhosted.org/packages/ca/0c/fc85b439014d5a58063e19c3a158a889deec399d47b5269a0f3b6a2e28bc/multidict-6.1.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:10a9b09aba0c5b48c53761b7c720aaaf7cf236d5fe394cd399c7ba662d5f9966", size = 120370 }, - { url = "https://files.pythonhosted.org/packages/db/46/d4416eb20176492d2258fbd47b4abe729ff3b6e9c829ea4236f93c865089/multidict-6.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1e16bf3e5fc9f44632affb159d30a437bfe286ce9e02754759be5536b169b305", size = 125178 }, - { url = "https://files.pythonhosted.org/packages/5b/46/73697ad7ec521df7de5531a32780bbfd908ded0643cbe457f981a701457c/multidict-6.1.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76f364861c3bfc98cbbcbd402d83454ed9e01a5224bb3a28bf70002a230f73e2", size = 119567 }, - { url = "https://files.pythonhosted.org/packages/cd/ed/51f060e2cb0e7635329fa6ff930aa5cffa17f4c7f5c6c3ddc3500708e2f2/multidict-6.1.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:820c661588bd01a0aa62a1283f20d2be4281b086f80dad9e955e690c75fb54a2", size = 129822 }, - { url = "https://files.pythonhosted.org/packages/df/9e/ee7d1954b1331da3eddea0c4e08d9142da5f14b1321c7301f5014f49d492/multidict-6.1.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:0e5f362e895bc5b9e67fe6e4ded2492d8124bdf817827f33c5b46c2fe3ffaca6", size = 128656 }, - { url = "https://files.pythonhosted.org/packages/77/00/8538f11e3356b5d95fa4b024aa566cde7a38aa7a5f08f4912b32a037c5dc/multidict-6.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3ec660d19bbc671e3a6443325f07263be452c453ac9e512f5eb935e7d4ac28b3", size = 125360 }, - { url = "https://files.pythonhosted.org/packages/be/05/5d334c1f2462d43fec2363cd00b1c44c93a78c3925d952e9a71caf662e96/multidict-6.1.0-cp312-cp312-win32.whl", hash = "sha256:58130ecf8f7b8112cdb841486404f1282b9c86ccb30d3519faf301b2e5659133", size = 26382 }, - { url = "https://files.pythonhosted.org/packages/a3/bf/f332a13486b1ed0496d624bcc7e8357bb8053823e8cd4b9a18edc1d97e73/multidict-6.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:188215fc0aafb8e03341995e7c4797860181562380f81ed0a87ff455b70bf1f1", size = 28529 }, - { url = "https://files.pythonhosted.org/packages/99/b7/b9e70fde2c0f0c9af4cc5277782a89b66d35948ea3369ec9f598358c3ac5/multidict-6.1.0-py3-none-any.whl", hash = "sha256:48e171e52d1c4d33888e529b999e5900356b9ae588c2f09a52dcefb158b27506", size = 10051 }, +version = "6.4.4" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/91/2f/a3470242707058fe856fe59241eee5635d79087100b7042a867368863a27/multidict-6.4.4.tar.gz", hash = "sha256:69ee9e6ba214b5245031b76233dd95408a0fd57fdb019ddcc1ead4790932a8e8", size = 90183, upload-time = "2025-05-19T14:16:37.381Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/19/1b/4c6e638195851524a63972c5773c7737bea7e47b1ba402186a37773acee2/multidict-6.4.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4f5f29794ac0e73d2a06ac03fd18870adc0135a9d384f4a306a951188ed02f95", size = 65515, upload-time = "2025-05-19T14:14:19.767Z" }, + { url = "https://files.pythonhosted.org/packages/25/d5/10e6bca9a44b8af3c7f920743e5fc0c2bcf8c11bf7a295d4cfe00b08fb46/multidict-6.4.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c04157266344158ebd57b7120d9b0b35812285d26d0e78193e17ef57bfe2979a", size = 38609, upload-time = "2025-05-19T14:14:21.538Z" }, + { url = "https://files.pythonhosted.org/packages/26/b4/91fead447ccff56247edc7f0535fbf140733ae25187a33621771ee598a18/multidict-6.4.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bb61ffd3ab8310d93427e460f565322c44ef12769f51f77277b4abad7b6f7223", size = 37871, upload-time = "2025-05-19T14:14:22.666Z" }, + { url = "https://files.pythonhosted.org/packages/3b/37/cbc977cae59277e99d15bbda84cc53b5e0c4929ffd91d958347200a42ad0/multidict-6.4.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5e0ba18a9afd495f17c351d08ebbc4284e9c9f7971d715f196b79636a4d0de44", size = 226661, upload-time = "2025-05-19T14:14:24.124Z" }, + { url = "https://files.pythonhosted.org/packages/15/cd/7e0b57fbd4dc2fc105169c4ecce5be1a63970f23bb4ec8c721b67e11953d/multidict-6.4.4-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:9faf1b1dcaadf9f900d23a0e6d6c8eadd6a95795a0e57fcca73acce0eb912065", size = 223422, upload-time = "2025-05-19T14:14:25.437Z" }, + { url = "https://files.pythonhosted.org/packages/f1/01/1de268da121bac9f93242e30cd3286f6a819e5f0b8896511162d6ed4bf8d/multidict-6.4.4-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a4d1cb1327c6082c4fce4e2a438483390964c02213bc6b8d782cf782c9b1471f", size = 235447, upload-time = "2025-05-19T14:14:26.793Z" }, + { url = "https://files.pythonhosted.org/packages/d2/8c/8b9a5e4aaaf4f2de14e86181a3a3d7b105077f668b6a06f043ec794f684c/multidict-6.4.4-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:941f1bec2f5dbd51feeb40aea654c2747f811ab01bdd3422a48a4e4576b7d76a", size = 231455, upload-time = "2025-05-19T14:14:28.149Z" }, + { url = "https://files.pythonhosted.org/packages/35/db/e1817dcbaa10b319c412769cf999b1016890849245d38905b73e9c286862/multidict-6.4.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e5f8a146184da7ea12910a4cec51ef85e44f6268467fb489c3caf0cd512f29c2", size = 223666, upload-time = "2025-05-19T14:14:29.584Z" }, + { url = "https://files.pythonhosted.org/packages/4a/e1/66e8579290ade8a00e0126b3d9a93029033ffd84f0e697d457ed1814d0fc/multidict-6.4.4-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:232b7237e57ec3c09be97206bfb83a0aa1c5d7d377faa019c68a210fa35831f1", size = 217392, upload-time = "2025-05-19T14:14:30.961Z" }, + { url = "https://files.pythonhosted.org/packages/7b/6f/f8639326069c24a48c7747c2a5485d37847e142a3f741ff3340c88060a9a/multidict-6.4.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:55ae0721c1513e5e3210bca4fc98456b980b0c2c016679d3d723119b6b202c42", size = 228969, upload-time = "2025-05-19T14:14:32.672Z" }, + { url = "https://files.pythonhosted.org/packages/d2/c3/3d58182f76b960eeade51c89fcdce450f93379340457a328e132e2f8f9ed/multidict-6.4.4-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:51d662c072579f63137919d7bb8fc250655ce79f00c82ecf11cab678f335062e", size = 217433, upload-time = "2025-05-19T14:14:34.016Z" }, + { url = "https://files.pythonhosted.org/packages/e1/4b/f31a562906f3bd375f3d0e83ce314e4a660c01b16c2923e8229b53fba5d7/multidict-6.4.4-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:0e05c39962baa0bb19a6b210e9b1422c35c093b651d64246b6c2e1a7e242d9fd", size = 225418, upload-time = "2025-05-19T14:14:35.376Z" }, + { url = "https://files.pythonhosted.org/packages/99/89/78bb95c89c496d64b5798434a3deee21996114d4d2c28dd65850bf3a691e/multidict-6.4.4-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:d5b1cc3ab8c31d9ebf0faa6e3540fb91257590da330ffe6d2393d4208e638925", size = 235042, upload-time = "2025-05-19T14:14:36.723Z" }, + { url = "https://files.pythonhosted.org/packages/74/91/8780a6e5885a8770442a8f80db86a0887c4becca0e5a2282ba2cae702bc4/multidict-6.4.4-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:93ec84488a384cd7b8a29c2c7f467137d8a73f6fe38bb810ecf29d1ade011a7c", size = 230280, upload-time = "2025-05-19T14:14:38.194Z" }, + { url = "https://files.pythonhosted.org/packages/68/c1/fcf69cabd542eb6f4b892469e033567ee6991d361d77abdc55e3a0f48349/multidict-6.4.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b308402608493638763abc95f9dc0030bbd6ac6aff784512e8ac3da73a88af08", size = 223322, upload-time = "2025-05-19T14:14:40.015Z" }, + { url = "https://files.pythonhosted.org/packages/b8/85/5b80bf4b83d8141bd763e1d99142a9cdfd0db83f0739b4797172a4508014/multidict-6.4.4-cp311-cp311-win32.whl", hash = "sha256:343892a27d1a04d6ae455ecece12904d242d299ada01633d94c4f431d68a8c49", size = 35070, upload-time = "2025-05-19T14:14:41.904Z" }, + { url = "https://files.pythonhosted.org/packages/09/66/0bed198ffd590ab86e001f7fa46b740d58cf8ff98c2f254e4a36bf8861ad/multidict-6.4.4-cp311-cp311-win_amd64.whl", hash = "sha256:73484a94f55359780c0f458bbd3c39cb9cf9c182552177d2136e828269dee529", size = 38667, upload-time = "2025-05-19T14:14:43.534Z" }, + { url = "https://files.pythonhosted.org/packages/d2/b5/5675377da23d60875fe7dae6be841787755878e315e2f517235f22f59e18/multidict-6.4.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:dc388f75a1c00000824bf28b7633e40854f4127ede80512b44c3cfeeea1839a2", size = 64293, upload-time = "2025-05-19T14:14:44.724Z" }, + { url = "https://files.pythonhosted.org/packages/34/a7/be384a482754bb8c95d2bbe91717bf7ccce6dc38c18569997a11f95aa554/multidict-6.4.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:98af87593a666f739d9dba5d0ae86e01b0e1a9cfcd2e30d2d361fbbbd1a9162d", size = 38096, upload-time = "2025-05-19T14:14:45.95Z" }, + { url = "https://files.pythonhosted.org/packages/66/6d/d59854bb4352306145bdfd1704d210731c1bb2c890bfee31fb7bbc1c4c7f/multidict-6.4.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:aff4cafea2d120327d55eadd6b7f1136a8e5a0ecf6fb3b6863e8aca32cd8e50a", size = 37214, upload-time = "2025-05-19T14:14:47.158Z" }, + { url = "https://files.pythonhosted.org/packages/99/e0/c29d9d462d7cfc5fc8f9bf24f9c6843b40e953c0b55e04eba2ad2cf54fba/multidict-6.4.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:169c4ba7858176b797fe551d6e99040c531c775d2d57b31bcf4de6d7a669847f", size = 224686, upload-time = "2025-05-19T14:14:48.366Z" }, + { url = "https://files.pythonhosted.org/packages/dc/4a/da99398d7fd8210d9de068f9a1b5f96dfaf67d51e3f2521f17cba4ee1012/multidict-6.4.4-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:b9eb4c59c54421a32b3273d4239865cb14ead53a606db066d7130ac80cc8ec93", size = 231061, upload-time = "2025-05-19T14:14:49.952Z" }, + { url = "https://files.pythonhosted.org/packages/21/f5/ac11add39a0f447ac89353e6ca46666847051103649831c08a2800a14455/multidict-6.4.4-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7cf3bd54c56aa16fdb40028d545eaa8d051402b61533c21e84046e05513d5780", size = 232412, upload-time = "2025-05-19T14:14:51.812Z" }, + { url = "https://files.pythonhosted.org/packages/d9/11/4b551e2110cded705a3c13a1d4b6a11f73891eb5a1c449f1b2b6259e58a6/multidict-6.4.4-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f682c42003c7264134bfe886376299db4cc0c6cd06a3295b41b347044bcb5482", size = 231563, upload-time = "2025-05-19T14:14:53.262Z" }, + { url = "https://files.pythonhosted.org/packages/4c/02/751530c19e78fe73b24c3da66618eda0aa0d7f6e7aa512e46483de6be210/multidict-6.4.4-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a920f9cf2abdf6e493c519492d892c362007f113c94da4c239ae88429835bad1", size = 223811, upload-time = "2025-05-19T14:14:55.232Z" }, + { url = "https://files.pythonhosted.org/packages/c7/cb/2be8a214643056289e51ca356026c7b2ce7225373e7a1f8c8715efee8988/multidict-6.4.4-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:530d86827a2df6504526106b4c104ba19044594f8722d3e87714e847c74a0275", size = 216524, upload-time = "2025-05-19T14:14:57.226Z" }, + { url = "https://files.pythonhosted.org/packages/19/f3/6d5011ec375c09081f5250af58de85f172bfcaafebff286d8089243c4bd4/multidict-6.4.4-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:ecde56ea2439b96ed8a8d826b50c57364612ddac0438c39e473fafad7ae1c23b", size = 229012, upload-time = "2025-05-19T14:14:58.597Z" }, + { url = "https://files.pythonhosted.org/packages/67/9c/ca510785df5cf0eaf5b2a8132d7d04c1ce058dcf2c16233e596ce37a7f8e/multidict-6.4.4-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:dc8c9736d8574b560634775ac0def6bdc1661fc63fa27ffdfc7264c565bcb4f2", size = 226765, upload-time = "2025-05-19T14:15:00.048Z" }, + { url = "https://files.pythonhosted.org/packages/36/c8/ca86019994e92a0f11e642bda31265854e6ea7b235642f0477e8c2e25c1f/multidict-6.4.4-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:7f3d3b3c34867579ea47cbd6c1f2ce23fbfd20a273b6f9e3177e256584f1eacc", size = 222888, upload-time = "2025-05-19T14:15:01.568Z" }, + { url = "https://files.pythonhosted.org/packages/c6/67/bc25a8e8bd522935379066950ec4e2277f9b236162a73548a2576d4b9587/multidict-6.4.4-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:87a728af265e08f96b6318ebe3c0f68b9335131f461efab2fc64cc84a44aa6ed", size = 234041, upload-time = "2025-05-19T14:15:03.759Z" }, + { url = "https://files.pythonhosted.org/packages/f1/a0/70c4c2d12857fccbe607b334b7ee28b6b5326c322ca8f73ee54e70d76484/multidict-6.4.4-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9f193eeda1857f8e8d3079a4abd258f42ef4a4bc87388452ed1e1c4d2b0c8740", size = 231046, upload-time = "2025-05-19T14:15:05.698Z" }, + { url = "https://files.pythonhosted.org/packages/c1/0f/52954601d02d39742aab01d6b92f53c1dd38b2392248154c50797b4df7f1/multidict-6.4.4-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:be06e73c06415199200e9a2324a11252a3d62030319919cde5e6950ffeccf72e", size = 227106, upload-time = "2025-05-19T14:15:07.124Z" }, + { url = "https://files.pythonhosted.org/packages/af/24/679d83ec4379402d28721790dce818e5d6b9f94ce1323a556fb17fa9996c/multidict-6.4.4-cp312-cp312-win32.whl", hash = "sha256:622f26ea6a7e19b7c48dd9228071f571b2fbbd57a8cd71c061e848f281550e6b", size = 35351, upload-time = "2025-05-19T14:15:08.556Z" }, + { url = "https://files.pythonhosted.org/packages/52/ef/40d98bc5f986f61565f9b345f102409534e29da86a6454eb6b7c00225a13/multidict-6.4.4-cp312-cp312-win_amd64.whl", hash = "sha256:5e2bcda30d5009996ff439e02a9f2b5c3d64a20151d34898c000a6281faa3781", size = 38791, upload-time = "2025-05-19T14:15:09.825Z" }, + { url = "https://files.pythonhosted.org/packages/84/5d/e17845bb0fa76334477d5de38654d27946d5b5d3695443987a094a71b440/multidict-6.4.4-py3-none-any.whl", hash = "sha256:bd4557071b561a8b3b6075c3ce93cf9bfb6182cb241805c3d66ced3b75eff4ac", size = 10481, upload-time = "2025-05-19T14:16:36.024Z" }, ] [[package]] @@ -1135,85 +1152,92 @@ dependencies = [ { name = "mypy-extensions" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ce/43/d5e49a86afa64bd3839ea0d5b9c7103487007d728e1293f52525d6d5486a/mypy-1.15.0.tar.gz", hash = "sha256:404534629d51d3efea5c800ee7c42b72a6554d6c400e6a79eafe15d11341fd43", size = 3239717 } +sdist = { url = "https://files.pythonhosted.org/packages/ce/43/d5e49a86afa64bd3839ea0d5b9c7103487007d728e1293f52525d6d5486a/mypy-1.15.0.tar.gz", hash = "sha256:404534629d51d3efea5c800ee7c42b72a6554d6c400e6a79eafe15d11341fd43", size = 3239717, upload-time = "2025-02-05T03:50:34.655Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/03/bc/f6339726c627bd7ca1ce0fa56c9ae2d0144604a319e0e339bdadafbbb599/mypy-1.15.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2922d42e16d6de288022e5ca321cd0618b238cfc5570e0263e5ba0a77dbef56f", size = 10662338 }, - { url = "https://files.pythonhosted.org/packages/e2/90/8dcf506ca1a09b0d17555cc00cd69aee402c203911410136cd716559efe7/mypy-1.15.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2ee2d57e01a7c35de00f4634ba1bbf015185b219e4dc5909e281016df43f5ee5", size = 9787540 }, - { url = "https://files.pythonhosted.org/packages/05/05/a10f9479681e5da09ef2f9426f650d7b550d4bafbef683b69aad1ba87457/mypy-1.15.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:973500e0774b85d9689715feeffcc980193086551110fd678ebe1f4342fb7c5e", size = 11538051 }, - { url = "https://files.pythonhosted.org/packages/e9/9a/1f7d18b30edd57441a6411fcbc0c6869448d1a4bacbaee60656ac0fc29c8/mypy-1.15.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5a95fb17c13e29d2d5195869262f8125dfdb5c134dc8d9a9d0aecf7525b10c2c", size = 12286751 }, - { url = "https://files.pythonhosted.org/packages/72/af/19ff499b6f1dafcaf56f9881f7a965ac2f474f69f6f618b5175b044299f5/mypy-1.15.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1905f494bfd7d85a23a88c5d97840888a7bd516545fc5aaedff0267e0bb54e2f", size = 12421783 }, - { url = "https://files.pythonhosted.org/packages/96/39/11b57431a1f686c1aed54bf794870efe0f6aeca11aca281a0bd87a5ad42c/mypy-1.15.0-cp311-cp311-win_amd64.whl", hash = "sha256:c9817fa23833ff189db061e6d2eff49b2f3b6ed9856b4a0a73046e41932d744f", size = 9265618 }, - { url = "https://files.pythonhosted.org/packages/98/3a/03c74331c5eb8bd025734e04c9840532226775c47a2c39b56a0c8d4f128d/mypy-1.15.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:aea39e0583d05124836ea645f412e88a5c7d0fd77a6d694b60d9b6b2d9f184fd", size = 10793981 }, - { url = "https://files.pythonhosted.org/packages/f0/1a/41759b18f2cfd568848a37c89030aeb03534411eef981df621d8fad08a1d/mypy-1.15.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2f2147ab812b75e5b5499b01ade1f4a81489a147c01585cda36019102538615f", size = 9749175 }, - { url = "https://files.pythonhosted.org/packages/12/7e/873481abf1ef112c582db832740f4c11b2bfa510e829d6da29b0ab8c3f9c/mypy-1.15.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ce436f4c6d218a070048ed6a44c0bbb10cd2cc5e272b29e7845f6a2f57ee4464", size = 11455675 }, - { url = "https://files.pythonhosted.org/packages/b3/d0/92ae4cde706923a2d3f2d6c39629134063ff64b9dedca9c1388363da072d/mypy-1.15.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8023ff13985661b50a5928fc7a5ca15f3d1affb41e5f0a9952cb68ef090b31ee", size = 12410020 }, - { url = "https://files.pythonhosted.org/packages/46/8b/df49974b337cce35f828ba6fda228152d6db45fed4c86ba56ffe442434fd/mypy-1.15.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1124a18bc11a6a62887e3e137f37f53fbae476dc36c185d549d4f837a2a6a14e", size = 12498582 }, - { url = "https://files.pythonhosted.org/packages/13/50/da5203fcf6c53044a0b699939f31075c45ae8a4cadf538a9069b165c1050/mypy-1.15.0-cp312-cp312-win_amd64.whl", hash = "sha256:171a9ca9a40cd1843abeca0e405bc1940cd9b305eaeea2dda769ba096932bb22", size = 9366614 }, - { url = "https://files.pythonhosted.org/packages/09/4e/a7d65c7322c510de2c409ff3828b03354a7c43f5a8ed458a7a131b41c7b9/mypy-1.15.0-py3-none-any.whl", hash = "sha256:5469affef548bd1895d86d3bf10ce2b44e33d86923c29e4d675b3e323437ea3e", size = 2221777 }, + { url = "https://files.pythonhosted.org/packages/03/bc/f6339726c627bd7ca1ce0fa56c9ae2d0144604a319e0e339bdadafbbb599/mypy-1.15.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2922d42e16d6de288022e5ca321cd0618b238cfc5570e0263e5ba0a77dbef56f", size = 10662338, upload-time = "2025-02-05T03:50:17.287Z" }, + { url = "https://files.pythonhosted.org/packages/e2/90/8dcf506ca1a09b0d17555cc00cd69aee402c203911410136cd716559efe7/mypy-1.15.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2ee2d57e01a7c35de00f4634ba1bbf015185b219e4dc5909e281016df43f5ee5", size = 9787540, upload-time = "2025-02-05T03:49:51.21Z" }, + { url = "https://files.pythonhosted.org/packages/05/05/a10f9479681e5da09ef2f9426f650d7b550d4bafbef683b69aad1ba87457/mypy-1.15.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:973500e0774b85d9689715feeffcc980193086551110fd678ebe1f4342fb7c5e", size = 11538051, upload-time = "2025-02-05T03:50:20.885Z" }, + { url = "https://files.pythonhosted.org/packages/e9/9a/1f7d18b30edd57441a6411fcbc0c6869448d1a4bacbaee60656ac0fc29c8/mypy-1.15.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5a95fb17c13e29d2d5195869262f8125dfdb5c134dc8d9a9d0aecf7525b10c2c", size = 12286751, upload-time = "2025-02-05T03:49:42.408Z" }, + { url = "https://files.pythonhosted.org/packages/72/af/19ff499b6f1dafcaf56f9881f7a965ac2f474f69f6f618b5175b044299f5/mypy-1.15.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1905f494bfd7d85a23a88c5d97840888a7bd516545fc5aaedff0267e0bb54e2f", size = 12421783, upload-time = "2025-02-05T03:49:07.707Z" }, + { url = "https://files.pythonhosted.org/packages/96/39/11b57431a1f686c1aed54bf794870efe0f6aeca11aca281a0bd87a5ad42c/mypy-1.15.0-cp311-cp311-win_amd64.whl", hash = "sha256:c9817fa23833ff189db061e6d2eff49b2f3b6ed9856b4a0a73046e41932d744f", size = 9265618, upload-time = "2025-02-05T03:49:54.581Z" }, + { url = "https://files.pythonhosted.org/packages/98/3a/03c74331c5eb8bd025734e04c9840532226775c47a2c39b56a0c8d4f128d/mypy-1.15.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:aea39e0583d05124836ea645f412e88a5c7d0fd77a6d694b60d9b6b2d9f184fd", size = 10793981, upload-time = "2025-02-05T03:50:28.25Z" }, + { url = "https://files.pythonhosted.org/packages/f0/1a/41759b18f2cfd568848a37c89030aeb03534411eef981df621d8fad08a1d/mypy-1.15.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2f2147ab812b75e5b5499b01ade1f4a81489a147c01585cda36019102538615f", size = 9749175, upload-time = "2025-02-05T03:50:13.411Z" }, + { url = "https://files.pythonhosted.org/packages/12/7e/873481abf1ef112c582db832740f4c11b2bfa510e829d6da29b0ab8c3f9c/mypy-1.15.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ce436f4c6d218a070048ed6a44c0bbb10cd2cc5e272b29e7845f6a2f57ee4464", size = 11455675, upload-time = "2025-02-05T03:50:31.421Z" }, + { url = "https://files.pythonhosted.org/packages/b3/d0/92ae4cde706923a2d3f2d6c39629134063ff64b9dedca9c1388363da072d/mypy-1.15.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8023ff13985661b50a5928fc7a5ca15f3d1affb41e5f0a9952cb68ef090b31ee", size = 12410020, upload-time = "2025-02-05T03:48:48.705Z" }, + { url = "https://files.pythonhosted.org/packages/46/8b/df49974b337cce35f828ba6fda228152d6db45fed4c86ba56ffe442434fd/mypy-1.15.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1124a18bc11a6a62887e3e137f37f53fbae476dc36c185d549d4f837a2a6a14e", size = 12498582, upload-time = "2025-02-05T03:49:03.628Z" }, + { url = "https://files.pythonhosted.org/packages/13/50/da5203fcf6c53044a0b699939f31075c45ae8a4cadf538a9069b165c1050/mypy-1.15.0-cp312-cp312-win_amd64.whl", hash = "sha256:171a9ca9a40cd1843abeca0e405bc1940cd9b305eaeea2dda769ba096932bb22", size = 9366614, upload-time = "2025-02-05T03:50:00.313Z" }, + { url = "https://files.pythonhosted.org/packages/09/4e/a7d65c7322c510de2c409ff3828b03354a7c43f5a8ed458a7a131b41c7b9/mypy-1.15.0-py3-none-any.whl", hash = "sha256:5469affef548bd1895d86d3bf10ce2b44e33d86923c29e4d675b3e323437ea3e", size = 2221777, upload-time = "2025-02-05T03:50:08.348Z" }, ] [[package]] name = "mypy-extensions" -version = "1.0.0" +version = "1.1.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/98/a4/1ab47638b92648243faf97a5aeb6ea83059cc3624972ab6b8d2316078d3f/mypy_extensions-1.0.0.tar.gz", hash = "sha256:75dbf8955dc00442a438fc4d0666508a9a97b6bd41aa2f0ffe9d2f2725af0782", size = 4433 } +sdist = { url = "https://files.pythonhosted.org/packages/a2/6e/371856a3fb9d31ca8dac321cda606860fa4548858c0cc45d9d1d4ca2628b/mypy_extensions-1.1.0.tar.gz", hash = "sha256:52e68efc3284861e772bbcd66823fde5ae21fd2fdb51c62a211403730b916558", size = 6343, upload-time = "2025-04-22T14:54:24.164Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2a/e2/5d3f6ada4297caebe1a2add3b126fe800c96f56dbe5d1988a2cbe0b267aa/mypy_extensions-1.0.0-py3-none-any.whl", hash = "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d", size = 4695 }, + { url = "https://files.pythonhosted.org/packages/79/7b/2c79738432f5c924bef5071f933bcc9efd0473bac3b4aa584a6f7c1c8df8/mypy_extensions-1.1.0-py3-none-any.whl", hash = "sha256:1be4cccdb0f2482337c4743e60421de3a356cd97508abadd57d47403e94f5505", size = 4963, upload-time = "2025-04-22T14:54:22.983Z" }, ] [[package]] name = "natsort" version = "8.4.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e2/a9/a0c57aee75f77794adaf35322f8b6404cbd0f89ad45c87197a937764b7d0/natsort-8.4.0.tar.gz", hash = "sha256:45312c4a0e5507593da193dedd04abb1469253b601ecaf63445ad80f0a1ea581", size = 76575 } +sdist = { url = "https://files.pythonhosted.org/packages/e2/a9/a0c57aee75f77794adaf35322f8b6404cbd0f89ad45c87197a937764b7d0/natsort-8.4.0.tar.gz", hash = "sha256:45312c4a0e5507593da193dedd04abb1469253b601ecaf63445ad80f0a1ea581", size = 76575, upload-time = "2023-06-20T04:17:19.925Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ef/82/7a9d0550484a62c6da82858ee9419f3dd1ccc9aa1c26a1e43da3ecd20b0d/natsort-8.4.0-py3-none-any.whl", hash = "sha256:4732914fb471f56b5cce04d7bae6f164a592c7712e1c85f9ef585e197299521c", size = 38268 }, + { url = "https://files.pythonhosted.org/packages/ef/82/7a9d0550484a62c6da82858ee9419f3dd1ccc9aa1c26a1e43da3ecd20b0d/natsort-8.4.0-py3-none-any.whl", hash = "sha256:4732914fb471f56b5cce04d7bae6f164a592c7712e1c85f9ef585e197299521c", size = 38268, upload-time = "2023-06-20T04:17:17.522Z" }, ] [[package]] name = "numpy" -version = "1.26.4" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/65/6e/09db70a523a96d25e115e71cc56a6f9031e7b8cd166c1ac8438307c14058/numpy-1.26.4.tar.gz", hash = "sha256:2a02aba9ed12e4ac4eb3ea9421c420301a0c6460d9830d74a9df87efa4912010", size = 15786129 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/11/57/baae43d14fe163fa0e4c47f307b6b2511ab8d7d30177c491960504252053/numpy-1.26.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4c66707fabe114439db9068ee468c26bbdf909cac0fb58686a42a24de1760c71", size = 20630554 }, - { url = "https://files.pythonhosted.org/packages/1a/2e/151484f49fd03944c4a3ad9c418ed193cfd02724e138ac8a9505d056c582/numpy-1.26.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:edd8b5fe47dab091176d21bb6de568acdd906d1887a4584a15a9a96a1dca06ef", size = 13997127 }, - { url = "https://files.pythonhosted.org/packages/79/ae/7e5b85136806f9dadf4878bf73cf223fe5c2636818ba3ab1c585d0403164/numpy-1.26.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7ab55401287bfec946ced39700c053796e7cc0e3acbef09993a9ad2adba6ca6e", size = 14222994 }, - { url = "https://files.pythonhosted.org/packages/3a/d0/edc009c27b406c4f9cbc79274d6e46d634d139075492ad055e3d68445925/numpy-1.26.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:666dbfb6ec68962c033a450943ded891bed2d54e6755e35e5835d63f4f6931d5", size = 18252005 }, - { url = "https://files.pythonhosted.org/packages/09/bf/2b1aaf8f525f2923ff6cfcf134ae5e750e279ac65ebf386c75a0cf6da06a/numpy-1.26.4-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:96ff0b2ad353d8f990b63294c8986f1ec3cb19d749234014f4e7eb0112ceba5a", size = 13885297 }, - { url = "https://files.pythonhosted.org/packages/df/a0/4e0f14d847cfc2a633a1c8621d00724f3206cfeddeb66d35698c4e2cf3d2/numpy-1.26.4-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:60dedbb91afcbfdc9bc0b1f3f402804070deed7392c23eb7a7f07fa857868e8a", size = 18093567 }, - { url = "https://files.pythonhosted.org/packages/d2/b7/a734c733286e10a7f1a8ad1ae8c90f2d33bf604a96548e0a4a3a6739b468/numpy-1.26.4-cp311-cp311-win32.whl", hash = "sha256:1af303d6b2210eb850fcf03064d364652b7120803a0b872f5211f5234b399f20", size = 5968812 }, - { url = "https://files.pythonhosted.org/packages/3f/6b/5610004206cf7f8e7ad91c5a85a8c71b2f2f8051a0c0c4d5916b76d6cbb2/numpy-1.26.4-cp311-cp311-win_amd64.whl", hash = "sha256:cd25bcecc4974d09257ffcd1f098ee778f7834c3ad767fe5db785be9a4aa9cb2", size = 15811913 }, - { url = "https://files.pythonhosted.org/packages/95/12/8f2020a8e8b8383ac0177dc9570aad031a3beb12e38847f7129bacd96228/numpy-1.26.4-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b3ce300f3644fb06443ee2222c2201dd3a89ea6040541412b8fa189341847218", size = 20335901 }, - { url = "https://files.pythonhosted.org/packages/75/5b/ca6c8bd14007e5ca171c7c03102d17b4f4e0ceb53957e8c44343a9546dcc/numpy-1.26.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:03a8c78d01d9781b28a6989f6fa1bb2c4f2d51201cf99d3dd875df6fbd96b23b", size = 13685868 }, - { url = "https://files.pythonhosted.org/packages/79/f8/97f10e6755e2a7d027ca783f63044d5b1bc1ae7acb12afe6a9b4286eac17/numpy-1.26.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9fad7dcb1aac3c7f0584a5a8133e3a43eeb2fe127f47e3632d43d677c66c102b", size = 13925109 }, - { url = "https://files.pythonhosted.org/packages/0f/50/de23fde84e45f5c4fda2488c759b69990fd4512387a8632860f3ac9cd225/numpy-1.26.4-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:675d61ffbfa78604709862923189bad94014bef562cc35cf61d3a07bba02a7ed", size = 17950613 }, - { url = "https://files.pythonhosted.org/packages/4c/0c/9c603826b6465e82591e05ca230dfc13376da512b25ccd0894709b054ed0/numpy-1.26.4-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:ab47dbe5cc8210f55aa58e4805fe224dac469cde56b9f731a4c098b91917159a", size = 13572172 }, - { url = "https://files.pythonhosted.org/packages/76/8c/2ba3902e1a0fc1c74962ea9bb33a534bb05984ad7ff9515bf8d07527cadd/numpy-1.26.4-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:1dda2e7b4ec9dd512f84935c5f126c8bd8b9f2fc001e9f54af255e8c5f16b0e0", size = 17786643 }, - { url = "https://files.pythonhosted.org/packages/28/4a/46d9e65106879492374999e76eb85f87b15328e06bd1550668f79f7b18c6/numpy-1.26.4-cp312-cp312-win32.whl", hash = "sha256:50193e430acfc1346175fcbdaa28ffec49947a06918b7b92130744e81e640110", size = 5677803 }, - { url = "https://files.pythonhosted.org/packages/16/2e/86f24451c2d530c88daf997cb8d6ac622c1d40d19f5a031ed68a4b73a374/numpy-1.26.4-cp312-cp312-win_amd64.whl", hash = "sha256:08beddf13648eb95f8d867350f6a018a4be2e5ad54c8d8caed89ebca558b2818", size = 15517754 }, +version = "2.1.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/25/ca/1166b75c21abd1da445b97bf1fa2f14f423c6cfb4fc7c4ef31dccf9f6a94/numpy-2.1.3.tar.gz", hash = "sha256:aa08e04e08aaf974d4458def539dece0d28146d866a39da5639596f4921fd761", size = 20166090, upload-time = "2024-11-02T17:48:55.832Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ad/81/c8167192eba5247593cd9d305ac236847c2912ff39e11402e72ae28a4985/numpy-2.1.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4d1167c53b93f1f5d8a139a742b3c6f4d429b54e74e6b57d0eff40045187b15d", size = 21156252, upload-time = "2024-11-02T17:34:01.372Z" }, + { url = "https://files.pythonhosted.org/packages/da/74/5a60003fc3d8a718d830b08b654d0eea2d2db0806bab8f3c2aca7e18e010/numpy-2.1.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c80e4a09b3d95b4e1cac08643f1152fa71a0a821a2d4277334c88d54b2219a41", size = 13784119, upload-time = "2024-11-02T17:34:23.809Z" }, + { url = "https://files.pythonhosted.org/packages/47/7c/864cb966b96fce5e63fcf25e1e4d957fe5725a635e5f11fe03f39dd9d6b5/numpy-2.1.3-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:576a1c1d25e9e02ed7fa5477f30a127fe56debd53b8d2c89d5578f9857d03ca9", size = 5352978, upload-time = "2024-11-02T17:34:34.001Z" }, + { url = "https://files.pythonhosted.org/packages/09/ac/61d07930a4993dd9691a6432de16d93bbe6aa4b1c12a5e573d468eefc1ca/numpy-2.1.3-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:973faafebaae4c0aaa1a1ca1ce02434554d67e628b8d805e61f874b84e136b09", size = 6892570, upload-time = "2024-11-02T17:34:45.401Z" }, + { url = "https://files.pythonhosted.org/packages/27/2f/21b94664f23af2bb52030653697c685022119e0dc93d6097c3cb45bce5f9/numpy-2.1.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:762479be47a4863e261a840e8e01608d124ee1361e48b96916f38b119cfda04a", size = 13896715, upload-time = "2024-11-02T17:35:06.564Z" }, + { url = "https://files.pythonhosted.org/packages/7a/f0/80811e836484262b236c684a75dfc4ba0424bc670e765afaa911468d9f39/numpy-2.1.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bc6f24b3d1ecc1eebfbf5d6051faa49af40b03be1aaa781ebdadcbc090b4539b", size = 16339644, upload-time = "2024-11-02T17:35:30.888Z" }, + { url = "https://files.pythonhosted.org/packages/fa/81/ce213159a1ed8eb7d88a2a6ef4fbdb9e4ffd0c76b866c350eb4e3c37e640/numpy-2.1.3-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:17ee83a1f4fef3c94d16dc1802b998668b5419362c8a4f4e8a491de1b41cc3ee", size = 16712217, upload-time = "2024-11-02T17:35:56.703Z" }, + { url = "https://files.pythonhosted.org/packages/7d/84/4de0b87d5a72f45556b2a8ee9fc8801e8518ec867fc68260c1f5dcb3903f/numpy-2.1.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:15cb89f39fa6d0bdfb600ea24b250e5f1a3df23f901f51c8debaa6a5d122b2f0", size = 14399053, upload-time = "2024-11-02T17:36:22.3Z" }, + { url = "https://files.pythonhosted.org/packages/7e/1c/e5fabb9ad849f9d798b44458fd12a318d27592d4bc1448e269dec070ff04/numpy-2.1.3-cp311-cp311-win32.whl", hash = "sha256:d9beb777a78c331580705326d2367488d5bc473b49a9bc3036c154832520aca9", size = 6534741, upload-time = "2024-11-02T17:36:33.552Z" }, + { url = "https://files.pythonhosted.org/packages/1e/48/a9a4b538e28f854bfb62e1dea3c8fea12e90216a276c7777ae5345ff29a7/numpy-2.1.3-cp311-cp311-win_amd64.whl", hash = "sha256:d89dd2b6da69c4fff5e39c28a382199ddedc3a5be5390115608345dec660b9e2", size = 12869487, upload-time = "2024-11-02T17:36:52.909Z" }, + { url = "https://files.pythonhosted.org/packages/8a/f0/385eb9970309643cbca4fc6eebc8bb16e560de129c91258dfaa18498da8b/numpy-2.1.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f55ba01150f52b1027829b50d70ef1dafd9821ea82905b63936668403c3b471e", size = 20849658, upload-time = "2024-11-02T17:37:23.919Z" }, + { url = "https://files.pythonhosted.org/packages/54/4a/765b4607f0fecbb239638d610d04ec0a0ded9b4951c56dc68cef79026abf/numpy-2.1.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:13138eadd4f4da03074851a698ffa7e405f41a0845a6b1ad135b81596e4e9958", size = 13492258, upload-time = "2024-11-02T17:37:45.252Z" }, + { url = "https://files.pythonhosted.org/packages/bd/a7/2332679479c70b68dccbf4a8eb9c9b5ee383164b161bee9284ac141fbd33/numpy-2.1.3-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:a6b46587b14b888e95e4a24d7b13ae91fa22386c199ee7b418f449032b2fa3b8", size = 5090249, upload-time = "2024-11-02T17:37:54.252Z" }, + { url = "https://files.pythonhosted.org/packages/c1/67/4aa00316b3b981a822c7a239d3a8135be2a6945d1fd11d0efb25d361711a/numpy-2.1.3-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:0fa14563cc46422e99daef53d725d0c326e99e468a9320a240affffe87852564", size = 6621704, upload-time = "2024-11-02T17:38:05.127Z" }, + { url = "https://files.pythonhosted.org/packages/5e/da/1a429ae58b3b6c364eeec93bf044c532f2ff7b48a52e41050896cf15d5b1/numpy-2.1.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8637dcd2caa676e475503d1f8fdb327bc495554e10838019651b76d17b98e512", size = 13606089, upload-time = "2024-11-02T17:38:25.997Z" }, + { url = "https://files.pythonhosted.org/packages/9e/3e/3757f304c704f2f0294a6b8340fcf2be244038be07da4cccf390fa678a9f/numpy-2.1.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2312b2aa89e1f43ecea6da6ea9a810d06aae08321609d8dc0d0eda6d946a541b", size = 16043185, upload-time = "2024-11-02T17:38:51.07Z" }, + { url = "https://files.pythonhosted.org/packages/43/97/75329c28fea3113d00c8d2daf9bc5828d58d78ed661d8e05e234f86f0f6d/numpy-2.1.3-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:a38c19106902bb19351b83802531fea19dee18e5b37b36454f27f11ff956f7fc", size = 16410751, upload-time = "2024-11-02T17:39:15.801Z" }, + { url = "https://files.pythonhosted.org/packages/ad/7a/442965e98b34e0ae9da319f075b387bcb9a1e0658276cc63adb8c9686f7b/numpy-2.1.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:02135ade8b8a84011cbb67dc44e07c58f28575cf9ecf8ab304e51c05528c19f0", size = 14082705, upload-time = "2024-11-02T17:39:38.274Z" }, + { url = "https://files.pythonhosted.org/packages/ac/b6/26108cf2cfa5c7e03fb969b595c93131eab4a399762b51ce9ebec2332e80/numpy-2.1.3-cp312-cp312-win32.whl", hash = "sha256:e6988e90fcf617da2b5c78902fe8e668361b43b4fe26dbf2d7b0f8034d4cafb9", size = 6239077, upload-time = "2024-11-02T17:39:49.299Z" }, + { url = "https://files.pythonhosted.org/packages/a6/84/fa11dad3404b7634aaab50733581ce11e5350383311ea7a7010f464c0170/numpy-2.1.3-cp312-cp312-win_amd64.whl", hash = "sha256:0d30c543f02e84e92c4b1f415b7c6b5326cbe45ee7882b6b77db7195fb971e3a", size = 12566858, upload-time = "2024-11-02T17:40:08.851Z" }, ] [[package]] name = "onnx" -version = "1.17.0" +version = "1.18.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "numpy" }, { name = "protobuf" }, + { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9a/54/0e385c26bf230d223810a9c7d06628d954008a5e5e4b73ee26ef02327282/onnx-1.17.0.tar.gz", hash = "sha256:48ca1a91ff73c1d5e3ea2eef20ae5d0e709bb8a2355ed798ffc2169753013fd3", size = 12165120 } +sdist = { url = "https://files.pythonhosted.org/packages/3d/60/e56e8ec44ed34006e6d4a73c92a04d9eea6163cc12440e35045aec069175/onnx-1.18.0.tar.gz", hash = "sha256:3d8dbf9e996629131ba3aa1afd1d8239b660d1f830c6688dd7e03157cccd6b9c", size = 12563009, upload-time = "2025-05-12T22:03:09.626Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e5/a9/8d1b1d53aec70df53e0f57e9f9fcf47004276539e29230c3d5f1f50719ba/onnx-1.17.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:d6fc3a03fc0129b8b6ac03f03bc894431ffd77c7d79ec023d0afd667b4d35869", size = 16647991 }, - { url = "https://files.pythonhosted.org/packages/7b/e3/cc80110e5996ca61878f7b4c73c7a286cd88918ff35eacb60dc75ab11ef5/onnx-1.17.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f01a4b63d4e1d8ec3e2f069e7b798b2955810aa434f7361f01bc8ca08d69cce4", size = 15908949 }, - { url = "https://files.pythonhosted.org/packages/b1/2f/91092557ed478e323a2b4471e2081fdf88d1dd52ae988ceaf7db4e4506ff/onnx-1.17.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4a183c6178be001bf398260e5ac2c927dc43e7746e8638d6c05c20e321f8c949", size = 16048190 }, - { url = "https://files.pythonhosted.org/packages/ac/59/9ea23fc22d0bb853133f363e6248e31bcbc6c1c90543a3938c00412ac02a/onnx-1.17.0-cp311-cp311-win32.whl", hash = "sha256:081ec43a8b950171767d99075b6b92553901fa429d4bc5eb3ad66b36ef5dbe3a", size = 14424299 }, - { url = "https://files.pythonhosted.org/packages/51/a5/19b0dfcb567b62e7adf1a21b08b23224f0c2d13842aee4d0abc6f07f9cf5/onnx-1.17.0-cp311-cp311-win_amd64.whl", hash = "sha256:95c03e38671785036bb704c30cd2e150825f6ab4763df3a4f1d249da48525957", size = 14529142 }, - { url = "https://files.pythonhosted.org/packages/b4/dd/c416a11a28847fafb0db1bf43381979a0f522eb9107b831058fde012dd56/onnx-1.17.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:0e906e6a83437de05f8139ea7eaf366bf287f44ae5cc44b2850a30e296421f2f", size = 16651271 }, - { url = "https://files.pythonhosted.org/packages/f0/6c/f040652277f514ecd81b7251841f96caa5538365af7df07f86c6018cda2b/onnx-1.17.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3d955ba2939878a520a97614bcf2e79c1df71b29203e8ced478fa78c9a9c63c2", size = 15907522 }, - { url = "https://files.pythonhosted.org/packages/3d/7c/67f4952d1b56b3f74a154b97d0dd0630d525923b354db117d04823b8b49b/onnx-1.17.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4f3fb5cc4e2898ac5312a7dc03a65133dd2abf9a5e520e69afb880a7251ec97a", size = 16046307 }, - { url = "https://files.pythonhosted.org/packages/ae/20/6da11042d2ab870dfb4ce4a6b52354d7651b6b4112038b6d2229ab9904c4/onnx-1.17.0-cp312-cp312-win32.whl", hash = "sha256:317870fca3349d19325a4b7d1b5628f6de3811e9710b1e3665c68b073d0e68d7", size = 14424235 }, - { url = "https://files.pythonhosted.org/packages/35/55/c4d11bee1fdb0c4bd84b4e3562ff811a19b63266816870ae1f95567aa6e1/onnx-1.17.0-cp312-cp312-win_amd64.whl", hash = "sha256:659b8232d627a5460d74fd3c96947ae83db6d03f035ac633e20cd69cfa029227", size = 14530453 }, + { url = "https://files.pythonhosted.org/packages/ed/3a/a336dac4db1eddba2bf577191e5b7d3e4c26fcee5ec518a5a5b11d13540d/onnx-1.18.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:735e06d8d0cf250dc498f54038831401063c655a8d6e5975b2527a4e7d24be3e", size = 18281831, upload-time = "2025-05-12T22:02:06.429Z" }, + { url = "https://files.pythonhosted.org/packages/02/3a/56475a111120d1e5d11939acbcbb17c92198c8e64a205cd68e00bdfd8a1f/onnx-1.18.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73160799472e1a86083f786fecdf864cf43d55325492a9b5a1cfa64d8a523ecc", size = 17424359, upload-time = "2025-05-12T22:02:09.866Z" }, + { url = "https://files.pythonhosted.org/packages/cf/03/5eb5e9ef446ed9e78c4627faf3c1bc25e0f707116dd00e9811de232a8df5/onnx-1.18.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6acafb3823238bbe8f4340c7ac32fb218689442e074d797bee1c5c9a02fdae75", size = 17586006, upload-time = "2025-05-12T22:02:13.217Z" }, + { url = "https://files.pythonhosted.org/packages/b0/4e/70943125729ce453271a6e46bb847b4a612496f64db6cbc6cb1f49f41ce1/onnx-1.18.0-cp311-cp311-win32.whl", hash = "sha256:4c8c4bbda760c654e65eaffddb1a7de71ec02e60092d33f9000521f897c99be9", size = 15734988, upload-time = "2025-05-12T22:02:16.561Z" }, + { url = "https://files.pythonhosted.org/packages/44/b0/435fd764011911e8f599e3361f0f33425b1004662c1ea33a0ad22e43db2d/onnx-1.18.0-cp311-cp311-win_amd64.whl", hash = "sha256:a5810194f0f6be2e58c8d6dedc6119510df7a14280dd07ed5f0f0a85bd74816a", size = 15849576, upload-time = "2025-05-12T22:02:19.569Z" }, + { url = "https://files.pythonhosted.org/packages/6c/f0/9e31f4b4626d60f1c034f71b411810bc9fafe31f4e7dd3598effd1b50e05/onnx-1.18.0-cp311-cp311-win_arm64.whl", hash = "sha256:aa1b7483fac6cdec26922174fc4433f8f5c2f239b1133c5625063bb3b35957d0", size = 15822961, upload-time = "2025-05-12T22:02:22.735Z" }, + { url = "https://files.pythonhosted.org/packages/a7/fe/16228aca685392a7114625b89aae98b2dc4058a47f0f467a376745efe8d0/onnx-1.18.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:521bac578448667cbb37c50bf05b53c301243ede8233029555239930996a625b", size = 18285770, upload-time = "2025-05-12T22:02:26.116Z" }, + { url = "https://files.pythonhosted.org/packages/1e/77/ba50a903a9b5e6f9be0fa50f59eb2fca4a26ee653375408fbc72c3acbf9f/onnx-1.18.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e4da451bf1c5ae381f32d430004a89f0405bc57a8471b0bddb6325a5b334aa40", size = 17421291, upload-time = "2025-05-12T22:02:29.645Z" }, + { url = "https://files.pythonhosted.org/packages/11/23/25ec2ba723ac62b99e8fed6d7b59094dadb15e38d4c007331cc9ae3dfa5f/onnx-1.18.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:99afac90b4cdb1471432203c3c1f74e16549c526df27056d39f41a9a47cfb4af", size = 17584084, upload-time = "2025-05-12T22:02:32.789Z" }, + { url = "https://files.pythonhosted.org/packages/6a/4d/2c253a36070fb43f340ff1d2c450df6a9ef50b938adcd105693fee43c4ee/onnx-1.18.0-cp312-cp312-win32.whl", hash = "sha256:ee159b41a3ae58d9c7341cf432fc74b96aaf50bd7bb1160029f657b40dc69715", size = 15734892, upload-time = "2025-05-12T22:02:35.527Z" }, + { url = "https://files.pythonhosted.org/packages/e8/92/048ba8fafe6b2b9a268ec2fb80def7e66c0b32ab2cae74de886981f05a27/onnx-1.18.0-cp312-cp312-win_amd64.whl", hash = "sha256:102c04edc76b16e9dfeda5a64c1fccd7d3d2913b1544750c01d38f1ac3c04e05", size = 15850336, upload-time = "2025-05-12T22:02:38.545Z" }, + { url = "https://files.pythonhosted.org/packages/a1/66/bbc4ffedd44165dcc407a51ea4c592802a5391ce3dc94aa5045350f64635/onnx-1.18.0-cp312-cp312-win_arm64.whl", hash = "sha256:911b37d724a5d97396f3c2ef9ea25361c55cbc9aa18d75b12a52b620b67145af", size = 15823802, upload-time = "2025-05-12T22:02:42.037Z" }, ] [[package]] @@ -1221,16 +1245,16 @@ name = "opencv-python-headless" version = "4.11.0.86" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "numpy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/36/2f/5b2b3ba52c864848885ba988f24b7f105052f68da9ab0e693cc7c25b0b30/opencv-python-headless-4.11.0.86.tar.gz", hash = "sha256:996eb282ca4b43ec6a3972414de0e2331f5d9cda2b41091a49739c19fb843798", size = 95177929 } +sdist = { url = "https://files.pythonhosted.org/packages/36/2f/5b2b3ba52c864848885ba988f24b7f105052f68da9ab0e693cc7c25b0b30/opencv-python-headless-4.11.0.86.tar.gz", hash = "sha256:996eb282ca4b43ec6a3972414de0e2331f5d9cda2b41091a49739c19fb843798", size = 95177929, upload-time = "2025-01-16T13:53:40.22Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/dc/53/2c50afa0b1e05ecdb4603818e85f7d174e683d874ef63a6abe3ac92220c8/opencv_python_headless-4.11.0.86-cp37-abi3-macosx_13_0_arm64.whl", hash = "sha256:48128188ade4a7e517237c8e1e11a9cdf5c282761473383e77beb875bb1e61ca", size = 37326460 }, - { url = "https://files.pythonhosted.org/packages/3b/43/68555327df94bb9b59a1fd645f63fafb0762515344d2046698762fc19d58/opencv_python_headless-4.11.0.86-cp37-abi3-macosx_13_0_x86_64.whl", hash = "sha256:a66c1b286a9de872c343ee7c3553b084244299714ebb50fbdcd76f07ebbe6c81", size = 56723330 }, - { url = "https://files.pythonhosted.org/packages/45/be/1438ce43ebe65317344a87e4b150865c5585f4c0db880a34cdae5ac46881/opencv_python_headless-4.11.0.86-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6efabcaa9df731f29e5ea9051776715b1bdd1845d7c9530065c7951d2a2899eb", size = 29487060 }, - { url = "https://files.pythonhosted.org/packages/dd/5c/c139a7876099916879609372bfa513b7f1257f7f1a908b0bdc1c2328241b/opencv_python_headless-4.11.0.86-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e0a27c19dd1f40ddff94976cfe43066fbbe9dfbb2ec1907d66c19caef42a57b", size = 49969856 }, - { url = "https://files.pythonhosted.org/packages/95/dd/ed1191c9dc91abcc9f752b499b7928aacabf10567bb2c2535944d848af18/opencv_python_headless-4.11.0.86-cp37-abi3-win32.whl", hash = "sha256:f447d8acbb0b6f2808da71fddd29c1cdd448d2bc98f72d9bb78a7a898fc9621b", size = 29324425 }, - { url = "https://files.pythonhosted.org/packages/86/8a/69176a64335aed183529207ba8bc3d329c2999d852b4f3818027203f50e6/opencv_python_headless-4.11.0.86-cp37-abi3-win_amd64.whl", hash = "sha256:6c304df9caa7a6a5710b91709dd4786bf20a74d57672b3c31f7033cc638174ca", size = 39402386 }, + { url = "https://files.pythonhosted.org/packages/dc/53/2c50afa0b1e05ecdb4603818e85f7d174e683d874ef63a6abe3ac92220c8/opencv_python_headless-4.11.0.86-cp37-abi3-macosx_13_0_arm64.whl", hash = "sha256:48128188ade4a7e517237c8e1e11a9cdf5c282761473383e77beb875bb1e61ca", size = 37326460, upload-time = "2025-01-16T13:52:57.015Z" }, + { url = "https://files.pythonhosted.org/packages/3b/43/68555327df94bb9b59a1fd645f63fafb0762515344d2046698762fc19d58/opencv_python_headless-4.11.0.86-cp37-abi3-macosx_13_0_x86_64.whl", hash = "sha256:a66c1b286a9de872c343ee7c3553b084244299714ebb50fbdcd76f07ebbe6c81", size = 56723330, upload-time = "2025-01-16T13:55:45.731Z" }, + { url = "https://files.pythonhosted.org/packages/45/be/1438ce43ebe65317344a87e4b150865c5585f4c0db880a34cdae5ac46881/opencv_python_headless-4.11.0.86-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6efabcaa9df731f29e5ea9051776715b1bdd1845d7c9530065c7951d2a2899eb", size = 29487060, upload-time = "2025-01-16T13:51:59.625Z" }, + { url = "https://files.pythonhosted.org/packages/dd/5c/c139a7876099916879609372bfa513b7f1257f7f1a908b0bdc1c2328241b/opencv_python_headless-4.11.0.86-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e0a27c19dd1f40ddff94976cfe43066fbbe9dfbb2ec1907d66c19caef42a57b", size = 49969856, upload-time = "2025-01-16T13:53:29.654Z" }, + { url = "https://files.pythonhosted.org/packages/95/dd/ed1191c9dc91abcc9f752b499b7928aacabf10567bb2c2535944d848af18/opencv_python_headless-4.11.0.86-cp37-abi3-win32.whl", hash = "sha256:f447d8acbb0b6f2808da71fddd29c1cdd448d2bc98f72d9bb78a7a898fc9621b", size = 29324425, upload-time = "2025-01-16T13:52:49.048Z" }, + { url = "https://files.pythonhosted.org/packages/86/8a/69176a64335aed183529207ba8bc3d329c2999d852b4f3818027203f50e6/opencv_python_headless-4.11.0.86-cp37-abi3-win_amd64.whl", hash = "sha256:6c304df9caa7a6a5710b91709dd4786bf20a74d57672b3c31f7033cc638174ca", size = 39402386, upload-time = "2025-01-16T13:52:56.418Z" }, ] [[package]] @@ -1270,6 +1294,7 @@ dependencies = [ { name = "sympy" }, { name = "tqdm" }, { name = "websocket-client" }, + { name = "xattr" }, { name = "zstandard" }, ] @@ -1350,7 +1375,7 @@ requires-dist = [ { name = "mkdocs", marker = "extra == 'docs'" }, { name = "mypy", marker = "extra == 'testing'" }, { name = "natsort", marker = "extra == 'docs'" }, - { name = "numpy", specifier = "<2.0.0" }, + { name = "numpy", specifier = ">=2.0,<2.2" }, { name = "onnx", specifier = ">=1.14.0" }, { name = "parameterized", marker = "extra == 'dev'", specifier = ">=0.8,<0.9" }, { name = "pre-commit-hooks", marker = "extra == 'testing'" }, @@ -1395,17 +1420,18 @@ requires-dist = [ { name = "types-requests", marker = "extra == 'dev'" }, { name = "types-tabulate", marker = "extra == 'dev'" }, { name = "websocket-client" }, + { name = "xattr" }, { name = "zstandard" }, ] provides-extras = ["docs", "testing", "dev", "tools"] [[package]] name = "packaging" -version = "24.2" +version = "25.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d0/63/68dbb6eb2de9cb10ee4c9c14a0148804425e13c4fb20d61cce69f53106da/packaging-24.2.tar.gz", hash = "sha256:c228a6dc5e932d346bc5739379109d49e8853dd8223571c7c5b55260edc0b97f", size = 163950 } +sdist = { url = "https://files.pythonhosted.org/packages/a1/d4/1fc4078c65507b51b96ca8f8c3ba19e6a61c8253c72794544580a7b6c24d/packaging-25.0.tar.gz", hash = "sha256:d443872c98d677bf60f6a1f2f8c1cb748e8fe762d2bf9d3148b5599295b0fc4f", size = 165727, upload-time = "2025-04-19T11:48:59.673Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/88/ef/eb23f262cca3c0c4eb7ab1933c3b1f03d021f2c48f54763065b6f0e321be/packaging-24.2-py3-none-any.whl", hash = "sha256:09abb1bccd265c01f4a3aa3f7a7db064b36514d2cba19a2f694fe6150451a759", size = 65451 }, + { url = "https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl", hash = "sha256:29572ef2b1f17581046b3a2227d5c611fb25ec70ca1ba8554b24b0e69331a484", size = 66469, upload-time = "2025-04-19T11:48:57.875Z" }, ] [[package]] @@ -1413,17 +1439,17 @@ name = "panda3d" version = "1.10.14" source = { registry = "https://pypi.org/simple" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f5/9a/31d07e3d7c1b40335e8418c540d63f4d33c571648ed8d69896ab778e65c3/panda3d-1.10.14-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:54b8ef9fe3684960a2c7d47b0d63c0354c17bc516795e59db6c1e5bda8c16c1c", size = 67700752 }, - { url = "https://files.pythonhosted.org/packages/61/05/fce327535d8907ac01f43813c980f30ea86d37db62c340847519ea2ab222/panda3d-1.10.14-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:93414675894b18eea8d27edc1bbd1dc719eae207d45ec263d47195504bc4705f", size = 118966179 }, - { url = "https://files.pythonhosted.org/packages/8a/54/24e205231e7b1bced58ba9620fbec7114673d821fc7ad9ed1804cab556b4/panda3d-1.10.14-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:d1bc0d926f90c8fa14a1587fa9dbe5f89a4eda8c9684fa183a8eaa35fc8e891a", size = 55145295 }, - { url = "https://files.pythonhosted.org/packages/06/d3/38e989822292935d7473d35117099f71481cc6b104cb2dd048cb8058a5a8/panda3d-1.10.14-cp311-cp311-win32.whl", hash = "sha256:1039340a4a7965fe4c3e904edb4fff691584df435a154fecccf534587cd07a34", size = 53137177 }, - { url = "https://files.pythonhosted.org/packages/5c/32/b16c81661ed0d8ad62976004d81845baa321e53314e253ef0841155be770/panda3d-1.10.14-cp311-cp311-win_amd64.whl", hash = "sha256:1ddf01040b9c5497fb8659e3c5ef793a26c869cfdfb1b75e6d04d6fba0c03b73", size = 64447666 }, - { url = "https://files.pythonhosted.org/packages/5a/d4/90e98993b1a3f3c9fae83267f8c51186e676a8c1365c4180dfc65cd7ba62/panda3d-1.10.14-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:1bfbcee77779f12ecce6a3d5a856e573b25d6343f8c4b107e814d9702e70a65d", size = 67839196 }, - { url = "https://files.pythonhosted.org/packages/dc/e5/862821575073863ce49cc57b8349b47cb25ce11feae0e419b3d023ac1a69/panda3d-1.10.14-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:bc6540c5559d7e14a8992eff7de0157b7c42406b7ba221941ed224289496841c", size = 119271341 }, - { url = "https://files.pythonhosted.org/packages/f4/20/f16d91805777825e530037177d9075c83da7384f12b778b133e3164a31f3/panda3d-1.10.14-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:143daab1ce6bedcba711ea3f6cab0ebe5082f22c5f43e7178fadd2dd01209da7", size = 47604077 }, - { url = "https://files.pythonhosted.org/packages/11/69/806dcdbaee3e8deee1956abeea0d3d3e504315d2e9814de82a44809a8617/panda3d-1.10.14-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:3c4399a286a142de7ff86f9356d7e526bbbd38892d7f7d39fecb5c33064972bc", size = 55539594 }, - { url = "https://files.pythonhosted.org/packages/ad/25/005de5e2b6d0acd546f8b3f2b547cd29e308cdd04a397f0ea68046e26571/panda3d-1.10.14-cp312-cp312-win32.whl", hash = "sha256:e92e0dd907e2af33085a2c31ca2263dc8023b1b7bc70ce1b9fbc84631e130e51", size = 53479813 }, - { url = "https://files.pythonhosted.org/packages/74/bb/cb57563855da994614a33f57bd5691fbcd69f12e5ccddd30d387d0be287f/panda3d-1.10.14-cp312-cp312-win_amd64.whl", hash = "sha256:a5f2defd822d38848f8ae1956115adcb6cc7f464f03a67e73681cc72df125ef4", size = 64893222 }, + { url = "https://files.pythonhosted.org/packages/f5/9a/31d07e3d7c1b40335e8418c540d63f4d33c571648ed8d69896ab778e65c3/panda3d-1.10.14-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:54b8ef9fe3684960a2c7d47b0d63c0354c17bc516795e59db6c1e5bda8c16c1c", size = 67700752, upload-time = "2024-01-08T19:05:55.559Z" }, + { url = "https://files.pythonhosted.org/packages/61/05/fce327535d8907ac01f43813c980f30ea86d37db62c340847519ea2ab222/panda3d-1.10.14-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:93414675894b18eea8d27edc1bbd1dc719eae207d45ec263d47195504bc4705f", size = 118966179, upload-time = "2024-01-08T19:06:03.165Z" }, + { url = "https://files.pythonhosted.org/packages/8a/54/24e205231e7b1bced58ba9620fbec7114673d821fc7ad9ed1804cab556b4/panda3d-1.10.14-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:d1bc0d926f90c8fa14a1587fa9dbe5f89a4eda8c9684fa183a8eaa35fc8e891a", size = 55145295, upload-time = "2024-01-08T19:06:10.319Z" }, + { url = "https://files.pythonhosted.org/packages/06/d3/38e989822292935d7473d35117099f71481cc6b104cb2dd048cb8058a5a8/panda3d-1.10.14-cp311-cp311-win32.whl", hash = "sha256:1039340a4a7965fe4c3e904edb4fff691584df435a154fecccf534587cd07a34", size = 53137177, upload-time = "2024-01-08T19:06:15.901Z" }, + { url = "https://files.pythonhosted.org/packages/5c/32/b16c81661ed0d8ad62976004d81845baa321e53314e253ef0841155be770/panda3d-1.10.14-cp311-cp311-win_amd64.whl", hash = "sha256:1ddf01040b9c5497fb8659e3c5ef793a26c869cfdfb1b75e6d04d6fba0c03b73", size = 64447666, upload-time = "2024-01-08T19:06:22.105Z" }, + { url = "https://files.pythonhosted.org/packages/5a/d4/90e98993b1a3f3c9fae83267f8c51186e676a8c1365c4180dfc65cd7ba62/panda3d-1.10.14-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:1bfbcee77779f12ecce6a3d5a856e573b25d6343f8c4b107e814d9702e70a65d", size = 67839196, upload-time = "2024-01-08T19:01:00.417Z" }, + { url = "https://files.pythonhosted.org/packages/dc/e5/862821575073863ce49cc57b8349b47cb25ce11feae0e419b3d023ac1a69/panda3d-1.10.14-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:bc6540c5559d7e14a8992eff7de0157b7c42406b7ba221941ed224289496841c", size = 119271341, upload-time = "2024-01-08T19:01:09.455Z" }, + { url = "https://files.pythonhosted.org/packages/f4/20/f16d91805777825e530037177d9075c83da7384f12b778b133e3164a31f3/panda3d-1.10.14-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:143daab1ce6bedcba711ea3f6cab0ebe5082f22c5f43e7178fadd2dd01209da7", size = 47604077, upload-time = "2024-05-28T20:25:37.118Z" }, + { url = "https://files.pythonhosted.org/packages/11/69/806dcdbaee3e8deee1956abeea0d3d3e504315d2e9814de82a44809a8617/panda3d-1.10.14-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:3c4399a286a142de7ff86f9356d7e526bbbd38892d7f7d39fecb5c33064972bc", size = 55539594, upload-time = "2024-01-08T19:01:15.979Z" }, + { url = "https://files.pythonhosted.org/packages/ad/25/005de5e2b6d0acd546f8b3f2b547cd29e308cdd04a397f0ea68046e26571/panda3d-1.10.14-cp312-cp312-win32.whl", hash = "sha256:e92e0dd907e2af33085a2c31ca2263dc8023b1b7bc70ce1b9fbc84631e130e51", size = 53479813, upload-time = "2024-01-08T19:01:20.923Z" }, + { url = "https://files.pythonhosted.org/packages/74/bb/cb57563855da994614a33f57bd5691fbcd69f12e5ccddd30d387d0be287f/panda3d-1.10.14-cp312-cp312-win_amd64.whl", hash = "sha256:a5f2defd822d38848f8ae1956115adcb6cc7f464f03a67e73681cc72df125ef4", size = 64893222, upload-time = "2024-01-08T19:01:26.347Z" }, ] [[package]] @@ -1431,103 +1457,98 @@ name = "panda3d-gltf" version = "0.13" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "panda3d", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "panda3d-simplepbr", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "panda3d" }, + { name = "panda3d-simplepbr" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/07/7f/9f18fc3fa843a080acb891af6bcc12262e7bdf1d194a530f7042bebfc81f/panda3d-gltf-0.13.tar.gz", hash = "sha256:d06d373bdd91cf530909b669f43080e599463bbf6d3ef00c3558bad6c6b19675", size = 25573 } +sdist = { url = "https://files.pythonhosted.org/packages/07/7f/9f18fc3fa843a080acb891af6bcc12262e7bdf1d194a530f7042bebfc81f/panda3d-gltf-0.13.tar.gz", hash = "sha256:d06d373bdd91cf530909b669f43080e599463bbf6d3ef00c3558bad6c6b19675", size = 25573, upload-time = "2021-05-21T05:46:32.738Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/70/94/98ed1f81ca0f5daf6de80533805cc1e98ac162abe4e3e1d382caa7ba5c3c/panda3d_gltf-0.13-py3-none-any.whl", hash = "sha256:02d1a980f447bb1895ff4b48c667f289ba78f07a28ef308d8839b665a621efe2", size = 25568 }, + { url = "https://files.pythonhosted.org/packages/70/94/98ed1f81ca0f5daf6de80533805cc1e98ac162abe4e3e1d382caa7ba5c3c/panda3d_gltf-0.13-py3-none-any.whl", hash = "sha256:02d1a980f447bb1895ff4b48c667f289ba78f07a28ef308d8839b665a621efe2", size = 25568, upload-time = "2021-05-21T05:46:31.28Z" }, ] [[package]] name = "panda3d-simplepbr" -version = "0.12.0" +version = "0.13.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "panda3d", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "typing-extensions", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "panda3d" }, + { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b1/af/505608eef09d7f9b822e69dc7631cd14102650b8fe1b6f60d9562d2788d9/panda3d-simplepbr-0.12.0.tar.gz", hash = "sha256:c71d490afeeb3a90455dcfde1d30c41f321a38742a97d18834e5c31016331ed5", size = 1929980 } +sdist = { url = "https://files.pythonhosted.org/packages/0d/be/c4d1ded04c22b357277cf6e6a44c1ab4abb285a700bd1991460460e05b99/panda3d_simplepbr-0.13.1.tar.gz", hash = "sha256:c83766d7c8f47499f365a07fe1dff078fc8b3054c2689bdc8dceabddfe7f1a35", size = 6216055, upload-time = "2025-03-30T16:57:41.087Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/46/4c/926e1cf17abfb1d91e12bf38e653cacf10e30c5030e37f9078f0f41aaf40/panda3d_simplepbr-0.12.0-py3-none-any.whl", hash = "sha256:6c43d1990ff07840cf1c557561d6122fd1250d8e76aacf227b61c3789149bcf9", size = 2458121 }, + { url = "https://files.pythonhosted.org/packages/11/5d/3744c6550dddf933785a37cdd4a9921fe13284e6d115b5a2637fe390f158/panda3d_simplepbr-0.13.1-py3-none-any.whl", hash = "sha256:cda41cb57cff035b851646956cfbdcc408bee42511dabd4f2d7bd4fbf48c57a9", size = 2457097, upload-time = "2025-03-30T16:57:39.729Z" }, ] [[package]] name = "parameterized" version = "0.8.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/c6/23/2288f308d238b4f261c039cafcd650435d624de97c6ffc903f06ea8af50f/parameterized-0.8.1.tar.gz", hash = "sha256:41bbff37d6186430f77f900d777e5bb6a24928a1c46fb1de692f8b52b8833b5c", size = 23936 } +sdist = { url = "https://files.pythonhosted.org/packages/c6/23/2288f308d238b4f261c039cafcd650435d624de97c6ffc903f06ea8af50f/parameterized-0.8.1.tar.gz", hash = "sha256:41bbff37d6186430f77f900d777e5bb6a24928a1c46fb1de692f8b52b8833b5c", size = 23936, upload-time = "2021-01-09T20:35:18.235Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/31/13/fe468c8c7400a8eca204e6e160a29bf7dcd45a76e20f1c030f3eaa690d93/parameterized-0.8.1-py2.py3-none-any.whl", hash = "sha256:9cbb0b69a03e8695d68b3399a8a5825200976536fe1cb79db60ed6a4c8c9efe9", size = 26354 }, + { url = "https://files.pythonhosted.org/packages/31/13/fe468c8c7400a8eca204e6e160a29bf7dcd45a76e20f1c030f3eaa690d93/parameterized-0.8.1-py2.py3-none-any.whl", hash = "sha256:9cbb0b69a03e8695d68b3399a8a5825200976536fe1cb79db60ed6a4c8c9efe9", size = 26354, upload-time = "2021-01-09T20:35:16.307Z" }, ] [[package]] name = "pathspec" version = "0.12.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ca/bc/f35b8446f4531a7cb215605d100cd88b7ac6f44ab3fc94870c120ab3adbf/pathspec-0.12.1.tar.gz", hash = "sha256:a482d51503a1ab33b1c67a6c3813a26953dbdc71c31dacaef9a838c4e29f5712", size = 51043 } +sdist = { url = "https://files.pythonhosted.org/packages/ca/bc/f35b8446f4531a7cb215605d100cd88b7ac6f44ab3fc94870c120ab3adbf/pathspec-0.12.1.tar.gz", hash = "sha256:a482d51503a1ab33b1c67a6c3813a26953dbdc71c31dacaef9a838c4e29f5712", size = 51043, upload-time = "2023-12-10T22:30:45Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/cc/20/ff623b09d963f88bfde16306a54e12ee5ea43e9b597108672ff3a408aad6/pathspec-0.12.1-py3-none-any.whl", hash = "sha256:a0d503e138a4c123b27490a4f7beda6a01c6f288df0e4a8b79c7eb0dc7b4cc08", size = 31191 }, + { url = "https://files.pythonhosted.org/packages/cc/20/ff623b09d963f88bfde16306a54e12ee5ea43e9b597108672ff3a408aad6/pathspec-0.12.1-py3-none-any.whl", hash = "sha256:a0d503e138a4c123b27490a4f7beda6a01c6f288df0e4a8b79c7eb0dc7b4cc08", size = 31191, upload-time = "2023-12-10T22:30:43.14Z" }, ] [[package]] name = "pillow" -version = "11.1.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f3/af/c097e544e7bd278333db77933e535098c259609c4eb3b85381109602fb5b/pillow-11.1.0.tar.gz", hash = "sha256:368da70808b36d73b4b390a8ffac11069f8a5c85f29eff1f1b01bcf3ef5b2a20", size = 46742715 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/dd/d6/2000bfd8d5414fb70cbbe52c8332f2283ff30ed66a9cde42716c8ecbe22c/pillow-11.1.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:e06695e0326d05b06833b40b7ef477e475d0b1ba3a6d27da1bb48c23209bf457", size = 3229968 }, - { url = "https://files.pythonhosted.org/packages/d9/45/3fe487010dd9ce0a06adf9b8ff4f273cc0a44536e234b0fad3532a42c15b/pillow-11.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:96f82000e12f23e4f29346e42702b6ed9a2f2fea34a740dd5ffffcc8c539eb35", size = 3101806 }, - { url = "https://files.pythonhosted.org/packages/e3/72/776b3629c47d9d5f1c160113158a7a7ad177688d3a1159cd3b62ded5a33a/pillow-11.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a3cd561ded2cf2bbae44d4605837221b987c216cff94f49dfeed63488bb228d2", size = 4322283 }, - { url = "https://files.pythonhosted.org/packages/e4/c2/e25199e7e4e71d64eeb869f5b72c7ddec70e0a87926398785ab944d92375/pillow-11.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f189805c8be5ca5add39e6f899e6ce2ed824e65fb45f3c28cb2841911da19070", size = 4402945 }, - { url = "https://files.pythonhosted.org/packages/c1/ed/51d6136c9d5911f78632b1b86c45241c712c5a80ed7fa7f9120a5dff1eba/pillow-11.1.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:dd0052e9db3474df30433f83a71b9b23bd9e4ef1de13d92df21a52c0303b8ab6", size = 4361228 }, - { url = "https://files.pythonhosted.org/packages/48/a4/fbfe9d5581d7b111b28f1d8c2762dee92e9821bb209af9fa83c940e507a0/pillow-11.1.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:837060a8599b8f5d402e97197d4924f05a2e0d68756998345c829c33186217b1", size = 4484021 }, - { url = "https://files.pythonhosted.org/packages/39/db/0b3c1a5018117f3c1d4df671fb8e47d08937f27519e8614bbe86153b65a5/pillow-11.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:aa8dd43daa836b9a8128dbe7d923423e5ad86f50a7a14dc688194b7be5c0dea2", size = 4287449 }, - { url = "https://files.pythonhosted.org/packages/d9/58/bc128da7fea8c89fc85e09f773c4901e95b5936000e6f303222490c052f3/pillow-11.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0a2f91f8a8b367e7a57c6e91cd25af510168091fb89ec5146003e424e1558a96", size = 4419972 }, - { url = "https://files.pythonhosted.org/packages/5f/bb/58f34379bde9fe197f51841c5bbe8830c28bbb6d3801f16a83b8f2ad37df/pillow-11.1.0-cp311-cp311-win32.whl", hash = "sha256:c12fc111ef090845de2bb15009372175d76ac99969bdf31e2ce9b42e4b8cd88f", size = 2291201 }, - { url = "https://files.pythonhosted.org/packages/3a/c6/fce9255272bcf0c39e15abd2f8fd8429a954cf344469eaceb9d0d1366913/pillow-11.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:fbd43429d0d7ed6533b25fc993861b8fd512c42d04514a0dd6337fb3ccf22761", size = 2625686 }, - { url = "https://files.pythonhosted.org/packages/c8/52/8ba066d569d932365509054859f74f2a9abee273edcef5cd75e4bc3e831e/pillow-11.1.0-cp311-cp311-win_arm64.whl", hash = "sha256:f7955ecf5609dee9442cbface754f2c6e541d9e6eda87fad7f7a989b0bdb9d71", size = 2375194 }, - { url = "https://files.pythonhosted.org/packages/95/20/9ce6ed62c91c073fcaa23d216e68289e19d95fb8188b9fb7a63d36771db8/pillow-11.1.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:2062ffb1d36544d42fcaa277b069c88b01bb7298f4efa06731a7fd6cc290b81a", size = 3226818 }, - { url = "https://files.pythonhosted.org/packages/b9/d8/f6004d98579a2596c098d1e30d10b248798cceff82d2b77aa914875bfea1/pillow-11.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a85b653980faad27e88b141348707ceeef8a1186f75ecc600c395dcac19f385b", size = 3101662 }, - { url = "https://files.pythonhosted.org/packages/08/d9/892e705f90051c7a2574d9f24579c9e100c828700d78a63239676f960b74/pillow-11.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9409c080586d1f683df3f184f20e36fb647f2e0bc3988094d4fd8c9f4eb1b3b3", size = 4329317 }, - { url = "https://files.pythonhosted.org/packages/8c/aa/7f29711f26680eab0bcd3ecdd6d23ed6bce180d82e3f6380fb7ae35fcf3b/pillow-11.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7fdadc077553621911f27ce206ffcbec7d3f8d7b50e0da39f10997e8e2bb7f6a", size = 4412999 }, - { url = "https://files.pythonhosted.org/packages/c8/c4/8f0fe3b9e0f7196f6d0bbb151f9fba323d72a41da068610c4c960b16632a/pillow-11.1.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:93a18841d09bcdd774dcdc308e4537e1f867b3dec059c131fde0327899734aa1", size = 4368819 }, - { url = "https://files.pythonhosted.org/packages/38/0d/84200ed6a871ce386ddc82904bfadc0c6b28b0c0ec78176871a4679e40b3/pillow-11.1.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:9aa9aeddeed452b2f616ff5507459e7bab436916ccb10961c4a382cd3e03f47f", size = 4496081 }, - { url = "https://files.pythonhosted.org/packages/84/9c/9bcd66f714d7e25b64118e3952d52841a4babc6d97b6d28e2261c52045d4/pillow-11.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:3cdcdb0b896e981678eee140d882b70092dac83ac1cdf6b3a60e2216a73f2b91", size = 4296513 }, - { url = "https://files.pythonhosted.org/packages/db/61/ada2a226e22da011b45f7104c95ebda1b63dcbb0c378ad0f7c2a710f8fd2/pillow-11.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:36ba10b9cb413e7c7dfa3e189aba252deee0602c86c309799da5a74009ac7a1c", size = 4431298 }, - { url = "https://files.pythonhosted.org/packages/e7/c4/fc6e86750523f367923522014b821c11ebc5ad402e659d8c9d09b3c9d70c/pillow-11.1.0-cp312-cp312-win32.whl", hash = "sha256:cfd5cd998c2e36a862d0e27b2df63237e67273f2fc78f47445b14e73a810e7e6", size = 2291630 }, - { url = "https://files.pythonhosted.org/packages/08/5c/2104299949b9d504baf3f4d35f73dbd14ef31bbd1ddc2c1b66a5b7dfda44/pillow-11.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:a697cd8ba0383bba3d2d3ada02b34ed268cb548b369943cd349007730c92bddf", size = 2626369 }, - { url = "https://files.pythonhosted.org/packages/37/f3/9b18362206b244167c958984b57c7f70a0289bfb59a530dd8af5f699b910/pillow-11.1.0-cp312-cp312-win_arm64.whl", hash = "sha256:4dd43a78897793f60766563969442020e90eb7847463eca901e41ba186a7d4a5", size = 2375240 }, +version = "11.2.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/af/cb/bb5c01fcd2a69335b86c22142b2bccfc3464087efb7fd382eee5ffc7fdf7/pillow-11.2.1.tar.gz", hash = "sha256:a64dd61998416367b7ef979b73d3a85853ba9bec4c2925f74e588879a58716b6", size = 47026707, upload-time = "2025-04-12T17:50:03.289Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/68/08/3fbf4b98924c73037a8e8b4c2c774784805e0fb4ebca6c5bb60795c40125/pillow-11.2.1-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:35ca289f712ccfc699508c4658a1d14652e8033e9b69839edf83cbdd0ba39e70", size = 3198450, upload-time = "2025-04-12T17:47:37.135Z" }, + { url = "https://files.pythonhosted.org/packages/84/92/6505b1af3d2849d5e714fc75ba9e69b7255c05ee42383a35a4d58f576b16/pillow-11.2.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:e0409af9f829f87a2dfb7e259f78f317a5351f2045158be321fd135973fff7bf", size = 3030550, upload-time = "2025-04-12T17:47:39.345Z" }, + { url = "https://files.pythonhosted.org/packages/3c/8c/ac2f99d2a70ff966bc7eb13dacacfaab57c0549b2ffb351b6537c7840b12/pillow-11.2.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d4e5c5edee874dce4f653dbe59db7c73a600119fbea8d31f53423586ee2aafd7", size = 4415018, upload-time = "2025-04-12T17:47:41.128Z" }, + { url = "https://files.pythonhosted.org/packages/1f/e3/0a58b5d838687f40891fff9cbaf8669f90c96b64dc8f91f87894413856c6/pillow-11.2.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b93a07e76d13bff9444f1a029e0af2964e654bfc2e2c2d46bfd080df5ad5f3d8", size = 4498006, upload-time = "2025-04-12T17:47:42.912Z" }, + { url = "https://files.pythonhosted.org/packages/21/f5/6ba14718135f08fbfa33308efe027dd02b781d3f1d5c471444a395933aac/pillow-11.2.1-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:e6def7eed9e7fa90fde255afaf08060dc4b343bbe524a8f69bdd2a2f0018f600", size = 4517773, upload-time = "2025-04-12T17:47:44.611Z" }, + { url = "https://files.pythonhosted.org/packages/20/f2/805ad600fc59ebe4f1ba6129cd3a75fb0da126975c8579b8f57abeb61e80/pillow-11.2.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:8f4f3724c068be008c08257207210c138d5f3731af6c155a81c2b09a9eb3a788", size = 4607069, upload-time = "2025-04-12T17:47:46.46Z" }, + { url = "https://files.pythonhosted.org/packages/71/6b/4ef8a288b4bb2e0180cba13ca0a519fa27aa982875882392b65131401099/pillow-11.2.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:a0a6709b47019dff32e678bc12c63008311b82b9327613f534e496dacaefb71e", size = 4583460, upload-time = "2025-04-12T17:47:49.255Z" }, + { url = "https://files.pythonhosted.org/packages/62/ae/f29c705a09cbc9e2a456590816e5c234382ae5d32584f451c3eb41a62062/pillow-11.2.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f6b0c664ccb879109ee3ca702a9272d877f4fcd21e5eb63c26422fd6e415365e", size = 4661304, upload-time = "2025-04-12T17:47:51.067Z" }, + { url = "https://files.pythonhosted.org/packages/6e/1a/c8217b6f2f73794a5e219fbad087701f412337ae6dbb956db37d69a9bc43/pillow-11.2.1-cp311-cp311-win32.whl", hash = "sha256:cc5d875d56e49f112b6def6813c4e3d3036d269c008bf8aef72cd08d20ca6df6", size = 2331809, upload-time = "2025-04-12T17:47:54.425Z" }, + { url = "https://files.pythonhosted.org/packages/e2/72/25a8f40170dc262e86e90f37cb72cb3de5e307f75bf4b02535a61afcd519/pillow-11.2.1-cp311-cp311-win_amd64.whl", hash = "sha256:0f5c7eda47bf8e3c8a283762cab94e496ba977a420868cb819159980b6709193", size = 2676338, upload-time = "2025-04-12T17:47:56.535Z" }, + { url = "https://files.pythonhosted.org/packages/06/9e/76825e39efee61efea258b479391ca77d64dbd9e5804e4ad0fa453b4ba55/pillow-11.2.1-cp311-cp311-win_arm64.whl", hash = "sha256:4d375eb838755f2528ac8cbc926c3e31cc49ca4ad0cf79cff48b20e30634a4a7", size = 2414918, upload-time = "2025-04-12T17:47:58.217Z" }, + { url = "https://files.pythonhosted.org/packages/c7/40/052610b15a1b8961f52537cc8326ca6a881408bc2bdad0d852edeb6ed33b/pillow-11.2.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:78afba22027b4accef10dbd5eed84425930ba41b3ea0a86fa8d20baaf19d807f", size = 3190185, upload-time = "2025-04-12T17:48:00.417Z" }, + { url = "https://files.pythonhosted.org/packages/e5/7e/b86dbd35a5f938632093dc40d1682874c33dcfe832558fc80ca56bfcb774/pillow-11.2.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:78092232a4ab376a35d68c4e6d5e00dfd73454bd12b230420025fbe178ee3b0b", size = 3030306, upload-time = "2025-04-12T17:48:02.391Z" }, + { url = "https://files.pythonhosted.org/packages/a4/5c/467a161f9ed53e5eab51a42923c33051bf8d1a2af4626ac04f5166e58e0c/pillow-11.2.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:25a5f306095c6780c52e6bbb6109624b95c5b18e40aab1c3041da3e9e0cd3e2d", size = 4416121, upload-time = "2025-04-12T17:48:04.554Z" }, + { url = "https://files.pythonhosted.org/packages/62/73/972b7742e38ae0e2ac76ab137ca6005dcf877480da0d9d61d93b613065b4/pillow-11.2.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0c7b29dbd4281923a2bfe562acb734cee96bbb129e96e6972d315ed9f232bef4", size = 4501707, upload-time = "2025-04-12T17:48:06.831Z" }, + { url = "https://files.pythonhosted.org/packages/e4/3a/427e4cb0b9e177efbc1a84798ed20498c4f233abde003c06d2650a6d60cb/pillow-11.2.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:3e645b020f3209a0181a418bffe7b4a93171eef6c4ef6cc20980b30bebf17b7d", size = 4522921, upload-time = "2025-04-12T17:48:09.229Z" }, + { url = "https://files.pythonhosted.org/packages/fe/7c/d8b1330458e4d2f3f45d9508796d7caf0c0d3764c00c823d10f6f1a3b76d/pillow-11.2.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:b2dbea1012ccb784a65349f57bbc93730b96e85b42e9bf7b01ef40443db720b4", size = 4612523, upload-time = "2025-04-12T17:48:11.631Z" }, + { url = "https://files.pythonhosted.org/packages/b3/2f/65738384e0b1acf451de5a573d8153fe84103772d139e1e0bdf1596be2ea/pillow-11.2.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:da3104c57bbd72948d75f6a9389e6727d2ab6333c3617f0a89d72d4940aa0443", size = 4587836, upload-time = "2025-04-12T17:48:13.592Z" }, + { url = "https://files.pythonhosted.org/packages/6a/c5/e795c9f2ddf3debb2dedd0df889f2fe4b053308bb59a3cc02a0cd144d641/pillow-11.2.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:598174aef4589af795f66f9caab87ba4ff860ce08cd5bb447c6fc553ffee603c", size = 4669390, upload-time = "2025-04-12T17:48:15.938Z" }, + { url = "https://files.pythonhosted.org/packages/96/ae/ca0099a3995976a9fce2f423166f7bff9b12244afdc7520f6ed38911539a/pillow-11.2.1-cp312-cp312-win32.whl", hash = "sha256:1d535df14716e7f8776b9e7fee118576d65572b4aad3ed639be9e4fa88a1cad3", size = 2332309, upload-time = "2025-04-12T17:48:17.885Z" }, + { url = "https://files.pythonhosted.org/packages/7c/18/24bff2ad716257fc03da964c5e8f05d9790a779a8895d6566e493ccf0189/pillow-11.2.1-cp312-cp312-win_amd64.whl", hash = "sha256:14e33b28bf17c7a38eede290f77db7c664e4eb01f7869e37fa98a5aa95978941", size = 2676768, upload-time = "2025-04-12T17:48:19.655Z" }, + { url = "https://files.pythonhosted.org/packages/da/bb/e8d656c9543276517ee40184aaa39dcb41e683bca121022f9323ae11b39d/pillow-11.2.1-cp312-cp312-win_arm64.whl", hash = "sha256:21e1470ac9e5739ff880c211fc3af01e3ae505859392bf65458c224d0bf283eb", size = 2415087, upload-time = "2025-04-12T17:48:21.991Z" }, + { url = "https://files.pythonhosted.org/packages/a4/ad/2613c04633c7257d9481ab21d6b5364b59fc5d75faafd7cb8693523945a3/pillow-11.2.1-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:80f1df8dbe9572b4b7abdfa17eb5d78dd620b1d55d9e25f834efdbee872d3aed", size = 3181734, upload-time = "2025-04-12T17:49:46.789Z" }, + { url = "https://files.pythonhosted.org/packages/a4/fd/dcdda4471ed667de57bb5405bb42d751e6cfdd4011a12c248b455c778e03/pillow-11.2.1-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:ea926cfbc3957090becbcbbb65ad177161a2ff2ad578b5a6ec9bb1e1cd78753c", size = 2999841, upload-time = "2025-04-12T17:49:48.812Z" }, + { url = "https://files.pythonhosted.org/packages/ac/89/8a2536e95e77432833f0db6fd72a8d310c8e4272a04461fb833eb021bf94/pillow-11.2.1-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:738db0e0941ca0376804d4de6a782c005245264edaa253ffce24e5a15cbdc7bd", size = 3437470, upload-time = "2025-04-12T17:49:50.831Z" }, + { url = "https://files.pythonhosted.org/packages/9d/8f/abd47b73c60712f88e9eda32baced7bfc3e9bd6a7619bb64b93acff28c3e/pillow-11.2.1-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9db98ab6565c69082ec9b0d4e40dd9f6181dab0dd236d26f7a50b8b9bfbd5076", size = 3460013, upload-time = "2025-04-12T17:49:53.278Z" }, + { url = "https://files.pythonhosted.org/packages/f6/20/5c0a0aa83b213b7a07ec01e71a3d6ea2cf4ad1d2c686cc0168173b6089e7/pillow-11.2.1-pp311-pypy311_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:036e53f4170e270ddb8797d4c590e6dd14d28e15c7da375c18978045f7e6c37b", size = 3527165, upload-time = "2025-04-12T17:49:55.164Z" }, + { url = "https://files.pythonhosted.org/packages/58/0e/2abab98a72202d91146abc839e10c14f7cf36166f12838ea0c4db3ca6ecb/pillow-11.2.1-pp311-pypy311_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:14f73f7c291279bd65fda51ee87affd7c1e097709f7fdd0188957a16c264601f", size = 3571586, upload-time = "2025-04-12T17:49:57.171Z" }, + { url = "https://files.pythonhosted.org/packages/21/2c/5e05f58658cf49b6667762cca03d6e7d85cededde2caf2ab37b81f80e574/pillow-11.2.1-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:208653868d5c9ecc2b327f9b9ef34e0e42a4cdd172c2988fd81d62d2bc9bc044", size = 2674751, upload-time = "2025-04-12T17:49:59.628Z" }, ] [[package]] name = "platformdirs" -version = "4.3.6" +version = "4.3.8" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/13/fc/128cc9cb8f03208bdbf93d3aa862e16d376844a14f9a0ce5cf4507372de4/platformdirs-4.3.6.tar.gz", hash = "sha256:357fb2acbc885b0419afd3ce3ed34564c13c9b95c89360cd9563f73aa5e2b907", size = 21302 } +sdist = { url = "https://files.pythonhosted.org/packages/fe/8b/3c73abc9c759ecd3f1f7ceff6685840859e8070c4d947c93fae71f6a0bf2/platformdirs-4.3.8.tar.gz", hash = "sha256:3d512d96e16bcb959a814c9f348431070822a6496326a4be0911c40b5a74c2bc", size = 21362, upload-time = "2025-05-07T22:47:42.121Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3c/a6/bc1012356d8ece4d66dd75c4b9fc6c1f6650ddd5991e421177d9f8f671be/platformdirs-4.3.6-py3-none-any.whl", hash = "sha256:73e575e1408ab8103900836b97580d5307456908a03e92031bab39e4554cc3fb", size = 18439 }, + { url = "https://files.pythonhosted.org/packages/fe/39/979e8e21520d4e47a0bbe349e2713c0aac6f3d853d0e5b34d76206c439aa/platformdirs-4.3.8-py3-none-any.whl", hash = "sha256:ff7059bb7eb1179e2685604f4aaf157cfd9535242bd23742eadc3c13542139b4", size = 18567, upload-time = "2025-05-07T22:47:40.376Z" }, ] [[package]] name = "pluggy" -version = "1.5.0" +version = "1.6.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/96/2d/02d4312c973c6050a18b314a5ad0b3210edb65a906f868e31c111dede4a6/pluggy-1.5.0.tar.gz", hash = "sha256:2cffa88e94fdc978c4c574f15f9e59b7f4201d439195c3715ca9e2486f1d0cf1", size = 67955 } +sdist = { url = "https://files.pythonhosted.org/packages/f9/e2/3e91f31a7d2b083fe6ef3fa267035b518369d9511ffab804f839851d2779/pluggy-1.6.0.tar.gz", hash = "sha256:7dcc130b76258d33b90f61b658791dede3486c3e6bfb003ee5c9bfb396dd22f3", size = 69412, upload-time = "2025-05-15T12:30:07.975Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/88/5f/e351af9a41f866ac3f1fac4ca0613908d9a41741cfcf2228f4ad853b697d/pluggy-1.5.0-py3-none-any.whl", hash = "sha256:44e1ad92c8ca002de6377e165f3e0f1be63266ab4d554740532335b9d75ea669", size = 20556 }, -] - -[[package]] -name = "portalocker" -version = "2.10.1" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "pywin32", marker = "sys_platform == 'win32'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/ed/d3/c6c64067759e87af98cc668c1cc75171347d0f1577fab7ca3749134e3cd4/portalocker-2.10.1.tar.gz", hash = "sha256:ef1bf844e878ab08aee7e40184156e1151f228f103aa5c6bd0724cc330960f8f", size = 40891 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/9b/fb/a70a4214956182e0d7a9099ab17d50bfcba1056188e9b14f35b9e2b62a0d/portalocker-2.10.1-py3-none-any.whl", hash = "sha256:53a5984ebc86a025552264b459b46a2086e269b21823cb572f8f28ee759e45bf", size = 18423 }, + { url = "https://files.pythonhosted.org/packages/54/20/4d324d65cc6d9205fabedc306948156824eb9f0ee1633355a8f7ec5c66bf/pluggy-1.6.0-py3-none-any.whl", hash = "sha256:e920276dd6813095e9377c0bc5566d94c932c33b27a3e3945d8389c374dd4746", size = 20538, upload-time = "2025-05-15T12:30:06.134Z" }, ] [[package]] @@ -1537,119 +1558,123 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ruamel-yaml" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ac/7d/3299241a753c738d114600c360d754550b28c285281dc6a5132c4ccfae65/pre_commit_hooks-5.0.0.tar.gz", hash = "sha256:10626959a9eaf602fbfc22bc61b6e75801436f82326bfcee82bb1f2fc4bc646e", size = 29747 } +sdist = { url = "https://files.pythonhosted.org/packages/ac/7d/3299241a753c738d114600c360d754550b28c285281dc6a5132c4ccfae65/pre_commit_hooks-5.0.0.tar.gz", hash = "sha256:10626959a9eaf602fbfc22bc61b6e75801436f82326bfcee82bb1f2fc4bc646e", size = 29747, upload-time = "2024-10-05T18:43:11.225Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1e/29/db1d855a661c02dbde5cab3057969133fcc62e7a0c6393e48fe9d0e81679/pre_commit_hooks-5.0.0-py2.py3-none-any.whl", hash = "sha256:8d71cfb582c5c314a5498d94e0104b6567a8b93fb35903ea845c491f4e290a7a", size = 41245 }, + { url = "https://files.pythonhosted.org/packages/1e/29/db1d855a661c02dbde5cab3057969133fcc62e7a0c6393e48fe9d0e81679/pre_commit_hooks-5.0.0-py2.py3-none-any.whl", hash = "sha256:8d71cfb582c5c314a5498d94e0104b6567a8b93fb35903ea845c491f4e290a7a", size = 41245, upload-time = "2024-10-05T18:43:09.901Z" }, ] [[package]] name = "progressbar" version = "2.5" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a3/a6/b8e451f6cff1c99b4747a2f7235aa904d2d49e8e1464e0b798272aa84358/progressbar-2.5.tar.gz", hash = "sha256:5d81cb529da2e223b53962afd6c8ca0f05c6670e40309a7219eacc36af9b6c63", size = 10046 } +sdist = { url = "https://files.pythonhosted.org/packages/a3/a6/b8e451f6cff1c99b4747a2f7235aa904d2d49e8e1464e0b798272aa84358/progressbar-2.5.tar.gz", hash = "sha256:5d81cb529da2e223b53962afd6c8ca0f05c6670e40309a7219eacc36af9b6c63", size = 10046, upload-time = "2018-06-29T02:32:00.222Z" } [[package]] name = "propcache" -version = "0.3.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/92/76/f941e63d55c0293ff7829dd21e7cf1147e90a526756869a9070f287a68c9/propcache-0.3.0.tar.gz", hash = "sha256:a8fd93de4e1d278046345f49e2238cdb298589325849b2645d4a94c53faeffc5", size = 42722 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/45/c9/cf09ff7e6d09f14149094f7cd50d2dec032b24e61af21fc4540da2b17bfb/propcache-0.3.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9ddd49258610499aab83b4f5b61b32e11fce873586282a0e972e5ab3bcadee51", size = 79568 }, - { url = "https://files.pythonhosted.org/packages/c8/32/2424d89da88cd81b7d148e0d2b3131461b570a02aa9d84a2e567509adb0d/propcache-0.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2578541776769b500bada3f8a4eeaf944530516b6e90c089aa368266ed70c49e", size = 45895 }, - { url = "https://files.pythonhosted.org/packages/f6/91/ee5b6aa7aa31754fefcf0c5180e09223cac380ef195c4ddc8c266eb641ea/propcache-0.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d8074c5dd61c8a3e915fa8fc04754fa55cfa5978200d2daa1e2d4294c1f136aa", size = 45427 }, - { url = "https://files.pythonhosted.org/packages/bf/73/38f0128462b8b616181d8c53bd5d04eac41c50c449b07615c65d56ba0a9b/propcache-0.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b58229a844931bca61b3a20efd2be2a2acb4ad1622fc026504309a6883686fbf", size = 232427 }, - { url = "https://files.pythonhosted.org/packages/59/82/f3d4e84f4539dcfc9c3d338282b9e915f5b63c921986ecfdf7af2d12f87c/propcache-0.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e45377d5d6fefe1677da2a2c07b024a6dac782088e37c0b1efea4cfe2b1be19b", size = 239985 }, - { url = "https://files.pythonhosted.org/packages/42/e8/029f58cccbae83c9969a7ee7a06558d5b83a93dfc54e0f4f70234bbaea1b/propcache-0.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ec5060592d83454e8063e487696ac3783cc48c9a329498bafae0d972bc7816c9", size = 238827 }, - { url = "https://files.pythonhosted.org/packages/8b/a2/c373561777c0cb9b9e7b9b9a10b9b3a7b6bde75a2535b962231cecc8fdb8/propcache-0.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:15010f29fbed80e711db272909a074dc79858c6d28e2915704cfc487a8ac89c6", size = 231348 }, - { url = "https://files.pythonhosted.org/packages/d7/d2/4673f715beedf6038b485bcd976813149231d9df5bb6196cb69a09c185c9/propcache-0.3.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a254537b9b696ede293bfdbc0a65200e8e4507bc9f37831e2a0318a9b333c85c", size = 220426 }, - { url = "https://files.pythonhosted.org/packages/e0/f6/1da65f900927bafd4675a16e890618ec7643f2f922bf0e4d84bb38645618/propcache-0.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2b975528998de037dfbc10144b8aed9b8dd5a99ec547f14d1cb7c5665a43f075", size = 220294 }, - { url = "https://files.pythonhosted.org/packages/ff/86/620451bdc02e91b1712cd71890c17077ee97e2a28493836a87e47b8e70ff/propcache-0.3.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:19d36bb351ad5554ff20f2ae75f88ce205b0748c38b146c75628577020351e3c", size = 212492 }, - { url = "https://files.pythonhosted.org/packages/6e/1b/e8f86921ed4016da80faf3b8f515f7829decabdbff106736bfff353bceba/propcache-0.3.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:6032231d4a5abd67c7f71168fd64a47b6b451fbcb91c8397c2f7610e67683810", size = 215113 }, - { url = "https://files.pythonhosted.org/packages/1a/95/a61d86cc49aa0945f6c06f3a4614fc543e311a50558c92861f5e9691a37c/propcache-0.3.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:6985a593417cdbc94c7f9c3403747335e450c1599da1647a5af76539672464d3", size = 228330 }, - { url = "https://files.pythonhosted.org/packages/8f/7d/10dbae48ff2bb189e92c2b3487a48f3229146a25941ad0d485934d1104d4/propcache-0.3.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:6a1948df1bb1d56b5e7b0553c0fa04fd0e320997ae99689488201f19fa90d2e7", size = 231942 }, - { url = "https://files.pythonhosted.org/packages/39/ce/82d16aec96c5513ae7db13ab901a65a1e54c915292fb5b2390e33275b61d/propcache-0.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:8319293e85feadbbfe2150a5659dbc2ebc4afdeaf7d98936fb9a2f2ba0d4c35c", size = 223077 }, - { url = "https://files.pythonhosted.org/packages/c8/e0/cb077e8e7a583c733df7f53327fcbdb92e42be59b976ce60bf1d904a0efe/propcache-0.3.0-cp311-cp311-win32.whl", hash = "sha256:63f26258a163c34542c24808f03d734b338da66ba91f410a703e505c8485791d", size = 40455 }, - { url = "https://files.pythonhosted.org/packages/d8/35/57abeb6146fe3c19081eeaf3d9d4cfea256f87f1e5101acf80d3332c1820/propcache-0.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:cacea77ef7a2195f04f9279297684955e3d1ae4241092ff0cfcef532bb7a1c32", size = 44705 }, - { url = "https://files.pythonhosted.org/packages/8d/2c/921f15dc365796ec23975b322b0078eae72995c7b4d49eba554c6a308d70/propcache-0.3.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e53d19c2bf7d0d1e6998a7e693c7e87300dd971808e6618964621ccd0e01fe4e", size = 79867 }, - { url = "https://files.pythonhosted.org/packages/11/a5/4a6cc1a559d1f2fb57ea22edc4245158cdffae92f7f92afcee2913f84417/propcache-0.3.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:a61a68d630e812b67b5bf097ab84e2cd79b48c792857dc10ba8a223f5b06a2af", size = 46109 }, - { url = "https://files.pythonhosted.org/packages/e1/6d/28bfd3af3a567ad7d667348e7f46a520bda958229c4d545ba138a044232f/propcache-0.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:fb91d20fa2d3b13deea98a690534697742029f4fb83673a3501ae6e3746508b5", size = 45635 }, - { url = "https://files.pythonhosted.org/packages/73/20/d75b42eaffe5075eac2f4e168f6393d21c664c91225288811d85451b2578/propcache-0.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:67054e47c01b7b349b94ed0840ccae075449503cf1fdd0a1fdd98ab5ddc2667b", size = 242159 }, - { url = "https://files.pythonhosted.org/packages/a5/fb/4b537dd92f9fd4be68042ec51c9d23885ca5fafe51ec24c58d9401034e5f/propcache-0.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:997e7b8f173a391987df40f3b52c423e5850be6f6df0dcfb5376365440b56667", size = 248163 }, - { url = "https://files.pythonhosted.org/packages/e7/af/8a9db04ac596d531ca0ef7dde518feaadfcdabef7b17d6a5ec59ee3effc2/propcache-0.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8d663fd71491dde7dfdfc899d13a067a94198e90695b4321084c6e450743b8c7", size = 248794 }, - { url = "https://files.pythonhosted.org/packages/9d/c4/ecfc988879c0fd9db03228725b662d76cf484b6b46f7e92fee94e4b52490/propcache-0.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8884ba1a0fe7210b775106b25850f5e5a9dc3c840d1ae9924ee6ea2eb3acbfe7", size = 243912 }, - { url = "https://files.pythonhosted.org/packages/04/a2/298dd27184faa8b7d91cc43488b578db218b3cc85b54d912ed27b8c5597a/propcache-0.3.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aa806bbc13eac1ab6291ed21ecd2dd426063ca5417dd507e6be58de20e58dfcf", size = 229402 }, - { url = "https://files.pythonhosted.org/packages/be/0d/efe7fec316ca92dbf4bc4a9ba49ca889c43ca6d48ab1d6fa99fc94e5bb98/propcache-0.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6f4d7a7c0aff92e8354cceca6fe223973ddf08401047920df0fcb24be2bd5138", size = 226896 }, - { url = "https://files.pythonhosted.org/packages/60/63/72404380ae1d9c96d96e165aa02c66c2aae6072d067fc4713da5cde96762/propcache-0.3.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:9be90eebc9842a93ef8335291f57b3b7488ac24f70df96a6034a13cb58e6ff86", size = 221447 }, - { url = "https://files.pythonhosted.org/packages/9d/18/b8392cab6e0964b67a30a8f4dadeaff64dc7022b5a34bb1d004ea99646f4/propcache-0.3.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:bf15fc0b45914d9d1b706f7c9c4f66f2b7b053e9517e40123e137e8ca8958b3d", size = 222440 }, - { url = "https://files.pythonhosted.org/packages/6f/be/105d9ceda0f97eff8c06bac1673448b2db2a497444de3646464d3f5dc881/propcache-0.3.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:5a16167118677d94bb48bfcd91e420088854eb0737b76ec374b91498fb77a70e", size = 234104 }, - { url = "https://files.pythonhosted.org/packages/cb/c9/f09a4ec394cfcce4053d8b2a04d622b5f22d21ba9bb70edd0cad061fa77b/propcache-0.3.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:41de3da5458edd5678b0f6ff66691507f9885f5fe6a0fb99a5d10d10c0fd2d64", size = 239086 }, - { url = "https://files.pythonhosted.org/packages/ea/aa/96f7f9ed6def82db67c972bdb7bd9f28b95d7d98f7e2abaf144c284bf609/propcache-0.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:728af36011bb5d344c4fe4af79cfe186729efb649d2f8b395d1572fb088a996c", size = 230991 }, - { url = "https://files.pythonhosted.org/packages/5a/11/bee5439de1307d06fad176f7143fec906e499c33d7aff863ea8428b8e98b/propcache-0.3.0-cp312-cp312-win32.whl", hash = "sha256:6b5b7fd6ee7b54e01759f2044f936dcf7dea6e7585f35490f7ca0420fe723c0d", size = 40337 }, - { url = "https://files.pythonhosted.org/packages/e4/17/e5789a54a0455a61cb9efc4ca6071829d992220c2998a27c59aeba749f6f/propcache-0.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:2d15bc27163cd4df433e75f546b9ac31c1ba7b0b128bfb1b90df19082466ff57", size = 44404 }, - { url = "https://files.pythonhosted.org/packages/b5/35/6c4c6fc8774a9e3629cd750dc24a7a4fb090a25ccd5c3246d127b70f9e22/propcache-0.3.0-py3-none-any.whl", hash = "sha256:67dda3c7325691c2081510e92c561f465ba61b975f481735aefdfc845d2cd043", size = 12101 }, +version = "0.3.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/07/c8/fdc6686a986feae3541ea23dcaa661bd93972d3940460646c6bb96e21c40/propcache-0.3.1.tar.gz", hash = "sha256:40d980c33765359098837527e18eddefc9a24cea5b45e078a7f3bb5b032c6ecf", size = 43651, upload-time = "2025-03-26T03:06:12.05Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/90/0f/5a5319ee83bd651f75311fcb0c492c21322a7fc8f788e4eef23f44243427/propcache-0.3.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7f30241577d2fef2602113b70ef7231bf4c69a97e04693bde08ddab913ba0ce5", size = 80243, upload-time = "2025-03-26T03:04:01.912Z" }, + { url = "https://files.pythonhosted.org/packages/ce/84/3db5537e0879942783e2256616ff15d870a11d7ac26541336fe1b673c818/propcache-0.3.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:43593c6772aa12abc3af7784bff4a41ffa921608dd38b77cf1dfd7f5c4e71371", size = 46503, upload-time = "2025-03-26T03:04:03.704Z" }, + { url = "https://files.pythonhosted.org/packages/e2/c8/b649ed972433c3f0d827d7f0cf9ea47162f4ef8f4fe98c5f3641a0bc63ff/propcache-0.3.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a75801768bbe65499495660b777e018cbe90c7980f07f8aa57d6be79ea6f71da", size = 45934, upload-time = "2025-03-26T03:04:05.257Z" }, + { url = "https://files.pythonhosted.org/packages/59/f9/4c0a5cf6974c2c43b1a6810c40d889769cc8f84cea676cbe1e62766a45f8/propcache-0.3.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f6f1324db48f001c2ca26a25fa25af60711e09b9aaf4b28488602776f4f9a744", size = 233633, upload-time = "2025-03-26T03:04:07.044Z" }, + { url = "https://files.pythonhosted.org/packages/e7/64/66f2f4d1b4f0007c6e9078bd95b609b633d3957fe6dd23eac33ebde4b584/propcache-0.3.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5cdb0f3e1eb6dfc9965d19734d8f9c481b294b5274337a8cb5cb01b462dcb7e0", size = 241124, upload-time = "2025-03-26T03:04:08.676Z" }, + { url = "https://files.pythonhosted.org/packages/aa/bf/7b8c9fd097d511638fa9b6af3d986adbdf567598a567b46338c925144c1b/propcache-0.3.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1eb34d90aac9bfbced9a58b266f8946cb5935869ff01b164573a7634d39fbcb5", size = 240283, upload-time = "2025-03-26T03:04:10.172Z" }, + { url = "https://files.pythonhosted.org/packages/fa/c9/e85aeeeaae83358e2a1ef32d6ff50a483a5d5248bc38510d030a6f4e2816/propcache-0.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f35c7070eeec2cdaac6fd3fe245226ed2a6292d3ee8c938e5bb645b434c5f256", size = 232498, upload-time = "2025-03-26T03:04:11.616Z" }, + { url = "https://files.pythonhosted.org/packages/8e/66/acb88e1f30ef5536d785c283af2e62931cb934a56a3ecf39105887aa8905/propcache-0.3.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b23c11c2c9e6d4e7300c92e022046ad09b91fd00e36e83c44483df4afa990073", size = 221486, upload-time = "2025-03-26T03:04:13.102Z" }, + { url = "https://files.pythonhosted.org/packages/f5/f9/233ddb05ffdcaee4448508ee1d70aa7deff21bb41469ccdfcc339f871427/propcache-0.3.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:3e19ea4ea0bf46179f8a3652ac1426e6dcbaf577ce4b4f65be581e237340420d", size = 222675, upload-time = "2025-03-26T03:04:14.658Z" }, + { url = "https://files.pythonhosted.org/packages/98/b8/eb977e28138f9e22a5a789daf608d36e05ed93093ef12a12441030da800a/propcache-0.3.1-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:bd39c92e4c8f6cbf5f08257d6360123af72af9f4da75a690bef50da77362d25f", size = 215727, upload-time = "2025-03-26T03:04:16.207Z" }, + { url = "https://files.pythonhosted.org/packages/89/2d/5f52d9c579f67b8ee1edd9ec073c91b23cc5b7ff7951a1e449e04ed8fdf3/propcache-0.3.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:b0313e8b923b3814d1c4a524c93dfecea5f39fa95601f6a9b1ac96cd66f89ea0", size = 217878, upload-time = "2025-03-26T03:04:18.11Z" }, + { url = "https://files.pythonhosted.org/packages/7a/fd/5283e5ed8a82b00c7a989b99bb6ea173db1ad750bf0bf8dff08d3f4a4e28/propcache-0.3.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:e861ad82892408487be144906a368ddbe2dc6297074ade2d892341b35c59844a", size = 230558, upload-time = "2025-03-26T03:04:19.562Z" }, + { url = "https://files.pythonhosted.org/packages/90/38/ab17d75938ef7ac87332c588857422ae126b1c76253f0f5b1242032923ca/propcache-0.3.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:61014615c1274df8da5991a1e5da85a3ccb00c2d4701ac6f3383afd3ca47ab0a", size = 233754, upload-time = "2025-03-26T03:04:21.065Z" }, + { url = "https://files.pythonhosted.org/packages/06/5d/3b921b9c60659ae464137508d3b4c2b3f52f592ceb1964aa2533b32fcf0b/propcache-0.3.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:71ebe3fe42656a2328ab08933d420df5f3ab121772eef78f2dc63624157f0ed9", size = 226088, upload-time = "2025-03-26T03:04:22.718Z" }, + { url = "https://files.pythonhosted.org/packages/54/6e/30a11f4417d9266b5a464ac5a8c5164ddc9dd153dfa77bf57918165eb4ae/propcache-0.3.1-cp311-cp311-win32.whl", hash = "sha256:58aa11f4ca8b60113d4b8e32d37e7e78bd8af4d1a5b5cb4979ed856a45e62005", size = 40859, upload-time = "2025-03-26T03:04:24.039Z" }, + { url = "https://files.pythonhosted.org/packages/1d/3a/8a68dd867da9ca2ee9dfd361093e9cb08cb0f37e5ddb2276f1b5177d7731/propcache-0.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:9532ea0b26a401264b1365146c440a6d78269ed41f83f23818d4b79497aeabe7", size = 45153, upload-time = "2025-03-26T03:04:25.211Z" }, + { url = "https://files.pythonhosted.org/packages/41/aa/ca78d9be314d1e15ff517b992bebbed3bdfef5b8919e85bf4940e57b6137/propcache-0.3.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f78eb8422acc93d7b69964012ad7048764bb45a54ba7a39bb9e146c72ea29723", size = 80430, upload-time = "2025-03-26T03:04:26.436Z" }, + { url = "https://files.pythonhosted.org/packages/1a/d8/f0c17c44d1cda0ad1979af2e593ea290defdde9eaeb89b08abbe02a5e8e1/propcache-0.3.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:89498dd49c2f9a026ee057965cdf8192e5ae070ce7d7a7bd4b66a8e257d0c976", size = 46637, upload-time = "2025-03-26T03:04:27.932Z" }, + { url = "https://files.pythonhosted.org/packages/ae/bd/c1e37265910752e6e5e8a4c1605d0129e5b7933c3dc3cf1b9b48ed83b364/propcache-0.3.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:09400e98545c998d57d10035ff623266927cb784d13dd2b31fd33b8a5316b85b", size = 46123, upload-time = "2025-03-26T03:04:30.659Z" }, + { url = "https://files.pythonhosted.org/packages/d4/b0/911eda0865f90c0c7e9f0415d40a5bf681204da5fd7ca089361a64c16b28/propcache-0.3.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aa8efd8c5adc5a2c9d3b952815ff8f7710cefdcaf5f2c36d26aff51aeca2f12f", size = 243031, upload-time = "2025-03-26T03:04:31.977Z" }, + { url = "https://files.pythonhosted.org/packages/0a/06/0da53397c76a74271621807265b6eb61fb011451b1ddebf43213df763669/propcache-0.3.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c2fe5c910f6007e716a06d269608d307b4f36e7babee5f36533722660e8c4a70", size = 249100, upload-time = "2025-03-26T03:04:33.45Z" }, + { url = "https://files.pythonhosted.org/packages/f1/eb/13090e05bf6b963fc1653cdc922133ced467cb4b8dab53158db5a37aa21e/propcache-0.3.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a0ab8cf8cdd2194f8ff979a43ab43049b1df0b37aa64ab7eca04ac14429baeb7", size = 250170, upload-time = "2025-03-26T03:04:35.542Z" }, + { url = "https://files.pythonhosted.org/packages/3b/4c/f72c9e1022b3b043ec7dc475a0f405d4c3e10b9b1d378a7330fecf0652da/propcache-0.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:563f9d8c03ad645597b8d010ef4e9eab359faeb11a0a2ac9f7b4bc8c28ebef25", size = 245000, upload-time = "2025-03-26T03:04:37.501Z" }, + { url = "https://files.pythonhosted.org/packages/e8/fd/970ca0e22acc829f1adf5de3724085e778c1ad8a75bec010049502cb3a86/propcache-0.3.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fb6e0faf8cb6b4beea5d6ed7b5a578254c6d7df54c36ccd3d8b3eb00d6770277", size = 230262, upload-time = "2025-03-26T03:04:39.532Z" }, + { url = "https://files.pythonhosted.org/packages/c4/42/817289120c6b9194a44f6c3e6b2c3277c5b70bbad39e7df648f177cc3634/propcache-0.3.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1c5c7ab7f2bb3f573d1cb921993006ba2d39e8621019dffb1c5bc94cdbae81e8", size = 236772, upload-time = "2025-03-26T03:04:41.109Z" }, + { url = "https://files.pythonhosted.org/packages/7c/9c/3b3942b302badd589ad6b672da3ca7b660a6c2f505cafd058133ddc73918/propcache-0.3.1-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:050b571b2e96ec942898f8eb46ea4bfbb19bd5502424747e83badc2d4a99a44e", size = 231133, upload-time = "2025-03-26T03:04:42.544Z" }, + { url = "https://files.pythonhosted.org/packages/98/a1/75f6355f9ad039108ff000dfc2e19962c8dea0430da9a1428e7975cf24b2/propcache-0.3.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:e1c4d24b804b3a87e9350f79e2371a705a188d292fd310e663483af6ee6718ee", size = 230741, upload-time = "2025-03-26T03:04:44.06Z" }, + { url = "https://files.pythonhosted.org/packages/67/0c/3e82563af77d1f8731132166da69fdfd95e71210e31f18edce08a1eb11ea/propcache-0.3.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:e4fe2a6d5ce975c117a6bb1e8ccda772d1e7029c1cca1acd209f91d30fa72815", size = 244047, upload-time = "2025-03-26T03:04:45.983Z" }, + { url = "https://files.pythonhosted.org/packages/f7/50/9fb7cca01532a08c4d5186d7bb2da6c4c587825c0ae134b89b47c7d62628/propcache-0.3.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:feccd282de1f6322f56f6845bf1207a537227812f0a9bf5571df52bb418d79d5", size = 246467, upload-time = "2025-03-26T03:04:47.699Z" }, + { url = "https://files.pythonhosted.org/packages/a9/02/ccbcf3e1c604c16cc525309161d57412c23cf2351523aedbb280eb7c9094/propcache-0.3.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ec314cde7314d2dd0510c6787326bbffcbdc317ecee6b7401ce218b3099075a7", size = 241022, upload-time = "2025-03-26T03:04:49.195Z" }, + { url = "https://files.pythonhosted.org/packages/db/19/e777227545e09ca1e77a6e21274ae9ec45de0f589f0ce3eca2a41f366220/propcache-0.3.1-cp312-cp312-win32.whl", hash = "sha256:7d2d5a0028d920738372630870e7d9644ce437142197f8c827194fca404bf03b", size = 40647, upload-time = "2025-03-26T03:04:50.595Z" }, + { url = "https://files.pythonhosted.org/packages/24/bb/3b1b01da5dd04c77a204c84e538ff11f624e31431cfde7201d9110b092b1/propcache-0.3.1-cp312-cp312-win_amd64.whl", hash = "sha256:88c423efef9d7a59dae0614eaed718449c09a5ac79a5f224a8b9664d603f04a3", size = 44784, upload-time = "2025-03-26T03:04:51.791Z" }, + { url = "https://files.pythonhosted.org/packages/b8/d3/c3cb8f1d6ae3b37f83e1de806713a9b3642c5895f0215a62e1a4bd6e5e34/propcache-0.3.1-py3-none-any.whl", hash = "sha256:9a8ecf38de50a7f518c21568c80f985e776397b902f1ce0b01f799aba1608b40", size = 12376, upload-time = "2025-03-26T03:06:10.5Z" }, ] [[package]] name = "protobuf" -version = "6.30.0" +version = "6.31.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/53/6a/2629bb3529e5bdfbd6c4608ff5c7d942cd4beae85793f84ba543aab2548a/protobuf-6.30.0.tar.gz", hash = "sha256:852b675d276a7d028f660da075af1841c768618f76b90af771a8e2c29e6f5965", size = 429239 } +sdist = { url = "https://files.pythonhosted.org/packages/13/48/718c1e104a2e89970a8ff3b06d87e152834b576c570a6908f8c17ba88d65/protobuf-6.31.0.tar.gz", hash = "sha256:314fab1a6a316469dc2dd46f993cbbe95c861ea6807da910becfe7475bc26ffe", size = 441644, upload-time = "2025-05-14T17:58:27.862Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/aa/76/8b1cbf762d98b09fcb29bbc6eca97dc6e1cd865b97a49c443aa23f1a9f82/protobuf-6.30.0-cp310-abi3-win32.whl", hash = "sha256:7337d76d8efe65ee09ee566b47b5914c517190196f414e5418fa236dfd1aed3e", size = 419141 }, - { url = "https://files.pythonhosted.org/packages/57/50/2ea2fb4533321438f5106723c70c303529ba184540e619ebe75e790d402e/protobuf-6.30.0-cp310-abi3-win_amd64.whl", hash = "sha256:9b33d51cc95a7ec4f407004c8b744330b6911a37a782e2629c67e1e8ac41318f", size = 430995 }, - { url = "https://files.pythonhosted.org/packages/a1/7d/a7dfa7aa3deda114920b1ed57c0026e85a976e74658db2784a0443510252/protobuf-6.30.0-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:52d4bb6fe76005860e1d0b8bfa126f5c97c19cc82704961f60718f50be16942d", size = 417570 }, - { url = "https://files.pythonhosted.org/packages/11/87/a9c7b020c4072dc34e3a2a3cde69366ffc623afff0e7f10f4e5275aaec01/protobuf-6.30.0-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:7940ab4dfd60d514b2e1d3161549ea7aed5be37d53bafde16001ac470a3e202b", size = 317310 }, - { url = "https://files.pythonhosted.org/packages/95/66/424db2262723781dc94208ff9ce201df2f44f18a46fbff3c067812c6b5b9/protobuf-6.30.0-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:d79bf6a202a536b192b7e8d295d7eece0c86fbd9b583d147faf8cfeff46bf598", size = 316203 }, - { url = "https://files.pythonhosted.org/packages/51/6f/21c2b7de96c3051f847a4a88a12fdf015ed6b7d50fc131fb101a739bd7a5/protobuf-6.30.0-py3-none-any.whl", hash = "sha256:e5ef216ea061b262b8994cb6b7d6637a4fb27b3fb4d8e216a6040c0b93bd10d7", size = 167054 }, + { url = "https://files.pythonhosted.org/packages/b6/77/8671682038b08237c927215fa3296bc1c54e4086fe542c87017c1b626663/protobuf-6.31.0-cp310-abi3-win32.whl", hash = "sha256:10bd62802dfa0588649740a59354090eaf54b8322f772fbdcca19bc78d27f0d6", size = 423437, upload-time = "2025-05-14T17:58:16.116Z" }, + { url = "https://files.pythonhosted.org/packages/e4/07/cc9b0cbf7593f6ef8cf87fa9b0e55cd74c5cb526dd89ad84aa7d6547ef8d/protobuf-6.31.0-cp310-abi3-win_amd64.whl", hash = "sha256:3e987c99fd634be8347246a02123250f394ba20573c953de133dc8b2c107dd71", size = 435118, upload-time = "2025-05-14T17:58:18.591Z" }, + { url = "https://files.pythonhosted.org/packages/21/46/33f884aa8bc59114dc97e0d954ca4618c556483670236008c88fbb7e834f/protobuf-6.31.0-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:2c812f0f96ceb6b514448cefeb1df54ec06dde456783f5099c0e2f8a0f2caa89", size = 425439, upload-time = "2025-05-14T17:58:19.709Z" }, + { url = "https://files.pythonhosted.org/packages/9b/f2/9a676b50229ce37b12777d7b21de90ae7bc0f9505d07e72e2e8d47b8d165/protobuf-6.31.0-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:67ce50195e4e584275623b8e6bc6d3d3dfd93924bf6116b86b3b8975ab9e4571", size = 321950, upload-time = "2025-05-14T17:58:22.04Z" }, + { url = "https://files.pythonhosted.org/packages/a1/a7/243fa2d3c1b7675d54744b32dacf30356f4c27c0d3ad940ca8745a1c6b2c/protobuf-6.31.0-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:5353e38844168a327acd2b2aa440044411cd8d1b6774d5701008bd1dba067c79", size = 320904, upload-time = "2025-05-14T17:58:23.438Z" }, + { url = "https://files.pythonhosted.org/packages/ee/01/1ed1d482960a5718fd99c82f6d79120181947cfd4667ec3944d448ed44a3/protobuf-6.31.0-py3-none-any.whl", hash = "sha256:6ac2e82556e822c17a8d23aa1190bbc1d06efb9c261981da95c71c9da09e9e23", size = 168558, upload-time = "2025-05-14T17:58:26.923Z" }, ] [[package]] name = "psutil" version = "7.0.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/2a/80/336820c1ad9286a4ded7e845b2eccfcb27851ab8ac6abece774a6ff4d3de/psutil-7.0.0.tar.gz", hash = "sha256:7be9c3eba38beccb6495ea33afd982a44074b78f28c434a1f51cc07fd315c456", size = 497003 } +sdist = { url = "https://files.pythonhosted.org/packages/2a/80/336820c1ad9286a4ded7e845b2eccfcb27851ab8ac6abece774a6ff4d3de/psutil-7.0.0.tar.gz", hash = "sha256:7be9c3eba38beccb6495ea33afd982a44074b78f28c434a1f51cc07fd315c456", size = 497003, upload-time = "2025-02-13T21:54:07.946Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ed/e6/2d26234410f8b8abdbf891c9da62bee396583f713fb9f3325a4760875d22/psutil-7.0.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:101d71dc322e3cffd7cea0650b09b3d08b8e7c4109dd6809fe452dfd00e58b25", size = 238051 }, - { url = "https://files.pythonhosted.org/packages/04/8b/30f930733afe425e3cbfc0e1468a30a18942350c1a8816acfade80c005c4/psutil-7.0.0-cp36-abi3-macosx_11_0_arm64.whl", hash = "sha256:39db632f6bb862eeccf56660871433e111b6ea58f2caea825571951d4b6aa3da", size = 239535 }, - { url = "https://files.pythonhosted.org/packages/2a/ed/d362e84620dd22876b55389248e522338ed1bf134a5edd3b8231d7207f6d/psutil-7.0.0-cp36-abi3-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1fcee592b4c6f146991ca55919ea3d1f8926497a713ed7faaf8225e174581e91", size = 275004 }, - { url = "https://files.pythonhosted.org/packages/bf/b9/b0eb3f3cbcb734d930fdf839431606844a825b23eaf9a6ab371edac8162c/psutil-7.0.0-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b1388a4f6875d7e2aff5c4ca1cc16c545ed41dd8bb596cefea80111db353a34", size = 277986 }, - { url = "https://files.pythonhosted.org/packages/eb/a2/709e0fe2f093556c17fbafda93ac032257242cabcc7ff3369e2cb76a97aa/psutil-7.0.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a5f098451abc2828f7dc6b58d44b532b22f2088f4999a937557b603ce72b1993", size = 279544 }, - { url = "https://files.pythonhosted.org/packages/50/e6/eecf58810b9d12e6427369784efe814a1eec0f492084ce8eb8f4d89d6d61/psutil-7.0.0-cp37-abi3-win32.whl", hash = "sha256:ba3fcef7523064a6c9da440fc4d6bd07da93ac726b5733c29027d7dc95b39d99", size = 241053 }, - { url = "https://files.pythonhosted.org/packages/50/1b/6921afe68c74868b4c9fa424dad3be35b095e16687989ebbb50ce4fceb7c/psutil-7.0.0-cp37-abi3-win_amd64.whl", hash = "sha256:4cf3d4eb1aa9b348dec30105c55cd9b7d4629285735a102beb4441e38db90553", size = 244885 }, + { url = "https://files.pythonhosted.org/packages/ed/e6/2d26234410f8b8abdbf891c9da62bee396583f713fb9f3325a4760875d22/psutil-7.0.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:101d71dc322e3cffd7cea0650b09b3d08b8e7c4109dd6809fe452dfd00e58b25", size = 238051, upload-time = "2025-02-13T21:54:12.36Z" }, + { url = "https://files.pythonhosted.org/packages/04/8b/30f930733afe425e3cbfc0e1468a30a18942350c1a8816acfade80c005c4/psutil-7.0.0-cp36-abi3-macosx_11_0_arm64.whl", hash = "sha256:39db632f6bb862eeccf56660871433e111b6ea58f2caea825571951d4b6aa3da", size = 239535, upload-time = "2025-02-13T21:54:16.07Z" }, + { url = "https://files.pythonhosted.org/packages/2a/ed/d362e84620dd22876b55389248e522338ed1bf134a5edd3b8231d7207f6d/psutil-7.0.0-cp36-abi3-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1fcee592b4c6f146991ca55919ea3d1f8926497a713ed7faaf8225e174581e91", size = 275004, upload-time = "2025-02-13T21:54:18.662Z" }, + { url = "https://files.pythonhosted.org/packages/bf/b9/b0eb3f3cbcb734d930fdf839431606844a825b23eaf9a6ab371edac8162c/psutil-7.0.0-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b1388a4f6875d7e2aff5c4ca1cc16c545ed41dd8bb596cefea80111db353a34", size = 277986, upload-time = "2025-02-13T21:54:21.811Z" }, + { url = "https://files.pythonhosted.org/packages/eb/a2/709e0fe2f093556c17fbafda93ac032257242cabcc7ff3369e2cb76a97aa/psutil-7.0.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a5f098451abc2828f7dc6b58d44b532b22f2088f4999a937557b603ce72b1993", size = 279544, upload-time = "2025-02-13T21:54:24.68Z" }, + { url = "https://files.pythonhosted.org/packages/50/e6/eecf58810b9d12e6427369784efe814a1eec0f492084ce8eb8f4d89d6d61/psutil-7.0.0-cp37-abi3-win32.whl", hash = "sha256:ba3fcef7523064a6c9da440fc4d6bd07da93ac726b5733c29027d7dc95b39d99", size = 241053, upload-time = "2025-02-13T21:54:34.31Z" }, + { url = "https://files.pythonhosted.org/packages/50/1b/6921afe68c74868b4c9fa424dad3be35b095e16687989ebbb50ce4fceb7c/psutil-7.0.0-cp37-abi3-win_amd64.whl", hash = "sha256:4cf3d4eb1aa9b348dec30105c55cd9b7d4629285735a102beb4441e38db90553", size = 244885, upload-time = "2025-02-13T21:54:37.486Z" }, ] [[package]] name = "pyarrow" -version = "19.0.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/7f/09/a9046344212690f0632b9c709f9bf18506522feb333c894d0de81d62341a/pyarrow-19.0.1.tar.gz", hash = "sha256:3bf266b485df66a400f282ac0b6d1b500b9d2ae73314a153dbe97d6d5cc8a99e", size = 1129437 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/a0/55/f1a8d838ec07fe3ca53edbe76f782df7b9aafd4417080eebf0b42aab0c52/pyarrow-19.0.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:cc55d71898ea30dc95900297d191377caba257612f384207fe9f8293b5850f90", size = 30713987 }, - { url = "https://files.pythonhosted.org/packages/13/12/428861540bb54c98a140ae858a11f71d041ef9e501e6b7eb965ca7909505/pyarrow-19.0.1-cp311-cp311-macosx_12_0_x86_64.whl", hash = "sha256:7a544ec12de66769612b2d6988c36adc96fb9767ecc8ee0a4d270b10b1c51e00", size = 32135613 }, - { url = "https://files.pythonhosted.org/packages/2f/8a/23d7cc5ae2066c6c736bce1db8ea7bc9ac3ef97ac7e1c1667706c764d2d9/pyarrow-19.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0148bb4fc158bfbc3d6dfe5001d93ebeed253793fff4435167f6ce1dc4bddeae", size = 41149147 }, - { url = "https://files.pythonhosted.org/packages/a2/7a/845d151bb81a892dfb368bf11db584cf8b216963ccce40a5cf50a2492a18/pyarrow-19.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f24faab6ed18f216a37870d8c5623f9c044566d75ec586ef884e13a02a9d62c5", size = 42178045 }, - { url = "https://files.pythonhosted.org/packages/a7/31/e7282d79a70816132cf6cae7e378adfccce9ae10352d21c2fecf9d9756dd/pyarrow-19.0.1-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:4982f8e2b7afd6dae8608d70ba5bd91699077323f812a0448d8b7abdff6cb5d3", size = 40532998 }, - { url = "https://files.pythonhosted.org/packages/b8/82/20f3c290d6e705e2ee9c1fa1d5a0869365ee477e1788073d8b548da8b64c/pyarrow-19.0.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:49a3aecb62c1be1d822f8bf629226d4a96418228a42f5b40835c1f10d42e4db6", size = 42084055 }, - { url = "https://files.pythonhosted.org/packages/ff/77/e62aebd343238863f2c9f080ad2ef6ace25c919c6ab383436b5b81cbeef7/pyarrow-19.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:008a4009efdb4ea3d2e18f05cd31f9d43c388aad29c636112c2966605ba33466", size = 25283133 }, - { url = "https://files.pythonhosted.org/packages/78/b4/94e828704b050e723f67d67c3535cf7076c7432cd4cf046e4bb3b96a9c9d/pyarrow-19.0.1-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:80b2ad2b193e7d19e81008a96e313fbd53157945c7be9ac65f44f8937a55427b", size = 30670749 }, - { url = "https://files.pythonhosted.org/packages/7e/3b/4692965e04bb1df55e2c314c4296f1eb12b4f3052d4cf43d29e076aedf66/pyarrow-19.0.1-cp312-cp312-macosx_12_0_x86_64.whl", hash = "sha256:ee8dec072569f43835932a3b10c55973593abc00936c202707a4ad06af7cb294", size = 32128007 }, - { url = "https://files.pythonhosted.org/packages/22/f7/2239af706252c6582a5635c35caa17cb4d401cd74a87821ef702e3888957/pyarrow-19.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d5d1ec7ec5324b98887bdc006f4d2ce534e10e60f7ad995e7875ffa0ff9cb14", size = 41144566 }, - { url = "https://files.pythonhosted.org/packages/fb/e3/c9661b2b2849cfefddd9fd65b64e093594b231b472de08ff658f76c732b2/pyarrow-19.0.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f3ad4c0eb4e2a9aeb990af6c09e6fa0b195c8c0e7b272ecc8d4d2b6574809d34", size = 42202991 }, - { url = "https://files.pythonhosted.org/packages/fe/4f/a2c0ed309167ef436674782dfee4a124570ba64299c551e38d3fdaf0a17b/pyarrow-19.0.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:d383591f3dcbe545f6cc62daaef9c7cdfe0dff0fb9e1c8121101cabe9098cfa6", size = 40507986 }, - { url = "https://files.pythonhosted.org/packages/27/2e/29bb28a7102a6f71026a9d70d1d61df926887e36ec797f2e6acfd2dd3867/pyarrow-19.0.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:b4c4156a625f1e35d6c0b2132635a237708944eb41df5fbe7d50f20d20c17832", size = 42087026 }, - { url = "https://files.pythonhosted.org/packages/16/33/2a67c0f783251106aeeee516f4806161e7b481f7d744d0d643d2f30230a5/pyarrow-19.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:5bd1618ae5e5476b7654c7b55a6364ae87686d4724538c24185bbb2952679960", size = 25250108 }, +version = "20.0.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a2/ee/a7810cb9f3d6e9238e61d312076a9859bf3668fd21c69744de9532383912/pyarrow-20.0.0.tar.gz", hash = "sha256:febc4a913592573c8d5805091a6c2b5064c8bd6e002131f01061797d91c783c1", size = 1125187, upload-time = "2025-04-27T12:34:23.264Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/47/a2/b7930824181ceadd0c63c1042d01fa4ef63eee233934826a7a2a9af6e463/pyarrow-20.0.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:24ca380585444cb2a31324c546a9a56abbe87e26069189e14bdba19c86c049f0", size = 30856035, upload-time = "2025-04-27T12:28:40.78Z" }, + { url = "https://files.pythonhosted.org/packages/9b/18/c765770227d7f5bdfa8a69f64b49194352325c66a5c3bb5e332dfd5867d9/pyarrow-20.0.0-cp311-cp311-macosx_12_0_x86_64.whl", hash = "sha256:95b330059ddfdc591a3225f2d272123be26c8fa76e8c9ee1a77aad507361cfdb", size = 32309552, upload-time = "2025-04-27T12:28:47.051Z" }, + { url = "https://files.pythonhosted.org/packages/44/fb/dfb2dfdd3e488bb14f822d7335653092dde150cffc2da97de6e7500681f9/pyarrow-20.0.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5f0fb1041267e9968c6d0d2ce3ff92e3928b243e2b6d11eeb84d9ac547308232", size = 41334704, upload-time = "2025-04-27T12:28:55.064Z" }, + { url = "https://files.pythonhosted.org/packages/58/0d/08a95878d38808051a953e887332d4a76bc06c6ee04351918ee1155407eb/pyarrow-20.0.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b8ff87cc837601532cc8242d2f7e09b4e02404de1b797aee747dd4ba4bd6313f", size = 42399836, upload-time = "2025-04-27T12:29:02.13Z" }, + { url = "https://files.pythonhosted.org/packages/f3/cd/efa271234dfe38f0271561086eedcad7bc0f2ddd1efba423916ff0883684/pyarrow-20.0.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:7a3a5dcf54286e6141d5114522cf31dd67a9e7c9133d150799f30ee302a7a1ab", size = 40711789, upload-time = "2025-04-27T12:29:09.951Z" }, + { url = "https://files.pythonhosted.org/packages/46/1f/7f02009bc7fc8955c391defee5348f510e589a020e4b40ca05edcb847854/pyarrow-20.0.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:a6ad3e7758ecf559900261a4df985662df54fb7fdb55e8e3b3aa99b23d526b62", size = 42301124, upload-time = "2025-04-27T12:29:17.187Z" }, + { url = "https://files.pythonhosted.org/packages/4f/92/692c562be4504c262089e86757a9048739fe1acb4024f92d39615e7bab3f/pyarrow-20.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6bb830757103a6cb300a04610e08d9636f0cd223d32f388418ea893a3e655f1c", size = 42916060, upload-time = "2025-04-27T12:29:24.253Z" }, + { url = "https://files.pythonhosted.org/packages/a4/ec/9f5c7e7c828d8e0a3c7ef50ee62eca38a7de2fa6eb1b8fa43685c9414fef/pyarrow-20.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:96e37f0766ecb4514a899d9a3554fadda770fb57ddf42b63d80f14bc20aa7db3", size = 44547640, upload-time = "2025-04-27T12:29:32.782Z" }, + { url = "https://files.pythonhosted.org/packages/54/96/46613131b4727f10fd2ffa6d0d6f02efcc09a0e7374eff3b5771548aa95b/pyarrow-20.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:3346babb516f4b6fd790da99b98bed9708e3f02e734c84971faccb20736848dc", size = 25781491, upload-time = "2025-04-27T12:29:38.464Z" }, + { url = "https://files.pythonhosted.org/packages/a1/d6/0c10e0d54f6c13eb464ee9b67a68b8c71bcf2f67760ef5b6fbcddd2ab05f/pyarrow-20.0.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:75a51a5b0eef32727a247707d4755322cb970be7e935172b6a3a9f9ae98404ba", size = 30815067, upload-time = "2025-04-27T12:29:44.384Z" }, + { url = "https://files.pythonhosted.org/packages/7e/e2/04e9874abe4094a06fd8b0cbb0f1312d8dd7d707f144c2ec1e5e8f452ffa/pyarrow-20.0.0-cp312-cp312-macosx_12_0_x86_64.whl", hash = "sha256:211d5e84cecc640c7a3ab900f930aaff5cd2702177e0d562d426fb7c4f737781", size = 32297128, upload-time = "2025-04-27T12:29:52.038Z" }, + { url = "https://files.pythonhosted.org/packages/31/fd/c565e5dcc906a3b471a83273039cb75cb79aad4a2d4a12f76cc5ae90a4b8/pyarrow-20.0.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4ba3cf4182828be7a896cbd232aa8dd6a31bd1f9e32776cc3796c012855e1199", size = 41334890, upload-time = "2025-04-27T12:29:59.452Z" }, + { url = "https://files.pythonhosted.org/packages/af/a9/3bdd799e2c9b20c1ea6dc6fa8e83f29480a97711cf806e823f808c2316ac/pyarrow-20.0.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c3a01f313ffe27ac4126f4c2e5ea0f36a5fc6ab51f8726cf41fee4b256680bd", size = 42421775, upload-time = "2025-04-27T12:30:06.875Z" }, + { url = "https://files.pythonhosted.org/packages/10/f7/da98ccd86354c332f593218101ae56568d5dcedb460e342000bd89c49cc1/pyarrow-20.0.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:a2791f69ad72addd33510fec7bb14ee06c2a448e06b649e264c094c5b5f7ce28", size = 40687231, upload-time = "2025-04-27T12:30:13.954Z" }, + { url = "https://files.pythonhosted.org/packages/bb/1b/2168d6050e52ff1e6cefc61d600723870bf569cbf41d13db939c8cf97a16/pyarrow-20.0.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:4250e28a22302ce8692d3a0e8ec9d9dde54ec00d237cff4dfa9c1fbf79e472a8", size = 42295639, upload-time = "2025-04-27T12:30:21.949Z" }, + { url = "https://files.pythonhosted.org/packages/b2/66/2d976c0c7158fd25591c8ca55aee026e6d5745a021915a1835578707feb3/pyarrow-20.0.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:89e030dc58fc760e4010148e6ff164d2f44441490280ef1e97a542375e41058e", size = 42908549, upload-time = "2025-04-27T12:30:29.551Z" }, + { url = "https://files.pythonhosted.org/packages/31/a9/dfb999c2fc6911201dcbf348247f9cc382a8990f9ab45c12eabfd7243a38/pyarrow-20.0.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:6102b4864d77102dbbb72965618e204e550135a940c2534711d5ffa787df2a5a", size = 44557216, upload-time = "2025-04-27T12:30:36.977Z" }, + { url = "https://files.pythonhosted.org/packages/a0/8e/9adee63dfa3911be2382fb4d92e4b2e7d82610f9d9f668493bebaa2af50f/pyarrow-20.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:96d6a0a37d9c98be08f5ed6a10831d88d52cac7b13f5287f1e0f625a0de8062b", size = 25660496, upload-time = "2025-04-27T12:30:42.809Z" }, ] [[package]] name = "pyaudio" version = "0.2.14" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/26/1d/8878c7752febb0f6716a7e1a52cb92ac98871c5aa522cba181878091607c/PyAudio-0.2.14.tar.gz", hash = "sha256:78dfff3879b4994d1f4fc6485646a57755c6ee3c19647a491f790a0895bd2f87", size = 47066 } +sdist = { url = "https://files.pythonhosted.org/packages/26/1d/8878c7752febb0f6716a7e1a52cb92ac98871c5aa522cba181878091607c/PyAudio-0.2.14.tar.gz", hash = "sha256:78dfff3879b4994d1f4fc6485646a57755c6ee3c19647a491f790a0895bd2f87", size = 47066, upload-time = "2023-11-07T07:11:48.806Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7b/f0/b0eab89eafa70a86b7b566a4df2f94c7880a2d483aa8de1c77d335335b5b/PyAudio-0.2.14-cp311-cp311-win32.whl", hash = "sha256:506b32a595f8693811682ab4b127602d404df7dfc453b499c91a80d0f7bad289", size = 144624 }, - { url = "https://files.pythonhosted.org/packages/82/d8/f043c854aad450a76e476b0cf9cda1956419e1dacf1062eb9df3c0055abe/PyAudio-0.2.14-cp311-cp311-win_amd64.whl", hash = "sha256:bbeb01d36a2f472ae5ee5e1451cacc42112986abe622f735bb870a5db77cf903", size = 164070 }, - { url = "https://files.pythonhosted.org/packages/8d/45/8d2b76e8f6db783f9326c1305f3f816d4a12c8eda5edc6a2e1d03c097c3b/PyAudio-0.2.14-cp312-cp312-win32.whl", hash = "sha256:5fce4bcdd2e0e8c063d835dbe2860dac46437506af509353c7f8114d4bacbd5b", size = 144750 }, - { url = "https://files.pythonhosted.org/packages/b0/6a/d25812e5f79f06285767ec607b39149d02aa3b31d50c2269768f48768930/PyAudio-0.2.14-cp312-cp312-win_amd64.whl", hash = "sha256:12f2f1ba04e06ff95d80700a78967897a489c05e093e3bffa05a84ed9c0a7fa3", size = 164126 }, + { url = "https://files.pythonhosted.org/packages/7b/f0/b0eab89eafa70a86b7b566a4df2f94c7880a2d483aa8de1c77d335335b5b/PyAudio-0.2.14-cp311-cp311-win32.whl", hash = "sha256:506b32a595f8693811682ab4b127602d404df7dfc453b499c91a80d0f7bad289", size = 144624, upload-time = "2023-11-07T07:11:36.94Z" }, + { url = "https://files.pythonhosted.org/packages/82/d8/f043c854aad450a76e476b0cf9cda1956419e1dacf1062eb9df3c0055abe/PyAudio-0.2.14-cp311-cp311-win_amd64.whl", hash = "sha256:bbeb01d36a2f472ae5ee5e1451cacc42112986abe622f735bb870a5db77cf903", size = 164070, upload-time = "2023-11-07T07:11:38.579Z" }, + { url = "https://files.pythonhosted.org/packages/8d/45/8d2b76e8f6db783f9326c1305f3f816d4a12c8eda5edc6a2e1d03c097c3b/PyAudio-0.2.14-cp312-cp312-win32.whl", hash = "sha256:5fce4bcdd2e0e8c063d835dbe2860dac46437506af509353c7f8114d4bacbd5b", size = 144750, upload-time = "2023-11-07T07:11:40.142Z" }, + { url = "https://files.pythonhosted.org/packages/b0/6a/d25812e5f79f06285767ec607b39149d02aa3b31d50c2269768f48768930/PyAudio-0.2.14-cp312-cp312-win_amd64.whl", hash = "sha256:12f2f1ba04e06ff95d80700a78967897a489c05e093e3bffa05a84ed9c0a7fa3", size = 164126, upload-time = "2023-11-07T07:11:41.539Z" }, ] [[package]] @@ -1666,103 +1691,104 @@ dependencies = [ { name = "python3-xlib", marker = "sys_platform == 'linux'" }, { name = "pytweening" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/65/ff/cdae0a8c2118a0de74b6cf4cbcdcaf8fd25857e6c3f205ce4b1794b27814/PyAutoGUI-0.9.54.tar.gz", hash = "sha256:dd1d29e8fd118941cb193f74df57e5c6ff8e9253b99c7b04f39cfc69f3ae04b2", size = 61236 } +sdist = { url = "https://files.pythonhosted.org/packages/65/ff/cdae0a8c2118a0de74b6cf4cbcdcaf8fd25857e6c3f205ce4b1794b27814/PyAutoGUI-0.9.54.tar.gz", hash = "sha256:dd1d29e8fd118941cb193f74df57e5c6ff8e9253b99c7b04f39cfc69f3ae04b2", size = 61236, upload-time = "2023-05-24T20:11:32.972Z" } [[package]] name = "pycapnp" version = "2.0.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/9b/fb/54b46b52c1fa2acd9afd81bd05810c61bb1b05c6084c9625b64bc6d41843/pycapnp-2.0.0.tar.gz", hash = "sha256:503ab9b7b16773590ee226f2460408972c6b1c2cb2d819037115b919bef682be", size = 574848 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/cb/82/cf311b1a9800b605759a38a0c337a55a639b685427364294e98a0f9b7306/pycapnp-2.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:829c7eb4e5f23dbcac25466110faf72a691035cf87c5d46e5053da15790e428d", size = 1673673 }, - { url = "https://files.pythonhosted.org/packages/ae/55/4c03ca95c568776a1f637db9ffdcf302fb63f46e4d2a4f13edd8cb1a5f90/pycapnp-2.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:dab60fbe3e4eaf99ec97918a0a776216c6c149b6d49261383d91c2201adb475d", size = 1513351 }, - { url = "https://files.pythonhosted.org/packages/55/98/e4b2dea076f8a2575abc45cd879a91bc9aa975c69ae2ac1cab61d83c5087/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c48a0582078bb74d7326d28571db0b8e6919563365537a5a13e8f5360c12bfc", size = 4910666 }, - { url = "https://files.pythonhosted.org/packages/1d/ee/3b5a182588f89074f4002fa6247e3f963bb85bc808acd1ac8deed91f1fa7/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bcb5ab54aff857e3711d2c0cc934194aaffacdeb3481daa56863daef07d27941", size = 5007434 }, - { url = "https://files.pythonhosted.org/packages/c5/e9/515a2ca7fdc84d57c654280d0b71dfd782fd1773d384c0ec0d56dc6fc35b/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9600778036e6fe9dbea68f0c37678c5f4d561d2f2306b3cb741de5e1670ef2ae", size = 5188923 }, - { url = "https://files.pythonhosted.org/packages/70/60/5db346e238985a526ba7589ed24f92195dad39e7dec9d85b17a567600b6f/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7278ba0262fab8c398e77d634ae7ba026866d44b52cbfc27262be8d396ecacd1", size = 5048105 }, - { url = "https://files.pythonhosted.org/packages/e3/ff/02b4a87c9ff9793f26d8f3d95312d902d260c094f216d84e19528a506606/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:23b2458d43c82302980a96518c96df257429204d2cc02bfff0c8cb6ebb371e01", size = 5063172 }, - { url = "https://files.pythonhosted.org/packages/10/a1/35a7e14d765f99cfdcdfdcebc69bdf382f27016944470daa7a03c557f681/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:dd7755cc3fedc2ad8cc7864a0729471ddeff10c184963fe0f3689e295130f1b2", size = 5408718 }, - { url = "https://files.pythonhosted.org/packages/5c/59/8bc8a993c38808c6fd90b10becba8de4a54543e8441bd87ce44ef3b7eee4/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:d47baf6b3db9981625ffc5ff188e089f2ebca8e7e1afb97aa5eb7bebb7bf3650", size = 5596714 }, - { url = "https://files.pythonhosted.org/packages/ea/7d/79c481ef77f29e81355e92bb250f0d2a37a76f5fe0ba9433bf6c6c88b6e4/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:b375be92d93fdb6f7ac127ea9390bcec0fed4e485db137b084f9e7114dde7c83", size = 5709896 }, - { url = "https://files.pythonhosted.org/packages/59/8d/f2eceeea1e8cae8b8a70a4752af5b772916f455e2ed388d0887e2b57d080/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:959bfdf1cddb3e5528e2293c4a375382be9a1bf044b073bc2e7eca1eb6b3a9a2", size = 5594823 }, - { url = "https://files.pythonhosted.org/packages/2c/86/f8284637b61f83232e5618dd561a66080dd98ce2272d7e3ae89335d4fd97/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:d873af167cf5cc7578ce5432eefcb442f866c8f7a6c57d188baf8c5e709fa39d", size = 5572564 }, - { url = "https://files.pythonhosted.org/packages/b3/b2/7f99d28a9935d1e37ec6955922c57b2be24fe0b74fe25929643686cc11e5/pycapnp-2.0.0-cp311-cp311-win32.whl", hash = "sha256:40ca8018e0b7686d549b920f087049b92a3e6f06976d9f5a8112603fc560cac4", size = 1040268 }, - { url = "https://files.pythonhosted.org/packages/1d/37/89ab98961f18cffeae20d98cfc24afcfa85024bc014ecc48b0c4ac264fe0/pycapnp-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:d15cd8e46d541a899c84809095d7d7b3951f43642d1859e7a39bd91910778479", size = 1141758 }, - { url = "https://files.pythonhosted.org/packages/ce/d5/0ee84de3ce34a86c373b6cfbea17d5486c2ca942d51efa99a0069723c1e3/pycapnp-2.0.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:0c111ef96676df25b8afef98f369d45f838ad4434e2898e48199eb43ef704efe", size = 1645816 }, - { url = "https://files.pythonhosted.org/packages/35/1e/580572083165ba791fac5ae2d8917facb94db6e3f0500421673f55165dac/pycapnp-2.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0d18906eb1fd1b9f206d93a9591ceedce1d52e7766b66e68f271453f104e9dca", size = 1507892 }, - { url = "https://files.pythonhosted.org/packages/d7/ed/46b3cc5d32c525b6a3acb67eb43de2cec692a62775ec1ab66dafe2b7d6ad/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f5d1ed365ab1beabb8838068907a7190cc0b6f16de3499d783627e670fcc0eb2", size = 4707960 }, - { url = "https://files.pythonhosted.org/packages/8e/51/0a0a4d4e44138adb84959478ea4966196c5ad32022f768b9b64d1590cb3e/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:495b39a7aa2629931bbca27ad743ce591c6c41e8f81792276be424742d9cd1c1", size = 4791780 }, - { url = "https://files.pythonhosted.org/packages/28/71/2b59c6ddb253b25b3d01ee6f7b32b0297ac205c7272beeb6d13399054430/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:50e814fbde072dcc3d868b5b5cbb9b7a66a70bff9ad03942f3be9baf3ca1cfc6", size = 4961068 }, - { url = "https://files.pythonhosted.org/packages/c3/b8/b64fdefa59d6d2802b5ee0a9439396c23a3e5954da6909be81f2722a234c/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:920fdda62d5fdef7a48339104dff0ceb9dcc21b138491f854457ba3a3d4d63ec", size = 4872917 }, - { url = "https://files.pythonhosted.org/packages/c8/55/867595f575eb6cb3662e9a0b50a24b4be42df86f2938003e586f6c81606f/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3f9142eb4714c152b09dda0b055ea9dd43fd8fd894132e7eb4fa235fb4915edd", size = 4912169 }, - { url = "https://files.pythonhosted.org/packages/e4/11/0d36b45e5005ecdf8510081d16c6fb7b22b49651f64af36d138df97980cc/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:c98f1d0c4d32109d03e42828ce3c65236afc895033633cbed3ca092993702e7b", size = 5201744 }, - { url = "https://files.pythonhosted.org/packages/05/29/ad1357998656b7141939e55bb3aea727c7a5478026feed7f8ee8cf52c935/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:4d3250c1875a309d67551843cd8bf3c5e7fccf159b7f5c118a92aee36c0e871c", size = 5351113 }, - { url = "https://files.pythonhosted.org/packages/5a/b1/f4c442907948a29b6427dd7436f31d3732bb0d77f5c1dbcad749ba56dac0/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:174e6babe01f5507111c0ed226cd0b5e9325a9d2850751cfe4a57c1670f13881", size = 5472055 }, - { url = "https://files.pythonhosted.org/packages/c1/06/a6eceb8b8015f518c0ccae1de5d1a6e18ed73b62b4b111aff54ce5f4f566/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:ed38ece414341285695526792e020f391f29f5064b2126d0367c8bdeef28e3e9", size = 5395743 }, - { url = "https://files.pythonhosted.org/packages/e7/b0/63f2b0327853ae08158de61b4dfc7fa43ae5a5c00f1d28f769e7c30cdf55/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8a20b7dc55ef83a1fa446bf12680bce25caeb8f81788b623b072c3ec820db50d", size = 5405076 }, - { url = "https://files.pythonhosted.org/packages/7d/24/e025dd95f1abf34e373fbab8841ac8e5fa62afe3af4a4b0c61bd01354400/pycapnp-2.0.0-cp312-cp312-win32.whl", hash = "sha256:145eea66233fb5ac9152cd1c06b999ddb691815126f87f5cc37b9cda5d569f8a", size = 1030361 }, - { url = "https://files.pythonhosted.org/packages/3f/70/a71108ee9d4db9a027b665a2c383202407207174f1956195d5be45aca705/pycapnp-2.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:b8b03000769b29b36a8810f458b931f0f706f42027ee6676821eff28092d7734", size = 1135121 }, +sdist = { url = "https://files.pythonhosted.org/packages/9b/fb/54b46b52c1fa2acd9afd81bd05810c61bb1b05c6084c9625b64bc6d41843/pycapnp-2.0.0.tar.gz", hash = "sha256:503ab9b7b16773590ee226f2460408972c6b1c2cb2d819037115b919bef682be", size = 574848, upload-time = "2024-04-12T15:35:44.019Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/cb/82/cf311b1a9800b605759a38a0c337a55a639b685427364294e98a0f9b7306/pycapnp-2.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:829c7eb4e5f23dbcac25466110faf72a691035cf87c5d46e5053da15790e428d", size = 1673673, upload-time = "2024-04-12T15:33:32.211Z" }, + { url = "https://files.pythonhosted.org/packages/ae/55/4c03ca95c568776a1f637db9ffdcf302fb63f46e4d2a4f13edd8cb1a5f90/pycapnp-2.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:dab60fbe3e4eaf99ec97918a0a776216c6c149b6d49261383d91c2201adb475d", size = 1513351, upload-time = "2024-04-12T15:33:35.156Z" }, + { url = "https://files.pythonhosted.org/packages/55/98/e4b2dea076f8a2575abc45cd879a91bc9aa975c69ae2ac1cab61d83c5087/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c48a0582078bb74d7326d28571db0b8e6919563365537a5a13e8f5360c12bfc", size = 4910666, upload-time = "2024-04-12T15:33:37.798Z" }, + { url = "https://files.pythonhosted.org/packages/1d/ee/3b5a182588f89074f4002fa6247e3f963bb85bc808acd1ac8deed91f1fa7/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bcb5ab54aff857e3711d2c0cc934194aaffacdeb3481daa56863daef07d27941", size = 5007434, upload-time = "2024-04-12T15:33:40.362Z" }, + { url = "https://files.pythonhosted.org/packages/c5/e9/515a2ca7fdc84d57c654280d0b71dfd782fd1773d384c0ec0d56dc6fc35b/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9600778036e6fe9dbea68f0c37678c5f4d561d2f2306b3cb741de5e1670ef2ae", size = 5188923, upload-time = "2024-04-12T15:33:42.33Z" }, + { url = "https://files.pythonhosted.org/packages/70/60/5db346e238985a526ba7589ed24f92195dad39e7dec9d85b17a567600b6f/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7278ba0262fab8c398e77d634ae7ba026866d44b52cbfc27262be8d396ecacd1", size = 5048105, upload-time = "2024-04-12T15:33:44.294Z" }, + { url = "https://files.pythonhosted.org/packages/e3/ff/02b4a87c9ff9793f26d8f3d95312d902d260c094f216d84e19528a506606/pycapnp-2.0.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:23b2458d43c82302980a96518c96df257429204d2cc02bfff0c8cb6ebb371e01", size = 5063172, upload-time = "2024-04-12T15:33:46.954Z" }, + { url = "https://files.pythonhosted.org/packages/10/a1/35a7e14d765f99cfdcdfdcebc69bdf382f27016944470daa7a03c557f681/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:dd7755cc3fedc2ad8cc7864a0729471ddeff10c184963fe0f3689e295130f1b2", size = 5408718, upload-time = "2024-04-12T15:33:49.587Z" }, + { url = "https://files.pythonhosted.org/packages/5c/59/8bc8a993c38808c6fd90b10becba8de4a54543e8441bd87ce44ef3b7eee4/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:d47baf6b3db9981625ffc5ff188e089f2ebca8e7e1afb97aa5eb7bebb7bf3650", size = 5596714, upload-time = "2024-04-12T15:33:51.518Z" }, + { url = "https://files.pythonhosted.org/packages/ea/7d/79c481ef77f29e81355e92bb250f0d2a37a76f5fe0ba9433bf6c6c88b6e4/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:b375be92d93fdb6f7ac127ea9390bcec0fed4e485db137b084f9e7114dde7c83", size = 5709896, upload-time = "2024-04-12T15:33:53.716Z" }, + { url = "https://files.pythonhosted.org/packages/59/8d/f2eceeea1e8cae8b8a70a4752af5b772916f455e2ed388d0887e2b57d080/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:959bfdf1cddb3e5528e2293c4a375382be9a1bf044b073bc2e7eca1eb6b3a9a2", size = 5594823, upload-time = "2024-04-12T15:33:55.573Z" }, + { url = "https://files.pythonhosted.org/packages/2c/86/f8284637b61f83232e5618dd561a66080dd98ce2272d7e3ae89335d4fd97/pycapnp-2.0.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:d873af167cf5cc7578ce5432eefcb442f866c8f7a6c57d188baf8c5e709fa39d", size = 5572564, upload-time = "2024-04-12T15:33:59.112Z" }, + { url = "https://files.pythonhosted.org/packages/b3/b2/7f99d28a9935d1e37ec6955922c57b2be24fe0b74fe25929643686cc11e5/pycapnp-2.0.0-cp311-cp311-win32.whl", hash = "sha256:40ca8018e0b7686d549b920f087049b92a3e6f06976d9f5a8112603fc560cac4", size = 1040268, upload-time = "2024-04-12T15:34:00.933Z" }, + { url = "https://files.pythonhosted.org/packages/1d/37/89ab98961f18cffeae20d98cfc24afcfa85024bc014ecc48b0c4ac264fe0/pycapnp-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:d15cd8e46d541a899c84809095d7d7b3951f43642d1859e7a39bd91910778479", size = 1141758, upload-time = "2024-04-12T15:34:02.607Z" }, + { url = "https://files.pythonhosted.org/packages/ce/d5/0ee84de3ce34a86c373b6cfbea17d5486c2ca942d51efa99a0069723c1e3/pycapnp-2.0.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:0c111ef96676df25b8afef98f369d45f838ad4434e2898e48199eb43ef704efe", size = 1645816, upload-time = "2024-04-12T15:34:04.428Z" }, + { url = "https://files.pythonhosted.org/packages/35/1e/580572083165ba791fac5ae2d8917facb94db6e3f0500421673f55165dac/pycapnp-2.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0d18906eb1fd1b9f206d93a9591ceedce1d52e7766b66e68f271453f104e9dca", size = 1507892, upload-time = "2024-04-12T15:34:06.933Z" }, + { url = "https://files.pythonhosted.org/packages/d7/ed/46b3cc5d32c525b6a3acb67eb43de2cec692a62775ec1ab66dafe2b7d6ad/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f5d1ed365ab1beabb8838068907a7190cc0b6f16de3499d783627e670fcc0eb2", size = 4707960, upload-time = "2024-04-12T15:34:08.771Z" }, + { url = "https://files.pythonhosted.org/packages/8e/51/0a0a4d4e44138adb84959478ea4966196c5ad32022f768b9b64d1590cb3e/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:495b39a7aa2629931bbca27ad743ce591c6c41e8f81792276be424742d9cd1c1", size = 4791780, upload-time = "2024-04-12T15:34:10.863Z" }, + { url = "https://files.pythonhosted.org/packages/28/71/2b59c6ddb253b25b3d01ee6f7b32b0297ac205c7272beeb6d13399054430/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:50e814fbde072dcc3d868b5b5cbb9b7a66a70bff9ad03942f3be9baf3ca1cfc6", size = 4961068, upload-time = "2024-04-12T15:34:13.543Z" }, + { url = "https://files.pythonhosted.org/packages/c3/b8/b64fdefa59d6d2802b5ee0a9439396c23a3e5954da6909be81f2722a234c/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:920fdda62d5fdef7a48339104dff0ceb9dcc21b138491f854457ba3a3d4d63ec", size = 4872917, upload-time = "2024-04-12T15:34:15.636Z" }, + { url = "https://files.pythonhosted.org/packages/c8/55/867595f575eb6cb3662e9a0b50a24b4be42df86f2938003e586f6c81606f/pycapnp-2.0.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3f9142eb4714c152b09dda0b055ea9dd43fd8fd894132e7eb4fa235fb4915edd", size = 4912169, upload-time = "2024-04-12T15:34:17.758Z" }, + { url = "https://files.pythonhosted.org/packages/e4/11/0d36b45e5005ecdf8510081d16c6fb7b22b49651f64af36d138df97980cc/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:c98f1d0c4d32109d03e42828ce3c65236afc895033633cbed3ca092993702e7b", size = 5201744, upload-time = "2024-04-12T15:34:20.468Z" }, + { url = "https://files.pythonhosted.org/packages/05/29/ad1357998656b7141939e55bb3aea727c7a5478026feed7f8ee8cf52c935/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:4d3250c1875a309d67551843cd8bf3c5e7fccf159b7f5c118a92aee36c0e871c", size = 5351113, upload-time = "2024-04-12T15:34:23.173Z" }, + { url = "https://files.pythonhosted.org/packages/5a/b1/f4c442907948a29b6427dd7436f31d3732bb0d77f5c1dbcad749ba56dac0/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:174e6babe01f5507111c0ed226cd0b5e9325a9d2850751cfe4a57c1670f13881", size = 5472055, upload-time = "2024-04-12T15:34:25.799Z" }, + { url = "https://files.pythonhosted.org/packages/c1/06/a6eceb8b8015f518c0ccae1de5d1a6e18ed73b62b4b111aff54ce5f4f566/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:ed38ece414341285695526792e020f391f29f5064b2126d0367c8bdeef28e3e9", size = 5395743, upload-time = "2024-04-12T15:34:28.134Z" }, + { url = "https://files.pythonhosted.org/packages/e7/b0/63f2b0327853ae08158de61b4dfc7fa43ae5a5c00f1d28f769e7c30cdf55/pycapnp-2.0.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8a20b7dc55ef83a1fa446bf12680bce25caeb8f81788b623b072c3ec820db50d", size = 5405076, upload-time = "2024-04-12T15:34:30.305Z" }, + { url = "https://files.pythonhosted.org/packages/7d/24/e025dd95f1abf34e373fbab8841ac8e5fa62afe3af4a4b0c61bd01354400/pycapnp-2.0.0-cp312-cp312-win32.whl", hash = "sha256:145eea66233fb5ac9152cd1c06b999ddb691815126f87f5cc37b9cda5d569f8a", size = 1030361, upload-time = "2024-04-12T15:34:32.25Z" }, + { url = "https://files.pythonhosted.org/packages/3f/70/a71108ee9d4db9a027b665a2c383202407207174f1956195d5be45aca705/pycapnp-2.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:b8b03000769b29b36a8810f458b931f0f706f42027ee6676821eff28092d7734", size = 1135121, upload-time = "2024-04-12T15:34:34.208Z" }, ] [[package]] name = "pycparser" version = "2.22" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1d/b2/31537cf4b1ca988837256c910a668b553fceb8f069bedc4b1c826024b52c/pycparser-2.22.tar.gz", hash = "sha256:491c8be9c040f5390f5bf44a5b07752bd07f56edf992381b05c701439eec10f6", size = 172736 } +sdist = { url = "https://files.pythonhosted.org/packages/1d/b2/31537cf4b1ca988837256c910a668b553fceb8f069bedc4b1c826024b52c/pycparser-2.22.tar.gz", hash = "sha256:491c8be9c040f5390f5bf44a5b07752bd07f56edf992381b05c701439eec10f6", size = 172736, upload-time = "2024-03-30T13:22:22.564Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/13/a3/a812df4e2dd5696d1f351d58b8fe16a405b234ad2886a0dab9183fb78109/pycparser-2.22-py3-none-any.whl", hash = "sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc", size = 117552 }, + { url = "https://files.pythonhosted.org/packages/13/a3/a812df4e2dd5696d1f351d58b8fe16a405b234ad2886a0dab9183fb78109/pycparser-2.22-py3-none-any.whl", hash = "sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc", size = 117552, upload-time = "2024-03-30T13:22:20.476Z" }, ] [[package]] name = "pycryptodome" -version = "3.21.0" +version = "3.23.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/13/52/13b9db4a913eee948152a079fe58d035bd3d1a519584155da8e786f767e6/pycryptodome-3.21.0.tar.gz", hash = "sha256:f7787e0d469bdae763b876174cf2e6c0f7be79808af26b1da96f1a64bcf47297", size = 4818071 } +sdist = { url = "https://files.pythonhosted.org/packages/8e/a6/8452177684d5e906854776276ddd34eca30d1b1e15aa1ee9cefc289a33f5/pycryptodome-3.23.0.tar.gz", hash = "sha256:447700a657182d60338bab09fdb27518f8856aecd80ae4c6bdddb67ff5da44ef", size = 4921276, upload-time = "2025-05-17T17:21:45.242Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a7/88/5e83de10450027c96c79dc65ac45e9d0d7a7fef334f39d3789a191f33602/pycryptodome-3.21.0-cp36-abi3-macosx_10_9_universal2.whl", hash = "sha256:2480ec2c72438430da9f601ebc12c518c093c13111a5c1644c82cdfc2e50b1e4", size = 2495937 }, - { url = "https://files.pythonhosted.org/packages/66/e1/8f28cd8cf7f7563319819d1e172879ccce2333781ae38da61c28fe22d6ff/pycryptodome-3.21.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:de18954104667f565e2fbb4783b56667f30fb49c4d79b346f52a29cb198d5b6b", size = 1634629 }, - { url = "https://files.pythonhosted.org/packages/6a/c1/f75a1aaff0c20c11df8dc8e2bf8057e7f73296af7dfd8cbb40077d1c930d/pycryptodome-3.21.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2de4b7263a33947ff440412339cb72b28a5a4c769b5c1ca19e33dd6cd1dcec6e", size = 2168708 }, - { url = "https://files.pythonhosted.org/packages/ea/66/6f2b7ddb457b19f73b82053ecc83ba768680609d56dd457dbc7e902c41aa/pycryptodome-3.21.0-cp36-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0714206d467fc911042d01ea3a1847c847bc10884cf674c82e12915cfe1649f8", size = 2254555 }, - { url = "https://files.pythonhosted.org/packages/2c/2b/152c330732a887a86cbf591ed69bd1b489439b5464806adb270f169ec139/pycryptodome-3.21.0-cp36-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7d85c1b613121ed3dbaa5a97369b3b757909531a959d229406a75b912dd51dd1", size = 2294143 }, - { url = "https://files.pythonhosted.org/packages/55/92/517c5c498c2980c1b6d6b9965dffbe31f3cd7f20f40d00ec4069559c5902/pycryptodome-3.21.0-cp36-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:8898a66425a57bcf15e25fc19c12490b87bd939800f39a03ea2de2aea5e3611a", size = 2160509 }, - { url = "https://files.pythonhosted.org/packages/39/1f/c74288f54d80a20a78da87df1818c6464ac1041d10988bb7d982c4153fbc/pycryptodome-3.21.0-cp36-abi3-musllinux_1_2_i686.whl", hash = "sha256:932c905b71a56474bff8a9c014030bc3c882cee696b448af920399f730a650c2", size = 2329480 }, - { url = "https://files.pythonhosted.org/packages/39/1b/d0b013bf7d1af7cf0a6a4fce13f5fe5813ab225313755367b36e714a63f8/pycryptodome-3.21.0-cp36-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:18caa8cfbc676eaaf28613637a89980ad2fd96e00c564135bf90bc3f0b34dd93", size = 2254397 }, - { url = "https://files.pythonhosted.org/packages/14/71/4cbd3870d3e926c34706f705d6793159ac49d9a213e3ababcdade5864663/pycryptodome-3.21.0-cp36-abi3-win32.whl", hash = "sha256:280b67d20e33bb63171d55b1067f61fbd932e0b1ad976b3a184303a3dad22764", size = 1775641 }, - { url = "https://files.pythonhosted.org/packages/43/1d/81d59d228381576b92ecede5cd7239762c14001a828bdba30d64896e9778/pycryptodome-3.21.0-cp36-abi3-win_amd64.whl", hash = "sha256:b7aa25fc0baa5b1d95b7633af4f5f1838467f1815442b22487426f94e0d66c53", size = 1812863 }, + { url = "https://files.pythonhosted.org/packages/db/6c/a1f71542c969912bb0e106f64f60a56cc1f0fabecf9396f45accbe63fa68/pycryptodome-3.23.0-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:187058ab80b3281b1de11c2e6842a357a1f71b42cb1e15bce373f3d238135c27", size = 2495627, upload-time = "2025-05-17T17:20:47.139Z" }, + { url = "https://files.pythonhosted.org/packages/6e/4e/a066527e079fc5002390c8acdd3aca431e6ea0a50ffd7201551175b47323/pycryptodome-3.23.0-cp37-abi3-macosx_10_9_x86_64.whl", hash = "sha256:cfb5cd445280c5b0a4e6187a7ce8de5a07b5f3f897f235caa11f1f435f182843", size = 1640362, upload-time = "2025-05-17T17:20:50.392Z" }, + { url = "https://files.pythonhosted.org/packages/50/52/adaf4c8c100a8c49d2bd058e5b551f73dfd8cb89eb4911e25a0c469b6b4e/pycryptodome-3.23.0-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:67bd81fcbe34f43ad9422ee8fd4843c8e7198dd88dd3d40e6de42ee65fbe1490", size = 2182625, upload-time = "2025-05-17T17:20:52.866Z" }, + { url = "https://files.pythonhosted.org/packages/5f/e9/a09476d436d0ff1402ac3867d933c61805ec2326c6ea557aeeac3825604e/pycryptodome-3.23.0-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c8987bd3307a39bc03df5c8e0e3d8be0c4c3518b7f044b0f4c15d1aa78f52575", size = 2268954, upload-time = "2025-05-17T17:20:55.027Z" }, + { url = "https://files.pythonhosted.org/packages/f9/c5/ffe6474e0c551d54cab931918127c46d70cab8f114e0c2b5a3c071c2f484/pycryptodome-3.23.0-cp37-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aa0698f65e5b570426fc31b8162ed4603b0c2841cbb9088e2b01641e3065915b", size = 2308534, upload-time = "2025-05-17T17:20:57.279Z" }, + { url = "https://files.pythonhosted.org/packages/18/28/e199677fc15ecf43010f2463fde4c1a53015d1fe95fb03bca2890836603a/pycryptodome-3.23.0-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:53ecbafc2b55353edcebd64bf5da94a2a2cdf5090a6915bcca6eca6cc452585a", size = 2181853, upload-time = "2025-05-17T17:20:59.322Z" }, + { url = "https://files.pythonhosted.org/packages/ce/ea/4fdb09f2165ce1365c9eaefef36625583371ee514db58dc9b65d3a255c4c/pycryptodome-3.23.0-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:156df9667ad9f2ad26255926524e1c136d6664b741547deb0a86a9acf5ea631f", size = 2342465, upload-time = "2025-05-17T17:21:03.83Z" }, + { url = "https://files.pythonhosted.org/packages/22/82/6edc3fc42fe9284aead511394bac167693fb2b0e0395b28b8bedaa07ef04/pycryptodome-3.23.0-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:dea827b4d55ee390dc89b2afe5927d4308a8b538ae91d9c6f7a5090f397af1aa", size = 2267414, upload-time = "2025-05-17T17:21:06.72Z" }, + { url = "https://files.pythonhosted.org/packages/59/fe/aae679b64363eb78326c7fdc9d06ec3de18bac68be4b612fc1fe8902693c/pycryptodome-3.23.0-cp37-abi3-win32.whl", hash = "sha256:507dbead45474b62b2bbe318eb1c4c8ee641077532067fec9c1aa82c31f84886", size = 1768484, upload-time = "2025-05-17T17:21:08.535Z" }, + { url = "https://files.pythonhosted.org/packages/54/2f/e97a1b8294db0daaa87012c24a7bb714147c7ade7656973fd6c736b484ff/pycryptodome-3.23.0-cp37-abi3-win_amd64.whl", hash = "sha256:c75b52aacc6c0c260f204cbdd834f76edc9fb0d8e0da9fbf8352ef58202564e2", size = 1799636, upload-time = "2025-05-17T17:21:10.393Z" }, + { url = "https://files.pythonhosted.org/packages/18/3d/f9441a0d798bf2b1e645adc3265e55706aead1255ccdad3856dbdcffec14/pycryptodome-3.23.0-cp37-abi3-win_arm64.whl", hash = "sha256:11eeeb6917903876f134b56ba11abe95c0b0fd5e3330def218083c7d98bbcb3c", size = 1703675, upload-time = "2025-05-17T17:21:13.146Z" }, ] [[package]] name = "pyee" -version = "12.1.1" +version = "13.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0a/37/8fb6e653597b2b67ef552ed49b438d5398ba3b85a9453f8ada0fd77d455c/pyee-12.1.1.tar.gz", hash = "sha256:bbc33c09e2ff827f74191e3e5bbc6be7da02f627b7ec30d86f5ce1a6fb2424a3", size = 30915 } +sdist = { url = "https://files.pythonhosted.org/packages/95/03/1fd98d5841cd7964a27d729ccf2199602fe05eb7a405c1462eb7277945ed/pyee-13.0.0.tar.gz", hash = "sha256:b391e3c5a434d1f5118a25615001dbc8f669cf410ab67d04c4d4e07c55481c37", size = 31250, upload-time = "2025-03-17T18:53:15.955Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/25/68/7e150cba9eeffdeb3c5cecdb6896d70c8edd46ce41c0491e12fb2b2256ff/pyee-12.1.1-py3-none-any.whl", hash = "sha256:18a19c650556bb6b32b406d7f017c8f513aceed1ef7ca618fb65de7bd2d347ef", size = 15527 }, + { url = "https://files.pythonhosted.org/packages/9b/4d/b9add7c84060d4c1906abe9a7e5359f2a60f7a9a4f67268b2766673427d8/pyee-13.0.0-py3-none-any.whl", hash = "sha256:48195a3cddb3b1515ce0695ed76036b5ccc2ef3a9f963ff9f77aec0139845498", size = 15730, upload-time = "2025-03-17T18:53:14.532Z" }, ] [[package]] name = "pygame" version = "2.6.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/49/cc/08bba60f00541f62aaa252ce0cfbd60aebd04616c0b9574f755b583e45ae/pygame-2.6.1.tar.gz", hash = "sha256:56fb02ead529cee00d415c3e007f75e0780c655909aaa8e8bf616ee09c9feb1f", size = 14808125 } +sdist = { url = "https://files.pythonhosted.org/packages/49/cc/08bba60f00541f62aaa252ce0cfbd60aebd04616c0b9574f755b583e45ae/pygame-2.6.1.tar.gz", hash = "sha256:56fb02ead529cee00d415c3e007f75e0780c655909aaa8e8bf616ee09c9feb1f", size = 14808125, upload-time = "2024-09-29T13:41:34.698Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c4/ca/8f367cb9fe734c4f6f6400e045593beea2635cd736158f9fabf58ee14e3c/pygame-2.6.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:20349195326a5e82a16e351ed93465a7845a7e2a9af55b7bc1b2110ea3e344e1", size = 13113753 }, - { url = "https://files.pythonhosted.org/packages/83/47/6edf2f890139616b3219be9cfcc8f0cb8f42eb15efd59597927e390538cb/pygame-2.6.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f3935459109da4bb0b3901da9904f0a3e52028a3332a355d298b1673a334cf21", size = 12378146 }, - { url = "https://files.pythonhosted.org/packages/00/9e/0d8aa8cf93db2d2ee38ebaf1c7b61d0df36ded27eb726221719c150c673d/pygame-2.6.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c31dbdb5d0217f32764797d21c2752e258e5fb7e895326538d82b5f75a0cd856", size = 13611760 }, - { url = "https://files.pythonhosted.org/packages/d7/9e/d06adaa5cc65876bcd7a24f59f67e07f7e4194e6298130024ed3fb22c456/pygame-2.6.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:173badf82fa198e6888017bea40f511cb28e69ecdd5a72b214e81e4dcd66c3b1", size = 14298054 }, - { url = "https://files.pythonhosted.org/packages/7a/a1/9ae2852ebd3a7cc7d9ae7ff7919ab983e4a5c1b7a14e840732f23b2b48f6/pygame-2.6.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ce8cc108b92de9b149b344ad2e25eedbe773af0dc41dfb24d1f07f679b558c60", size = 13977107 }, - { url = "https://files.pythonhosted.org/packages/31/df/6788fd2e9a864d0496a77670e44a7c012184b7a5382866ab0e60c55c0f28/pygame-2.6.1-cp311-cp311-win32.whl", hash = "sha256:811e7b925146d8149d79193652cbb83e0eca0aae66476b1cb310f0f4226b8b5c", size = 10250863 }, - { url = "https://files.pythonhosted.org/packages/d2/55/ca3eb851aeef4f6f2e98a360c201f0d00bd1ba2eb98e2c7850d80aabc526/pygame-2.6.1-cp311-cp311-win_amd64.whl", hash = "sha256:91476902426facd4bb0dad4dc3b2573bc82c95c71b135e0daaea072ed528d299", size = 10622016 }, - { url = "https://files.pythonhosted.org/packages/92/16/2c602c332f45ff9526d61f6bd764db5096ff9035433e2172e2d2cadae8db/pygame-2.6.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4ee7f2771f588c966fa2fa8b829be26698c9b4836f82ede5e4edc1a68594942e", size = 13118279 }, - { url = "https://files.pythonhosted.org/packages/cd/53/77ccbc384b251c6e34bfd2e734c638233922449a7844e3c7a11ef91cee39/pygame-2.6.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:c8040ea2ab18c6b255af706ec01355c8a6b08dc48d77fd4ee783f8fc46a843bf", size = 12384524 }, - { url = "https://files.pythonhosted.org/packages/06/be/3ed337583f010696c3b3435e89a74fb29d0c74d0931e8f33c0a4246307a9/pygame-2.6.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c47a6938de93fa610accd4969e638c2aebcb29b2fca518a84c3a39d91ab47116", size = 13587123 }, - { url = "https://files.pythonhosted.org/packages/fd/ca/b015586a450db59313535662991b34d24c1f0c0dc149cc5f496573900f4e/pygame-2.6.1-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:33006f784e1c7d7e466fcb61d5489da59cc5f7eb098712f792a225df1d4e229d", size = 14275532 }, - { url = "https://files.pythonhosted.org/packages/b9/f2/d31e6ad42d657af07be2ffd779190353f759a07b51232b9e1d724f2cda46/pygame-2.6.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1206125f14cae22c44565c9d333607f1d9f59487b1f1432945dfc809aeaa3e88", size = 13952653 }, - { url = "https://files.pythonhosted.org/packages/f3/42/8ea2a6979e6fa971702fece1747e862e2256d4a8558fe0da6364dd946c53/pygame-2.6.1-cp312-cp312-win32.whl", hash = "sha256:84fc4054e25262140d09d39e094f6880d730199710829902f0d8ceae0213379e", size = 10252421 }, - { url = "https://files.pythonhosted.org/packages/5f/90/7d766d54bb95939725e9a9361f9c06b0cfbe3fe100aa35400f0a461a278a/pygame-2.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:3a9e7396be0d9633831c3f8d5d82dd63ba373ad65599628294b7a4f8a5a01a65", size = 10624591 }, + { url = "https://files.pythonhosted.org/packages/c4/ca/8f367cb9fe734c4f6f6400e045593beea2635cd736158f9fabf58ee14e3c/pygame-2.6.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:20349195326a5e82a16e351ed93465a7845a7e2a9af55b7bc1b2110ea3e344e1", size = 13113753, upload-time = "2024-09-29T14:26:13.751Z" }, + { url = "https://files.pythonhosted.org/packages/83/47/6edf2f890139616b3219be9cfcc8f0cb8f42eb15efd59597927e390538cb/pygame-2.6.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f3935459109da4bb0b3901da9904f0a3e52028a3332a355d298b1673a334cf21", size = 12378146, upload-time = "2024-09-29T14:26:22.456Z" }, + { url = "https://files.pythonhosted.org/packages/00/9e/0d8aa8cf93db2d2ee38ebaf1c7b61d0df36ded27eb726221719c150c673d/pygame-2.6.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c31dbdb5d0217f32764797d21c2752e258e5fb7e895326538d82b5f75a0cd856", size = 13611760, upload-time = "2024-09-29T11:10:47.317Z" }, + { url = "https://files.pythonhosted.org/packages/d7/9e/d06adaa5cc65876bcd7a24f59f67e07f7e4194e6298130024ed3fb22c456/pygame-2.6.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:173badf82fa198e6888017bea40f511cb28e69ecdd5a72b214e81e4dcd66c3b1", size = 14298054, upload-time = "2024-09-29T11:39:53.891Z" }, + { url = "https://files.pythonhosted.org/packages/7a/a1/9ae2852ebd3a7cc7d9ae7ff7919ab983e4a5c1b7a14e840732f23b2b48f6/pygame-2.6.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ce8cc108b92de9b149b344ad2e25eedbe773af0dc41dfb24d1f07f679b558c60", size = 13977107, upload-time = "2024-09-29T11:39:56.831Z" }, + { url = "https://files.pythonhosted.org/packages/31/df/6788fd2e9a864d0496a77670e44a7c012184b7a5382866ab0e60c55c0f28/pygame-2.6.1-cp311-cp311-win32.whl", hash = "sha256:811e7b925146d8149d79193652cbb83e0eca0aae66476b1cb310f0f4226b8b5c", size = 10250863, upload-time = "2024-09-29T11:44:48.199Z" }, + { url = "https://files.pythonhosted.org/packages/d2/55/ca3eb851aeef4f6f2e98a360c201f0d00bd1ba2eb98e2c7850d80aabc526/pygame-2.6.1-cp311-cp311-win_amd64.whl", hash = "sha256:91476902426facd4bb0dad4dc3b2573bc82c95c71b135e0daaea072ed528d299", size = 10622016, upload-time = "2024-09-29T12:17:01.545Z" }, + { url = "https://files.pythonhosted.org/packages/92/16/2c602c332f45ff9526d61f6bd764db5096ff9035433e2172e2d2cadae8db/pygame-2.6.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4ee7f2771f588c966fa2fa8b829be26698c9b4836f82ede5e4edc1a68594942e", size = 13118279, upload-time = "2024-09-29T14:26:30.427Z" }, + { url = "https://files.pythonhosted.org/packages/cd/53/77ccbc384b251c6e34bfd2e734c638233922449a7844e3c7a11ef91cee39/pygame-2.6.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:c8040ea2ab18c6b255af706ec01355c8a6b08dc48d77fd4ee783f8fc46a843bf", size = 12384524, upload-time = "2024-09-29T14:26:49.996Z" }, + { url = "https://files.pythonhosted.org/packages/06/be/3ed337583f010696c3b3435e89a74fb29d0c74d0931e8f33c0a4246307a9/pygame-2.6.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c47a6938de93fa610accd4969e638c2aebcb29b2fca518a84c3a39d91ab47116", size = 13587123, upload-time = "2024-09-29T11:10:50.072Z" }, + { url = "https://files.pythonhosted.org/packages/fd/ca/b015586a450db59313535662991b34d24c1f0c0dc149cc5f496573900f4e/pygame-2.6.1-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:33006f784e1c7d7e466fcb61d5489da59cc5f7eb098712f792a225df1d4e229d", size = 14275532, upload-time = "2024-09-29T11:39:59.356Z" }, + { url = "https://files.pythonhosted.org/packages/b9/f2/d31e6ad42d657af07be2ffd779190353f759a07b51232b9e1d724f2cda46/pygame-2.6.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1206125f14cae22c44565c9d333607f1d9f59487b1f1432945dfc809aeaa3e88", size = 13952653, upload-time = "2024-09-29T11:40:01.781Z" }, + { url = "https://files.pythonhosted.org/packages/f3/42/8ea2a6979e6fa971702fece1747e862e2256d4a8558fe0da6364dd946c53/pygame-2.6.1-cp312-cp312-win32.whl", hash = "sha256:84fc4054e25262140d09d39e094f6880d730199710829902f0d8ceae0213379e", size = 10252421, upload-time = "2024-09-29T11:14:26.877Z" }, + { url = "https://files.pythonhosted.org/packages/5f/90/7d766d54bb95939725e9a9361f9c06b0cfbe3fe100aa35400f0a461a278a/pygame-2.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:3a9e7396be0d9633831c3f8d5d82dd63ba373ad65599628294b7a4f8a5a01a65", size = 10624591, upload-time = "2024-09-29T11:52:54.489Z" }, ] [[package]] @@ -1772,24 +1798,24 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pyrect" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e1/70/c7a4f46dbf06048c6d57d9489b8e0f9c4c3d36b7479f03c5ca97eaa2541d/PyGetWindow-0.0.9.tar.gz", hash = "sha256:17894355e7d2b305cd832d717708384017c1698a90ce24f6f7fbf0242dd0a688", size = 9699 } +sdist = { url = "https://files.pythonhosted.org/packages/e1/70/c7a4f46dbf06048c6d57d9489b8e0f9c4c3d36b7479f03c5ca97eaa2541d/PyGetWindow-0.0.9.tar.gz", hash = "sha256:17894355e7d2b305cd832d717708384017c1698a90ce24f6f7fbf0242dd0a688", size = 9699, upload-time = "2020-10-04T02:12:50.806Z" } [[package]] name = "pygments" version = "2.19.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/7c/2d/c3338d48ea6cc0feb8446d8e6937e1408088a72a39937982cc6111d17f84/pygments-2.19.1.tar.gz", hash = "sha256:61c16d2a8576dc0649d9f39e089b5f02bcd27fba10d8fb4dcc28173f7a45151f", size = 4968581 } +sdist = { url = "https://files.pythonhosted.org/packages/7c/2d/c3338d48ea6cc0feb8446d8e6937e1408088a72a39937982cc6111d17f84/pygments-2.19.1.tar.gz", hash = "sha256:61c16d2a8576dc0649d9f39e089b5f02bcd27fba10d8fb4dcc28173f7a45151f", size = 4968581, upload-time = "2025-01-06T17:26:30.443Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/8a/0b/9fcc47d19c48b59121088dd6da2488a49d5f72dacf8262e2790a1d2c7d15/pygments-2.19.1-py3-none-any.whl", hash = "sha256:9ea1544ad55cecf4b8242fab6dd35a93bbce657034b0611ee383099054ab6d8c", size = 1225293 }, + { url = "https://files.pythonhosted.org/packages/8a/0b/9fcc47d19c48b59121088dd6da2488a49d5f72dacf8262e2790a1d2c7d15/pygments-2.19.1-py3-none-any.whl", hash = "sha256:9ea1544ad55cecf4b8242fab6dd35a93bbce657034b0611ee383099054ab6d8c", size = 1225293, upload-time = "2025-01-06T17:26:25.553Z" }, ] [[package]] name = "pyjwt" version = "2.10.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e7/46/bd74733ff231675599650d3e47f361794b22ef3e3770998dda30d3b63726/pyjwt-2.10.1.tar.gz", hash = "sha256:3cc5772eb20009233caf06e9d8a0577824723b44e6648ee0a2aedb6cf9381953", size = 87785 } +sdist = { url = "https://files.pythonhosted.org/packages/e7/46/bd74733ff231675599650d3e47f361794b22ef3e3770998dda30d3b63726/pyjwt-2.10.1.tar.gz", hash = "sha256:3cc5772eb20009233caf06e9d8a0577824723b44e6648ee0a2aedb6cf9381953", size = 87785, upload-time = "2024-11-28T03:43:29.933Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/61/ad/689f02752eeec26aed679477e80e632ef1b682313be70793d798c1d5fc8f/PyJWT-2.10.1-py3-none-any.whl", hash = "sha256:dcdd193e30abefd5debf142f9adfcdd2b58004e644f25406ffaebd50bd98dacb", size = 22997 }, + { url = "https://files.pythonhosted.org/packages/61/ad/689f02752eeec26aed679477e80e632ef1b682313be70793d798c1d5fc8f/PyJWT-2.10.1-py3-none-any.whl", hash = "sha256:dcdd193e30abefd5debf142f9adfcdd2b58004e644f25406ffaebd50bd98dacb", size = 22997, upload-time = "2024-11-28T03:43:27.893Z" }, ] [package.optional-dependencies] @@ -1799,20 +1825,23 @@ crypto = [ [[package]] name = "pylibsrtp" -version = "0.11.0" +version = "0.12.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2e/49/1c5101ecfeda540699e0754dddfc91c401fbf736ebe99d66e59fe3dad2ba/pylibsrtp-0.11.0.tar.gz", hash = "sha256:5a8d19b1448baebde5ae3cedfa51f10e8ada3d9d99f43046ced0ecf1c105b8ec", size = 10786 } +sdist = { url = "https://files.pythonhosted.org/packages/54/c8/a59e61f5dd655f5f21033bd643dd31fe980a537ed6f373cdfb49d3a3bd32/pylibsrtp-0.12.0.tar.gz", hash = "sha256:f5c3c0fb6954e7bb74dc7e6398352740ca67327e6759a199fe852dbc7b84b8ac", size = 10878, upload-time = "2025-04-06T12:35:51.804Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b5/95/65650bf56e1080beb5f7c963a0bb11a6ee7599bfd89b33ff4525d2b5824b/pylibsrtp-0.11.0-cp39-abi3-macosx_10_9_x86_64.whl", hash = "sha256:36c6b33347d47c889b7dd465c6ae1f44d7705d00436ca613fd2a8f5dd401b104", size = 1727506 }, - { url = "https://files.pythonhosted.org/packages/4e/b0/f12c489ea8716e74343559abc5d0dfb94d66bcfe1924d64d58424a50f496/pylibsrtp-0.11.0-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:cf18b80f9513484a70e55136ece6ec80e7d21c03cc69abbb428e4f2745ca3cee", size = 2058008 }, - { url = "https://files.pythonhosted.org/packages/e1/2e/6040cd6da6f82f3aa1763c8c45f7fcfdfe08db5560c73f5e1deb4c36c2bb/pylibsrtp-0.11.0-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:81bbe0cd777979f7fc45c85f0c619c9cbe709faffbf91675d9dcce560734b353", size = 2566705 }, - { url = "https://files.pythonhosted.org/packages/2b/c9/fd313ac3a23e9c45493131d9fa3463770289e59bb8422c6c6877ab3add40/pylibsrtp-0.11.0-cp39-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:78fcdfe63925ea9a5017884c31fe9687b9b8b9f7d9beb7e25e3be47aa6ece495", size = 2168163 }, - { url = "https://files.pythonhosted.org/packages/f9/b3/ae0bac50cc0cca4b8c14de8063ba410ed3edd82c71a2315f284c9be7d679/pylibsrtp-0.11.0-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1909f7e781a7675d5c92cbad9e7ed3642e626e2bea5834243e423976e5420ac3", size = 2224343 }, - { url = "https://files.pythonhosted.org/packages/51/c4/650c2cecd5810f84adc89f3a94a28ea02d7ac8eaf3ee718a629c6f8ebf09/pylibsrtp-0.11.0-cp39-abi3-win32.whl", hash = "sha256:15123cecd377248747c95de9305ac314f3bcccdae46022bb4b9d60a552a26a10", size = 1156330 }, - { url = "https://files.pythonhosted.org/packages/fe/78/724307095b95c937e54c48133be3e85779cebea770f7536be555217b31f2/pylibsrtp-0.11.0-cp39-abi3-win_amd64.whl", hash = "sha256:bea2fb98029d19de516538b13c4827b6474d6f85d9ea50fae349e9671b946f7a", size = 1486448 }, + { url = "https://files.pythonhosted.org/packages/65/f0/b818395c4cae2d5cc5a0c78fc47d694eae78e6a0d678baeb52a381a26327/pylibsrtp-0.12.0-cp39-abi3-macosx_10_9_x86_64.whl", hash = "sha256:5adde3cf9a5feef561d0eb7ed99dedb30b9bf1ce9a0c1770b2bf19fd0b98bc9a", size = 1727918, upload-time = "2025-04-06T12:35:36.456Z" }, + { url = "https://files.pythonhosted.org/packages/05/1a/ee553abe4431b7bd9bab18f078c0ad2298b94ea55e664da6ecb8700b1052/pylibsrtp-0.12.0-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:d2c81d152606721331ece87c80ed17159ba6da55c7c61a6b750cff67ab7f63a5", size = 2057900, upload-time = "2025-04-06T12:35:38.253Z" }, + { url = "https://files.pythonhosted.org/packages/7f/a2/2dd0188be58d3cba48c5eb4b3c787e5743c111cd0c9289de4b6f2798382a/pylibsrtp-0.12.0-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:242fa3d44219846bf1734d5df595563a2c8fbb0fb00ccc79ab0f569fc0af2c1b", size = 2567047, upload-time = "2025-04-06T12:35:39.797Z" }, + { url = "https://files.pythonhosted.org/packages/6c/3a/4bdab9fc1d78f2efa02c8a8f3e9c187bfa278e89481b5123f07c8dd69310/pylibsrtp-0.12.0-cp39-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b74aaf8fac1b119a3c762f54751c3d20e77227b84c26d85aae57c2c43129b49c", size = 2168775, upload-time = "2025-04-06T12:35:41.422Z" }, + { url = "https://files.pythonhosted.org/packages/d0/fc/0b1e1bfed420d79427d50aff84c370dcd78d81af9500c1e86fbcc5bf95e1/pylibsrtp-0.12.0-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:33e3e223102989b71f07e1deeb804170ed53fb4e1b283762eb031bd45bb425d4", size = 2225033, upload-time = "2025-04-06T12:35:43.03Z" }, + { url = "https://files.pythonhosted.org/packages/39/7b/e1021d27900315c2c077ec7d45f50274cedbdde067ff679d44df06f01a8a/pylibsrtp-0.12.0-cp39-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:36d07de64dbc82dbbb99fd77f36c8e23d6730bdbcccf09701945690a9a9a422a", size = 2606093, upload-time = "2025-04-06T12:35:44.587Z" }, + { url = "https://files.pythonhosted.org/packages/eb/c2/0fae6687a06fcde210a778148ec808af49e431c36fe9908503a695c35479/pylibsrtp-0.12.0-cp39-abi3-musllinux_1_2_i686.whl", hash = "sha256:ef03b4578577690f716fd023daed8914eee6de9a764fa128eda19a0e645cc032", size = 2193213, upload-time = "2025-04-06T12:35:46.167Z" }, + { url = "https://files.pythonhosted.org/packages/67/c2/2ed7a4a5c38b999fd34298f76b93d29f5ba8c06f85cfad3efd9468343715/pylibsrtp-0.12.0-cp39-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:0a8421e9fe4d20ce48d439430e55149f12b1bca1b0436741972c362c49948c0a", size = 2256774, upload-time = "2025-04-06T12:35:47.704Z" }, + { url = "https://files.pythonhosted.org/packages/48/d7/f13fedce3b21d24f6f154d1dee7287464a34728dcb3b0c50f687dbad5765/pylibsrtp-0.12.0-cp39-abi3-win32.whl", hash = "sha256:cbc9bfbfb2597e993a1aa16b832ba16a9dd4647f70815421bb78484f8b50b924", size = 1156186, upload-time = "2025-04-06T12:35:48.78Z" }, + { url = "https://files.pythonhosted.org/packages/9b/26/3a20b638a3a3995368f856eeb10701dd6c0e9ace9fb6665eeb1b95ccce19/pylibsrtp-0.12.0-cp39-abi3-win_amd64.whl", hash = "sha256:061ef1dbb5f08079ac6d7515b7e67ca48a3163e16e5b820beea6b01cb31d7e54", size = 1485072, upload-time = "2025-04-06T12:35:50.312Z" }, ] [[package]] @@ -1827,190 +1856,190 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/2d/13/076a20da28b82be281f7e43e16d9da0f545090f5d14b2125699232b9feba/PyMonCtl-0.92-py3-none-any.whl", hash = "sha256:2495d8dab78f9a7dbce37e74543e60b8bd404a35c3108935697dda7768611b5a", size = 45945 }, + { url = "https://files.pythonhosted.org/packages/2d/13/076a20da28b82be281f7e43e16d9da0f545090f5d14b2125699232b9feba/PyMonCtl-0.92-py3-none-any.whl", hash = "sha256:2495d8dab78f9a7dbce37e74543e60b8bd404a35c3108935697dda7768611b5a", size = 45945, upload-time = "2024-04-22T10:07:09.566Z" }, ] [[package]] name = "pymsgbox" version = "1.0.9" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/7d/ff/4c6f31a4f08979f12a663f2aeb6c8b765d3bd592e66eaaac445f547bb875/PyMsgBox-1.0.9.tar.gz", hash = "sha256:2194227de8bff7a3d6da541848705a155dcbb2a06ee120d9f280a1d7f51263ff", size = 18829 } +sdist = { url = "https://files.pythonhosted.org/packages/7d/ff/4c6f31a4f08979f12a663f2aeb6c8b765d3bd592e66eaaac445f547bb875/PyMsgBox-1.0.9.tar.gz", hash = "sha256:2194227de8bff7a3d6da541848705a155dcbb2a06ee120d9f280a1d7f51263ff", size = 18829, upload-time = "2020-10-11T01:51:43.227Z" } [[package]] name = "pyobjc" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accessibility", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accounts", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-addressbook", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-adservices", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-adsupport", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applescriptkit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applescriptobjc", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applicationservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-apptrackingtransparency", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-audiovideobridging", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-authenticationservices", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-automaticassessmentconfiguration", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-automator", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avkit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avrouting", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-backgroundassets", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-browserenginekit", marker = "platform_release >= '23.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-businesschat", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-calendarstore", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-callkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-carbon", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cfnetwork", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cinematic", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-classkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cloudkit", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-collaboration", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-colorsync", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contacts", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contactsui", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudiokit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corebluetooth", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corehaptics", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremediaio", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremidi", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreml", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremotion", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corespotlight", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coretext", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corewlan", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cryptotokenkit", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-datadetection", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-devicecheck", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-devicediscoveryextension", marker = "platform_release >= '24.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-dictionaryservices", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecording", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecordingui", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-diskarbitration", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-dvdplayback", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-eventkit", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-exceptionhandling", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-executionpolicy", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-extensionkit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-externalaccessory", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileprovider", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileproviderui", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-findersync", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fsevents", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamecenter", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamecontroller", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamekit", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gameplaykit", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-healthkit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-imagecapturecore", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-inputmethodkit", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-installerplugins", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-instantmessage", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intents", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intentsui", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetooth", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetoothui", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iosurface", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-ituneslibrary", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-kernelmanagement", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-latentsemanticmapping", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-launchservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-libdispatch", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-libxpc", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-linkpresentation", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthentication", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthenticationembeddedui", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mailkit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mapkit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaaccessibility", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaextension", marker = "platform_release >= '24.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-medialibrary", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaplayer", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediatoolbox", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalfx", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalkit", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshaders", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshadersgraph", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metrickit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mlcompute", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-modelio", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-multipeerconnectivity", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-naturallanguage", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-netfs", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-network", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-networkextension", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-notificationcenter", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-opendirectory", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-osakit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-oslog", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-passkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-pencilkit", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-phase", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-photos", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-photosui", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-preferencepanes", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-pushkit", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quicklookthumbnailing", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-replaykit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-safariservices", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-safetykit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-scenekit", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screencapturekit", marker = "platform_release >= '21.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screensaver", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screentime", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-scriptingbridge", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-searchkit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-securityfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-securityinterface", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sensitivecontentanalysis", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-servicemanagement", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyou", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyoucore", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-shazamkit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-social", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-soundanalysis", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-speech", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-spritekit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-storekit", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-symbols", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-syncservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-systemconfiguration", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-systemextensions", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-threadnetwork", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-uniformtypeidentifiers", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotifications", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotificationsui", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-videosubscriberaccount", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-videotoolbox", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-virtualization", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-vision", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-webkit", marker = "sys_platform == 'darwin'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/e1/d6/27b1c9a02f6cb4954984ce1a0239618e52f78c329c7e7450bf1f219b0f0a/pyobjc-11.0.tar.gz", hash = "sha256:a8f7baed65797f67afd46290b02f652c23f4b158ddf960bce0441b78f6803418", size = 11044 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/18/55/d0971bccf8a5a347eaccf8caa4718766a68281baab83d2b5e211b2767504/pyobjc-11.0-py3-none-any.whl", hash = "sha256:3ed5e4e993192fd7fadd42a4148d266a3587af7453ea3b240bab724d02e34e64", size = 4169 }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-accessibility", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-accounts", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-addressbook" }, + { name = "pyobjc-framework-adservices", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-adsupport", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-applescriptkit" }, + { name = "pyobjc-framework-applescriptobjc", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-applicationservices" }, + { name = "pyobjc-framework-apptrackingtransparency", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-audiovideobridging", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-authenticationservices", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-automaticassessmentconfiguration", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-automator" }, + { name = "pyobjc-framework-avfoundation", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-avkit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-avrouting", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-backgroundassets", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-browserenginekit", marker = "platform_release >= '23.4'" }, + { name = "pyobjc-framework-businesschat", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-calendarstore", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-callkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-carbon" }, + { name = "pyobjc-framework-cfnetwork" }, + { name = "pyobjc-framework-cinematic", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-classkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-cloudkit", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-collaboration", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-colorsync", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-contacts", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-contactsui", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coreaudiokit" }, + { name = "pyobjc-framework-corebluetooth", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-coredata" }, + { name = "pyobjc-framework-corehaptics", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-corelocation", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-coremedia", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-coremediaio", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-coremidi" }, + { name = "pyobjc-framework-coreml", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-coremotion", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-coreservices" }, + { name = "pyobjc-framework-corespotlight", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-coretext" }, + { name = "pyobjc-framework-corewlan", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-cryptotokenkit", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-datadetection", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-devicecheck", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-devicediscoveryextension", marker = "platform_release >= '24.0'" }, + { name = "pyobjc-framework-dictionaryservices", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-discrecording" }, + { name = "pyobjc-framework-discrecordingui" }, + { name = "pyobjc-framework-diskarbitration" }, + { name = "pyobjc-framework-dvdplayback" }, + { name = "pyobjc-framework-eventkit", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-exceptionhandling" }, + { name = "pyobjc-framework-executionpolicy", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-extensionkit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-externalaccessory", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-fileprovider", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-fileproviderui", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-findersync", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-fsevents", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-gamecenter", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-gamecontroller", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-gamekit", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-gameplaykit", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-healthkit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-imagecapturecore", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-inputmethodkit", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-installerplugins" }, + { name = "pyobjc-framework-instantmessage", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-intents", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-intentsui", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-iobluetooth" }, + { name = "pyobjc-framework-iobluetoothui" }, + { name = "pyobjc-framework-iosurface", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-ituneslibrary", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-kernelmanagement", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-latentsemanticmapping" }, + { name = "pyobjc-framework-launchservices" }, + { name = "pyobjc-framework-libdispatch", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-libxpc", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-linkpresentation", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-localauthentication", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-localauthenticationembeddedui", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mailkit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mapkit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaaccessibility", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaextension", marker = "platform_release >= '24.0'" }, + { name = "pyobjc-framework-medialibrary", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaplayer", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-mediatoolbox", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-metal", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-metalfx", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-metalkit", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-metalperformanceshaders", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-metalperformanceshadersgraph", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-metrickit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mlcompute", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-modelio", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-multipeerconnectivity", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-naturallanguage", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-netfs", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-network", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-networkextension", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-notificationcenter", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-opendirectory", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-osakit" }, + { name = "pyobjc-framework-oslog", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-passkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-pencilkit", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-phase", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-photos", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-photosui", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-preferencepanes" }, + { name = "pyobjc-framework-pushkit", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-quartz" }, + { name = "pyobjc-framework-quicklookthumbnailing", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-replaykit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-safariservices", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-safetykit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-scenekit", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-screencapturekit", marker = "platform_release >= '21.4'" }, + { name = "pyobjc-framework-screensaver" }, + { name = "pyobjc-framework-screentime", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-scriptingbridge", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-searchkit" }, + { name = "pyobjc-framework-security" }, + { name = "pyobjc-framework-securityfoundation" }, + { name = "pyobjc-framework-securityinterface" }, + { name = "pyobjc-framework-sensitivecontentanalysis", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-servicemanagement", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-sharedwithyou", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-sharedwithyoucore", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-shazamkit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-social", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-soundanalysis", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-speech", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-spritekit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-storekit", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-symbols", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-syncservices" }, + { name = "pyobjc-framework-systemconfiguration" }, + { name = "pyobjc-framework-systemextensions", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-threadnetwork", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-uniformtypeidentifiers", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-usernotifications", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-usernotificationsui", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-videosubscriberaccount", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-videotoolbox", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-virtualization", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-vision", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-webkit" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/e1/d6/27b1c9a02f6cb4954984ce1a0239618e52f78c329c7e7450bf1f219b0f0a/pyobjc-11.0.tar.gz", hash = "sha256:a8f7baed65797f67afd46290b02f652c23f4b158ddf960bce0441b78f6803418", size = 11044, upload-time = "2025-01-14T19:02:12.55Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/18/55/d0971bccf8a5a347eaccf8caa4718766a68281baab83d2b5e211b2767504/pyobjc-11.0-py3-none-any.whl", hash = "sha256:3ed5e4e993192fd7fadd42a4148d266a3587af7453ea3b240bab724d02e34e64", size = 4169, upload-time = "2025-01-14T18:46:44.385Z" }, ] [[package]] name = "pyobjc-core" version = "11.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5c/94/a111239b98260869780a5767e5d74bfd3a8c13a40457f479c28dcd91f89d/pyobjc_core-11.0.tar.gz", hash = "sha256:63bced211cb8a8fb5c8ff46473603da30e51112861bd02c438fbbbc8578d9a70", size = 994931 } +sdist = { url = "https://files.pythonhosted.org/packages/5c/94/a111239b98260869780a5767e5d74bfd3a8c13a40457f479c28dcd91f89d/pyobjc_core-11.0.tar.gz", hash = "sha256:63bced211cb8a8fb5c8ff46473603da30e51112861bd02c438fbbbc8578d9a70", size = 994931, upload-time = "2025-01-14T19:02:13.938Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/52/05/fa97309c3b1bc1ec90d701db89902e0bd5e1024023aa2c5387b889458b1b/pyobjc_core-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:50675c0bb8696fe960a28466f9baf6943df2928a1fd85625d678fa2f428bd0bd", size = 727295 }, - { url = "https://files.pythonhosted.org/packages/56/ce/bf3ff9a9347721a398c3dfb83e29b43fb166b7ef590f3f7b7ddcd283df39/pyobjc_core-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a03061d4955c62ddd7754224a80cdadfdf17b6b5f60df1d9169a3b1b02923f0b", size = 739750 }, + { url = "https://files.pythonhosted.org/packages/52/05/fa97309c3b1bc1ec90d701db89902e0bd5e1024023aa2c5387b889458b1b/pyobjc_core-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:50675c0bb8696fe960a28466f9baf6943df2928a1fd85625d678fa2f428bd0bd", size = 727295, upload-time = "2025-01-14T18:46:50.208Z" }, + { url = "https://files.pythonhosted.org/packages/56/ce/bf3ff9a9347721a398c3dfb83e29b43fb166b7ef590f3f7b7ddcd283df39/pyobjc_core-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a03061d4955c62ddd7754224a80cdadfdf17b6b5f60df1d9169a3b1b02923f0b", size = 739750, upload-time = "2025-01-14T18:46:53.039Z" }, ] [[package]] @@ -2018,14 +2047,14 @@ name = "pyobjc-framework-accessibility" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b5/61/7484cc4ad3aa7854cd4c969379a5f044261259d08f7c20b6718493b484f9/pyobjc_framework_accessibility-11.0.tar.gz", hash = "sha256:097450c641fa9ac665199762e77867f2a82775be2f749b8fa69223b828f60656", size = 44597 } +sdist = { url = "https://files.pythonhosted.org/packages/b5/61/7484cc4ad3aa7854cd4c969379a5f044261259d08f7c20b6718493b484f9/pyobjc_framework_accessibility-11.0.tar.gz", hash = "sha256:097450c641fa9ac665199762e77867f2a82775be2f749b8fa69223b828f60656", size = 44597, upload-time = "2025-01-14T19:02:17.596Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/52/2e/babcd02cd833c0aba34e10c34a2184021b8a3c7cb45d1ae806156c2b519d/pyobjc_framework_Accessibility-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c3a751d17b288bb56a98a10b52b253b3002c885fe686b604788acac1e9739437", size = 10948 }, - { url = "https://files.pythonhosted.org/packages/e8/ea/da3f982eeaffb80efb480892106caa19a2c9c8b8954570837ddbcd983520/pyobjc_framework_Accessibility-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:34536f3d60aeda618b384b1207a8c6f9978de278ce229c3469ef14fd27a3befa", size = 10962 }, + { url = "https://files.pythonhosted.org/packages/52/2e/babcd02cd833c0aba34e10c34a2184021b8a3c7cb45d1ae806156c2b519d/pyobjc_framework_Accessibility-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c3a751d17b288bb56a98a10b52b253b3002c885fe686b604788acac1e9739437", size = 10948, upload-time = "2025-01-14T18:47:34.37Z" }, + { url = "https://files.pythonhosted.org/packages/e8/ea/da3f982eeaffb80efb480892106caa19a2c9c8b8954570837ddbcd983520/pyobjc_framework_Accessibility-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:34536f3d60aeda618b384b1207a8c6f9978de278ce229c3469ef14fd27a3befa", size = 10962, upload-time = "2025-01-14T18:47:35.313Z" }, ] [[package]] @@ -2033,13 +2062,13 @@ name = "pyobjc-framework-accounts" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c2/fa/b64f3f02e0a8b189dc07c391546e2dbe30ef1b3515d1427cdab743545b90/pyobjc_framework_accounts-11.0.tar.gz", hash = "sha256:afc4ae277be1e3e1f90269001c2fd886093a5465e365d7f9a3a0af3e17f06210", size = 17340 } +sdist = { url = "https://files.pythonhosted.org/packages/c2/fa/b64f3f02e0a8b189dc07c391546e2dbe30ef1b3515d1427cdab743545b90/pyobjc_framework_accounts-11.0.tar.gz", hash = "sha256:afc4ae277be1e3e1f90269001c2fd886093a5465e365d7f9a3a0af3e17f06210", size = 17340, upload-time = "2025-01-14T19:02:18.625Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/93/45/5dfc72c82087d458ce7ddb17a338a38ae1848e72620537f31ed97192c65e/pyobjc_framework_Accounts-11.0-py2.py3-none-any.whl", hash = "sha256:3e4b494e1158e3250e4b4a09e9ff33b38f82d31aefe50dd47152c4a20ecdeec4", size = 5035 }, - { url = "https://files.pythonhosted.org/packages/96/96/39b0cc9ced1180a93c75924a06598f24d0a7554b3e8ddfcb0828c0957476/pyobjc_framework_Accounts-11.0-py3-none-any.whl", hash = "sha256:ad0e378bd07ca7c88b45cda63b85424bc344e81ea44c0ae7327872d91cad311a", size = 5104 }, + { url = "https://files.pythonhosted.org/packages/93/45/5dfc72c82087d458ce7ddb17a338a38ae1848e72620537f31ed97192c65e/pyobjc_framework_Accounts-11.0-py2.py3-none-any.whl", hash = "sha256:3e4b494e1158e3250e4b4a09e9ff33b38f82d31aefe50dd47152c4a20ecdeec4", size = 5035, upload-time = "2025-01-14T18:47:40.92Z" }, + { url = "https://files.pythonhosted.org/packages/96/96/39b0cc9ced1180a93c75924a06598f24d0a7554b3e8ddfcb0828c0957476/pyobjc_framework_Accounts-11.0-py3-none-any.whl", hash = "sha256:ad0e378bd07ca7c88b45cda63b85424bc344e81ea44c0ae7327872d91cad311a", size = 5104, upload-time = "2025-01-14T18:47:41.967Z" }, ] [[package]] @@ -2047,13 +2076,13 @@ name = "pyobjc-framework-addressbook" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/68/ef/5b5f6b61907ae43509fbf1654e043115d9a64d97efdc28fbb90d06c199f6/pyobjc_framework_addressbook-11.0.tar.gz", hash = "sha256:87073c85bb342eb27faa6eceb7a0e8a4c1e32ad1f2b62bb12dafb5e7b9f15837", size = 97116 } +sdist = { url = "https://files.pythonhosted.org/packages/68/ef/5b5f6b61907ae43509fbf1654e043115d9a64d97efdc28fbb90d06c199f6/pyobjc_framework_addressbook-11.0.tar.gz", hash = "sha256:87073c85bb342eb27faa6eceb7a0e8a4c1e32ad1f2b62bb12dafb5e7b9f15837", size = 97116, upload-time = "2025-01-14T19:02:19.527Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2d/7a/8b874a52ff57dad999330ac1f899e6df8e35cec2cad8a90d8002d3c5f196/pyobjc_framework_AddressBook-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:af7de23aac7571a3b9dad5b2881d8f186653aa72903db8d7dbfd2c7b993156b9", size = 13010 }, - { url = "https://files.pythonhosted.org/packages/0c/b4/93de1195c22cbaf4996aeb6d55e79fc7d76311cacfe8fd716c70fb20e391/pyobjc_framework_AddressBook-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3b634ef80920ab9208f2937527e4a498e7afa6e2ceb639ebb483387ab5b9accc", size = 13039 }, + { url = "https://files.pythonhosted.org/packages/2d/7a/8b874a52ff57dad999330ac1f899e6df8e35cec2cad8a90d8002d3c5f196/pyobjc_framework_AddressBook-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:af7de23aac7571a3b9dad5b2881d8f186653aa72903db8d7dbfd2c7b993156b9", size = 13010, upload-time = "2025-01-14T18:47:47.925Z" }, + { url = "https://files.pythonhosted.org/packages/0c/b4/93de1195c22cbaf4996aeb6d55e79fc7d76311cacfe8fd716c70fb20e391/pyobjc_framework_AddressBook-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3b634ef80920ab9208f2937527e4a498e7afa6e2ceb639ebb483387ab5b9accc", size = 13039, upload-time = "2025-01-14T18:47:49.509Z" }, ] [[package]] @@ -2061,13 +2090,13 @@ name = "pyobjc-framework-adservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/51/7c/0c6e01f83b0c5c7968564a40146f4d07080df278457bdb5a982c8f26a74d/pyobjc_framework_adservices-11.0.tar.gz", hash = "sha256:d2e1a2f395e93e1bbe754ab0d76ce1d64c0d3928472634437e0382eafc6765cd", size = 12732 } +sdist = { url = "https://files.pythonhosted.org/packages/51/7c/0c6e01f83b0c5c7968564a40146f4d07080df278457bdb5a982c8f26a74d/pyobjc_framework_adservices-11.0.tar.gz", hash = "sha256:d2e1a2f395e93e1bbe754ab0d76ce1d64c0d3928472634437e0382eafc6765cd", size = 12732, upload-time = "2025-01-14T19:02:20.559Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1d/10/601c9f5a07450ce75e166042d9ac5efe6286ac2d15212885a920260af9e3/pyobjc_framework_AdServices-11.0-py2.py3-none-any.whl", hash = "sha256:7cd1458f60175cd46bd88061c20e82f04b2576fc00bc5d54d67c18dcb870e27f", size = 3420 }, - { url = "https://files.pythonhosted.org/packages/89/40/98a9116790e163d6c9ac0d19ce66307b03f9ac5ee64631db69899457b154/pyobjc_framework_AdServices-11.0-py3-none-any.whl", hash = "sha256:6426d4e4a43f5ee5ce7bab44d85647dbded3e17c0c62d8923cebaf927c4162ca", size = 3486 }, + { url = "https://files.pythonhosted.org/packages/1d/10/601c9f5a07450ce75e166042d9ac5efe6286ac2d15212885a920260af9e3/pyobjc_framework_AdServices-11.0-py2.py3-none-any.whl", hash = "sha256:7cd1458f60175cd46bd88061c20e82f04b2576fc00bc5d54d67c18dcb870e27f", size = 3420, upload-time = "2025-01-14T18:47:42.812Z" }, + { url = "https://files.pythonhosted.org/packages/89/40/98a9116790e163d6c9ac0d19ce66307b03f9ac5ee64631db69899457b154/pyobjc_framework_AdServices-11.0-py3-none-any.whl", hash = "sha256:6426d4e4a43f5ee5ce7bab44d85647dbded3e17c0c62d8923cebaf927c4162ca", size = 3486, upload-time = "2025-01-14T18:47:43.845Z" }, ] [[package]] @@ -2075,13 +2104,13 @@ name = "pyobjc-framework-adsupport" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0c/07/b8b5f741d1e2cad97100444b255e6ecaca3668e7414039981799aa330035/pyobjc_framework_adsupport-11.0.tar.gz", hash = "sha256:20eb8a683d34fb7a6efeceaf964a24b88c3434875c44f66db5e1b609e678043a", size = 12819 } +sdist = { url = "https://files.pythonhosted.org/packages/0c/07/b8b5f741d1e2cad97100444b255e6ecaca3668e7414039981799aa330035/pyobjc_framework_adsupport-11.0.tar.gz", hash = "sha256:20eb8a683d34fb7a6efeceaf964a24b88c3434875c44f66db5e1b609e678043a", size = 12819, upload-time = "2025-01-14T19:02:23.032Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6f/7f/2023c0a973f8823175c7e409fdbd306b275b0bb2723acf12ffade6ba5dbe/pyobjc_framework_AdSupport-11.0-py2.py3-none-any.whl", hash = "sha256:59161f5046def176d3aa6fdd6a05916029ca69ac69f836c67e0dd780a5efcf0f", size = 3334 }, - { url = "https://files.pythonhosted.org/packages/cf/84/26c4275732952416603026888ca5462ed84372d412d0ccd7a1c750c01673/pyobjc_framework_AdSupport-11.0-py3-none-any.whl", hash = "sha256:91ba05eb5602911287bd04b0efefb7a485f9af255095b87c3e77bb7d1d1242ed", size = 3405 }, + { url = "https://files.pythonhosted.org/packages/6f/7f/2023c0a973f8823175c7e409fdbd306b275b0bb2723acf12ffade6ba5dbe/pyobjc_framework_AdSupport-11.0-py2.py3-none-any.whl", hash = "sha256:59161f5046def176d3aa6fdd6a05916029ca69ac69f836c67e0dd780a5efcf0f", size = 3334, upload-time = "2025-01-14T18:47:44.747Z" }, + { url = "https://files.pythonhosted.org/packages/cf/84/26c4275732952416603026888ca5462ed84372d412d0ccd7a1c750c01673/pyobjc_framework_AdSupport-11.0-py3-none-any.whl", hash = "sha256:91ba05eb5602911287bd04b0efefb7a485f9af255095b87c3e77bb7d1d1242ed", size = 3405, upload-time = "2025-01-14T18:47:45.767Z" }, ] [[package]] @@ -2089,13 +2118,13 @@ name = "pyobjc-framework-applescriptkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/14/c3/d7f9a33de7ab8e3950350e0862214e66f27ed6bff1a491bc391c377ab83e/pyobjc_framework_applescriptkit-11.0.tar.gz", hash = "sha256:4bafac4a036f0fb8ba01488b8e91d3ac861ce6e61154ffbd0b26f82b99779b50", size = 12638 } +sdist = { url = "https://files.pythonhosted.org/packages/14/c3/d7f9a33de7ab8e3950350e0862214e66f27ed6bff1a491bc391c377ab83e/pyobjc_framework_applescriptkit-11.0.tar.gz", hash = "sha256:4bafac4a036f0fb8ba01488b8e91d3ac861ce6e61154ffbd0b26f82b99779b50", size = 12638, upload-time = "2025-01-14T19:02:25.1Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/97/4b/5e7f6a182129be6f229ee6c036d84359b46b0f5f695824315c47b19d3149/pyobjc_framework_AppleScriptKit-11.0-py2.py3-none-any.whl", hash = "sha256:e8acc5ca99f5123ec4e60cb356c7cc407d5fe533ca53e5fa341b51f65495973b", size = 4246 }, - { url = "https://files.pythonhosted.org/packages/b6/ce/7965604f553c91fbd5602e17057b0935c100542abaf76291921335b6f75c/pyobjc_framework_AppleScriptKit-11.0-py3-none-any.whl", hash = "sha256:92cffd943a4d17f684bb51245744e9d0bb8992b2967125845dfeab09d26fc624", size = 4317 }, + { url = "https://files.pythonhosted.org/packages/97/4b/5e7f6a182129be6f229ee6c036d84359b46b0f5f695824315c47b19d3149/pyobjc_framework_AppleScriptKit-11.0-py2.py3-none-any.whl", hash = "sha256:e8acc5ca99f5123ec4e60cb356c7cc407d5fe533ca53e5fa341b51f65495973b", size = 4246, upload-time = "2025-01-14T18:47:59.508Z" }, + { url = "https://files.pythonhosted.org/packages/b6/ce/7965604f553c91fbd5602e17057b0935c100542abaf76291921335b6f75c/pyobjc_framework_AppleScriptKit-11.0-py3-none-any.whl", hash = "sha256:92cffd943a4d17f684bb51245744e9d0bb8992b2967125845dfeab09d26fc624", size = 4317, upload-time = "2025-01-14T18:48:02.221Z" }, ] [[package]] @@ -2103,13 +2132,13 @@ name = "pyobjc-framework-applescriptobjc" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fb/9f/bb4fdbcea418f8472d7a67d4d2e4a15fca11fed04648db5208b0fce84807/pyobjc_framework_applescriptobjc-11.0.tar.gz", hash = "sha256:baff9988b6e886aed0e76441358417707de9088be5733f22055fed7904ca1001", size = 12675 } +sdist = { url = "https://files.pythonhosted.org/packages/fb/9f/bb4fdbcea418f8472d7a67d4d2e4a15fca11fed04648db5208b0fce84807/pyobjc_framework_applescriptobjc-11.0.tar.gz", hash = "sha256:baff9988b6e886aed0e76441358417707de9088be5733f22055fed7904ca1001", size = 12675, upload-time = "2025-01-14T19:02:25.947Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b8/7d/b3e28759df060f26a31407282e789a1a321612afcee3871134fdac8dc75f/pyobjc_framework_AppleScriptObjC-11.0-py2.py3-none-any.whl", hash = "sha256:a4c8d417fdb64180a283eadf8ddb804ba7f9e3cef149216a11b65e1d3509c55b", size = 4347 }, - { url = "https://files.pythonhosted.org/packages/0d/e7/c080a1cd77ce04e3bf4079a941105d3d670b9ba0fc91a54d4a1764bea02d/pyobjc_framework_AppleScriptObjC-11.0-py3-none-any.whl", hash = "sha256:681006b0cdf0279cd06b6d0f62b542b7f3b3b9b5d2391f7aa3798d8b355d67bf", size = 4416 }, + { url = "https://files.pythonhosted.org/packages/b8/7d/b3e28759df060f26a31407282e789a1a321612afcee3871134fdac8dc75f/pyobjc_framework_AppleScriptObjC-11.0-py2.py3-none-any.whl", hash = "sha256:a4c8d417fdb64180a283eadf8ddb804ba7f9e3cef149216a11b65e1d3509c55b", size = 4347, upload-time = "2025-01-14T18:48:03.193Z" }, + { url = "https://files.pythonhosted.org/packages/0d/e7/c080a1cd77ce04e3bf4079a941105d3d670b9ba0fc91a54d4a1764bea02d/pyobjc_framework_AppleScriptObjC-11.0-py3-none-any.whl", hash = "sha256:681006b0cdf0279cd06b6d0f62b542b7f3b3b9b5d2391f7aa3798d8b355d67bf", size = 4416, upload-time = "2025-01-14T18:48:04.219Z" }, ] [[package]] @@ -2117,15 +2146,15 @@ name = "pyobjc-framework-applicationservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coretext", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coretext" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ba/fb/4e42573b0d3baa3fa18ec53614cf979f951313f1451e8f2e17df9429da1f/pyobjc_framework_applicationservices-11.0.tar.gz", hash = "sha256:d6ea18dfc7d5626a3ecf4ac72d510405c0d3a648ca38cae8db841acdebecf4d2", size = 224334 } +sdist = { url = "https://files.pythonhosted.org/packages/ba/fb/4e42573b0d3baa3fa18ec53614cf979f951313f1451e8f2e17df9429da1f/pyobjc_framework_applicationservices-11.0.tar.gz", hash = "sha256:d6ea18dfc7d5626a3ecf4ac72d510405c0d3a648ca38cae8db841acdebecf4d2", size = 224334, upload-time = "2025-01-14T19:02:26.828Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/99/37/3d4dc6c004aaeb67bd43f7261d7c169ff45b8fc0eefbc7ba8cd6b0c881bc/pyobjc_framework_ApplicationServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:61a99eef23abb704257310db4f5271137707e184768f6407030c01de4731b67b", size = 30846 }, - { url = "https://files.pythonhosted.org/packages/74/a9/7a45a67e126d32c61ea22ffd80e87ff7e05b4acf32bede6cce071fbfffc8/pyobjc_framework_ApplicationServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5fbeb425897d6129471d451ec61a29ddd5b1386eb26b1dd49cb313e34616ee21", size = 30908 }, + { url = "https://files.pythonhosted.org/packages/99/37/3d4dc6c004aaeb67bd43f7261d7c169ff45b8fc0eefbc7ba8cd6b0c881bc/pyobjc_framework_ApplicationServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:61a99eef23abb704257310db4f5271137707e184768f6407030c01de4731b67b", size = 30846, upload-time = "2025-01-14T18:48:06.286Z" }, + { url = "https://files.pythonhosted.org/packages/74/a9/7a45a67e126d32c61ea22ffd80e87ff7e05b4acf32bede6cce071fbfffc8/pyobjc_framework_ApplicationServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5fbeb425897d6129471d451ec61a29ddd5b1386eb26b1dd49cb313e34616ee21", size = 30908, upload-time = "2025-01-14T18:48:07.177Z" }, ] [[package]] @@ -2133,13 +2162,13 @@ name = "pyobjc-framework-apptrackingtransparency" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/36/40/c1c48ed49b5e55c7a635aa1e7ca41ffa1c5547e26243f26489c4768cd730/pyobjc_framework_apptrackingtransparency-11.0.tar.gz", hash = "sha256:cd5c834b5b19c21ad6c317ba5d29f30a8d0ae5d14e7cf557da22abc0850f1e91", size = 13385 } +sdist = { url = "https://files.pythonhosted.org/packages/36/40/c1c48ed49b5e55c7a635aa1e7ca41ffa1c5547e26243f26489c4768cd730/pyobjc_framework_apptrackingtransparency-11.0.tar.gz", hash = "sha256:cd5c834b5b19c21ad6c317ba5d29f30a8d0ae5d14e7cf557da22abc0850f1e91", size = 13385, upload-time = "2025-01-14T19:02:29.226Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c4/72/6e460cd763a3048c4d75769ed60a5af7832122b78224f710e40a9eb1c5cf/pyobjc_framework_AppTrackingTransparency-11.0-py2.py3-none-any.whl", hash = "sha256:1bf6d4f148d9f5d5befe90fcfd88ce988458a52719d53d5989b08e4fbed58864", size = 3805 }, - { url = "https://files.pythonhosted.org/packages/33/cb/ef2622ee08349293aae6f81216cfee2423ad37d8a1d14ba4690b537d8850/pyobjc_framework_AppTrackingTransparency-11.0-py3-none-any.whl", hash = "sha256:347f876aea9d9f47d9fbf6dfa6d3f250ecd46f56a7c4616386327061e2ecc4e9", size = 3878 }, + { url = "https://files.pythonhosted.org/packages/c4/72/6e460cd763a3048c4d75769ed60a5af7832122b78224f710e40a9eb1c5cf/pyobjc_framework_AppTrackingTransparency-11.0-py2.py3-none-any.whl", hash = "sha256:1bf6d4f148d9f5d5befe90fcfd88ce988458a52719d53d5989b08e4fbed58864", size = 3805, upload-time = "2025-01-14T18:47:57.492Z" }, + { url = "https://files.pythonhosted.org/packages/33/cb/ef2622ee08349293aae6f81216cfee2423ad37d8a1d14ba4690b537d8850/pyobjc_framework_AppTrackingTransparency-11.0-py3-none-any.whl", hash = "sha256:347f876aea9d9f47d9fbf6dfa6d3f250ecd46f56a7c4616386327061e2ecc4e9", size = 3878, upload-time = "2025-01-14T18:47:58.595Z" }, ] [[package]] @@ -2147,13 +2176,13 @@ name = "pyobjc-framework-audiovideobridging" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/89/5f/0bd5beded0415b53f443da804410eda6a53e1bc64f8779ed9a592719da8c/pyobjc_framework_audiovideobridging-11.0.tar.gz", hash = "sha256:dbc45b06418dd780c365956fdfd69d007436b5ee54c51e671196562eb8290ba6", size = 72418 } +sdist = { url = "https://files.pythonhosted.org/packages/89/5f/0bd5beded0415b53f443da804410eda6a53e1bc64f8779ed9a592719da8c/pyobjc_framework_audiovideobridging-11.0.tar.gz", hash = "sha256:dbc45b06418dd780c365956fdfd69d007436b5ee54c51e671196562eb8290ba6", size = 72418, upload-time = "2025-01-14T19:02:30.083Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3c/33/2ee33542febb40174d40ae8bbdf672b4e438a3fb41ba6a4d4a3e6800121b/pyobjc_framework_AudioVideoBridging-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d025e49ca6238be96d0a1c22942b548a8d445ef8eb71259b4769e119810f42c6", size = 10944 }, - { url = "https://files.pythonhosted.org/packages/45/ea/db8295e17b0b544b06620e4019afcc76d7b743a8f03cb8a1024b2bc118ac/pyobjc_framework_AudioVideoBridging-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d414ecffeb23cddc8e64262af170e663c93e8d462d18aa7067d4584069967859", size = 10962 }, + { url = "https://files.pythonhosted.org/packages/3c/33/2ee33542febb40174d40ae8bbdf672b4e438a3fb41ba6a4d4a3e6800121b/pyobjc_framework_AudioVideoBridging-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d025e49ca6238be96d0a1c22942b548a8d445ef8eb71259b4769e119810f42c6", size = 10944, upload-time = "2025-01-14T18:48:11.978Z" }, + { url = "https://files.pythonhosted.org/packages/45/ea/db8295e17b0b544b06620e4019afcc76d7b743a8f03cb8a1024b2bc118ac/pyobjc_framework_AudioVideoBridging-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d414ecffeb23cddc8e64262af170e663c93e8d462d18aa7067d4584069967859", size = 10962, upload-time = "2025-01-14T18:48:12.953Z" }, ] [[package]] @@ -2161,13 +2190,13 @@ name = "pyobjc-framework-authenticationservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/31/0f/2de0d941e9c9b2eb1ce8b22eb31adc7227badfe1e53f615431d3a7fdcd48/pyobjc_framework_authenticationservices-11.0.tar.gz", hash = "sha256:6a060ce651df142e8923d1383449bc6f2c7f5eb0b517152dac609bde3901064e", size = 140036 } +sdist = { url = "https://files.pythonhosted.org/packages/31/0f/2de0d941e9c9b2eb1ce8b22eb31adc7227badfe1e53f615431d3a7fdcd48/pyobjc_framework_authenticationservices-11.0.tar.gz", hash = "sha256:6a060ce651df142e8923d1383449bc6f2c7f5eb0b517152dac609bde3901064e", size = 140036, upload-time = "2025-01-14T19:02:31.115Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/45/16/6246cf10e2d245f4018c02f351f8eb4cc93823f6e7e4dd584ab292cda786/pyobjc_framework_AuthenticationServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:84e3b23478cf8995883acfe6c1a24503c84caf2f8dbe540377fe19fb787ce9b2", size = 20079 }, - { url = "https://files.pythonhosted.org/packages/b7/ca/81a55a0714e73695b536bfbcbf0f5ddf68da9485b468406f6ef887a04938/pyobjc_framework_AuthenticationServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1779f72c264f749946fcbfba0575a985c1e297d426617739a533554dbf172f9a", size = 20105 }, + { url = "https://files.pythonhosted.org/packages/45/16/6246cf10e2d245f4018c02f351f8eb4cc93823f6e7e4dd584ab292cda786/pyobjc_framework_AuthenticationServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:84e3b23478cf8995883acfe6c1a24503c84caf2f8dbe540377fe19fb787ce9b2", size = 20079, upload-time = "2025-01-14T18:48:19.023Z" }, + { url = "https://files.pythonhosted.org/packages/b7/ca/81a55a0714e73695b536bfbcbf0f5ddf68da9485b468406f6ef887a04938/pyobjc_framework_AuthenticationServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1779f72c264f749946fcbfba0575a985c1e297d426617739a533554dbf172f9a", size = 20105, upload-time = "2025-01-14T18:48:19.945Z" }, ] [[package]] @@ -2175,13 +2204,13 @@ name = "pyobjc-framework-automaticassessmentconfiguration" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/09/d5/5febfee260b88e426c7e799cc95990818feeaa9f740fb9dd516559c96520/pyobjc_framework_automaticassessmentconfiguration-11.0.tar.gz", hash = "sha256:5d3691af2b94e44ca594b6791556e15a9f0a3f9432df51cb891f5f859a65e467", size = 24420 } +sdist = { url = "https://files.pythonhosted.org/packages/09/d5/5febfee260b88e426c7e799cc95990818feeaa9f740fb9dd516559c96520/pyobjc_framework_automaticassessmentconfiguration-11.0.tar.gz", hash = "sha256:5d3691af2b94e44ca594b6791556e15a9f0a3f9432df51cb891f5f859a65e467", size = 24420, upload-time = "2025-01-14T19:02:32.101Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/50/3f/b593adce2f5b9f9427d784db56d8195adc2cfb340d4d3578914539a17faa/pyobjc_framework_AutomaticAssessmentConfiguration-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:25f2db399eb0a47e345d0471c7af930f5a3be899ba6edb40bd9125719e4b526f", size = 9015 }, - { url = "https://files.pythonhosted.org/packages/4e/c3/b6b779d783dcf3667a2011d8af0d801f6639df9735cdc34c6e6b79822298/pyobjc_framework_AutomaticAssessmentConfiguration-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b6433452d2c4cdb0eef16cc78a24ba9c61efb5bb04709ee10ca94b69119e889c", size = 9034 }, + { url = "https://files.pythonhosted.org/packages/50/3f/b593adce2f5b9f9427d784db56d8195adc2cfb340d4d3578914539a17faa/pyobjc_framework_AutomaticAssessmentConfiguration-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:25f2db399eb0a47e345d0471c7af930f5a3be899ba6edb40bd9125719e4b526f", size = 9015, upload-time = "2025-01-14T18:48:25.686Z" }, + { url = "https://files.pythonhosted.org/packages/4e/c3/b6b779d783dcf3667a2011d8af0d801f6639df9735cdc34c6e6b79822298/pyobjc_framework_AutomaticAssessmentConfiguration-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b6433452d2c4cdb0eef16cc78a24ba9c61efb5bb04709ee10ca94b69119e889c", size = 9034, upload-time = "2025-01-14T18:48:26.58Z" }, ] [[package]] @@ -2189,13 +2218,13 @@ name = "pyobjc-framework-automator" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/25/1b/1ba4eb296c3915f2e367e45470cb310a9c78b4dd65a37bd522f458f245aa/pyobjc_framework_automator-11.0.tar.gz", hash = "sha256:412d330f8c6f30066cad15e1bdecdc865510bbce469cc7d9477384c4e9f2550f", size = 200905 } +sdist = { url = "https://files.pythonhosted.org/packages/25/1b/1ba4eb296c3915f2e367e45470cb310a9c78b4dd65a37bd522f458f245aa/pyobjc_framework_automator-11.0.tar.gz", hash = "sha256:412d330f8c6f30066cad15e1bdecdc865510bbce469cc7d9477384c4e9f2550f", size = 200905, upload-time = "2025-01-14T19:02:33.039Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7b/2b/bfe673491042849ad400bebf557b8047317757283b98ad9921fbb6f6cae9/pyobjc_framework_Automator-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:850f9641a54cc8d9a3d02c2d87a4e80aed2413b37aa6c26a7046088b77da5b42", size = 9811 }, - { url = "https://files.pythonhosted.org/packages/13/00/e60db832c536fd354fab7e813ee781327358e6bcbc4cacbd9695dade7006/pyobjc_framework_Automator-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:eb1b9b16873ec1d2f8af9a04ca1b2fcaa324ce4a1fada0d02fa239f6fecf773b", size = 9827 }, + { url = "https://files.pythonhosted.org/packages/7b/2b/bfe673491042849ad400bebf557b8047317757283b98ad9921fbb6f6cae9/pyobjc_framework_Automator-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:850f9641a54cc8d9a3d02c2d87a4e80aed2413b37aa6c26a7046088b77da5b42", size = 9811, upload-time = "2025-01-14T18:48:31.987Z" }, + { url = "https://files.pythonhosted.org/packages/13/00/e60db832c536fd354fab7e813ee781327358e6bcbc4cacbd9695dade7006/pyobjc_framework_Automator-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:eb1b9b16873ec1d2f8af9a04ca1b2fcaa324ce4a1fada0d02fa239f6fecf773b", size = 9827, upload-time = "2025-01-14T18:48:32.958Z" }, ] [[package]] @@ -2203,16 +2232,16 @@ name = "pyobjc-framework-avfoundation" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/76/06/018ad0e2a38dbdbc5c126d7ce37488c4d581d4e2a2b9ef678162bb36d5f6/pyobjc_framework_avfoundation-11.0.tar.gz", hash = "sha256:269a592bdaf8a16948d8935f0cf7c8cb9a53e7ea609a963ada0e55f749ddb530", size = 871064 } +sdist = { url = "https://files.pythonhosted.org/packages/76/06/018ad0e2a38dbdbc5c126d7ce37488c4d581d4e2a2b9ef678162bb36d5f6/pyobjc_framework_avfoundation-11.0.tar.gz", hash = "sha256:269a592bdaf8a16948d8935f0cf7c8cb9a53e7ea609a963ada0e55f749ddb530", size = 871064, upload-time = "2025-01-14T19:02:35.757Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/44/b5/327654548fa210b4637350de016183fbb1f6f8f9213d2c6c9b492eb8b44c/pyobjc_framework_AVFoundation-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:87db350311c1d7e07d68036cdde3d01c09d97b8ba502241c0c1699d7a9c6f2e4", size = 71345 }, - { url = "https://files.pythonhosted.org/packages/f5/36/e09b20f280953fa7be95a9266e5ad75f2e8b184cc39260c0537b3e60b534/pyobjc_framework_AVFoundation-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6bb6f4be53c0fb42bee3f46cf0bb5396a8fd13f92d47a01f6b77037a1134f26b", size = 71314 }, + { url = "https://files.pythonhosted.org/packages/44/b5/327654548fa210b4637350de016183fbb1f6f8f9213d2c6c9b492eb8b44c/pyobjc_framework_AVFoundation-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:87db350311c1d7e07d68036cdde3d01c09d97b8ba502241c0c1699d7a9c6f2e4", size = 71345, upload-time = "2025-01-14T18:47:04.589Z" }, + { url = "https://files.pythonhosted.org/packages/f5/36/e09b20f280953fa7be95a9266e5ad75f2e8b184cc39260c0537b3e60b534/pyobjc_framework_AVFoundation-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6bb6f4be53c0fb42bee3f46cf0bb5396a8fd13f92d47a01f6b77037a1134f26b", size = 71314, upload-time = "2025-01-14T18:47:05.616Z" }, ] [[package]] @@ -2220,14 +2249,14 @@ name = "pyobjc-framework-avkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/de/79/5b2fcb94b051da32a24b54bb0d90b1d01b190e1402b6303747de47fb17ac/pyobjc_framework_avkit-11.0.tar.gz", hash = "sha256:5fa40919320277b820df3e4c6e84cba91ef7221a28f4eb5374e3dbd80d1e521a", size = 46311 } +sdist = { url = "https://files.pythonhosted.org/packages/de/79/5b2fcb94b051da32a24b54bb0d90b1d01b190e1402b6303747de47fb17ac/pyobjc_framework_avkit-11.0.tar.gz", hash = "sha256:5fa40919320277b820df3e4c6e84cba91ef7221a28f4eb5374e3dbd80d1e521a", size = 46311, upload-time = "2025-01-14T19:02:37.018Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d2/ae/aed1023150483a288922c447e1997f4f4e9d0460038e1a070a3a53b85c19/pyobjc_framework_AVKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:16b5560860c1e13e692c677ad04d8e194d0b9931dd3f15e3df4dbd7217cc8ab1", size = 11960 }, - { url = "https://files.pythonhosted.org/packages/01/f4/08684e5af2a2e8940e6411e96ef1d7ed1e51a121abb19c93c25c34969213/pyobjc_framework_AVKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f4da468b97bb7f356024e31647619cd1cd435b543e467209da0ee0abdfdc7121", size = 11969 }, + { url = "https://files.pythonhosted.org/packages/d2/ae/aed1023150483a288922c447e1997f4f4e9d0460038e1a070a3a53b85c19/pyobjc_framework_AVKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:16b5560860c1e13e692c677ad04d8e194d0b9931dd3f15e3df4dbd7217cc8ab1", size = 11960, upload-time = "2025-01-14T18:47:15.738Z" }, + { url = "https://files.pythonhosted.org/packages/01/f4/08684e5af2a2e8940e6411e96ef1d7ed1e51a121abb19c93c25c34969213/pyobjc_framework_AVKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f4da468b97bb7f356024e31647619cd1cd435b543e467209da0ee0abdfdc7121", size = 11969, upload-time = "2025-01-14T18:47:16.602Z" }, ] [[package]] @@ -2235,13 +2264,13 @@ name = "pyobjc-framework-avrouting" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d5/80/63680dc7788bc3573a20fc5421dfcf606970a0cd3b2457829d9b66603ae0/pyobjc_framework_avrouting-11.0.tar.gz", hash = "sha256:54ec9ea0b5adb5149b554e23c07c6b4f4bdb2892ca2ed7b3e88a5de936313025", size = 20561 } +sdist = { url = "https://files.pythonhosted.org/packages/d5/80/63680dc7788bc3573a20fc5421dfcf606970a0cd3b2457829d9b66603ae0/pyobjc_framework_avrouting-11.0.tar.gz", hash = "sha256:54ec9ea0b5adb5149b554e23c07c6b4f4bdb2892ca2ed7b3e88a5de936313025", size = 20561, upload-time = "2025-01-14T19:02:38.157Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/8b/9c/ea6924de09e13f858210d6dd934f00773b1e3db6af886c72841ed545560f/pyobjc_framework_AVRouting-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:54e58cd0292f734aba035599f37a0c00f03761e9ff5cf53a0857cec7949bb39c", size = 8067 }, - { url = "https://files.pythonhosted.org/packages/3f/92/774e10af5aba5742c4a2dd563fa819550d9caa755d2648b3cc87bbe30129/pyobjc_framework_AVRouting-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:779db3fb0048b22c5dcf5871930025c0fd93068f87946e8053f31a3366fa6fb0", size = 8078 }, + { url = "https://files.pythonhosted.org/packages/8b/9c/ea6924de09e13f858210d6dd934f00773b1e3db6af886c72841ed545560f/pyobjc_framework_AVRouting-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:54e58cd0292f734aba035599f37a0c00f03761e9ff5cf53a0857cec7949bb39c", size = 8067, upload-time = "2025-01-14T18:47:26.354Z" }, + { url = "https://files.pythonhosted.org/packages/3f/92/774e10af5aba5742c4a2dd563fa819550d9caa755d2648b3cc87bbe30129/pyobjc_framework_AVRouting-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:779db3fb0048b22c5dcf5871930025c0fd93068f87946e8053f31a3366fa6fb0", size = 8078, upload-time = "2025-01-14T18:47:28.53Z" }, ] [[package]] @@ -2249,13 +2278,13 @@ name = "pyobjc-framework-backgroundassets" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a3/17/83b873069b0c0763365de88648ad4a2472e9e96fcac39fa534f3633552e8/pyobjc_framework_backgroundassets-11.0.tar.gz", hash = "sha256:9488c3f86bf427898a88b7100e77200c08a487a35c75c1b5735bd69c57ba38cb", size = 23658 } +sdist = { url = "https://files.pythonhosted.org/packages/a3/17/83b873069b0c0763365de88648ad4a2472e9e96fcac39fa534f3633552e8/pyobjc_framework_backgroundassets-11.0.tar.gz", hash = "sha256:9488c3f86bf427898a88b7100e77200c08a487a35c75c1b5735bd69c57ba38cb", size = 23658, upload-time = "2025-01-14T19:02:42.665Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e9/9d/bea4408649199340ec7ed154bbaa1942a0b0955006b3153088b3f35e6ff6/pyobjc_framework_BackgroundAssets-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:812bcc4eaf71c1cc42e94edc2b5ad0414d16cfe1da5c421edd9382417d625f06", size = 9499 }, - { url = "https://files.pythonhosted.org/packages/bd/79/726c14fd26553c8bbe8b2ed55caa45d89093e2e85b45c1b598dd04ea7589/pyobjc_framework_BackgroundAssets-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:96b3fc40c514867d4a0b3ad4d256bc5134d789e22fa306a6b21e49ecadc51698", size = 9521 }, + { url = "https://files.pythonhosted.org/packages/e9/9d/bea4408649199340ec7ed154bbaa1942a0b0955006b3153088b3f35e6ff6/pyobjc_framework_BackgroundAssets-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:812bcc4eaf71c1cc42e94edc2b5ad0414d16cfe1da5c421edd9382417d625f06", size = 9499, upload-time = "2025-01-14T18:48:39.156Z" }, + { url = "https://files.pythonhosted.org/packages/bd/79/726c14fd26553c8bbe8b2ed55caa45d89093e2e85b45c1b598dd04ea7589/pyobjc_framework_BackgroundAssets-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:96b3fc40c514867d4a0b3ad4d256bc5134d789e22fa306a6b21e49ecadc51698", size = 9521, upload-time = "2025-01-14T18:48:40.063Z" }, ] [[package]] @@ -2263,16 +2292,16 @@ name = "pyobjc-framework-browserenginekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9f/2e/df3d2f7e53132d398c2922d331dd1d2aa352997a1a4a1390e59db51c1d13/pyobjc_framework_browserenginekit-11.0.tar.gz", hash = "sha256:51971527f5103c0e09a4ef438c352ebb037fcad8971f8420a781c72ee421f758", size = 31352 } +sdist = { url = "https://files.pythonhosted.org/packages/9f/2e/df3d2f7e53132d398c2922d331dd1d2aa352997a1a4a1390e59db51c1d13/pyobjc_framework_browserenginekit-11.0.tar.gz", hash = "sha256:51971527f5103c0e09a4ef438c352ebb037fcad8971f8420a781c72ee421f758", size = 31352, upload-time = "2025-01-14T19:02:45.499Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/da/6d/6aa929d4993453817523db9c82a4e6e2cce7104fa59e29ee857f9e926b0d/pyobjc_framework_BrowserEngineKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:58494bc3ccc21a63751b7c9f8788d0240c3f1aad84cf221c0e42c9764a069ba4", size = 10913 }, - { url = "https://files.pythonhosted.org/packages/a8/2f/dd18f7ff9438ad4612febfbdb2e4bded37033347b9f0e1355df76f2c5213/pyobjc_framework_BrowserEngineKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0925edfd60a24f53819cfd11f07926fd42bc0fbeb7a4982998a08742e859dbff", size = 10933 }, + { url = "https://files.pythonhosted.org/packages/da/6d/6aa929d4993453817523db9c82a4e6e2cce7104fa59e29ee857f9e926b0d/pyobjc_framework_BrowserEngineKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:58494bc3ccc21a63751b7c9f8788d0240c3f1aad84cf221c0e42c9764a069ba4", size = 10913, upload-time = "2025-01-14T18:48:44.801Z" }, + { url = "https://files.pythonhosted.org/packages/a8/2f/dd18f7ff9438ad4612febfbdb2e4bded37033347b9f0e1355df76f2c5213/pyobjc_framework_BrowserEngineKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0925edfd60a24f53819cfd11f07926fd42bc0fbeb7a4982998a08742e859dbff", size = 10933, upload-time = "2025-01-14T18:48:45.673Z" }, ] [[package]] @@ -2280,13 +2309,13 @@ name = "pyobjc-framework-businesschat" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5a/f2/4541989f2c9c5fc3cdfc94ebf31fc6619554b6c22dafdbb57f866a392bc1/pyobjc_framework_businesschat-11.0.tar.gz", hash = "sha256:20fe1c8c848ef3c2e132172d9a007a8aa65b08875a9ca5c27afbfc4396b16dbb", size = 12953 } +sdist = { url = "https://files.pythonhosted.org/packages/5a/f2/4541989f2c9c5fc3cdfc94ebf31fc6619554b6c22dafdbb57f866a392bc1/pyobjc_framework_businesschat-11.0.tar.gz", hash = "sha256:20fe1c8c848ef3c2e132172d9a007a8aa65b08875a9ca5c27afbfc4396b16dbb", size = 12953, upload-time = "2025-01-14T19:02:46.378Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d4/5b/d7313368ea4056092400c7a4ed5c705d3d21a443641d98b140054edbd930/pyobjc_framework_BusinessChat-11.0-py2.py3-none-any.whl", hash = "sha256:1f732fdace31d2abdd14b3054f27a5e0f4591c7e1bef069b6aeb4f9c8d9ec487", size = 3408 }, - { url = "https://files.pythonhosted.org/packages/8a/e6/c82e2eb2b4ad4407f1ada6d41ef583eb211cce88ffcc2e05c826760f721d/pyobjc_framework_BusinessChat-11.0-py3-none-any.whl", hash = "sha256:47a2e4da9b061daa89a6367cb0e6bb8cdea0627379dd6d5095a8fd20243d8613", size = 3477 }, + { url = "https://files.pythonhosted.org/packages/d4/5b/d7313368ea4056092400c7a4ed5c705d3d21a443641d98b140054edbd930/pyobjc_framework_BusinessChat-11.0-py2.py3-none-any.whl", hash = "sha256:1f732fdace31d2abdd14b3054f27a5e0f4591c7e1bef069b6aeb4f9c8d9ec487", size = 3408, upload-time = "2025-01-14T18:48:51.116Z" }, + { url = "https://files.pythonhosted.org/packages/8a/e6/c82e2eb2b4ad4407f1ada6d41ef583eb211cce88ffcc2e05c826760f721d/pyobjc_framework_BusinessChat-11.0-py3-none-any.whl", hash = "sha256:47a2e4da9b061daa89a6367cb0e6bb8cdea0627379dd6d5095a8fd20243d8613", size = 3477, upload-time = "2025-01-14T18:48:52.723Z" }, ] [[package]] @@ -2294,13 +2323,13 @@ name = "pyobjc-framework-calendarstore" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9f/d3/722c1b16c7d9bdd5c408735c15193e8396f2d22ab6410b0af4569f39c46e/pyobjc_framework_calendarstore-11.0.tar.gz", hash = "sha256:40173f729df56b70ec14f9680962a248c3ce7b4babb46e8b0d760a13975ef174", size = 68475 } +sdist = { url = "https://files.pythonhosted.org/packages/9f/d3/722c1b16c7d9bdd5c408735c15193e8396f2d22ab6410b0af4569f39c46e/pyobjc_framework_calendarstore-11.0.tar.gz", hash = "sha256:40173f729df56b70ec14f9680962a248c3ce7b4babb46e8b0d760a13975ef174", size = 68475, upload-time = "2025-01-14T19:02:48.544Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e3/e1/02bda98aae43957943adb09700265603f8ff8ff2197e57b082237a8e1a8f/pyobjc_framework_CalendarStore-11.0-py2.py3-none-any.whl", hash = "sha256:67ddc18c96bba42118fc92f1117b053c58c8888edb74193f0be67a10051cc9e2", size = 5183 }, - { url = "https://files.pythonhosted.org/packages/a2/5b/922df21b738e8d349df27b2a73eaf8bba93c84c8c4d0d133fdd5de2ff236/pyobjc_framework_CalendarStore-11.0-py3-none-any.whl", hash = "sha256:9b310fe66ac12e0feb7c8e3166034bec357a45f7f8b8916e93eddc6f199d08c8", size = 5251 }, + { url = "https://files.pythonhosted.org/packages/e3/e1/02bda98aae43957943adb09700265603f8ff8ff2197e57b082237a8e1a8f/pyobjc_framework_CalendarStore-11.0-py2.py3-none-any.whl", hash = "sha256:67ddc18c96bba42118fc92f1117b053c58c8888edb74193f0be67a10051cc9e2", size = 5183, upload-time = "2025-01-14T18:49:01.649Z" }, + { url = "https://files.pythonhosted.org/packages/a2/5b/922df21b738e8d349df27b2a73eaf8bba93c84c8c4d0d133fdd5de2ff236/pyobjc_framework_CalendarStore-11.0-py3-none-any.whl", hash = "sha256:9b310fe66ac12e0feb7c8e3166034bec357a45f7f8b8916e93eddc6f199d08c8", size = 5251, upload-time = "2025-01-14T18:49:03.224Z" }, ] [[package]] @@ -2308,13 +2337,13 @@ name = "pyobjc-framework-callkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e4/0a/9d39ebac92006960b8059f664d8eb7b9cdb8763fe4e8102b2d24b853004f/pyobjc_framework_callkit-11.0.tar.gz", hash = "sha256:52e44a05d0357558e1479977ed2bcb325fabc8d337f641f0249178b5b491fc59", size = 39720 } +sdist = { url = "https://files.pythonhosted.org/packages/e4/0a/9d39ebac92006960b8059f664d8eb7b9cdb8763fe4e8102b2d24b853004f/pyobjc_framework_callkit-11.0.tar.gz", hash = "sha256:52e44a05d0357558e1479977ed2bcb325fabc8d337f641f0249178b5b491fc59", size = 39720, upload-time = "2025-01-14T19:02:50.697Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/22/86/8d7dc24702ae810b6230d8b2cebb1c31e12abc31507095b1a9655715c921/pyobjc_framework_CallKit-11.0-py2.py3-none-any.whl", hash = "sha256:f19d94b61ecd981f4691fd244f536f947687b872ac793ccc2b3122b3854e887a", size = 5248 }, - { url = "https://files.pythonhosted.org/packages/25/bd/ff89f7e5438c767fc43f603bee42a447315be48a09f64b9aa4da719ecdfc/pyobjc_framework_CallKit-11.0-py3-none-any.whl", hash = "sha256:95394b7f7a50916debe4f7a884ce9135d11733a14e07a8c502171e77bd0087a4", size = 5314 }, + { url = "https://files.pythonhosted.org/packages/22/86/8d7dc24702ae810b6230d8b2cebb1c31e12abc31507095b1a9655715c921/pyobjc_framework_CallKit-11.0-py2.py3-none-any.whl", hash = "sha256:f19d94b61ecd981f4691fd244f536f947687b872ac793ccc2b3122b3854e887a", size = 5248, upload-time = "2025-01-14T18:49:05.438Z" }, + { url = "https://files.pythonhosted.org/packages/25/bd/ff89f7e5438c767fc43f603bee42a447315be48a09f64b9aa4da719ecdfc/pyobjc_framework_CallKit-11.0-py3-none-any.whl", hash = "sha256:95394b7f7a50916debe4f7a884ce9135d11733a14e07a8c502171e77bd0087a4", size = 5314, upload-time = "2025-01-14T18:49:06.459Z" }, ] [[package]] @@ -2322,13 +2351,13 @@ name = "pyobjc-framework-carbon" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/22/15/51964f36a8ae1002b16d213d2e5ba11cc861bdd9369f1e3f116350d788c5/pyobjc_framework_carbon-11.0.tar.gz", hash = "sha256:476f690f0b34aa9e4cb3923e61481aefdcf33e38ec6087b530a94871eee2b914", size = 37538 } +sdist = { url = "https://files.pythonhosted.org/packages/22/15/51964f36a8ae1002b16d213d2e5ba11cc861bdd9369f1e3f116350d788c5/pyobjc_framework_carbon-11.0.tar.gz", hash = "sha256:476f690f0b34aa9e4cb3923e61481aefdcf33e38ec6087b530a94871eee2b914", size = 37538, upload-time = "2025-01-14T19:02:51.62Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/93/fb/e5724934c3a2bbed4fbda4230e15a8b7b86313b39491876647300cb4fb11/pyobjc_framework_Carbon-11.0-py2.py3-none-any.whl", hash = "sha256:beef5095269d8e5427e09f9687963515c1b79fbf6927ff756a8414445892987d", size = 4700 }, - { url = "https://files.pythonhosted.org/packages/1a/3d/b53c2d8949067f3f45491e250620e437569f1b4e6a028f2f5e721726283e/pyobjc_framework_Carbon-11.0-py3-none-any.whl", hash = "sha256:9a269042e8f5705897ac64d2b48515ba055462c88460cf140f5d8d4b8c806a42", size = 4768 }, + { url = "https://files.pythonhosted.org/packages/93/fb/e5724934c3a2bbed4fbda4230e15a8b7b86313b39491876647300cb4fb11/pyobjc_framework_Carbon-11.0-py2.py3-none-any.whl", hash = "sha256:beef5095269d8e5427e09f9687963515c1b79fbf6927ff756a8414445892987d", size = 4700, upload-time = "2025-01-14T18:49:07.341Z" }, + { url = "https://files.pythonhosted.org/packages/1a/3d/b53c2d8949067f3f45491e250620e437569f1b4e6a028f2f5e721726283e/pyobjc_framework_Carbon-11.0-py3-none-any.whl", hash = "sha256:9a269042e8f5705897ac64d2b48515ba055462c88460cf140f5d8d4b8c806a42", size = 4768, upload-time = "2025-01-14T18:49:10.256Z" }, ] [[package]] @@ -2336,13 +2365,13 @@ name = "pyobjc-framework-cfnetwork" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/4f/36/7cebdfb621c7d46eeab3173256bc2e1cba1bbbbe6c0ac8aeb9a4fe2a4627/pyobjc_framework_cfnetwork-11.0.tar.gz", hash = "sha256:eb742fc6a42b248886ff09c3cf247d56e65236864bbea4264e70af8377948d96", size = 78532 } +sdist = { url = "https://files.pythonhosted.org/packages/4f/36/7cebdfb621c7d46eeab3173256bc2e1cba1bbbbe6c0ac8aeb9a4fe2a4627/pyobjc_framework_cfnetwork-11.0.tar.gz", hash = "sha256:eb742fc6a42b248886ff09c3cf247d56e65236864bbea4264e70af8377948d96", size = 78532, upload-time = "2025-01-14T19:02:52.777Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d9/85/11047cfe2d31c242694d780783f0dea81d73cbb09929c7d4b918ce2d29bf/pyobjc_framework_CFNetwork-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6e6905c86ccb5608f4153aacb931758ad39af8b708fcebb497431f9741f39e6d", size = 18988 }, - { url = "https://files.pythonhosted.org/packages/3e/6e/7d90c329030e7dd6ebbec217434820ff6158a3af9906e2abbb43e9b685d6/pyobjc_framework_CFNetwork-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5f61010503073e3518e29d440079a7c0b40aef91be6d3c2032e492c21bada80b", size = 19144 }, + { url = "https://files.pythonhosted.org/packages/d9/85/11047cfe2d31c242694d780783f0dea81d73cbb09929c7d4b918ce2d29bf/pyobjc_framework_CFNetwork-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6e6905c86ccb5608f4153aacb931758ad39af8b708fcebb497431f9741f39e6d", size = 18988, upload-time = "2025-01-14T18:48:54.869Z" }, + { url = "https://files.pythonhosted.org/packages/3e/6e/7d90c329030e7dd6ebbec217434820ff6158a3af9906e2abbb43e9b685d6/pyobjc_framework_CFNetwork-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5f61010503073e3518e29d440079a7c0b40aef91be6d3c2032e492c21bada80b", size = 19144, upload-time = "2025-01-14T18:48:55.864Z" }, ] [[package]] @@ -2350,16 +2379,16 @@ name = "pyobjc-framework-cinematic" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-metal" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/33/ef/b5857d567cd6e0366f61c381ebea52383b98d1ac03341f39e779a085812a/pyobjc_framework_cinematic-11.0.tar.gz", hash = "sha256:94a2de8bf3f38bd190311b6bf98d1e2cea7888840b3ce3aa92e464c0216a5cdb", size = 25740 } +sdist = { url = "https://files.pythonhosted.org/packages/33/ef/b5857d567cd6e0366f61c381ebea52383b98d1ac03341f39e779a085812a/pyobjc_framework_cinematic-11.0.tar.gz", hash = "sha256:94a2de8bf3f38bd190311b6bf98d1e2cea7888840b3ce3aa92e464c0216a5cdb", size = 25740, upload-time = "2025-01-14T19:02:54.95Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/55/cf/a60e131bddf5cced32a3c0050d264f2255d63c45be398cede1db03ea8b51/pyobjc_framework_Cinematic-11.0-py2.py3-none-any.whl", hash = "sha256:281721969978d726ded9bae38c4acd6713495c399025ff2b4179fc02ec68b336", size = 4508 }, - { url = "https://files.pythonhosted.org/packages/09/a8/4ea347c1fc5774e2bbe7bb688fc625d583103d1e212f7b896ed19d14844b/pyobjc_framework_Cinematic-11.0-py3-none-any.whl", hash = "sha256:3a24f3528d7f77637f51fd1862cc8c79e4d0da4ba6fd3dd02b54adddec365826", size = 4580 }, + { url = "https://files.pythonhosted.org/packages/55/cf/a60e131bddf5cced32a3c0050d264f2255d63c45be398cede1db03ea8b51/pyobjc_framework_Cinematic-11.0-py2.py3-none-any.whl", hash = "sha256:281721969978d726ded9bae38c4acd6713495c399025ff2b4179fc02ec68b336", size = 4508, upload-time = "2025-01-14T18:49:11.202Z" }, + { url = "https://files.pythonhosted.org/packages/09/a8/4ea347c1fc5774e2bbe7bb688fc625d583103d1e212f7b896ed19d14844b/pyobjc_framework_Cinematic-11.0-py3-none-any.whl", hash = "sha256:3a24f3528d7f77637f51fd1862cc8c79e4d0da4ba6fd3dd02b54adddec365826", size = 4580, upload-time = "2025-01-14T18:49:12.251Z" }, ] [[package]] @@ -2367,13 +2396,13 @@ name = "pyobjc-framework-classkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f5/81/126075eaf5ccf254ddb4cfd99d92a266c30803c5b4572ea3a920fd85e850/pyobjc_framework_classkit-11.0.tar.gz", hash = "sha256:dc5b3856612cafdc7071fbebc252b8908dbf2433e0e5ddb15a0bcd1ee282d27c", size = 39301 } +sdist = { url = "https://files.pythonhosted.org/packages/f5/81/126075eaf5ccf254ddb4cfd99d92a266c30803c5b4572ea3a920fd85e850/pyobjc_framework_classkit-11.0.tar.gz", hash = "sha256:dc5b3856612cafdc7071fbebc252b8908dbf2433e0e5ddb15a0bcd1ee282d27c", size = 39301, upload-time = "2025-01-14T19:02:55.779Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a8/77/2e31bcf1e9b63f6723c01329c1191ac163e79b0f548b7cd92414115c26ff/pyobjc_framework_ClassKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:723a07591e1e40380c339b58033e8491e58be4080c0f77a26be0728f1c5025c8", size = 8776 }, - { url = "https://files.pythonhosted.org/packages/68/87/f566c4f1ffd1e383c7b38cd22753dfef0863f30bfdb0b3c5102293057fc2/pyobjc_framework_ClassKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7c7ff2eb8a9d87cb69618668e96c41ed9467fd4b4a8fef517c49923c0f6418e6", size = 8794 }, + { url = "https://files.pythonhosted.org/packages/a8/77/2e31bcf1e9b63f6723c01329c1191ac163e79b0f548b7cd92414115c26ff/pyobjc_framework_ClassKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:723a07591e1e40380c339b58033e8491e58be4080c0f77a26be0728f1c5025c8", size = 8776, upload-time = "2025-01-14T18:49:14.05Z" }, + { url = "https://files.pythonhosted.org/packages/68/87/f566c4f1ffd1e383c7b38cd22753dfef0863f30bfdb0b3c5102293057fc2/pyobjc_framework_ClassKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7c7ff2eb8a9d87cb69618668e96c41ed9467fd4b4a8fef517c49923c0f6418e6", size = 8794, upload-time = "2025-01-14T18:49:14.985Z" }, ] [[package]] @@ -2381,16 +2410,16 @@ name = "pyobjc-framework-cloudkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accounts", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-accounts" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, + { name = "pyobjc-framework-corelocation" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/89/6c/b0709fed7fc5a1e81de311b9273bb7ba3820a636f8ba880e90510bb6d460/pyobjc_framework_cloudkit-11.0.tar.gz", hash = "sha256:e3f6bf2c3358dd394174b1e69fcec6859951fcd15f6433c6fa3082e3b7e2656d", size = 123034 } +sdist = { url = "https://files.pythonhosted.org/packages/89/6c/b0709fed7fc5a1e81de311b9273bb7ba3820a636f8ba880e90510bb6d460/pyobjc_framework_cloudkit-11.0.tar.gz", hash = "sha256:e3f6bf2c3358dd394174b1e69fcec6859951fcd15f6433c6fa3082e3b7e2656d", size = 123034, upload-time = "2025-01-14T19:02:56.769Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c2/db/9f914422be88eb2c917d67aebac9dde2e272ea1b510ca1e0db17a09db125/pyobjc_framework_CloudKit-11.0-py2.py3-none-any.whl", hash = "sha256:10cb153d7185dd260d21596f75fca8502236f6afd8e72e866cff8acd9c025f14", size = 10785 }, - { url = "https://files.pythonhosted.org/packages/53/73/239581763a1bd56475ebd9bdde52a79cf0b6cac20b3d4442283b1ef8705c/pyobjc_framework_CloudKit-11.0-py3-none-any.whl", hash = "sha256:b2376d92d5822ce7e4feefcffdc3f4d1d230929f1735793da6d36b52b161b552", size = 10854 }, + { url = "https://files.pythonhosted.org/packages/c2/db/9f914422be88eb2c917d67aebac9dde2e272ea1b510ca1e0db17a09db125/pyobjc_framework_CloudKit-11.0-py2.py3-none-any.whl", hash = "sha256:10cb153d7185dd260d21596f75fca8502236f6afd8e72e866cff8acd9c025f14", size = 10785, upload-time = "2025-01-14T18:49:21.369Z" }, + { url = "https://files.pythonhosted.org/packages/53/73/239581763a1bd56475ebd9bdde52a79cf0b6cac20b3d4442283b1ef8705c/pyobjc_framework_CloudKit-11.0-py3-none-any.whl", hash = "sha256:b2376d92d5822ce7e4feefcffdc3f4d1d230929f1735793da6d36b52b161b552", size = 10854, upload-time = "2025-01-14T18:49:23.612Z" }, ] [[package]] @@ -2398,12 +2427,12 @@ name = "pyobjc-framework-cocoa" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c5/32/53809096ad5fc3e7a2c5ddea642590a5f2cb5b81d0ad6ea67fdb2263d9f9/pyobjc_framework_cocoa-11.0.tar.gz", hash = "sha256:00346a8cb81ad7b017b32ff7bf596000f9faa905807b1bd234644ebd47f692c5", size = 6173848 } +sdist = { url = "https://files.pythonhosted.org/packages/c5/32/53809096ad5fc3e7a2c5ddea642590a5f2cb5b81d0ad6ea67fdb2263d9f9/pyobjc_framework_cocoa-11.0.tar.gz", hash = "sha256:00346a8cb81ad7b017b32ff7bf596000f9faa905807b1bd234644ebd47f692c5", size = 6173848, upload-time = "2025-01-14T19:03:00.125Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/23/97/81fd41ad90e9c241172110aa635a6239d56f50d75923aaedbbe351828580/pyobjc_framework_Cocoa-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3ea7be6e6dd801b297440de02d312ba3fa7fd3c322db747ae1cb237e975f5d33", size = 385534 }, - { url = "https://files.pythonhosted.org/packages/5b/8d/0e2558447c26b3ba64f7c9776a5a6c9d2ae8abf9d34308b174ae0934402e/pyobjc_framework_Cocoa-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:280a577b83c68175a28b2b7138d1d2d3111f2b2b66c30e86f81a19c2b02eae71", size = 385811 }, + { url = "https://files.pythonhosted.org/packages/23/97/81fd41ad90e9c241172110aa635a6239d56f50d75923aaedbbe351828580/pyobjc_framework_Cocoa-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3ea7be6e6dd801b297440de02d312ba3fa7fd3c322db747ae1cb237e975f5d33", size = 385534, upload-time = "2025-01-14T18:49:27.898Z" }, + { url = "https://files.pythonhosted.org/packages/5b/8d/0e2558447c26b3ba64f7c9776a5a6c9d2ae8abf9d34308b174ae0934402e/pyobjc_framework_Cocoa-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:280a577b83c68175a28b2b7138d1d2d3111f2b2b66c30e86f81a19c2b02eae71", size = 385811, upload-time = "2025-01-14T18:49:29.259Z" }, ] [[package]] @@ -2411,13 +2440,13 @@ name = "pyobjc-framework-collaboration" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/6b/ee/1f6893eb882af5ecc6a6f4182b2ec85df777c4bc6b9a20a6b42c23abff3f/pyobjc_framework_collaboration-11.0.tar.gz", hash = "sha256:9f53929dd6d5b1a5511494432bf83807041c6f8b9ab6cf6ff184eee0b6f8226f", size = 17084 } +sdist = { url = "https://files.pythonhosted.org/packages/6b/ee/1f6893eb882af5ecc6a6f4182b2ec85df777c4bc6b9a20a6b42c23abff3f/pyobjc_framework_collaboration-11.0.tar.gz", hash = "sha256:9f53929dd6d5b1a5511494432bf83807041c6f8b9ab6cf6ff184eee0b6f8226f", size = 17084, upload-time = "2025-01-14T19:03:01.98Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c1/ee/95883b6fbdbeecd99217c50c415ca024db5beb1923b935189a113412203d/pyobjc_framework_Collaboration-11.0-py2.py3-none-any.whl", hash = "sha256:acf11e584e21f6342e6d7be1675f36c92804082c29d2f373d1ca623a63959e76", size = 4807 }, - { url = "https://files.pythonhosted.org/packages/c0/e5/d3ba7e3e3f306ba93c021c083287c668704d84605e0f788583abcfde815f/pyobjc_framework_Collaboration-11.0-py3-none-any.whl", hash = "sha256:e7789503ea9280ba365ce2c4e6c7c8b13dfa9174b2ecf9d174bbf9773f25f97a", size = 4876 }, + { url = "https://files.pythonhosted.org/packages/c1/ee/95883b6fbdbeecd99217c50c415ca024db5beb1923b935189a113412203d/pyobjc_framework_Collaboration-11.0-py2.py3-none-any.whl", hash = "sha256:acf11e584e21f6342e6d7be1675f36c92804082c29d2f373d1ca623a63959e76", size = 4807, upload-time = "2025-01-14T18:49:37.145Z" }, + { url = "https://files.pythonhosted.org/packages/c0/e5/d3ba7e3e3f306ba93c021c083287c668704d84605e0f788583abcfde815f/pyobjc_framework_Collaboration-11.0-py3-none-any.whl", hash = "sha256:e7789503ea9280ba365ce2c4e6c7c8b13dfa9174b2ecf9d174bbf9773f25f97a", size = 4876, upload-time = "2025-01-14T18:49:39.887Z" }, ] [[package]] @@ -2425,13 +2454,13 @@ name = "pyobjc-framework-colorsync" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9a/24/397a80cd2313cc9e1b73b9acb1de66b740bbece4fe87ed4ea158de8fcef8/pyobjc_framework_colorsync-11.0.tar.gz", hash = "sha256:4f531f6075d9cc4b9d426620a1b04d3aaeb56b5ff178d0a6b0e93d068a5db0d2", size = 39249 } +sdist = { url = "https://files.pythonhosted.org/packages/9a/24/397a80cd2313cc9e1b73b9acb1de66b740bbece4fe87ed4ea158de8fcef8/pyobjc_framework_colorsync-11.0.tar.gz", hash = "sha256:4f531f6075d9cc4b9d426620a1b04d3aaeb56b5ff178d0a6b0e93d068a5db0d2", size = 39249, upload-time = "2025-01-14T19:03:02.887Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/78/16/d806b5c3ff5bf8f46a4770f89b2076d2596c1301c851c60bb43aea457cd3/pyobjc_framework_ColorSync-11.0-py2.py3-none-any.whl", hash = "sha256:24f5c3e0987bfdfe6a0de36f2f908e30ea52000eb649db7b0373928140518163", size = 5916 }, - { url = "https://files.pythonhosted.org/packages/06/18/777bad37aab42f75d2ef2efb9240308c15c33b3a0636278111ec6c5df550/pyobjc_framework_ColorSync-11.0-py3-none-any.whl", hash = "sha256:cbee2211f64be927eb4e4717bf6e275bf28954ed86e4a4655d367c30f856494d", size = 5987 }, + { url = "https://files.pythonhosted.org/packages/78/16/d806b5c3ff5bf8f46a4770f89b2076d2596c1301c851c60bb43aea457cd3/pyobjc_framework_ColorSync-11.0-py2.py3-none-any.whl", hash = "sha256:24f5c3e0987bfdfe6a0de36f2f908e30ea52000eb649db7b0373928140518163", size = 5916, upload-time = "2025-01-14T18:49:41.273Z" }, + { url = "https://files.pythonhosted.org/packages/06/18/777bad37aab42f75d2ef2efb9240308c15c33b3a0636278111ec6c5df550/pyobjc_framework_ColorSync-11.0-py3-none-any.whl", hash = "sha256:cbee2211f64be927eb4e4717bf6e275bf28954ed86e4a4655d367c30f856494d", size = 5987, upload-time = "2025-01-14T18:49:42.286Z" }, ] [[package]] @@ -2439,13 +2468,13 @@ name = "pyobjc-framework-contacts" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f5/a2/89053853b28c1f2f2e69092d3e81b7c26073bc8396fc87772b3b1bfb9d57/pyobjc_framework_contacts-11.0.tar.gz", hash = "sha256:fc215baa9f66dbf9ffa1cb8170d102a3546cfd708b2b42de4e9d43645aec03d9", size = 84253 } +sdist = { url = "https://files.pythonhosted.org/packages/f5/a2/89053853b28c1f2f2e69092d3e81b7c26073bc8396fc87772b3b1bfb9d57/pyobjc_framework_contacts-11.0.tar.gz", hash = "sha256:fc215baa9f66dbf9ffa1cb8170d102a3546cfd708b2b42de4e9d43645aec03d9", size = 84253, upload-time = "2025-01-14T19:03:03.743Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/91/4f/b7a7b08535015494940a62fd63825eccf4cace7f8ca87050f0837470eca8/pyobjc_framework_Contacts-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b16758fc1edc40f0ec288d67b7e39b59609fb1df2523f4362c958d150619dbe5", size = 11880 }, - { url = "https://files.pythonhosted.org/packages/07/4b/0d2b41a32b6432182548cb84bb6b1c3228a7ff428ea15dfaf812b39c028f/pyobjc_framework_Contacts-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:80972851e2163b94d82fd4b0d9801790ad420dffa91a37c90fa2949031881c02", size = 11957 }, + { url = "https://files.pythonhosted.org/packages/91/4f/b7a7b08535015494940a62fd63825eccf4cace7f8ca87050f0837470eca8/pyobjc_framework_Contacts-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b16758fc1edc40f0ec288d67b7e39b59609fb1df2523f4362c958d150619dbe5", size = 11880, upload-time = "2025-01-14T18:49:44.316Z" }, + { url = "https://files.pythonhosted.org/packages/07/4b/0d2b41a32b6432182548cb84bb6b1c3228a7ff428ea15dfaf812b39c028f/pyobjc_framework_Contacts-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:80972851e2163b94d82fd4b0d9801790ad420dffa91a37c90fa2949031881c02", size = 11957, upload-time = "2025-01-14T18:49:46.952Z" }, ] [[package]] @@ -2453,14 +2482,14 @@ name = "pyobjc-framework-contactsui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contacts", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-contacts" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3f/67/122b16fd7f2da7f0f48c1d7fcaf0f1951253ddd5489d909a1b5fb80f3925/pyobjc_framework_contactsui-11.0.tar.gz", hash = "sha256:d0f2a4afea807fbe4db1518c4f81f0dc9aa1817fe7cb16115308fc00375a70db", size = 19486 } +sdist = { url = "https://files.pythonhosted.org/packages/3f/67/122b16fd7f2da7f0f48c1d7fcaf0f1951253ddd5489d909a1b5fb80f3925/pyobjc_framework_contactsui-11.0.tar.gz", hash = "sha256:d0f2a4afea807fbe4db1518c4f81f0dc9aa1817fe7cb16115308fc00375a70db", size = 19486, upload-time = "2025-01-14T19:03:04.72Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fc/47/b1dbe48c64e2d061bf8b4ee532413b97e6c5748fdba43598a30421086fcc/pyobjc_framework_ContactsUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:fd3efaf3f67e92704f41927c5de06ccc4aa9daa09865cba7ac476da9c6e1c3c2", size = 7734 }, - { url = "https://files.pythonhosted.org/packages/5d/c5/465656c744301bfb7640e4077c57170d245843311e0e66702b53295e2534/pyobjc_framework_ContactsUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:da9c85dccdf518a0ac80c627daca32d56a4636e3f118359579de51a428e85ba7", size = 7739 }, + { url = "https://files.pythonhosted.org/packages/fc/47/b1dbe48c64e2d061bf8b4ee532413b97e6c5748fdba43598a30421086fcc/pyobjc_framework_ContactsUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:fd3efaf3f67e92704f41927c5de06ccc4aa9daa09865cba7ac476da9c6e1c3c2", size = 7734, upload-time = "2025-01-14T18:49:52.765Z" }, + { url = "https://files.pythonhosted.org/packages/5d/c5/465656c744301bfb7640e4077c57170d245843311e0e66702b53295e2534/pyobjc_framework_ContactsUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:da9c85dccdf518a0ac80c627daca32d56a4636e3f118359579de51a428e85ba7", size = 7739, upload-time = "2025-01-14T18:49:55.507Z" }, ] [[package]] @@ -2468,13 +2497,13 @@ name = "pyobjc-framework-coreaudio" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/31/e6/3b7a8af3defec012d6cacf277fd8d5c3e254ceace63a05447dc1119f3a7e/pyobjc_framework_coreaudio-11.0.tar.gz", hash = "sha256:38b6b531381119be6998cf704d04c9ea475aaa33f6dd460e0584351475acd0ae", size = 140507 } +sdist = { url = "https://files.pythonhosted.org/packages/31/e6/3b7a8af3defec012d6cacf277fd8d5c3e254ceace63a05447dc1119f3a7e/pyobjc_framework_coreaudio-11.0.tar.gz", hash = "sha256:38b6b531381119be6998cf704d04c9ea475aaa33f6dd460e0584351475acd0ae", size = 140507, upload-time = "2025-01-14T19:03:05.612Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/78/f8/6f583376d2ef6a6123141d310f7f7e3e93ba9129ffbbc6eb26e25c4289c5/pyobjc_framework_CoreAudio-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:143cd44d5c069aee1abc5a88794e9531250b9fe70a98f6a08e493184dcf64b3e", size = 35750 }, - { url = "https://files.pythonhosted.org/packages/df/14/b33556c06529a3c54853c41c5163e30a3fb9b2ae920e0c65a42ccd82e279/pyobjc_framework_CoreAudio-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d26eac5bc325bf046fc0bfdaa3322ddc828690dab726275f1c4c118bb888cc00", size = 36584 }, + { url = "https://files.pythonhosted.org/packages/78/f8/6f583376d2ef6a6123141d310f7f7e3e93ba9129ffbbc6eb26e25c4289c5/pyobjc_framework_CoreAudio-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:143cd44d5c069aee1abc5a88794e9531250b9fe70a98f6a08e493184dcf64b3e", size = 35750, upload-time = "2025-01-14T18:50:00.665Z" }, + { url = "https://files.pythonhosted.org/packages/df/14/b33556c06529a3c54853c41c5163e30a3fb9b2ae920e0c65a42ccd82e279/pyobjc_framework_CoreAudio-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d26eac5bc325bf046fc0bfdaa3322ddc828690dab726275f1c4c118bb888cc00", size = 36584, upload-time = "2025-01-14T18:50:01.806Z" }, ] [[package]] @@ -2482,14 +2511,14 @@ name = "pyobjc-framework-coreaudiokit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ef/1a/604cac8d992b6e66adbb98edb1f65820116f5d74d8decd6d43898ae2929d/pyobjc_framework_coreaudiokit-11.0.tar.gz", hash = "sha256:1a4c3de4a02b0dfa7410c012c7f0939edd2e127d439fb934aeafc68450615f1d", size = 21450 } +sdist = { url = "https://files.pythonhosted.org/packages/ef/1a/604cac8d992b6e66adbb98edb1f65820116f5d74d8decd6d43898ae2929d/pyobjc_framework_coreaudiokit-11.0.tar.gz", hash = "sha256:1a4c3de4a02b0dfa7410c012c7f0939edd2e127d439fb934aeafc68450615f1d", size = 21450, upload-time = "2025-01-14T19:03:06.681Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4c/b9/d75a4da2d6a3cb75bafd363c447d45e134fe78a340dee408423a40c04aac/pyobjc_framework_CoreAudioKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6dbf01f2625689b392c2ba02f3ab8186c914d84d6bd896bdef5181a15a9463df", size = 7192 }, - { url = "https://files.pythonhosted.org/packages/46/1f/5c15023665cc0476cdd7cbc054d5b06489fc09990f068768ed2fda8a02a2/pyobjc_framework_CoreAudioKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8ccf2d92052a446d1d38bfd7eaa1dcd2451d59c37e73070a9a1fee394a532d9d", size = 7214 }, + { url = "https://files.pythonhosted.org/packages/4c/b9/d75a4da2d6a3cb75bafd363c447d45e134fe78a340dee408423a40c04aac/pyobjc_framework_CoreAudioKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6dbf01f2625689b392c2ba02f3ab8186c914d84d6bd896bdef5181a15a9463df", size = 7192, upload-time = "2025-01-14T18:50:09.524Z" }, + { url = "https://files.pythonhosted.org/packages/46/1f/5c15023665cc0476cdd7cbc054d5b06489fc09990f068768ed2fda8a02a2/pyobjc_framework_CoreAudioKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8ccf2d92052a446d1d38bfd7eaa1dcd2451d59c37e73070a9a1fee394a532d9d", size = 7214, upload-time = "2025-01-14T18:50:10.399Z" }, ] [[package]] @@ -2497,13 +2526,13 @@ name = "pyobjc-framework-corebluetooth" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/93/74/66a62a36da9db5924ee15de6fe1eb544930609b307b3bfbc021b5cf43781/pyobjc_framework_corebluetooth-11.0.tar.gz", hash = "sha256:1dcb7c039c2efa7c72dc14cdda80e677240b49fa38999941a77ee02ca142998d", size = 59797 } +sdist = { url = "https://files.pythonhosted.org/packages/93/74/66a62a36da9db5924ee15de6fe1eb544930609b307b3bfbc021b5cf43781/pyobjc_framework_corebluetooth-11.0.tar.gz", hash = "sha256:1dcb7c039c2efa7c72dc14cdda80e677240b49fa38999941a77ee02ca142998d", size = 59797, upload-time = "2025-01-14T19:03:07.584Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/53/a8/df866e8a84fd33d29af1ee383f13715bbd98ad67d5795dfb276a3887560f/pyobjc_framework_CoreBluetooth-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:044069d63447554ba2c65cb1bf58d489d14ea279344810386392e583a2e611ef", size = 13683 }, - { url = "https://files.pythonhosted.org/packages/44/fa/ad2165bc93c9d3fb174a0d8d5a4db3a7dfcf4dcaeca7913d59748ef62fdb/pyobjc_framework_CoreBluetooth-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:bae8f909512d014eed85f80deae671185af4bb5a671fba19f85c7b4c973b61bb", size = 13713 }, + { url = "https://files.pythonhosted.org/packages/53/a8/df866e8a84fd33d29af1ee383f13715bbd98ad67d5795dfb276a3887560f/pyobjc_framework_CoreBluetooth-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:044069d63447554ba2c65cb1bf58d489d14ea279344810386392e583a2e611ef", size = 13683, upload-time = "2025-01-14T18:50:16.231Z" }, + { url = "https://files.pythonhosted.org/packages/44/fa/ad2165bc93c9d3fb174a0d8d5a4db3a7dfcf4dcaeca7913d59748ef62fdb/pyobjc_framework_CoreBluetooth-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:bae8f909512d014eed85f80deae671185af4bb5a671fba19f85c7b4c973b61bb", size = 13713, upload-time = "2025-01-14T18:50:17.122Z" }, ] [[package]] @@ -2511,13 +2540,13 @@ name = "pyobjc-framework-coredata" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/84/22/6787205b91cb6d526b6b472ebaa5baff275200774050a55b4b25d2bd957a/pyobjc_framework_coredata-11.0.tar.gz", hash = "sha256:b11acb51ff31cfb69a53f4e127996bf194bcac770e8fa67cb5ba3fb16a496058", size = 260029 } +sdist = { url = "https://files.pythonhosted.org/packages/84/22/6787205b91cb6d526b6b472ebaa5baff275200774050a55b4b25d2bd957a/pyobjc_framework_coredata-11.0.tar.gz", hash = "sha256:b11acb51ff31cfb69a53f4e127996bf194bcac770e8fa67cb5ba3fb16a496058", size = 260029, upload-time = "2025-01-14T19:03:08.609Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/86/b0/32c23ee168e5081391daa8737fddde79670b083e948dffb8d74308f1dd43/pyobjc_framework_CoreData-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:74ac5e7658df10544708f6017a8823a100fbe41dc3aa9f61bf2fd4f8773c3dd7", size = 16194 }, - { url = "https://files.pythonhosted.org/packages/6a/9e/39ca8124c6d87dc6fa85bcf850a2c23a062a408a26300062041c10363a3f/pyobjc_framework_CoreData-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c23b8c9106b0ec6f43aca80d2b2e0b0cc8fcb4ba78db4ae3c1f39a67464357d7", size = 16208 }, + { url = "https://files.pythonhosted.org/packages/86/b0/32c23ee168e5081391daa8737fddde79670b083e948dffb8d74308f1dd43/pyobjc_framework_CoreData-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:74ac5e7658df10544708f6017a8823a100fbe41dc3aa9f61bf2fd4f8773c3dd7", size = 16194, upload-time = "2025-01-14T18:50:22.924Z" }, + { url = "https://files.pythonhosted.org/packages/6a/9e/39ca8124c6d87dc6fa85bcf850a2c23a062a408a26300062041c10363a3f/pyobjc_framework_CoreData-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c23b8c9106b0ec6f43aca80d2b2e0b0cc8fcb4ba78db4ae3c1f39a67464357d7", size = 16208, upload-time = "2025-01-14T18:50:23.838Z" }, ] [[package]] @@ -2525,13 +2554,13 @@ name = "pyobjc-framework-corehaptics" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2a/b8/66481497362171e7ad42fc8fcc0272c04b95a707c5c1e7e8f8a8bfe58917/pyobjc_framework_corehaptics-11.0.tar.gz", hash = "sha256:1949b56ac0bd4219eb04c466cdd0f7f93d6826ed92ee61f01a4b5e98139ee039", size = 42956 } +sdist = { url = "https://files.pythonhosted.org/packages/2a/b8/66481497362171e7ad42fc8fcc0272c04b95a707c5c1e7e8f8a8bfe58917/pyobjc_framework_corehaptics-11.0.tar.gz", hash = "sha256:1949b56ac0bd4219eb04c466cdd0f7f93d6826ed92ee61f01a4b5e98139ee039", size = 42956, upload-time = "2025-01-14T19:03:09.753Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/96/16/16d4365c8da1f708e145500237a3cdbbdde3e83b7f3f8673b038efac03b9/pyobjc_framework_CoreHaptics-11.0-py2.py3-none-any.whl", hash = "sha256:ff1d8f58dd3b29287dfad16a60bb45706c91f1910e400b632cb664eb2e56588b", size = 5307 }, - { url = "https://files.pythonhosted.org/packages/12/72/b9fca92b3704af8f5f3b5507d0d9f3d0f5eb16605664de669f4468858627/pyobjc_framework_CoreHaptics-11.0-py3-none-any.whl", hash = "sha256:33f7a767efe6867fa6821ad73872ea88aec44650a22217bcdc9c1ec7c41fd9dc", size = 5377 }, + { url = "https://files.pythonhosted.org/packages/96/16/16d4365c8da1f708e145500237a3cdbbdde3e83b7f3f8673b038efac03b9/pyobjc_framework_CoreHaptics-11.0-py2.py3-none-any.whl", hash = "sha256:ff1d8f58dd3b29287dfad16a60bb45706c91f1910e400b632cb664eb2e56588b", size = 5307, upload-time = "2025-01-14T18:50:33.074Z" }, + { url = "https://files.pythonhosted.org/packages/12/72/b9fca92b3704af8f5f3b5507d0d9f3d0f5eb16605664de669f4468858627/pyobjc_framework_CoreHaptics-11.0-py3-none-any.whl", hash = "sha256:33f7a767efe6867fa6821ad73872ea88aec44650a22217bcdc9c1ec7c41fd9dc", size = 5377, upload-time = "2025-01-14T18:50:34.484Z" }, ] [[package]] @@ -2539,13 +2568,13 @@ name = "pyobjc-framework-corelocation" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0a/2d/b21ca49a34db49390420a9d7d05fd9eb89850dbec0a555c9ee408f52609c/pyobjc_framework_corelocation-11.0.tar.gz", hash = "sha256:05055c3b567f7f8f796845da43fb755d84d630909b927a39f25cf706ef52687d", size = 103955 } +sdist = { url = "https://files.pythonhosted.org/packages/0a/2d/b21ca49a34db49390420a9d7d05fd9eb89850dbec0a555c9ee408f52609c/pyobjc_framework_corelocation-11.0.tar.gz", hash = "sha256:05055c3b567f7f8f796845da43fb755d84d630909b927a39f25cf706ef52687d", size = 103955, upload-time = "2025-01-14T19:03:10.707Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/10/99/c7844f6e583f4764c6fab4a5b5ad9e949c6fce8c30f95226118bead41e01/pyobjc_framework_CoreLocation-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:046f211a23de55364c8553cfd660dc5adeff28af4d25f5ed9b5a8bfa83266b4d", size = 13075 }, - { url = "https://files.pythonhosted.org/packages/88/6b/bb4fbcd259404fb60fdbfecef3c426dc23da5a0f0bc5bf96a4169b047478/pyobjc_framework_CoreLocation-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9bca9974f143bc9e93bd7ec4ef91655964d8ad0ca5ffccc8404fb6f098fa08dc", size = 13076 }, + { url = "https://files.pythonhosted.org/packages/10/99/c7844f6e583f4764c6fab4a5b5ad9e949c6fce8c30f95226118bead41e01/pyobjc_framework_CoreLocation-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:046f211a23de55364c8553cfd660dc5adeff28af4d25f5ed9b5a8bfa83266b4d", size = 13075, upload-time = "2025-01-14T18:50:37.789Z" }, + { url = "https://files.pythonhosted.org/packages/88/6b/bb4fbcd259404fb60fdbfecef3c426dc23da5a0f0bc5bf96a4169b047478/pyobjc_framework_CoreLocation-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9bca9974f143bc9e93bd7ec4ef91655964d8ad0ca5ffccc8404fb6f098fa08dc", size = 13076, upload-time = "2025-01-14T18:50:38.693Z" }, ] [[package]] @@ -2553,13 +2582,13 @@ name = "pyobjc-framework-coremedia" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/02/60/7c7b9f13c94910882de6cc08f48a52cce9739e75cc3b3b6de5c857e6536a/pyobjc_framework_coremedia-11.0.tar.gz", hash = "sha256:a414db97ba30b43c9dd96213459d6efb169f9e92ce1ad7a75516a679b181ddfb", size = 249161 } +sdist = { url = "https://files.pythonhosted.org/packages/02/60/7c7b9f13c94910882de6cc08f48a52cce9739e75cc3b3b6de5c857e6536a/pyobjc_framework_coremedia-11.0.tar.gz", hash = "sha256:a414db97ba30b43c9dd96213459d6efb169f9e92ce1ad7a75516a679b181ddfb", size = 249161, upload-time = "2025-01-14T19:03:12.291Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a5/b3/7baca352ddd7256840a4eb8f38fda39bc2e023b222b86d11c1a77cc0a8fa/pyobjc_framework_CoreMedia-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:057e63e533577fe5d764a5a9d307f60e8d9c58803112951ace42183abe9437e3", size = 29422 }, - { url = "https://files.pythonhosted.org/packages/68/73/7ed3eba9c5a4a2071c3a64d6b1388d13474ad8d972529f3d5c950942513d/pyobjc_framework_CoreMedia-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:afd8eb59f5ce0730ff15476ad3989aa84ffb8d8d02c9b8b2c9c1248b0541dbff", size = 29297 }, + { url = "https://files.pythonhosted.org/packages/a5/b3/7baca352ddd7256840a4eb8f38fda39bc2e023b222b86d11c1a77cc0a8fa/pyobjc_framework_CoreMedia-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:057e63e533577fe5d764a5a9d307f60e8d9c58803112951ace42183abe9437e3", size = 29422, upload-time = "2025-01-14T18:50:56.964Z" }, + { url = "https://files.pythonhosted.org/packages/68/73/7ed3eba9c5a4a2071c3a64d6b1388d13474ad8d972529f3d5c950942513d/pyobjc_framework_CoreMedia-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:afd8eb59f5ce0730ff15476ad3989aa84ffb8d8d02c9b8b2c9c1248b0541dbff", size = 29297, upload-time = "2025-01-14T18:50:58.388Z" }, ] [[package]] @@ -2567,13 +2596,13 @@ name = "pyobjc-framework-coremediaio" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a1/59/904af57d302caa4c20d3bfebb9fb9300ccc3c396134460821c9f1e8ab65b/pyobjc_framework_coremediaio-11.0.tar.gz", hash = "sha256:7d652cf1a2a75c78ea6e8dbc7fc8b782bfc0f07eafc84b700598172c82f373d8", size = 107856 } +sdist = { url = "https://files.pythonhosted.org/packages/a1/59/904af57d302caa4c20d3bfebb9fb9300ccc3c396134460821c9f1e8ab65b/pyobjc_framework_coremediaio-11.0.tar.gz", hash = "sha256:7d652cf1a2a75c78ea6e8dbc7fc8b782bfc0f07eafc84b700598172c82f373d8", size = 107856, upload-time = "2025-01-14T19:03:14.225Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/27/02/09fda96c4727ff0c632c3cf4b09faa5b82be9f18422860dd80b5bc676ae1/pyobjc_framework_CoreMediaIO-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a4182b91c72923d5c4d52eca3c221cc6f149d80a96242c0caab1d5bc9ccbcbbb", size = 17492 }, - { url = "https://files.pythonhosted.org/packages/3f/db/a7b11cbf7d31964a65c5593ac30a02b0db35260845431046d467b08fc059/pyobjc_framework_CoreMediaIO-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1ad1e0f74126b6c6d25017e4ba08f66fe5422c902060d64b69e06a0c10214355", size = 17534 }, + { url = "https://files.pythonhosted.org/packages/27/02/09fda96c4727ff0c632c3cf4b09faa5b82be9f18422860dd80b5bc676ae1/pyobjc_framework_CoreMediaIO-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a4182b91c72923d5c4d52eca3c221cc6f149d80a96242c0caab1d5bc9ccbcbbb", size = 17492, upload-time = "2025-01-14T18:51:04.559Z" }, + { url = "https://files.pythonhosted.org/packages/3f/db/a7b11cbf7d31964a65c5593ac30a02b0db35260845431046d467b08fc059/pyobjc_framework_CoreMediaIO-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1ad1e0f74126b6c6d25017e4ba08f66fe5422c902060d64b69e06a0c10214355", size = 17534, upload-time = "2025-01-14T18:51:06.752Z" }, ] [[package]] @@ -2581,13 +2610,13 @@ name = "pyobjc-framework-coremidi" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/96/90/d004cdf4c52b8b16842e15135495de882d743b4f0217946bd8ae1a920173/pyobjc_framework_coremidi-11.0.tar.gz", hash = "sha256:acace4448b3e4802ab5dd75bbf875aae5e1f6c8cab2b2f1d58af20fc8b2a5a7f", size = 107342 } +sdist = { url = "https://files.pythonhosted.org/packages/96/90/d004cdf4c52b8b16842e15135495de882d743b4f0217946bd8ae1a920173/pyobjc_framework_coremidi-11.0.tar.gz", hash = "sha256:acace4448b3e4802ab5dd75bbf875aae5e1f6c8cab2b2f1d58af20fc8b2a5a7f", size = 107342, upload-time = "2025-01-14T19:03:15.235Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4d/b9/c67886891ad3cd21107cf1e65f1431cbdcff33acd74bf55ad3d6e10f3adf/pyobjc_framework_CoreMIDI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:78dec1bcd253a0385ac0b758a455e2a9367fc3cb9e2306d410c61bafa8d4c2eb", size = 24314 }, - { url = "https://files.pythonhosted.org/packages/c0/7a/0639bc1ac35373b68f0f15fbcb9bb4f317cc4452997ea8e611ce79f623e9/pyobjc_framework_CoreMIDI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:97158830d76b999255d87191f31624d4373ee8ff662af4f4376c584cfb805573", size = 24346 }, + { url = "https://files.pythonhosted.org/packages/4d/b9/c67886891ad3cd21107cf1e65f1431cbdcff33acd74bf55ad3d6e10f3adf/pyobjc_framework_CoreMIDI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:78dec1bcd253a0385ac0b758a455e2a9367fc3cb9e2306d410c61bafa8d4c2eb", size = 24314, upload-time = "2025-01-14T18:50:44.817Z" }, + { url = "https://files.pythonhosted.org/packages/c0/7a/0639bc1ac35373b68f0f15fbcb9bb4f317cc4452997ea8e611ce79f623e9/pyobjc_framework_CoreMIDI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:97158830d76b999255d87191f31624d4373ee8ff662af4f4376c584cfb805573", size = 24346, upload-time = "2025-01-14T18:50:45.805Z" }, ] [[package]] @@ -2595,13 +2624,13 @@ name = "pyobjc-framework-coreml" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2e/64/4f0a990ec0955fe9b88f1fa58303c8471c551996670216527b4ac559ed8f/pyobjc_framework_coreml-11.0.tar.gz", hash = "sha256:143a1f73a0ea0a0ea103f3175cb87a61bbcb98f70f85320ed4c61302b9156d58", size = 81452 } +sdist = { url = "https://files.pythonhosted.org/packages/2e/64/4f0a990ec0955fe9b88f1fa58303c8471c551996670216527b4ac559ed8f/pyobjc_framework_coreml-11.0.tar.gz", hash = "sha256:143a1f73a0ea0a0ea103f3175cb87a61bbcb98f70f85320ed4c61302b9156d58", size = 81452, upload-time = "2025-01-14T19:03:16.283Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/50/dc/334823bb3faa490259df7611772e804eb883c56436fc69123e8a3a5ba0ea/pyobjc_framework_CoreML-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e290ad9c0ac5f057ce3885d35e33fadc115f59111f2e04f168c45e2890cb86e8", size = 11320 }, - { url = "https://files.pythonhosted.org/packages/90/9f/3d053b95fbeeaf480d33fcc067504e205049591f6bee17e3a700b988d96c/pyobjc_framework_CoreML-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:48320a57589634c206d659799284a5133aaa006cf4562f772697df5b479043e4", size = 11321 }, + { url = "https://files.pythonhosted.org/packages/50/dc/334823bb3faa490259df7611772e804eb883c56436fc69123e8a3a5ba0ea/pyobjc_framework_CoreML-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e290ad9c0ac5f057ce3885d35e33fadc115f59111f2e04f168c45e2890cb86e8", size = 11320, upload-time = "2025-01-14T18:50:50.914Z" }, + { url = "https://files.pythonhosted.org/packages/90/9f/3d053b95fbeeaf480d33fcc067504e205049591f6bee17e3a700b988d96c/pyobjc_framework_CoreML-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:48320a57589634c206d659799284a5133aaa006cf4562f772697df5b479043e4", size = 11321, upload-time = "2025-01-14T18:50:51.803Z" }, ] [[package]] @@ -2609,13 +2638,13 @@ name = "pyobjc-framework-coremotion" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/be/79/5c4ff39a48f0dc0f764d1330b2360e9f31e3a32414e8690e7f20e4574e93/pyobjc_framework_coremotion-11.0.tar.gz", hash = "sha256:d1e7ca418897e35365d07c6fd5b5d625a3c44261b6ce46dcf80787f634ad6fa5", size = 66508 } +sdist = { url = "https://files.pythonhosted.org/packages/be/79/5c4ff39a48f0dc0f764d1330b2360e9f31e3a32414e8690e7f20e4574e93/pyobjc_framework_coremotion-11.0.tar.gz", hash = "sha256:d1e7ca418897e35365d07c6fd5b5d625a3c44261b6ce46dcf80787f634ad6fa5", size = 66508, upload-time = "2025-01-14T19:03:17.254Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/01/35/da29fd7350cd68bfe70f30a9e03e1350d7363c7c4fcdb5b0cd16f4bb47e2/pyobjc_framework_CoreMotion-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8e32de44e30028500e4d17c114eea69e7e74e5ae7aef6c208edc5bac34dfc21e", size = 10229 }, - { url = "https://files.pythonhosted.org/packages/ca/f6/8061b58f0f3e1daf34c19511f0eeefe4ad66d10d1994b84d7fa3733b7852/pyobjc_framework_CoreMotion-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:697a3121615e95e56808f388b0882217a50e5ff6b459eccae93f2809d5ea4389", size = 10250 }, + { url = "https://files.pythonhosted.org/packages/01/35/da29fd7350cd68bfe70f30a9e03e1350d7363c7c4fcdb5b0cd16f4bb47e2/pyobjc_framework_CoreMotion-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8e32de44e30028500e4d17c114eea69e7e74e5ae7aef6c208edc5bac34dfc21e", size = 10229, upload-time = "2025-01-14T18:51:12.825Z" }, + { url = "https://files.pythonhosted.org/packages/ca/f6/8061b58f0f3e1daf34c19511f0eeefe4ad66d10d1994b84d7fa3733b7852/pyobjc_framework_CoreMotion-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:697a3121615e95e56808f388b0882217a50e5ff6b459eccae93f2809d5ea4389", size = 10250, upload-time = "2025-01-14T18:51:13.746Z" }, ] [[package]] @@ -2623,14 +2652,14 @@ name = "pyobjc-framework-coreservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fsevents", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-fsevents" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ca/b5/19c096b9938d6e2fdb1b436f21ad989b77dbeb4e59b3db4bd344800fa1e8/pyobjc_framework_coreservices-11.0.tar.gz", hash = "sha256:ac96954f1945a1153bdfef685611665749eaa8016b5af6f34bd56a274952b03a", size = 1244406 } +sdist = { url = "https://files.pythonhosted.org/packages/ca/b5/19c096b9938d6e2fdb1b436f21ad989b77dbeb4e59b3db4bd344800fa1e8/pyobjc_framework_coreservices-11.0.tar.gz", hash = "sha256:ac96954f1945a1153bdfef685611665749eaa8016b5af6f34bd56a274952b03a", size = 1244406, upload-time = "2025-01-14T19:03:19.202Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e9/cc/3899a59ed62fa36d2c1b95b94ff52e181ac48fde4011b68ca6abcbddd47a/pyobjc_framework_CoreServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f7538ca6e22f4da0c3a70ddd9781f9240a3fe2fd7a7aa4dfb31c31f2532f008e", size = 30258 }, - { url = "https://files.pythonhosted.org/packages/82/7b/8e059764951d0414f053bfebb6b1fba803a3b14397755cfd388b0a6363a7/pyobjc_framework_CoreServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3b175b5aa7a78484fd07b93533174b125901a6b791df2c51e05df1ea5d5badab", size = 30250 }, + { url = "https://files.pythonhosted.org/packages/e9/cc/3899a59ed62fa36d2c1b95b94ff52e181ac48fde4011b68ca6abcbddd47a/pyobjc_framework_CoreServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f7538ca6e22f4da0c3a70ddd9781f9240a3fe2fd7a7aa4dfb31c31f2532f008e", size = 30258, upload-time = "2025-01-14T18:51:20.487Z" }, + { url = "https://files.pythonhosted.org/packages/82/7b/8e059764951d0414f053bfebb6b1fba803a3b14397755cfd388b0a6363a7/pyobjc_framework_CoreServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3b175b5aa7a78484fd07b93533174b125901a6b791df2c51e05df1ea5d5badab", size = 30250, upload-time = "2025-01-14T18:51:21.448Z" }, ] [[package]] @@ -2638,13 +2667,13 @@ name = "pyobjc-framework-corespotlight" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fc/6a/6707d7ef339b9ad2dd0994d1df42969ee3b231f2d098f3377d40aed60b4f/pyobjc_framework_corespotlight-11.0.tar.gz", hash = "sha256:a96c9b4ba473bc3ee19afa01a9af989458e6a56e9656c2cdea1850d2b13720e6", size = 86130 } +sdist = { url = "https://files.pythonhosted.org/packages/fc/6a/6707d7ef339b9ad2dd0994d1df42969ee3b231f2d098f3377d40aed60b4f/pyobjc_framework_corespotlight-11.0.tar.gz", hash = "sha256:a96c9b4ba473bc3ee19afa01a9af989458e6a56e9656c2cdea1850d2b13720e6", size = 86130, upload-time = "2025-01-14T19:03:20.457Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ba/f1/54f9522d7f6ec7a6618c86abe0236869f61dd371b49df02dff7930433656/pyobjc_framework_CoreSpotlight-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:551878bfb9cc815fe2532fdf455f500dda44f8cd203dd836a6f1eb5cc0d49a9a", size = 9579 }, - { url = "https://files.pythonhosted.org/packages/6c/24/dae8d0be7cb90328a8c1100c454e52faef95acc59940796f530b665b9555/pyobjc_framework_CoreSpotlight-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b0c595d0a422a0f81008df93a0a2b38a1fd62434c6f61e31f1dceec927803b80", size = 9597 }, + { url = "https://files.pythonhosted.org/packages/ba/f1/54f9522d7f6ec7a6618c86abe0236869f61dd371b49df02dff7930433656/pyobjc_framework_CoreSpotlight-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:551878bfb9cc815fe2532fdf455f500dda44f8cd203dd836a6f1eb5cc0d49a9a", size = 9579, upload-time = "2025-01-14T18:51:28.889Z" }, + { url = "https://files.pythonhosted.org/packages/6c/24/dae8d0be7cb90328a8c1100c454e52faef95acc59940796f530b665b9555/pyobjc_framework_CoreSpotlight-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b0c595d0a422a0f81008df93a0a2b38a1fd62434c6f61e31f1dceec927803b80", size = 9597, upload-time = "2025-01-14T18:51:30.677Z" }, ] [[package]] @@ -2652,14 +2681,14 @@ name = "pyobjc-framework-coretext" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9d/e8/9b68dc788828e38143a3e834e66346713751cb83d7f0955016323005c1a2/pyobjc_framework_coretext-11.0.tar.gz", hash = "sha256:a68437153e627847e3898754dd3f13ae0cb852246b016a91f9c9cbccb9f91a43", size = 274222 } +sdist = { url = "https://files.pythonhosted.org/packages/9d/e8/9b68dc788828e38143a3e834e66346713751cb83d7f0955016323005c1a2/pyobjc_framework_coretext-11.0.tar.gz", hash = "sha256:a68437153e627847e3898754dd3f13ae0cb852246b016a91f9c9cbccb9f91a43", size = 274222, upload-time = "2025-01-14T19:03:21.521Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f6/20/b8a967101b585a2425ffe645135f8618edd51e1430aeb668373475a07d1f/pyobjc_framework_CoreText-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:56a4889858308b0d9f147d568b4d91c441cc0ffd332497cb4f709bb1990450c1", size = 30397 }, - { url = "https://files.pythonhosted.org/packages/0d/14/d300b8bf18acd1d98d40820d2a9b5c5b6cf96325bdfc5020bc963218e001/pyobjc_framework_CoreText-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fb90e7f370b3fd7cb2fb442e3dc63fedf0b4af6908db1c18df694d10dc94669d", size = 30456 }, + { url = "https://files.pythonhosted.org/packages/f6/20/b8a967101b585a2425ffe645135f8618edd51e1430aeb668373475a07d1f/pyobjc_framework_CoreText-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:56a4889858308b0d9f147d568b4d91c441cc0ffd332497cb4f709bb1990450c1", size = 30397, upload-time = "2025-01-14T18:51:35.844Z" }, + { url = "https://files.pythonhosted.org/packages/0d/14/d300b8bf18acd1d98d40820d2a9b5c5b6cf96325bdfc5020bc963218e001/pyobjc_framework_CoreText-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fb90e7f370b3fd7cb2fb442e3dc63fedf0b4af6908db1c18df694d10dc94669d", size = 30456, upload-time = "2025-01-14T18:51:36.962Z" }, ] [[package]] @@ -2667,13 +2696,13 @@ name = "pyobjc-framework-corewlan" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/2e/a9/cda522b270adb75d62bae447b2131da62912b5eda058a07e3a433689116f/pyobjc_framework_corewlan-11.0.tar.gz", hash = "sha256:8803981d64e3eb4fa0ea56657a9b98e4004de5a84d56e32e5444815d8ed6fa6f", size = 65254 } +sdist = { url = "https://files.pythonhosted.org/packages/2e/a9/cda522b270adb75d62bae447b2131da62912b5eda058a07e3a433689116f/pyobjc_framework_corewlan-11.0.tar.gz", hash = "sha256:8803981d64e3eb4fa0ea56657a9b98e4004de5a84d56e32e5444815d8ed6fa6f", size = 65254, upload-time = "2025-01-14T19:03:23.938Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/da/e7/a869bf3e8673c8fdf496706672dac77fc305493db3c1057e3ca5f8d49c3f/pyobjc_framework_CoreWLAN-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4384ba68d4beb4d610ca0d661593e16efe541faf1790222b898b3f4dd389c98a", size = 9895 }, - { url = "https://files.pythonhosted.org/packages/7c/d7/87626e23f010aa865eef10c796d1d87ddd87b78656f4e4ef0e808c8268f7/pyobjc_framework_CoreWLAN-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5f5c365f6ebdae4a87d534cf8af877a57d2aabe50fe5949a9334e75173291898", size = 9917 }, + { url = "https://files.pythonhosted.org/packages/da/e7/a869bf3e8673c8fdf496706672dac77fc305493db3c1057e3ca5f8d49c3f/pyobjc_framework_CoreWLAN-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4384ba68d4beb4d610ca0d661593e16efe541faf1790222b898b3f4dd389c98a", size = 9895, upload-time = "2025-01-14T18:51:43.245Z" }, + { url = "https://files.pythonhosted.org/packages/7c/d7/87626e23f010aa865eef10c796d1d87ddd87b78656f4e4ef0e808c8268f7/pyobjc_framework_CoreWLAN-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5f5c365f6ebdae4a87d534cf8af877a57d2aabe50fe5949a9334e75173291898", size = 9917, upload-time = "2025-01-14T18:51:45.362Z" }, ] [[package]] @@ -2681,13 +2710,13 @@ name = "pyobjc-framework-cryptotokenkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b8/72/b871fa5476479e4a22a4a0e971fb4724b0eb94c721365539ad55f4dc3135/pyobjc_framework_cryptotokenkit-11.0.tar.gz", hash = "sha256:a1bbfe9170c35cb427d39167af55aefea651c5c8a45c0de60226dae04b61a6b1", size = 58734 } +sdist = { url = "https://files.pythonhosted.org/packages/b8/72/b871fa5476479e4a22a4a0e971fb4724b0eb94c721365539ad55f4dc3135/pyobjc_framework_cryptotokenkit-11.0.tar.gz", hash = "sha256:a1bbfe9170c35cb427d39167af55aefea651c5c8a45c0de60226dae04b61a6b1", size = 58734, upload-time = "2025-01-14T19:03:24.851Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ac/60/ddf022ce94f829a605992f11b9bfa861d7a1579f794e03d969c209d0de2a/pyobjc_framework_CryptoTokenKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3c42620047cc75a749fbed045d181dc76284bc27edea904b97df1ad82c2fdafc", size = 12949 }, - { url = "https://files.pythonhosted.org/packages/d7/2d/9641cae1800281faace48698646f71c3de23ea1343031c12f6637d31e6f1/pyobjc_framework_CryptoTokenKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:95b05efb06b09987e23fb62dc3af378f38cfd0bd5872940cd95cf0f39dac6a57", size = 12978 }, + { url = "https://files.pythonhosted.org/packages/ac/60/ddf022ce94f829a605992f11b9bfa861d7a1579f794e03d969c209d0de2a/pyobjc_framework_CryptoTokenKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3c42620047cc75a749fbed045d181dc76284bc27edea904b97df1ad82c2fdafc", size = 12949, upload-time = "2025-01-14T18:51:50.055Z" }, + { url = "https://files.pythonhosted.org/packages/d7/2d/9641cae1800281faace48698646f71c3de23ea1343031c12f6637d31e6f1/pyobjc_framework_CryptoTokenKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:95b05efb06b09987e23fb62dc3af378f38cfd0bd5872940cd95cf0f39dac6a57", size = 12978, upload-time = "2025-01-14T18:51:51.215Z" }, ] [[package]] @@ -2695,13 +2724,13 @@ name = "pyobjc-framework-datadetection" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/33/6b/b896feb16e914dc81b6ed6cdbd0b6e6390eaafc80fff5297ec17eb0bd716/pyobjc_framework_datadetection-11.0.tar.gz", hash = "sha256:9967555151892f8400cffac86e8656f2cb8d7866963fdee255e0747fa1386533", size = 13738 } +sdist = { url = "https://files.pythonhosted.org/packages/33/6b/b896feb16e914dc81b6ed6cdbd0b6e6390eaafc80fff5297ec17eb0bd716/pyobjc_framework_datadetection-11.0.tar.gz", hash = "sha256:9967555151892f8400cffac86e8656f2cb8d7866963fdee255e0747fa1386533", size = 13738, upload-time = "2025-01-14T19:03:27.054Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/11/a1/63653827a78c8329a0106ac06e68ec0434e7f104f022dee5929bdf8fed62/pyobjc_framework_DataDetection-11.0-py2.py3-none-any.whl", hash = "sha256:0fd191ddee9bc6a491e05dfb7de780c0266fd6c90ca783e168786c4b0b5d7d7c", size = 3428 }, - { url = "https://files.pythonhosted.org/packages/1b/61/ee4579efb7c02b794d26ab0458722598726678d0bb227c9aa925a34f36af/pyobjc_framework_DataDetection-11.0-py3-none-any.whl", hash = "sha256:21b4a1dbf6cb56fdc971224476453dd1a7a4bb72d2c670444e81ae96fde97cb2", size = 3501 }, + { url = "https://files.pythonhosted.org/packages/11/a1/63653827a78c8329a0106ac06e68ec0434e7f104f022dee5929bdf8fed62/pyobjc_framework_DataDetection-11.0-py2.py3-none-any.whl", hash = "sha256:0fd191ddee9bc6a491e05dfb7de780c0266fd6c90ca783e168786c4b0b5d7d7c", size = 3428, upload-time = "2025-01-14T18:51:58.111Z" }, + { url = "https://files.pythonhosted.org/packages/1b/61/ee4579efb7c02b794d26ab0458722598726678d0bb227c9aa925a34f36af/pyobjc_framework_DataDetection-11.0-py3-none-any.whl", hash = "sha256:21b4a1dbf6cb56fdc971224476453dd1a7a4bb72d2c670444e81ae96fde97cb2", size = 3501, upload-time = "2025-01-14T18:51:59.104Z" }, ] [[package]] @@ -2709,13 +2738,13 @@ name = "pyobjc-framework-devicecheck" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/de/f8/237a92dd9ba8a88b7027f78cba83e61b0011bfc2a49351ecaa177233f639/pyobjc_framework_devicecheck-11.0.tar.gz", hash = "sha256:66cff0323dc8eef1b76d60f9c9752684f11e534ebda60ecbf6858a9c73553f64", size = 14198 } +sdist = { url = "https://files.pythonhosted.org/packages/de/f8/237a92dd9ba8a88b7027f78cba83e61b0011bfc2a49351ecaa177233f639/pyobjc_framework_devicecheck-11.0.tar.gz", hash = "sha256:66cff0323dc8eef1b76d60f9c9752684f11e534ebda60ecbf6858a9c73553f64", size = 14198, upload-time = "2025-01-14T19:03:27.918Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5c/c1/d889e1c515c23b911594aa0b53a9d8ab6173e07adaaad8db89324a731fb7/pyobjc_framework_DeviceCheck-11.0-py2.py3-none-any.whl", hash = "sha256:d9252173a57dfba09ae37ccc3049f4b4990c1cbdcde338622b42c66296a8740e", size = 3612 }, - { url = "https://files.pythonhosted.org/packages/65/8b/fa0cc2da2d49897f64e27a8a4e2a68f5784515f1adcea3a90f90b8ae8d44/pyobjc_framework_DeviceCheck-11.0-py3-none-any.whl", hash = "sha256:e8ed3965808963b2f0a7e069537d752bc659b75db1901cc24e5138925b9a7052", size = 3684 }, + { url = "https://files.pythonhosted.org/packages/5c/c1/d889e1c515c23b911594aa0b53a9d8ab6173e07adaaad8db89324a731fb7/pyobjc_framework_DeviceCheck-11.0-py2.py3-none-any.whl", hash = "sha256:d9252173a57dfba09ae37ccc3049f4b4990c1cbdcde338622b42c66296a8740e", size = 3612, upload-time = "2025-01-14T18:52:00.097Z" }, + { url = "https://files.pythonhosted.org/packages/65/8b/fa0cc2da2d49897f64e27a8a4e2a68f5784515f1adcea3a90f90b8ae8d44/pyobjc_framework_DeviceCheck-11.0-py3-none-any.whl", hash = "sha256:e8ed3965808963b2f0a7e069537d752bc659b75db1901cc24e5138925b9a7052", size = 3684, upload-time = "2025-01-14T18:52:02.389Z" }, ] [[package]] @@ -2723,13 +2752,13 @@ name = "pyobjc-framework-devicediscoveryextension" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e1/48/178a1879109128f34334fdae2fe4463c7620f169593bea96704f347d945e/pyobjc_framework_devicediscoveryextension-11.0.tar.gz", hash = "sha256:576dac3f418cfc4f71020a45f06231d14e4b2a8e182ef0020dd9da3cf238d02f", size = 14511 } +sdist = { url = "https://files.pythonhosted.org/packages/e1/48/178a1879109128f34334fdae2fe4463c7620f169593bea96704f347d945e/pyobjc_framework_devicediscoveryextension-11.0.tar.gz", hash = "sha256:576dac3f418cfc4f71020a45f06231d14e4b2a8e182ef0020dd9da3cf238d02f", size = 14511, upload-time = "2025-01-14T19:03:32.132Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2a/be/3353a87691796a277ff4c048c4fa9a43db6f353fd683e8bb9e297651950c/pyobjc_framework_DeviceDiscoveryExtension-11.0-py2.py3-none-any.whl", hash = "sha256:82032e567d0031839d626947368d6d3d4ca97c915f15d2779a444cf4b2ffa4a3", size = 4194 }, - { url = "https://files.pythonhosted.org/packages/06/87/52137a60498c03ab0acd3b9eadafe3c371c12e0549718e6a1f0fff8b7725/pyobjc_framework_DeviceDiscoveryExtension-11.0-py3-none-any.whl", hash = "sha256:9c94057173f13472089d561b780d93b5aa244d048b4760a0e1ab54fe7c2253c5", size = 4265 }, + { url = "https://files.pythonhosted.org/packages/2a/be/3353a87691796a277ff4c048c4fa9a43db6f353fd683e8bb9e297651950c/pyobjc_framework_DeviceDiscoveryExtension-11.0-py2.py3-none-any.whl", hash = "sha256:82032e567d0031839d626947368d6d3d4ca97c915f15d2779a444cf4b2ffa4a3", size = 4194, upload-time = "2025-01-14T18:52:03.253Z" }, + { url = "https://files.pythonhosted.org/packages/06/87/52137a60498c03ab0acd3b9eadafe3c371c12e0549718e6a1f0fff8b7725/pyobjc_framework_DeviceDiscoveryExtension-11.0-py3-none-any.whl", hash = "sha256:9c94057173f13472089d561b780d93b5aa244d048b4760a0e1ab54fe7c2253c5", size = 4265, upload-time = "2025-01-14T18:52:05.101Z" }, ] [[package]] @@ -2737,13 +2766,13 @@ name = "pyobjc-framework-dictionaryservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d8/cf/2913c7df737eb8519acb7ef6429127e40d6c334415e38cfa18d6481150eb/pyobjc_framework_dictionaryservices-11.0.tar.gz", hash = "sha256:6b5f27c75424860f169e7c7e182fabffdba22854fedb8023de180e8770661dce", size = 10823 } +sdist = { url = "https://files.pythonhosted.org/packages/d8/cf/2913c7df737eb8519acb7ef6429127e40d6c334415e38cfa18d6481150eb/pyobjc_framework_dictionaryservices-11.0.tar.gz", hash = "sha256:6b5f27c75424860f169e7c7e182fabffdba22854fedb8023de180e8770661dce", size = 10823, upload-time = "2025-01-14T19:03:32.942Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/0a/68/5ea9766a8a6301f1a2ee39d595fe03d50b84b979d3d059e3e0ff541eab45/pyobjc_framework_DictionaryServices-11.0-py2.py3-none-any.whl", hash = "sha256:7c081371855240ac8e22783a71f32393c0f1e0b94d2fd193e8fef0a8be007080", size = 3829 }, - { url = "https://files.pythonhosted.org/packages/dd/c4/62b73f813c012f72a3a8e2f6326506803b45e91dc4ce6683e02a52a7f414/pyobjc_framework_DictionaryServices-11.0-py3-none-any.whl", hash = "sha256:15cdc3b64cb73713ee928cdcc0a12c845729f117bb8e73c7511f6e3f256d9d39", size = 3901 }, + { url = "https://files.pythonhosted.org/packages/0a/68/5ea9766a8a6301f1a2ee39d595fe03d50b84b979d3d059e3e0ff541eab45/pyobjc_framework_DictionaryServices-11.0-py2.py3-none-any.whl", hash = "sha256:7c081371855240ac8e22783a71f32393c0f1e0b94d2fd193e8fef0a8be007080", size = 3829, upload-time = "2025-01-14T18:52:07.379Z" }, + { url = "https://files.pythonhosted.org/packages/dd/c4/62b73f813c012f72a3a8e2f6326506803b45e91dc4ce6683e02a52a7f414/pyobjc_framework_DictionaryServices-11.0-py3-none-any.whl", hash = "sha256:15cdc3b64cb73713ee928cdcc0a12c845729f117bb8e73c7511f6e3f256d9d39", size = 3901, upload-time = "2025-01-14T18:52:08.403Z" }, ] [[package]] @@ -2751,13 +2780,13 @@ name = "pyobjc-framework-discrecording" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/96/cc/f36612b67ca1fff7659d7933b563dce61f8c84dad0bf79fab08bb34949ad/pyobjc_framework_discrecording-11.0.tar.gz", hash = "sha256:6bdc533f067d049ea5032f65af70b5cdab68673574ac32dacb46509a9411d256", size = 122426 } +sdist = { url = "https://files.pythonhosted.org/packages/96/cc/f36612b67ca1fff7659d7933b563dce61f8c84dad0bf79fab08bb34949ad/pyobjc_framework_discrecording-11.0.tar.gz", hash = "sha256:6bdc533f067d049ea5032f65af70b5cdab68673574ac32dacb46509a9411d256", size = 122426, upload-time = "2025-01-14T19:03:35.589Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7e/0b/fbe460ccddb4c613eb04e2b81cc9c75b0e0c407fd9fb91776381416f99af/pyobjc_framework_DiscRecording-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:eab79d83c2d974aa5564f3f6f4415218573dca69010026d2d000d232494a9d81", size = 14491 }, - { url = "https://files.pythonhosted.org/packages/10/6f/c4c220d979771f4d7782deddef5ea9026baa177abe81cbe63d626a215de7/pyobjc_framework_DiscRecording-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e309e7394aed23d6ccce2e035f23c0c015d029c2ad531c6b1dce820b7eea8512", size = 14505 }, + { url = "https://files.pythonhosted.org/packages/7e/0b/fbe460ccddb4c613eb04e2b81cc9c75b0e0c407fd9fb91776381416f99af/pyobjc_framework_DiscRecording-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:eab79d83c2d974aa5564f3f6f4415218573dca69010026d2d000d232494a9d81", size = 14491, upload-time = "2025-01-14T18:52:10.415Z" }, + { url = "https://files.pythonhosted.org/packages/10/6f/c4c220d979771f4d7782deddef5ea9026baa177abe81cbe63d626a215de7/pyobjc_framework_DiscRecording-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e309e7394aed23d6ccce2e035f23c0c015d029c2ad531c6b1dce820b7eea8512", size = 14505, upload-time = "2025-01-14T18:52:11.414Z" }, ] [[package]] @@ -2765,14 +2794,14 @@ name = "pyobjc-framework-discrecordingui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecording", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-discrecording" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d4/6b/3c120c59a939854dd4b7a162fad47011375c5ba00a12940f7217aea90eeb/pyobjc_framework_discrecordingui-11.0.tar.gz", hash = "sha256:bec8a252fd2022dce6c58b1f3366a7295efb0c7c77817f11f9efcce70527d7a2", size = 19614 } +sdist = { url = "https://files.pythonhosted.org/packages/d4/6b/3c120c59a939854dd4b7a162fad47011375c5ba00a12940f7217aea90eeb/pyobjc_framework_discrecordingui-11.0.tar.gz", hash = "sha256:bec8a252fd2022dce6c58b1f3366a7295efb0c7c77817f11f9efcce70527d7a2", size = 19614, upload-time = "2025-01-14T19:03:36.695Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/de/45/4852afc5e093b76ba8f718d80fe1cc8604122a752806354379a7dbc41dc3/pyobjc_framework_DiscRecordingUI-11.0-py2.py3-none-any.whl", hash = "sha256:1af226c9350bb1d49960c02505e1e2f286e9377040dc2777a3f9a318925e081b", size = 4671 }, - { url = "https://files.pythonhosted.org/packages/98/01/c5645513eeaadf0b9e387849fa656fc22524a1881f0d3a44d5b78784f836/pyobjc_framework_DiscRecordingUI-11.0-py3-none-any.whl", hash = "sha256:943df030f497a5ab73e969a04df8a653138fb67ebcf2380fedb4b4886d4ffba0", size = 4736 }, + { url = "https://files.pythonhosted.org/packages/de/45/4852afc5e093b76ba8f718d80fe1cc8604122a752806354379a7dbc41dc3/pyobjc_framework_DiscRecordingUI-11.0-py2.py3-none-any.whl", hash = "sha256:1af226c9350bb1d49960c02505e1e2f286e9377040dc2777a3f9a318925e081b", size = 4671, upload-time = "2025-01-14T18:52:16.645Z" }, + { url = "https://files.pythonhosted.org/packages/98/01/c5645513eeaadf0b9e387849fa656fc22524a1881f0d3a44d5b78784f836/pyobjc_framework_DiscRecordingUI-11.0-py3-none-any.whl", hash = "sha256:943df030f497a5ab73e969a04df8a653138fb67ebcf2380fedb4b4886d4ffba0", size = 4736, upload-time = "2025-01-14T18:52:17.655Z" }, ] [[package]] @@ -2780,13 +2809,13 @@ name = "pyobjc-framework-diskarbitration" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/43/fb/5d3ff093144f499904b1e1bce18d010fe2171b9be62b4679d3dda8b3ad19/pyobjc_framework_diskarbitration-11.0.tar.gz", hash = "sha256:1c3e21398b366a1ce96cf68501a2e415f5ccad4b43a3e7cc901e09e896dfb545", size = 20096 } +sdist = { url = "https://files.pythonhosted.org/packages/43/fb/5d3ff093144f499904b1e1bce18d010fe2171b9be62b4679d3dda8b3ad19/pyobjc_framework_diskarbitration-11.0.tar.gz", hash = "sha256:1c3e21398b366a1ce96cf68501a2e415f5ccad4b43a3e7cc901e09e896dfb545", size = 20096, upload-time = "2025-01-14T19:03:37.659Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d2/f4/f7ad86b2bb922b94745c369b90420cda984e6ad1ac9eb79ec32f5e332123/pyobjc_framework_DiskArbitration-11.0-py2.py3-none-any.whl", hash = "sha256:58823297eb09ff020ee156649170ab824fec32825bd32f2814c32e005920a72c", size = 4793 }, - { url = "https://files.pythonhosted.org/packages/8e/87/bf0fc2aa781a819421e572cf6315fae7d0baf46607f9a67c86525c7e0e03/pyobjc_framework_DiskArbitration-11.0-py3-none-any.whl", hash = "sha256:7d41189a2d82045a7195c4661d8ec16195b6325a2f68f9d960e9a9f6649d1131", size = 4865 }, + { url = "https://files.pythonhosted.org/packages/d2/f4/f7ad86b2bb922b94745c369b90420cda984e6ad1ac9eb79ec32f5e332123/pyobjc_framework_DiskArbitration-11.0-py2.py3-none-any.whl", hash = "sha256:58823297eb09ff020ee156649170ab824fec32825bd32f2814c32e005920a72c", size = 4793, upload-time = "2025-01-14T18:52:18.561Z" }, + { url = "https://files.pythonhosted.org/packages/8e/87/bf0fc2aa781a819421e572cf6315fae7d0baf46607f9a67c86525c7e0e03/pyobjc_framework_DiskArbitration-11.0-py3-none-any.whl", hash = "sha256:7d41189a2d82045a7195c4661d8ec16195b6325a2f68f9d960e9a9f6649d1131", size = 4865, upload-time = "2025-01-14T18:52:19.786Z" }, ] [[package]] @@ -2794,13 +2823,13 @@ name = "pyobjc-framework-dvdplayback" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c0/89/89ebee4863fd6f173bff9373b5bda4ffa87eba6197337617ab086e23c7d5/pyobjc_framework_dvdplayback-11.0.tar.gz", hash = "sha256:9a005f441afbc34aea301857e166fd650d82762a75d024253e18d1102b21b2f8", size = 64798 } +sdist = { url = "https://files.pythonhosted.org/packages/c0/89/89ebee4863fd6f173bff9373b5bda4ffa87eba6197337617ab086e23c7d5/pyobjc_framework_dvdplayback-11.0.tar.gz", hash = "sha256:9a005f441afbc34aea301857e166fd650d82762a75d024253e18d1102b21b2f8", size = 64798, upload-time = "2025-01-14T19:03:38.491Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6b/7f/6073ef2c5170abf55a15750cd069b0c3fdd03e48f3c86761a6a8ecaa0a38/pyobjc_framework_DVDPlayback-11.0-py2.py3-none-any.whl", hash = "sha256:2013289aa38166d81bcbf25d6600ead1996e50de2bc689e5cf36f36a45346424", size = 8171 }, - { url = "https://files.pythonhosted.org/packages/db/e4/97ed8d41491f366908581efb8644376fd81ede07ec2cf204cdb3c300ed1e/pyobjc_framework_DVDPlayback-11.0-py3-none-any.whl", hash = "sha256:c6be6ae410d8dce7179d6ee8c9bc421468d4b9c19af3ff0e59c93ae71cfc33e0", size = 8245 }, + { url = "https://files.pythonhosted.org/packages/6b/7f/6073ef2c5170abf55a15750cd069b0c3fdd03e48f3c86761a6a8ecaa0a38/pyobjc_framework_DVDPlayback-11.0-py2.py3-none-any.whl", hash = "sha256:2013289aa38166d81bcbf25d6600ead1996e50de2bc689e5cf36f36a45346424", size = 8171, upload-time = "2025-01-14T18:51:55.282Z" }, + { url = "https://files.pythonhosted.org/packages/db/e4/97ed8d41491f366908581efb8644376fd81ede07ec2cf204cdb3c300ed1e/pyobjc_framework_DVDPlayback-11.0-py3-none-any.whl", hash = "sha256:c6be6ae410d8dce7179d6ee8c9bc421468d4b9c19af3ff0e59c93ae71cfc33e0", size = 8245, upload-time = "2025-01-14T18:51:57.205Z" }, ] [[package]] @@ -2808,13 +2837,13 @@ name = "pyobjc-framework-eventkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/54/13/38a98e5cee62e1655d84cfb88cad54fdec4ec272b5fd0c5ac3fc21e33e49/pyobjc_framework_eventkit-11.0.tar.gz", hash = "sha256:3d412203a510b3d62a5eb0987406e0951b13ed39c3351c0ec874afd72496627c", size = 75399 } +sdist = { url = "https://files.pythonhosted.org/packages/54/13/38a98e5cee62e1655d84cfb88cad54fdec4ec272b5fd0c5ac3fc21e33e49/pyobjc_framework_eventkit-11.0.tar.gz", hash = "sha256:3d412203a510b3d62a5eb0987406e0951b13ed39c3351c0ec874afd72496627c", size = 75399, upload-time = "2025-01-14T19:03:39.441Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/97/d5/e866c951237fb1b6423b85e1623a7f8cc417862261196e276ecc23141976/pyobjc_framework_EventKit-11.0-py2.py3-none-any.whl", hash = "sha256:934e31f4c82f887e1bf01f96d33de4c7c6727de3fdb55bc739e1c686c10cc151", size = 6717 }, - { url = "https://files.pythonhosted.org/packages/dc/47/3c0cc7b8c95e6759804b426e78510f65b8e7409c425b85f1b0109d14cdcc/pyobjc_framework_EventKit-11.0-py3-none-any.whl", hash = "sha256:5467977c79649dac9e0183dc72511f7dd49aab0260b67c2cfa25079a5a303f11", size = 6789 }, + { url = "https://files.pythonhosted.org/packages/97/d5/e866c951237fb1b6423b85e1623a7f8cc417862261196e276ecc23141976/pyobjc_framework_EventKit-11.0-py2.py3-none-any.whl", hash = "sha256:934e31f4c82f887e1bf01f96d33de4c7c6727de3fdb55bc739e1c686c10cc151", size = 6717, upload-time = "2025-01-14T18:52:20.684Z" }, + { url = "https://files.pythonhosted.org/packages/dc/47/3c0cc7b8c95e6759804b426e78510f65b8e7409c425b85f1b0109d14cdcc/pyobjc_framework_EventKit-11.0-py3-none-any.whl", hash = "sha256:5467977c79649dac9e0183dc72511f7dd49aab0260b67c2cfa25079a5a303f11", size = 6789, upload-time = "2025-01-14T18:52:21.73Z" }, ] [[package]] @@ -2822,13 +2851,13 @@ name = "pyobjc-framework-exceptionhandling" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/cc/46/6c2c4805697a0cfb8413eb7bc6901298e7a1febd49bb1ea960274fc33af3/pyobjc_framework_exceptionhandling-11.0.tar.gz", hash = "sha256:b11562c6eeaef5d8d43e9d817cf50feceb02396e5eb6a7f61df2c0cec93d912b", size = 18157 } +sdist = { url = "https://files.pythonhosted.org/packages/cc/46/6c2c4805697a0cfb8413eb7bc6901298e7a1febd49bb1ea960274fc33af3/pyobjc_framework_exceptionhandling-11.0.tar.gz", hash = "sha256:b11562c6eeaef5d8d43e9d817cf50feceb02396e5eb6a7f61df2c0cec93d912b", size = 18157, upload-time = "2025-01-14T19:03:40.393Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e7/9d/c25b0bc0d300dd5aedd61f0cbd94a91ec6608b550821108d554e9eea0ed7/pyobjc_framework_ExceptionHandling-11.0-py2.py3-none-any.whl", hash = "sha256:972e0a376fee4d3d4c5161f82a8e5f6305392dbf19e98c4c6486d737759ebd89", size = 6993 }, - { url = "https://files.pythonhosted.org/packages/cb/04/4b75e083325313e80e66f42d9a932c3febd2db48609d5d960a319b568f7c/pyobjc_framework_ExceptionHandling-11.0-py3-none-any.whl", hash = "sha256:d7f95fdb60a2636416066d3d12fad06cbf597e038576f8ed46fd3c742cc22252", size = 7063 }, + { url = "https://files.pythonhosted.org/packages/e7/9d/c25b0bc0d300dd5aedd61f0cbd94a91ec6608b550821108d554e9eea0ed7/pyobjc_framework_ExceptionHandling-11.0-py2.py3-none-any.whl", hash = "sha256:972e0a376fee4d3d4c5161f82a8e5f6305392dbf19e98c4c6486d737759ebd89", size = 6993, upload-time = "2025-01-14T18:52:22.621Z" }, + { url = "https://files.pythonhosted.org/packages/cb/04/4b75e083325313e80e66f42d9a932c3febd2db48609d5d960a319b568f7c/pyobjc_framework_ExceptionHandling-11.0-py3-none-any.whl", hash = "sha256:d7f95fdb60a2636416066d3d12fad06cbf597e038576f8ed46fd3c742cc22252", size = 7063, upload-time = "2025-01-14T18:52:24.447Z" }, ] [[package]] @@ -2836,13 +2865,13 @@ name = "pyobjc-framework-executionpolicy" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ab/91/2e4cacbdabf01bc1207817edacc814b6bc486df12e857a8d86964d98fef4/pyobjc_framework_executionpolicy-11.0.tar.gz", hash = "sha256:de953a8acae98079015b19e75ec8154a311ac1a70fb6d885e17fab09464c98a9", size = 13753 } +sdist = { url = "https://files.pythonhosted.org/packages/ab/91/2e4cacbdabf01bc1207817edacc814b6bc486df12e857a8d86964d98fef4/pyobjc_framework_executionpolicy-11.0.tar.gz", hash = "sha256:de953a8acae98079015b19e75ec8154a311ac1a70fb6d885e17fab09464c98a9", size = 13753, upload-time = "2025-01-14T19:03:42.353Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d5/03/a433c64c21c754ed796ae5ca0bad63fcb1d51134968ce0c53d4ee806ccd8/pyobjc_framework_ExecutionPolicy-11.0-py2.py3-none-any.whl", hash = "sha256:fdf78bf22fa6ea6f27b574f73856a8a22992d0c0d5a6ed64823e00000c06ffe7", size = 3668 }, - { url = "https://files.pythonhosted.org/packages/0b/47/da969dd9d56403e23cc95e68c4816563f64ed6fde7ff4e3c3710e8e8efcf/pyobjc_framework_ExecutionPolicy-11.0-py3-none-any.whl", hash = "sha256:d2dba6f3f7803d1cd0a5608a7ad75085b73097b6c3a935b7f1326c7202249751", size = 3737 }, + { url = "https://files.pythonhosted.org/packages/d5/03/a433c64c21c754ed796ae5ca0bad63fcb1d51134968ce0c53d4ee806ccd8/pyobjc_framework_ExecutionPolicy-11.0-py2.py3-none-any.whl", hash = "sha256:fdf78bf22fa6ea6f27b574f73856a8a22992d0c0d5a6ed64823e00000c06ffe7", size = 3668, upload-time = "2025-01-14T18:52:28.64Z" }, + { url = "https://files.pythonhosted.org/packages/0b/47/da969dd9d56403e23cc95e68c4816563f64ed6fde7ff4e3c3710e8e8efcf/pyobjc_framework_ExecutionPolicy-11.0-py3-none-any.whl", hash = "sha256:d2dba6f3f7803d1cd0a5608a7ad75085b73097b6c3a935b7f1326c7202249751", size = 3737, upload-time = "2025-01-14T18:52:30.841Z" }, ] [[package]] @@ -2850,13 +2879,13 @@ name = "pyobjc-framework-extensionkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/22/98/803e3cb000dac227eb0d223802a0aeb052d34a741e572d9584e7d83afca7/pyobjc_framework_extensionkit-11.0.tar.gz", hash = "sha256:82d9e79532e5a0ff0eadf1ccac236c5d3dca344e1090a0f3e88519faa24143c7", size = 19200 } +sdist = { url = "https://files.pythonhosted.org/packages/22/98/803e3cb000dac227eb0d223802a0aeb052d34a741e572d9584e7d83afca7/pyobjc_framework_extensionkit-11.0.tar.gz", hash = "sha256:82d9e79532e5a0ff0eadf1ccac236c5d3dca344e1090a0f3e88519faa24143c7", size = 19200, upload-time = "2025-01-14T19:03:43.188Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a7/1d/ed580ce024d7e9a1ea88ee592d03b34f0b688414793bf8b7be5a367ecea8/pyobjc_framework_ExtensionKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:98957dd51f0a4e02aa3d9d3a184f37ca5f99f4cb9e11282a2fc793d18de02af8", size = 7781 }, - { url = "https://files.pythonhosted.org/packages/fd/9e/a68989bf7bbba7b5fb1ade168d2179e37164439daaad63a27ccb790a6593/pyobjc_framework_ExtensionKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e341979ee4a7fc5978fe44d6d1d461c774411042cac4e119a32704d6c989de6f", size = 7783 }, + { url = "https://files.pythonhosted.org/packages/a7/1d/ed580ce024d7e9a1ea88ee592d03b34f0b688414793bf8b7be5a367ecea8/pyobjc_framework_ExtensionKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:98957dd51f0a4e02aa3d9d3a184f37ca5f99f4cb9e11282a2fc793d18de02af8", size = 7781, upload-time = "2025-01-14T18:52:32.843Z" }, + { url = "https://files.pythonhosted.org/packages/fd/9e/a68989bf7bbba7b5fb1ade168d2179e37164439daaad63a27ccb790a6593/pyobjc_framework_ExtensionKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e341979ee4a7fc5978fe44d6d1d461c774411042cac4e119a32704d6c989de6f", size = 7783, upload-time = "2025-01-14T18:52:33.711Z" }, ] [[package]] @@ -2864,13 +2893,13 @@ name = "pyobjc-framework-externalaccessory" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/67/b0/ac0a02fe26e66c33fee751a65c1ed06bbd2934db8636e08bb491e8334bad/pyobjc_framework_externalaccessory-11.0.tar.gz", hash = "sha256:39e59331ced75cdcccf23bb5ffe0fa9d67e0c190c1da8887a0e4349b7e27584f", size = 22577 } +sdist = { url = "https://files.pythonhosted.org/packages/67/b0/ac0a02fe26e66c33fee751a65c1ed06bbd2934db8636e08bb491e8334bad/pyobjc_framework_externalaccessory-11.0.tar.gz", hash = "sha256:39e59331ced75cdcccf23bb5ffe0fa9d67e0c190c1da8887a0e4349b7e27584f", size = 22577, upload-time = "2025-01-14T19:03:44.021Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a3/96/bddfe9f72a59a3038ec3208a7d2a62332d5e171d7e3c338ccff6bd6e76b8/pyobjc_framework_ExternalAccessory-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:319f66edb96505f833fe7fe9ba810cb3b0d0c65605b8674bea52f040e8caebd6", size = 8785 }, - { url = "https://files.pythonhosted.org/packages/e7/e2/26e9cbb18723200ef71580e46c46f037b7feecc07cf50051cd6fcb426472/pyobjc_framework_ExternalAccessory-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:aaae920c9241d1b35a58ba76dba761689b248250d782179526f6dea151b1fda0", size = 8808 }, + { url = "https://files.pythonhosted.org/packages/a3/96/bddfe9f72a59a3038ec3208a7d2a62332d5e171d7e3c338ccff6bd6e76b8/pyobjc_framework_ExternalAccessory-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:319f66edb96505f833fe7fe9ba810cb3b0d0c65605b8674bea52f040e8caebd6", size = 8785, upload-time = "2025-01-14T18:52:40.529Z" }, + { url = "https://files.pythonhosted.org/packages/e7/e2/26e9cbb18723200ef71580e46c46f037b7feecc07cf50051cd6fcb426472/pyobjc_framework_ExternalAccessory-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:aaae920c9241d1b35a58ba76dba761689b248250d782179526f6dea151b1fda0", size = 8808, upload-time = "2025-01-14T18:52:42.142Z" }, ] [[package]] @@ -2878,13 +2907,13 @@ name = "pyobjc-framework-fileprovider" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/44/fc/b8593d8645b9933e60a885f451d0c12d9c0e1b00e62121d8660d95852dff/pyobjc_framework_fileprovider-11.0.tar.gz", hash = "sha256:dcc3ac3c90117c1b8027ea5f26dad6fe5045f688ce3e60d07ece12ec56e17ab3", size = 78701 } +sdist = { url = "https://files.pythonhosted.org/packages/44/fc/b8593d8645b9933e60a885f451d0c12d9c0e1b00e62121d8660d95852dff/pyobjc_framework_fileprovider-11.0.tar.gz", hash = "sha256:dcc3ac3c90117c1b8027ea5f26dad6fe5045f688ce3e60d07ece12ec56e17ab3", size = 78701, upload-time = "2025-01-14T19:03:44.931Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4a/57/1f959ec54650d1afc08e89d2995a1534f44229b1371cf66429a45b27c32d/pyobjc_framework_FileProvider-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8c7e803a37f7327c191a4de7dbb36e5fbf8bd08dadbcc7f626e491451c7a3849", size = 19179 }, - { url = "https://files.pythonhosted.org/packages/30/79/ff4dfe06eb43c97bd723f066ef2b92b00b1020206b4dcc5abe9b49746cad/pyobjc_framework_FileProvider-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d7acdc5e0f4b5488bcbf47d3eea469b22897a4b783fe3f5d4b2b1f3288e82038", size = 19154 }, + { url = "https://files.pythonhosted.org/packages/4a/57/1f959ec54650d1afc08e89d2995a1534f44229b1371cf66429a45b27c32d/pyobjc_framework_FileProvider-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8c7e803a37f7327c191a4de7dbb36e5fbf8bd08dadbcc7f626e491451c7a3849", size = 19179, upload-time = "2025-01-14T18:53:01.659Z" }, + { url = "https://files.pythonhosted.org/packages/30/79/ff4dfe06eb43c97bd723f066ef2b92b00b1020206b4dcc5abe9b49746cad/pyobjc_framework_FileProvider-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d7acdc5e0f4b5488bcbf47d3eea469b22897a4b783fe3f5d4b2b1f3288e82038", size = 19154, upload-time = "2025-01-14T18:53:02.597Z" }, ] [[package]] @@ -2892,13 +2921,13 @@ name = "pyobjc-framework-fileproviderui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileprovider", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-fileprovider" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3d/9d/ca4aed36e6188623e9da633634af772f239bee74934322e1c19ae7b79a53/pyobjc_framework_fileproviderui-11.0.tar.gz", hash = "sha256:cf5c7d32b29d344b65217397eea7b1a2913ce52ce923c9e04135a7a298848d04", size = 13419 } +sdist = { url = "https://files.pythonhosted.org/packages/3d/9d/ca4aed36e6188623e9da633634af772f239bee74934322e1c19ae7b79a53/pyobjc_framework_fileproviderui-11.0.tar.gz", hash = "sha256:cf5c7d32b29d344b65217397eea7b1a2913ce52ce923c9e04135a7a298848d04", size = 13419, upload-time = "2025-01-14T19:03:46.016Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/0b/2e/8a91cfa9485a2e9ad295da8bb5505d0dc1046dec8557d2ae17eef75f3912/pyobjc_framework_FileProviderUI-11.0-py2.py3-none-any.whl", hash = "sha256:5102651febb5a6140f99b116b73d0fd6c9822372a5203506e4904ac0ebb1313c", size = 3642 }, - { url = "https://files.pythonhosted.org/packages/75/9b/a542159b1aefedb24f01440a929b7bbc6f4bbae3a74d09ad05a7f4adb9c0/pyobjc_framework_FileProviderUI-11.0-py3-none-any.whl", hash = "sha256:b75f70eef2af3696f3cb2e0de88bbb437343b53070078573ae72d64bf56fce9d", size = 3712 }, + { url = "https://files.pythonhosted.org/packages/0b/2e/8a91cfa9485a2e9ad295da8bb5505d0dc1046dec8557d2ae17eef75f3912/pyobjc_framework_FileProviderUI-11.0-py2.py3-none-any.whl", hash = "sha256:5102651febb5a6140f99b116b73d0fd6c9822372a5203506e4904ac0ebb1313c", size = 3642, upload-time = "2025-01-14T18:53:06.378Z" }, + { url = "https://files.pythonhosted.org/packages/75/9b/a542159b1aefedb24f01440a929b7bbc6f4bbae3a74d09ad05a7f4adb9c0/pyobjc_framework_FileProviderUI-11.0-py3-none-any.whl", hash = "sha256:b75f70eef2af3696f3cb2e0de88bbb437343b53070078573ae72d64bf56fce9d", size = 3712, upload-time = "2025-01-14T18:53:07.403Z" }, ] [[package]] @@ -2906,13 +2935,13 @@ name = "pyobjc-framework-findersync" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f6/e3/24df6e24b589073815be13f2943b93feb12afbf558f6e54c4033b57c29ee/pyobjc_framework_findersync-11.0.tar.gz", hash = "sha256:8dab3feff5debd6bc3746a21ded991716723d98713d1ba37cec1c5e2ad78ee63", size = 15295 } +sdist = { url = "https://files.pythonhosted.org/packages/f6/e3/24df6e24b589073815be13f2943b93feb12afbf558f6e54c4033b57c29ee/pyobjc_framework_findersync-11.0.tar.gz", hash = "sha256:8dab3feff5debd6bc3746a21ded991716723d98713d1ba37cec1c5e2ad78ee63", size = 15295, upload-time = "2025-01-14T19:03:46.91Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/96/f1/42797ae9065e0127df4b5bb7a45e06eff8568a476edbc8d590cea9d25228/pyobjc_framework_FinderSync-11.0-py2.py3-none-any.whl", hash = "sha256:cafb262d1ad1e3a86af333f673aeda4f9bdcf528ded97c2232fd1cf440d1db5a", size = 4788 }, - { url = "https://files.pythonhosted.org/packages/d8/96/2ed2ca5536f76102ea3bfb886cdc7b34ec51f53b122b9c535b4ac9b1ee03/pyobjc_framework_FinderSync-11.0-py3-none-any.whl", hash = "sha256:d00285b85038c5546e8566bec9cd3a4615708f0e6cb774d0ea804c69546ec915", size = 4860 }, + { url = "https://files.pythonhosted.org/packages/96/f1/42797ae9065e0127df4b5bb7a45e06eff8568a476edbc8d590cea9d25228/pyobjc_framework_FinderSync-11.0-py2.py3-none-any.whl", hash = "sha256:cafb262d1ad1e3a86af333f673aeda4f9bdcf528ded97c2232fd1cf440d1db5a", size = 4788, upload-time = "2025-01-14T18:53:09.559Z" }, + { url = "https://files.pythonhosted.org/packages/d8/96/2ed2ca5536f76102ea3bfb886cdc7b34ec51f53b122b9c535b4ac9b1ee03/pyobjc_framework_FinderSync-11.0-py3-none-any.whl", hash = "sha256:d00285b85038c5546e8566bec9cd3a4615708f0e6cb774d0ea804c69546ec915", size = 4860, upload-time = "2025-01-14T18:53:11.765Z" }, ] [[package]] @@ -2920,13 +2949,13 @@ name = "pyobjc-framework-fsevents" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/82/37/4c09cc7b8678e2bb5b68ebc62e817eb88c409b1c41bdc1510d7d24a0372d/pyobjc_framework_fsevents-11.0.tar.gz", hash = "sha256:e01dab04704a518e4c3e1f7d8722819a4f228d5082978e11618aa7abba3883fe", size = 29078 } +sdist = { url = "https://files.pythonhosted.org/packages/82/37/4c09cc7b8678e2bb5b68ebc62e817eb88c409b1c41bdc1510d7d24a0372d/pyobjc_framework_fsevents-11.0.tar.gz", hash = "sha256:e01dab04704a518e4c3e1f7d8722819a4f228d5082978e11618aa7abba3883fe", size = 29078, upload-time = "2025-01-14T19:03:49.762Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1f/8a/75fd630865c9f9d69b1364208582872fc818b4c1a70fd9ae85a5cf7a2c5a/pyobjc_framework_FSEvents-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e0b3c7835251a35453e3079cf929b9e5329d02e2f4eaac2ebabbe19e1abd18ab", size = 13209 }, - { url = "https://files.pythonhosted.org/packages/19/c6/cae1a6a96ad493339e9f0f175bcf18c1526abe422b63309d873acd663dc2/pyobjc_framework_FSEvents-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fb8a5a7f7b5a70e15dae80672f10ecc16b5d1c1afe62ad2ccadb17a8098876cd", size = 13274 }, + { url = "https://files.pythonhosted.org/packages/1f/8a/75fd630865c9f9d69b1364208582872fc818b4c1a70fd9ae85a5cf7a2c5a/pyobjc_framework_FSEvents-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e0b3c7835251a35453e3079cf929b9e5329d02e2f4eaac2ebabbe19e1abd18ab", size = 13209, upload-time = "2025-01-14T18:52:49.478Z" }, + { url = "https://files.pythonhosted.org/packages/19/c6/cae1a6a96ad493339e9f0f175bcf18c1526abe422b63309d873acd663dc2/pyobjc_framework_FSEvents-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fb8a5a7f7b5a70e15dae80672f10ecc16b5d1c1afe62ad2ccadb17a8098876cd", size = 13274, upload-time = "2025-01-14T18:52:51.588Z" }, ] [[package]] @@ -2934,13 +2963,13 @@ name = "pyobjc-framework-gamecenter" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/7f/3b/e66caebc948d9fe3b2671659caab220aff6d5e80ac25442d83331b523d23/pyobjc_framework_gamecenter-11.0.tar.gz", hash = "sha256:18a05500dbcf2cca4a0f05839ec010c76ee08ab65b65020c9538a31feb274483", size = 31459 } +sdist = { url = "https://files.pythonhosted.org/packages/7f/3b/e66caebc948d9fe3b2671659caab220aff6d5e80ac25442d83331b523d23/pyobjc_framework_gamecenter-11.0.tar.gz", hash = "sha256:18a05500dbcf2cca4a0f05839ec010c76ee08ab65b65020c9538a31feb274483", size = 31459, upload-time = "2025-01-14T19:03:50.766Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1e/7e/8a41ab9880e415143baf771d55566e2a863ec538837480a5ee17e1ddc08b/pyobjc_framework_GameCenter-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f8bff2a36cf3cb52cbe321203147766e95997f881062143171cdd8ef2fde9e53", size = 18472 }, - { url = "https://files.pythonhosted.org/packages/c4/78/846aa21be2303cba955aaf781a362504a722183b8f6a030ba02f2b2073ad/pyobjc_framework_GameCenter-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8de57380e3b51579a6e8bc397c2bb5be5d0f6dcd4bf5abed587700cf7f57afd4", size = 18437 }, + { url = "https://files.pythonhosted.org/packages/1e/7e/8a41ab9880e415143baf771d55566e2a863ec538837480a5ee17e1ddc08b/pyobjc_framework_GameCenter-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f8bff2a36cf3cb52cbe321203147766e95997f881062143171cdd8ef2fde9e53", size = 18472, upload-time = "2025-01-14T18:53:13.794Z" }, + { url = "https://files.pythonhosted.org/packages/c4/78/846aa21be2303cba955aaf781a362504a722183b8f6a030ba02f2b2073ad/pyobjc_framework_GameCenter-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8de57380e3b51579a6e8bc397c2bb5be5d0f6dcd4bf5abed587700cf7f57afd4", size = 18437, upload-time = "2025-01-14T18:53:14.802Z" }, ] [[package]] @@ -2948,13 +2977,13 @@ name = "pyobjc-framework-gamecontroller" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fa/30/02ca5a4fb911acf3e8018abcbd29631a842aeac02958ae91fab1acb13ad1/pyobjc_framework_gamecontroller-11.0.tar.gz", hash = "sha256:6d62f4493d634eba03a43a14c4d1e4511e1e3a2ca2e9cbefa6ae9278a272c1d0", size = 115318 } +sdist = { url = "https://files.pythonhosted.org/packages/fa/30/02ca5a4fb911acf3e8018abcbd29631a842aeac02958ae91fab1acb13ad1/pyobjc_framework_gamecontroller-11.0.tar.gz", hash = "sha256:6d62f4493d634eba03a43a14c4d1e4511e1e3a2ca2e9cbefa6ae9278a272c1d0", size = 115318, upload-time = "2025-01-14T19:03:52.264Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/98/ec/05f356ab2d747a385c2a68908f2f67ee1b1e7a169b1497b0771b2226a174/pyobjc_framework_GameController-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:30e8f251be49ff67491df758c73149e7c7e87bee89919966ed1b2bf56fdaacf7", size = 20995 }, - { url = "https://files.pythonhosted.org/packages/66/b3/38319c9232e3508297bfedde700b125676845b1e27afe2bb681e8829f34a/pyobjc_framework_GameController-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:46403f23aaaf6a2e1a51e3954c53d6e910b80058117fdcf3a0a8100f25e30f07", size = 20919 }, + { url = "https://files.pythonhosted.org/packages/98/ec/05f356ab2d747a385c2a68908f2f67ee1b1e7a169b1497b0771b2226a174/pyobjc_framework_GameController-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:30e8f251be49ff67491df758c73149e7c7e87bee89919966ed1b2bf56fdaacf7", size = 20995, upload-time = "2025-01-14T18:53:19.979Z" }, + { url = "https://files.pythonhosted.org/packages/66/b3/38319c9232e3508297bfedde700b125676845b1e27afe2bb681e8829f34a/pyobjc_framework_GameController-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:46403f23aaaf6a2e1a51e3954c53d6e910b80058117fdcf3a0a8100f25e30f07", size = 20919, upload-time = "2025-01-14T18:53:20.943Z" }, ] [[package]] @@ -2962,14 +2991,14 @@ name = "pyobjc-framework-gamekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3f/df/c161460e5736a34f9b59aa0a3f2d6ad1d1cd9a913aa63c89c41a6ba3b6ae/pyobjc_framework_gamekit-11.0.tar.gz", hash = "sha256:29b5464ca78f0de62e6b6d56e80bbeccb96dc13820b6d5b4e835ab1cc127e5b9", size = 164394 } +sdist = { url = "https://files.pythonhosted.org/packages/3f/df/c161460e5736a34f9b59aa0a3f2d6ad1d1cd9a913aa63c89c41a6ba3b6ae/pyobjc_framework_gamekit-11.0.tar.gz", hash = "sha256:29b5464ca78f0de62e6b6d56e80bbeccb96dc13820b6d5b4e835ab1cc127e5b9", size = 164394, upload-time = "2025-01-14T19:03:53.762Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/88/4d/9fe843671c7b94d8e8a925662775d4b2632c138c6a0a9d1bb2c379f225c0/pyobjc_framework_GameKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:dabe856c8638940d2b346abc7a1828cca12d00b47d2951d0ac9f4e27ecc8d3ec", size = 21667 }, - { url = "https://files.pythonhosted.org/packages/98/b2/d4d1f123fead83bf68eb4ecfab2125933f3114eaf2ed420d7bb99238ba67/pyobjc_framework_GameKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:40d506505f71ed57779c8be9b4e07ec9337c45aebe323b3f8dd8f8c75e6fce50", size = 21627 }, + { url = "https://files.pythonhosted.org/packages/88/4d/9fe843671c7b94d8e8a925662775d4b2632c138c6a0a9d1bb2c379f225c0/pyobjc_framework_GameKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:dabe856c8638940d2b346abc7a1828cca12d00b47d2951d0ac9f4e27ecc8d3ec", size = 21667, upload-time = "2025-01-14T18:53:27.239Z" }, + { url = "https://files.pythonhosted.org/packages/98/b2/d4d1f123fead83bf68eb4ecfab2125933f3114eaf2ed420d7bb99238ba67/pyobjc_framework_GameKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:40d506505f71ed57779c8be9b4e07ec9337c45aebe323b3f8dd8f8c75e6fce50", size = 21627, upload-time = "2025-01-14T18:53:28.228Z" }, ] [[package]] @@ -2977,14 +3006,14 @@ name = "pyobjc-framework-gameplaykit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-spritekit", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-spritekit" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/41/f0/980c4fc3c594d9726b7eb6ae83f73127b22560e1541c7d272d23d17fdf0d/pyobjc_framework_gameplaykit-11.0.tar.gz", hash = "sha256:90eeec464fba992d75a406ccbddb35ed7420a4f5226f19c018982fa3ba7bf431", size = 72837 } +sdist = { url = "https://files.pythonhosted.org/packages/41/f0/980c4fc3c594d9726b7eb6ae83f73127b22560e1541c7d272d23d17fdf0d/pyobjc_framework_gameplaykit-11.0.tar.gz", hash = "sha256:90eeec464fba992d75a406ccbddb35ed7420a4f5226f19c018982fa3ba7bf431", size = 72837, upload-time = "2025-01-14T19:03:56.127Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/30/e7/3530071bf1897f2fe2e5f0c54620f0df9fcac586b9ba6bb5726fc9d295c2/pyobjc_framework_GameplayKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:01f59bbf5beb0cfcfea17011987995f1cccf2ec081d91269f95e71283dd83c67", size = 13381 }, - { url = "https://files.pythonhosted.org/packages/b9/07/075369dd9d4e3849646285d4083a9d28214fdd043b499c7929047b942c7f/pyobjc_framework_GameplayKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f2d56af0a84439b3ddc64cdec90e3fab08b1d43da97bed0fb8d60714f47c4372", size = 13382 }, + { url = "https://files.pythonhosted.org/packages/30/e7/3530071bf1897f2fe2e5f0c54620f0df9fcac586b9ba6bb5726fc9d295c2/pyobjc_framework_GameplayKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:01f59bbf5beb0cfcfea17011987995f1cccf2ec081d91269f95e71283dd83c67", size = 13381, upload-time = "2025-01-14T18:53:34.217Z" }, + { url = "https://files.pythonhosted.org/packages/b9/07/075369dd9d4e3849646285d4083a9d28214fdd043b499c7929047b942c7f/pyobjc_framework_GameplayKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f2d56af0a84439b3ddc64cdec90e3fab08b1d43da97bed0fb8d60714f47c4372", size = 13382, upload-time = "2025-01-14T18:53:36.303Z" }, ] [[package]] @@ -2992,13 +3021,13 @@ name = "pyobjc-framework-healthkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/7b/2f/d79d2ec7c23bfc94bfaa7b7c6f6487a8bffdb73263eea6900aab56135889/pyobjc_framework_healthkit-11.0.tar.gz", hash = "sha256:e78ccb05f747ae3e70b5d73522030b7ba01ef2d390155fba7d50c1c614ae241f", size = 201558 } +sdist = { url = "https://files.pythonhosted.org/packages/7b/2f/d79d2ec7c23bfc94bfaa7b7c6f6487a8bffdb73263eea6900aab56135889/pyobjc_framework_healthkit-11.0.tar.gz", hash = "sha256:e78ccb05f747ae3e70b5d73522030b7ba01ef2d390155fba7d50c1c614ae241f", size = 201558, upload-time = "2025-01-14T19:03:57.117Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f0/66/36a2fa7ef61b54a8e283355518ed003aa28b26e1dfad9ecbb7f543a08acd/pyobjc_framework_HealthKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ee87453c28bd4040b12a3bc834f0ea1989e331400845a14079e8f4a6ede70aa2", size = 20139 }, - { url = "https://files.pythonhosted.org/packages/5f/fd/95d40483d9d185317adbf8433d0c7e83ba36ec6c5a824159b87160f6cebe/pyobjc_framework_HealthKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:680da6d67b0c79d15e897f1c588a8b02d780573aef3692e982294c43727eecf3", size = 20163 }, + { url = "https://files.pythonhosted.org/packages/f0/66/36a2fa7ef61b54a8e283355518ed003aa28b26e1dfad9ecbb7f543a08acd/pyobjc_framework_HealthKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ee87453c28bd4040b12a3bc834f0ea1989e331400845a14079e8f4a6ede70aa2", size = 20139, upload-time = "2025-01-14T18:53:44.342Z" }, + { url = "https://files.pythonhosted.org/packages/5f/fd/95d40483d9d185317adbf8433d0c7e83ba36ec6c5a824159b87160f6cebe/pyobjc_framework_HealthKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:680da6d67b0c79d15e897f1c588a8b02d780573aef3692e982294c43727eecf3", size = 20163, upload-time = "2025-01-14T18:53:45.278Z" }, ] [[package]] @@ -3006,13 +3035,13 @@ name = "pyobjc-framework-imagecapturecore" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/38/fe/db1fc3ffd784a9010070cd87a05d7fd2542c400395589341fab5970a01e1/pyobjc_framework_imagecapturecore-11.0.tar.gz", hash = "sha256:f5d185d8c8b564f8b4a815381bcdb424b10d203ba5bdf0fc887085e007df6f7a", size = 99935 } +sdist = { url = "https://files.pythonhosted.org/packages/38/fe/db1fc3ffd784a9010070cd87a05d7fd2542c400395589341fab5970a01e1/pyobjc_framework_imagecapturecore-11.0.tar.gz", hash = "sha256:f5d185d8c8b564f8b4a815381bcdb424b10d203ba5bdf0fc887085e007df6f7a", size = 99935, upload-time = "2025-01-14T19:03:58.548Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e2/fb/29f20521e0df5da0110f1d6a48e4ed3530a2c0b670bf62d89ceeddd42c18/pyobjc_framework_ImageCaptureCore-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3fd78aa4a69e24caed38ae17a69b973e505324d966df86b47441318800a52db9", size = 16611 }, - { url = "https://files.pythonhosted.org/packages/0e/ce/404666e27318435a0513dcf64b85d7cd99195b2e822e03796b03af549c52/pyobjc_framework_ImageCaptureCore-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c5cc6c6acbfca05977adc0e339e1225d5cd314af2fa455a70baebb54f9fb2b64", size = 16636 }, + { url = "https://files.pythonhosted.org/packages/e2/fb/29f20521e0df5da0110f1d6a48e4ed3530a2c0b670bf62d89ceeddd42c18/pyobjc_framework_ImageCaptureCore-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3fd78aa4a69e24caed38ae17a69b973e505324d966df86b47441318800a52db9", size = 16611, upload-time = "2025-01-14T18:54:05.308Z" }, + { url = "https://files.pythonhosted.org/packages/0e/ce/404666e27318435a0513dcf64b85d7cd99195b2e822e03796b03af549c52/pyobjc_framework_ImageCaptureCore-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c5cc6c6acbfca05977adc0e339e1225d5cd314af2fa455a70baebb54f9fb2b64", size = 16636, upload-time = "2025-01-14T18:54:06.288Z" }, ] [[package]] @@ -3020,13 +3049,13 @@ name = "pyobjc-framework-inputmethodkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e7/e9/13d007285582e598903264a7d25cc6771a2a52d6c2a96a68fe91db0844fb/pyobjc_framework_inputmethodkit-11.0.tar.gz", hash = "sha256:86cd648bf98c4e777c884b7f69ebcafba84866740430d297645bf388eee6ce52", size = 26684 } +sdist = { url = "https://files.pythonhosted.org/packages/e7/e9/13d007285582e598903264a7d25cc6771a2a52d6c2a96a68fe91db0844fb/pyobjc_framework_inputmethodkit-11.0.tar.gz", hash = "sha256:86cd648bf98c4e777c884b7f69ebcafba84866740430d297645bf388eee6ce52", size = 26684, upload-time = "2025-01-14T19:03:59.525Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b5/08/18572def66bf1e0ee6d079b45b34f8b4cbf2ab40b3024c351e4bd83cfa4c/pyobjc_framework_InputMethodKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1a58273233e236cb9fa2d8d9295017c6bf26d6f47cc3a5dc9ba81f1c1e64a346", size = 9369 }, - { url = "https://files.pythonhosted.org/packages/9d/c9/7793b0d7b363548e62499660899893dff2953ae3a56aa5080e9b199d1291/pyobjc_framework_InputMethodKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7869db2b08586e97181ec2b60b8f5b9d3a683097bae4ce4bb29dc3c5709c3f13", size = 9390 }, + { url = "https://files.pythonhosted.org/packages/b5/08/18572def66bf1e0ee6d079b45b34f8b4cbf2ab40b3024c351e4bd83cfa4c/pyobjc_framework_InputMethodKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1a58273233e236cb9fa2d8d9295017c6bf26d6f47cc3a5dc9ba81f1c1e64a346", size = 9369, upload-time = "2025-01-14T18:54:12.452Z" }, + { url = "https://files.pythonhosted.org/packages/9d/c9/7793b0d7b363548e62499660899893dff2953ae3a56aa5080e9b199d1291/pyobjc_framework_InputMethodKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7869db2b08586e97181ec2b60b8f5b9d3a683097bae4ce4bb29dc3c5709c3f13", size = 9390, upload-time = "2025-01-14T18:54:13.383Z" }, ] [[package]] @@ -3034,13 +3063,13 @@ name = "pyobjc-framework-installerplugins" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f2/f3/0379655e8ea3566002768d5e7b3ccd72ca845390632a8dabf801348af3a7/pyobjc_framework_installerplugins-11.0.tar.gz", hash = "sha256:88ec84e6999e8b2df874758b09878504a4fbfc8471cf3cd589d57e556f5b916e", size = 27687 } +sdist = { url = "https://files.pythonhosted.org/packages/f2/f3/0379655e8ea3566002768d5e7b3ccd72ca845390632a8dabf801348af3a7/pyobjc_framework_installerplugins-11.0.tar.gz", hash = "sha256:88ec84e6999e8b2df874758b09878504a4fbfc8471cf3cd589d57e556f5b916e", size = 27687, upload-time = "2025-01-14T19:04:00.515Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/03/db/0f3334648a53c8ad663fd19d5421863cb0b711e38a2eb742798d50ed33ef/pyobjc_framework_InstallerPlugins-11.0-py2.py3-none-any.whl", hash = "sha256:cb21bfd5597233a2de3d8c0a8d50f23cf92c43e8963edf85787430ac3cadf4a3", size = 4716 }, - { url = "https://files.pythonhosted.org/packages/f7/56/fe6f50d74d19b0f85035aba977db7039eedbd2de5ac991278a6a5be475a0/pyobjc_framework_InstallerPlugins-11.0-py3-none-any.whl", hash = "sha256:2221301f466d30d6fd32c7317560c85926a3ee93f1de52d320e3b3cd826a8f93", size = 4784 }, + { url = "https://files.pythonhosted.org/packages/03/db/0f3334648a53c8ad663fd19d5421863cb0b711e38a2eb742798d50ed33ef/pyobjc_framework_InstallerPlugins-11.0-py2.py3-none-any.whl", hash = "sha256:cb21bfd5597233a2de3d8c0a8d50f23cf92c43e8963edf85787430ac3cadf4a3", size = 4716, upload-time = "2025-01-14T18:54:17.885Z" }, + { url = "https://files.pythonhosted.org/packages/f7/56/fe6f50d74d19b0f85035aba977db7039eedbd2de5ac991278a6a5be475a0/pyobjc_framework_InstallerPlugins-11.0-py3-none-any.whl", hash = "sha256:2221301f466d30d6fd32c7317560c85926a3ee93f1de52d320e3b3cd826a8f93", size = 4784, upload-time = "2025-01-14T18:54:19.028Z" }, ] [[package]] @@ -3048,14 +3077,14 @@ name = "pyobjc-framework-instantmessage" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/08/4d/6810a1f2039ff24d9498858b3ebb46357d4091aa5cec9ff4e41bbcdb25de/pyobjc_framework_instantmessage-11.0.tar.gz", hash = "sha256:ec5c4c70c9b0e61ae82888067246e4f931e700d625b3c42604e54759d4fbf65c", size = 34027 } +sdist = { url = "https://files.pythonhosted.org/packages/08/4d/6810a1f2039ff24d9498858b3ebb46357d4091aa5cec9ff4e41bbcdb25de/pyobjc_framework_instantmessage-11.0.tar.gz", hash = "sha256:ec5c4c70c9b0e61ae82888067246e4f931e700d625b3c42604e54759d4fbf65c", size = 34027, upload-time = "2025-01-14T19:04:01.405Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/8c/41/4c0ec3d59f9930e9c52570f7e26d79055881e0009e07466b4988c107ef7c/pyobjc_framework_InstantMessage-11.0-py2.py3-none-any.whl", hash = "sha256:ce364e4e18ec8551512b7d968c0d950ccf7de4bb470f66fe524f3bc8d23df0d1", size = 5334 }, - { url = "https://files.pythonhosted.org/packages/19/d9/e3620a5316c986b27361d2f21dd74b48f70c6f7bfe580075e970ca9d7bd6/pyobjc_framework_InstantMessage-11.0-py3-none-any.whl", hash = "sha256:a2817353eaf8f37fe6063c28006b2a0889892e3de801b51b059c153a9d3f35f8", size = 5402 }, + { url = "https://files.pythonhosted.org/packages/8c/41/4c0ec3d59f9930e9c52570f7e26d79055881e0009e07466b4988c107ef7c/pyobjc_framework_InstantMessage-11.0-py2.py3-none-any.whl", hash = "sha256:ce364e4e18ec8551512b7d968c0d950ccf7de4bb470f66fe524f3bc8d23df0d1", size = 5334, upload-time = "2025-01-14T18:54:20.187Z" }, + { url = "https://files.pythonhosted.org/packages/19/d9/e3620a5316c986b27361d2f21dd74b48f70c6f7bfe580075e970ca9d7bd6/pyobjc_framework_InstantMessage-11.0-py3-none-any.whl", hash = "sha256:a2817353eaf8f37fe6063c28006b2a0889892e3de801b51b059c153a9d3f35f8", size = 5402, upload-time = "2025-01-14T18:54:21.261Z" }, ] [[package]] @@ -3063,13 +3092,13 @@ name = "pyobjc-framework-intents" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/56/88/07e47b0c5c46fe97c23c883ae7a053c2ca6f6fd6afe851d1c2c784644f0f/pyobjc_framework_intents-11.0.tar.gz", hash = "sha256:6405c816dfed8ffa8b3f8b0fae75f61d64787dbae8db1c475bb4450cf8fdf6b5", size = 447921 } +sdist = { url = "https://files.pythonhosted.org/packages/56/88/07e47b0c5c46fe97c23c883ae7a053c2ca6f6fd6afe851d1c2c784644f0f/pyobjc_framework_intents-11.0.tar.gz", hash = "sha256:6405c816dfed8ffa8b3f8b0fae75f61d64787dbae8db1c475bb4450cf8fdf6b5", size = 447921, upload-time = "2025-01-14T19:04:02.487Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/86/2e/cd8a4aa10a1d3808dd6f71195a28906c573345673dd92b774fbb8c93dd75/pyobjc_framework_Intents-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a9a445a3d4a0622ebf96c65b0ac0be7cec1e72cf7fd9900cd5ace6acf4e84bce", size = 32021 }, - { url = "https://files.pythonhosted.org/packages/4a/0e/05c457dab601e3eb5ed7243a04fede32423f08dd03a08e988611359d55b4/pyobjc_framework_Intents-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1e148accce2c7c9243ff90ab3f1a200f93d93506da9c3a2cd034fd5579cb839a", size = 32008 }, + { url = "https://files.pythonhosted.org/packages/86/2e/cd8a4aa10a1d3808dd6f71195a28906c573345673dd92b774fbb8c93dd75/pyobjc_framework_Intents-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a9a445a3d4a0622ebf96c65b0ac0be7cec1e72cf7fd9900cd5ace6acf4e84bce", size = 32021, upload-time = "2025-01-14T18:54:23.325Z" }, + { url = "https://files.pythonhosted.org/packages/4a/0e/05c457dab601e3eb5ed7243a04fede32423f08dd03a08e988611359d55b4/pyobjc_framework_Intents-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1e148accce2c7c9243ff90ab3f1a200f93d93506da9c3a2cd034fd5579cb839a", size = 32008, upload-time = "2025-01-14T18:54:24.317Z" }, ] [[package]] @@ -3077,13 +3106,13 @@ name = "pyobjc-framework-intentsui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intents", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-intents" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ee/96/3b3b367f70a4d0a60d2c6251e4a1f4bf470945ae939e0ba20e6d56d10c7a/pyobjc_framework_intentsui-11.0.tar.gz", hash = "sha256:4ce04f926c823fbc1fba7d9c5b33d512b514396719e6bc50ef65b82774e42bc5", size = 20774 } +sdist = { url = "https://files.pythonhosted.org/packages/ee/96/3b3b367f70a4d0a60d2c6251e4a1f4bf470945ae939e0ba20e6d56d10c7a/pyobjc_framework_intentsui-11.0.tar.gz", hash = "sha256:4ce04f926c823fbc1fba7d9c5b33d512b514396719e6bc50ef65b82774e42bc5", size = 20774, upload-time = "2025-01-14T19:04:03.648Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/89/19/f32a14585e749258bb945805da93fd71e05534b14e09fab243fb5ec507ff/pyobjc_framework_IntentsUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7c677225d38fffc5e00df803f93a6a627c466b35a362ed27173f7901e185882e", size = 8772 }, - { url = "https://files.pythonhosted.org/packages/2f/d4/e81e9cfafef63cef481ab251a961ca98e176ca244be91368e0f6b6fe8793/pyobjc_framework_IntentsUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b93a1d9594f471596f255db354c13d67caed7aa020afb9f4e69cde2674f4db71", size = 8789 }, + { url = "https://files.pythonhosted.org/packages/89/19/f32a14585e749258bb945805da93fd71e05534b14e09fab243fb5ec507ff/pyobjc_framework_IntentsUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7c677225d38fffc5e00df803f93a6a627c466b35a362ed27173f7901e185882e", size = 8772, upload-time = "2025-01-14T18:54:29.958Z" }, + { url = "https://files.pythonhosted.org/packages/2f/d4/e81e9cfafef63cef481ab251a961ca98e176ca244be91368e0f6b6fe8793/pyobjc_framework_IntentsUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b93a1d9594f471596f255db354c13d67caed7aa020afb9f4e69cde2674f4db71", size = 8789, upload-time = "2025-01-14T18:54:30.984Z" }, ] [[package]] @@ -3091,13 +3120,13 @@ name = "pyobjc-framework-iobluetooth" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/1e/46/62913f8e5ac307b154b3dd50a7a0b167c9d7ac2a579223e33208c141c387/pyobjc_framework_iobluetooth-11.0.tar.gz", hash = "sha256:869f01f573482da92674abbae4a154143e993b1fe4b2c3523f9e0f9c48b798d4", size = 300463 } +sdist = { url = "https://files.pythonhosted.org/packages/1e/46/62913f8e5ac307b154b3dd50a7a0b167c9d7ac2a579223e33208c141c387/pyobjc_framework_iobluetooth-11.0.tar.gz", hash = "sha256:869f01f573482da92674abbae4a154143e993b1fe4b2c3523f9e0f9c48b798d4", size = 300463, upload-time = "2025-01-14T19:04:04.582Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7a/2e/2037b1c3459008ccdc41d65ab236d7919eed9bbadd0f02f65dc0193bb170/pyobjc_framework_IOBluetooth-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7d2005d3eff2afed4b5930613ae3c1b50004ebabffb86c0d5dd28d54436e16e6", size = 41010 }, - { url = "https://files.pythonhosted.org/packages/2a/52/c266636ff3edc98c1aaf2cc154392876a68d4167bed0351dc2933d5ccc3c/pyobjc_framework_IOBluetooth-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f86d2e675ee2a61ba3d2a446322e918e8ef2dc3e242e893ef81abfc480a6f2c2", size = 41012 }, + { url = "https://files.pythonhosted.org/packages/7a/2e/2037b1c3459008ccdc41d65ab236d7919eed9bbadd0f02f65dc0193bb170/pyobjc_framework_IOBluetooth-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7d2005d3eff2afed4b5930613ae3c1b50004ebabffb86c0d5dd28d54436e16e6", size = 41010, upload-time = "2025-01-14T18:53:51.62Z" }, + { url = "https://files.pythonhosted.org/packages/2a/52/c266636ff3edc98c1aaf2cc154392876a68d4167bed0351dc2933d5ccc3c/pyobjc_framework_IOBluetooth-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f86d2e675ee2a61ba3d2a446322e918e8ef2dc3e242e893ef81abfc480a6f2c2", size = 41012, upload-time = "2025-01-14T18:53:52.757Z" }, ] [[package]] @@ -3105,13 +3134,13 @@ name = "pyobjc-framework-iobluetoothui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetooth", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-iobluetooth" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/76/55/d194de8cfa63c96970e6c90c35e80ce3fceb42934a85d3728736a0e416ff/pyobjc_framework_iobluetoothui-11.0.tar.gz", hash = "sha256:a583758d3e54149ee2dcf00374685aa99e8ae407e044f7c378acc002f9f27e63", size = 23091 } +sdist = { url = "https://files.pythonhosted.org/packages/76/55/d194de8cfa63c96970e6c90c35e80ce3fceb42934a85d3728736a0e416ff/pyobjc_framework_iobluetoothui-11.0.tar.gz", hash = "sha256:a583758d3e54149ee2dcf00374685aa99e8ae407e044f7c378acc002f9f27e63", size = 23091, upload-time = "2025-01-14T19:04:05.659Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d9/75/9401ae099f32a6be2e5759f8d25c573bcf103833343457ca5981153262ab/pyobjc_framework_IOBluetoothUI-11.0-py2.py3-none-any.whl", hash = "sha256:0f94afeb5ecbde07712ea7658a38d6b0e3558154a6bc29c9a33b633f5952b2c3", size = 3972 }, - { url = "https://files.pythonhosted.org/packages/11/a3/75e473de9d25084bfbfa4c0ba24edf038956a604d78219894dc0b412e501/pyobjc_framework_IOBluetoothUI-11.0-py3-none-any.whl", hash = "sha256:5bc366a9904532168ac2c49523e7f090f81b6acbb7b8929ffc7855be0b1d4cf7", size = 4043 }, + { url = "https://files.pythonhosted.org/packages/d9/75/9401ae099f32a6be2e5759f8d25c573bcf103833343457ca5981153262ab/pyobjc_framework_IOBluetoothUI-11.0-py2.py3-none-any.whl", hash = "sha256:0f94afeb5ecbde07712ea7658a38d6b0e3558154a6bc29c9a33b633f5952b2c3", size = 3972, upload-time = "2025-01-14T18:53:57.925Z" }, + { url = "https://files.pythonhosted.org/packages/11/a3/75e473de9d25084bfbfa4c0ba24edf038956a604d78219894dc0b412e501/pyobjc_framework_IOBluetoothUI-11.0-py3-none-any.whl", hash = "sha256:5bc366a9904532168ac2c49523e7f090f81b6acbb7b8929ffc7855be0b1d4cf7", size = 4043, upload-time = "2025-01-14T18:54:00.086Z" }, ] [[package]] @@ -3119,13 +3148,13 @@ name = "pyobjc-framework-iosurface" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fb/91/ae9ca9e1a777eb786d9d43649437d01d24386736cffe9bb2f504b57e8db6/pyobjc_framework_iosurface-11.0.tar.gz", hash = "sha256:24da8d1cf9356717b1c7e75a1c61e9a9417b62f051d13423a4a7b0978d3dcda5", size = 20555 } +sdist = { url = "https://files.pythonhosted.org/packages/fb/91/ae9ca9e1a777eb786d9d43649437d01d24386736cffe9bb2f504b57e8db6/pyobjc_framework_iosurface-11.0.tar.gz", hash = "sha256:24da8d1cf9356717b1c7e75a1c61e9a9417b62f051d13423a4a7b0978d3dcda5", size = 20555, upload-time = "2025-01-14T19:04:09.475Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b8/08/b96f84b623e2dd2ef733ccdd67a1694f51bfdb4dfd81d38e7755566ab9e5/pyobjc_framework_IOSurface-11.0-py2.py3-none-any.whl", hash = "sha256:58c6e79401a00dc63a5797cd3cc067542d4f94fcd2fc8979dc248c3b06c3b829", size = 4905 }, - { url = "https://files.pythonhosted.org/packages/2d/af/4d7ece43c993369a8593c36e0f239b739b78c01e71d74553a630dadd1599/pyobjc_framework_IOSurface-11.0-py3-none-any.whl", hash = "sha256:f2bc13cbfd178396bde6e7558b05a49f69cce376885a07f645a5dd69d2b578fc", size = 4972 }, + { url = "https://files.pythonhosted.org/packages/b8/08/b96f84b623e2dd2ef733ccdd67a1694f51bfdb4dfd81d38e7755566ab9e5/pyobjc_framework_IOSurface-11.0-py2.py3-none-any.whl", hash = "sha256:58c6e79401a00dc63a5797cd3cc067542d4f94fcd2fc8979dc248c3b06c3b829", size = 4905, upload-time = "2025-01-14T18:54:00.978Z" }, + { url = "https://files.pythonhosted.org/packages/2d/af/4d7ece43c993369a8593c36e0f239b739b78c01e71d74553a630dadd1599/pyobjc_framework_IOSurface-11.0-py3-none-any.whl", hash = "sha256:f2bc13cbfd178396bde6e7558b05a49f69cce376885a07f645a5dd69d2b578fc", size = 4972, upload-time = "2025-01-14T18:54:03.244Z" }, ] [[package]] @@ -3133,13 +3162,13 @@ name = "pyobjc-framework-ituneslibrary" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/41/fe/881ab1058d795fe68ccc1e14df0d5e161601dced15d3be84105ecc44bae6/pyobjc_framework_ituneslibrary-11.0.tar.gz", hash = "sha256:2e15dcfbb9d5e95634ddff153de159a28f5879f1a13fdf95504e011773056c6e", size = 47647 } +sdist = { url = "https://files.pythonhosted.org/packages/41/fe/881ab1058d795fe68ccc1e14df0d5e161601dced15d3be84105ecc44bae6/pyobjc_framework_ituneslibrary-11.0.tar.gz", hash = "sha256:2e15dcfbb9d5e95634ddff153de159a28f5879f1a13fdf95504e011773056c6e", size = 47647, upload-time = "2025-01-14T19:04:11.333Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5f/d2/52d1c71ec91ec299e1324658d023954cf62ce4c275155dc66cd298517ae2/pyobjc_framework_iTunesLibrary-11.0-py2.py3-none-any.whl", hash = "sha256:3836fccec315f5186e4b029b486fd18d4b1f24a4c2e73f2d9f3e157ee66d294d", size = 5147 }, - { url = "https://files.pythonhosted.org/packages/dc/97/c23c522d506ae01740c04982a1db5861888056dc65d56876a2de0fc490bc/pyobjc_framework_iTunesLibrary-11.0-py3-none-any.whl", hash = "sha256:bfd40fde3f057318329e5fb6e256051eea3f6cd2e2adb9c1f1f51fcb87deb05a", size = 5210 }, + { url = "https://files.pythonhosted.org/packages/5f/d2/52d1c71ec91ec299e1324658d023954cf62ce4c275155dc66cd298517ae2/pyobjc_framework_iTunesLibrary-11.0-py2.py3-none-any.whl", hash = "sha256:3836fccec315f5186e4b029b486fd18d4b1f24a4c2e73f2d9f3e157ee66d294d", size = 5147, upload-time = "2025-01-14T19:01:49.97Z" }, + { url = "https://files.pythonhosted.org/packages/dc/97/c23c522d506ae01740c04982a1db5861888056dc65d56876a2de0fc490bc/pyobjc_framework_iTunesLibrary-11.0-py3-none-any.whl", hash = "sha256:bfd40fde3f057318329e5fb6e256051eea3f6cd2e2adb9c1f1f51fcb87deb05a", size = 5210, upload-time = "2025-01-14T19:01:51.573Z" }, ] [[package]] @@ -3147,13 +3176,13 @@ name = "pyobjc-framework-kernelmanagement" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/4a/ea/8ef534fce78817fc577f18de2b34e363873f785894f2bbbfc694823f5088/pyobjc_framework_kernelmanagement-11.0.tar.gz", hash = "sha256:812479d5f85eae27aeeaa22f64c20b926b28b5b9b2bf31c8eab9496d3e038028", size = 12794 } +sdist = { url = "https://files.pythonhosted.org/packages/4a/ea/8ef534fce78817fc577f18de2b34e363873f785894f2bbbfc694823f5088/pyobjc_framework_kernelmanagement-11.0.tar.gz", hash = "sha256:812479d5f85eae27aeeaa22f64c20b926b28b5b9b2bf31c8eab9496d3e038028", size = 12794, upload-time = "2025-01-14T19:04:14.204Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ee/fe/ad7278325d8c760d5366b08d6162193612a3bf33bb0fa98d83d7dcc41918/pyobjc_framework_KernelManagement-11.0-py2.py3-none-any.whl", hash = "sha256:e2ad0efd00c0dce90fc05efac296733282c482d54ec7c5fdcb86b4fb8dff1eb8", size = 3604 }, - { url = "https://files.pythonhosted.org/packages/1e/20/8aff6699bf780c88770214f72e92b9db736de078aa1aaaea45312758116e/pyobjc_framework_KernelManagement-11.0-py3-none-any.whl", hash = "sha256:90baacf8bea2883fd62ffb5d7dc6e6ae43fcc6f444458c884da8d92170fcaa5e", size = 3675 }, + { url = "https://files.pythonhosted.org/packages/ee/fe/ad7278325d8c760d5366b08d6162193612a3bf33bb0fa98d83d7dcc41918/pyobjc_framework_KernelManagement-11.0-py2.py3-none-any.whl", hash = "sha256:e2ad0efd00c0dce90fc05efac296733282c482d54ec7c5fdcb86b4fb8dff1eb8", size = 3604, upload-time = "2025-01-14T18:54:36.643Z" }, + { url = "https://files.pythonhosted.org/packages/1e/20/8aff6699bf780c88770214f72e92b9db736de078aa1aaaea45312758116e/pyobjc_framework_KernelManagement-11.0-py3-none-any.whl", hash = "sha256:90baacf8bea2883fd62ffb5d7dc6e6ae43fcc6f444458c884da8d92170fcaa5e", size = 3675, upload-time = "2025-01-14T18:54:37.62Z" }, ] [[package]] @@ -3161,13 +3190,13 @@ name = "pyobjc-framework-latentsemanticmapping" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/42/29/8838eefeb82da95931134b06624364812dedf7e9cc905f36d95d497f2904/pyobjc_framework_latentsemanticmapping-11.0.tar.gz", hash = "sha256:6f578c3e0a171706bdbfcfc2c572a8059bf8039d22c1475df13583749a35cec1", size = 17704 } +sdist = { url = "https://files.pythonhosted.org/packages/42/29/8838eefeb82da95931134b06624364812dedf7e9cc905f36d95d497f2904/pyobjc_framework_latentsemanticmapping-11.0.tar.gz", hash = "sha256:6f578c3e0a171706bdbfcfc2c572a8059bf8039d22c1475df13583749a35cec1", size = 17704, upload-time = "2025-01-14T19:04:14.972Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7f/87/a8d2f508c021afa4f8af51773ab22cbd883270bfda8368a86d473736b05a/pyobjc_framework_LatentSemanticMapping-11.0-py2.py3-none-any.whl", hash = "sha256:87fd91320fb7ce0b2c482fda41a5c38388f5a694ee2d7208725d22ff75438c00", size = 5369 }, - { url = "https://files.pythonhosted.org/packages/df/f0/cea2a0d25ad20aef6eb38c432d2c93bda2cb2239c6286b6086f8687a8072/pyobjc_framework_LatentSemanticMapping-11.0-py3-none-any.whl", hash = "sha256:073b8a4e7a22e6abd58005b7d7091144aec4fc1d4b519e9f972b3aee9da30009", size = 5435 }, + { url = "https://files.pythonhosted.org/packages/7f/87/a8d2f508c021afa4f8af51773ab22cbd883270bfda8368a86d473736b05a/pyobjc_framework_LatentSemanticMapping-11.0-py2.py3-none-any.whl", hash = "sha256:87fd91320fb7ce0b2c482fda41a5c38388f5a694ee2d7208725d22ff75438c00", size = 5369, upload-time = "2025-01-14T18:54:38.493Z" }, + { url = "https://files.pythonhosted.org/packages/df/f0/cea2a0d25ad20aef6eb38c432d2c93bda2cb2239c6286b6086f8687a8072/pyobjc_framework_LatentSemanticMapping-11.0-py3-none-any.whl", hash = "sha256:073b8a4e7a22e6abd58005b7d7091144aec4fc1d4b519e9f972b3aee9da30009", size = 5435, upload-time = "2025-01-14T18:54:39.643Z" }, ] [[package]] @@ -3175,13 +3204,13 @@ name = "pyobjc-framework-launchservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/da/59/eb847389224c670c885ae3d008b1ffe3b996bbe094b43e49dfa84f3947a9/pyobjc_framework_launchservices-11.0.tar.gz", hash = "sha256:7c5c8a8cec013e2cb3fa82a167ca2d61505c36a79f75c718f3f913e597f9ffee", size = 20691 } +sdist = { url = "https://files.pythonhosted.org/packages/da/59/eb847389224c670c885ae3d008b1ffe3b996bbe094b43e49dfa84f3947a9/pyobjc_framework_launchservices-11.0.tar.gz", hash = "sha256:7c5c8a8cec013e2cb3fa82a167ca2d61505c36a79f75c718f3f913e597f9ffee", size = 20691, upload-time = "2025-01-14T19:04:15.884Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/35/46/72937390e3eb0f31809f0d56004a388d20b49724495885e8be677707c07c/pyobjc_framework_LaunchServices-11.0-py2.py3-none-any.whl", hash = "sha256:654572e5f2997d8f802b97f619fc6c7d4f927abb03ce53b3dad89b376517b2d1", size = 3807 }, - { url = "https://files.pythonhosted.org/packages/c0/12/74b96f187beb2f5605f9d487c3141ac8d25193556f2f5febff3580e8b2cb/pyobjc_framework_LaunchServices-11.0-py3-none-any.whl", hash = "sha256:dbc169442deae53f881d1d07fc79c9da6459e5f0b411e8dd1cfd1c519b3a99c8", size = 3876 }, + { url = "https://files.pythonhosted.org/packages/35/46/72937390e3eb0f31809f0d56004a388d20b49724495885e8be677707c07c/pyobjc_framework_LaunchServices-11.0-py2.py3-none-any.whl", hash = "sha256:654572e5f2997d8f802b97f619fc6c7d4f927abb03ce53b3dad89b376517b2d1", size = 3807, upload-time = "2025-01-14T18:54:40.579Z" }, + { url = "https://files.pythonhosted.org/packages/c0/12/74b96f187beb2f5605f9d487c3141ac8d25193556f2f5febff3580e8b2cb/pyobjc_framework_LaunchServices-11.0-py3-none-any.whl", hash = "sha256:dbc169442deae53f881d1d07fc79c9da6459e5f0b411e8dd1cfd1c519b3a99c8", size = 3876, upload-time = "2025-01-14T18:54:41.577Z" }, ] [[package]] @@ -3189,13 +3218,13 @@ name = "pyobjc-framework-libdispatch" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ab/33/4ec96a9edd37948f09e94635852c2db695141430cc1adc7b25968e1f3a95/pyobjc_framework_libdispatch-11.0.tar.gz", hash = "sha256:d22df11b07b1c3c8e7cfc4ba9e876a95c19f44acd36cf13d40c5cccc1ffda04b", size = 53496 } +sdist = { url = "https://files.pythonhosted.org/packages/ab/33/4ec96a9edd37948f09e94635852c2db695141430cc1adc7b25968e1f3a95/pyobjc_framework_libdispatch-11.0.tar.gz", hash = "sha256:d22df11b07b1c3c8e7cfc4ba9e876a95c19f44acd36cf13d40c5cccc1ffda04b", size = 53496, upload-time = "2025-01-14T19:04:16.82Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/24/1f/f3273cc8261d45a6bef1fa48ac39cd94f6a1e77b1ec70f79bae52ad54015/pyobjc_framework_libdispatch-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cebdc33a1a771c9ab03fe5c8a2b0ed9698804e7bccdbfcd3cc0045c4b4aad4f3", size = 20607 }, - { url = "https://files.pythonhosted.org/packages/32/08/40638a5e916b1b94b4b29abacb18628fd47871d80fdf2fc1ef7216726d29/pyobjc_framework_libdispatch-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:999815af50ad2216e28d76893023b7839b7f1e8f22bcf7062d81d9a51ade4613", size = 15949 }, + { url = "https://files.pythonhosted.org/packages/24/1f/f3273cc8261d45a6bef1fa48ac39cd94f6a1e77b1ec70f79bae52ad54015/pyobjc_framework_libdispatch-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cebdc33a1a771c9ab03fe5c8a2b0ed9698804e7bccdbfcd3cc0045c4b4aad4f3", size = 20607, upload-time = "2025-01-14T19:01:53.577Z" }, + { url = "https://files.pythonhosted.org/packages/32/08/40638a5e916b1b94b4b29abacb18628fd47871d80fdf2fc1ef7216726d29/pyobjc_framework_libdispatch-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:999815af50ad2216e28d76893023b7839b7f1e8f22bcf7062d81d9a51ade4613", size = 15949, upload-time = "2025-01-14T19:01:54.496Z" }, ] [[package]] @@ -3203,13 +3232,13 @@ name = "pyobjc-framework-libxpc" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b9/7e/9fa73ce6925db9cfd8a6b45d97943af8fe59f92251e7fd201b6e4608c172/pyobjc_framework_libxpc-11.0.tar.gz", hash = "sha256:e0c336913ab6a526b036915aa9038de2a5281e696ac2d3db3347b3040519c11d", size = 48627 } +sdist = { url = "https://files.pythonhosted.org/packages/b9/7e/9fa73ce6925db9cfd8a6b45d97943af8fe59f92251e7fd201b6e4608c172/pyobjc_framework_libxpc-11.0.tar.gz", hash = "sha256:e0c336913ab6a526b036915aa9038de2a5281e696ac2d3db3347b3040519c11d", size = 48627, upload-time = "2025-01-14T19:04:17.728Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/21/c2/b77019e344b3f46ca4169c19e0539cff9586c8db0a97715590696993bd00/pyobjc_framework_libxpc-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5f05f9eb3662df5832ff09ab788d6f6099f4674cb015200db317ea8c69f8c5e8", size = 19683 }, - { url = "https://files.pythonhosted.org/packages/3c/b9/bf34709c2d8f62a029f4c8e7f9a58c6eb5f3a68542cbcd2a15070b66485a/pyobjc_framework_libxpc-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e000cad8588a961a3e6e5016736cd76b5d992b080cfe8b95745691db5a0ce8df", size = 19788 }, + { url = "https://files.pythonhosted.org/packages/21/c2/b77019e344b3f46ca4169c19e0539cff9586c8db0a97715590696993bd00/pyobjc_framework_libxpc-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5f05f9eb3662df5832ff09ab788d6f6099f4674cb015200db317ea8c69f8c5e8", size = 19683, upload-time = "2025-01-14T19:02:02.364Z" }, + { url = "https://files.pythonhosted.org/packages/3c/b9/bf34709c2d8f62a029f4c8e7f9a58c6eb5f3a68542cbcd2a15070b66485a/pyobjc_framework_libxpc-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e000cad8588a961a3e6e5016736cd76b5d992b080cfe8b95745691db5a0ce8df", size = 19788, upload-time = "2025-01-14T19:02:03.327Z" }, ] [[package]] @@ -3217,14 +3246,14 @@ name = "pyobjc-framework-linkpresentation" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/95/5c/dac9fe4ad0a4076c863b5ac9925e751fc18c637ae411e4891c4b7558a5b3/pyobjc_framework_linkpresentation-11.0.tar.gz", hash = "sha256:bc4ace4aab4da4a4e4df10517bd478b6d51ebf00b423268ee8d9f356f9e87be9", size = 15231 } +sdist = { url = "https://files.pythonhosted.org/packages/95/5c/dac9fe4ad0a4076c863b5ac9925e751fc18c637ae411e4891c4b7558a5b3/pyobjc_framework_linkpresentation-11.0.tar.gz", hash = "sha256:bc4ace4aab4da4a4e4df10517bd478b6d51ebf00b423268ee8d9f356f9e87be9", size = 15231, upload-time = "2025-01-14T19:04:20.763Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/12/fc/aa3f0016e2246c4574cce0e323416303992411a012266b5bdda74095ebef/pyobjc_framework_LinkPresentation-11.0-py2.py3-none-any.whl", hash = "sha256:c10ee1ac48bb7cd2d67ade7f354ec71af1f4244a8deb8530ba646fd4ba327b21", size = 3799 }, - { url = "https://files.pythonhosted.org/packages/85/0b/77c16f2d4541a4490723e18c03c3bd6ecf7db789cf4988e628753e2e4526/pyobjc_framework_LinkPresentation-11.0-py3-none-any.whl", hash = "sha256:5b063900715c5bcf58f533e6c9672473cb07fe3eaa0f0454d93947defa09f13e", size = 3865 }, + { url = "https://files.pythonhosted.org/packages/12/fc/aa3f0016e2246c4574cce0e323416303992411a012266b5bdda74095ebef/pyobjc_framework_LinkPresentation-11.0-py2.py3-none-any.whl", hash = "sha256:c10ee1ac48bb7cd2d67ade7f354ec71af1f4244a8deb8530ba646fd4ba327b21", size = 3799, upload-time = "2025-01-14T18:54:43.137Z" }, + { url = "https://files.pythonhosted.org/packages/85/0b/77c16f2d4541a4490723e18c03c3bd6ecf7db789cf4988e628753e2e4526/pyobjc_framework_LinkPresentation-11.0-py3-none-any.whl", hash = "sha256:5b063900715c5bcf58f533e6c9672473cb07fe3eaa0f0454d93947defa09f13e", size = 3865, upload-time = "2025-01-14T18:54:44.287Z" }, ] [[package]] @@ -3232,14 +3261,14 @@ name = "pyobjc-framework-localauthentication" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ec/b1/bea4b5f8adbb69c0b34eddee63e052f35271cc630db43fbef6873352e21f/pyobjc_framework_localauthentication-11.0.tar.gz", hash = "sha256:eb55a3de647894092d6ed3f8f13fdc38e5dbf4850be320ea14dd2ac83176b298", size = 40020 } +sdist = { url = "https://files.pythonhosted.org/packages/ec/b1/bea4b5f8adbb69c0b34eddee63e052f35271cc630db43fbef6873352e21f/pyobjc_framework_localauthentication-11.0.tar.gz", hash = "sha256:eb55a3de647894092d6ed3f8f13fdc38e5dbf4850be320ea14dd2ac83176b298", size = 40020, upload-time = "2025-01-14T19:04:22.206Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d1/dd/eaa44e4fe3b5c312190c0468afcab0a4372da29535fe9f860b6b9e1e6b4a/pyobjc_framework_LocalAuthentication-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8c6500bb5b195799d70f2a622d89a9c2531cb13d6afe30916cf073a195dd86eb", size = 10515 }, - { url = "https://files.pythonhosted.org/packages/31/86/f4e913e966a6dbefbaa95aed35e7d235ba2f172d079d3c0b4351a584357b/pyobjc_framework_LocalAuthentication-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c0291e743fb1534c1df900e9adacc809af0651744627ce8ae25cfd021e3db73b", size = 10530 }, + { url = "https://files.pythonhosted.org/packages/d1/dd/eaa44e4fe3b5c312190c0468afcab0a4372da29535fe9f860b6b9e1e6b4a/pyobjc_framework_LocalAuthentication-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8c6500bb5b195799d70f2a622d89a9c2531cb13d6afe30916cf073a195dd86eb", size = 10515, upload-time = "2025-01-14T18:54:46.214Z" }, + { url = "https://files.pythonhosted.org/packages/31/86/f4e913e966a6dbefbaa95aed35e7d235ba2f172d079d3c0b4351a584357b/pyobjc_framework_LocalAuthentication-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c0291e743fb1534c1df900e9adacc809af0651744627ce8ae25cfd021e3db73b", size = 10530, upload-time = "2025-01-14T18:54:47.16Z" }, ] [[package]] @@ -3247,14 +3276,14 @@ name = "pyobjc-framework-localauthenticationembeddedui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthentication", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-localauthentication" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e1/ee/821f2d2e9da4cba3dc47e50c8367c6405e91551fb7d8ec842858d5b1d45d/pyobjc_framework_localauthenticationembeddedui-11.0.tar.gz", hash = "sha256:7e9bf6df77ff12a4e827988d8578c15b4431694b2fcfd5b0dad5d7738757ee6a", size = 14204 } +sdist = { url = "https://files.pythonhosted.org/packages/e1/ee/821f2d2e9da4cba3dc47e50c8367c6405e91551fb7d8ec842858d5b1d45d/pyobjc_framework_localauthenticationembeddedui-11.0.tar.gz", hash = "sha256:7e9bf6df77ff12a4e827988d8578c15b4431694b2fcfd5b0dad5d7738757ee6a", size = 14204, upload-time = "2025-01-14T19:04:23.566Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/da/66/2151e5ee7fb97b34c7eda9f8b1442683cced27bcb273d34c8aa2c564e528/pyobjc_framework_LocalAuthenticationEmbeddedUI-11.0-py2.py3-none-any.whl", hash = "sha256:0ccbbdd8c7142b1670885881c803f684ee356df83a5338be9135f46462caae6c", size = 3914 }, - { url = "https://files.pythonhosted.org/packages/d8/a9/c362ac3586bb2d46868b8ea9da3747c9aae3f0c9448ee09934a1be805383/pyobjc_framework_LocalAuthenticationEmbeddedUI-11.0-py3-none-any.whl", hash = "sha256:e8da98dc38a88995e344742585d3735af9b5bd9926a29774d77e2aa6dd46b7af", size = 3984 }, + { url = "https://files.pythonhosted.org/packages/da/66/2151e5ee7fb97b34c7eda9f8b1442683cced27bcb273d34c8aa2c564e528/pyobjc_framework_LocalAuthenticationEmbeddedUI-11.0-py2.py3-none-any.whl", hash = "sha256:0ccbbdd8c7142b1670885881c803f684ee356df83a5338be9135f46462caae6c", size = 3914, upload-time = "2025-01-14T18:54:52.074Z" }, + { url = "https://files.pythonhosted.org/packages/d8/a9/c362ac3586bb2d46868b8ea9da3747c9aae3f0c9448ee09934a1be805383/pyobjc_framework_LocalAuthenticationEmbeddedUI-11.0-py3-none-any.whl", hash = "sha256:e8da98dc38a88995e344742585d3735af9b5bd9926a29774d77e2aa6dd46b7af", size = 3984, upload-time = "2025-01-14T18:54:54.974Z" }, ] [[package]] @@ -3262,13 +3291,13 @@ name = "pyobjc-framework-mailkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d8/79/9c9140f726ba14898762ddc19e7142724e0ce5930f08eb20f33f78b05be8/pyobjc_framework_mailkit-11.0.tar.gz", hash = "sha256:d08a2dcc95b5e7955c7c385fe6e018325113d02c007c4178d3fb3c9ab326c163", size = 32274 } +sdist = { url = "https://files.pythonhosted.org/packages/d8/79/9c9140f726ba14898762ddc19e7142724e0ce5930f08eb20f33f78b05be8/pyobjc_framework_mailkit-11.0.tar.gz", hash = "sha256:d08a2dcc95b5e7955c7c385fe6e018325113d02c007c4178d3fb3c9ab326c163", size = 32274, upload-time = "2025-01-14T19:04:25.086Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d2/38/f9bcd204c1ba0943365f3cc505d934ea93fe4b99d61e961ced0f0991a4f9/pyobjc_framework_MailKit-11.0-py2.py3-none-any.whl", hash = "sha256:78e54ff3988fd1af16c06e0c39dea3b7ff522e367d262f58e88962772291c7f9", size = 4803 }, - { url = "https://files.pythonhosted.org/packages/64/4a/f3596583795c608838c7fa84fc4836f365c5744a3e412392d47a200a6221/pyobjc_framework_MailKit-11.0-py3-none-any.whl", hash = "sha256:0573ee0be66419130774aca36b611d0d07fcf7c756524860acba8fe17eefeec2", size = 4874 }, + { url = "https://files.pythonhosted.org/packages/d2/38/f9bcd204c1ba0943365f3cc505d934ea93fe4b99d61e961ced0f0991a4f9/pyobjc_framework_MailKit-11.0-py2.py3-none-any.whl", hash = "sha256:78e54ff3988fd1af16c06e0c39dea3b7ff522e367d262f58e88962772291c7f9", size = 4803, upload-time = "2025-01-14T18:54:58.295Z" }, + { url = "https://files.pythonhosted.org/packages/64/4a/f3596583795c608838c7fa84fc4836f365c5744a3e412392d47a200a6221/pyobjc_framework_MailKit-11.0-py3-none-any.whl", hash = "sha256:0573ee0be66419130774aca36b611d0d07fcf7c756524860acba8fe17eefeec2", size = 4874, upload-time = "2025-01-14T18:55:00.648Z" }, ] [[package]] @@ -3276,15 +3305,15 @@ name = "pyobjc-framework-mapkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-corelocation" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/96/7e/ef86c6e218a58bb9497ce9754a77f12ffe01c4b3609279727b7d7e44655a/pyobjc_framework_mapkit-11.0.tar.gz", hash = "sha256:cd8a91df4c0b442fcf1b14d735e566a06b21b3f48a2a4afe269fca45bfa49117", size = 165080 } +sdist = { url = "https://files.pythonhosted.org/packages/96/7e/ef86c6e218a58bb9497ce9754a77f12ffe01c4b3609279727b7d7e44655a/pyobjc_framework_mapkit-11.0.tar.gz", hash = "sha256:cd8a91df4c0b442fcf1b14d735e566a06b21b3f48a2a4afe269fca45bfa49117", size = 165080, upload-time = "2025-01-14T19:04:26.606Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fc/7e/f0457c7ca001a01f47aa944c1f86a24d2d04db0aa1c19f51cbf77a65cc9b/pyobjc_framework_MapKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:83128d79aa7644e5b966b32346f7da749b1dbb110dadba857b93ecf5663e24e6", size = 23045 }, - { url = "https://files.pythonhosted.org/packages/d5/b0/532b4f57f8783cf6394b17e76174c393d0503ee41e026782a9950bd46279/pyobjc_framework_MapKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e6aa1d00cfe2e02b301467e24ca51e469e9a8a2ec2a9f097b73adca1a5a2a054", size = 23040 }, + { url = "https://files.pythonhosted.org/packages/fc/7e/f0457c7ca001a01f47aa944c1f86a24d2d04db0aa1c19f51cbf77a65cc9b/pyobjc_framework_MapKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:83128d79aa7644e5b966b32346f7da749b1dbb110dadba857b93ecf5663e24e6", size = 23045, upload-time = "2025-01-14T18:55:02.629Z" }, + { url = "https://files.pythonhosted.org/packages/d5/b0/532b4f57f8783cf6394b17e76174c393d0503ee41e026782a9950bd46279/pyobjc_framework_MapKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e6aa1d00cfe2e02b301467e24ca51e469e9a8a2ec2a9f097b73adca1a5a2a054", size = 23040, upload-time = "2025-01-14T18:55:04.055Z" }, ] [[package]] @@ -3292,13 +3321,13 @@ name = "pyobjc-framework-mediaaccessibility" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/81/8e/9fe2cb251ff6107a03bafa07f63b6593df145a2579fffb096023fb21b167/pyobjc_framework_mediaaccessibility-11.0.tar.gz", hash = "sha256:1298cc0128e1c0724e8f8e63a6167ea6809a985922c67399b997f8243de59ab4", size = 18671 } +sdist = { url = "https://files.pythonhosted.org/packages/81/8e/9fe2cb251ff6107a03bafa07f63b6593df145a2579fffb096023fb21b167/pyobjc_framework_mediaaccessibility-11.0.tar.gz", hash = "sha256:1298cc0128e1c0724e8f8e63a6167ea6809a985922c67399b997f8243de59ab4", size = 18671, upload-time = "2025-01-14T19:04:27.624Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/50/1f/36b1115cfd02d68d39cc3fe976fe3d40bad1d1a0a9c8175c66d230bb7276/pyobjc_framework_MediaAccessibility-11.0-py2.py3-none-any.whl", hash = "sha256:901961f171f7af184decbf5a3899debfa56dbd1a63a53d0ff3d93eff90f2f464", size = 4637 }, - { url = "https://files.pythonhosted.org/packages/72/3f/fa350681a6599ed6756dc598fcd17fda1521249e4570a57b4a9b9c900f47/pyobjc_framework_MediaAccessibility-11.0-py3-none-any.whl", hash = "sha256:3f4b9e4d1ac8e7f8cdb7a2e9839ab75cb358dead3e6365ccd8d6017d7e93811e", size = 4708 }, + { url = "https://files.pythonhosted.org/packages/50/1f/36b1115cfd02d68d39cc3fe976fe3d40bad1d1a0a9c8175c66d230bb7276/pyobjc_framework_MediaAccessibility-11.0-py2.py3-none-any.whl", hash = "sha256:901961f171f7af184decbf5a3899debfa56dbd1a63a53d0ff3d93eff90f2f464", size = 4637, upload-time = "2025-01-14T18:55:08.968Z" }, + { url = "https://files.pythonhosted.org/packages/72/3f/fa350681a6599ed6756dc598fcd17fda1521249e4570a57b4a9b9c900f47/pyobjc_framework_MediaAccessibility-11.0-py3-none-any.whl", hash = "sha256:3f4b9e4d1ac8e7f8cdb7a2e9839ab75cb358dead3e6365ccd8d6017d7e93811e", size = 4708, upload-time = "2025-01-14T18:55:09.939Z" }, ] [[package]] @@ -3306,15 +3335,15 @@ name = "pyobjc-framework-mediaextension" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/18/1f/e31d9431bc71077b09583ea863b3c91b7de9371d0cc17a8be99be8119daa/pyobjc_framework_mediaextension-11.0.tar.gz", hash = "sha256:ecd8a64939e1c16be005690117c21fd406fc04d3036e2adea7600d2a0c53f4ea", size = 57931 } +sdist = { url = "https://files.pythonhosted.org/packages/18/1f/e31d9431bc71077b09583ea863b3c91b7de9371d0cc17a8be99be8119daa/pyobjc_framework_mediaextension-11.0.tar.gz", hash = "sha256:ecd8a64939e1c16be005690117c21fd406fc04d3036e2adea7600d2a0c53f4ea", size = 57931, upload-time = "2025-01-14T19:04:28.65Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4d/94/1e4aa67e424a043dfa886c946bb872f9653cc12ad59bd7c2c24e3d19a4f5/pyobjc_framework_MediaExtension-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9f25d674f381bae800761efe1628959293009d287f7127616f75318a87e4543d", size = 39781 }, - { url = "https://files.pythonhosted.org/packages/02/3c/2cbd4498950daadd111639a7b8dea2aaa6825526677b31ae49bc940f1036/pyobjc_framework_MediaExtension-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9a167725f7a6921d446084b132505392bb375a5ef91498f7be5d94c0d48d26ae", size = 39777 }, + { url = "https://files.pythonhosted.org/packages/4d/94/1e4aa67e424a043dfa886c946bb872f9653cc12ad59bd7c2c24e3d19a4f5/pyobjc_framework_MediaExtension-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9f25d674f381bae800761efe1628959293009d287f7127616f75318a87e4543d", size = 39781, upload-time = "2025-01-14T18:55:13.454Z" }, + { url = "https://files.pythonhosted.org/packages/02/3c/2cbd4498950daadd111639a7b8dea2aaa6825526677b31ae49bc940f1036/pyobjc_framework_MediaExtension-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9a167725f7a6921d446084b132505392bb375a5ef91498f7be5d94c0d48d26ae", size = 39777, upload-time = "2025-01-14T18:55:14.434Z" }, ] [[package]] @@ -3322,14 +3351,14 @@ name = "pyobjc-framework-medialibrary" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a8/a4/8c7d1635994800dc412a5db2c4b43ed499184651efcec0c8da3cf8e2bcc7/pyobjc_framework_medialibrary-11.0.tar.gz", hash = "sha256:692889fab1e479a9c207f0ff23c900dad5f47caf47c05cc995d9bb7c1e56e8b9", size = 18975 } +sdist = { url = "https://files.pythonhosted.org/packages/a8/a4/8c7d1635994800dc412a5db2c4b43ed499184651efcec0c8da3cf8e2bcc7/pyobjc_framework_medialibrary-11.0.tar.gz", hash = "sha256:692889fab1e479a9c207f0ff23c900dad5f47caf47c05cc995d9bb7c1e56e8b9", size = 18975, upload-time = "2025-01-14T19:04:29.739Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/16/b6/c079b41a7a4b6b856b4ba7196500f058fb9d9f4f021269b49cf0861ace1f/pyobjc_framework_MediaLibrary-11.0-py2.py3-none-any.whl", hash = "sha256:3d273d4db7e1894fd2a95448c26eeced6e13e33555f727988aeec4b2762246fb", size = 4288 }, - { url = "https://files.pythonhosted.org/packages/b0/ae/05f2ee15f5e8524b27d6e446822edfed977c1ed0d3201644ae4d5d78bdde/pyobjc_framework_MediaLibrary-11.0-py3-none-any.whl", hash = "sha256:b8b97bb9067cf81942ce69d3273e2b18d093290c3fd692172a54f012ab64c0b3", size = 4359 }, + { url = "https://files.pythonhosted.org/packages/16/b6/c079b41a7a4b6b856b4ba7196500f058fb9d9f4f021269b49cf0861ace1f/pyobjc_framework_MediaLibrary-11.0-py2.py3-none-any.whl", hash = "sha256:3d273d4db7e1894fd2a95448c26eeced6e13e33555f727988aeec4b2762246fb", size = 4288, upload-time = "2025-01-14T18:55:20.473Z" }, + { url = "https://files.pythonhosted.org/packages/b0/ae/05f2ee15f5e8524b27d6e446822edfed977c1ed0d3201644ae4d5d78bdde/pyobjc_framework_MediaLibrary-11.0-py3-none-any.whl", hash = "sha256:b8b97bb9067cf81942ce69d3273e2b18d093290c3fd692172a54f012ab64c0b3", size = 4359, upload-time = "2025-01-14T18:55:21.491Z" }, ] [[package]] @@ -3337,13 +3366,13 @@ name = "pyobjc-framework-mediaplayer" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a2/ce/3d2783f2f96ddf51bebcf6537a4a0f2a8a1fe4e520de218fc1b7c5b219ed/pyobjc_framework_mediaplayer-11.0.tar.gz", hash = "sha256:c61be0ba6c648db6b1d013a52f9afb8901a8d7fbabd983df2175c1b1fbff81e5", size = 94020 } +sdist = { url = "https://files.pythonhosted.org/packages/a2/ce/3d2783f2f96ddf51bebcf6537a4a0f2a8a1fe4e520de218fc1b7c5b219ed/pyobjc_framework_mediaplayer-11.0.tar.gz", hash = "sha256:c61be0ba6c648db6b1d013a52f9afb8901a8d7fbabd983df2175c1b1fbff81e5", size = 94020, upload-time = "2025-01-14T19:04:30.617Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/96/b2/57b7b75bb5f2b624ce48cd48fb7d651d2f24d279918b352ae8fb03384b47/pyobjc_framework_MediaPlayer-11.0-py2.py3-none-any.whl", hash = "sha256:b124b0f18444b69b64142bad2579287d0b1a4a35cb6b14526523a822066d527d", size = 6903 }, - { url = "https://files.pythonhosted.org/packages/e9/8e/4969374f0fb243dd06336f2edc8c755743a683e73a57c3253279d048a455/pyobjc_framework_MediaPlayer-11.0-py3-none-any.whl", hash = "sha256:1a051624b536666feb5fd1a4bb54000ab45dac0c8aea4cd4707cbde1773acf57", size = 6977 }, + { url = "https://files.pythonhosted.org/packages/96/b2/57b7b75bb5f2b624ce48cd48fb7d651d2f24d279918b352ae8fb03384b47/pyobjc_framework_MediaPlayer-11.0-py2.py3-none-any.whl", hash = "sha256:b124b0f18444b69b64142bad2579287d0b1a4a35cb6b14526523a822066d527d", size = 6903, upload-time = "2025-01-14T18:55:24.375Z" }, + { url = "https://files.pythonhosted.org/packages/e9/8e/4969374f0fb243dd06336f2edc8c755743a683e73a57c3253279d048a455/pyobjc_framework_MediaPlayer-11.0-py3-none-any.whl", hash = "sha256:1a051624b536666feb5fd1a4bb54000ab45dac0c8aea4cd4707cbde1773acf57", size = 6977, upload-time = "2025-01-14T18:55:25.359Z" }, ] [[package]] @@ -3351,13 +3380,13 @@ name = "pyobjc-framework-mediatoolbox" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/da/46/cf5f3bde6cad32f10095850ca44f24ba241d18b26379187c412be1260f39/pyobjc_framework_mediatoolbox-11.0.tar.gz", hash = "sha256:de949a44f10b5a15e5a7131ee53b2806b8cb753fd01a955970ec0f475952ba24", size = 23067 } +sdist = { url = "https://files.pythonhosted.org/packages/da/46/cf5f3bde6cad32f10095850ca44f24ba241d18b26379187c412be1260f39/pyobjc_framework_mediatoolbox-11.0.tar.gz", hash = "sha256:de949a44f10b5a15e5a7131ee53b2806b8cb753fd01a955970ec0f475952ba24", size = 23067, upload-time = "2025-01-14T19:04:32.823Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c3/d5/ee184e33bd743c363d7ab59d8412289c6ac14c78a035545a067b98704ae2/pyobjc_framework_MediaToolbox-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:df09e4db52d4efeafe4a324600b9c5062fd87c1d1217ebec2df65c8b6b0ce9ef", size = 12776 }, - { url = "https://files.pythonhosted.org/packages/e9/a5/c02d2c44ebcd5884d7ccf55c597c0960d14e4e8f386b65dcd76f9f50ec3d/pyobjc_framework_MediaToolbox-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e80e3057f5030fb034ac93c3e891cee346716e1669f280ebbd63ccfa52b2b7ff", size = 12937 }, + { url = "https://files.pythonhosted.org/packages/c3/d5/ee184e33bd743c363d7ab59d8412289c6ac14c78a035545a067b98704ae2/pyobjc_framework_MediaToolbox-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:df09e4db52d4efeafe4a324600b9c5062fd87c1d1217ebec2df65c8b6b0ce9ef", size = 12776, upload-time = "2025-01-14T18:55:30.277Z" }, + { url = "https://files.pythonhosted.org/packages/e9/a5/c02d2c44ebcd5884d7ccf55c597c0960d14e4e8f386b65dcd76f9f50ec3d/pyobjc_framework_MediaToolbox-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e80e3057f5030fb034ac93c3e891cee346716e1669f280ebbd63ccfa52b2b7ff", size = 12937, upload-time = "2025-01-14T18:55:34.139Z" }, ] [[package]] @@ -3365,13 +3394,13 @@ name = "pyobjc-framework-metal" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/77/e0/a6d18a1183410a5d8610ca1ae6c065b8944586441f8669faee7509817246/pyobjc_framework_metal-11.0.tar.gz", hash = "sha256:cad390150aa63502d5cfe242026b55ed39ffaf816342ddf51e44a9aead6c24be", size = 446102 } +sdist = { url = "https://files.pythonhosted.org/packages/77/e0/a6d18a1183410a5d8610ca1ae6c065b8944586441f8669faee7509817246/pyobjc_framework_metal-11.0.tar.gz", hash = "sha256:cad390150aa63502d5cfe242026b55ed39ffaf816342ddf51e44a9aead6c24be", size = 446102, upload-time = "2025-01-14T19:04:34.011Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e2/fe/083727028e63ffcf7455d10288df05696737ee74a31decdc671e32624f58/pyobjc_framework_Metal-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7ac5f317d52cd7523dea2e172fbe8b03e7452b907da42a0a5e5c5ab427c5e9de", size = 57321 }, - { url = "https://files.pythonhosted.org/packages/78/85/396ad46929ec6e2aa554c29a3fae2f7c7ffb2e1a3fbb9c41948d5a573dc8/pyobjc_framework_Metal-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:45802d48d1a35cc66fee08539c8ca9fc6a0dc4ab700cf78a81cf5f8982ed6f5b", size = 57099 }, + { url = "https://files.pythonhosted.org/packages/e2/fe/083727028e63ffcf7455d10288df05696737ee74a31decdc671e32624f58/pyobjc_framework_Metal-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7ac5f317d52cd7523dea2e172fbe8b03e7452b907da42a0a5e5c5ab427c5e9de", size = 57321, upload-time = "2025-01-14T18:55:39.025Z" }, + { url = "https://files.pythonhosted.org/packages/78/85/396ad46929ec6e2aa554c29a3fae2f7c7ffb2e1a3fbb9c41948d5a573dc8/pyobjc_framework_Metal-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:45802d48d1a35cc66fee08539c8ca9fc6a0dc4ab700cf78a81cf5f8982ed6f5b", size = 57099, upload-time = "2025-01-14T18:55:40.091Z" }, ] [[package]] @@ -3379,13 +3408,13 @@ name = "pyobjc-framework-metalfx" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/68/cf/ff9367e4737a12ebd12a17e693ec247028cf065761acc073ebefb2b2393a/pyobjc_framework_metalfx-11.0.tar.gz", hash = "sha256:2ae41991bf7a733c44fcd5b6550cedea3accaaf0f529643975d3da113c9f0caa", size = 26436 } +sdist = { url = "https://files.pythonhosted.org/packages/68/cf/ff9367e4737a12ebd12a17e693ec247028cf065761acc073ebefb2b2393a/pyobjc_framework_metalfx-11.0.tar.gz", hash = "sha256:2ae41991bf7a733c44fcd5b6550cedea3accaaf0f529643975d3da113c9f0caa", size = 26436, upload-time = "2025-01-14T19:04:36.161Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/16/f1/4140b63b3128cb2f12e136c4158a082ce170e4eb979bccb628768c59fd98/pyobjc_framework_MetalFX-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a3a3847812d40cb6bb7a5f0e735f9f28cba83a1e1264d4dafc630ce894e98a20", size = 10308 }, - { url = "https://files.pythonhosted.org/packages/c0/85/460abd4f96a7a3efd36404a480ed4d31a51f4b3ed64dc4595502a5f725c3/pyobjc_framework_MetalFX-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a37dc271513b217fcba4a99c6cd92997ee171b49b974e0a9dd1b35feb32b7109", size = 10338 }, + { url = "https://files.pythonhosted.org/packages/16/f1/4140b63b3128cb2f12e136c4158a082ce170e4eb979bccb628768c59fd98/pyobjc_framework_MetalFX-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a3a3847812d40cb6bb7a5f0e735f9f28cba83a1e1264d4dafc630ce894e98a20", size = 10308, upload-time = "2025-01-14T18:55:47.719Z" }, + { url = "https://files.pythonhosted.org/packages/c0/85/460abd4f96a7a3efd36404a480ed4d31a51f4b3ed64dc4595502a5f725c3/pyobjc_framework_MetalFX-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a37dc271513b217fcba4a99c6cd92997ee171b49b974e0a9dd1b35feb32b7109", size = 10338, upload-time = "2025-01-14T18:55:48.593Z" }, ] [[package]] @@ -3393,14 +3422,14 @@ name = "pyobjc-framework-metalkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-metal" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/92/27/fb3c1b10914abf2ae6682837abf76bcd8cb7af2ba613fbc55fb9d055bb95/pyobjc_framework_metalkit-11.0.tar.gz", hash = "sha256:1bbbe35c7c6a481383d32f6eaae59a1cd8084319a65c1aa343d63a257d8b4ddb", size = 44628 } +sdist = { url = "https://files.pythonhosted.org/packages/92/27/fb3c1b10914abf2ae6682837abf76bcd8cb7af2ba613fbc55fb9d055bb95/pyobjc_framework_metalkit-11.0.tar.gz", hash = "sha256:1bbbe35c7c6a481383d32f6eaae59a1cd8084319a65c1aa343d63a257d8b4ddb", size = 44628, upload-time = "2025-01-14T19:04:36.977Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d3/44/e7eb6746d9e1ad0ad08ab0a8ac20d264b049960363a8f28a744d1d9c319c/pyobjc_framework_MetalKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f314478a5d772d2f7b4db09957ecb63acd6e3f0cde8c18b1b6b35caa9ea7def2", size = 8598 }, - { url = "https://files.pythonhosted.org/packages/a6/1c/1ae6d629065e495e8e0b7def36e1d632e461a933f616f9776a914d69b2fd/pyobjc_framework_MetalKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1f2d93180e7ac5abd906e492165a72f82d308d68101eadd213bba68a4b1dc4a8", size = 8611 }, + { url = "https://files.pythonhosted.org/packages/d3/44/e7eb6746d9e1ad0ad08ab0a8ac20d264b049960363a8f28a744d1d9c319c/pyobjc_framework_MetalKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f314478a5d772d2f7b4db09957ecb63acd6e3f0cde8c18b1b6b35caa9ea7def2", size = 8598, upload-time = "2025-01-14T18:55:56.761Z" }, + { url = "https://files.pythonhosted.org/packages/a6/1c/1ae6d629065e495e8e0b7def36e1d632e461a933f616f9776a914d69b2fd/pyobjc_framework_MetalKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1f2d93180e7ac5abd906e492165a72f82d308d68101eadd213bba68a4b1dc4a8", size = 8611, upload-time = "2025-01-14T18:55:58.085Z" }, ] [[package]] @@ -3408,13 +3437,13 @@ name = "pyobjc-framework-metalperformanceshaders" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/14/c2/c08996a8c6cfef09fb9e726cc99b0bf3ad0ffcef66d5c2543e6b35dd4e2e/pyobjc_framework_metalperformanceshaders-11.0.tar.gz", hash = "sha256:41179e3a11e55325153fffd84f48946d47c1dc1944677febd871a127021e056d", size = 301444 } +sdist = { url = "https://files.pythonhosted.org/packages/14/c2/c08996a8c6cfef09fb9e726cc99b0bf3ad0ffcef66d5c2543e6b35dd4e2e/pyobjc_framework_metalperformanceshaders-11.0.tar.gz", hash = "sha256:41179e3a11e55325153fffd84f48946d47c1dc1944677febd871a127021e056d", size = 301444, upload-time = "2025-01-14T19:04:38.064Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e6/e9/3741ac0e745e1014961f12cf967eac1d4ec5b110d3ed13fdf9dd4ce27933/pyobjc_framework_MetalPerformanceShaders-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:460a30ff31f04bbe82bf3304949171e148e3171ba0c0773dd9bfc42dad766d2e", size = 33004 }, - { url = "https://files.pythonhosted.org/packages/39/b4/51434a9a897a47f6a0d1f6079725e3de4dbc75a7004275f116a2043cf80b/pyobjc_framework_MetalPerformanceShaders-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:abd4649de32aedfa45f8535d74227ba3e1411b6426f794026e8426feab43ea8e", size = 33222 }, + { url = "https://files.pythonhosted.org/packages/e6/e9/3741ac0e745e1014961f12cf967eac1d4ec5b110d3ed13fdf9dd4ce27933/pyobjc_framework_MetalPerformanceShaders-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:460a30ff31f04bbe82bf3304949171e148e3171ba0c0773dd9bfc42dad766d2e", size = 33004, upload-time = "2025-01-14T18:56:02.993Z" }, + { url = "https://files.pythonhosted.org/packages/39/b4/51434a9a897a47f6a0d1f6079725e3de4dbc75a7004275f116a2043cf80b/pyobjc_framework_MetalPerformanceShaders-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:abd4649de32aedfa45f8535d74227ba3e1411b6426f794026e8426feab43ea8e", size = 33222, upload-time = "2025-01-14T18:56:04.78Z" }, ] [[package]] @@ -3422,13 +3451,13 @@ name = "pyobjc-framework-metalperformanceshadersgraph" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshaders", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metalperformanceshaders" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b5/b8/353852c76eb437e907ca0acf8a5b5f9255e9b9ee8c0706b69b0c17498f97/pyobjc_framework_metalperformanceshadersgraph-11.0.tar.gz", hash = "sha256:33077ebbbe1aa7787de2552a83534be6c439d7f4272de17915a85fda8fd3b72d", size = 105381 } +sdist = { url = "https://files.pythonhosted.org/packages/b5/b8/353852c76eb437e907ca0acf8a5b5f9255e9b9ee8c0706b69b0c17498f97/pyobjc_framework_metalperformanceshadersgraph-11.0.tar.gz", hash = "sha256:33077ebbbe1aa7787de2552a83534be6c439d7f4272de17915a85fda8fd3b72d", size = 105381, upload-time = "2025-01-14T19:04:39.831Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/0d/8c/3d8f1cc6cfe7f9fd73f3911bb62256fdefc4d7f5375b8be84870d8c15650/pyobjc_framework_MetalPerformanceShadersGraph-11.0-py2.py3-none-any.whl", hash = "sha256:d48ffe401fbc8273a23e908685635a51c64d4ebfb5ad32742664ab9fac6c5194", size = 6403 }, - { url = "https://files.pythonhosted.org/packages/ef/26/ca0441ac11d5ecc7814b48b3af9df467ead93622f0edc67e947f1a4afe97/pyobjc_framework_MetalPerformanceShadersGraph-11.0-py3-none-any.whl", hash = "sha256:f0702a6e91b273e552283ff2782220ce08eb65325aa45ad428e0b7f3b45cf211", size = 6474 }, + { url = "https://files.pythonhosted.org/packages/0d/8c/3d8f1cc6cfe7f9fd73f3911bb62256fdefc4d7f5375b8be84870d8c15650/pyobjc_framework_MetalPerformanceShadersGraph-11.0-py2.py3-none-any.whl", hash = "sha256:d48ffe401fbc8273a23e908685635a51c64d4ebfb5ad32742664ab9fac6c5194", size = 6403, upload-time = "2025-01-14T18:56:10.236Z" }, + { url = "https://files.pythonhosted.org/packages/ef/26/ca0441ac11d5ecc7814b48b3af9df467ead93622f0edc67e947f1a4afe97/pyobjc_framework_MetalPerformanceShadersGraph-11.0-py3-none-any.whl", hash = "sha256:f0702a6e91b273e552283ff2782220ce08eb65325aa45ad428e0b7f3b45cf211", size = 6474, upload-time = "2025-01-14T18:56:11.479Z" }, ] [[package]] @@ -3436,13 +3465,13 @@ name = "pyobjc-framework-metrickit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/28/82/605ad654f40ff4480ba9366ad3726da80c98e33b73f122fb91259be1ce81/pyobjc_framework_metrickit-11.0.tar.gz", hash = "sha256:ee3da403863beec181a2d6dc7b7eeb4d07e954b88bbabac58a82523b2f83fdc7", size = 40414 } +sdist = { url = "https://files.pythonhosted.org/packages/28/82/605ad654f40ff4480ba9366ad3726da80c98e33b73f122fb91259be1ce81/pyobjc_framework_metrickit-11.0.tar.gz", hash = "sha256:ee3da403863beec181a2d6dc7b7eeb4d07e954b88bbabac58a82523b2f83fdc7", size = 40414, upload-time = "2025-01-14T19:04:41.186Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/13/1f/cc897b07b3ed96a26a3008f43e0deefaa60e280ac13118a2ff4224fca0d8/pyobjc_framework_MetricKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:422b6ca1f082dae864df8cc4aa0bac3829be95675b72ef63cd3ee00d30966b97", size = 7958 }, - { url = "https://files.pythonhosted.org/packages/19/63/f37010479670958d3c976d007d45107c3fc53b5626586527c6310821e15a/pyobjc_framework_MetricKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b94313601bbf0181c8f75712e82646261ff0e020da5c83d25914952db53a7955", size = 7966 }, + { url = "https://files.pythonhosted.org/packages/13/1f/cc897b07b3ed96a26a3008f43e0deefaa60e280ac13118a2ff4224fca0d8/pyobjc_framework_MetricKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:422b6ca1f082dae864df8cc4aa0bac3829be95675b72ef63cd3ee00d30966b97", size = 7958, upload-time = "2025-01-14T18:56:13.428Z" }, + { url = "https://files.pythonhosted.org/packages/19/63/f37010479670958d3c976d007d45107c3fc53b5626586527c6310821e15a/pyobjc_framework_MetricKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b94313601bbf0181c8f75712e82646261ff0e020da5c83d25914952db53a7955", size = 7966, upload-time = "2025-01-14T18:56:14.36Z" }, ] [[package]] @@ -3450,13 +3479,13 @@ name = "pyobjc-framework-mlcompute" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c5/c9/22fe4720685724ec1444c8e5cdb41d360b1434d0971fb3e43cf3e9bf51fd/pyobjc_framework_mlcompute-11.0.tar.gz", hash = "sha256:1a1ee9ab43d1824300055ff94b042a26f38f1d18f6f0aa08be1c88278e7284d9", size = 89265 } +sdist = { url = "https://files.pythonhosted.org/packages/c5/c9/22fe4720685724ec1444c8e5cdb41d360b1434d0971fb3e43cf3e9bf51fd/pyobjc_framework_mlcompute-11.0.tar.gz", hash = "sha256:1a1ee9ab43d1824300055ff94b042a26f38f1d18f6f0aa08be1c88278e7284d9", size = 89265, upload-time = "2025-01-14T19:04:43.326Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/75/06/a5865c0e4db4e7289bf6b40242b7149af87d5779f34ca168df5cabf2d5a4/pyobjc_framework_MLCompute-11.0-py2.py3-none-any.whl", hash = "sha256:16ec2942af9915f931df76b42e7f42348109b599faef955f5bea540735f87677", size = 6729 }, - { url = "https://files.pythonhosted.org/packages/b5/15/3c69df5b5b99cea4a573e1d0e3c0b607cfe4ea1404ea1fe3a302361eb452/pyobjc_framework_MLCompute-11.0-py3-none-any.whl", hash = "sha256:bcdf94fe060fb034aed41db84af1cfcdbf3925e69b2b11df89d4546fac6cf0bf", size = 6799 }, + { url = "https://files.pythonhosted.org/packages/75/06/a5865c0e4db4e7289bf6b40242b7149af87d5779f34ca168df5cabf2d5a4/pyobjc_framework_MLCompute-11.0-py2.py3-none-any.whl", hash = "sha256:16ec2942af9915f931df76b42e7f42348109b599faef955f5bea540735f87677", size = 6729, upload-time = "2025-01-14T18:54:55.927Z" }, + { url = "https://files.pythonhosted.org/packages/b5/15/3c69df5b5b99cea4a573e1d0e3c0b607cfe4ea1404ea1fe3a302361eb452/pyobjc_framework_MLCompute-11.0-py3-none-any.whl", hash = "sha256:bcdf94fe060fb034aed41db84af1cfcdbf3925e69b2b11df89d4546fac6cf0bf", size = 6799, upload-time = "2025-01-14T18:54:56.893Z" }, ] [[package]] @@ -3464,14 +3493,14 @@ name = "pyobjc-framework-modelio" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ca/7c/b75b84d41e7854ffe9c9a42846f8105227a5fd0b02b690b4a75018b2caa3/pyobjc_framework_modelio-11.0.tar.gz", hash = "sha256:c875eb6ff7f94d18362a00faaa3016ae0c28140326338d18aa03c0b62f1c6b9d", size = 122652 } +sdist = { url = "https://files.pythonhosted.org/packages/ca/7c/b75b84d41e7854ffe9c9a42846f8105227a5fd0b02b690b4a75018b2caa3/pyobjc_framework_modelio-11.0.tar.gz", hash = "sha256:c875eb6ff7f94d18362a00faaa3016ae0c28140326338d18aa03c0b62f1c6b9d", size = 122652, upload-time = "2025-01-14T19:04:44.263Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/11/98/a30e8df5624c7929dfcd9748bf859929e8aa2c7d836efe5888dafc05f729/pyobjc_framework_ModelIO-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c126318b878ffb31c39b0c7c91ca20a3b46c14c18f000e3bfb854e4541fe0147", size = 20715 }, - { url = "https://files.pythonhosted.org/packages/a9/f8/bb4bc635eb16331c20731cae2e495645d0d10e25962451631eb9085a3f85/pyobjc_framework_ModelIO-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a7357f07b77f3ab0a8107d827acdbc3e1fd458ce396335c057930b6a3f225a93", size = 20715 }, + { url = "https://files.pythonhosted.org/packages/11/98/a30e8df5624c7929dfcd9748bf859929e8aa2c7d836efe5888dafc05f729/pyobjc_framework_ModelIO-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c126318b878ffb31c39b0c7c91ca20a3b46c14c18f000e3bfb854e4541fe0147", size = 20715, upload-time = "2025-01-14T18:56:22.163Z" }, + { url = "https://files.pythonhosted.org/packages/a9/f8/bb4bc635eb16331c20731cae2e495645d0d10e25962451631eb9085a3f85/pyobjc_framework_ModelIO-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a7357f07b77f3ab0a8107d827acdbc3e1fd458ce396335c057930b6a3f225a93", size = 20715, upload-time = "2025-01-14T18:56:23.297Z" }, ] [[package]] @@ -3479,13 +3508,13 @@ name = "pyobjc-framework-multipeerconnectivity" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/14/80/4137cb9751aa3846c4954b3e61f948aae17afeb6851e01194aa50683caef/pyobjc_framework_multipeerconnectivity-11.0.tar.gz", hash = "sha256:8278a3483c0b6b88a8888ca76c46fd85808f9df56d45708cbc4e4182a5565cd3", size = 25534 } +sdist = { url = "https://files.pythonhosted.org/packages/14/80/4137cb9751aa3846c4954b3e61f948aae17afeb6851e01194aa50683caef/pyobjc_framework_multipeerconnectivity-11.0.tar.gz", hash = "sha256:8278a3483c0b6b88a8888ca76c46fd85808f9df56d45708cbc4e4182a5565cd3", size = 25534, upload-time = "2025-01-14T19:04:45.211Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2d/d2/a4144f966cbe998f8da46b936783561bcd3e7e84b8f2dc45eb49ee3f6f21/pyobjc_framework_MultipeerConnectivity-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e338b22f5b0fcb398e316552398c252bedfc3375c058340861eb205e3cdf994e", size = 12423 }, - { url = "https://files.pythonhosted.org/packages/7b/50/ac9213aca34d30993a36525c23d19ba5a568d3ea4e31e3bc2a6940ddafde/pyobjc_framework_MultipeerConnectivity-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:66bef15f5e5afd6b966cdadf2162082b0171f4a45af6d2cb2644f38431011911", size = 12447 }, + { url = "https://files.pythonhosted.org/packages/2d/d2/a4144f966cbe998f8da46b936783561bcd3e7e84b8f2dc45eb49ee3f6f21/pyobjc_framework_MultipeerConnectivity-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e338b22f5b0fcb398e316552398c252bedfc3375c058340861eb205e3cdf994e", size = 12423, upload-time = "2025-01-14T18:56:30.132Z" }, + { url = "https://files.pythonhosted.org/packages/7b/50/ac9213aca34d30993a36525c23d19ba5a568d3ea4e31e3bc2a6940ddafde/pyobjc_framework_MultipeerConnectivity-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:66bef15f5e5afd6b966cdadf2162082b0171f4a45af6d2cb2644f38431011911", size = 12447, upload-time = "2025-01-14T18:56:31.04Z" }, ] [[package]] @@ -3493,13 +3522,13 @@ name = "pyobjc-framework-naturallanguage" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/62/64/63e97635fa637384bc8c980796573dc7a9e7074a6866aef073b1faf3e11d/pyobjc_framework_naturallanguage-11.0.tar.gz", hash = "sha256:4c9471fa2c48a8fd4899de4406823e66cb0292dbba7b471622017f3647d53fa4", size = 46385 } +sdist = { url = "https://files.pythonhosted.org/packages/62/64/63e97635fa637384bc8c980796573dc7a9e7074a6866aef073b1faf3e11d/pyobjc_framework_naturallanguage-11.0.tar.gz", hash = "sha256:4c9471fa2c48a8fd4899de4406823e66cb0292dbba7b471622017f3647d53fa4", size = 46385, upload-time = "2025-01-14T19:04:46.185Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7d/72/2246c0a6dc2d087951a626157f52c81cf88fe28393994163e9572fd1eb61/pyobjc_framework_NaturalLanguage-11.0-py2.py3-none-any.whl", hash = "sha256:0744a2871690dcc9ec9e7169023b492abdde63ef97abde46013c01477b4d047c", size = 5250 }, - { url = "https://files.pythonhosted.org/packages/3a/49/f5faf3fab0f1ffb21882115878f1e5023257239aa576d6c01c31e42dd1da/pyobjc_framework_NaturalLanguage-11.0-py3-none-any.whl", hash = "sha256:7c021b270fda5469b56b9804e860cf5a80a485b817fc5fd3bb002383b2982d94", size = 5321 }, + { url = "https://files.pythonhosted.org/packages/7d/72/2246c0a6dc2d087951a626157f52c81cf88fe28393994163e9572fd1eb61/pyobjc_framework_NaturalLanguage-11.0-py2.py3-none-any.whl", hash = "sha256:0744a2871690dcc9ec9e7169023b492abdde63ef97abde46013c01477b4d047c", size = 5250, upload-time = "2025-01-14T18:56:34.675Z" }, + { url = "https://files.pythonhosted.org/packages/3a/49/f5faf3fab0f1ffb21882115878f1e5023257239aa576d6c01c31e42dd1da/pyobjc_framework_NaturalLanguage-11.0-py3-none-any.whl", hash = "sha256:7c021b270fda5469b56b9804e860cf5a80a485b817fc5fd3bb002383b2982d94", size = 5321, upload-time = "2025-01-14T18:56:36.377Z" }, ] [[package]] @@ -3507,13 +3536,13 @@ name = "pyobjc-framework-netfs" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c7/29/eb569870b52c7581104ed2806cae2d425d60b5ab304128cd58155d5b567f/pyobjc_framework_netfs-11.0.tar.gz", hash = "sha256:3de5f627a62addf4aab8a4d2d07213e9b2b6c8adbe6cc4c332ee868075785a6a", size = 16173 } +sdist = { url = "https://files.pythonhosted.org/packages/c7/29/eb569870b52c7581104ed2806cae2d425d60b5ab304128cd58155d5b567f/pyobjc_framework_netfs-11.0.tar.gz", hash = "sha256:3de5f627a62addf4aab8a4d2d07213e9b2b6c8adbe6cc4c332ee868075785a6a", size = 16173, upload-time = "2025-01-14T19:04:47.11Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/00/e7/4be35bc2adbebffb5ac7ede2b8459432194a82bd8f325af12b77b7c26248/pyobjc_framework_NetFS-11.0-py2.py3-none-any.whl", hash = "sha256:11e06da73a1d590b8462f3a1412604758d49b5e04d134b6e991282453b76abb8", size = 4088 }, - { url = "https://files.pythonhosted.org/packages/fe/83/b7c8dfaee82c0312af25c2b31621505ce19f01fab7bb55eec69c0b4d24ad/pyobjc_framework_NetFS-11.0-py3-none-any.whl", hash = "sha256:9b69a36e3a6782ce37cd3140c584dd7d5c96f7355662d004a2927583b112b4dd", size = 4162 }, + { url = "https://files.pythonhosted.org/packages/00/e7/4be35bc2adbebffb5ac7ede2b8459432194a82bd8f325af12b77b7c26248/pyobjc_framework_NetFS-11.0-py2.py3-none-any.whl", hash = "sha256:11e06da73a1d590b8462f3a1412604758d49b5e04d134b6e991282453b76abb8", size = 4088, upload-time = "2025-01-14T18:56:37.646Z" }, + { url = "https://files.pythonhosted.org/packages/fe/83/b7c8dfaee82c0312af25c2b31621505ce19f01fab7bb55eec69c0b4d24ad/pyobjc_framework_NetFS-11.0-py3-none-any.whl", hash = "sha256:9b69a36e3a6782ce37cd3140c584dd7d5c96f7355662d004a2927583b112b4dd", size = 4162, upload-time = "2025-01-14T18:56:38.682Z" }, ] [[package]] @@ -3521,13 +3550,13 @@ name = "pyobjc-framework-network" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/78/8e/18e55aff83549e041484d2ee94dd91b29cec9de40508e7fe9c4afec110a7/pyobjc_framework_network-11.0.tar.gz", hash = "sha256:d4dcc02773d7d642a385c7f0d951aeb7361277446c912a49230cddab60a65ab8", size = 124160 } +sdist = { url = "https://files.pythonhosted.org/packages/78/8e/18e55aff83549e041484d2ee94dd91b29cec9de40508e7fe9c4afec110a7/pyobjc_framework_network-11.0.tar.gz", hash = "sha256:d4dcc02773d7d642a385c7f0d951aeb7361277446c912a49230cddab60a65ab8", size = 124160, upload-time = "2025-01-14T19:04:50.191Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/24/b5/16800524e6d8d99467f53dbafa661abb1405d08d50def7edb933504197a3/pyobjc_framework_Network-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6fc797537690a241b555475923bcee28824efacd501e235457daeb4496b4b700", size = 19507 }, - { url = "https://files.pythonhosted.org/packages/36/7c/a5966976564e8e71c0e66bf68e9282c279ad0c3ce81be61fa20ca8e0ca2e/pyobjc_framework_Network-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0b9bb4a0cbd01cc4acb120ce313662763bca0c5ef11c01a0a0cae64c80b120c5", size = 19532 }, + { url = "https://files.pythonhosted.org/packages/24/b5/16800524e6d8d99467f53dbafa661abb1405d08d50def7edb933504197a3/pyobjc_framework_Network-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6fc797537690a241b555475923bcee28824efacd501e235457daeb4496b4b700", size = 19507, upload-time = "2025-01-14T18:56:41.544Z" }, + { url = "https://files.pythonhosted.org/packages/36/7c/a5966976564e8e71c0e66bf68e9282c279ad0c3ce81be61fa20ca8e0ca2e/pyobjc_framework_Network-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0b9bb4a0cbd01cc4acb120ce313662763bca0c5ef11c01a0a0cae64c80b120c5", size = 19532, upload-time = "2025-01-14T18:56:42.499Z" }, ] [[package]] @@ -3535,13 +3564,13 @@ name = "pyobjc-framework-networkextension" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/59/90/97dcfac5895b07e891adf634c3a074b68992d132ccfab386c186ac1a598c/pyobjc_framework_networkextension-11.0.tar.gz", hash = "sha256:5ba2254e2c13010b6c4f1e2948047d95eff86bfddfc77716747718fa3a8cb1af", size = 188551 } +sdist = { url = "https://files.pythonhosted.org/packages/59/90/97dcfac5895b07e891adf634c3a074b68992d132ccfab386c186ac1a598c/pyobjc_framework_networkextension-11.0.tar.gz", hash = "sha256:5ba2254e2c13010b6c4f1e2948047d95eff86bfddfc77716747718fa3a8cb1af", size = 188551, upload-time = "2025-01-14T19:04:51.352Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f2/a4/120aba6e1ccf473d7294c200687f500b096947fec58d94dc772b1a444ecc/pyobjc_framework_NetworkExtension-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4bba4f338748c8ad2cb4320c4dd64b64772a863c6b6f991c2636b2a2f4cb839a", size = 13945 }, - { url = "https://files.pythonhosted.org/packages/d1/0f/f7039d2bae0dcd63f66aff008613860499b6014dbd272726026f6c4c768d/pyobjc_framework_NetworkExtension-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:abf63433992ff1830f42cb813d1575473f0034ca6f62827f43bb2b33cc31e095", size = 13960 }, + { url = "https://files.pythonhosted.org/packages/f2/a4/120aba6e1ccf473d7294c200687f500b096947fec58d94dc772b1a444ecc/pyobjc_framework_NetworkExtension-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4bba4f338748c8ad2cb4320c4dd64b64772a863c6b6f991c2636b2a2f4cb839a", size = 13945, upload-time = "2025-01-14T18:56:53.477Z" }, + { url = "https://files.pythonhosted.org/packages/d1/0f/f7039d2bae0dcd63f66aff008613860499b6014dbd272726026f6c4c768d/pyobjc_framework_NetworkExtension-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:abf63433992ff1830f42cb813d1575473f0034ca6f62827f43bb2b33cc31e095", size = 13960, upload-time = "2025-01-14T18:56:55.661Z" }, ] [[package]] @@ -3549,13 +3578,13 @@ name = "pyobjc-framework-notificationcenter" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d7/d0/f0a602e01173531a2b639e283a092cf1f307fd873abd2ed590b9c4122337/pyobjc_framework_notificationcenter-11.0.tar.gz", hash = "sha256:f878b318c693d63d6b8bd1c3e2ad4f8097b22872f18f40142e394d84f1ead9f6", size = 22844 } +sdist = { url = "https://files.pythonhosted.org/packages/d7/d0/f0a602e01173531a2b639e283a092cf1f307fd873abd2ed590b9c4122337/pyobjc_framework_notificationcenter-11.0.tar.gz", hash = "sha256:f878b318c693d63d6b8bd1c3e2ad4f8097b22872f18f40142e394d84f1ead9f6", size = 22844, upload-time = "2025-01-14T19:04:52.459Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/bf/f2/22f04062b772e2f47ee2d54eac3f80c5aef727ec468ef5ab9a3272dd2a73/pyobjc_framework_NotificationCenter-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:075853f3e36eb4377182589e552226b2207a575035d7e128055cfde9dcad84b7", size = 9684 }, - { url = "https://files.pythonhosted.org/packages/16/22/531c2aab1639ab13aeaf3ac324afa102515b8d5eb860cb1a566018d98058/pyobjc_framework_NotificationCenter-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:093e50badfbc78edf088f9241cddba7516a58188d401f299e361f1ec85e93fce", size = 9707 }, + { url = "https://files.pythonhosted.org/packages/bf/f2/22f04062b772e2f47ee2d54eac3f80c5aef727ec468ef5ab9a3272dd2a73/pyobjc_framework_NotificationCenter-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:075853f3e36eb4377182589e552226b2207a575035d7e128055cfde9dcad84b7", size = 9684, upload-time = "2025-01-14T18:57:02.779Z" }, + { url = "https://files.pythonhosted.org/packages/16/22/531c2aab1639ab13aeaf3ac324afa102515b8d5eb860cb1a566018d98058/pyobjc_framework_NotificationCenter-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:093e50badfbc78edf088f9241cddba7516a58188d401f299e361f1ec85e93fce", size = 9707, upload-time = "2025-01-14T18:57:03.659Z" }, ] [[package]] @@ -3563,13 +3592,13 @@ name = "pyobjc-framework-opendirectory" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/55/cf/ba0cf807758acdc6a19e4787fdcda2eb59034aa22c4203d04fd49b276981/pyobjc_framework_opendirectory-11.0.tar.gz", hash = "sha256:0c82594f4f0bcf2318c4641527f9243962d7b03e67d4f3fb111b899a299fc7eb", size = 189165 } +sdist = { url = "https://files.pythonhosted.org/packages/55/cf/ba0cf807758acdc6a19e4787fdcda2eb59034aa22c4203d04fd49b276981/pyobjc_framework_opendirectory-11.0.tar.gz", hash = "sha256:0c82594f4f0bcf2318c4641527f9243962d7b03e67d4f3fb111b899a299fc7eb", size = 189165, upload-time = "2025-01-14T19:04:53.42Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b4/0a/e5a03c46a5873db83fb89ea829e4a0c02fb3f56f3639a6053e72854f435b/pyobjc_framework_OpenDirectory-11.0-py2.py3-none-any.whl", hash = "sha256:8a0feeda5a7f34b25b72c71cd1e4dd57b636cc4103248ff91bcb8571d4915eb4", size = 11747 }, - { url = "https://files.pythonhosted.org/packages/da/fd/be3815a19978ab2a3abe9563a031195b40647077fcebbee86232af260176/pyobjc_framework_OpenDirectory-11.0-py3-none-any.whl", hash = "sha256:bfac495de433a62e3934619e2f5d2254177f960b7d4e905ed4ef359127e23b24", size = 11816 }, + { url = "https://files.pythonhosted.org/packages/b4/0a/e5a03c46a5873db83fb89ea829e4a0c02fb3f56f3639a6053e72854f435b/pyobjc_framework_OpenDirectory-11.0-py2.py3-none-any.whl", hash = "sha256:8a0feeda5a7f34b25b72c71cd1e4dd57b636cc4103248ff91bcb8571d4915eb4", size = 11747, upload-time = "2025-01-14T18:57:17.445Z" }, + { url = "https://files.pythonhosted.org/packages/da/fd/be3815a19978ab2a3abe9563a031195b40647077fcebbee86232af260176/pyobjc_framework_OpenDirectory-11.0-py3-none-any.whl", hash = "sha256:bfac495de433a62e3934619e2f5d2254177f960b7d4e905ed4ef359127e23b24", size = 11816, upload-time = "2025-01-14T18:57:18.486Z" }, ] [[package]] @@ -3577,13 +3606,13 @@ name = "pyobjc-framework-osakit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d3/4a/e49680f7f3ab9c0632ed9be76a0a59299e7fd797335690b3da4d117f2d7b/pyobjc_framework_osakit-11.0.tar.gz", hash = "sha256:77ac18e2660133a9eeb01c76ad3df3b4b36fd29005fc36bca00f57cca121aac3", size = 22535 } +sdist = { url = "https://files.pythonhosted.org/packages/d3/4a/e49680f7f3ab9c0632ed9be76a0a59299e7fd797335690b3da4d117f2d7b/pyobjc_framework_osakit-11.0.tar.gz", hash = "sha256:77ac18e2660133a9eeb01c76ad3df3b4b36fd29005fc36bca00f57cca121aac3", size = 22535, upload-time = "2025-01-14T19:04:54.753Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/56/f6/1dcff2f76280946368ee75ab39c92e261a851656c5979a50513563d08cf0/pyobjc_framework_OSAKit-11.0-py2.py3-none-any.whl", hash = "sha256:3183414e345af83a2187b00356130909a7c2a41b2227dc579b662737300c3ba4", size = 4094 }, - { url = "https://files.pythonhosted.org/packages/17/75/745985429f0ff4776ffb8ba261199e11f4d6977b1814ad2b39084f83bad5/pyobjc_framework_OSAKit-11.0-py3-none-any.whl", hash = "sha256:79150c47d2aeffc72fb6551060518ce472275edbad3b56aef5923a6086371c28", size = 4162 }, + { url = "https://files.pythonhosted.org/packages/56/f6/1dcff2f76280946368ee75ab39c92e261a851656c5979a50513563d08cf0/pyobjc_framework_OSAKit-11.0-py2.py3-none-any.whl", hash = "sha256:3183414e345af83a2187b00356130909a7c2a41b2227dc579b662737300c3ba4", size = 4094, upload-time = "2025-01-14T18:57:08.639Z" }, + { url = "https://files.pythonhosted.org/packages/17/75/745985429f0ff4776ffb8ba261199e11f4d6977b1814ad2b39084f83bad5/pyobjc_framework_OSAKit-11.0-py3-none-any.whl", hash = "sha256:79150c47d2aeffc72fb6551060518ce472275edbad3b56aef5923a6086371c28", size = 4162, upload-time = "2025-01-14T18:57:09.71Z" }, ] [[package]] @@ -3591,15 +3620,15 @@ name = "pyobjc-framework-oslog" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b0/93/0a72353d0212a815bd5e43aec528ce7b28b71d461d26e5fa3882ff96ffa3/pyobjc_framework_oslog-11.0.tar.gz", hash = "sha256:9d29eb7c89a41d7c702dffb6e2e338a2d5219387c8dae22b67754ddf9e2fcb3f", size = 24151 } +sdist = { url = "https://files.pythonhosted.org/packages/b0/93/0a72353d0212a815bd5e43aec528ce7b28b71d461d26e5fa3882ff96ffa3/pyobjc_framework_oslog-11.0.tar.gz", hash = "sha256:9d29eb7c89a41d7c702dffb6e2e338a2d5219387c8dae22b67754ddf9e2fcb3f", size = 24151, upload-time = "2025-01-14T19:04:55.587Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9c/54/6b507a18d0adadf8b707be9616bc9bab157963b81fa3c9928a0148d3bfd8/pyobjc_framework_OSLog-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c0131851fca9b741f290ffa727dd30328dd8526b87c8cef623b79239bed99187", size = 7694 }, - { url = "https://files.pythonhosted.org/packages/d1/79/81e64a55023f458aa5d99d10671fd9bcc6c0dcf8339768152fbc28c92cef/pyobjc_framework_OSLog-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:17d8b49113a476372b24ac8e544d88f6d12f878f1081dd611ab203c4484f2039", size = 7720 }, + { url = "https://files.pythonhosted.org/packages/9c/54/6b507a18d0adadf8b707be9616bc9bab157963b81fa3c9928a0148d3bfd8/pyobjc_framework_OSLog-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c0131851fca9b741f290ffa727dd30328dd8526b87c8cef623b79239bed99187", size = 7694, upload-time = "2025-01-14T18:57:12.713Z" }, + { url = "https://files.pythonhosted.org/packages/d1/79/81e64a55023f458aa5d99d10671fd9bcc6c0dcf8339768152fbc28c92cef/pyobjc_framework_OSLog-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:17d8b49113a476372b24ac8e544d88f6d12f878f1081dd611ab203c4484f2039", size = 7720, upload-time = "2025-01-14T18:57:13.695Z" }, ] [[package]] @@ -3607,13 +3636,13 @@ name = "pyobjc-framework-passkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/cb/f8/ebb2bc840f87292a4f60080463ee698ca08516cc958364741dfff2858b33/pyobjc_framework_passkit-11.0.tar.gz", hash = "sha256:2044d9d634dd98b7b624ee09487b27e5f26a7729f6689abba23a4a011febe19c", size = 120495 } +sdist = { url = "https://files.pythonhosted.org/packages/cb/f8/ebb2bc840f87292a4f60080463ee698ca08516cc958364741dfff2858b33/pyobjc_framework_passkit-11.0.tar.gz", hash = "sha256:2044d9d634dd98b7b624ee09487b27e5f26a7729f6689abba23a4a011febe19c", size = 120495, upload-time = "2025-01-14T19:04:57.689Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/53/72/d7dae8f5a1c5b12d9cf404a71a82fd5a638bc4de2d1099bf838aee1026f0/pyobjc_framework_PassKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:710372134c3adedb9017bfc2fbc592ef0e94ae916145b58e57234239bf903b90", size = 14354 }, - { url = "https://files.pythonhosted.org/packages/c3/b1/5ee2f5581877241a4fc2db4ab4a33d595a918bde1b4a59796240e2b2244b/pyobjc_framework_PassKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fe0144177f7feb96577bea53841d9b9b3f63185735a1bf1b36368ab189fd6282", size = 14391 }, + { url = "https://files.pythonhosted.org/packages/53/72/d7dae8f5a1c5b12d9cf404a71a82fd5a638bc4de2d1099bf838aee1026f0/pyobjc_framework_PassKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:710372134c3adedb9017bfc2fbc592ef0e94ae916145b58e57234239bf903b90", size = 14354, upload-time = "2025-01-14T18:57:24.436Z" }, + { url = "https://files.pythonhosted.org/packages/c3/b1/5ee2f5581877241a4fc2db4ab4a33d595a918bde1b4a59796240e2b2244b/pyobjc_framework_PassKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fe0144177f7feb96577bea53841d9b9b3f63185735a1bf1b36368ab189fd6282", size = 14391, upload-time = "2025-01-14T18:57:26.67Z" }, ] [[package]] @@ -3621,13 +3650,13 @@ name = "pyobjc-framework-pencilkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f4/8d/1e97cd72b776e5e1294cbda84325b364702617dd435d32448dcc0a80bd93/pyobjc_framework_pencilkit-11.0.tar.gz", hash = "sha256:9598c28e83f5b7f091592cc1af2b16f7ae94cf00045d8d14ed2c17cb9e4ffd50", size = 22812 } +sdist = { url = "https://files.pythonhosted.org/packages/f4/8d/1e97cd72b776e5e1294cbda84325b364702617dd435d32448dcc0a80bd93/pyobjc_framework_pencilkit-11.0.tar.gz", hash = "sha256:9598c28e83f5b7f091592cc1af2b16f7ae94cf00045d8d14ed2c17cb9e4ffd50", size = 22812, upload-time = "2025-01-14T19:04:58.652Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/af/5b/24fb83a97648eaa0d231df7908532dff7b36d5f516d55c92ed9ae07c4e1b/pyobjc_framework_PencilKit-11.0-py2.py3-none-any.whl", hash = "sha256:22cbb6ed2504be4c8d631c4711b00fae48ef731c10c69861b4de1e4fcdc19279", size = 3970 }, - { url = "https://files.pythonhosted.org/packages/08/fd/89a005c86b06137837952838d976ce6e39b31082392d78c382d44e03944d/pyobjc_framework_PencilKit-11.0-py3-none-any.whl", hash = "sha256:a4e606c5b69e6adb80ef30fc95fe0095971735d12ab6fc4fe4d982e4c8a3881a", size = 4045 }, + { url = "https://files.pythonhosted.org/packages/af/5b/24fb83a97648eaa0d231df7908532dff7b36d5f516d55c92ed9ae07c4e1b/pyobjc_framework_PencilKit-11.0-py2.py3-none-any.whl", hash = "sha256:22cbb6ed2504be4c8d631c4711b00fae48ef731c10c69861b4de1e4fcdc19279", size = 3970, upload-time = "2025-01-14T18:57:30.597Z" }, + { url = "https://files.pythonhosted.org/packages/08/fd/89a005c86b06137837952838d976ce6e39b31082392d78c382d44e03944d/pyobjc_framework_PencilKit-11.0-py3-none-any.whl", hash = "sha256:a4e606c5b69e6adb80ef30fc95fe0095971735d12ab6fc4fe4d982e4c8a3881a", size = 4045, upload-time = "2025-01-14T18:57:31.87Z" }, ] [[package]] @@ -3635,13 +3664,13 @@ name = "pyobjc-framework-phase" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d2/a2/65182dcb44fceb2173f4134d6cd4325dfd0731225b621aa2027d2a03d043/pyobjc_framework_phase-11.0.tar.gz", hash = "sha256:e06a0f8308ae4f3731f88b3e1239b7bdfdda3eef97023e3ce972e2f386451d80", size = 59214 } +sdist = { url = "https://files.pythonhosted.org/packages/d2/a2/65182dcb44fceb2173f4134d6cd4325dfd0731225b621aa2027d2a03d043/pyobjc_framework_phase-11.0.tar.gz", hash = "sha256:e06a0f8308ae4f3731f88b3e1239b7bdfdda3eef97023e3ce972e2f386451d80", size = 59214, upload-time = "2025-01-14T19:04:59.461Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a9/97/efb9d770ba05d285384b0c121e9e911929893356da1944a0bb03ea0df0f2/pyobjc_framework_PHASE-11.0-py2.py3-none-any.whl", hash = "sha256:d3e41c2b2fdf4b2ce39f558a08762c6864449ff87b618e42747777ad3f821323", size = 6777 }, - { url = "https://files.pythonhosted.org/packages/38/85/03420927e4243d0ef8e3e8aa1ca511b5638743d7ec319a570a472a50d60f/pyobjc_framework_PHASE-11.0-py3-none-any.whl", hash = "sha256:78c0600477ea294304b51f8284a2fb299be284c33ae2c135e1c7cd26fdf4def4", size = 6846 }, + { url = "https://files.pythonhosted.org/packages/a9/97/efb9d770ba05d285384b0c121e9e911929893356da1944a0bb03ea0df0f2/pyobjc_framework_PHASE-11.0-py2.py3-none-any.whl", hash = "sha256:d3e41c2b2fdf4b2ce39f558a08762c6864449ff87b618e42747777ad3f821323", size = 6777, upload-time = "2025-01-14T18:57:20.135Z" }, + { url = "https://files.pythonhosted.org/packages/38/85/03420927e4243d0ef8e3e8aa1ca511b5638743d7ec319a570a472a50d60f/pyobjc_framework_PHASE-11.0-py3-none-any.whl", hash = "sha256:78c0600477ea294304b51f8284a2fb299be284c33ae2c135e1c7cd26fdf4def4", size = 6846, upload-time = "2025-01-14T18:57:21.193Z" }, ] [[package]] @@ -3649,13 +3678,13 @@ name = "pyobjc-framework-photos" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f7/c3/fc755c1f8f411433d7ba2e92f3fe3e7b417e9629675ad6baf94ac8b01e64/pyobjc_framework_photos-11.0.tar.gz", hash = "sha256:cfdfdefb0d560b091425227d5c0e24a40b445b5251ff4d37bd326cd8626b80cd", size = 92122 } +sdist = { url = "https://files.pythonhosted.org/packages/f7/c3/fc755c1f8f411433d7ba2e92f3fe3e7b417e9629675ad6baf94ac8b01e64/pyobjc_framework_photos-11.0.tar.gz", hash = "sha256:cfdfdefb0d560b091425227d5c0e24a40b445b5251ff4d37bd326cd8626b80cd", size = 92122, upload-time = "2025-01-14T19:05:01.804Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/80/27/62e5833b9629121b4b6ea8f2b2aa295cf6b719dc6316387f77ec0bd41d77/pyobjc_framework_Photos-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:71bf849888713e4a00eb44074c5000ed081c905ba35b3a55ee84c6367ce60ce8", size = 12085 }, - { url = "https://files.pythonhosted.org/packages/b9/6e/54108271ea34b0fc51bf8d0bf677788e4d39a1e29ad481f8c78c100f3159/pyobjc_framework_Photos-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ea630c3abf4620b022f23167ef5f3d6b157b38697d7ffc5df0fc507e95bed655", size = 12107 }, + { url = "https://files.pythonhosted.org/packages/80/27/62e5833b9629121b4b6ea8f2b2aa295cf6b719dc6316387f77ec0bd41d77/pyobjc_framework_Photos-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:71bf849888713e4a00eb44074c5000ed081c905ba35b3a55ee84c6367ce60ce8", size = 12085, upload-time = "2025-01-14T18:57:34.615Z" }, + { url = "https://files.pythonhosted.org/packages/b9/6e/54108271ea34b0fc51bf8d0bf677788e4d39a1e29ad481f8c78c100f3159/pyobjc_framework_Photos-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ea630c3abf4620b022f23167ef5f3d6b157b38697d7ffc5df0fc507e95bed655", size = 12107, upload-time = "2025-01-14T18:57:35.66Z" }, ] [[package]] @@ -3663,13 +3692,13 @@ name = "pyobjc-framework-photosui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e4/2c/70ac99fb2b7ba14d220c78cf6401c0c7a47992269f85f699220a6a2cff09/pyobjc_framework_photosui-11.0.tar.gz", hash = "sha256:3c65342e31f6109d8229992b2712b29cab1021475969b55f4f215dd97e2a99db", size = 47898 } +sdist = { url = "https://files.pythonhosted.org/packages/e4/2c/70ac99fb2b7ba14d220c78cf6401c0c7a47992269f85f699220a6a2cff09/pyobjc_framework_photosui-11.0.tar.gz", hash = "sha256:3c65342e31f6109d8229992b2712b29cab1021475969b55f4f215dd97e2a99db", size = 47898, upload-time = "2025-01-14T19:05:02.737Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/94/ec/9574692e2852d546b28bac853b2b0584c4d4f093a4befac0e105789ee9f6/pyobjc_framework_PhotosUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5b3865d2cc4fad4d34255941fe93ce504b9d2c7a7043bd0f4c715da9f4af1cf1", size = 12165 }, - { url = "https://files.pythonhosted.org/packages/90/a9/85d70fe9eee0d15a0615a3f7b2ef92120c32614e350286d347d733fcf1d0/pyobjc_framework_PhotosUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:66826184121cd15415750d801160721adad80b53cbb315192522229b17252ebb", size = 12176 }, + { url = "https://files.pythonhosted.org/packages/94/ec/9574692e2852d546b28bac853b2b0584c4d4f093a4befac0e105789ee9f6/pyobjc_framework_PhotosUI-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5b3865d2cc4fad4d34255941fe93ce504b9d2c7a7043bd0f4c715da9f4af1cf1", size = 12165, upload-time = "2025-01-14T18:57:44.048Z" }, + { url = "https://files.pythonhosted.org/packages/90/a9/85d70fe9eee0d15a0615a3f7b2ef92120c32614e350286d347d733fcf1d0/pyobjc_framework_PhotosUI-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:66826184121cd15415750d801160721adad80b53cbb315192522229b17252ebb", size = 12176, upload-time = "2025-01-14T18:57:44.993Z" }, ] [[package]] @@ -3677,13 +3706,13 @@ name = "pyobjc-framework-preferencepanes" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/35/01/81cc46e0a92d15f2b664b2efdcc8fd310acac570c9f63a99d446e0489784/pyobjc_framework_preferencepanes-11.0.tar.gz", hash = "sha256:ee000c351befeb81f4fa678ada85695ca4af07933b6bd9b1947164e16dd0b3e5", size = 26419 } +sdist = { url = "https://files.pythonhosted.org/packages/35/01/81cc46e0a92d15f2b664b2efdcc8fd310acac570c9f63a99d446e0489784/pyobjc_framework_preferencepanes-11.0.tar.gz", hash = "sha256:ee000c351befeb81f4fa678ada85695ca4af07933b6bd9b1947164e16dd0b3e5", size = 26419, upload-time = "2025-01-14T19:05:03.787Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/70/f7/5d0d9b94563ef06fe0a9c15ba2b77922b73bcc4b6630c487936edf382e20/pyobjc_framework_PreferencePanes-11.0-py2.py3-none-any.whl", hash = "sha256:2143851549430d6bb951adae44cb65c1986662ac7c8cbe15891ed194cbe283a2", size = 4706 }, - { url = "https://files.pythonhosted.org/packages/9b/0e/76d694eea953b39318249ae24c956c3e115d8222343fb01f0186f7ca0043/pyobjc_framework_PreferencePanes-11.0-py3-none-any.whl", hash = "sha256:9f1287716374338fa99445ca13dfcc6c9be5597c8a5ce06680a8ca245b4e0acc", size = 4772 }, + { url = "https://files.pythonhosted.org/packages/70/f7/5d0d9b94563ef06fe0a9c15ba2b77922b73bcc4b6630c487936edf382e20/pyobjc_framework_PreferencePanes-11.0-py2.py3-none-any.whl", hash = "sha256:2143851549430d6bb951adae44cb65c1986662ac7c8cbe15891ed194cbe283a2", size = 4706, upload-time = "2025-01-14T18:57:51.425Z" }, + { url = "https://files.pythonhosted.org/packages/9b/0e/76d694eea953b39318249ae24c956c3e115d8222343fb01f0186f7ca0043/pyobjc_framework_PreferencePanes-11.0-py3-none-any.whl", hash = "sha256:9f1287716374338fa99445ca13dfcc6c9be5597c8a5ce06680a8ca245b4e0acc", size = 4772, upload-time = "2025-01-14T18:57:52.684Z" }, ] [[package]] @@ -3691,13 +3720,13 @@ name = "pyobjc-framework-pushkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/17/ab/7fe55ce5b32c434142be026ec27b1801a2d4694b159b502f9ecd568eebf2/pyobjc_framework_pushkit-11.0.tar.gz", hash = "sha256:df9854ed4065c50022863b3c11c2a21c4279b36c2b5c8f08b834174aacb44e81", size = 20816 } +sdist = { url = "https://files.pythonhosted.org/packages/17/ab/7fe55ce5b32c434142be026ec27b1801a2d4694b159b502f9ecd568eebf2/pyobjc_framework_pushkit-11.0.tar.gz", hash = "sha256:df9854ed4065c50022863b3c11c2a21c4279b36c2b5c8f08b834174aacb44e81", size = 20816, upload-time = "2025-01-14T19:05:05.468Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/17/5f/de178da22fa628cd88f599fea2a70b7d1d9ebc65576307df0bf29822a347/pyobjc_framework_PushKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:0185cebcc5aad73aae50804c7a2412da6275717b8f872b830d71c484efcdea7a", size = 8010 }, - { url = "https://files.pythonhosted.org/packages/5f/a5/60f93031302aba7cdff28728b8141b58c3bd5c12f4a6cef5796a8cc2e666/pyobjc_framework_PushKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:43bd1ed31664982e4d8397a7e07e58a7deb85bf9c9866ea966fd7ca25796014c", size = 8032 }, + { url = "https://files.pythonhosted.org/packages/17/5f/de178da22fa628cd88f599fea2a70b7d1d9ebc65576307df0bf29822a347/pyobjc_framework_PushKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:0185cebcc5aad73aae50804c7a2412da6275717b8f872b830d71c484efcdea7a", size = 8010, upload-time = "2025-01-14T18:57:59.042Z" }, + { url = "https://files.pythonhosted.org/packages/5f/a5/60f93031302aba7cdff28728b8141b58c3bd5c12f4a6cef5796a8cc2e666/pyobjc_framework_PushKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:43bd1ed31664982e4d8397a7e07e58a7deb85bf9c9866ea966fd7ca25796014c", size = 8032, upload-time = "2025-01-14T18:57:59.973Z" }, ] [[package]] @@ -3705,13 +3734,13 @@ name = "pyobjc-framework-quartz" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a5/ad/f00f3f53387c23bbf4e0bb1410e11978cbf87c82fa6baff0ee86f74c5fb6/pyobjc_framework_quartz-11.0.tar.gz", hash = "sha256:3205bf7795fb9ae34747f701486b3db6dfac71924894d1f372977c4d70c3c619", size = 3952463 } +sdist = { url = "https://files.pythonhosted.org/packages/a5/ad/f00f3f53387c23bbf4e0bb1410e11978cbf87c82fa6baff0ee86f74c5fb6/pyobjc_framework_quartz-11.0.tar.gz", hash = "sha256:3205bf7795fb9ae34747f701486b3db6dfac71924894d1f372977c4d70c3c619", size = 3952463, upload-time = "2025-01-14T19:05:07.931Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a3/6a/68957c8c5e8f0128d4d419728bac397d48fa7ad7a66e82b70e64d129ffca/pyobjc_framework_Quartz-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d251696bfd8e8ef72fbc90eb29fec95cb9d1cc409008a183d5cc3246130ae8c2", size = 212349 }, - { url = "https://files.pythonhosted.org/packages/60/5d/df827b78dcb5140652ad08af8038c9ddd7e01e6bdf84462bfee644e6e661/pyobjc_framework_Quartz-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:cb4a9f2d9d580ea15e25e6b270f47681afb5689cafc9e25712445ce715bcd18e", size = 212061 }, + { url = "https://files.pythonhosted.org/packages/a3/6a/68957c8c5e8f0128d4d419728bac397d48fa7ad7a66e82b70e64d129ffca/pyobjc_framework_Quartz-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d251696bfd8e8ef72fbc90eb29fec95cb9d1cc409008a183d5cc3246130ae8c2", size = 212349, upload-time = "2025-01-14T18:58:08.963Z" }, + { url = "https://files.pythonhosted.org/packages/60/5d/df827b78dcb5140652ad08af8038c9ddd7e01e6bdf84462bfee644e6e661/pyobjc_framework_Quartz-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:cb4a9f2d9d580ea15e25e6b270f47681afb5689cafc9e25712445ce715bcd18e", size = 212061, upload-time = "2025-01-14T18:58:10.2Z" }, ] [[package]] @@ -3719,14 +3748,14 @@ name = "pyobjc-framework-quicklookthumbnailing" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/50/a1/35ca40d2d4ab05acbc9766986d482482d466529003711c7b4e52a8df4935/pyobjc_framework_quicklookthumbnailing-11.0.tar.gz", hash = "sha256:40763284bd0f71e6a55803f5234ad9cd8e8dd3aaaf5e1fd204e6c952b3f3530d", size = 16784 } +sdist = { url = "https://files.pythonhosted.org/packages/50/a1/35ca40d2d4ab05acbc9766986d482482d466529003711c7b4e52a8df4935/pyobjc_framework_quicklookthumbnailing-11.0.tar.gz", hash = "sha256:40763284bd0f71e6a55803f5234ad9cd8e8dd3aaaf5e1fd204e6c952b3f3530d", size = 16784, upload-time = "2025-01-14T19:05:09.857Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9d/85/1a66fefa99e7a4eb7534b2f56f9a24d33beda450dd2ca45d180307e76c74/pyobjc_framework_QuickLookThumbnailing-11.0-py2.py3-none-any.whl", hash = "sha256:6e567a764942845ce4db7ccfc0f8a9d091216bd029ecca955e618a43d64a5d84", size = 4164 }, - { url = "https://files.pythonhosted.org/packages/05/d7/26decb13136b7c95a1ca3ecf202644ad2fd515a57e1117c71bfc86429b20/pyobjc_framework_QuickLookThumbnailing-11.0-py3-none-any.whl", hash = "sha256:e0f7f62b9a1df55e5f717518baf3260dc2cb8a9722cc5e9c6fffc643f69bda27", size = 4229 }, + { url = "https://files.pythonhosted.org/packages/9d/85/1a66fefa99e7a4eb7534b2f56f9a24d33beda450dd2ca45d180307e76c74/pyobjc_framework_QuickLookThumbnailing-11.0-py2.py3-none-any.whl", hash = "sha256:6e567a764942845ce4db7ccfc0f8a9d091216bd029ecca955e618a43d64a5d84", size = 4164, upload-time = "2025-01-14T18:58:16.381Z" }, + { url = "https://files.pythonhosted.org/packages/05/d7/26decb13136b7c95a1ca3ecf202644ad2fd515a57e1117c71bfc86429b20/pyobjc_framework_QuickLookThumbnailing-11.0-py3-none-any.whl", hash = "sha256:e0f7f62b9a1df55e5f717518baf3260dc2cb8a9722cc5e9c6fffc643f69bda27", size = 4229, upload-time = "2025-01-14T18:58:17.404Z" }, ] [[package]] @@ -3734,13 +3763,13 @@ name = "pyobjc-framework-replaykit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/aa/43/c751c517dbb8ee599a31e59832c01080473c7964b6996ca29906f46c0967/pyobjc_framework_replaykit-11.0.tar.gz", hash = "sha256:e5693589423eb9ad99d63a7395169f97b484a58108321877b0fc27c748344593", size = 25589 } +sdist = { url = "https://files.pythonhosted.org/packages/aa/43/c751c517dbb8ee599a31e59832c01080473c7964b6996ca29906f46c0967/pyobjc_framework_replaykit-11.0.tar.gz", hash = "sha256:e5693589423eb9ad99d63a7395169f97b484a58108321877b0fc27c748344593", size = 25589, upload-time = "2025-01-14T19:05:10.791Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fe/56/89a8544426a46bf176c9462511c08d4c94ae7e0403abb2d73632af68ee8e/pyobjc_framework_ReplayKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:262fb834400e8379f4c795e65137763348992f3010284602d876050b8adb9ea4", size = 9904 }, - { url = "https://files.pythonhosted.org/packages/47/af/9abfa41060efc96000cc9ae77f302bb8210f3be0f793ba5d11f98a03e468/pyobjc_framework_ReplayKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:da9db123ee52761a670c6e41e5f9d9a47a2ca5582a9c4a7c8662a8bb56a0f593", size = 9903 }, + { url = "https://files.pythonhosted.org/packages/fe/56/89a8544426a46bf176c9462511c08d4c94ae7e0403abb2d73632af68ee8e/pyobjc_framework_ReplayKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:262fb834400e8379f4c795e65137763348992f3010284602d876050b8adb9ea4", size = 9904, upload-time = "2025-01-14T18:58:19.332Z" }, + { url = "https://files.pythonhosted.org/packages/47/af/9abfa41060efc96000cc9ae77f302bb8210f3be0f793ba5d11f98a03e468/pyobjc_framework_ReplayKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:da9db123ee52761a670c6e41e5f9d9a47a2ca5582a9c4a7c8662a8bb56a0f593", size = 9903, upload-time = "2025-01-14T18:58:20.222Z" }, ] [[package]] @@ -3748,13 +3777,13 @@ name = "pyobjc-framework-safariservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/40/ec/c9a97b1aa713145cc8c522c4146af06b293cfe1a959a03ee91007949533b/pyobjc_framework_safariservices-11.0.tar.gz", hash = "sha256:dba416bd0ed5f4481bc400bf56ce57e982c19feaae94bc4eb75d8bda9af15b7e", size = 34367 } +sdist = { url = "https://files.pythonhosted.org/packages/40/ec/c9a97b1aa713145cc8c522c4146af06b293cfe1a959a03ee91007949533b/pyobjc_framework_safariservices-11.0.tar.gz", hash = "sha256:dba416bd0ed5f4481bc400bf56ce57e982c19feaae94bc4eb75d8bda9af15b7e", size = 34367, upload-time = "2025-01-14T19:05:12.914Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/40/39/d69f8e7dbf6f366cb5fdaa8aa7ceef1dadb93a5e4d9fc63217477bba5e32/pyobjc_framework_SafariServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:55c02a533073e0a2aaf6db544f087fd861bace6b62035c3bb2e6b20f0b921b2b", size = 7262 }, - { url = "https://files.pythonhosted.org/packages/36/76/a625330bdf7a5d9962299562b6e19f6cbd1ea1b14887958e42a4372d3344/pyobjc_framework_SafariServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:31ba086a39ee06d8622a504e3ea3a1f6dc8fab1d4c4c7930d5af6e989f38ec56", size = 7262 }, + { url = "https://files.pythonhosted.org/packages/40/39/d69f8e7dbf6f366cb5fdaa8aa7ceef1dadb93a5e4d9fc63217477bba5e32/pyobjc_framework_SafariServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:55c02a533073e0a2aaf6db544f087fd861bace6b62035c3bb2e6b20f0b921b2b", size = 7262, upload-time = "2025-01-14T18:58:29.754Z" }, + { url = "https://files.pythonhosted.org/packages/36/76/a625330bdf7a5d9962299562b6e19f6cbd1ea1b14887958e42a4372d3344/pyobjc_framework_SafariServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:31ba086a39ee06d8622a504e3ea3a1f6dc8fab1d4c4c7930d5af6e989f38ec56", size = 7262, upload-time = "2025-01-14T18:58:30.725Z" }, ] [[package]] @@ -3762,14 +3791,14 @@ name = "pyobjc-framework-safetykit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/4e/30/89bfdbdca93e57b19891ddeff1742b20a2019cdeb2e44902027dce2642e1/pyobjc_framework_safetykit-11.0.tar.gz", hash = "sha256:9ec996a6a8eecada4b9fd1138244bcffea96a37722531f0ec16566049dfd4cdb", size = 20745 } +sdist = { url = "https://files.pythonhosted.org/packages/4e/30/89bfdbdca93e57b19891ddeff1742b20a2019cdeb2e44902027dce2642e1/pyobjc_framework_safetykit-11.0.tar.gz", hash = "sha256:9ec996a6a8eecada4b9fd1138244bcffea96a37722531f0ec16566049dfd4cdb", size = 20745, upload-time = "2025-01-14T19:05:13.925Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/37/c5/68b79c0f128eb735397aa68a40e5ac48b88c12967f69358f25f753a3fc1c/pyobjc_framework_SafetyKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:83a1f313c9c63ba107a7c543a8300ae225fa5ff17d963b1c499859da45ceaf55", size = 8395 }, - { url = "https://files.pythonhosted.org/packages/99/02/2853a00e75cca8db8b5053ff2648ff2a26f5c02f07af1c70630a36b58d04/pyobjc_framework_SafetyKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c6dd23fcaca9c41d6aadf2ca0a6d07c4032a0c4ea8873ee06da6efd1e868f97e", size = 8418 }, + { url = "https://files.pythonhosted.org/packages/37/c5/68b79c0f128eb735397aa68a40e5ac48b88c12967f69358f25f753a3fc1c/pyobjc_framework_SafetyKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:83a1f313c9c63ba107a7c543a8300ae225fa5ff17d963b1c499859da45ceaf55", size = 8395, upload-time = "2025-01-14T18:58:35.46Z" }, + { url = "https://files.pythonhosted.org/packages/99/02/2853a00e75cca8db8b5053ff2648ff2a26f5c02f07af1c70630a36b58d04/pyobjc_framework_SafetyKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c6dd23fcaca9c41d6aadf2ca0a6d07c4032a0c4ea8873ee06da6efd1e868f97e", size = 8418, upload-time = "2025-01-14T18:58:36.369Z" }, ] [[package]] @@ -3777,14 +3806,14 @@ name = "pyobjc-framework-scenekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/26/3f/a2761585399e752bce8275c9d56990d4b83e57b13d06dd98335891176a89/pyobjc_framework_scenekit-11.0.tar.gz", hash = "sha256:c0f37019f8de2a583f66e6d14dfd4ae23c8d8703e93f61c1c91728a21f62cd26", size = 213647 } +sdist = { url = "https://files.pythonhosted.org/packages/26/3f/a2761585399e752bce8275c9d56990d4b83e57b13d06dd98335891176a89/pyobjc_framework_scenekit-11.0.tar.gz", hash = "sha256:c0f37019f8de2a583f66e6d14dfd4ae23c8d8703e93f61c1c91728a21f62cd26", size = 213647, upload-time = "2025-01-14T19:05:15.129Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/aa/4c/5ec624ae043fbbe15be2a989e3fc6cb08d992e0a5061450b84b33f96429c/pyobjc_framework_SceneKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:86d23456e4c7a7bb7bb49be2b98647678ac7a39955e6bb242e0ac125d8b770e8", size = 33108 }, - { url = "https://files.pythonhosted.org/packages/b8/7f/fef1cf3eaf1366a6f3f93c5a6b164acfdfdc2d15b3243b70763ac217ce03/pyobjc_framework_SceneKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d0a0d557167adddf27a42fb109a1dce29a22ff09aca34558fccd1c22f08ae2b4", size = 33130 }, + { url = "https://files.pythonhosted.org/packages/aa/4c/5ec624ae043fbbe15be2a989e3fc6cb08d992e0a5061450b84b33f96429c/pyobjc_framework_SceneKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:86d23456e4c7a7bb7bb49be2b98647678ac7a39955e6bb242e0ac125d8b770e8", size = 33108, upload-time = "2025-01-14T18:58:43.577Z" }, + { url = "https://files.pythonhosted.org/packages/b8/7f/fef1cf3eaf1366a6f3f93c5a6b164acfdfdc2d15b3243b70763ac217ce03/pyobjc_framework_SceneKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d0a0d557167adddf27a42fb109a1dce29a22ff09aca34558fccd1c22f08ae2b4", size = 33130, upload-time = "2025-01-14T18:58:44.549Z" }, ] [[package]] @@ -3792,14 +3821,14 @@ name = "pyobjc-framework-screencapturekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/77/90/71f10db2f52ea324f82eaccc959442c43d21778cc5b1294c29e1942e635c/pyobjc_framework_screencapturekit-11.0.tar.gz", hash = "sha256:ca2c960e28216e56f33e4ca9b9b1eda12d9c17b719bae727181e8b96f0314c4b", size = 53046 } +sdist = { url = "https://files.pythonhosted.org/packages/77/90/71f10db2f52ea324f82eaccc959442c43d21778cc5b1294c29e1942e635c/pyobjc_framework_screencapturekit-11.0.tar.gz", hash = "sha256:ca2c960e28216e56f33e4ca9b9b1eda12d9c17b719bae727181e8b96f0314c4b", size = 53046, upload-time = "2025-01-14T19:05:16.834Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/af/aa/d6d0818564570065411874cbe3de86dee105dc9906161c0584009a1a63bc/pyobjc_framework_ScreenCaptureKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:38468e833ec1498778bd33ce30578afed2e13ac14c73e8e6290ff06a2e0c50d8", size = 11110 }, - { url = "https://files.pythonhosted.org/packages/27/61/557e725aef9ad76a1a7c48b361f8c5636a606cbaf9ba520ff8f69d3cf791/pyobjc_framework_ScreenCaptureKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7d8a83dcc0950699242677cfefda545b9c0a0567111f8f3d3df1cf6ed75ea480", size = 11121 }, + { url = "https://files.pythonhosted.org/packages/af/aa/d6d0818564570065411874cbe3de86dee105dc9906161c0584009a1a63bc/pyobjc_framework_ScreenCaptureKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:38468e833ec1498778bd33ce30578afed2e13ac14c73e8e6290ff06a2e0c50d8", size = 11110, upload-time = "2025-01-14T18:58:51.475Z" }, + { url = "https://files.pythonhosted.org/packages/27/61/557e725aef9ad76a1a7c48b361f8c5636a606cbaf9ba520ff8f69d3cf791/pyobjc_framework_ScreenCaptureKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7d8a83dcc0950699242677cfefda545b9c0a0567111f8f3d3df1cf6ed75ea480", size = 11121, upload-time = "2025-01-14T18:58:53.055Z" }, ] [[package]] @@ -3807,13 +3836,13 @@ name = "pyobjc-framework-screensaver" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f6/b6/71c20259a1bfffcb5103be62564006b1bbc21f80180658101e2370683bcb/pyobjc_framework_screensaver-11.0.tar.gz", hash = "sha256:2e4c643624cc0cffeafc535c43faf5f8de8be030307fa8a5bea257845e8af474", size = 23774 } +sdist = { url = "https://files.pythonhosted.org/packages/f6/b6/71c20259a1bfffcb5103be62564006b1bbc21f80180658101e2370683bcb/pyobjc_framework_screensaver-11.0.tar.gz", hash = "sha256:2e4c643624cc0cffeafc535c43faf5f8de8be030307fa8a5bea257845e8af474", size = 23774, upload-time = "2025-01-14T19:05:19.325Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d7/ab/f17cd36458e6cf6d64c412128641edcfc220b8147283f6b34ef56c7db111/pyobjc_framework_ScreenSaver-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:436357c822d87220df64912da04b421e82a5e1e6464d48f2dbccc69529d19cd3", size = 8445 }, - { url = "https://files.pythonhosted.org/packages/52/57/300b641e929741a5d38cf80c74496918be1d2fe5e210d3fceb3e768747b2/pyobjc_framework_ScreenSaver-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:03b12e89bc164cb01527ca795f3f590f286d15de6ee0e4ff1d36705740d6d72f", size = 8372 }, + { url = "https://files.pythonhosted.org/packages/d7/ab/f17cd36458e6cf6d64c412128641edcfc220b8147283f6b34ef56c7db111/pyobjc_framework_ScreenSaver-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:436357c822d87220df64912da04b421e82a5e1e6464d48f2dbccc69529d19cd3", size = 8445, upload-time = "2025-01-14T18:58:59.299Z" }, + { url = "https://files.pythonhosted.org/packages/52/57/300b641e929741a5d38cf80c74496918be1d2fe5e210d3fceb3e768747b2/pyobjc_framework_ScreenSaver-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:03b12e89bc164cb01527ca795f3f590f286d15de6ee0e4ff1d36705740d6d72f", size = 8372, upload-time = "2025-01-14T18:59:00.358Z" }, ] [[package]] @@ -3821,13 +3850,13 @@ name = "pyobjc-framework-screentime" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/42/a7/ee60ee5b0471a4367eaa1c8a243418874fd48fac5dbdfdd318a653d94aaa/pyobjc_framework_screentime-11.0.tar.gz", hash = "sha256:6dd74dc64be1865346fcff63b8849253697f7ac68d83ee2708019cf3852c1cd7", size = 14398 } +sdist = { url = "https://files.pythonhosted.org/packages/42/a7/ee60ee5b0471a4367eaa1c8a243418874fd48fac5dbdfdd318a653d94aaa/pyobjc_framework_screentime-11.0.tar.gz", hash = "sha256:6dd74dc64be1865346fcff63b8849253697f7ac68d83ee2708019cf3852c1cd7", size = 14398, upload-time = "2025-01-14T19:05:21.547Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/40/7a/8df61f80725e993fd0dc1a111217de6a8efec35b02a4796749de0b7e8c34/pyobjc_framework_ScreenTime-11.0-py2.py3-none-any.whl", hash = "sha256:723938c7d47e3c5c1c0f79010a01139762384bd0c03c51ee7a4736fc3f128fed", size = 3721 }, - { url = "https://files.pythonhosted.org/packages/c4/62/2f86cedd4cc439625976848832c1d1571fcb69cc087dd71c9cf09e793db5/pyobjc_framework_ScreenTime-11.0-py3-none-any.whl", hash = "sha256:45db846ec9249cab90e86cbb31cf70e13800305b7c74819ab681a91854c91df2", size = 3790 }, + { url = "https://files.pythonhosted.org/packages/40/7a/8df61f80725e993fd0dc1a111217de6a8efec35b02a4796749de0b7e8c34/pyobjc_framework_ScreenTime-11.0-py2.py3-none-any.whl", hash = "sha256:723938c7d47e3c5c1c0f79010a01139762384bd0c03c51ee7a4736fc3f128fed", size = 3721, upload-time = "2025-01-14T18:59:04.027Z" }, + { url = "https://files.pythonhosted.org/packages/c4/62/2f86cedd4cc439625976848832c1d1571fcb69cc087dd71c9cf09e793db5/pyobjc_framework_ScreenTime-11.0-py3-none-any.whl", hash = "sha256:45db846ec9249cab90e86cbb31cf70e13800305b7c74819ab681a91854c91df2", size = 3790, upload-time = "2025-01-14T18:59:06.363Z" }, ] [[package]] @@ -3835,13 +3864,13 @@ name = "pyobjc-framework-scriptingbridge" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/4d/f0/592af19047935e44c07ddd1eba4f05aa8eb460ee842f7d5d48501231cd69/pyobjc_framework_scriptingbridge-11.0.tar.gz", hash = "sha256:65e5edd0ea608ae7f01808b963dfa25743315f563705d75c493c2fa7032f88cc", size = 22626 } +sdist = { url = "https://files.pythonhosted.org/packages/4d/f0/592af19047935e44c07ddd1eba4f05aa8eb460ee842f7d5d48501231cd69/pyobjc_framework_scriptingbridge-11.0.tar.gz", hash = "sha256:65e5edd0ea608ae7f01808b963dfa25743315f563705d75c493c2fa7032f88cc", size = 22626, upload-time = "2025-01-14T19:05:22.461Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7d/2c/2fd33c0318a8fe35f00f0089a44a2c27d4d0fd0b4b5e13628051a4d8c9d3/pyobjc_framework_ScriptingBridge-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c98d080446aa8ba4074e43eb0be1feed96781dbc0718496f172fcd20e84a9158", size = 8209 }, - { url = "https://files.pythonhosted.org/packages/93/3b/b2b721248e951eef6b7e6b25cb3a1d6683702235bc73683d0239f068d2df/pyobjc_framework_ScriptingBridge-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:23a4b2e2e57b7b4d992777ea9efb15273ccd8e8105385143dab9bd5a10962317", size = 8238 }, + { url = "https://files.pythonhosted.org/packages/7d/2c/2fd33c0318a8fe35f00f0089a44a2c27d4d0fd0b4b5e13628051a4d8c9d3/pyobjc_framework_ScriptingBridge-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c98d080446aa8ba4074e43eb0be1feed96781dbc0718496f172fcd20e84a9158", size = 8209, upload-time = "2025-01-14T18:59:11.107Z" }, + { url = "https://files.pythonhosted.org/packages/93/3b/b2b721248e951eef6b7e6b25cb3a1d6683702235bc73683d0239f068d2df/pyobjc_framework_ScriptingBridge-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:23a4b2e2e57b7b4d992777ea9efb15273ccd8e8105385143dab9bd5a10962317", size = 8238, upload-time = "2025-01-14T18:59:13.27Z" }, ] [[package]] @@ -3849,13 +3878,13 @@ name = "pyobjc-framework-searchkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/15/27/9676327cf7d13346d546325b411a5deaa072bd0fbe733c8aae8a9a00c0e0/pyobjc_framework_searchkit-11.0.tar.gz", hash = "sha256:36f3109e74bc5e6fab60c02be804d5ed1c511ad51ea0d597a6c6a9653573ddf5", size = 31182 } +sdist = { url = "https://files.pythonhosted.org/packages/15/27/9676327cf7d13346d546325b411a5deaa072bd0fbe733c8aae8a9a00c0e0/pyobjc_framework_searchkit-11.0.tar.gz", hash = "sha256:36f3109e74bc5e6fab60c02be804d5ed1c511ad51ea0d597a6c6a9653573ddf5", size = 31182, upload-time = "2025-01-14T19:05:24.667Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f2/d4/64fa608b5d91859b11c26ceca83a41d2bf1d0dcbf1d9df847bab5a52ccc8/pyobjc_framework_SearchKit-11.0-py2.py3-none-any.whl", hash = "sha256:332f9d30ec3b223efaac681fbdd923ba660575e241abb4ed5e03207c97799530", size = 3633 }, - { url = "https://files.pythonhosted.org/packages/93/e2/83e94c505c5436821982d724cc890f74d717f9473782f7278ce78634685d/pyobjc_framework_SearchKit-11.0-py3-none-any.whl", hash = "sha256:5f4304cb77c327b28ac0f7ec9b99313075afd742091d39368eb64f076bb7d141", size = 3699 }, + { url = "https://files.pythonhosted.org/packages/f2/d4/64fa608b5d91859b11c26ceca83a41d2bf1d0dcbf1d9df847bab5a52ccc8/pyobjc_framework_SearchKit-11.0-py2.py3-none-any.whl", hash = "sha256:332f9d30ec3b223efaac681fbdd923ba660575e241abb4ed5e03207c97799530", size = 3633, upload-time = "2025-01-14T18:59:18.343Z" }, + { url = "https://files.pythonhosted.org/packages/93/e2/83e94c505c5436821982d724cc890f74d717f9473782f7278ce78634685d/pyobjc_framework_SearchKit-11.0-py3-none-any.whl", hash = "sha256:5f4304cb77c327b28ac0f7ec9b99313075afd742091d39368eb64f076bb7d141", size = 3699, upload-time = "2025-01-14T18:59:20.754Z" }, ] [[package]] @@ -3863,13 +3892,13 @@ name = "pyobjc-framework-security" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c5/75/4b916bff8c650e387077a35916b7a7d331d5ff03bed7275099d96dcc6cd9/pyobjc_framework_security-11.0.tar.gz", hash = "sha256:ac078bb9cc6762d6f0f25f68325dcd7fe77acdd8c364bf4378868493f06a0758", size = 347059 } +sdist = { url = "https://files.pythonhosted.org/packages/c5/75/4b916bff8c650e387077a35916b7a7d331d5ff03bed7275099d96dcc6cd9/pyobjc_framework_security-11.0.tar.gz", hash = "sha256:ac078bb9cc6762d6f0f25f68325dcd7fe77acdd8c364bf4378868493f06a0758", size = 347059, upload-time = "2025-01-14T19:05:26.17Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fa/d8/092940f8c46cf09000a9d026e9854772846d5335e3e8a44d0a81aa1f359e/pyobjc_framework_Security-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:93bc23630563de2551ac49048af010ac9cb40f927cc25c898b7cc48550ccd526", size = 41499 }, - { url = "https://files.pythonhosted.org/packages/0b/fc/8710bbe80b825c97ecc312aaead3b0f606a23b62b895f6e0a07df8bfeeae/pyobjc_framework_Security-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:421e03b8560ed296a7f5ee67f42f5f978f8c7959d65c8fec99cd77dc65786355", size = 41523 }, + { url = "https://files.pythonhosted.org/packages/fa/d8/092940f8c46cf09000a9d026e9854772846d5335e3e8a44d0a81aa1f359e/pyobjc_framework_Security-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:93bc23630563de2551ac49048af010ac9cb40f927cc25c898b7cc48550ccd526", size = 41499, upload-time = "2025-01-14T18:59:22.819Z" }, + { url = "https://files.pythonhosted.org/packages/0b/fc/8710bbe80b825c97ecc312aaead3b0f606a23b62b895f6e0a07df8bfeeae/pyobjc_framework_Security-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:421e03b8560ed296a7f5ee67f42f5f978f8c7959d65c8fec99cd77dc65786355", size = 41523, upload-time = "2025-01-14T18:59:25.368Z" }, ] [[package]] @@ -3877,14 +3906,14 @@ name = "pyobjc-framework-securityfoundation" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/84/d6/0d817edb11d2bdb0f536059e913191e587f1984e39397bb3341209d92c21/pyobjc_framework_securityfoundation-11.0.tar.gz", hash = "sha256:5ae906ded5dd40046c013a7e0c1f59416abafb4b72bc947b6cd259749745e637", size = 13526 } +sdist = { url = "https://files.pythonhosted.org/packages/84/d6/0d817edb11d2bdb0f536059e913191e587f1984e39397bb3341209d92c21/pyobjc_framework_securityfoundation-11.0.tar.gz", hash = "sha256:5ae906ded5dd40046c013a7e0c1f59416abafb4b72bc947b6cd259749745e637", size = 13526, upload-time = "2025-01-14T19:05:27.275Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f8/41/50da30e87841c8b9ee1f17e9720dc9dbb2c2e59abac84fffe899ed5f9188/pyobjc_framework_SecurityFoundation-11.0-py2.py3-none-any.whl", hash = "sha256:8f8e43b91ae7cb45f3251c14c0c6caf5fdcdb93794176c4b118214a108ee2ef3", size = 3716 }, - { url = "https://files.pythonhosted.org/packages/cb/61/e73a61de62e31b33378ee635534228f4801b1554fbd89a47e0b36965908d/pyobjc_framework_SecurityFoundation-11.0-py3-none-any.whl", hash = "sha256:1fa89969fbf7a4fd57214388a43f7ed6b6b1fd0c0ec7aa77752444eb1604143c", size = 3787 }, + { url = "https://files.pythonhosted.org/packages/f8/41/50da30e87841c8b9ee1f17e9720dc9dbb2c2e59abac84fffe899ed5f9188/pyobjc_framework_SecurityFoundation-11.0-py2.py3-none-any.whl", hash = "sha256:8f8e43b91ae7cb45f3251c14c0c6caf5fdcdb93794176c4b118214a108ee2ef3", size = 3716, upload-time = "2025-01-14T18:59:29.79Z" }, + { url = "https://files.pythonhosted.org/packages/cb/61/e73a61de62e31b33378ee635534228f4801b1554fbd89a47e0b36965908d/pyobjc_framework_SecurityFoundation-11.0-py3-none-any.whl", hash = "sha256:1fa89969fbf7a4fd57214388a43f7ed6b6b1fd0c0ec7aa77752444eb1604143c", size = 3787, upload-time = "2025-01-14T18:59:30.764Z" }, ] [[package]] @@ -3892,14 +3921,14 @@ name = "pyobjc-framework-securityinterface" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b1/88/d7c4942650707fe5b1d3b45b42684f58f2cab7d2772ec74ca96ecef575eb/pyobjc_framework_securityinterface-11.0.tar.gz", hash = "sha256:8843a27cf30a8e4dd6e2cb7702a6d65ad4222429f0ccc6c062537af4683b1c08", size = 37118 } +sdist = { url = "https://files.pythonhosted.org/packages/b1/88/d7c4942650707fe5b1d3b45b42684f58f2cab7d2772ec74ca96ecef575eb/pyobjc_framework_securityinterface-11.0.tar.gz", hash = "sha256:8843a27cf30a8e4dd6e2cb7702a6d65ad4222429f0ccc6c062537af4683b1c08", size = 37118, upload-time = "2025-01-14T19:05:28.569Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/88/5f/a96da5f43da5a9d0e5d016bc672a4dca09f88d091c96d9ecff5f753ad1d5/pyobjc_framework_SecurityInterface-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2771dae043c8aa278887f96c7d206957164c7a81a562fa391bf0b9316d6755eb", size = 10706 }, - { url = "https://files.pythonhosted.org/packages/50/86/fc41dcf8f5300ad2c6508568535d9c0a83b412b0a4a961616441c8acf10f/pyobjc_framework_SecurityInterface-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6453732f7608d514e8f7005d80d238422cbebc4ab4d6d6fed1e51175f9f7244f", size = 10781 }, + { url = "https://files.pythonhosted.org/packages/88/5f/a96da5f43da5a9d0e5d016bc672a4dca09f88d091c96d9ecff5f753ad1d5/pyobjc_framework_SecurityInterface-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2771dae043c8aa278887f96c7d206957164c7a81a562fa391bf0b9316d6755eb", size = 10706, upload-time = "2025-01-14T18:59:32.632Z" }, + { url = "https://files.pythonhosted.org/packages/50/86/fc41dcf8f5300ad2c6508568535d9c0a83b412b0a4a961616441c8acf10f/pyobjc_framework_SecurityInterface-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6453732f7608d514e8f7005d80d238422cbebc4ab4d6d6fed1e51175f9f7244f", size = 10781, upload-time = "2025-01-14T18:59:33.832Z" }, ] [[package]] @@ -3907,14 +3936,14 @@ name = "pyobjc-framework-sensitivecontentanalysis" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/00/e4/f1e0f150ae6c6ad7dde9b248f34f324f4f8b1c42260dbf62420f80d79ba9/pyobjc_framework_sensitivecontentanalysis-11.0.tar.gz", hash = "sha256:0f09034688f894c0f4409c16adaf857d78714d55472de4aa2ac40fbd7ba233d6", size = 13060 } +sdist = { url = "https://files.pythonhosted.org/packages/00/e4/f1e0f150ae6c6ad7dde9b248f34f324f4f8b1c42260dbf62420f80d79ba9/pyobjc_framework_sensitivecontentanalysis-11.0.tar.gz", hash = "sha256:0f09034688f894c0f4409c16adaf857d78714d55472de4aa2ac40fbd7ba233d6", size = 13060, upload-time = "2025-01-14T19:05:29.655Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3d/eb/e0d60b3e233860a237fdddd44ab961c9115c33e947058d73c222dafc50af/pyobjc_framework_SensitiveContentAnalysis-11.0-py2.py3-none-any.whl", hash = "sha256:e19d2edc807f98aef31fa4db5472a509cf90523436c971d1095a000b0e357058", size = 3791 }, - { url = "https://files.pythonhosted.org/packages/c4/1c/fb2138cf08cd0215ea4f78032871a1d89e7e41d9fad18b55e937f0577c03/pyobjc_framework_SensitiveContentAnalysis-11.0-py3-none-any.whl", hash = "sha256:027bd0be0785f7aea3bfd56ff7c3496e5d383211122393c599c28ea392675589", size = 3863 }, + { url = "https://files.pythonhosted.org/packages/3d/eb/e0d60b3e233860a237fdddd44ab961c9115c33e947058d73c222dafc50af/pyobjc_framework_SensitiveContentAnalysis-11.0-py2.py3-none-any.whl", hash = "sha256:e19d2edc807f98aef31fa4db5472a509cf90523436c971d1095a000b0e357058", size = 3791, upload-time = "2025-01-14T18:59:39.563Z" }, + { url = "https://files.pythonhosted.org/packages/c4/1c/fb2138cf08cd0215ea4f78032871a1d89e7e41d9fad18b55e937f0577c03/pyobjc_framework_SensitiveContentAnalysis-11.0-py3-none-any.whl", hash = "sha256:027bd0be0785f7aea3bfd56ff7c3496e5d383211122393c599c28ea392675589", size = 3863, upload-time = "2025-01-14T18:59:40.548Z" }, ] [[package]] @@ -3922,13 +3951,13 @@ name = "pyobjc-framework-servicemanagement" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/1b/59/8d38b5cdbcfb57ab842e080436dbd04d5a5d2080e99a2ea1e286cfad12a8/pyobjc_framework_servicemanagement-11.0.tar.gz", hash = "sha256:10b1bbcee3de5bb2b9fc3d6763eb682b7a1d9ddd4bd2c882fece62783cb17885", size = 16882 } +sdist = { url = "https://files.pythonhosted.org/packages/1b/59/8d38b5cdbcfb57ab842e080436dbd04d5a5d2080e99a2ea1e286cfad12a8/pyobjc_framework_servicemanagement-11.0.tar.gz", hash = "sha256:10b1bbcee3de5bb2b9fc3d6763eb682b7a1d9ddd4bd2c882fece62783cb17885", size = 16882, upload-time = "2025-01-14T19:05:30.537Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5b/35/cbac7db272d0e5e71b300be1517b0a1dc7cf035944675eaed7066d41e883/pyobjc_framework_ServiceManagement-11.0-py2.py3-none-any.whl", hash = "sha256:35cfd7a369a120fa55e64b719a2dda00295b2cc6ddab16ffa8939f4326d1b37d", size = 5254 }, - { url = "https://files.pythonhosted.org/packages/b3/40/26c5d63d131e3e415815bfbb4bd035ba10d45f0d87733646221966871b6b/pyobjc_framework_ServiceManagement-11.0-py3-none-any.whl", hash = "sha256:7ec19c9632f67d589ad37815d001e8e443d92e75001c370486a1070a4359e166", size = 5322 }, + { url = "https://files.pythonhosted.org/packages/5b/35/cbac7db272d0e5e71b300be1517b0a1dc7cf035944675eaed7066d41e883/pyobjc_framework_ServiceManagement-11.0-py2.py3-none-any.whl", hash = "sha256:35cfd7a369a120fa55e64b719a2dda00295b2cc6ddab16ffa8939f4326d1b37d", size = 5254, upload-time = "2025-01-14T18:59:41.438Z" }, + { url = "https://files.pythonhosted.org/packages/b3/40/26c5d63d131e3e415815bfbb4bd035ba10d45f0d87733646221966871b6b/pyobjc_framework_ServiceManagement-11.0-py3-none-any.whl", hash = "sha256:7ec19c9632f67d589ad37815d001e8e443d92e75001c370486a1070a4359e166", size = 5322, upload-time = "2025-01-14T18:59:42.585Z" }, ] [[package]] @@ -3936,13 +3965,13 @@ name = "pyobjc-framework-sharedwithyou" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyoucore", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-sharedwithyoucore" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/20/84/db667061f815537717a6cac891df01a45b65e6feaa2dfa0c9d2e3803a1ef/pyobjc_framework_sharedwithyou-11.0.tar.gz", hash = "sha256:a3a03daac77ad7364ed22109ca90c6cd2dcb7611a96cbdf37d30543ef1579399", size = 33696 } +sdist = { url = "https://files.pythonhosted.org/packages/20/84/db667061f815537717a6cac891df01a45b65e6feaa2dfa0c9d2e3803a1ef/pyobjc_framework_sharedwithyou-11.0.tar.gz", hash = "sha256:a3a03daac77ad7364ed22109ca90c6cd2dcb7611a96cbdf37d30543ef1579399", size = 33696, upload-time = "2025-01-14T19:05:31.396Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3c/ab/391ef0de3021997ec9a12d8044c0b7e884780a9bead7f847254e06d0f075/pyobjc_framework_SharedWithYou-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6dac74375d3dc18d67cae46f3f16a45cef699b1976a4012827c0f15256da55df", size = 8606 }, - { url = "https://files.pythonhosted.org/packages/cf/04/6a3eb12bf9c35f3063be678f36430beb92b7e2683f4b952596396473a74d/pyobjc_framework_SharedWithYou-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6076a0893a3597e054918c136f3391671a225a37fe1b1a070046817e3a232954", size = 8629 }, + { url = "https://files.pythonhosted.org/packages/3c/ab/391ef0de3021997ec9a12d8044c0b7e884780a9bead7f847254e06d0f075/pyobjc_framework_SharedWithYou-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6dac74375d3dc18d67cae46f3f16a45cef699b1976a4012827c0f15256da55df", size = 8606, upload-time = "2025-01-14T18:59:44.537Z" }, + { url = "https://files.pythonhosted.org/packages/cf/04/6a3eb12bf9c35f3063be678f36430beb92b7e2683f4b952596396473a74d/pyobjc_framework_SharedWithYou-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6076a0893a3597e054918c136f3391671a225a37fe1b1a070046817e3a232954", size = 8629, upload-time = "2025-01-14T18:59:45.579Z" }, ] [[package]] @@ -3950,13 +3979,13 @@ name = "pyobjc-framework-sharedwithyoucore" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/52/2a/86904cd9cc3bf5cdb9101481e17e67358f39f81ffa0f36768097287e34b3/pyobjc_framework_sharedwithyoucore-11.0.tar.gz", hash = "sha256:3932452677df5d67ea27845ab26ccaaa1d1779196bf16b62c5655f13d822c82d", size = 28877 } +sdist = { url = "https://files.pythonhosted.org/packages/52/2a/86904cd9cc3bf5cdb9101481e17e67358f39f81ffa0f36768097287e34b3/pyobjc_framework_sharedwithyoucore-11.0.tar.gz", hash = "sha256:3932452677df5d67ea27845ab26ccaaa1d1779196bf16b62c5655f13d822c82d", size = 28877, upload-time = "2025-01-14T19:05:32.283Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/21/40/69ae712e223991cd975c1f8ba2b00a5aa4c129ac0e76838b4d936740e4c7/pyobjc_framework_SharedWithYouCore-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:46cd00a97c5fec747ef057000daa88495699ea5d5d6fe1f302bfb89b2d431645", size = 8366 }, - { url = "https://files.pythonhosted.org/packages/c2/ce/500ad643f2d07e8ef065e8ddc5a08954f5d59cc199c89b700581eaf821ee/pyobjc_framework_SharedWithYouCore-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8b5f180371a63da718fe6c3b58e7613c6b2adf9b483cefbf6d9467eb8ac2f0ca", size = 8380 }, + { url = "https://files.pythonhosted.org/packages/21/40/69ae712e223991cd975c1f8ba2b00a5aa4c129ac0e76838b4d936740e4c7/pyobjc_framework_SharedWithYouCore-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:46cd00a97c5fec747ef057000daa88495699ea5d5d6fe1f302bfb89b2d431645", size = 8366, upload-time = "2025-01-14T18:59:55.641Z" }, + { url = "https://files.pythonhosted.org/packages/c2/ce/500ad643f2d07e8ef065e8ddc5a08954f5d59cc199c89b700581eaf821ee/pyobjc_framework_SharedWithYouCore-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8b5f180371a63da718fe6c3b58e7613c6b2adf9b483cefbf6d9467eb8ac2f0ca", size = 8380, upload-time = "2025-01-14T18:59:56.546Z" }, ] [[package]] @@ -3964,13 +3993,13 @@ name = "pyobjc-framework-shazamkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/dd/2a/1f4ad92260860e500cb61119e8e7fe604b0788c32f5b00446b5a56705a2b/pyobjc_framework_shazamkit-11.0.tar.gz", hash = "sha256:cea736cefe90b6bb989d0a8abdc21ef4b3b431b27657abb09d6deb0b2c1bd37a", size = 25172 } +sdist = { url = "https://files.pythonhosted.org/packages/dd/2a/1f4ad92260860e500cb61119e8e7fe604b0788c32f5b00446b5a56705a2b/pyobjc_framework_shazamkit-11.0.tar.gz", hash = "sha256:cea736cefe90b6bb989d0a8abdc21ef4b3b431b27657abb09d6deb0b2c1bd37a", size = 25172, upload-time = "2025-01-14T19:05:34.497Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/05/81/edfcd4be626aae356dd1b991f521eaeffa1798e91ddae9e7d9ae8ed371d1/pyobjc_framework_ShazamKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ecdc2392d7e8d6e2540c7ad3073a229d08b0818c5dd044a26c93b765ce9868aa", size = 8411 }, - { url = "https://files.pythonhosted.org/packages/e1/f7/f3d2ae7a604e3e3c0de93ed229895be6757edfa0cc76f2a44670f28a81c8/pyobjc_framework_ShazamKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ef79d863cc7d4023aa552f55d4120653eceed862baf1edba8e08b1af10fab036", size = 8419 }, + { url = "https://files.pythonhosted.org/packages/05/81/edfcd4be626aae356dd1b991f521eaeffa1798e91ddae9e7d9ae8ed371d1/pyobjc_framework_ShazamKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ecdc2392d7e8d6e2540c7ad3073a229d08b0818c5dd044a26c93b765ce9868aa", size = 8411, upload-time = "2025-01-14T19:00:02.908Z" }, + { url = "https://files.pythonhosted.org/packages/e1/f7/f3d2ae7a604e3e3c0de93ed229895be6757edfa0cc76f2a44670f28a81c8/pyobjc_framework_ShazamKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ef79d863cc7d4023aa552f55d4120653eceed862baf1edba8e08b1af10fab036", size = 8419, upload-time = "2025-01-14T19:00:05.081Z" }, ] [[package]] @@ -3978,13 +4007,13 @@ name = "pyobjc-framework-social" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/6f/56/ed483f85105ef929241ab1a6ed3dbfd0be558bb900e36b274f997db9c869/pyobjc_framework_social-11.0.tar.gz", hash = "sha256:ccedd6eddb6744049467bce19b4ec4f0667ec60552731c02dcbfa8938a3ac798", size = 14806 } +sdist = { url = "https://files.pythonhosted.org/packages/6f/56/ed483f85105ef929241ab1a6ed3dbfd0be558bb900e36b274f997db9c869/pyobjc_framework_social-11.0.tar.gz", hash = "sha256:ccedd6eddb6744049467bce19b4ec4f0667ec60552731c02dcbfa8938a3ac798", size = 14806, upload-time = "2025-01-14T19:05:35.394Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/46/1d/2cc0f753ac8b1f5c15cfa9201d8584ff4de6dc940fc954cd9c52d1a615f9/pyobjc_framework_Social-11.0-py2.py3-none-any.whl", hash = "sha256:aa379009738afb0d6abc0347e8189f7f316109e9dfcb904f7f14e6b7c3d5bad8", size = 4362 }, - { url = "https://files.pythonhosted.org/packages/a8/25/b762b1f9429f8ea0df754e7d58bafd48d73e5527b0423e67570661a7907e/pyobjc_framework_Social-11.0-py3-none-any.whl", hash = "sha256:94db183e8b3ad21272a1ba24e9cda763d603c6021fd80a96d00ce78b6b94e1c2", size = 4428 }, + { url = "https://files.pythonhosted.org/packages/46/1d/2cc0f753ac8b1f5c15cfa9201d8584ff4de6dc940fc954cd9c52d1a615f9/pyobjc_framework_Social-11.0-py2.py3-none-any.whl", hash = "sha256:aa379009738afb0d6abc0347e8189f7f316109e9dfcb904f7f14e6b7c3d5bad8", size = 4362, upload-time = "2025-01-14T19:00:10.058Z" }, + { url = "https://files.pythonhosted.org/packages/a8/25/b762b1f9429f8ea0df754e7d58bafd48d73e5527b0423e67570661a7907e/pyobjc_framework_Social-11.0-py3-none-any.whl", hash = "sha256:94db183e8b3ad21272a1ba24e9cda763d603c6021fd80a96d00ce78b6b94e1c2", size = 4428, upload-time = "2025-01-14T19:00:11.242Z" }, ] [[package]] @@ -3992,13 +4021,13 @@ name = "pyobjc-framework-soundanalysis" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9a/14/697ca1b76228a96bb459f3cf43234798b05fdf11691202449d98d9d887af/pyobjc_framework_soundanalysis-11.0.tar.gz", hash = "sha256:f541fcd04ec5d7528dd2ae2d873a92a3092e87fb70b8df229c79defb4d807d1a", size = 16789 } +sdist = { url = "https://files.pythonhosted.org/packages/9a/14/697ca1b76228a96bb459f3cf43234798b05fdf11691202449d98d9d887af/pyobjc_framework_soundanalysis-11.0.tar.gz", hash = "sha256:f541fcd04ec5d7528dd2ae2d873a92a3092e87fb70b8df229c79defb4d807d1a", size = 16789, upload-time = "2025-01-14T19:05:36.576Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/d4/91afb41c514d1e236567b971a981f96c1d20f16eb0658256369c53a4bf45/pyobjc_framework_SoundAnalysis-11.0-py2.py3-none-any.whl", hash = "sha256:5969096cadb07f9ba9855cedf6f53674ddb030a324b4981091834d1b31c8c27e", size = 4111 }, - { url = "https://files.pythonhosted.org/packages/af/7a/f960ad1e727f6d917e6c84b7383f3eacbb2948bc60396be3bce40cbd8128/pyobjc_framework_SoundAnalysis-11.0-py3-none-any.whl", hash = "sha256:70f70923756e118203cde4ac25083a34ead69a6034baed9c694a36f5fe2325f3", size = 4182 }, + { url = "https://files.pythonhosted.org/packages/ab/d4/91afb41c514d1e236567b971a981f96c1d20f16eb0658256369c53a4bf45/pyobjc_framework_SoundAnalysis-11.0-py2.py3-none-any.whl", hash = "sha256:5969096cadb07f9ba9855cedf6f53674ddb030a324b4981091834d1b31c8c27e", size = 4111, upload-time = "2025-01-14T19:00:13.327Z" }, + { url = "https://files.pythonhosted.org/packages/af/7a/f960ad1e727f6d917e6c84b7383f3eacbb2948bc60396be3bce40cbd8128/pyobjc_framework_SoundAnalysis-11.0-py3-none-any.whl", hash = "sha256:70f70923756e118203cde4ac25083a34ead69a6034baed9c694a36f5fe2325f3", size = 4182, upload-time = "2025-01-14T19:00:15.68Z" }, ] [[package]] @@ -4006,13 +4035,13 @@ name = "pyobjc-framework-speech" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5f/39/e9f0a73243c38d85f8da6a1a2afda73503e2fcc31a72f5479770bceae0c1/pyobjc_framework_speech-11.0.tar.gz", hash = "sha256:92a191c3ecfe7032eea2140ab5dda826a59c7bb84b13a2edb0ebc471a76e6d7b", size = 40620 } +sdist = { url = "https://files.pythonhosted.org/packages/5f/39/e9f0a73243c38d85f8da6a1a2afda73503e2fcc31a72f5479770bceae0c1/pyobjc_framework_speech-11.0.tar.gz", hash = "sha256:92a191c3ecfe7032eea2140ab5dda826a59c7bb84b13a2edb0ebc471a76e6d7b", size = 40620, upload-time = "2025-01-14T19:05:38.391Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b0/85/e989076ff0cd40c7cfb3ed7d621703de11bfd8286f1729aca759db1f42a3/pyobjc_framework_Speech-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:353179210683e38bfbd675df6a35eec46b30ce30b7291bcb07a5cadaf11a3bd7", size = 9016 }, - { url = "https://files.pythonhosted.org/packages/00/03/827acde068787c2318981e2bfef2c3cadbe8552434ccc0634b30084ef914/pyobjc_framework_Speech-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:134e08025f4638e428602f7e16bbec94b00477eec090316138d758a86e10fd5f", size = 9037 }, + { url = "https://files.pythonhosted.org/packages/b0/85/e989076ff0cd40c7cfb3ed7d621703de11bfd8286f1729aca759db1f42a3/pyobjc_framework_Speech-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:353179210683e38bfbd675df6a35eec46b30ce30b7291bcb07a5cadaf11a3bd7", size = 9016, upload-time = "2025-01-14T19:00:17.661Z" }, + { url = "https://files.pythonhosted.org/packages/00/03/827acde068787c2318981e2bfef2c3cadbe8552434ccc0634b30084ef914/pyobjc_framework_Speech-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:134e08025f4638e428602f7e16bbec94b00477eec090316138d758a86e10fd5f", size = 9037, upload-time = "2025-01-14T19:00:21.186Z" }, ] [[package]] @@ -4020,14 +4049,14 @@ name = "pyobjc-framework-spritekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b7/6e/642e64f5b62a7777c784931c7f018788b5620e307907d416c837fd0c4315/pyobjc_framework_spritekit-11.0.tar.gz", hash = "sha256:aa43927e325d4ac253b7c0ec4df95393b0354bd278ebe9871803419d12d1ef80", size = 129851 } +sdist = { url = "https://files.pythonhosted.org/packages/b7/6e/642e64f5b62a7777c784931c7f018788b5620e307907d416c837fd0c4315/pyobjc_framework_spritekit-11.0.tar.gz", hash = "sha256:aa43927e325d4ac253b7c0ec4df95393b0354bd278ebe9871803419d12d1ef80", size = 129851, upload-time = "2025-01-14T19:05:39.709Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e1/80/319f156ac6f6cab0dbc85881d81a74d4a7f17913256338683ae8d9ed56c4/pyobjc_framework_SpriteKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3d0971a7a85786edc521ab897bdb0c78696278e6417bf389abdfe2151358e854", size = 18077 }, - { url = "https://files.pythonhosted.org/packages/bb/09/303d76844a10745cdbac1ff76c2c8630c1ef46455014562dc79aaa72a6e3/pyobjc_framework_SpriteKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0da5f2b52636a2f04fc38a123fed9d7f8d6fd353df027c51c0bfc91e244a9d2b", size = 18145 }, + { url = "https://files.pythonhosted.org/packages/e1/80/319f156ac6f6cab0dbc85881d81a74d4a7f17913256338683ae8d9ed56c4/pyobjc_framework_SpriteKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3d0971a7a85786edc521ab897bdb0c78696278e6417bf389abdfe2151358e854", size = 18077, upload-time = "2025-01-14T19:00:26.815Z" }, + { url = "https://files.pythonhosted.org/packages/bb/09/303d76844a10745cdbac1ff76c2c8630c1ef46455014562dc79aaa72a6e3/pyobjc_framework_SpriteKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0da5f2b52636a2f04fc38a123fed9d7f8d6fd353df027c51c0bfc91e244a9d2b", size = 18145, upload-time = "2025-01-14T19:00:27.956Z" }, ] [[package]] @@ -4035,13 +4064,13 @@ name = "pyobjc-framework-storekit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/69/ca/f4e5a1ff8c98bbbf208639b2bef7bf3b88936bccda1d8ed34aa7d052f589/pyobjc_framework_storekit-11.0.tar.gz", hash = "sha256:ef7e75b28f1fa8b0b6413e64b9d5d78b8ca358fc2477483d2783f688ff8d75e0", size = 75855 } +sdist = { url = "https://files.pythonhosted.org/packages/69/ca/f4e5a1ff8c98bbbf208639b2bef7bf3b88936bccda1d8ed34aa7d052f589/pyobjc_framework_storekit-11.0.tar.gz", hash = "sha256:ef7e75b28f1fa8b0b6413e64b9d5d78b8ca358fc2477483d2783f688ff8d75e0", size = 75855, upload-time = "2025-01-14T19:05:41.605Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/40/af53ad7781515866003c2c71056a053d2f033cf2aa31920a8a1fdb829d7a/pyobjc_framework_StoreKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1d51a05a5e0277c542978b1f5a6aa33331359de7c0a2cf0ad922760b36e5066a", size = 11655 }, - { url = "https://files.pythonhosted.org/packages/f3/11/ba3259d3b22980e08c5e8255a48cc97180bec47d72ffbbd41ab699df39b1/pyobjc_framework_StoreKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:29269183e91043bbfee79851ae712073feba1e10845b8deeb7e6aaa20cfb3cf4", size = 11680 }, + { url = "https://files.pythonhosted.org/packages/ab/40/af53ad7781515866003c2c71056a053d2f033cf2aa31920a8a1fdb829d7a/pyobjc_framework_StoreKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1d51a05a5e0277c542978b1f5a6aa33331359de7c0a2cf0ad922760b36e5066a", size = 11655, upload-time = "2025-01-14T19:00:32.894Z" }, + { url = "https://files.pythonhosted.org/packages/f3/11/ba3259d3b22980e08c5e8255a48cc97180bec47d72ffbbd41ab699df39b1/pyobjc_framework_StoreKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:29269183e91043bbfee79851ae712073feba1e10845b8deeb7e6aaa20cfb3cf4", size = 11680, upload-time = "2025-01-14T19:00:35.36Z" }, ] [[package]] @@ -4049,13 +4078,13 @@ name = "pyobjc-framework-symbols" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/dc/92/a20a3d7af3c99e0ea086e43715675160a04b86c1d069bdaeb3acdb015d92/pyobjc_framework_symbols-11.0.tar.gz", hash = "sha256:e3de7736dfb8107f515cfd23f03e874dd9468e88ab076d01d922a73fefb620fa", size = 13682 } +sdist = { url = "https://files.pythonhosted.org/packages/dc/92/a20a3d7af3c99e0ea086e43715675160a04b86c1d069bdaeb3acdb015d92/pyobjc_framework_symbols-11.0.tar.gz", hash = "sha256:e3de7736dfb8107f515cfd23f03e874dd9468e88ab076d01d922a73fefb620fa", size = 13682, upload-time = "2025-01-14T19:05:45.727Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/66/ff/341d44f5347d48491682bece366444f3e230e33109266dcc6a17e6a7fc3d/pyobjc_framework_Symbols-11.0-py2.py3-none-any.whl", hash = "sha256:f1490823f40a8a540ac10628190695f27a717343914fe5db5fafa500f7c7bf44", size = 3263 }, - { url = "https://files.pythonhosted.org/packages/94/a4/c21353872a2fc643206a44ac55b92b5b7533cdb2cb26c44a9048debc295a/pyobjc_framework_Symbols-11.0-py3-none-any.whl", hash = "sha256:0919e85fcf6f420f61d8d9a67cafa2ab4678666441ef4f001b31f5457900b314", size = 3335 }, + { url = "https://files.pythonhosted.org/packages/66/ff/341d44f5347d48491682bece366444f3e230e33109266dcc6a17e6a7fc3d/pyobjc_framework_Symbols-11.0-py2.py3-none-any.whl", hash = "sha256:f1490823f40a8a540ac10628190695f27a717343914fe5db5fafa500f7c7bf44", size = 3263, upload-time = "2025-01-14T19:00:41.055Z" }, + { url = "https://files.pythonhosted.org/packages/94/a4/c21353872a2fc643206a44ac55b92b5b7533cdb2cb26c44a9048debc295a/pyobjc_framework_Symbols-11.0-py3-none-any.whl", hash = "sha256:0919e85fcf6f420f61d8d9a67cafa2ab4678666441ef4f001b31f5457900b314", size = 3335, upload-time = "2025-01-14T19:00:43.294Z" }, ] [[package]] @@ -4063,14 +4092,14 @@ name = "pyobjc-framework-syncservices" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5a/22/642186906f672461bab1d7773b35ef74e432b9789ca2248186b766e9fd3b/pyobjc_framework_syncservices-11.0.tar.gz", hash = "sha256:7867c23895a8289da8d56e962c144c36ed16bd101dc07d05281c55930b142471", size = 57453 } +sdist = { url = "https://files.pythonhosted.org/packages/5a/22/642186906f672461bab1d7773b35ef74e432b9789ca2248186b766e9fd3b/pyobjc_framework_syncservices-11.0.tar.gz", hash = "sha256:7867c23895a8289da8d56e962c144c36ed16bd101dc07d05281c55930b142471", size = 57453, upload-time = "2025-01-14T19:05:46.559Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/15/9b/484db4eed6b1e29e0d69275bd459ab21a6b3f98e8b2ce61beeb9971303ca/pyobjc_framework_SyncServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:89a398df6518cff1c63b7cccf3025e388f3ef299645734112c5aa1ac5f7ca30a", size = 13989 }, - { url = "https://files.pythonhosted.org/packages/8d/d8/dc86d708434b7cb59825c56549e64b118ba4b8584d2eb5a1514d1cd5d1bd/pyobjc_framework_SyncServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e870e82ed34c43607cc50dbae57a81dd419b75abc06670630cbbf41ae6e1402c", size = 14008 }, + { url = "https://files.pythonhosted.org/packages/15/9b/484db4eed6b1e29e0d69275bd459ab21a6b3f98e8b2ce61beeb9971303ca/pyobjc_framework_SyncServices-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:89a398df6518cff1c63b7cccf3025e388f3ef299645734112c5aa1ac5f7ca30a", size = 13989, upload-time = "2025-01-14T19:00:45.216Z" }, + { url = "https://files.pythonhosted.org/packages/8d/d8/dc86d708434b7cb59825c56549e64b118ba4b8584d2eb5a1514d1cd5d1bd/pyobjc_framework_SyncServices-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e870e82ed34c43607cc50dbae57a81dd419b75abc06670630cbbf41ae6e1402c", size = 14008, upload-time = "2025-01-14T19:00:46.188Z" }, ] [[package]] @@ -4078,13 +4107,13 @@ name = "pyobjc-framework-systemconfiguration" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/70/70/ebebf311523f436df2407f35d7ce62482c01e530b77aceb3ca6356dcef43/pyobjc_framework_systemconfiguration-11.0.tar.gz", hash = "sha256:06487f0fdd43c6447b5fd3d7f3f59826178d32bcf74f848c5b3ea597191d471d", size = 142949 } +sdist = { url = "https://files.pythonhosted.org/packages/70/70/ebebf311523f436df2407f35d7ce62482c01e530b77aceb3ca6356dcef43/pyobjc_framework_systemconfiguration-11.0.tar.gz", hash = "sha256:06487f0fdd43c6447b5fd3d7f3f59826178d32bcf74f848c5b3ea597191d471d", size = 142949, upload-time = "2025-01-14T19:05:47.466Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/28/8f/1b5f7e8e848d2c84204da08d5c63e42feff86b26cd508da7a4f95960b842/pyobjc_framework_SystemConfiguration-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:89d3c54abedcedbc2ce52c31ff4878251ca54a8535407ed6bd6584ce099c148b", size = 21836 }, - { url = "https://files.pythonhosted.org/packages/6d/49/8660b3d0a46ac2f88e73cec3d10e21885b107f54635680ef0c677ac5cf3e/pyobjc_framework_SystemConfiguration-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8cbcb9662dbb5a034cfc5a44adaf2a0226a2985ae299a4ef4fd75bb49f30f5a0", size = 21727 }, + { url = "https://files.pythonhosted.org/packages/28/8f/1b5f7e8e848d2c84204da08d5c63e42feff86b26cd508da7a4f95960b842/pyobjc_framework_SystemConfiguration-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:89d3c54abedcedbc2ce52c31ff4878251ca54a8535407ed6bd6584ce099c148b", size = 21836, upload-time = "2025-01-14T19:00:51.698Z" }, + { url = "https://files.pythonhosted.org/packages/6d/49/8660b3d0a46ac2f88e73cec3d10e21885b107f54635680ef0c677ac5cf3e/pyobjc_framework_SystemConfiguration-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8cbcb9662dbb5a034cfc5a44adaf2a0226a2985ae299a4ef4fd75bb49f30f5a0", size = 21727, upload-time = "2025-01-14T19:00:52.685Z" }, ] [[package]] @@ -4092,13 +4121,13 @@ name = "pyobjc-framework-systemextensions" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/62/4b/904d818debf6216b7be009d492d998c819bf2f2791bfb75870a952e32cf9/pyobjc_framework_systemextensions-11.0.tar.gz", hash = "sha256:da293c99b428fb7f18a7a1d311b17177f73a20c7ffa94de3f72d760df924255e", size = 22531 } +sdist = { url = "https://files.pythonhosted.org/packages/62/4b/904d818debf6216b7be009d492d998c819bf2f2791bfb75870a952e32cf9/pyobjc_framework_systemextensions-11.0.tar.gz", hash = "sha256:da293c99b428fb7f18a7a1d311b17177f73a20c7ffa94de3f72d760df924255e", size = 22531, upload-time = "2025-01-14T19:05:48.463Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/15/3c/8f91b89554ef3127e037d90b3ef83c77a994bb889b7884a995756cd06b63/pyobjc_framework_SystemExtensions-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f7a2ec417fa0d383cc066bc292541aa78fd2aec9cca83a98d41b7982f185d1f7", size = 8975 }, - { url = "https://files.pythonhosted.org/packages/21/8c/cf2a018b5f1ecd216f8cb26a3b6fbe590d08de81a6c6b4658e001a203886/pyobjc_framework_SystemExtensions-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:62b99c6bd88bce642960fc2b9d5903fbfca680d16be9a4565a883eb4ba17ca5e", size = 8999 }, + { url = "https://files.pythonhosted.org/packages/15/3c/8f91b89554ef3127e037d90b3ef83c77a994bb889b7884a995756cd06b63/pyobjc_framework_SystemExtensions-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f7a2ec417fa0d383cc066bc292541aa78fd2aec9cca83a98d41b7982f185d1f7", size = 8975, upload-time = "2025-01-14T19:00:57.822Z" }, + { url = "https://files.pythonhosted.org/packages/21/8c/cf2a018b5f1ecd216f8cb26a3b6fbe590d08de81a6c6b4658e001a203886/pyobjc_framework_SystemExtensions-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:62b99c6bd88bce642960fc2b9d5903fbfca680d16be9a4565a883eb4ba17ca5e", size = 8999, upload-time = "2025-01-14T19:00:58.865Z" }, ] [[package]] @@ -4106,13 +4135,13 @@ name = "pyobjc-framework-threadnetwork" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c4/17/fc8fde4eeb6697e0a5ba1a306cd62d3a95b53f3334744cd22b87037d8a14/pyobjc_framework_threadnetwork-11.0.tar.gz", hash = "sha256:f5713579380f6fb89c877796de86cb4e98428d7a9cbfebe566fb827ba23b2d8e", size = 13820 } +sdist = { url = "https://files.pythonhosted.org/packages/c4/17/fc8fde4eeb6697e0a5ba1a306cd62d3a95b53f3334744cd22b87037d8a14/pyobjc_framework_threadnetwork-11.0.tar.gz", hash = "sha256:f5713579380f6fb89c877796de86cb4e98428d7a9cbfebe566fb827ba23b2d8e", size = 13820, upload-time = "2025-01-14T19:05:49.307Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/55/a9/908184da457e33a110de7d2d262efa69beaba6db243342df5654da03566b/pyobjc_framework_ThreadNetwork-11.0-py2.py3-none-any.whl", hash = "sha256:950d46a009cb992b12dbd8169a0450d8cc101fc982e03e6543078c6d7790e353", size = 3700 }, - { url = "https://files.pythonhosted.org/packages/59/d4/4694fc7a627d2b6b37c51433ba7f02a39a283a445dc77349b82fe24534f1/pyobjc_framework_ThreadNetwork-11.0-py3-none-any.whl", hash = "sha256:1218649e4f488ca411af13b74f1dee1e7a178169e0f5963342ba8a7c46037ea7", size = 3770 }, + { url = "https://files.pythonhosted.org/packages/55/a9/908184da457e33a110de7d2d262efa69beaba6db243342df5654da03566b/pyobjc_framework_ThreadNetwork-11.0-py2.py3-none-any.whl", hash = "sha256:950d46a009cb992b12dbd8169a0450d8cc101fc982e03e6543078c6d7790e353", size = 3700, upload-time = "2025-01-14T19:01:03.254Z" }, + { url = "https://files.pythonhosted.org/packages/59/d4/4694fc7a627d2b6b37c51433ba7f02a39a283a445dc77349b82fe24534f1/pyobjc_framework_ThreadNetwork-11.0-py3-none-any.whl", hash = "sha256:1218649e4f488ca411af13b74f1dee1e7a178169e0f5963342ba8a7c46037ea7", size = 3770, upload-time = "2025-01-14T19:01:05.456Z" }, ] [[package]] @@ -4120,13 +4149,13 @@ name = "pyobjc-framework-uniformtypeidentifiers" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/56/4f/fd571c1f87d5ee3d86c4d2008806e9623d2662bbc788d9001b3fff35275f/pyobjc_framework_uniformtypeidentifiers-11.0.tar.gz", hash = "sha256:6ae6927a3ed1f0197a8c472226f11f46ccd5ed398b4449613e1d10346d9ed15d", size = 20860 } +sdist = { url = "https://files.pythonhosted.org/packages/56/4f/fd571c1f87d5ee3d86c4d2008806e9623d2662bbc788d9001b3fff35275f/pyobjc_framework_uniformtypeidentifiers-11.0.tar.gz", hash = "sha256:6ae6927a3ed1f0197a8c472226f11f46ccd5ed398b4449613e1d10346d9ed15d", size = 20860, upload-time = "2025-01-14T19:05:50.073Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/82/f2/094888af07fb7f0443996e5d91915e74b87e8705b599b68b516a0e94a63d/pyobjc_framework_UniformTypeIdentifiers-11.0-py2.py3-none-any.whl", hash = "sha256:acffb86e8b03b66c49274236b3df3a254cacd32b9f25bd7a5bd59baaaf738624", size = 4841 }, - { url = "https://files.pythonhosted.org/packages/88/9c/4cc0522cc546e6a3bf8a921e3a9f0ed078e3cf907d616760d9f3d7754919/pyobjc_framework_UniformTypeIdentifiers-11.0-py3-none-any.whl", hash = "sha256:a3097f186c7e231b19218a3ceecb3b70a8f2b2e9e642ef409dc7a195a30c869e", size = 4910 }, + { url = "https://files.pythonhosted.org/packages/82/f2/094888af07fb7f0443996e5d91915e74b87e8705b599b68b516a0e94a63d/pyobjc_framework_UniformTypeIdentifiers-11.0-py2.py3-none-any.whl", hash = "sha256:acffb86e8b03b66c49274236b3df3a254cacd32b9f25bd7a5bd59baaaf738624", size = 4841, upload-time = "2025-01-14T19:01:06.404Z" }, + { url = "https://files.pythonhosted.org/packages/88/9c/4cc0522cc546e6a3bf8a921e3a9f0ed078e3cf907d616760d9f3d7754919/pyobjc_framework_UniformTypeIdentifiers-11.0-py3-none-any.whl", hash = "sha256:a3097f186c7e231b19218a3ceecb3b70a8f2b2e9e642ef409dc7a195a30c869e", size = 4910, upload-time = "2025-01-14T19:01:07.393Z" }, ] [[package]] @@ -4134,13 +4163,13 @@ name = "pyobjc-framework-usernotifications" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/78/f5/ca3e6a7d940b3aca4323e4f5409b14b5d2eb45432158430c584e3800ce4d/pyobjc_framework_usernotifications-11.0.tar.gz", hash = "sha256:7950a1c6a8297f006c26c3d286705ffc2a07061d6e844f1106290572097b872c", size = 54857 } +sdist = { url = "https://files.pythonhosted.org/packages/78/f5/ca3e6a7d940b3aca4323e4f5409b14b5d2eb45432158430c584e3800ce4d/pyobjc_framework_usernotifications-11.0.tar.gz", hash = "sha256:7950a1c6a8297f006c26c3d286705ffc2a07061d6e844f1106290572097b872c", size = 54857, upload-time = "2025-01-14T19:05:52.42Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1f/bf/5545d5c9d0d10a603ad406a5ce727de6a47daace9c38d4484818611599f3/pyobjc_framework_UserNotifications-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4bf78fa37f574f5b43db9b83ca02e82ab45803589f970042afdcd1cb8c01396d", size = 9483 }, - { url = "https://files.pythonhosted.org/packages/7a/1e/41f4d18120b2c006f756edde1845a2df45fdbd6957e540f8ebcfae25747f/pyobjc_framework_UserNotifications-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0b4c06c3862405e103e964327581c28e5390a2d4cd0cef3d8e64afda03c9f431", size = 9506 }, + { url = "https://files.pythonhosted.org/packages/1f/bf/5545d5c9d0d10a603ad406a5ce727de6a47daace9c38d4484818611599f3/pyobjc_framework_UserNotifications-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4bf78fa37f574f5b43db9b83ca02e82ab45803589f970042afdcd1cb8c01396d", size = 9483, upload-time = "2025-01-14T19:01:09.256Z" }, + { url = "https://files.pythonhosted.org/packages/7a/1e/41f4d18120b2c006f756edde1845a2df45fdbd6957e540f8ebcfae25747f/pyobjc_framework_UserNotifications-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0b4c06c3862405e103e964327581c28e5390a2d4cd0cef3d8e64afda03c9f431", size = 9506, upload-time = "2025-01-14T19:01:10.218Z" }, ] [[package]] @@ -4148,14 +4177,14 @@ name = "pyobjc-framework-usernotificationsui" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotifications", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-usernotifications" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e9/e8/f0d50cdc678260a628b92e55b5752155f941c2f72b96fe3f2412a28c5d79/pyobjc_framework_usernotificationsui-11.0.tar.gz", hash = "sha256:d0ec597d189b4d228b0b836474aef318652c1c287b33442a1403c49dc59fdb7f", size = 14369 } +sdist = { url = "https://files.pythonhosted.org/packages/e9/e8/f0d50cdc678260a628b92e55b5752155f941c2f72b96fe3f2412a28c5d79/pyobjc_framework_usernotificationsui-11.0.tar.gz", hash = "sha256:d0ec597d189b4d228b0b836474aef318652c1c287b33442a1403c49dc59fdb7f", size = 14369, upload-time = "2025-01-14T19:05:54.498Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/bb/f7/64c95c6f82e92bb1cbcb8d5c3658c79c954668627eef28f11e76025a3ed1/pyobjc_framework_UserNotificationsUI-11.0-py2.py3-none-any.whl", hash = "sha256:6185d9c9513b6a823cd72dcf40d2fb33bbf0f2c9a98528e0e112580b47ac3632", size = 3856 }, - { url = "https://files.pythonhosted.org/packages/eb/c3/e1d64c9e523b5192e0179b6723ee465e74d6c282104a49a67347d527a65d/pyobjc_framework_UserNotificationsUI-11.0-py3-none-any.whl", hash = "sha256:e4439e549265929ddad1feca7b062d00c2d3732470f349cb0d594705e0257919", size = 3932 }, + { url = "https://files.pythonhosted.org/packages/bb/f7/64c95c6f82e92bb1cbcb8d5c3658c79c954668627eef28f11e76025a3ed1/pyobjc_framework_UserNotificationsUI-11.0-py2.py3-none-any.whl", hash = "sha256:6185d9c9513b6a823cd72dcf40d2fb33bbf0f2c9a98528e0e112580b47ac3632", size = 3856, upload-time = "2025-01-14T19:01:15.43Z" }, + { url = "https://files.pythonhosted.org/packages/eb/c3/e1d64c9e523b5192e0179b6723ee465e74d6c282104a49a67347d527a65d/pyobjc_framework_UserNotificationsUI-11.0-py3-none-any.whl", hash = "sha256:e4439e549265929ddad1feca7b062d00c2d3732470f349cb0d594705e0257919", size = 3932, upload-time = "2025-01-14T19:01:16.486Z" }, ] [[package]] @@ -4163,13 +4192,13 @@ name = "pyobjc-framework-videosubscriberaccount" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/7e/2e/6a7debd84911a9384b4e7a9cc3f308e3461a00a9d74f33b153bdd872f15f/pyobjc_framework_videosubscriberaccount-11.0.tar.gz", hash = "sha256:163b32f361f48b9d20f317461464abd4427b3242693ae011633fc443c7d5449c", size = 29100 } +sdist = { url = "https://files.pythonhosted.org/packages/7e/2e/6a7debd84911a9384b4e7a9cc3f308e3461a00a9d74f33b153bdd872f15f/pyobjc_framework_videosubscriberaccount-11.0.tar.gz", hash = "sha256:163b32f361f48b9d20f317461464abd4427b3242693ae011633fc443c7d5449c", size = 29100, upload-time = "2025-01-14T19:05:55.319Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/51/82/94650fe5cc68c0c32fe56fe22cd7eb2874b28f987a9e259fac12cbea7705/pyobjc_framework_VideoSubscriberAccount-11.0-py2.py3-none-any.whl", hash = "sha256:1deec8d5a0138ae51b5ca7bfb7f6fe1b0dc3cbb52db3111059708efa5f8a8d04", size = 4637 }, - { url = "https://files.pythonhosted.org/packages/61/54/1765507adad1b0c9bc6be10f09b249d425212bc0d9fef1efdfd872ee9807/pyobjc_framework_VideoSubscriberAccount-11.0-py3-none-any.whl", hash = "sha256:0095eddb5fc942f9e049bc4c683cf28c77ea60c60942552c3c48bf74c8fdca9b", size = 4709 }, + { url = "https://files.pythonhosted.org/packages/51/82/94650fe5cc68c0c32fe56fe22cd7eb2874b28f987a9e259fac12cbea7705/pyobjc_framework_VideoSubscriberAccount-11.0-py2.py3-none-any.whl", hash = "sha256:1deec8d5a0138ae51b5ca7bfb7f6fe1b0dc3cbb52db3111059708efa5f8a8d04", size = 4637, upload-time = "2025-01-14T19:01:17.365Z" }, + { url = "https://files.pythonhosted.org/packages/61/54/1765507adad1b0c9bc6be10f09b249d425212bc0d9fef1efdfd872ee9807/pyobjc_framework_VideoSubscriberAccount-11.0-py3-none-any.whl", hash = "sha256:0095eddb5fc942f9e049bc4c683cf28c77ea60c60942552c3c48bf74c8fdca9b", size = 4709, upload-time = "2025-01-14T19:01:18.349Z" }, ] [[package]] @@ -4177,15 +4206,15 @@ name = "pyobjc-framework-videotoolbox" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ba/2d/c031a132b142fcd20846cc1ac3ba92abaa58ec04164fd36ca978d9374f1c/pyobjc_framework_videotoolbox-11.0.tar.gz", hash = "sha256:a54ed8f8bcbdd2bdea2a296dc02a8a7d42f81e2b6ccbf4d1f10cec5e7a09bec0", size = 81157 } +sdist = { url = "https://files.pythonhosted.org/packages/ba/2d/c031a132b142fcd20846cc1ac3ba92abaa58ec04164fd36ca978d9374f1c/pyobjc_framework_videotoolbox-11.0.tar.gz", hash = "sha256:a54ed8f8bcbdd2bdea2a296dc02a8a7d42f81e2b6ccbf4d1f10cec5e7a09bec0", size = 81157, upload-time = "2025-01-14T19:05:56.135Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/44/ae/ff697840bdcf3530e8fba84e2a606813eda1ee90be074f12e2857460cebf/pyobjc_framework_VideoToolbox-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:12af56190e65c3b60c6ca14fe69045e5ffb5908ea1363580506eb32603b80855", size = 13446 }, - { url = "https://files.pythonhosted.org/packages/1e/ef/9e7230435da47016983a3c9ea7b1d5237b43fce2d8b2b923eb638b7694f5/pyobjc_framework_VideoToolbox-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:4ed7f073bd8dfecca0da6359d5cd871b2f39144883930bddd41ca818447de608", size = 13451 }, + { url = "https://files.pythonhosted.org/packages/44/ae/ff697840bdcf3530e8fba84e2a606813eda1ee90be074f12e2857460cebf/pyobjc_framework_VideoToolbox-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:12af56190e65c3b60c6ca14fe69045e5ffb5908ea1363580506eb32603b80855", size = 13446, upload-time = "2025-01-14T19:01:21.066Z" }, + { url = "https://files.pythonhosted.org/packages/1e/ef/9e7230435da47016983a3c9ea7b1d5237b43fce2d8b2b923eb638b7694f5/pyobjc_framework_VideoToolbox-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:4ed7f073bd8dfecca0da6359d5cd871b2f39144883930bddd41ca818447de608", size = 13451, upload-time = "2025-01-14T19:01:22.009Z" }, ] [[package]] @@ -4193,13 +4222,13 @@ name = "pyobjc-framework-virtualization" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/65/8d/e57e1f2c5ac950dc3da6c977effde4a55b8b70424b1bdb97b5530559f5bc/pyobjc_framework_virtualization-11.0.tar.gz", hash = "sha256:03e1c1fa20950aa7c275e5f11f1257108b6d1c6a7403afb86f4e9d5fae87b73c", size = 78144 } +sdist = { url = "https://files.pythonhosted.org/packages/65/8d/e57e1f2c5ac950dc3da6c977effde4a55b8b70424b1bdb97b5530559f5bc/pyobjc_framework_virtualization-11.0.tar.gz", hash = "sha256:03e1c1fa20950aa7c275e5f11f1257108b6d1c6a7403afb86f4e9d5fae87b73c", size = 78144, upload-time = "2025-01-14T19:05:57.086Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6b/c9/b2f8322d7ced14822270481be5b44f1846aa7c09b4b3cb52517dc1054f4b/pyobjc_framework_Virtualization-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:334712792136ffcf3c63a63cea01ce33d60309a82721c95e25f0cc26b95f72cc", size = 13417 }, - { url = "https://files.pythonhosted.org/packages/1e/96/d64425811a4ef2c8b38914ea1a91bbd2aa6136bb79989e4821acd6d28e67/pyobjc_framework_Virtualization-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5b848b1ab365906b11a507c8146e477c27d2bf56159d49d21fda15b93c2811ec", size = 13430 }, + { url = "https://files.pythonhosted.org/packages/6b/c9/b2f8322d7ced14822270481be5b44f1846aa7c09b4b3cb52517dc1054f4b/pyobjc_framework_Virtualization-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:334712792136ffcf3c63a63cea01ce33d60309a82721c95e25f0cc26b95f72cc", size = 13417, upload-time = "2025-01-14T19:01:28.821Z" }, + { url = "https://files.pythonhosted.org/packages/1e/96/d64425811a4ef2c8b38914ea1a91bbd2aa6136bb79989e4821acd6d28e67/pyobjc_framework_Virtualization-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5b848b1ab365906b11a507c8146e477c27d2bf56159d49d21fda15b93c2811ec", size = 13430, upload-time = "2025-01-14T19:01:29.733Z" }, ] [[package]] @@ -4207,15 +4236,15 @@ name = "pyobjc-framework-vision" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreml", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreml" }, + { name = "pyobjc-framework-quartz" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ef/53/dc2e0562a177af9306efceb84bc21f5cf7470acaa8f28f64e62bf828b7e1/pyobjc_framework_vision-11.0.tar.gz", hash = "sha256:45342e5253c306dbcd056a68bff04ffbfa00e9ac300a02aabf2e81053b771e39", size = 133175 } +sdist = { url = "https://files.pythonhosted.org/packages/ef/53/dc2e0562a177af9306efceb84bc21f5cf7470acaa8f28f64e62bf828b7e1/pyobjc_framework_vision-11.0.tar.gz", hash = "sha256:45342e5253c306dbcd056a68bff04ffbfa00e9ac300a02aabf2e81053b771e39", size = 133175, upload-time = "2025-01-14T19:05:58.013Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7f/84/d23a745d46858409a1dca3e7f5cb3089c148ebb8d42e7a6289e1972ad650/pyobjc_framework_Vision-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ca7cc48332d804a02b5b17f31bed52dd4b7c323f9e4ff4b4e7ecd35d39cc0759", size = 21754 }, - { url = "https://files.pythonhosted.org/packages/3a/80/6db9fc2a3f8b991860156f4700f979ad8aa1e9617b0efa720ee3b52e3602/pyobjc_framework_Vision-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1b07aa867dda47d2a4883cd969e248039988b49190ba097cbe9747156b5d1f30", size = 17099 }, + { url = "https://files.pythonhosted.org/packages/7f/84/d23a745d46858409a1dca3e7f5cb3089c148ebb8d42e7a6289e1972ad650/pyobjc_framework_Vision-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ca7cc48332d804a02b5b17f31bed52dd4b7c323f9e4ff4b4e7ecd35d39cc0759", size = 21754, upload-time = "2025-01-14T19:01:35.504Z" }, + { url = "https://files.pythonhosted.org/packages/3a/80/6db9fc2a3f8b991860156f4700f979ad8aa1e9617b0efa720ee3b52e3602/pyobjc_framework_Vision-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1b07aa867dda47d2a4883cd969e248039988b49190ba097cbe9747156b5d1f30", size = 17099, upload-time = "2025-01-14T19:01:37.457Z" }, ] [[package]] @@ -4223,13 +4252,13 @@ name = "pyobjc-framework-webkit" version = "11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/79/4f/02a6270acf225c2a34339677e796002c77506238475059ae6e855358a40c/pyobjc_framework_webkit-11.0.tar.gz", hash = "sha256:fa6bedf9873786b3376a74ce2ea9dcd311f2a80f61e33dcbd931cc956aa29644", size = 767210 } +sdist = { url = "https://files.pythonhosted.org/packages/79/4f/02a6270acf225c2a34339677e796002c77506238475059ae6e855358a40c/pyobjc_framework_webkit-11.0.tar.gz", hash = "sha256:fa6bedf9873786b3376a74ce2ea9dcd311f2a80f61e33dcbd931cc956aa29644", size = 767210, upload-time = "2025-01-14T19:05:59.3Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/47/63/6f04faa75c4c39c54007b256a8e13838c1de213d487f561937d342ec2eac/pyobjc_framework_WebKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:163abaa5a665b59626ef20cdc3dcc5e2e3fcd9830d5fc328507e13f663acd0ed", size = 44940 }, - { url = "https://files.pythonhosted.org/packages/3e/61/934f03510e7f49454fbf6eeff8ad2eca5d8bfbe71aa4b8a034f8132af2fa/pyobjc_framework_WebKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2e4911519e94822011d99fdb9addf4a176f45a79808dab18dc303293f4590f7c", size = 44901 }, + { url = "https://files.pythonhosted.org/packages/47/63/6f04faa75c4c39c54007b256a8e13838c1de213d487f561937d342ec2eac/pyobjc_framework_WebKit-11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:163abaa5a665b59626ef20cdc3dcc5e2e3fcd9830d5fc328507e13f663acd0ed", size = 44940, upload-time = "2025-01-14T19:01:44.396Z" }, + { url = "https://files.pythonhosted.org/packages/3e/61/934f03510e7f49454fbf6eeff8ad2eca5d8bfbe71aa4b8a034f8132af2fa/pyobjc_framework_WebKit-11.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2e4911519e94822011d99fdb9addf4a176f45a79808dab18dc303293f4590f7c", size = 44901, upload-time = "2025-01-14T19:01:45.476Z" }, ] [[package]] @@ -4237,22 +4266,22 @@ name = "pyopencl" version = "2025.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "platformdirs", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "pytools", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "numpy" }, + { name = "platformdirs" }, + { name = "pytools" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/28/88/0ac460d3e2def08b2ad6345db6a13613815f616bbbd60c6f4bdf774f4c41/pyopencl-2025.1.tar.gz", hash = "sha256:0116736d7f7920f87b8db4b66a03f27b1d930d2e37ddd14518407cc22dd24779", size = 422510 } +sdist = { url = "https://files.pythonhosted.org/packages/28/88/0ac460d3e2def08b2ad6345db6a13613815f616bbbd60c6f4bdf774f4c41/pyopencl-2025.1.tar.gz", hash = "sha256:0116736d7f7920f87b8db4b66a03f27b1d930d2e37ddd14518407cc22dd24779", size = 422510, upload-time = "2025-01-22T00:16:58.421Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/99/ce/c40c6248b29195397a6e176615c24a8047cdd3afe847932a1f27603c1b14/pyopencl-2025.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:a302e4ee1bb19ff244f5ae2b5a83a98977daa13f31929a85f23723020a4bec01", size = 424117 }, - { url = "https://files.pythonhosted.org/packages/71/dd/8dd4e18396c705567be7eda65234932f8eb7e975cc15ae167265ed9c7d20/pyopencl-2025.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:48527fc5a250b9e89f2eaaa1c9423e1bc15ff181bd41ffa1e29e31890dc1d3b7", size = 408327 }, - { url = "https://files.pythonhosted.org/packages/47/7b/270c4e6765b675eaa97af8ff0c964e21dc74ac2a2f04e2c24431c91ce382/pyopencl-2025.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:95490199c490e47b245b88e64e06f95272502d13810da172ac3b0f0340cf8715", size = 724636 }, - { url = "https://files.pythonhosted.org/packages/0d/55/996d7877793acfc340678a71dc98151a8c39dbb289cf24ecae08c0af68eb/pyopencl-2025.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:cd2cb3c031beeec93cf660c8809d6ad58a2cde7dcd95ae12b4b2da6ac8e2da41", size = 1173429 }, - { url = "https://files.pythonhosted.org/packages/3d/7c/d2a89b1c24c318375856e8b7611bc03ddf687134f68ddbb387496453eda8/pyopencl-2025.1-cp311-cp311-win_amd64.whl", hash = "sha256:d8d3cdb02dc8750a9cc11c5b37f219da1f61b4216af4a830eb52b451a0e9f9a7", size = 457877 }, - { url = "https://files.pythonhosted.org/packages/02/c0/d9536211ecfddd3bdf7eaa1658d085fcd92120061ac6f4e662a5062660ff/pyopencl-2025.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:88c564d94a5067ab6b9429a7d92b655254da8b2b5a33c7e30e10c5a0cf3154e1", size = 425706 }, - { url = "https://files.pythonhosted.org/packages/63/b9/3e6dd574cc9ffb2271be135ecdb36cd6aea70a1f74e80539b048072a256a/pyopencl-2025.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f204cd6974ca19e7ffe14f21afac9967b06a6718f3aecbbc4a4df313e8e7ebc2", size = 408163 }, - { url = "https://files.pythonhosted.org/packages/a4/4d/7f6f2e24b12585b81fd49f689d21ba62187656d061e3cb43840f12097dad/pyopencl-2025.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dce8d1b3fd2046e89377b754117fdb3505f45edacfda6ad2b3a29670c0526ad1", size = 719348 }, - { url = "https://files.pythonhosted.org/packages/f0/45/3c93510819859e047d494dd8f4ed80c26378bb964a8e5e850cc079cc1f6e/pyopencl-2025.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fbb0b7b775424f0c4c929a00f09eb351075ea9e4d2b1c80afe37d09bec218ee9", size = 1170733 }, - { url = "https://files.pythonhosted.org/packages/91/ba/b745715085ef893fa7d1c7e04c95e3e554b6b27b2fb0800d6bbca563b43c/pyopencl-2025.1-cp312-cp312-win_amd64.whl", hash = "sha256:78f2a58d2e177793fb5a7b9c8a574e3a5f1d178c4df713969d1b08341c817d60", size = 457762 }, + { url = "https://files.pythonhosted.org/packages/99/ce/c40c6248b29195397a6e176615c24a8047cdd3afe847932a1f27603c1b14/pyopencl-2025.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:a302e4ee1bb19ff244f5ae2b5a83a98977daa13f31929a85f23723020a4bec01", size = 424117, upload-time = "2025-01-22T00:16:08.957Z" }, + { url = "https://files.pythonhosted.org/packages/71/dd/8dd4e18396c705567be7eda65234932f8eb7e975cc15ae167265ed9c7d20/pyopencl-2025.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:48527fc5a250b9e89f2eaaa1c9423e1bc15ff181bd41ffa1e29e31890dc1d3b7", size = 408327, upload-time = "2025-01-22T00:16:10.42Z" }, + { url = "https://files.pythonhosted.org/packages/47/7b/270c4e6765b675eaa97af8ff0c964e21dc74ac2a2f04e2c24431c91ce382/pyopencl-2025.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:95490199c490e47b245b88e64e06f95272502d13810da172ac3b0f0340cf8715", size = 724636, upload-time = "2025-01-22T00:16:12.881Z" }, + { url = "https://files.pythonhosted.org/packages/0d/55/996d7877793acfc340678a71dc98151a8c39dbb289cf24ecae08c0af68eb/pyopencl-2025.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:cd2cb3c031beeec93cf660c8809d6ad58a2cde7dcd95ae12b4b2da6ac8e2da41", size = 1173429, upload-time = "2025-01-22T00:16:14.466Z" }, + { url = "https://files.pythonhosted.org/packages/3d/7c/d2a89b1c24c318375856e8b7611bc03ddf687134f68ddbb387496453eda8/pyopencl-2025.1-cp311-cp311-win_amd64.whl", hash = "sha256:d8d3cdb02dc8750a9cc11c5b37f219da1f61b4216af4a830eb52b451a0e9f9a7", size = 457877, upload-time = "2025-01-22T00:16:17.21Z" }, + { url = "https://files.pythonhosted.org/packages/02/c0/d9536211ecfddd3bdf7eaa1658d085fcd92120061ac6f4e662a5062660ff/pyopencl-2025.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:88c564d94a5067ab6b9429a7d92b655254da8b2b5a33c7e30e10c5a0cf3154e1", size = 425706, upload-time = "2025-01-22T00:16:18.771Z" }, + { url = "https://files.pythonhosted.org/packages/63/b9/3e6dd574cc9ffb2271be135ecdb36cd6aea70a1f74e80539b048072a256a/pyopencl-2025.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f204cd6974ca19e7ffe14f21afac9967b06a6718f3aecbbc4a4df313e8e7ebc2", size = 408163, upload-time = "2025-01-22T00:16:20.282Z" }, + { url = "https://files.pythonhosted.org/packages/a4/4d/7f6f2e24b12585b81fd49f689d21ba62187656d061e3cb43840f12097dad/pyopencl-2025.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dce8d1b3fd2046e89377b754117fdb3505f45edacfda6ad2b3a29670c0526ad1", size = 719348, upload-time = "2025-01-22T00:16:22.15Z" }, + { url = "https://files.pythonhosted.org/packages/f0/45/3c93510819859e047d494dd8f4ed80c26378bb964a8e5e850cc079cc1f6e/pyopencl-2025.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fbb0b7b775424f0c4c929a00f09eb351075ea9e4d2b1c80afe37d09bec218ee9", size = 1170733, upload-time = "2025-01-22T00:16:24.575Z" }, + { url = "https://files.pythonhosted.org/packages/91/ba/b745715085ef893fa7d1c7e04c95e3e554b6b27b2fb0800d6bbca563b43c/pyopencl-2025.1-cp312-cp312-win_amd64.whl", hash = "sha256:78f2a58d2e177793fb5a7b9c8a574e3a5f1d178c4df713969d1b08341c817d60", size = 457762, upload-time = "2025-01-22T00:16:27.334Z" }, ] [[package]] @@ -4262,37 +4291,37 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cryptography" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5d/70/ff56a63248562e77c0c8ee4aefc3224258f1856977e0c1472672b62dadb8/pyopenssl-24.2.1.tar.gz", hash = "sha256:4247f0dbe3748d560dcbb2ff3ea01af0f9a1a001ef5f7c4c647956ed8cbf0e95", size = 184323 } +sdist = { url = "https://files.pythonhosted.org/packages/5d/70/ff56a63248562e77c0c8ee4aefc3224258f1856977e0c1472672b62dadb8/pyopenssl-24.2.1.tar.gz", hash = "sha256:4247f0dbe3748d560dcbb2ff3ea01af0f9a1a001ef5f7c4c647956ed8cbf0e95", size = 184323, upload-time = "2024-07-20T17:26:31.252Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d9/dd/e0aa7ebef5168c75b772eda64978c597a9129b46be17779054652a7999e4/pyOpenSSL-24.2.1-py3-none-any.whl", hash = "sha256:967d5719b12b243588573f39b0c677637145c7a1ffedcd495a487e58177fbb8d", size = 58390 }, + { url = "https://files.pythonhosted.org/packages/d9/dd/e0aa7ebef5168c75b772eda64978c597a9129b46be17779054652a7999e4/pyOpenSSL-24.2.1-py3-none-any.whl", hash = "sha256:967d5719b12b243588573f39b0c677637145c7a1ffedcd495a487e58177fbb8d", size = 58390, upload-time = "2024-07-20T17:26:29.057Z" }, ] [[package]] name = "pyparsing" -version = "3.2.1" +version = "3.2.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/8b/1a/3544f4f299a47911c2ab3710f534e52fea62a633c96806995da5d25be4b2/pyparsing-3.2.1.tar.gz", hash = "sha256:61980854fd66de3a90028d679a954d5f2623e83144b5afe5ee86f43d762e5f0a", size = 1067694 } +sdist = { url = "https://files.pythonhosted.org/packages/bb/22/f1129e69d94ffff626bdb5c835506b3a5b4f3d070f17ea295e12c2c6f60f/pyparsing-3.2.3.tar.gz", hash = "sha256:b9c13f1ab8b3b542f72e28f634bad4de758ab3ce4546e4301970ad6fa77c38be", size = 1088608, upload-time = "2025-03-25T05:01:28.114Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1c/a7/c8a2d361bf89c0d9577c934ebb7421b25dc84bf3a8e3ac0a40aed9acc547/pyparsing-3.2.1-py3-none-any.whl", hash = "sha256:506ff4f4386c4cec0590ec19e6302d3aedb992fdc02c761e90416f158dacf8e1", size = 107716 }, + { url = "https://files.pythonhosted.org/packages/05/e7/df2285f3d08fee213f2d041540fa4fc9ca6c2d44cf36d3a035bf2a8d2bcc/pyparsing-3.2.3-py3-none-any.whl", hash = "sha256:a749938e02d6fd0b59b356ca504a24982314bb090c383e3cf201c95ef7e2bfcf", size = 111120, upload-time = "2025-03-25T05:01:24.908Z" }, ] [[package]] name = "pyperclip" version = "1.9.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/30/23/2f0a3efc4d6a32f3b63cdff36cd398d9701d26cda58e3ab97ac79fb5e60d/pyperclip-1.9.0.tar.gz", hash = "sha256:b7de0142ddc81bfc5c7507eea19da920b92252b548b96186caf94a5e2527d310", size = 20961 } +sdist = { url = "https://files.pythonhosted.org/packages/30/23/2f0a3efc4d6a32f3b63cdff36cd398d9701d26cda58e3ab97ac79fb5e60d/pyperclip-1.9.0.tar.gz", hash = "sha256:b7de0142ddc81bfc5c7507eea19da920b92252b548b96186caf94a5e2527d310", size = 20961, upload-time = "2024-06-18T20:38:48.401Z" } [[package]] name = "pyprof2calltree" version = "1.4.5" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ca/2a/e9a76261183b4b5e059a6625d7aae0bcb0a77622bc767d4497148ce2e218/pyprof2calltree-1.4.5.tar.gz", hash = "sha256:a635672ff31677486350b2be9a823ef92f740e6354a6aeda8fa4a8a3768e8f2f", size = 10080 } +sdist = { url = "https://files.pythonhosted.org/packages/ca/2a/e9a76261183b4b5e059a6625d7aae0bcb0a77622bc767d4497148ce2e218/pyprof2calltree-1.4.5.tar.gz", hash = "sha256:a635672ff31677486350b2be9a823ef92f740e6354a6aeda8fa4a8a3768e8f2f", size = 10080, upload-time = "2020-04-19T10:39:09.819Z" } [[package]] name = "pyrect" version = "0.2.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/cb/04/2ba023d5f771b645f7be0c281cdacdcd939fe13d1deb331fc5ed1a6b3a98/PyRect-0.2.0.tar.gz", hash = "sha256:f65155f6df9b929b67caffbd57c0947c5ae5449d3b580d178074bffb47a09b78", size = 17219 } +sdist = { url = "https://files.pythonhosted.org/packages/cb/04/2ba023d5f771b645f7be0c281cdacdcd939fe13d1deb331fc5ed1a6b3a98/PyRect-0.2.0.tar.gz", hash = "sha256:f65155f6df9b929b67caffbd57c0947c5ae5449d3b580d178074bffb47a09b78", size = 17219, upload-time = "2022-03-16T04:45:52.36Z" } [[package]] name = "pyscreeze" @@ -4301,15 +4330,15 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pillow", marker = "python_full_version < '3.12'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ee/f0/cb456ac4f1a73723d5b866933b7986f02bacea27516629c00f8e7da94c2d/pyscreeze-1.0.1.tar.gz", hash = "sha256:cf1662710f1b46aa5ff229ee23f367da9e20af4a78e6e365bee973cad0ead4be", size = 27826 } +sdist = { url = "https://files.pythonhosted.org/packages/ee/f0/cb456ac4f1a73723d5b866933b7986f02bacea27516629c00f8e7da94c2d/pyscreeze-1.0.1.tar.gz", hash = "sha256:cf1662710f1b46aa5ff229ee23f367da9e20af4a78e6e365bee973cad0ead4be", size = 27826, upload-time = "2024-08-20T23:03:07.291Z" } [[package]] name = "pyserial" version = "3.5" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1e/7d/ae3f0a63f41e4d2f6cb66a5b57197850f919f59e558159a4dd3a818f5082/pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb", size = 159125 } +sdist = { url = "https://files.pythonhosted.org/packages/1e/7d/ae3f0a63f41e4d2f6cb66a5b57197850f919f59e558159a4dd3a818f5082/pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb", size = 159125, upload-time = "2020-11-23T03:59:15.045Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585 }, + { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585, upload-time = "2020-11-23T03:59:13.41Z" }, ] [[package]] @@ -4322,34 +4351,34 @@ dependencies = [ { name = "packaging" }, { name = "pluggy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ae/3c/c9d525a414d506893f0cd8a8d0de7706446213181570cdbd766691164e40/pytest-8.3.5.tar.gz", hash = "sha256:f4efe70cc14e511565ac476b57c279e12a855b11f48f212af1080ef2263d3845", size = 1450891 } +sdist = { url = "https://files.pythonhosted.org/packages/ae/3c/c9d525a414d506893f0cd8a8d0de7706446213181570cdbd766691164e40/pytest-8.3.5.tar.gz", hash = "sha256:f4efe70cc14e511565ac476b57c279e12a855b11f48f212af1080ef2263d3845", size = 1450891, upload-time = "2025-03-02T12:54:54.503Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/30/3d/64ad57c803f1fa1e963a7946b6e0fea4a70df53c1a7fed304586539c2bac/pytest-8.3.5-py3-none-any.whl", hash = "sha256:c69214aa47deac29fad6c2a4f590b9c4a9fdb16a403176fe154b79c0b4d4d820", size = 343634 }, + { url = "https://files.pythonhosted.org/packages/30/3d/64ad57c803f1fa1e963a7946b6e0fea4a70df53c1a7fed304586539c2bac/pytest-8.3.5-py3-none-any.whl", hash = "sha256:c69214aa47deac29fad6c2a4f590b9c4a9fdb16a403176fe154b79c0b4d4d820", size = 343634, upload-time = "2025-03-02T12:54:52.069Z" }, ] [[package]] name = "pytest-asyncio" -version = "0.25.3" +version = "0.26.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/f2/a8/ecbc8ede70921dd2f544ab1cadd3ff3bf842af27f87bbdea774c7baa1d38/pytest_asyncio-0.25.3.tar.gz", hash = "sha256:fc1da2cf9f125ada7e710b4ddad05518d4cee187ae9412e9ac9271003497f07a", size = 54239 } +sdist = { url = "https://files.pythonhosted.org/packages/8e/c4/453c52c659521066969523e87d85d54139bbd17b78f09532fb8eb8cdb58e/pytest_asyncio-0.26.0.tar.gz", hash = "sha256:c4df2a697648241ff39e7f0e4a73050b03f123f760673956cf0d72a4990e312f", size = 54156, upload-time = "2025-03-25T06:22:28.883Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/67/17/3493c5624e48fd97156ebaec380dcaafee9506d7e2c46218ceebbb57d7de/pytest_asyncio-0.25.3-py3-none-any.whl", hash = "sha256:9e89518e0f9bd08928f97a3482fdc4e244df17529460bc038291ccaf8f85c7c3", size = 19467 }, + { url = "https://files.pythonhosted.org/packages/20/7f/338843f449ace853647ace35870874f69a764d251872ed1b4de9f234822c/pytest_asyncio-0.26.0-py3-none-any.whl", hash = "sha256:7b51ed894f4fbea1340262bdae5135797ebbe21d8638978e35d31c6d19f72fb0", size = 19694, upload-time = "2025-03-25T06:22:27.807Z" }, ] [[package]] name = "pytest-cov" -version = "6.0.0" +version = "6.1.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coverage", extra = ["toml"] }, { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/be/45/9b538de8cef30e17c7b45ef42f538a94889ed6a16f2387a6c89e73220651/pytest-cov-6.0.0.tar.gz", hash = "sha256:fde0b595ca248bb8e2d76f020b465f3b107c9632e6a1d1705f17834c89dcadc0", size = 66945 } +sdist = { url = "https://files.pythonhosted.org/packages/25/69/5f1e57f6c5a39f81411b550027bf72842c4567ff5fd572bed1edc9e4b5d9/pytest_cov-6.1.1.tar.gz", hash = "sha256:46935f7aaefba760e716c2ebfbe1c216240b9592966e7da99ea8292d4d3e2a0a", size = 66857, upload-time = "2025-04-05T14:07:51.592Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/36/3b/48e79f2cd6a61dbbd4807b4ed46cb564b4fd50a76166b1c4ea5c1d9e2371/pytest_cov-6.0.0-py3-none-any.whl", hash = "sha256:eee6f1b9e61008bd34975a4d5bab25801eb31898b032dd55addc93e96fcaaa35", size = 22949 }, + { url = "https://files.pythonhosted.org/packages/28/d0/def53b4a790cfb21483016430ed828f64830dd981ebe1089971cd10cab25/pytest_cov-6.1.1-py3-none-any.whl", hash = "sha256:bddf29ed2d0ab6f4df17b4c55b0a657287db8684af9c42ea546b21b1041b3dde", size = 23841, upload-time = "2025-04-05T14:07:49.641Z" }, ] [[package]] @@ -4359,9 +4388,9 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/cf/a1/c2679d7ff2da20a0f89c7820ae2739cde739eac9b43c192531117b31b5f4/pytest_cpp-2.6.0.tar.gz", hash = "sha256:c2f49d3c038539ac84786a94d852e4f4619c34c95979c2bc69c20b3bdf051d85", size = 465490 } +sdist = { url = "https://files.pythonhosted.org/packages/cf/a1/c2679d7ff2da20a0f89c7820ae2739cde739eac9b43c192531117b31b5f4/pytest_cpp-2.6.0.tar.gz", hash = "sha256:c2f49d3c038539ac84786a94d852e4f4619c34c95979c2bc69c20b3bdf051d85", size = 465490, upload-time = "2024-09-18T00:08:08.251Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2a/44/dc2f5d53165264ae5831f361fe7723c45da05718a97015b2eddc452cf503/pytest_cpp-2.6.0-py3-none-any.whl", hash = "sha256:b33de94609450feea2fba9efff3558b8ac8f1fdf40a99e263b395d4798b911bb", size = 15074 }, + { url = "https://files.pythonhosted.org/packages/2a/44/dc2f5d53165264ae5831f361fe7723c45da05718a97015b2eddc452cf503/pytest_cpp-2.6.0-py3-none-any.whl", hash = "sha256:b33de94609450feea2fba9efff3558b8ac8f1fdf40a99e263b395d4798b911bb", size = 15074, upload-time = "2024-09-18T00:08:06.415Z" }, ] [[package]] @@ -4371,9 +4400,9 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c6/90/a955c3ab35ccd41ad4de556596fa86685bf4fc5ffcc62d22d856cfd4e29a/pytest-mock-3.14.0.tar.gz", hash = "sha256:2719255a1efeceadbc056d6bf3df3d1c5015530fb40cf347c0f9afac88410bd0", size = 32814 } +sdist = { url = "https://files.pythonhosted.org/packages/c6/90/a955c3ab35ccd41ad4de556596fa86685bf4fc5ffcc62d22d856cfd4e29a/pytest-mock-3.14.0.tar.gz", hash = "sha256:2719255a1efeceadbc056d6bf3df3d1c5015530fb40cf347c0f9afac88410bd0", size = 32814, upload-time = "2024-03-21T22:14:04.964Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f2/3b/b26f90f74e2986a82df6e7ac7e319b8ea7ccece1caec9f8ab6104dc70603/pytest_mock-3.14.0-py3-none-any.whl", hash = "sha256:0b72c38033392a5f4621342fe11e9219ac11ec9d375f8e2a0c164539e0d70f6f", size = 9863 }, + { url = "https://files.pythonhosted.org/packages/f2/3b/b26f90f74e2986a82df6e7ac7e319b8ea7ccece1caec9f8ab6104dc70603/pytest_mock-3.14.0-py3-none-any.whl", hash = "sha256:0b72c38033392a5f4621342fe11e9219ac11ec9d375f8e2a0c164539e0d70f6f", size = 9863, upload-time = "2024-03-21T22:14:02.694Z" }, ] [[package]] @@ -4383,21 +4412,21 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c0/68/d221ed7f4a2a49a664da721b8e87b52af6dd317af2a6cb51549cf17ac4b8/pytest_randomly-3.16.0.tar.gz", hash = "sha256:11bf4d23a26484de7860d82f726c0629837cf4064b79157bd18ec9d41d7feb26", size = 13367 } +sdist = { url = "https://files.pythonhosted.org/packages/c0/68/d221ed7f4a2a49a664da721b8e87b52af6dd317af2a6cb51549cf17ac4b8/pytest_randomly-3.16.0.tar.gz", hash = "sha256:11bf4d23a26484de7860d82f726c0629837cf4064b79157bd18ec9d41d7feb26", size = 13367, upload-time = "2024-10-25T15:45:34.274Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/22/70/b31577d7c46d8e2f9baccfed5067dd8475262a2331ffb0bfdf19361c9bde/pytest_randomly-3.16.0-py3-none-any.whl", hash = "sha256:8633d332635a1a0983d3bba19342196807f6afb17c3eef78e02c2f85dade45d6", size = 8396 }, + { url = "https://files.pythonhosted.org/packages/22/70/b31577d7c46d8e2f9baccfed5067dd8475262a2331ffb0bfdf19361c9bde/pytest_randomly-3.16.0-py3-none-any.whl", hash = "sha256:8633d332635a1a0983d3bba19342196807f6afb17c3eef78e02c2f85dade45d6", size = 8396, upload-time = "2024-10-25T15:45:32.78Z" }, ] [[package]] name = "pytest-repeat" -version = "0.9.3" +version = "0.9.4" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/86/5e/99365eb229efff0b1bd475886150fc6db9937ab7e1bd21f6f65c1279e0eb/pytest_repeat-0.9.3.tar.gz", hash = "sha256:ffd3836dfcd67bb270bec648b330e20be37d2966448c4148c4092d1e8aba8185", size = 6272 } +sdist = { url = "https://files.pythonhosted.org/packages/80/d4/69e9dbb9b8266df0b157c72be32083403c412990af15c7c15f7a3fd1b142/pytest_repeat-0.9.4.tar.gz", hash = "sha256:d92ac14dfaa6ffcfe6917e5d16f0c9bc82380c135b03c2a5f412d2637f224485", size = 6488, upload-time = "2025-04-07T14:59:53.077Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/49/a8/0a0aec0c2541b8baf4a0b95af2ba99abce217ee43534adf9cb7c908cf184/pytest_repeat-0.9.3-py3-none-any.whl", hash = "sha256:26ab2df18226af9d5ce441c858f273121e92ff55f5bb311d25755b8d7abdd8ed", size = 4196 }, + { url = "https://files.pythonhosted.org/packages/73/d4/8b706b81b07b43081bd68a2c0359fe895b74bf664b20aca8005d2bb3be71/pytest_repeat-0.9.4-py3-none-any.whl", hash = "sha256:c1738b4e412a6f3b3b9e0b8b29fcd7a423e50f87381ad9307ef6f5a8601139f3", size = 4180, upload-time = "2025-04-07T14:59:51.492Z" }, ] [[package]] @@ -4408,21 +4437,21 @@ dependencies = [ { name = "attrs" }, { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c0/4c/ba9eab21a2250c2d46c06c0e3cd316850fde9a90da0ac8d0202f074c6817/pytest_subtests-0.14.1.tar.gz", hash = "sha256:350c00adc36c3aff676a66135c81aed9e2182e15f6c3ec8721366918bbbf7580", size = 17632 } +sdist = { url = "https://files.pythonhosted.org/packages/c0/4c/ba9eab21a2250c2d46c06c0e3cd316850fde9a90da0ac8d0202f074c6817/pytest_subtests-0.14.1.tar.gz", hash = "sha256:350c00adc36c3aff676a66135c81aed9e2182e15f6c3ec8721366918bbbf7580", size = 17632, upload-time = "2024-12-10T00:21:04.856Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a9/b7/7ca948d35642ae72500efda6ba6fa61dcb6683feb596d19c4747c63c0789/pytest_subtests-0.14.1-py3-none-any.whl", hash = "sha256:e92a780d98b43118c28a16044ad9b841727bd7cb6a417073b38fd2d7ccdf052d", size = 8833 }, + { url = "https://files.pythonhosted.org/packages/a9/b7/7ca948d35642ae72500efda6ba6fa61dcb6683feb596d19c4747c63c0789/pytest_subtests-0.14.1-py3-none-any.whl", hash = "sha256:e92a780d98b43118c28a16044ad9b841727bd7cb6a417073b38fd2d7ccdf052d", size = 8833, upload-time = "2024-12-10T00:20:58.873Z" }, ] [[package]] name = "pytest-timeout" -version = "2.3.1" +version = "2.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/93/0d/04719abc7a4bdb3a7a1f968f24b0f5253d698c9cc94975330e9d3145befb/pytest-timeout-2.3.1.tar.gz", hash = "sha256:12397729125c6ecbdaca01035b9e5239d4db97352320af155b3f5de1ba5165d9", size = 17697 } +sdist = { url = "https://files.pythonhosted.org/packages/ac/82/4c9ecabab13363e72d880f2fb504c5f750433b2b6f16e99f4ec21ada284c/pytest_timeout-2.4.0.tar.gz", hash = "sha256:7e68e90b01f9eff71332b25001f85c75495fc4e3a836701876183c4bcfd0540a", size = 17973, upload-time = "2025-05-05T19:44:34.99Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/03/27/14af9ef8321f5edc7527e47def2a21d8118c6f329a9342cc61387a0c0599/pytest_timeout-2.3.1-py3-none-any.whl", hash = "sha256:68188cb703edfc6a18fad98dc25a3c61e9f24d644b0b70f33af545219fc7813e", size = 14148 }, + { url = "https://files.pythonhosted.org/packages/fa/b6/3127540ecdf1464a00e5a01ee60a1b09175f6913f0644ac748494d9c4b21/pytest_timeout-2.4.0-py3-none-any.whl", hash = "sha256:c42667e5cdadb151aeb5b26d114aff6bdf5a907f176a007a30b940d3d865b5c2", size = 14382, upload-time = "2025-05-05T19:44:33.502Z" }, ] [[package]] @@ -4433,9 +4462,9 @@ dependencies = [ { name = "execnet" }, { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/41/c4/3c310a19bc1f1e9ef50075582652673ef2bfc8cd62afef9585683821902f/pytest_xdist-3.6.1.tar.gz", hash = "sha256:ead156a4db231eec769737f57668ef58a2084a34b2e55c4a8fa20d861107300d", size = 84060 } +sdist = { url = "https://files.pythonhosted.org/packages/41/c4/3c310a19bc1f1e9ef50075582652673ef2bfc8cd62afef9585683821902f/pytest_xdist-3.6.1.tar.gz", hash = "sha256:ead156a4db231eec769737f57668ef58a2084a34b2e55c4a8fa20d861107300d", size = 84060, upload-time = "2024-04-28T19:29:54.414Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6d/82/1d96bf03ee4c0fdc3c0cbe61470070e659ca78dc0086fb88b66c185e2449/pytest_xdist-3.6.1-py3-none-any.whl", hash = "sha256:9ed4adfb68a016610848639bb7e02c9352d5d9f03d04809919e2dafc3be4cca7", size = 46108 }, + { url = "https://files.pythonhosted.org/packages/6d/82/1d96bf03ee4c0fdc3c0cbe61470070e659ca78dc0086fb88b66c185e2449/pytest_xdist-3.6.1-py3-none-any.whl", hash = "sha256:9ed4adfb68a016610848639bb7e02c9352d5d9f03d04809919e2dafc3be4cca7", size = 46108, upload-time = "2024-04-28T19:29:52.813Z" }, ] [[package]] @@ -4445,9 +4474,9 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "six" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/66/c0/0c8b6ad9f17a802ee498c46e004a0eb49bc148f2fd230864601a86dcf6db/python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3", size = 342432 } +sdist = { url = "https://files.pythonhosted.org/packages/66/c0/0c8b6ad9f17a802ee498c46e004a0eb49bc148f2fd230864601a86dcf6db/python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3", size = 342432, upload-time = "2024-03-01T18:36:20.211Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ec/57/56b9bcc3c9c6a792fcbaf139543cee77261f3651ca9da0c93f5c1221264b/python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427", size = 229892 }, + { url = "https://files.pythonhosted.org/packages/ec/57/56b9bcc3c9c6a792fcbaf139543cee77261f3651ca9da0c93f5c1221264b/python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427", size = 229892, upload-time = "2024-03-01T18:36:18.57Z" }, ] [[package]] @@ -4455,50 +4484,50 @@ name = "python-xlib" version = "0.33" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "six", marker = "sys_platform != 'darwin'" }, + { name = "six" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/86/f5/8c0653e5bb54e0cbdfe27bf32d41f27bc4e12faa8742778c17f2a71be2c0/python-xlib-0.33.tar.gz", hash = "sha256:55af7906a2c75ce6cb280a584776080602444f75815a7aff4d287bb2d7018b32", size = 269068 } +sdist = { url = "https://files.pythonhosted.org/packages/86/f5/8c0653e5bb54e0cbdfe27bf32d41f27bc4e12faa8742778c17f2a71be2c0/python-xlib-0.33.tar.gz", hash = "sha256:55af7906a2c75ce6cb280a584776080602444f75815a7aff4d287bb2d7018b32", size = 269068, upload-time = "2022-12-25T18:53:00.824Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/fc/b8/ff33610932e0ee81ae7f1269c890f697d56ff74b9f5b2ee5d9b7fa2c5355/python_xlib-0.33-py2.py3-none-any.whl", hash = "sha256:c3534038d42e0df2f1392a1b30a15a4ff5fdc2b86cfa94f072bf11b10a164398", size = 182185 }, + { url = "https://files.pythonhosted.org/packages/fc/b8/ff33610932e0ee81ae7f1269c890f697d56ff74b9f5b2ee5d9b7fa2c5355/python_xlib-0.33-py2.py3-none-any.whl", hash = "sha256:c3534038d42e0df2f1392a1b30a15a4ff5fdc2b86cfa94f072bf11b10a164398", size = 182185, upload-time = "2022-12-25T18:52:58.662Z" }, ] [[package]] name = "python3-xlib" version = "0.15" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ef/c6/2c5999de3bb1533521f1101e8fe56fd9c266732f4d48011c7c69b29d12ae/python3-xlib-0.15.tar.gz", hash = "sha256:dc4245f3ae4aa5949c1d112ee4723901ade37a96721ba9645f2bfa56e5b383f8", size = 132828 } +sdist = { url = "https://files.pythonhosted.org/packages/ef/c6/2c5999de3bb1533521f1101e8fe56fd9c266732f4d48011c7c69b29d12ae/python3-xlib-0.15.tar.gz", hash = "sha256:dc4245f3ae4aa5949c1d112ee4723901ade37a96721ba9645f2bfa56e5b383f8", size = 132828, upload-time = "2014-05-31T12:28:59.603Z" } [[package]] name = "pytools" version = "2024.1.10" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "platformdirs", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "siphash24", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, - { name = "typing-extensions", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "platformdirs" }, + { name = "siphash24" }, + { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ee/0f/56e109c0307f831b5d598ad73976aaaa84b4d0e98da29a642e797eaa940c/pytools-2024.1.10.tar.gz", hash = "sha256:9af6f4b045212c49be32bb31fe19606c478ee4b09631886d05a32459f4ce0a12", size = 81741 } +sdist = { url = "https://files.pythonhosted.org/packages/ee/0f/56e109c0307f831b5d598ad73976aaaa84b4d0e98da29a642e797eaa940c/pytools-2024.1.10.tar.gz", hash = "sha256:9af6f4b045212c49be32bb31fe19606c478ee4b09631886d05a32459f4ce0a12", size = 81741, upload-time = "2024-07-17T18:47:38.287Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/66/cf/0a6aaa44b1f9e02b8c0648b5665a82246a93bcc75224c167b4fafa25c093/pytools-2024.1.10-py3-none-any.whl", hash = "sha256:9cabb71038048291400e244e2da441a051d86053339bc484e64e58d8ea263f44", size = 88108 }, + { url = "https://files.pythonhosted.org/packages/66/cf/0a6aaa44b1f9e02b8c0648b5665a82246a93bcc75224c167b4fafa25c093/pytools-2024.1.10-py3-none-any.whl", hash = "sha256:9cabb71038048291400e244e2da441a051d86053339bc484e64e58d8ea263f44", size = 88108, upload-time = "2024-07-17T18:47:36.173Z" }, ] [[package]] name = "pytweening" version = "1.2.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/79/0c/c16bc93ac2755bac0066a8ecbd2a2931a1735a6fffd99a2b9681c7e83e90/pytweening-1.2.0.tar.gz", hash = "sha256:243318b7736698066c5f362ec5c2b6434ecf4297c3c8e7caa8abfe6af4cac71b", size = 171241 } +sdist = { url = "https://files.pythonhosted.org/packages/79/0c/c16bc93ac2755bac0066a8ecbd2a2931a1735a6fffd99a2b9681c7e83e90/pytweening-1.2.0.tar.gz", hash = "sha256:243318b7736698066c5f362ec5c2b6434ecf4297c3c8e7caa8abfe6af4cac71b", size = 171241, upload-time = "2024-02-20T03:37:56.809Z" } [[package]] name = "pywin32" -version = "309" +version = "310" source = { registry = "https://pypi.org/simple" } wheels = [ - { url = "https://files.pythonhosted.org/packages/05/54/6409b1d98f2b8fed3bc2cc854859e48ae4a2dd956176664e38ee49c50a4c/pywin32-309-cp311-cp311-win32.whl", hash = "sha256:d5df6faa32b868baf9ade7c9b25337fa5eced28eb1ab89082c8dae9c48e4cd51", size = 8779225 }, - { url = "https://files.pythonhosted.org/packages/6a/f0/ae8ddb56771093dd2905baa852958fd65d42a8972aeefcf13578dfae69f4/pywin32-309-cp311-cp311-win_amd64.whl", hash = "sha256:e7ec2cef6df0926f8a89fd64959eba591a1eeaf0258082065f7bdbe2121228db", size = 9514129 }, - { url = "https://files.pythonhosted.org/packages/7a/4b/1f5e377a04448cf410e13040bc0e4c408bfa0a65705cabf96904178f18df/pywin32-309-cp311-cp311-win_arm64.whl", hash = "sha256:54ee296f6d11db1627216e9b4d4c3231856ed2d9f194c82f26c6cb5650163f4c", size = 8450450 }, - { url = "https://files.pythonhosted.org/packages/20/2c/b0240b14ff3dba7a8a7122dc9bbf7fbd21ed0e8b57c109633675b5d1761f/pywin32-309-cp312-cp312-win32.whl", hash = "sha256:de9acacced5fa82f557298b1fed5fef7bd49beee04190f68e1e4783fbdc19926", size = 8790648 }, - { url = "https://files.pythonhosted.org/packages/dd/11/c36884c732e2b3397deee808b5dac1abbb170ec37f94c6606fcb04d1e9d7/pywin32-309-cp312-cp312-win_amd64.whl", hash = "sha256:6ff9eebb77ffc3d59812c68db33c0a7817e1337e3537859499bd27586330fc9e", size = 9497399 }, - { url = "https://files.pythonhosted.org/packages/18/9f/79703972958f8ba3fd38bc9bf1165810bd75124982419b0cc433a2894d46/pywin32-309-cp312-cp312-win_arm64.whl", hash = "sha256:619f3e0a327b5418d833f44dc87859523635cf339f86071cc65a13c07be3110f", size = 8454122 }, + { url = "https://files.pythonhosted.org/packages/f7/b1/68aa2986129fb1011dabbe95f0136f44509afaf072b12b8f815905a39f33/pywin32-310-cp311-cp311-win32.whl", hash = "sha256:1e765f9564e83011a63321bb9d27ec456a0ed90d3732c4b2e312b855365ed8bd", size = 8784284, upload-time = "2025-03-17T00:55:53.124Z" }, + { url = "https://files.pythonhosted.org/packages/b3/bd/d1592635992dd8db5bb8ace0551bc3a769de1ac8850200cfa517e72739fb/pywin32-310-cp311-cp311-win_amd64.whl", hash = "sha256:126298077a9d7c95c53823934f000599f66ec9296b09167810eb24875f32689c", size = 9520748, upload-time = "2025-03-17T00:55:55.203Z" }, + { url = "https://files.pythonhosted.org/packages/90/b1/ac8b1ffce6603849eb45a91cf126c0fa5431f186c2e768bf56889c46f51c/pywin32-310-cp311-cp311-win_arm64.whl", hash = "sha256:19ec5fc9b1d51c4350be7bb00760ffce46e6c95eaf2f0b2f1150657b1a43c582", size = 8455941, upload-time = "2025-03-17T00:55:57.048Z" }, + { url = "https://files.pythonhosted.org/packages/6b/ec/4fdbe47932f671d6e348474ea35ed94227fb5df56a7c30cbbb42cd396ed0/pywin32-310-cp312-cp312-win32.whl", hash = "sha256:8a75a5cc3893e83a108c05d82198880704c44bbaee4d06e442e471d3c9ea4f3d", size = 8796239, upload-time = "2025-03-17T00:55:58.807Z" }, + { url = "https://files.pythonhosted.org/packages/e3/e5/b0627f8bb84e06991bea89ad8153a9e50ace40b2e1195d68e9dff6b03d0f/pywin32-310-cp312-cp312-win_amd64.whl", hash = "sha256:bf5c397c9a9a19a6f62f3fb821fbf36cac08f03770056711f765ec1503972060", size = 9503839, upload-time = "2025-03-17T00:56:00.8Z" }, + { url = "https://files.pythonhosted.org/packages/1f/32/9ccf53748df72301a89713936645a664ec001abd35ecc8578beda593d37d/pywin32-310-cp312-cp312-win_arm64.whl", hash = "sha256:2349cc906eae872d0663d4d6290d13b90621eaf78964bb1578632ff20e152966", size = 8459470, upload-time = "2025-03-17T00:56:02.601Z" }, ] [[package]] @@ -4513,7 +4542,7 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/b1/37/d59397221e15d2a7f38afaa4e8e6b8c244d818044f7daa0bdc5988df0a69/PyWinBox-0.7-py3-none-any.whl", hash = "sha256:8b2506a8dd7afa0a910b368762adfac885274132ef9151b0c81b0d2c6ffd6f83", size = 12274 }, + { url = "https://files.pythonhosted.org/packages/b1/37/d59397221e15d2a7f38afaa4e8e6b8c244d818044f7daa0bdc5988df0a69/PyWinBox-0.7-py3-none-any.whl", hash = "sha256:8b2506a8dd7afa0a910b368762adfac885274132ef9151b0c81b0d2c6ffd6f83", size = 12274, upload-time = "2024-04-17T10:10:31.899Z" }, ] [[package]] @@ -4530,80 +4559,83 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/be/33/8e4f632210b28fc9e998a9ab990e7ed97ecd2800cc50038e3800e1d85dbe/PyWinCtl-0.4.1-py3-none-any.whl", hash = "sha256:4d875e22969e1c6239d8c73156193630aaab876366167b8d97716f956384b089", size = 63158 }, + { url = "https://files.pythonhosted.org/packages/be/33/8e4f632210b28fc9e998a9ab990e7ed97ecd2800cc50038e3800e1d85dbe/PyWinCtl-0.4.1-py3-none-any.whl", hash = "sha256:4d875e22969e1c6239d8c73156193630aaab876366167b8d97716f956384b089", size = 63158, upload-time = "2024-09-23T08:33:39.881Z" }, ] [[package]] name = "pyyaml" version = "6.0.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/54/ed/79a089b6be93607fa5cdaedf301d7dfb23af5f25c398d5ead2525b063e17/pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e", size = 130631 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/f8/aa/7af4e81f7acba21a4c6be026da38fd2b872ca46226673c89a758ebdc4fd2/PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774", size = 184612 }, - { url = "https://files.pythonhosted.org/packages/8b/62/b9faa998fd185f65c1371643678e4d58254add437edb764a08c5a98fb986/PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee", size = 172040 }, - { url = "https://files.pythonhosted.org/packages/ad/0c/c804f5f922a9a6563bab712d8dcc70251e8af811fce4524d57c2c0fd49a4/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c", size = 736829 }, - { url = "https://files.pythonhosted.org/packages/51/16/6af8d6a6b210c8e54f1406a6b9481febf9c64a3109c541567e35a49aa2e7/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317", size = 764167 }, - { url = "https://files.pythonhosted.org/packages/75/e4/2c27590dfc9992f73aabbeb9241ae20220bd9452df27483b6e56d3975cc5/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85", size = 762952 }, - { url = "https://files.pythonhosted.org/packages/9b/97/ecc1abf4a823f5ac61941a9c00fe501b02ac3ab0e373c3857f7d4b83e2b6/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4", size = 735301 }, - { url = "https://files.pythonhosted.org/packages/45/73/0f49dacd6e82c9430e46f4a027baa4ca205e8b0a9dce1397f44edc23559d/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e", size = 756638 }, - { url = "https://files.pythonhosted.org/packages/22/5f/956f0f9fc65223a58fbc14459bf34b4cc48dec52e00535c79b8db361aabd/PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5", size = 143850 }, - { url = "https://files.pythonhosted.org/packages/ed/23/8da0bbe2ab9dcdd11f4f4557ccaf95c10b9811b13ecced089d43ce59c3c8/PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44", size = 161980 }, - { url = "https://files.pythonhosted.org/packages/86/0c/c581167fc46d6d6d7ddcfb8c843a4de25bdd27e4466938109ca68492292c/PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab", size = 183873 }, - { url = "https://files.pythonhosted.org/packages/a8/0c/38374f5bb272c051e2a69281d71cba6fdb983413e6758b84482905e29a5d/PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725", size = 173302 }, - { url = "https://files.pythonhosted.org/packages/c3/93/9916574aa8c00aa06bbac729972eb1071d002b8e158bd0e83a3b9a20a1f7/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5", size = 739154 }, - { url = "https://files.pythonhosted.org/packages/95/0f/b8938f1cbd09739c6da569d172531567dbcc9789e0029aa070856f123984/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425", size = 766223 }, - { url = "https://files.pythonhosted.org/packages/b9/2b/614b4752f2e127db5cc206abc23a8c19678e92b23c3db30fc86ab731d3bd/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476", size = 767542 }, - { url = "https://files.pythonhosted.org/packages/d4/00/dd137d5bcc7efea1836d6264f049359861cf548469d18da90cd8216cf05f/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48", size = 731164 }, - { url = "https://files.pythonhosted.org/packages/c9/1f/4f998c900485e5c0ef43838363ba4a9723ac0ad73a9dc42068b12aaba4e4/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b", size = 756611 }, - { url = "https://files.pythonhosted.org/packages/df/d1/f5a275fdb252768b7a11ec63585bc38d0e87c9e05668a139fea92b80634c/PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4", size = 140591 }, - { url = "https://files.pythonhosted.org/packages/0c/e8/4f648c598b17c3d06e8753d7d13d57542b30d56e6c2dedf9c331ae56312e/PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8", size = 156338 }, +sdist = { url = "https://files.pythonhosted.org/packages/54/ed/79a089b6be93607fa5cdaedf301d7dfb23af5f25c398d5ead2525b063e17/pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e", size = 130631, upload-time = "2024-08-06T20:33:50.674Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/f8/aa/7af4e81f7acba21a4c6be026da38fd2b872ca46226673c89a758ebdc4fd2/PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774", size = 184612, upload-time = "2024-08-06T20:32:03.408Z" }, + { url = "https://files.pythonhosted.org/packages/8b/62/b9faa998fd185f65c1371643678e4d58254add437edb764a08c5a98fb986/PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee", size = 172040, upload-time = "2024-08-06T20:32:04.926Z" }, + { url = "https://files.pythonhosted.org/packages/ad/0c/c804f5f922a9a6563bab712d8dcc70251e8af811fce4524d57c2c0fd49a4/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c", size = 736829, upload-time = "2024-08-06T20:32:06.459Z" }, + { url = "https://files.pythonhosted.org/packages/51/16/6af8d6a6b210c8e54f1406a6b9481febf9c64a3109c541567e35a49aa2e7/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317", size = 764167, upload-time = "2024-08-06T20:32:08.338Z" }, + { url = "https://files.pythonhosted.org/packages/75/e4/2c27590dfc9992f73aabbeb9241ae20220bd9452df27483b6e56d3975cc5/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85", size = 762952, upload-time = "2024-08-06T20:32:14.124Z" }, + { url = "https://files.pythonhosted.org/packages/9b/97/ecc1abf4a823f5ac61941a9c00fe501b02ac3ab0e373c3857f7d4b83e2b6/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4", size = 735301, upload-time = "2024-08-06T20:32:16.17Z" }, + { url = "https://files.pythonhosted.org/packages/45/73/0f49dacd6e82c9430e46f4a027baa4ca205e8b0a9dce1397f44edc23559d/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e", size = 756638, upload-time = "2024-08-06T20:32:18.555Z" }, + { url = "https://files.pythonhosted.org/packages/22/5f/956f0f9fc65223a58fbc14459bf34b4cc48dec52e00535c79b8db361aabd/PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5", size = 143850, upload-time = "2024-08-06T20:32:19.889Z" }, + { url = "https://files.pythonhosted.org/packages/ed/23/8da0bbe2ab9dcdd11f4f4557ccaf95c10b9811b13ecced089d43ce59c3c8/PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44", size = 161980, upload-time = "2024-08-06T20:32:21.273Z" }, + { url = "https://files.pythonhosted.org/packages/86/0c/c581167fc46d6d6d7ddcfb8c843a4de25bdd27e4466938109ca68492292c/PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab", size = 183873, upload-time = "2024-08-06T20:32:25.131Z" }, + { url = "https://files.pythonhosted.org/packages/a8/0c/38374f5bb272c051e2a69281d71cba6fdb983413e6758b84482905e29a5d/PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725", size = 173302, upload-time = "2024-08-06T20:32:26.511Z" }, + { url = "https://files.pythonhosted.org/packages/c3/93/9916574aa8c00aa06bbac729972eb1071d002b8e158bd0e83a3b9a20a1f7/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5", size = 739154, upload-time = "2024-08-06T20:32:28.363Z" }, + { url = "https://files.pythonhosted.org/packages/95/0f/b8938f1cbd09739c6da569d172531567dbcc9789e0029aa070856f123984/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425", size = 766223, upload-time = "2024-08-06T20:32:30.058Z" }, + { url = "https://files.pythonhosted.org/packages/b9/2b/614b4752f2e127db5cc206abc23a8c19678e92b23c3db30fc86ab731d3bd/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476", size = 767542, upload-time = "2024-08-06T20:32:31.881Z" }, + { url = "https://files.pythonhosted.org/packages/d4/00/dd137d5bcc7efea1836d6264f049359861cf548469d18da90cd8216cf05f/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48", size = 731164, upload-time = "2024-08-06T20:32:37.083Z" }, + { url = "https://files.pythonhosted.org/packages/c9/1f/4f998c900485e5c0ef43838363ba4a9723ac0ad73a9dc42068b12aaba4e4/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b", size = 756611, upload-time = "2024-08-06T20:32:38.898Z" }, + { url = "https://files.pythonhosted.org/packages/df/d1/f5a275fdb252768b7a11ec63585bc38d0e87c9e05668a139fea92b80634c/PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4", size = 140591, upload-time = "2024-08-06T20:32:40.241Z" }, + { url = "https://files.pythonhosted.org/packages/0c/e8/4f648c598b17c3d06e8753d7d13d57542b30d56e6c2dedf9c331ae56312e/PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8", size = 156338, upload-time = "2024-08-06T20:32:41.93Z" }, ] [[package]] name = "pyyaml-env-tag" -version = "0.1" +version = "1.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pyyaml" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/fb/8e/da1c6c58f751b70f8ceb1eb25bc25d524e8f14fe16edcce3f4e3ba08629c/pyyaml_env_tag-0.1.tar.gz", hash = "sha256:70092675bda14fdec33b31ba77e7543de9ddc88f2e5b99160396572d11525bdb", size = 5631 } +sdist = { url = "https://files.pythonhosted.org/packages/eb/2e/79c822141bfd05a853236b504869ebc6b70159afc570e1d5a20641782eaa/pyyaml_env_tag-1.1.tar.gz", hash = "sha256:2eb38b75a2d21ee0475d6d97ec19c63287a7e140231e4214969d0eac923cd7ff", size = 5737, upload-time = "2025-05-13T15:24:01.64Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5a/66/bbb1dd374f5c870f59c5bb1db0e18cbe7fa739415a24cbd95b2d1f5ae0c4/pyyaml_env_tag-0.1-py3-none-any.whl", hash = "sha256:af31106dec8a4d68c60207c1886031cbf839b68aa7abccdb19868200532c2069", size = 3911 }, + { url = "https://files.pythonhosted.org/packages/04/11/432f32f8097b03e3cd5fe57e88efb685d964e2e5178a48ed61e841f7fdce/pyyaml_env_tag-1.1-py3-none-any.whl", hash = "sha256:17109e1a528561e32f026364712fee1264bc2ea6715120891174ed1b980d2e04", size = 4722, upload-time = "2025-05-13T15:23:59.629Z" }, ] [[package]] name = "pyzmq" -version = "26.2.1" +version = "26.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi", marker = "implementation_name == 'pypy'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5a/e3/8d0382cb59feb111c252b54e8728257416a38ffcb2243c4e4775a3c990fe/pyzmq-26.2.1.tar.gz", hash = "sha256:17d72a74e5e9ff3829deb72897a175333d3ef5b5413948cae3cf7ebf0b02ecca", size = 278433 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/b9/03/5ecc46a6ed5971299f5c03e016ca637802d8660e44392bea774fb7797405/pyzmq-26.2.1-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:c059883840e634a21c5b31d9b9a0e2b48f991b94d60a811092bc37992715146a", size = 1346032 }, - { url = "https://files.pythonhosted.org/packages/40/51/48fec8f990ee644f461ff14c8fe5caa341b0b9b3a0ad7544f8ef17d6f528/pyzmq-26.2.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ed038a921df836d2f538e509a59cb638df3e70ca0fcd70d0bf389dfcdf784d2a", size = 943324 }, - { url = "https://files.pythonhosted.org/packages/c1/f4/f322b389727c687845e38470b48d7a43c18a83f26d4d5084603c6c3f79ca/pyzmq-26.2.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9027a7fcf690f1a3635dc9e55e38a0d6602dbbc0548935d08d46d2e7ec91f454", size = 678418 }, - { url = "https://files.pythonhosted.org/packages/a8/df/2834e3202533bd05032d83e02db7ac09fa1be853bbef59974f2b2e3a8557/pyzmq-26.2.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6d75fcb00a1537f8b0c0bb05322bc7e35966148ffc3e0362f0369e44a4a1de99", size = 915466 }, - { url = "https://files.pythonhosted.org/packages/b5/e2/45c0f6e122b562cb8c6c45c0dcac1160a4e2207385ef9b13463e74f93031/pyzmq-26.2.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f0019cc804ac667fb8c8eaecdb66e6d4a68acf2e155d5c7d6381a5645bd93ae4", size = 873347 }, - { url = "https://files.pythonhosted.org/packages/de/b9/3e0fbddf8b87454e914501d368171466a12550c70355b3844115947d68ea/pyzmq-26.2.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:f19dae58b616ac56b96f2e2290f2d18730a898a171f447f491cc059b073ca1fa", size = 874545 }, - { url = "https://files.pythonhosted.org/packages/1f/1c/1ee41d6e10b2127263b1994bc53b9e74ece015b0d2c0a30e0afaf69b78b2/pyzmq-26.2.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:f5eeeb82feec1fc5cbafa5ee9022e87ffdb3a8c48afa035b356fcd20fc7f533f", size = 1208630 }, - { url = "https://files.pythonhosted.org/packages/3d/a9/50228465c625851a06aeee97c74f253631f509213f979166e83796299c60/pyzmq-26.2.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:000760e374d6f9d1a3478a42ed0c98604de68c9e94507e5452951e598ebecfba", size = 1519568 }, - { url = "https://files.pythonhosted.org/packages/c6/f2/6360b619e69da78863c2108beb5196ae8b955fe1e161c0b886b95dc6b1ac/pyzmq-26.2.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:817fcd3344d2a0b28622722b98500ae9c8bfee0f825b8450932ff19c0b15bebd", size = 1419677 }, - { url = "https://files.pythonhosted.org/packages/da/d5/f179da989168f5dfd1be8103ef508ade1d38a8078dda4f10ebae3131a490/pyzmq-26.2.1-cp311-cp311-win32.whl", hash = "sha256:88812b3b257f80444a986b3596e5ea5c4d4ed4276d2b85c153a6fbc5ca457ae7", size = 582682 }, - { url = "https://files.pythonhosted.org/packages/60/50/e5b2e9de3ffab73ff92bee736216cf209381081fa6ab6ba96427777d98b1/pyzmq-26.2.1-cp311-cp311-win_amd64.whl", hash = "sha256:ef29630fde6022471d287c15c0a2484aba188adbfb978702624ba7a54ddfa6c1", size = 648128 }, - { url = "https://files.pythonhosted.org/packages/d9/fe/7bb93476dd8405b0fc9cab1fd921a08bd22d5e3016aa6daea1a78d54129b/pyzmq-26.2.1-cp311-cp311-win_arm64.whl", hash = "sha256:f32718ee37c07932cc336096dc7403525301fd626349b6eff8470fe0f996d8d7", size = 562465 }, - { url = "https://files.pythonhosted.org/packages/9c/b9/260a74786f162c7f521f5f891584a51d5a42fd15f5dcaa5c9226b2865fcc/pyzmq-26.2.1-cp312-cp312-macosx_10_15_universal2.whl", hash = "sha256:a6549ecb0041dafa55b5932dcbb6c68293e0bd5980b5b99f5ebb05f9a3b8a8f3", size = 1348495 }, - { url = "https://files.pythonhosted.org/packages/bf/73/8a0757e4b68f5a8ccb90ddadbb76c6a5f880266cdb18be38c99bcdc17aaa/pyzmq-26.2.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:0250c94561f388db51fd0213cdccbd0b9ef50fd3c57ce1ac937bf3034d92d72e", size = 945035 }, - { url = "https://files.pythonhosted.org/packages/cf/de/f02ec973cd33155bb772bae33ace774acc7cc71b87b25c4829068bec35de/pyzmq-26.2.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:36ee4297d9e4b34b5dc1dd7ab5d5ea2cbba8511517ef44104d2915a917a56dc8", size = 671213 }, - { url = "https://files.pythonhosted.org/packages/d1/80/8fc583085f85ac91682744efc916888dd9f11f9f75a31aef1b78a5486c6c/pyzmq-26.2.1-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c2a9cb17fd83b7a3a3009901aca828feaf20aa2451a8a487b035455a86549c09", size = 908750 }, - { url = "https://files.pythonhosted.org/packages/c3/25/0b4824596f261a3cc512ab152448b383047ff5f143a6906a36876415981c/pyzmq-26.2.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:786dd8a81b969c2081b31b17b326d3a499ddd1856e06d6d79ad41011a25148da", size = 865416 }, - { url = "https://files.pythonhosted.org/packages/a1/d1/6fda77a034d02034367b040973fd3861d945a5347e607bd2e98c99f20599/pyzmq-26.2.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:2d88ba221a07fc2c5581565f1d0fe8038c15711ae79b80d9462e080a1ac30435", size = 865922 }, - { url = "https://files.pythonhosted.org/packages/ad/81/48f7fd8a71c427412e739ce576fc1ee14f3dc34527ca9b0076e471676183/pyzmq-26.2.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:1c84c1297ff9f1cd2440da4d57237cb74be21fdfe7d01a10810acba04e79371a", size = 1201526 }, - { url = "https://files.pythonhosted.org/packages/c7/d8/818f15c6ef36b5450e435cbb0d3a51599fc884a5d2b27b46b9c00af68ef1/pyzmq-26.2.1-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:46d4ebafc27081a7f73a0f151d0c38d4291656aa134344ec1f3d0199ebfbb6d4", size = 1512808 }, - { url = "https://files.pythonhosted.org/packages/d9/c4/b3edb7d0ae82ad6fb1a8cdb191a4113c427a01e85139906f3b655b07f4f8/pyzmq-26.2.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:91e2bfb8e9a29f709d51b208dd5f441dc98eb412c8fe75c24ea464734ccdb48e", size = 1411836 }, - { url = "https://files.pythonhosted.org/packages/69/1c/151e3d42048f02cc5cd6dfc241d9d36b38375b4dee2e728acb5c353a6d52/pyzmq-26.2.1-cp312-cp312-win32.whl", hash = "sha256:4a98898fdce380c51cc3e38ebc9aa33ae1e078193f4dc641c047f88b8c690c9a", size = 581378 }, - { url = "https://files.pythonhosted.org/packages/b6/b9/d59a7462848aaab7277fddb253ae134a570520115d80afa85e952287e6bc/pyzmq-26.2.1-cp312-cp312-win_amd64.whl", hash = "sha256:a0741edbd0adfe5f30bba6c5223b78c131b5aa4a00a223d631e5ef36e26e6d13", size = 643737 }, - { url = "https://files.pythonhosted.org/packages/55/09/f37e707937cce328944c1d57e5e50ab905011d35252a0745c4f7e5822a76/pyzmq-26.2.1-cp312-cp312-win_arm64.whl", hash = "sha256:e5e33b1491555843ba98d5209439500556ef55b6ab635f3a01148545498355e5", size = 558303 }, +sdist = { url = "https://files.pythonhosted.org/packages/b1/11/b9213d25230ac18a71b39b3723494e57adebe36e066397b961657b3b41c1/pyzmq-26.4.0.tar.gz", hash = "sha256:4bd13f85f80962f91a651a7356fe0472791a5f7a92f227822b5acf44795c626d", size = 278293, upload-time = "2025-04-04T12:05:44.049Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/32/6d/234e3b0aa82fd0290b1896e9992f56bdddf1f97266110be54d0177a9d2d9/pyzmq-26.4.0-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:bfcf82644c9b45ddd7cd2a041f3ff8dce4a0904429b74d73a439e8cab1bd9e54", size = 1339723, upload-time = "2025-04-04T12:03:24.358Z" }, + { url = "https://files.pythonhosted.org/packages/4f/11/6d561efe29ad83f7149a7cd48e498e539ed09019c6cd7ecc73f4cc725028/pyzmq-26.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e9bcae3979b2654d5289d3490742378b2f3ce804b0b5fd42036074e2bf35b030", size = 672645, upload-time = "2025-04-04T12:03:25.693Z" }, + { url = "https://files.pythonhosted.org/packages/19/fd/81bfe3e23f418644660bad1a90f0d22f0b3eebe33dd65a79385530bceb3d/pyzmq-26.4.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ccdff8ac4246b6fb60dcf3982dfaeeff5dd04f36051fe0632748fc0aa0679c01", size = 910133, upload-time = "2025-04-04T12:03:27.625Z" }, + { url = "https://files.pythonhosted.org/packages/97/68/321b9c775595ea3df832a9516252b653fe32818db66fdc8fa31c9b9fce37/pyzmq-26.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4550af385b442dc2d55ab7717837812799d3674cb12f9a3aa897611839c18e9e", size = 867428, upload-time = "2025-04-04T12:03:29.004Z" }, + { url = "https://files.pythonhosted.org/packages/4e/6e/159cbf2055ef36aa2aa297e01b24523176e5b48ead283c23a94179fb2ba2/pyzmq-26.4.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:2f9f7ffe9db1187a253fca95191854b3fda24696f086e8789d1d449308a34b88", size = 862409, upload-time = "2025-04-04T12:03:31.032Z" }, + { url = "https://files.pythonhosted.org/packages/05/1c/45fb8db7be5a7d0cadea1070a9cbded5199a2d578de2208197e592f219bd/pyzmq-26.4.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:3709c9ff7ba61589b7372923fd82b99a81932b592a5c7f1a24147c91da9a68d6", size = 1205007, upload-time = "2025-04-04T12:03:32.687Z" }, + { url = "https://files.pythonhosted.org/packages/f8/fa/658c7f583af6498b463f2fa600f34e298e1b330886f82f1feba0dc2dd6c3/pyzmq-26.4.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:f8f3c30fb2d26ae5ce36b59768ba60fb72507ea9efc72f8f69fa088450cff1df", size = 1514599, upload-time = "2025-04-04T12:03:34.084Z" }, + { url = "https://files.pythonhosted.org/packages/4d/d7/44d641522353ce0a2bbd150379cb5ec32f7120944e6bfba4846586945658/pyzmq-26.4.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:382a4a48c8080e273427fc692037e3f7d2851959ffe40864f2db32646eeb3cef", size = 1414546, upload-time = "2025-04-04T12:03:35.478Z" }, + { url = "https://files.pythonhosted.org/packages/72/76/c8ed7263218b3d1e9bce07b9058502024188bd52cc0b0a267a9513b431fc/pyzmq-26.4.0-cp311-cp311-win32.whl", hash = "sha256:d56aad0517d4c09e3b4f15adebba8f6372c5102c27742a5bdbfc74a7dceb8fca", size = 579247, upload-time = "2025-04-04T12:03:36.846Z" }, + { url = "https://files.pythonhosted.org/packages/c3/d0/2d9abfa2571a0b1a67c0ada79a8aa1ba1cce57992d80f771abcdf99bb32c/pyzmq-26.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:963977ac8baed7058c1e126014f3fe58b3773f45c78cce7af5c26c09b6823896", size = 644727, upload-time = "2025-04-04T12:03:38.578Z" }, + { url = "https://files.pythonhosted.org/packages/0d/d1/c8ad82393be6ccedfc3c9f3adb07f8f3976e3c4802640fe3f71441941e70/pyzmq-26.4.0-cp311-cp311-win_arm64.whl", hash = "sha256:c0c8e8cadc81e44cc5088fcd53b9b3b4ce9344815f6c4a03aec653509296fae3", size = 559942, upload-time = "2025-04-04T12:03:40.143Z" }, + { url = "https://files.pythonhosted.org/packages/10/44/a778555ebfdf6c7fc00816aad12d185d10a74d975800341b1bc36bad1187/pyzmq-26.4.0-cp312-cp312-macosx_10_15_universal2.whl", hash = "sha256:5227cb8da4b6f68acfd48d20c588197fd67745c278827d5238c707daf579227b", size = 1341586, upload-time = "2025-04-04T12:03:41.954Z" }, + { url = "https://files.pythonhosted.org/packages/9c/4f/f3a58dc69ac757e5103be3bd41fb78721a5e17da7cc617ddb56d973a365c/pyzmq-26.4.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e1c07a7fa7f7ba86554a2b1bef198c9fed570c08ee062fd2fd6a4dcacd45f905", size = 665880, upload-time = "2025-04-04T12:03:43.45Z" }, + { url = "https://files.pythonhosted.org/packages/fe/45/50230bcfb3ae5cb98bee683b6edeba1919f2565d7cc1851d3c38e2260795/pyzmq-26.4.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ae775fa83f52f52de73183f7ef5395186f7105d5ed65b1ae65ba27cb1260de2b", size = 902216, upload-time = "2025-04-04T12:03:45.572Z" }, + { url = "https://files.pythonhosted.org/packages/41/59/56bbdc5689be5e13727491ad2ba5efd7cd564365750514f9bc8f212eef82/pyzmq-26.4.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:66c760d0226ebd52f1e6b644a9e839b5db1e107a23f2fcd46ec0569a4fdd4e63", size = 859814, upload-time = "2025-04-04T12:03:47.188Z" }, + { url = "https://files.pythonhosted.org/packages/81/b1/57db58cfc8af592ce94f40649bd1804369c05b2190e4cbc0a2dad572baeb/pyzmq-26.4.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:ef8c6ecc1d520debc147173eaa3765d53f06cd8dbe7bd377064cdbc53ab456f5", size = 855889, upload-time = "2025-04-04T12:03:49.223Z" }, + { url = "https://files.pythonhosted.org/packages/e8/92/47542e629cbac8f221c230a6d0f38dd3d9cff9f6f589ed45fdf572ffd726/pyzmq-26.4.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:3150ef4084e163dec29ae667b10d96aad309b668fac6810c9e8c27cf543d6e0b", size = 1197153, upload-time = "2025-04-04T12:03:50.591Z" }, + { url = "https://files.pythonhosted.org/packages/07/e5/b10a979d1d565d54410afc87499b16c96b4a181af46e7645ab4831b1088c/pyzmq-26.4.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:4448c9e55bf8329fa1dcedd32f661bf611214fa70c8e02fee4347bc589d39a84", size = 1507352, upload-time = "2025-04-04T12:03:52.473Z" }, + { url = "https://files.pythonhosted.org/packages/ab/58/5a23db84507ab9c01c04b1232a7a763be66e992aa2e66498521bbbc72a71/pyzmq-26.4.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:e07dde3647afb084d985310d067a3efa6efad0621ee10826f2cb2f9a31b89d2f", size = 1406834, upload-time = "2025-04-04T12:03:54Z" }, + { url = "https://files.pythonhosted.org/packages/22/74/aaa837b331580c13b79ac39396601fb361454ee184ca85e8861914769b99/pyzmq-26.4.0-cp312-cp312-win32.whl", hash = "sha256:ba034a32ecf9af72adfa5ee383ad0fd4f4e38cdb62b13624278ef768fe5b5b44", size = 577992, upload-time = "2025-04-04T12:03:55.815Z" }, + { url = "https://files.pythonhosted.org/packages/30/0f/55f8c02c182856743b82dde46b2dc3e314edda7f1098c12a8227eeda0833/pyzmq-26.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:056a97aab4064f526ecb32f4343917a4022a5d9efb6b9df990ff72e1879e40be", size = 640466, upload-time = "2025-04-04T12:03:57.231Z" }, + { url = "https://files.pythonhosted.org/packages/e4/29/073779afc3ef6f830b8de95026ef20b2d1ec22d0324d767748d806e57379/pyzmq-26.4.0-cp312-cp312-win_arm64.whl", hash = "sha256:2f23c750e485ce1eb639dbd576d27d168595908aa2d60b149e2d9e34c9df40e0", size = 556342, upload-time = "2025-04-04T12:03:59.218Z" }, + { url = "https://files.pythonhosted.org/packages/04/52/a70fcd5592715702248306d8e1729c10742c2eac44529984413b05c68658/pyzmq-26.4.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:4478b14cb54a805088299c25a79f27eaf530564a7a4f72bf432a040042b554eb", size = 834405, upload-time = "2025-04-04T12:05:13.3Z" }, + { url = "https://files.pythonhosted.org/packages/25/f9/1a03f1accff16b3af1a6fa22cbf7ced074776abbf688b2e9cb4629700c62/pyzmq-26.4.0-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8a28ac29c60e4ba84b5f58605ace8ad495414a724fe7aceb7cf06cd0598d04e1", size = 569578, upload-time = "2025-04-04T12:05:15.36Z" }, + { url = "https://files.pythonhosted.org/packages/76/0c/3a633acd762aa6655fcb71fa841907eae0ab1e8582ff494b137266de341d/pyzmq-26.4.0-pp311-pypy311_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:43b03c1ceea27c6520124f4fb2ba9c647409b9abdf9a62388117148a90419494", size = 798248, upload-time = "2025-04-04T12:05:17.376Z" }, + { url = "https://files.pythonhosted.org/packages/cd/cc/6c99c84aa60ac1cc56747bed6be8ce6305b9b861d7475772e7a25ce019d3/pyzmq-26.4.0-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7731abd23a782851426d4e37deb2057bf9410848a4459b5ede4fe89342e687a9", size = 756757, upload-time = "2025-04-04T12:05:19.19Z" }, + { url = "https://files.pythonhosted.org/packages/13/9c/d8073bd898eb896e94c679abe82e47506e2b750eb261cf6010ced869797c/pyzmq-26.4.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:a222ad02fbe80166b0526c038776e8042cd4e5f0dec1489a006a1df47e9040e0", size = 555371, upload-time = "2025-04-04T12:05:20.702Z" }, ] [[package]] @@ -4613,21 +4645,21 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/8c/35/9bf3a2af73c55fd4310dcaec4f997c739888e0db9b4dfac71b7680810852/raylib-5.5.0.2.tar.gz", hash = "sha256:83c108ae3b4af40b53c93d1de2afbe309e986dd5efeb280ebe2e61c79956edb0", size = 181172 } +sdist = { url = "https://files.pythonhosted.org/packages/8c/35/9bf3a2af73c55fd4310dcaec4f997c739888e0db9b4dfac71b7680810852/raylib-5.5.0.2.tar.gz", hash = "sha256:83c108ae3b4af40b53c93d1de2afbe309e986dd5efeb280ebe2e61c79956edb0", size = 181172, upload-time = "2024-11-26T11:12:02.791Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9e/c4/ce21721b474eb8f65379f7315b382ccfe1d5df728eea4dcf287b874e7461/raylib-5.5.0.2-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:37eb0ec97fc6b08f989489a50e09b5dde519e1bb8eb17e4033ac82227b0e5eda", size = 1703742 }, - { url = "https://files.pythonhosted.org/packages/23/61/138e305c82549869bb8cd41abe75571559eafbeab6aed1ce7d8fbe3ffd58/raylib-5.5.0.2-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:bb9e506ecd3dbec6dba868eb036269837a8bde68220690842c3238239ee887ef", size = 1247449 }, - { url = "https://files.pythonhosted.org/packages/85/e0/dc638c42d1a505f0992263d48e1434d82c21afdf376b06f549d2e281dfd4/raylib-5.5.0.2-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:70aa8bed67875a8cf25191f35263ef92d646bdfcb1f507915c81562a321f4931", size = 2184315 }, - { url = "https://files.pythonhosted.org/packages/c9/1a/49db57283a28fdc1ff0e4604911b7fff085128c2ac8bdd9efa8c5c47439d/raylib-5.5.0.2-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:0365e8c578f72f598795d9377fc70342f0d62aa193c2f304ca048b3e28866752", size = 2278139 }, - { url = "https://files.pythonhosted.org/packages/f0/8a/e1a690ab6889d4cb67346a2d32bad8b8e8b0f85ec826b00f76b0ad7e6ad6/raylib-5.5.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:5219be70e7fca03e9c4fddebf7e60e885d77137125c7a13f3800a947f8562a13", size = 1693944 }, - { url = "https://files.pythonhosted.org/packages/69/2b/49bfa6833ad74ddf318d54ecafe73d535f583531469ecbd5b009d79667d1/raylib-5.5.0.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:5233c529d9a0cfd469d88239c2182e55c5215a7755d83cc3d611148d3b9c9e67", size = 1706157 }, - { url = "https://files.pythonhosted.org/packages/58/9c/8a3f4de0c81ad1228bf26410cfe3ecdc73011c59f18e542685ffc92c0120/raylib-5.5.0.2-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:1f76204ffbc492722b571b12dbdc0dca89b10da76ddf48c12a3968d2db061dff", size = 1248027 }, - { url = "https://files.pythonhosted.org/packages/7f/16/63baf1aae94832b9f5d15cafcee67bb6dd07a20cf64d40bac09903b79274/raylib-5.5.0.2-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:f8cc2e39f1d6b29211a97ec0ac818a5b04c43a40e747e4b4622101d48c711f9e", size = 2195374 }, - { url = "https://files.pythonhosted.org/packages/70/bd/61a006b4e3ce4a6ca974cb0ceeb19f3816815ebabac650e9bf82767e65f6/raylib-5.5.0.2-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:f12da578a28da7f48481f46323e5aab8dd25461982b0e80d045782d6e69649f5", size = 2299593 }, - { url = "https://files.pythonhosted.org/packages/f4/4f/59d554cc495bea8235b17cebfc76ed57aaa602c613b870159e31282fd4c1/raylib-5.5.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:b40234bbad9523fd6a2049640c76a98b4d6f0b8f4bd19bd33eaee55faf5e050d", size = 1696780 }, - { url = "https://files.pythonhosted.org/packages/4a/22/2e02e3738ad041f5ec2830aecdfab411fc2960bfc3400e03b477284bfaf7/raylib-5.5.0.2-pp311-pypy311_pp73-macosx_10_13_x86_64.whl", hash = "sha256:bc45fe1c0aac50aa319a9a66d44bb2bd0dcd038a44d95978191ae7bfeb4a06d8", size = 1216231 }, - { url = "https://files.pythonhosted.org/packages/fe/7d/b29afedc4a706b12143f74f322cb32ad5a6f43e56aaca2a9fb89b0d94eee/raylib-5.5.0.2-pp311-pypy311_pp73-manylinux2014_x86_64.whl", hash = "sha256:2242fd6079da5137e9863a447224f800adef6386ca8f59013a5d62cc5cadab2b", size = 1394928 }, - { url = "https://files.pythonhosted.org/packages/b6/fa/2daf36d78078c6871b241168a36156169cfc8ea089faba5abe8edad304be/raylib-5.5.0.2-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:e475a40764c9f83f9e66406bd86d85587eb923329a61ade463c3c59e1e880b16", size = 1564224 }, + { url = "https://files.pythonhosted.org/packages/9e/c4/ce21721b474eb8f65379f7315b382ccfe1d5df728eea4dcf287b874e7461/raylib-5.5.0.2-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:37eb0ec97fc6b08f989489a50e09b5dde519e1bb8eb17e4033ac82227b0e5eda", size = 1703742, upload-time = "2024-11-26T11:09:31.115Z" }, + { url = "https://files.pythonhosted.org/packages/23/61/138e305c82549869bb8cd41abe75571559eafbeab6aed1ce7d8fbe3ffd58/raylib-5.5.0.2-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:bb9e506ecd3dbec6dba868eb036269837a8bde68220690842c3238239ee887ef", size = 1247449, upload-time = "2024-11-26T11:09:34.182Z" }, + { url = "https://files.pythonhosted.org/packages/85/e0/dc638c42d1a505f0992263d48e1434d82c21afdf376b06f549d2e281dfd4/raylib-5.5.0.2-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:70aa8bed67875a8cf25191f35263ef92d646bdfcb1f507915c81562a321f4931", size = 2184315, upload-time = "2024-11-26T11:09:36.715Z" }, + { url = "https://files.pythonhosted.org/packages/c9/1a/49db57283a28fdc1ff0e4604911b7fff085128c2ac8bdd9efa8c5c47439d/raylib-5.5.0.2-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:0365e8c578f72f598795d9377fc70342f0d62aa193c2f304ca048b3e28866752", size = 2278139, upload-time = "2024-11-26T11:09:39.475Z" }, + { url = "https://files.pythonhosted.org/packages/f0/8a/e1a690ab6889d4cb67346a2d32bad8b8e8b0f85ec826b00f76b0ad7e6ad6/raylib-5.5.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:5219be70e7fca03e9c4fddebf7e60e885d77137125c7a13f3800a947f8562a13", size = 1693944, upload-time = "2024-11-26T11:09:41.596Z" }, + { url = "https://files.pythonhosted.org/packages/69/2b/49bfa6833ad74ddf318d54ecafe73d535f583531469ecbd5b009d79667d1/raylib-5.5.0.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:5233c529d9a0cfd469d88239c2182e55c5215a7755d83cc3d611148d3b9c9e67", size = 1706157, upload-time = "2024-11-26T11:09:43.6Z" }, + { url = "https://files.pythonhosted.org/packages/58/9c/8a3f4de0c81ad1228bf26410cfe3ecdc73011c59f18e542685ffc92c0120/raylib-5.5.0.2-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:1f76204ffbc492722b571b12dbdc0dca89b10da76ddf48c12a3968d2db061dff", size = 1248027, upload-time = "2025-01-04T20:21:46.269Z" }, + { url = "https://files.pythonhosted.org/packages/7f/16/63baf1aae94832b9f5d15cafcee67bb6dd07a20cf64d40bac09903b79274/raylib-5.5.0.2-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:f8cc2e39f1d6b29211a97ec0ac818a5b04c43a40e747e4b4622101d48c711f9e", size = 2195374, upload-time = "2024-11-26T11:09:46.114Z" }, + { url = "https://files.pythonhosted.org/packages/70/bd/61a006b4e3ce4a6ca974cb0ceeb19f3816815ebabac650e9bf82767e65f6/raylib-5.5.0.2-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:f12da578a28da7f48481f46323e5aab8dd25461982b0e80d045782d6e69649f5", size = 2299593, upload-time = "2024-11-26T11:09:48.963Z" }, + { url = "https://files.pythonhosted.org/packages/f4/4f/59d554cc495bea8235b17cebfc76ed57aaa602c613b870159e31282fd4c1/raylib-5.5.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:b40234bbad9523fd6a2049640c76a98b4d6f0b8f4bd19bd33eaee55faf5e050d", size = 1696780, upload-time = "2024-11-26T11:09:50.787Z" }, + { url = "https://files.pythonhosted.org/packages/4a/22/2e02e3738ad041f5ec2830aecdfab411fc2960bfc3400e03b477284bfaf7/raylib-5.5.0.2-pp311-pypy311_pp73-macosx_10_13_x86_64.whl", hash = "sha256:bc45fe1c0aac50aa319a9a66d44bb2bd0dcd038a44d95978191ae7bfeb4a06d8", size = 1216231, upload-time = "2025-02-12T04:21:59.38Z" }, + { url = "https://files.pythonhosted.org/packages/fe/7d/b29afedc4a706b12143f74f322cb32ad5a6f43e56aaca2a9fb89b0d94eee/raylib-5.5.0.2-pp311-pypy311_pp73-manylinux2014_x86_64.whl", hash = "sha256:2242fd6079da5137e9863a447224f800adef6386ca8f59013a5d62cc5cadab2b", size = 1394928, upload-time = "2025-02-12T04:22:03.021Z" }, + { url = "https://files.pythonhosted.org/packages/b6/fa/2daf36d78078c6871b241168a36156169cfc8ea089faba5abe8edad304be/raylib-5.5.0.2-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:e475a40764c9f83f9e66406bd86d85587eb923329a61ade463c3c59e1e880b16", size = 1564224, upload-time = "2025-02-12T04:22:05.911Z" }, ] [[package]] @@ -4640,14 +4672,14 @@ dependencies = [ { name = "idna" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/63/70/2bf7780ad2d390a8d301ad0b550f1581eadbd9a20f896afe06353c2a2913/requests-2.32.3.tar.gz", hash = "sha256:55365417734eb18255590a9ff9eb97e9e1da868d4ccd6402399eaf68af20a760", size = 131218 } +sdist = { url = "https://files.pythonhosted.org/packages/63/70/2bf7780ad2d390a8d301ad0b550f1581eadbd9a20f896afe06353c2a2913/requests-2.32.3.tar.gz", hash = "sha256:55365417734eb18255590a9ff9eb97e9e1da868d4ccd6402399eaf68af20a760", size = 131218, upload-time = "2024-05-29T15:37:49.536Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f9/9b/335f9764261e915ed497fcdeb11df5dfd6f7bf257d4a6a2a686d80da4d54/requests-2.32.3-py3-none-any.whl", hash = "sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6", size = 64928 }, + { url = "https://files.pythonhosted.org/packages/f9/9b/335f9764261e915ed497fcdeb11df5dfd6f7bf257d4a6a2a686d80da4d54/requests-2.32.3-py3-none-any.whl", hash = "sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6", size = 64928, upload-time = "2024-05-29T15:37:47.027Z" }, ] [[package]] name = "rerun-sdk" -version = "0.22.1" +version = "0.23.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "attrs" }, @@ -4657,11 +4689,11 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/a9/41/f9724c6ee4b4d45f9ae433f41fc8b4f2827d5b3f9459b9e9a9c55fdda5ab/rerun_sdk-0.22.1-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:176853d14bcac0b3cab8b240fe6760e32a577b1edd9ecb2fd0656e83f046a2c4", size = 46819325 }, - { url = "https://files.pythonhosted.org/packages/01/8e/db9fd7e7d9d9ec6e3f0781ce6f3b71c06952f9b0c40e9720822fd83f711e/rerun_sdk-0.22.1-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:dea4a50c916bc82bd97a8f9dc44c71f9a9fccec7e73f37edfaa0de800caf5dce", size = 44566672 }, - { url = "https://files.pythonhosted.org/packages/ad/41/87079d0a897e4fc2dd54a356be9556626f40ec1ff1c3393178e7ac9feb9d/rerun_sdk-0.22.1-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:29d807909f5e484aa6427d9fb25706d0a154de392a4ca47eb303fbd135c0e382", size = 49830061 }, - { url = "https://files.pythonhosted.org/packages/1e/db/3ce2be017d7d4ac0948fb064bf7417b36c96bc07d1b8a922017606ba03c6/rerun_sdk-0.22.1-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:b9672412d0cdf57c79c10ca683e59716399da3358df78b985b25093d022ebbaf", size = 51423327 }, - { url = "https://files.pythonhosted.org/packages/43/eb/edafdcba1619955c2c9b66c7a1bcbbce4ad62a1a36db984b46aa793fe366/rerun_sdk-0.22.1-cp38-abi3-win_amd64.whl", hash = "sha256:d3d0afe1b8e749a1088a0bb75f372ad7fe70eb3728bd32e07bf78300436a053d", size = 42085149 }, + { url = "https://files.pythonhosted.org/packages/24/98/ee9acc4ac36e977bcacd3d65704127026a02228f4f5efa9cfd4243dd2036/rerun_sdk-0.23.2-cp39-abi3-macosx_10_12_x86_64.whl", hash = "sha256:fb9f0279a8b87f64bc29ed2c4c3cbb602e36b9b373f691ff657968ed6009c5c3", size = 66816731, upload-time = "2025-05-06T15:54:46.177Z" }, + { url = "https://files.pythonhosted.org/packages/3a/84/6164958c9b4dcd9b9dab16e1adbf4cea4339f52ce212c084b57bc0fd1a05/rerun_sdk-0.23.2-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:02d99f48659abeca86fcbd56498d30ab0c4b34b8a0732b02324c3fe79830cf6f", size = 62697629, upload-time = "2025-05-06T15:54:52.083Z" }, + { url = "https://files.pythonhosted.org/packages/c0/4d/1b9dc66a5827f25f9ce5fe9b719f97f42403d1a2276e765082d224590dbe/rerun_sdk-0.23.2-cp39-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:fdc844eddb6dcc924e48b3cd8dd88ed8b70751301d386175dd2fd7c9594580b3", size = 68935354, upload-time = "2025-05-06T15:54:56.27Z" }, + { url = "https://files.pythonhosted.org/packages/e7/7b/16b9bcd67b3dea1842d556100ce2e0b5c6bd9ad7943aeab2a76bae4b2be5/rerun_sdk-0.23.2-cp39-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:dac599ef5d5563f4ebc90c20f09b77c458bac4df845e178112257f79f3eef579", size = 72209426, upload-time = "2025-05-06T15:55:00.641Z" }, + { url = "https://files.pythonhosted.org/packages/67/54/ecb761555f6fbd4e32c384ba5a8424c761925be54259708093205c916c64/rerun_sdk-0.23.2-cp39-abi3-win_amd64.whl", hash = "sha256:ce3f9adfb04df79f30ca1e6deb997b021af87878672f79dfa3543a4f6a83491f", size = 58180134, upload-time = "2025-05-06T15:55:06.284Z" }, ] [[package]] @@ -4671,273 +4703,277 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ruamel-yaml-clib", marker = "platform_python_implementation == 'CPython'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ea/46/f44d8be06b85bc7c4d8c95d658be2b68f27711f279bf9dd0612a5e4794f5/ruamel.yaml-0.18.10.tar.gz", hash = "sha256:20c86ab29ac2153f80a428e1254a8adf686d3383df04490514ca3b79a362db58", size = 143447 } +sdist = { url = "https://files.pythonhosted.org/packages/ea/46/f44d8be06b85bc7c4d8c95d658be2b68f27711f279bf9dd0612a5e4794f5/ruamel.yaml-0.18.10.tar.gz", hash = "sha256:20c86ab29ac2153f80a428e1254a8adf686d3383df04490514ca3b79a362db58", size = 143447, upload-time = "2025-01-06T14:08:51.334Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c2/36/dfc1ebc0081e6d39924a2cc53654497f967a084a436bb64402dfce4254d9/ruamel.yaml-0.18.10-py3-none-any.whl", hash = "sha256:30f22513ab2301b3d2b577adc121c6471f28734d3d9728581245f1e76468b4f1", size = 117729 }, + { url = "https://files.pythonhosted.org/packages/c2/36/dfc1ebc0081e6d39924a2cc53654497f967a084a436bb64402dfce4254d9/ruamel.yaml-0.18.10-py3-none-any.whl", hash = "sha256:30f22513ab2301b3d2b577adc121c6471f28734d3d9728581245f1e76468b4f1", size = 117729, upload-time = "2025-01-06T14:08:47.471Z" }, ] [[package]] name = "ruamel-yaml-clib" version = "0.2.12" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/20/84/80203abff8ea4993a87d823a5f632e4d92831ef75d404c9fc78d0176d2b5/ruamel.yaml.clib-0.2.12.tar.gz", hash = "sha256:6c8fbb13ec503f99a91901ab46e0b07ae7941cd527393187039aec586fdfd36f", size = 225315 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/fb/8f/683c6ad562f558cbc4f7c029abcd9599148c51c54b5ef0f24f2638da9fbb/ruamel.yaml.clib-0.2.12-cp311-cp311-macosx_13_0_arm64.whl", hash = "sha256:4a6679521a58256a90b0d89e03992c15144c5f3858f40d7c18886023d7943db6", size = 132224 }, - { url = "https://files.pythonhosted.org/packages/3c/d2/b79b7d695e2f21da020bd44c782490578f300dd44f0a4c57a92575758a76/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:d84318609196d6bd6da0edfa25cedfbabd8dbde5140a0a23af29ad4b8f91fb1e", size = 641480 }, - { url = "https://files.pythonhosted.org/packages/68/6e/264c50ce2a31473a9fdbf4fa66ca9b2b17c7455b31ef585462343818bd6c/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bb43a269eb827806502c7c8efb7ae7e9e9d0573257a46e8e952f4d4caba4f31e", size = 739068 }, - { url = "https://files.pythonhosted.org/packages/86/29/88c2567bc893c84d88b4c48027367c3562ae69121d568e8a3f3a8d363f4d/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:811ea1594b8a0fb466172c384267a4e5e367298af6b228931f273b111f17ef52", size = 703012 }, - { url = "https://files.pythonhosted.org/packages/11/46/879763c619b5470820f0cd6ca97d134771e502776bc2b844d2adb6e37753/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:cf12567a7b565cbf65d438dec6cfbe2917d3c1bdddfce84a9930b7d35ea59642", size = 704352 }, - { url = "https://files.pythonhosted.org/packages/02/80/ece7e6034256a4186bbe50dee28cd032d816974941a6abf6a9d65e4228a7/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:7dd5adc8b930b12c8fc5b99e2d535a09889941aa0d0bd06f4749e9a9397c71d2", size = 737344 }, - { url = "https://files.pythonhosted.org/packages/f0/ca/e4106ac7e80efbabdf4bf91d3d32fc424e41418458251712f5672eada9ce/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1492a6051dab8d912fc2adeef0e8c72216b24d57bd896ea607cb90bb0c4981d3", size = 714498 }, - { url = "https://files.pythonhosted.org/packages/67/58/b1f60a1d591b771298ffa0428237afb092c7f29ae23bad93420b1eb10703/ruamel.yaml.clib-0.2.12-cp311-cp311-win32.whl", hash = "sha256:bd0a08f0bab19093c54e18a14a10b4322e1eacc5217056f3c063bd2f59853ce4", size = 100205 }, - { url = "https://files.pythonhosted.org/packages/b4/4f/b52f634c9548a9291a70dfce26ca7ebce388235c93588a1068028ea23fcc/ruamel.yaml.clib-0.2.12-cp311-cp311-win_amd64.whl", hash = "sha256:a274fb2cb086c7a3dea4322ec27f4cb5cc4b6298adb583ab0e211a4682f241eb", size = 118185 }, - { url = "https://files.pythonhosted.org/packages/48/41/e7a405afbdc26af961678474a55373e1b323605a4f5e2ddd4a80ea80f628/ruamel.yaml.clib-0.2.12-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:20b0f8dc160ba83b6dcc0e256846e1a02d044e13f7ea74a3d1d56ede4e48c632", size = 133433 }, - { url = "https://files.pythonhosted.org/packages/ec/b0/b850385604334c2ce90e3ee1013bd911aedf058a934905863a6ea95e9eb4/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:943f32bc9dedb3abff9879edc134901df92cfce2c3d5c9348f172f62eb2d771d", size = 647362 }, - { url = "https://files.pythonhosted.org/packages/44/d0/3f68a86e006448fb6c005aee66565b9eb89014a70c491d70c08de597f8e4/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:95c3829bb364fdb8e0332c9931ecf57d9be3519241323c5274bd82f709cebc0c", size = 754118 }, - { url = "https://files.pythonhosted.org/packages/52/a9/d39f3c5ada0a3bb2870d7db41901125dbe2434fa4f12ca8c5b83a42d7c53/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:749c16fcc4a2b09f28843cda5a193e0283e47454b63ec4b81eaa2242f50e4ccd", size = 706497 }, - { url = "https://files.pythonhosted.org/packages/b0/fa/097e38135dadd9ac25aecf2a54be17ddf6e4c23e43d538492a90ab3d71c6/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:bf165fef1f223beae7333275156ab2022cffe255dcc51c27f066b4370da81e31", size = 698042 }, - { url = "https://files.pythonhosted.org/packages/ec/d5/a659ca6f503b9379b930f13bc6b130c9f176469b73b9834296822a83a132/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:32621c177bbf782ca5a18ba4d7af0f1082a3f6e517ac2a18b3974d4edf349680", size = 745831 }, - { url = "https://files.pythonhosted.org/packages/db/5d/36619b61ffa2429eeaefaab4f3374666adf36ad8ac6330d855848d7d36fd/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b82a7c94a498853aa0b272fd5bc67f29008da798d4f93a2f9f289feb8426a58d", size = 715692 }, - { url = "https://files.pythonhosted.org/packages/b1/82/85cb92f15a4231c89b95dfe08b09eb6adca929ef7df7e17ab59902b6f589/ruamel.yaml.clib-0.2.12-cp312-cp312-win32.whl", hash = "sha256:e8c4ebfcfd57177b572e2040777b8abc537cdef58a2120e830124946aa9b42c5", size = 98777 }, - { url = "https://files.pythonhosted.org/packages/d7/8f/c3654f6f1ddb75daf3922c3d8fc6005b1ab56671ad56ffb874d908bfa668/ruamel.yaml.clib-0.2.12-cp312-cp312-win_amd64.whl", hash = "sha256:0467c5965282c62203273b838ae77c0d29d7638c8a4e3a1c8bdd3602c10904e4", size = 115523 }, +sdist = { url = "https://files.pythonhosted.org/packages/20/84/80203abff8ea4993a87d823a5f632e4d92831ef75d404c9fc78d0176d2b5/ruamel.yaml.clib-0.2.12.tar.gz", hash = "sha256:6c8fbb13ec503f99a91901ab46e0b07ae7941cd527393187039aec586fdfd36f", size = 225315, upload-time = "2024-10-20T10:10:56.22Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/fb/8f/683c6ad562f558cbc4f7c029abcd9599148c51c54b5ef0f24f2638da9fbb/ruamel.yaml.clib-0.2.12-cp311-cp311-macosx_13_0_arm64.whl", hash = "sha256:4a6679521a58256a90b0d89e03992c15144c5f3858f40d7c18886023d7943db6", size = 132224, upload-time = "2024-10-20T10:12:45.162Z" }, + { url = "https://files.pythonhosted.org/packages/3c/d2/b79b7d695e2f21da020bd44c782490578f300dd44f0a4c57a92575758a76/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:d84318609196d6bd6da0edfa25cedfbabd8dbde5140a0a23af29ad4b8f91fb1e", size = 641480, upload-time = "2024-10-20T10:12:46.758Z" }, + { url = "https://files.pythonhosted.org/packages/68/6e/264c50ce2a31473a9fdbf4fa66ca9b2b17c7455b31ef585462343818bd6c/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bb43a269eb827806502c7c8efb7ae7e9e9d0573257a46e8e952f4d4caba4f31e", size = 739068, upload-time = "2024-10-20T10:12:48.605Z" }, + { url = "https://files.pythonhosted.org/packages/86/29/88c2567bc893c84d88b4c48027367c3562ae69121d568e8a3f3a8d363f4d/ruamel.yaml.clib-0.2.12-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:811ea1594b8a0fb466172c384267a4e5e367298af6b228931f273b111f17ef52", size = 703012, upload-time = "2024-10-20T10:12:51.124Z" }, + { url = "https://files.pythonhosted.org/packages/11/46/879763c619b5470820f0cd6ca97d134771e502776bc2b844d2adb6e37753/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:cf12567a7b565cbf65d438dec6cfbe2917d3c1bdddfce84a9930b7d35ea59642", size = 704352, upload-time = "2024-10-21T11:26:41.438Z" }, + { url = "https://files.pythonhosted.org/packages/02/80/ece7e6034256a4186bbe50dee28cd032d816974941a6abf6a9d65e4228a7/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:7dd5adc8b930b12c8fc5b99e2d535a09889941aa0d0bd06f4749e9a9397c71d2", size = 737344, upload-time = "2024-10-21T11:26:43.62Z" }, + { url = "https://files.pythonhosted.org/packages/f0/ca/e4106ac7e80efbabdf4bf91d3d32fc424e41418458251712f5672eada9ce/ruamel.yaml.clib-0.2.12-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1492a6051dab8d912fc2adeef0e8c72216b24d57bd896ea607cb90bb0c4981d3", size = 714498, upload-time = "2024-12-11T19:58:15.592Z" }, + { url = "https://files.pythonhosted.org/packages/67/58/b1f60a1d591b771298ffa0428237afb092c7f29ae23bad93420b1eb10703/ruamel.yaml.clib-0.2.12-cp311-cp311-win32.whl", hash = "sha256:bd0a08f0bab19093c54e18a14a10b4322e1eacc5217056f3c063bd2f59853ce4", size = 100205, upload-time = "2024-10-20T10:12:52.865Z" }, + { url = "https://files.pythonhosted.org/packages/b4/4f/b52f634c9548a9291a70dfce26ca7ebce388235c93588a1068028ea23fcc/ruamel.yaml.clib-0.2.12-cp311-cp311-win_amd64.whl", hash = "sha256:a274fb2cb086c7a3dea4322ec27f4cb5cc4b6298adb583ab0e211a4682f241eb", size = 118185, upload-time = "2024-10-20T10:12:54.652Z" }, + { url = "https://files.pythonhosted.org/packages/48/41/e7a405afbdc26af961678474a55373e1b323605a4f5e2ddd4a80ea80f628/ruamel.yaml.clib-0.2.12-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:20b0f8dc160ba83b6dcc0e256846e1a02d044e13f7ea74a3d1d56ede4e48c632", size = 133433, upload-time = "2024-10-20T10:12:55.657Z" }, + { url = "https://files.pythonhosted.org/packages/ec/b0/b850385604334c2ce90e3ee1013bd911aedf058a934905863a6ea95e9eb4/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:943f32bc9dedb3abff9879edc134901df92cfce2c3d5c9348f172f62eb2d771d", size = 647362, upload-time = "2024-10-20T10:12:57.155Z" }, + { url = "https://files.pythonhosted.org/packages/44/d0/3f68a86e006448fb6c005aee66565b9eb89014a70c491d70c08de597f8e4/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:95c3829bb364fdb8e0332c9931ecf57d9be3519241323c5274bd82f709cebc0c", size = 754118, upload-time = "2024-10-20T10:12:58.501Z" }, + { url = "https://files.pythonhosted.org/packages/52/a9/d39f3c5ada0a3bb2870d7db41901125dbe2434fa4f12ca8c5b83a42d7c53/ruamel.yaml.clib-0.2.12-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:749c16fcc4a2b09f28843cda5a193e0283e47454b63ec4b81eaa2242f50e4ccd", size = 706497, upload-time = "2024-10-20T10:13:00.211Z" }, + { url = "https://files.pythonhosted.org/packages/b0/fa/097e38135dadd9ac25aecf2a54be17ddf6e4c23e43d538492a90ab3d71c6/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:bf165fef1f223beae7333275156ab2022cffe255dcc51c27f066b4370da81e31", size = 698042, upload-time = "2024-10-21T11:26:46.038Z" }, + { url = "https://files.pythonhosted.org/packages/ec/d5/a659ca6f503b9379b930f13bc6b130c9f176469b73b9834296822a83a132/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:32621c177bbf782ca5a18ba4d7af0f1082a3f6e517ac2a18b3974d4edf349680", size = 745831, upload-time = "2024-10-21T11:26:47.487Z" }, + { url = "https://files.pythonhosted.org/packages/db/5d/36619b61ffa2429eeaefaab4f3374666adf36ad8ac6330d855848d7d36fd/ruamel.yaml.clib-0.2.12-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b82a7c94a498853aa0b272fd5bc67f29008da798d4f93a2f9f289feb8426a58d", size = 715692, upload-time = "2024-12-11T19:58:17.252Z" }, + { url = "https://files.pythonhosted.org/packages/b1/82/85cb92f15a4231c89b95dfe08b09eb6adca929ef7df7e17ab59902b6f589/ruamel.yaml.clib-0.2.12-cp312-cp312-win32.whl", hash = "sha256:e8c4ebfcfd57177b572e2040777b8abc537cdef58a2120e830124946aa9b42c5", size = 98777, upload-time = "2024-10-20T10:13:01.395Z" }, + { url = "https://files.pythonhosted.org/packages/d7/8f/c3654f6f1ddb75daf3922c3d8fc6005b1ab56671ad56ffb874d908bfa668/ruamel.yaml.clib-0.2.12-cp312-cp312-win_amd64.whl", hash = "sha256:0467c5965282c62203273b838ae77c0d29d7638c8a4e3a1c8bdd3602c10904e4", size = 115523, upload-time = "2024-10-20T10:13:02.768Z" }, ] [[package]] name = "rubicon-objc" version = "0.5.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d3/13/586c9baa985eae0f718029506b40ca41295d51a546567414b2bcf8ccacef/rubicon_objc-0.5.0.tar.gz", hash = "sha256:18f075649780d95df53d483642068c767d7d2cfbbf075ddef124a44b40b6d92e", size = 173652 } +sdist = { url = "https://files.pythonhosted.org/packages/d3/13/586c9baa985eae0f718029506b40ca41295d51a546567414b2bcf8ccacef/rubicon_objc-0.5.0.tar.gz", hash = "sha256:18f075649780d95df53d483642068c767d7d2cfbbf075ddef124a44b40b6d92e", size = 173652, upload-time = "2025-01-07T00:25:10.491Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6d/30/5b2407b8762ed882e5732e19c485b9ea2f07d35462615a3212638bab66c2/rubicon_objc-0.5.0-py3-none-any.whl", hash = "sha256:a9c2a605120d6e5be327d3f42a71b60963125987e116f51846757b5e110854fa", size = 62711 }, + { url = "https://files.pythonhosted.org/packages/6d/30/5b2407b8762ed882e5732e19c485b9ea2f07d35462615a3212638bab66c2/rubicon_objc-0.5.0-py3-none-any.whl", hash = "sha256:a9c2a605120d6e5be327d3f42a71b60963125987e116f51846757b5e110854fa", size = 62711, upload-time = "2025-01-07T00:25:08.959Z" }, ] [[package]] name = "ruff" -version = "0.9.10" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/20/8e/fafaa6f15c332e73425d9c44ada85360501045d5ab0b81400076aff27cf6/ruff-0.9.10.tar.gz", hash = "sha256:9bacb735d7bada9cfb0f2c227d3658fc443d90a727b47f206fb33f52f3c0eac7", size = 3759776 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/73/b2/af7c2cc9e438cbc19fafeec4f20bfcd72165460fe75b2b6e9a0958c8c62b/ruff-0.9.10-py3-none-linux_armv6l.whl", hash = "sha256:eb4d25532cfd9fe461acc83498361ec2e2252795b4f40b17e80692814329e42d", size = 10049494 }, - { url = "https://files.pythonhosted.org/packages/6d/12/03f6dfa1b95ddd47e6969f0225d60d9d7437c91938a310835feb27927ca0/ruff-0.9.10-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:188a6638dab1aa9bb6228a7302387b2c9954e455fb25d6b4470cb0641d16759d", size = 10853584 }, - { url = "https://files.pythonhosted.org/packages/02/49/1c79e0906b6ff551fb0894168763f705bf980864739572b2815ecd3c9df0/ruff-0.9.10-py3-none-macosx_11_0_arm64.whl", hash = "sha256:5284dcac6b9dbc2fcb71fdfc26a217b2ca4ede6ccd57476f52a587451ebe450d", size = 10155692 }, - { url = "https://files.pythonhosted.org/packages/5b/01/85e8082e41585e0e1ceb11e41c054e9e36fed45f4b210991052d8a75089f/ruff-0.9.10-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:47678f39fa2a3da62724851107f438c8229a3470f533894b5568a39b40029c0c", size = 10369760 }, - { url = "https://files.pythonhosted.org/packages/a1/90/0bc60bd4e5db051f12445046d0c85cc2c617095c0904f1aa81067dc64aea/ruff-0.9.10-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:99713a6e2766b7a17147b309e8c915b32b07a25c9efd12ada79f217c9c778b3e", size = 9912196 }, - { url = "https://files.pythonhosted.org/packages/66/ea/0b7e8c42b1ec608033c4d5a02939c82097ddcb0b3e393e4238584b7054ab/ruff-0.9.10-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:524ee184d92f7c7304aa568e2db20f50c32d1d0caa235d8ddf10497566ea1a12", size = 11434985 }, - { url = "https://files.pythonhosted.org/packages/d5/86/3171d1eff893db4f91755175a6e1163c5887be1f1e2f4f6c0c59527c2bfd/ruff-0.9.10-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:df92aeac30af821f9acf819fc01b4afc3dfb829d2782884f8739fb52a8119a16", size = 12155842 }, - { url = "https://files.pythonhosted.org/packages/89/9e/700ca289f172a38eb0bca752056d0a42637fa17b81649b9331786cb791d7/ruff-0.9.10-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de42e4edc296f520bb84954eb992a07a0ec5a02fecb834498415908469854a52", size = 11613804 }, - { url = "https://files.pythonhosted.org/packages/f2/92/648020b3b5db180f41a931a68b1c8575cca3e63cec86fd26807422a0dbad/ruff-0.9.10-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d257f95b65806104b6b1ffca0ea53f4ef98454036df65b1eda3693534813ecd1", size = 13823776 }, - { url = "https://files.pythonhosted.org/packages/5e/a6/cc472161cd04d30a09d5c90698696b70c169eeba2c41030344194242db45/ruff-0.9.10-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b60dec7201c0b10d6d11be00e8f2dbb6f40ef1828ee75ed739923799513db24c", size = 11302673 }, - { url = "https://files.pythonhosted.org/packages/6c/db/d31c361c4025b1b9102b4d032c70a69adb9ee6fde093f6c3bf29f831c85c/ruff-0.9.10-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:d838b60007da7a39c046fcdd317293d10b845001f38bcb55ba766c3875b01e43", size = 10235358 }, - { url = "https://files.pythonhosted.org/packages/d1/86/d6374e24a14d4d93ebe120f45edd82ad7dcf3ef999ffc92b197d81cdc2a5/ruff-0.9.10-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:ccaf903108b899beb8e09a63ffae5869057ab649c1e9231c05ae354ebc62066c", size = 9886177 }, - { url = "https://files.pythonhosted.org/packages/00/62/a61691f6eaaac1e945a1f3f59f1eea9a218513139d5b6c2b8f88b43b5b8f/ruff-0.9.10-py3-none-musllinux_1_2_i686.whl", hash = "sha256:f9567d135265d46e59d62dc60c0bfad10e9a6822e231f5b24032dba5a55be6b5", size = 10864747 }, - { url = "https://files.pythonhosted.org/packages/ee/94/2c7065e1d92a8a8a46d46d9c3cf07b0aa7e0a1e0153d74baa5e6620b4102/ruff-0.9.10-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:5f202f0d93738c28a89f8ed9eaba01b7be339e5d8d642c994347eaa81c6d75b8", size = 11360441 }, - { url = "https://files.pythonhosted.org/packages/a7/8f/1f545ea6f9fcd7bf4368551fb91d2064d8f0577b3079bb3f0ae5779fb773/ruff-0.9.10-py3-none-win32.whl", hash = "sha256:bfb834e87c916521ce46b1788fbb8484966e5113c02df216680102e9eb960029", size = 10247401 }, - { url = "https://files.pythonhosted.org/packages/4f/18/fb703603ab108e5c165f52f5b86ee2aa9be43bb781703ec87c66a5f5d604/ruff-0.9.10-py3-none-win_amd64.whl", hash = "sha256:f2160eeef3031bf4b17df74e307d4c5fb689a6f3a26a2de3f7ef4044e3c484f1", size = 11366360 }, - { url = "https://files.pythonhosted.org/packages/35/85/338e603dc68e7d9994d5d84f24adbf69bae760ba5efd3e20f5ff2cec18da/ruff-0.9.10-py3-none-win_arm64.whl", hash = "sha256:5fd804c0327a5e5ea26615550e706942f348b197d5475ff34c19733aee4b2e69", size = 10436892 }, +version = "0.11.10" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e8/4c/4a3c5a97faaae6b428b336dcca81d03ad04779f8072c267ad2bd860126bf/ruff-0.11.10.tar.gz", hash = "sha256:d522fb204b4959909ecac47da02830daec102eeb100fb50ea9554818d47a5fa6", size = 4165632, upload-time = "2025-05-15T14:08:56.76Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/2f/9f/596c628f8824a2ce4cd12b0f0b4c0629a62dfffc5d0f742c19a1d71be108/ruff-0.11.10-py3-none-linux_armv6l.whl", hash = "sha256:859a7bfa7bc8888abbea31ef8a2b411714e6a80f0d173c2a82f9041ed6b50f58", size = 10316243, upload-time = "2025-05-15T14:08:12.884Z" }, + { url = "https://files.pythonhosted.org/packages/3c/38/c1e0b77ab58b426f8c332c1d1d3432d9fc9a9ea622806e208220cb133c9e/ruff-0.11.10-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:968220a57e09ea5e4fd48ed1c646419961a0570727c7e069842edd018ee8afed", size = 11083636, upload-time = "2025-05-15T14:08:16.551Z" }, + { url = "https://files.pythonhosted.org/packages/23/41/b75e15961d6047d7fe1b13886e56e8413be8467a4e1be0a07f3b303cd65a/ruff-0.11.10-py3-none-macosx_11_0_arm64.whl", hash = "sha256:1067245bad978e7aa7b22f67113ecc6eb241dca0d9b696144256c3a879663bca", size = 10441624, upload-time = "2025-05-15T14:08:19.032Z" }, + { url = "https://files.pythonhosted.org/packages/b6/2c/e396b6703f131406db1811ea3d746f29d91b41bbd43ad572fea30da1435d/ruff-0.11.10-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f4854fd09c7aed5b1590e996a81aeff0c9ff51378b084eb5a0b9cd9518e6cff2", size = 10624358, upload-time = "2025-05-15T14:08:21.542Z" }, + { url = "https://files.pythonhosted.org/packages/bd/8c/ee6cca8bdaf0f9a3704796022851a33cd37d1340bceaf4f6e991eb164e2e/ruff-0.11.10-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:8b4564e9f99168c0f9195a0fd5fa5928004b33b377137f978055e40008a082c5", size = 10176850, upload-time = "2025-05-15T14:08:23.682Z" }, + { url = "https://files.pythonhosted.org/packages/e9/ce/4e27e131a434321b3b7c66512c3ee7505b446eb1c8a80777c023f7e876e6/ruff-0.11.10-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5b6a9cc5b62c03cc1fea0044ed8576379dbaf751d5503d718c973d5418483641", size = 11759787, upload-time = "2025-05-15T14:08:25.733Z" }, + { url = "https://files.pythonhosted.org/packages/58/de/1e2e77fc72adc7cf5b5123fd04a59ed329651d3eab9825674a9e640b100b/ruff-0.11.10-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:607ecbb6f03e44c9e0a93aedacb17b4eb4f3563d00e8b474298a201622677947", size = 12430479, upload-time = "2025-05-15T14:08:28.013Z" }, + { url = "https://files.pythonhosted.org/packages/07/ed/af0f2340f33b70d50121628ef175523cc4c37619e98d98748c85764c8d88/ruff-0.11.10-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7b3a522fa389402cd2137df9ddefe848f727250535c70dafa840badffb56b7a4", size = 11919760, upload-time = "2025-05-15T14:08:30.956Z" }, + { url = "https://files.pythonhosted.org/packages/24/09/d7b3d3226d535cb89234390f418d10e00a157b6c4a06dfbe723e9322cb7d/ruff-0.11.10-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2f071b0deed7e9245d5820dac235cbdd4ef99d7b12ff04c330a241ad3534319f", size = 14041747, upload-time = "2025-05-15T14:08:33.297Z" }, + { url = "https://files.pythonhosted.org/packages/62/b3/a63b4e91850e3f47f78795e6630ee9266cb6963de8f0191600289c2bb8f4/ruff-0.11.10-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4a60e3a0a617eafba1f2e4186d827759d65348fa53708ca547e384db28406a0b", size = 11550657, upload-time = "2025-05-15T14:08:35.639Z" }, + { url = "https://files.pythonhosted.org/packages/46/63/a4f95c241d79402ccdbdb1d823d156c89fbb36ebfc4289dce092e6c0aa8f/ruff-0.11.10-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:da8ec977eaa4b7bf75470fb575bea2cb41a0e07c7ea9d5a0a97d13dbca697bf2", size = 10489671, upload-time = "2025-05-15T14:08:38.437Z" }, + { url = "https://files.pythonhosted.org/packages/6a/9b/c2238bfebf1e473495659c523d50b1685258b6345d5ab0b418ca3f010cd7/ruff-0.11.10-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:ddf8967e08227d1bd95cc0851ef80d2ad9c7c0c5aab1eba31db49cf0a7b99523", size = 10160135, upload-time = "2025-05-15T14:08:41.247Z" }, + { url = "https://files.pythonhosted.org/packages/ba/ef/ba7251dd15206688dbfba7d413c0312e94df3b31b08f5d695580b755a899/ruff-0.11.10-py3-none-musllinux_1_2_i686.whl", hash = "sha256:5a94acf798a82db188f6f36575d80609072b032105d114b0f98661e1679c9125", size = 11170179, upload-time = "2025-05-15T14:08:43.762Z" }, + { url = "https://files.pythonhosted.org/packages/73/9f/5c336717293203ba275dbfa2ea16e49b29a9fd9a0ea8b6febfc17e133577/ruff-0.11.10-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:3afead355f1d16d95630df28d4ba17fb2cb9c8dfac8d21ced14984121f639bad", size = 11626021, upload-time = "2025-05-15T14:08:46.451Z" }, + { url = "https://files.pythonhosted.org/packages/d9/2b/162fa86d2639076667c9aa59196c020dc6d7023ac8f342416c2f5ec4bda0/ruff-0.11.10-py3-none-win32.whl", hash = "sha256:dc061a98d32a97211af7e7f3fa1d4ca2fcf919fb96c28f39551f35fc55bdbc19", size = 10494958, upload-time = "2025-05-15T14:08:49.601Z" }, + { url = "https://files.pythonhosted.org/packages/24/f3/66643d8f32f50a4b0d09a4832b7d919145ee2b944d43e604fbd7c144d175/ruff-0.11.10-py3-none-win_amd64.whl", hash = "sha256:5cc725fbb4d25b0f185cb42df07ab6b76c4489b4bfb740a175f3a59c70e8a224", size = 11650285, upload-time = "2025-05-15T14:08:52.392Z" }, + { url = "https://files.pythonhosted.org/packages/95/3a/2e8704d19f376c799748ff9cb041225c1d59f3e7711bc5596c8cfdc24925/ruff-0.11.10-py3-none-win_arm64.whl", hash = "sha256:ef69637b35fb8b210743926778d0e45e1bffa850a7c61e428c6b971549b5f5d1", size = 10765278, upload-time = "2025-05-15T14:08:54.56Z" }, ] [[package]] name = "scons" -version = "4.9.0" +version = "4.9.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/61/7e/79e07dc2eb8874580934cd0c834a8a78f15d5b0d6155a424f6c7b35441c3/scons-4.9.0.tar.gz", hash = "sha256:f1a5e161bf3d1411d780d65d7919654b9405555994621d3d68e42d62114b592a", size = 3251763 } +sdist = { url = "https://files.pythonhosted.org/packages/c8/c1/30176c76c1ef723fab62e5cdb15d3c972427a146cb6f868748613d7b25af/scons-4.9.1.tar.gz", hash = "sha256:bacac880ba2e86d6a156c116e2f8f2bfa82b257046f3ac2666c85c53c615c338", size = 3252106, upload-time = "2025-03-27T20:42:19.765Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/18/f5/77635f6c68ed742a23e1f52977267e191ea7c2aec89b9604a86487405da1/scons-4.9.0-py3-none-any.whl", hash = "sha256:c8cc309db0f91cffdc27c1374fa3d31e9421bcb31d210de071b0b11adc84739b", size = 4130637 }, + { url = "https://files.pythonhosted.org/packages/45/92/50b739021983b131dcacd57aa8b04d31c5acc2e7e0eb4ed4a362f438c6b7/scons-4.9.1-py3-none-any.whl", hash = "sha256:d2db1a22eb6039e97cbbb0106f18f435af033d0aad190299c9688378e2810a5e", size = 4131331, upload-time = "2025-03-27T20:42:16.665Z" }, ] [[package]] name = "sentry-sdk" -version = "2.22.0" +version = "2.29.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/81/b6/662988ecd2345bf6c3a5c306a9a3590852742eff91d0a78a143398b816f3/sentry_sdk-2.22.0.tar.gz", hash = "sha256:b4bf43bb38f547c84b2eadcefbe389b36ef75f3f38253d7a74d6b928c07ae944", size = 303539 } +sdist = { url = "https://files.pythonhosted.org/packages/22/67/d552a5f8e5a6a56b2feea6529e2d8ccd54349084c84176d5a1f7295044bc/sentry_sdk-2.29.1.tar.gz", hash = "sha256:8d4a0206b95fa5fe85e5e7517ed662e3888374bdc342c00e435e10e6d831aa6d", size = 325518, upload-time = "2025-05-19T14:27:38.512Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/12/7f/0e4459173e9671ba5f75a48dda2442bcc48a12c79e54e5789381c8c6a9bc/sentry_sdk-2.22.0-py2.py3-none-any.whl", hash = "sha256:3d791d631a6c97aad4da7074081a57073126c69487560c6f8bffcf586461de66", size = 325815 }, + { url = "https://files.pythonhosted.org/packages/f0/e5/da07b0bd832cefd52d16f2b9bbbe31624d57552602c06631686b93ccb1bd/sentry_sdk-2.29.1-py2.py3-none-any.whl", hash = "sha256:90862fe0616ded4572da6c9dadb363121a1ae49a49e21c418f0634e9d10b4c19", size = 341553, upload-time = "2025-05-19T14:27:36.882Z" }, ] [[package]] name = "setproctitle" -version = "1.3.5" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/c4/4d/6a840c8d2baa07b57329490e7094f90aac177a1d5226bc919046f1106860/setproctitle-1.3.5.tar.gz", hash = "sha256:1e6eaeaf8a734d428a95d8c104643b39af7d247d604f40a7bebcf3960a853c5e", size = 26737 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ec/4a/9e0243c5df221102fb834a947f5753d9da06ad5f84e36b0e2e93f7865edb/setproctitle-1.3.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1c8dcc250872385f2780a5ea58050b58cbc8b6a7e8444952a5a65c359886c593", size = 17256 }, - { url = "https://files.pythonhosted.org/packages/c7/a1/76ad2ba6f5bd00609238e3d64eeded4598e742a5f25b5cc1a0efdae5f674/setproctitle-1.3.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ca82fae9eb4800231dd20229f06e8919787135a5581da245b8b05e864f34cc8b", size = 11893 }, - { url = "https://files.pythonhosted.org/packages/47/3a/75d11fedff5b21ba9a4c5fe3dfa5e596f831d094ef1896713a72e9e38833/setproctitle-1.3.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0424e1d33232322541cb36fb279ea5242203cd6f20de7b4fb2a11973d8e8c2ce", size = 31631 }, - { url = "https://files.pythonhosted.org/packages/5a/12/58220de5600e0ed2e5562297173187d863db49babb03491ffe9c101299bc/setproctitle-1.3.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fec8340ab543144d04a9d805d80a0aad73fdeb54bea6ff94e70d39a676ea4ec0", size = 32975 }, - { url = "https://files.pythonhosted.org/packages/fa/c4/fbb308680d83c1c7aa626950308318c6e6381a8273779163a31741f3c752/setproctitle-1.3.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:eab441c89f181271ab749077dcc94045a423e51f2fb0b120a1463ef9820a08d0", size = 30126 }, - { url = "https://files.pythonhosted.org/packages/31/6e/baaf70bd9a881dd8c12cbccdd7ca0ff291024a37044a8245e942e12e7135/setproctitle-1.3.5-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d2c371550a2288901a0dcd84192691ebd3197a43c95f3e0b396ed6d1cedf5c6c", size = 31135 }, - { url = "https://files.pythonhosted.org/packages/a6/dc/d8ab6b1c3d844dc14f596e3cce76604570848f8a67ba6a3812775ed2c015/setproctitle-1.3.5-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:78288ff5f9c415c56595b2257ad218936dd9fa726b36341b373b31ca958590fe", size = 30874 }, - { url = "https://files.pythonhosted.org/packages/d4/84/62a359b3aa51228bd88f78b44ebb0256a5b96dd2487881c1e984a59b617d/setproctitle-1.3.5-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f1f13a25fc46731acab518602bb1149bfd8b5fabedf8290a7c0926d61414769d", size = 29893 }, - { url = "https://files.pythonhosted.org/packages/e2/d6/b3c52c03ee41e7f006e1a737e0db1c58d1dc28e258b83548e653d0c34f1c/setproctitle-1.3.5-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:1534d6cd3854d035e40bf4c091984cbdd4d555d7579676d406c53c8f187c006f", size = 32293 }, - { url = "https://files.pythonhosted.org/packages/55/09/c0ba311879d9c05860503a7e2708ace85913b9a816786402a92c664fe930/setproctitle-1.3.5-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:62a01c76708daac78b9688ffb95268c57cb57fa90b543043cda01358912fe2db", size = 30247 }, - { url = "https://files.pythonhosted.org/packages/9e/43/cc7155461f0b5a48aebdb87d78239ff3a51ebda0905de478d9fa6ab92d9c/setproctitle-1.3.5-cp311-cp311-win32.whl", hash = "sha256:ea07f29735d839eaed985990a0ec42c8aecefe8050da89fec35533d146a7826d", size = 11476 }, - { url = "https://files.pythonhosted.org/packages/e7/57/6e937ac7aa52db69225f02db2cfdcb66ba1db6fdc65a4ddbdf78e214f72a/setproctitle-1.3.5-cp311-cp311-win_amd64.whl", hash = "sha256:ab3ae11e10d13d514d4a5a15b4f619341142ba3e18da48c40e8614c5a1b5e3c3", size = 12189 }, - { url = "https://files.pythonhosted.org/packages/2b/19/04755958495de57e4891de50f03e77b3fe9ca6716a86de00faa00ad0ee5a/setproctitle-1.3.5-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:523424b9be4dea97d95b8a584b183f35c7bab2d0a3d995b01febf5b8a8de90e4", size = 17250 }, - { url = "https://files.pythonhosted.org/packages/b9/3d/2ca9df5aa49b975296411dcbbe272cdb1c5e514c43b8be7d61751bb71a46/setproctitle-1.3.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b6ec1d86c1b4d7b5f2bdceadf213310cf24696b82480a2a702194b8a0bfbcb47", size = 11878 }, - { url = "https://files.pythonhosted.org/packages/36/d6/e90e23b4627e016a4f862d4f892be92c9765dd6bf1e27a48e52cd166d4a3/setproctitle-1.3.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ea6c505264275a43e9b2acd2acfc11ac33caf52bc3167c9fced4418a810f6b1c", size = 31940 }, - { url = "https://files.pythonhosted.org/packages/15/13/167cdd55e00a8e10b36aad79646c3bf3c23fba0c08a9b8db9b74622c1b13/setproctitle-1.3.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0b91e68e6685998e6353f296100ecabc313a6cb3e413d66a03d74b988b61f5ff", size = 33370 }, - { url = "https://files.pythonhosted.org/packages/9b/22/574a110527df133409a75053b7d6ff740993ccf30b8713d042f26840d351/setproctitle-1.3.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bc1fda208ae3a2285ad27aeab44c41daf2328abe58fa3270157a739866779199", size = 30628 }, - { url = "https://files.pythonhosted.org/packages/52/79/78b05c7d792c9167b917acdab1773b1ff73b016560f45d8155be2baa1a82/setproctitle-1.3.5-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:828727d220e46f048b82289018300a64547b46aaed96bf8810c05fe105426b41", size = 31672 }, - { url = "https://files.pythonhosted.org/packages/b0/62/4509735be062129694751ac55d5e1fbb6d86fa46a8689b7d5e2c23dae5b0/setproctitle-1.3.5-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:83b016221cf80028b2947be20630faa14e3e72a403e35f0ba29550b4e856767b", size = 31378 }, - { url = "https://files.pythonhosted.org/packages/72/e7/b394c55934b89f00c2ef7d5e6f18cca5d8dfa26ef628700c4de0c85e3f3d/setproctitle-1.3.5-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:6d8a411e752e794d052434139ca4234ffeceeb8d8d8ddc390a9051d7942b2726", size = 30370 }, - { url = "https://files.pythonhosted.org/packages/13/ee/e1f27bf52d2bec7060bb6311ab0ccede8de98ed5394e3a59e7a14a453fb5/setproctitle-1.3.5-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:50cfbf86b9c63a2c2903f1231f0a58edeb775e651ae1af84eec8430b0571f29b", size = 32875 }, - { url = "https://files.pythonhosted.org/packages/6e/08/13b561085d2de53b9becfa5578545d99114e9ff2aa3dc151bcaadf80b17e/setproctitle-1.3.5-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f3b5e2eacd572444770026c9dd3ddc7543ce427cdf452d40a408d1e95beefb30", size = 30903 }, - { url = "https://files.pythonhosted.org/packages/65/f0/6cd06fffff2553be7b0571447d0c0ef8b727ef44cc2d6a33452677a311c8/setproctitle-1.3.5-cp312-cp312-win32.whl", hash = "sha256:cf4e3ded98027de2596c6cc5bbd3302adfb3ca315c848f56516bb0b7e88de1e9", size = 11468 }, - { url = "https://files.pythonhosted.org/packages/c1/8c/e8a7cb568c4552618838941b332203bfc77ab0f2d67c1cb8f24dee0370ec/setproctitle-1.3.5-cp312-cp312-win_amd64.whl", hash = "sha256:f7a8c01ffd013dda2bed6e7d5cb59fbb609e72f805abf3ee98360f38f7758d9b", size = 12190 }, +version = "1.3.6" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/9e/af/56efe21c53ac81ac87e000b15e60b3d8104224b4313b6eacac3597bd183d/setproctitle-1.3.6.tar.gz", hash = "sha256:c9f32b96c700bb384f33f7cf07954bb609d35dd82752cef57fb2ee0968409169", size = 26889, upload-time = "2025-04-29T13:35:00.184Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/27/3b/8288d0cd969a63500dd62fc2c99ce6980f9909ccef0770ab1f86c361e0bf/setproctitle-1.3.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a1d856b0f4e4a33e31cdab5f50d0a14998f3a2d726a3fd5cb7c4d45a57b28d1b", size = 17412, upload-time = "2025-04-29T13:32:58.135Z" }, + { url = "https://files.pythonhosted.org/packages/39/37/43a5a3e25ca1048dbbf4db0d88d346226f5f1acd131bb8e660f4bfe2799f/setproctitle-1.3.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:50706b9c0eda55f7de18695bfeead5f28b58aa42fd5219b3b1692d554ecbc9ec", size = 11963, upload-time = "2025-04-29T13:32:59.17Z" }, + { url = "https://files.pythonhosted.org/packages/5b/47/f103c40e133154783c91a10ab08ac9fc410ed835aa85bcf7107cb882f505/setproctitle-1.3.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:af188f3305f0a65c3217c30c6d4c06891e79144076a91e8b454f14256acc7279", size = 31718, upload-time = "2025-04-29T13:33:00.36Z" }, + { url = "https://files.pythonhosted.org/packages/1f/13/7325dd1c008dd6c0ebd370ddb7505977054a87e406f142318e395031a792/setproctitle-1.3.6-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cce0ed8b3f64c71c140f0ec244e5fdf8ecf78ddf8d2e591d4a8b6aa1c1214235", size = 33027, upload-time = "2025-04-29T13:33:01.499Z" }, + { url = "https://files.pythonhosted.org/packages/0c/0a/6075bfea05a71379d77af98a9ac61163e8b6e5ef1ae58cd2b05871b2079c/setproctitle-1.3.6-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:70100e2087fe05359f249a0b5f393127b3a1819bf34dec3a3e0d4941138650c9", size = 30223, upload-time = "2025-04-29T13:33:03.259Z" }, + { url = "https://files.pythonhosted.org/packages/cc/41/fbf57ec52f4f0776193bd94334a841f0bc9d17e745f89c7790f336420c65/setproctitle-1.3.6-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1065ed36bd03a3fd4186d6c6de5f19846650b015789f72e2dea2d77be99bdca1", size = 31204, upload-time = "2025-04-29T13:33:04.455Z" }, + { url = "https://files.pythonhosted.org/packages/97/b5/f799fb7a00de29fb0ac1dfd015528dea425b9e31a8f1068a0b3df52d317f/setproctitle-1.3.6-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:4adf6a0013fe4e0844e3ba7583ec203ca518b9394c6cc0d3354df2bf31d1c034", size = 31181, upload-time = "2025-04-29T13:33:05.697Z" }, + { url = "https://files.pythonhosted.org/packages/b5/b7/81f101b612014ec61723436022c31146178813d6ca6b947f7b9c84e9daf4/setproctitle-1.3.6-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:eb7452849f6615871eabed6560ffedfe56bc8af31a823b6be4ce1e6ff0ab72c5", size = 30101, upload-time = "2025-04-29T13:33:07.223Z" }, + { url = "https://files.pythonhosted.org/packages/67/23/681232eed7640eab96719daa8647cc99b639e3daff5c287bd270ef179a73/setproctitle-1.3.6-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a094b7ce455ca341b59a0f6ce6be2e11411ba6e2860b9aa3dbb37468f23338f4", size = 32438, upload-time = "2025-04-29T13:33:08.538Z" }, + { url = "https://files.pythonhosted.org/packages/19/f8/4d075a7bdc3609ac71535b849775812455e4c40aedfbf0778a6f123b1774/setproctitle-1.3.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:ad1c2c2baaba62823a7f348f469a967ece0062140ca39e7a48e4bbb1f20d54c4", size = 30625, upload-time = "2025-04-29T13:33:09.707Z" }, + { url = "https://files.pythonhosted.org/packages/5f/73/a2a8259ebee166aee1ca53eead75de0e190b3ddca4f716e5c7470ebb7ef6/setproctitle-1.3.6-cp311-cp311-win32.whl", hash = "sha256:8050c01331135f77ec99d99307bfbc6519ea24d2f92964b06f3222a804a3ff1f", size = 11488, upload-time = "2025-04-29T13:33:10.953Z" }, + { url = "https://files.pythonhosted.org/packages/c9/15/52cf5e1ff0727d53704cfdde2858eaf237ce523b0b04db65faa84ff83e13/setproctitle-1.3.6-cp311-cp311-win_amd64.whl", hash = "sha256:9b73cf0fe28009a04a35bb2522e4c5b5176cc148919431dcb73fdbdfaab15781", size = 12201, upload-time = "2025-04-29T13:33:12.389Z" }, + { url = "https://files.pythonhosted.org/packages/8f/fb/99456fd94d4207c5f6c40746a048a33a52b4239cd7d9c8d4889e2210ec82/setproctitle-1.3.6-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:af44bb7a1af163806bbb679eb8432fa7b4fb6d83a5d403b541b675dcd3798638", size = 17399, upload-time = "2025-04-29T13:33:13.406Z" }, + { url = "https://files.pythonhosted.org/packages/d5/48/9699191fe6062827683c43bfa9caac33a2c89f8781dd8c7253fa3dba85fd/setproctitle-1.3.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3cca16fd055316a48f0debfcbfb6af7cea715429fc31515ab3fcac05abd527d8", size = 11966, upload-time = "2025-04-29T13:33:14.976Z" }, + { url = "https://files.pythonhosted.org/packages/33/03/b085d192b9ecb9c7ce6ad6ef30ecf4110b7f39430b58a56245569827fcf4/setproctitle-1.3.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ea002088d5554fd75e619742cefc78b84a212ba21632e59931b3501f0cfc8f67", size = 32017, upload-time = "2025-04-29T13:33:16.163Z" }, + { url = "https://files.pythonhosted.org/packages/ae/68/c53162e645816f97212002111420d1b2f75bf6d02632e37e961dc2cd6d8b/setproctitle-1.3.6-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:bb465dd5825356c1191a038a86ee1b8166e3562d6e8add95eec04ab484cfb8a2", size = 33419, upload-time = "2025-04-29T13:33:18.239Z" }, + { url = "https://files.pythonhosted.org/packages/ac/0d/119a45d15a816a6cf5ccc61b19729f82620095b27a47e0a6838216a95fae/setproctitle-1.3.6-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d2c8e20487b3b73c1fa72c56f5c89430617296cd380373e7af3a538a82d4cd6d", size = 30711, upload-time = "2025-04-29T13:33:19.571Z" }, + { url = "https://files.pythonhosted.org/packages/e3/fb/5e9b5068df9e9f31a722a775a5e8322a29a638eaaa3eac5ea7f0b35e6314/setproctitle-1.3.6-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a0d6252098e98129a1decb59b46920d4eca17b0395f3d71b0d327d086fefe77d", size = 31742, upload-time = "2025-04-29T13:33:21.172Z" }, + { url = "https://files.pythonhosted.org/packages/35/88/54de1e73e8fce87d587889c7eedb48fc4ee2bbe4e4ca6331690d03024f86/setproctitle-1.3.6-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:cf355fbf0d4275d86f9f57be705d8e5eaa7f8ddb12b24ced2ea6cbd68fdb14dc", size = 31925, upload-time = "2025-04-29T13:33:22.427Z" }, + { url = "https://files.pythonhosted.org/packages/f3/01/65948d7badd66e63e3db247b923143da142790fa293830fdecf832712c2d/setproctitle-1.3.6-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:e288f8a162d663916060beb5e8165a8551312b08efee9cf68302687471a6545d", size = 30981, upload-time = "2025-04-29T13:33:23.739Z" }, + { url = "https://files.pythonhosted.org/packages/22/20/c495e61786f1d38d5dc340b9d9077fee9be3dfc7e89f515afe12e1526dbc/setproctitle-1.3.6-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:b2e54f4a2dc6edf0f5ea5b1d0a608d2af3dcb5aa8c8eeab9c8841b23e1b054fe", size = 33209, upload-time = "2025-04-29T13:33:24.915Z" }, + { url = "https://files.pythonhosted.org/packages/98/3f/a457b8550fbd34d5b482fe20b8376b529e76bf1fbf9a474a6d9a641ab4ad/setproctitle-1.3.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:b6f4abde9a2946f57e8daaf1160b2351bcf64274ef539e6675c1d945dbd75e2a", size = 31587, upload-time = "2025-04-29T13:33:26.123Z" }, + { url = "https://files.pythonhosted.org/packages/44/fe/743517340e5a635e3f1c4310baea20c16c66202f96a6f4cead222ffd6d84/setproctitle-1.3.6-cp312-cp312-win32.whl", hash = "sha256:db608db98ccc21248370d30044a60843b3f0f3d34781ceeea67067c508cd5a28", size = 11487, upload-time = "2025-04-29T13:33:27.403Z" }, + { url = "https://files.pythonhosted.org/packages/60/9a/d88f1c1f0f4efff1bd29d9233583ee341114dda7d9613941453984849674/setproctitle-1.3.6-cp312-cp312-win_amd64.whl", hash = "sha256:082413db8a96b1f021088e8ec23f0a61fec352e649aba20881895815388b66d3", size = 12208, upload-time = "2025-04-29T13:33:28.852Z" }, ] [[package]] name = "setuptools" -version = "76.0.0" +version = "80.8.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/32/d2/7b171caf085ba0d40d8391f54e1c75a1cda9255f542becf84575cfd8a732/setuptools-76.0.0.tar.gz", hash = "sha256:43b4ee60e10b0d0ee98ad11918e114c70701bc6051662a9a675a0496c1a158f4", size = 1349387 } +sdist = { url = "https://files.pythonhosted.org/packages/8d/d2/ec1acaaff45caed5c2dedb33b67055ba9d4e96b091094df90762e60135fe/setuptools-80.8.0.tar.gz", hash = "sha256:49f7af965996f26d43c8ae34539c8d99c5042fbff34302ea151eaa9c207cd257", size = 1319720, upload-time = "2025-05-20T14:02:53.503Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/37/66/d2d7e6ad554f3a7c7297c3f8ef6e22643ad3d35ef5c63bf488bc89f32f31/setuptools-76.0.0-py3-none-any.whl", hash = "sha256:199466a166ff664970d0ee145839f5582cb9bca7a0a3a2e795b6a9cb2308e9c6", size = 1236106 }, + { url = "https://files.pythonhosted.org/packages/58/29/93c53c098d301132196c3238c312825324740851d77a8500a2462c0fd888/setuptools-80.8.0-py3-none-any.whl", hash = "sha256:95a60484590d24103af13b686121328cc2736bee85de8936383111e421b9edc0", size = 1201470, upload-time = "2025-05-20T14:02:51.348Z" }, ] [[package]] name = "shapely" -version = "2.0.7" +version = "2.1.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "numpy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/21/c0/a911d1fd765d07a2b6769ce155219a281bfbe311584ebe97340d75c5bdb1/shapely-2.0.7.tar.gz", hash = "sha256:28fe2997aab9a9dc026dc6a355d04e85841546b2a5d232ed953e3321ab958ee5", size = 283413 } +sdist = { url = "https://files.pythonhosted.org/packages/ca/3c/2da625233f4e605155926566c0e7ea8dda361877f48e8b1655e53456f252/shapely-2.1.1.tar.gz", hash = "sha256:500621967f2ffe9642454808009044c21e5b35db89ce69f8a2042c2ffd0e2772", size = 315422, upload-time = "2025-05-19T11:04:41.265Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1d/ad/21798c2fec013e289f8ab91d42d4d3299c315b8c4460c08c75fef0901713/shapely-2.0.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5cf23400cb25deccf48c56a7cdda8197ae66c0e9097fcdd122ac2007e320bc34", size = 1473091 }, - { url = "https://files.pythonhosted.org/packages/15/63/eef4f180f1b5859c70e7f91d2f2570643e5c61e7d7c40743d15f8c6cbc42/shapely-2.0.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d8f1da01c04527f7da59ee3755d8ee112cd8967c15fab9e43bba936b81e2a013", size = 1332921 }, - { url = "https://files.pythonhosted.org/packages/fe/67/77851dd17738bbe7762a0ef1acf7bc499d756f68600dd68a987d78229412/shapely-2.0.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8f623b64bb219d62014781120f47499a7adc30cf7787e24b659e56651ceebcb0", size = 2427949 }, - { url = "https://files.pythonhosted.org/packages/0b/a5/2c8dbb0f383519771df19164e3bf3a8895d195d2edeab4b6040f176ee28e/shapely-2.0.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e6d95703efaa64aaabf278ced641b888fc23d9c6dd71f8215091afd8a26a66e3", size = 2529282 }, - { url = "https://files.pythonhosted.org/packages/dc/4e/e1d608773c7fe4cde36d48903c0d6298e3233dc69412403783ac03fa5205/shapely-2.0.7-cp311-cp311-win32.whl", hash = "sha256:2f6e4759cf680a0f00a54234902415f2fa5fe02f6b05546c662654001f0793a2", size = 1295751 }, - { url = "https://files.pythonhosted.org/packages/27/57/8ec7c62012bed06731f7ee979da7f207bbc4b27feed5f36680b6a70df54f/shapely-2.0.7-cp311-cp311-win_amd64.whl", hash = "sha256:b52f3ab845d32dfd20afba86675c91919a622f4627182daec64974db9b0b4608", size = 1442684 }, - { url = "https://files.pythonhosted.org/packages/4f/3e/ea100eec5811bafd0175eb21828a3be5b0960f65250f4474391868be7c0f/shapely-2.0.7-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4c2b9859424facbafa54f4a19b625a752ff958ab49e01bc695f254f7db1835fa", size = 1482451 }, - { url = "https://files.pythonhosted.org/packages/ce/53/c6a3487716fd32e1f813d2a9608ba7b72a8a52a6966e31c6443480a1d016/shapely-2.0.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5aed1c6764f51011d69a679fdf6b57e691371ae49ebe28c3edb5486537ffbd51", size = 1345765 }, - { url = "https://files.pythonhosted.org/packages/fd/dd/b35d7891d25cc11066a70fb8d8169a6a7fca0735dd9b4d563a84684969a3/shapely-2.0.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73c9ae8cf443187d784d57202199bf9fd2d4bb7d5521fe8926ba40db1bc33e8e", size = 2421540 }, - { url = "https://files.pythonhosted.org/packages/62/de/8dbd7df60eb23cb983bb698aac982944b3d602ef0ce877a940c269eae34e/shapely-2.0.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a9469f49ff873ef566864cb3516091881f217b5d231c8164f7883990eec88b73", size = 2525741 }, - { url = "https://files.pythonhosted.org/packages/96/64/faf0413ebc7a84fe7a0790bf39ec0b02b40132b68e57aba985c0b6e4e7b6/shapely-2.0.7-cp312-cp312-win32.whl", hash = "sha256:6bca5095e86be9d4ef3cb52d56bdd66df63ff111d580855cb8546f06c3c907cd", size = 1296552 }, - { url = "https://files.pythonhosted.org/packages/63/05/8a1c279c226d6ad7604d9e237713dd21788eab96db97bf4ce0ea565e5596/shapely-2.0.7-cp312-cp312-win_amd64.whl", hash = "sha256:f86e2c0259fe598c4532acfcf638c1f520fa77c1275912bbc958faecbf00b108", size = 1443464 }, + { url = "https://files.pythonhosted.org/packages/19/97/2df985b1e03f90c503796ad5ecd3d9ed305123b64d4ccb54616b30295b29/shapely-2.1.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:587a1aa72bc858fab9b8c20427b5f6027b7cbc92743b8e2c73b9de55aa71c7a7", size = 1819368, upload-time = "2025-05-19T11:03:55.937Z" }, + { url = "https://files.pythonhosted.org/packages/56/17/504518860370f0a28908b18864f43d72f03581e2b6680540ca668f07aa42/shapely-2.1.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9fa5c53b0791a4b998f9ad84aad456c988600757a96b0a05e14bba10cebaaaea", size = 1625362, upload-time = "2025-05-19T11:03:57.06Z" }, + { url = "https://files.pythonhosted.org/packages/36/a1/9677337d729b79fce1ef3296aac6b8ef4743419086f669e8a8070eff8f40/shapely-2.1.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aabecd038841ab5310d23495253f01c2a82a3aedae5ab9ca489be214aa458aa7", size = 2999005, upload-time = "2025-05-19T11:03:58.692Z" }, + { url = "https://files.pythonhosted.org/packages/a2/17/e09357274699c6e012bbb5a8ea14765a4d5860bb658df1931c9f90d53bd3/shapely-2.1.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:586f6aee1edec04e16227517a866df3e9a2e43c1f635efc32978bb3dc9c63753", size = 3108489, upload-time = "2025-05-19T11:04:00.059Z" }, + { url = "https://files.pythonhosted.org/packages/17/5d/93a6c37c4b4e9955ad40834f42b17260ca74ecf36df2e81bb14d12221b90/shapely-2.1.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b9878b9e37ad26c72aada8de0c9cfe418d9e2ff36992a1693b7f65a075b28647", size = 3945727, upload-time = "2025-05-19T11:04:01.786Z" }, + { url = "https://files.pythonhosted.org/packages/a3/1a/ad696648f16fd82dd6bfcca0b3b8fbafa7aacc13431c7fc4c9b49e481681/shapely-2.1.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d9a531c48f289ba355e37b134e98e28c557ff13965d4653a5228d0f42a09aed0", size = 4109311, upload-time = "2025-05-19T11:04:03.134Z" }, + { url = "https://files.pythonhosted.org/packages/d4/38/150dd245beab179ec0d4472bf6799bf18f21b1efbef59ac87de3377dbf1c/shapely-2.1.1-cp311-cp311-win32.whl", hash = "sha256:4866de2673a971820c75c0167b1f1cd8fb76f2d641101c23d3ca021ad0449bab", size = 1522982, upload-time = "2025-05-19T11:04:05.217Z" }, + { url = "https://files.pythonhosted.org/packages/93/5b/842022c00fbb051083c1c85430f3bb55565b7fd2d775f4f398c0ba8052ce/shapely-2.1.1-cp311-cp311-win_amd64.whl", hash = "sha256:20a9d79958b3d6c70d8a886b250047ea32ff40489d7abb47d01498c704557a93", size = 1703872, upload-time = "2025-05-19T11:04:06.791Z" }, + { url = "https://files.pythonhosted.org/packages/fb/64/9544dc07dfe80a2d489060791300827c941c451e2910f7364b19607ea352/shapely-2.1.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:2827365b58bf98efb60affc94a8e01c56dd1995a80aabe4b701465d86dcbba43", size = 1833021, upload-time = "2025-05-19T11:04:08.022Z" }, + { url = "https://files.pythonhosted.org/packages/07/aa/fb5f545e72e89b6a0f04a0effda144f5be956c9c312c7d4e00dfddbddbcf/shapely-2.1.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a9c551f7fa7f1e917af2347fe983f21f212863f1d04f08eece01e9c275903fad", size = 1643018, upload-time = "2025-05-19T11:04:09.343Z" }, + { url = "https://files.pythonhosted.org/packages/03/46/61e03edba81de729f09d880ce7ae5c1af873a0814206bbfb4402ab5c3388/shapely-2.1.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:78dec4d4fbe7b1db8dc36de3031767e7ece5911fb7782bc9e95c5cdec58fb1e9", size = 2986417, upload-time = "2025-05-19T11:04:10.56Z" }, + { url = "https://files.pythonhosted.org/packages/1f/1e/83ec268ab8254a446b4178b45616ab5822d7b9d2b7eb6e27cf0b82f45601/shapely-2.1.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:872d3c0a7b8b37da0e23d80496ec5973c4692920b90de9f502b5beb994bbaaef", size = 3098224, upload-time = "2025-05-19T11:04:11.903Z" }, + { url = "https://files.pythonhosted.org/packages/f1/44/0c21e7717c243e067c9ef8fa9126de24239f8345a5bba9280f7bb9935959/shapely-2.1.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:2e2b9125ebfbc28ecf5353511de62f75a8515ae9470521c9a693e4bb9fbe0cf1", size = 3925982, upload-time = "2025-05-19T11:04:13.224Z" }, + { url = "https://files.pythonhosted.org/packages/15/50/d3b4e15fefc103a0eb13d83bad5f65cd6e07a5d8b2ae920e767932a247d1/shapely-2.1.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4b96cea171b3d7f6786976a0520f178c42792897653ecca0c5422fb1e6946e6d", size = 4089122, upload-time = "2025-05-19T11:04:14.477Z" }, + { url = "https://files.pythonhosted.org/packages/bd/05/9a68f27fc6110baeedeeebc14fd86e73fa38738c5b741302408fb6355577/shapely-2.1.1-cp312-cp312-win32.whl", hash = "sha256:39dca52201e02996df02e447f729da97cfb6ff41a03cb50f5547f19d02905af8", size = 1522437, upload-time = "2025-05-19T11:04:16.203Z" }, + { url = "https://files.pythonhosted.org/packages/bc/e9/a4560e12b9338842a1f82c9016d2543eaa084fce30a1ca11991143086b57/shapely-2.1.1-cp312-cp312-win_amd64.whl", hash = "sha256:13d643256f81d55a50013eff6321142781cf777eb6a9e207c2c9e6315ba6044a", size = 1703479, upload-time = "2025-05-19T11:04:18.497Z" }, ] [[package]] name = "siphash24" version = "1.7" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/0e/be/f0a0ffbb00c51c5633b41459b5ce9b017c025a9256b4403e648c18e70850/siphash24-1.7.tar.gz", hash = "sha256:6e90fee5f199ea25b4e7303646b31872a437174fe885a93dbd4cf7784eb48164", size = 19801 } +sdist = { url = "https://files.pythonhosted.org/packages/0e/be/f0a0ffbb00c51c5633b41459b5ce9b017c025a9256b4403e648c18e70850/siphash24-1.7.tar.gz", hash = "sha256:6e90fee5f199ea25b4e7303646b31872a437174fe885a93dbd4cf7784eb48164", size = 19801, upload-time = "2024-10-15T13:41:51.924Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4e/67/4ffd23a848739966e1b314ef99f6410035bccee00be14261313787b8f506/siphash24-1.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:de75488e93f1cd12c8d5004efd1ebd958c0265205a9d73e8dd8b071900838841", size = 80493 }, - { url = "https://files.pythonhosted.org/packages/56/bd/ec198a8c7aef65e967ae84f633bd9950d784c9e527d738c9a3e4bccc34a5/siphash24-1.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ffca9908450f9f346e97a223185fcd16217d67d84c6f246f3080c4224f41a514", size = 75350 }, - { url = "https://files.pythonhosted.org/packages/50/5a/77838c916bd15addfc2e51286db4c442cb12e25eb4f8d296c394c2280240/siphash24-1.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b8ff44ce166452993fea267ea1b2fd089d8e7f103b13d360da441f12b0df121d", size = 100567 }, - { url = "https://files.pythonhosted.org/packages/f0/aa/736a0a2efae9a6f69ac1ee4d28c2274fcad2150349fac752d6c525c4e06e/siphash24-1.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4062548dcb1eef13bbe0356d6f8675bfe4571ef38d7103445daa82ba167240d1", size = 105630 }, - { url = "https://files.pythonhosted.org/packages/79/52/1afbd70142d3db093d49197e3abe15ca2f1a14678299327ba776944b4771/siphash24-1.7-cp311-cp311-win32.whl", hash = "sha256:7b4ea29376b688fbcc3d25707c15a9dfe7b4ebbc4322878d75bb77e199210a39", size = 67648 }, - { url = "https://files.pythonhosted.org/packages/b5/1d/bedcd04c2d1d199c9f6b3e61a6caae0e17257696c9f49594e49856b17a99/siphash24-1.7-cp311-cp311-win_amd64.whl", hash = "sha256:ec06104e6ef1e512ee30f1b8aeae2b83c0f55f12a94042f0df5a87d43a1f4c52", size = 80046 }, - { url = "https://files.pythonhosted.org/packages/3e/62/93e552af9535a416f684327f870143ee42fc9e816091672467cdfd62cce6/siphash24-1.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:76a64ff0cdd192e4d0a391956d9b121c56ed56e773c5ab7eb7c3e035fd16e8cb", size = 82084 }, - { url = "https://files.pythonhosted.org/packages/59/3e/b0791ab53aa9ac191b71a021eab2e75baa7c27d7feb7ec148d7961d148ba/siphash24-1.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:49ca649bc7437d614f758891deade3b187832792a853269219e77f10509f82fe", size = 76233 }, - { url = "https://files.pythonhosted.org/packages/29/4c/4c1b809bf302e9b60f3ec09ba115b2a4ac1ff6755735ee8884924fcdb45e/siphash24-1.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bc37dd0aed23f76bd257fbd2953fd5d954b329d7463c6ff57263a2699c52dde6", size = 98188 }, - { url = "https://files.pythonhosted.org/packages/96/bf/e6b49f8ff88130bd224f291ea77d30fdde4df5f6572c519aca5d8fc8a27c/siphash24-1.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eea490a200891905856b6ad0f9c56d4ec787876220bcb34c49441b2566b97887", size = 102946 }, - { url = "https://files.pythonhosted.org/packages/3d/75/45c831626013950fb2ea715c218c3397e5cf2328a67208bf5d8ff69aa9e6/siphash24-1.7-cp312-cp312-win32.whl", hash = "sha256:69eb8c2c112a738875bb283cd53ef5e86874bc5aed17f3020b38e9174208fb79", size = 68323 }, - { url = "https://files.pythonhosted.org/packages/e0/d3/39190c40a68defd19b99c1082dd7455543a52283803bfa111b0e45fae968/siphash24-1.7-cp312-cp312-win_amd64.whl", hash = "sha256:7459569ea4669b6feeaf7d299fc5157cc5c69ca1231dc0decb7a7da2397c782e", size = 81000 }, + { url = "https://files.pythonhosted.org/packages/4e/67/4ffd23a848739966e1b314ef99f6410035bccee00be14261313787b8f506/siphash24-1.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:de75488e93f1cd12c8d5004efd1ebd958c0265205a9d73e8dd8b071900838841", size = 80493, upload-time = "2024-10-15T13:41:14.727Z" }, + { url = "https://files.pythonhosted.org/packages/56/bd/ec198a8c7aef65e967ae84f633bd9950d784c9e527d738c9a3e4bccc34a5/siphash24-1.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ffca9908450f9f346e97a223185fcd16217d67d84c6f246f3080c4224f41a514", size = 75350, upload-time = "2024-10-15T13:41:16.262Z" }, + { url = "https://files.pythonhosted.org/packages/50/5a/77838c916bd15addfc2e51286db4c442cb12e25eb4f8d296c394c2280240/siphash24-1.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b8ff44ce166452993fea267ea1b2fd089d8e7f103b13d360da441f12b0df121d", size = 100567, upload-time = "2024-10-15T13:41:17.435Z" }, + { url = "https://files.pythonhosted.org/packages/f0/aa/736a0a2efae9a6f69ac1ee4d28c2274fcad2150349fac752d6c525c4e06e/siphash24-1.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4062548dcb1eef13bbe0356d6f8675bfe4571ef38d7103445daa82ba167240d1", size = 105630, upload-time = "2024-10-15T13:41:18.578Z" }, + { url = "https://files.pythonhosted.org/packages/79/52/1afbd70142d3db093d49197e3abe15ca2f1a14678299327ba776944b4771/siphash24-1.7-cp311-cp311-win32.whl", hash = "sha256:7b4ea29376b688fbcc3d25707c15a9dfe7b4ebbc4322878d75bb77e199210a39", size = 67648, upload-time = "2024-10-15T13:41:19.606Z" }, + { url = "https://files.pythonhosted.org/packages/b5/1d/bedcd04c2d1d199c9f6b3e61a6caae0e17257696c9f49594e49856b17a99/siphash24-1.7-cp311-cp311-win_amd64.whl", hash = "sha256:ec06104e6ef1e512ee30f1b8aeae2b83c0f55f12a94042f0df5a87d43a1f4c52", size = 80046, upload-time = "2024-10-15T13:41:20.654Z" }, + { url = "https://files.pythonhosted.org/packages/3e/62/93e552af9535a416f684327f870143ee42fc9e816091672467cdfd62cce6/siphash24-1.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:76a64ff0cdd192e4d0a391956d9b121c56ed56e773c5ab7eb7c3e035fd16e8cb", size = 82084, upload-time = "2024-10-15T13:41:21.776Z" }, + { url = "https://files.pythonhosted.org/packages/59/3e/b0791ab53aa9ac191b71a021eab2e75baa7c27d7feb7ec148d7961d148ba/siphash24-1.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:49ca649bc7437d614f758891deade3b187832792a853269219e77f10509f82fe", size = 76233, upload-time = "2024-10-15T13:41:22.787Z" }, + { url = "https://files.pythonhosted.org/packages/29/4c/4c1b809bf302e9b60f3ec09ba115b2a4ac1ff6755735ee8884924fcdb45e/siphash24-1.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bc37dd0aed23f76bd257fbd2953fd5d954b329d7463c6ff57263a2699c52dde6", size = 98188, upload-time = "2024-10-15T13:41:24.327Z" }, + { url = "https://files.pythonhosted.org/packages/96/bf/e6b49f8ff88130bd224f291ea77d30fdde4df5f6572c519aca5d8fc8a27c/siphash24-1.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eea490a200891905856b6ad0f9c56d4ec787876220bcb34c49441b2566b97887", size = 102946, upload-time = "2024-10-15T13:41:25.633Z" }, + { url = "https://files.pythonhosted.org/packages/3d/75/45c831626013950fb2ea715c218c3397e5cf2328a67208bf5d8ff69aa9e6/siphash24-1.7-cp312-cp312-win32.whl", hash = "sha256:69eb8c2c112a738875bb283cd53ef5e86874bc5aed17f3020b38e9174208fb79", size = 68323, upload-time = "2024-10-15T13:41:27.349Z" }, + { url = "https://files.pythonhosted.org/packages/e0/d3/39190c40a68defd19b99c1082dd7455543a52283803bfa111b0e45fae968/siphash24-1.7-cp312-cp312-win_amd64.whl", hash = "sha256:7459569ea4669b6feeaf7d299fc5157cc5c69ca1231dc0decb7a7da2397c782e", size = 81000, upload-time = "2024-10-15T13:41:28.364Z" }, ] [[package]] name = "six" version = "1.17.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/94/e7/b2c673351809dca68a0e064b6af791aa332cf192da575fd474ed7d6f16a2/six-1.17.0.tar.gz", hash = "sha256:ff70335d468e7eb6ec65b95b99d3a2836546063f63acc5171de367e834932a81", size = 34031 } +sdist = { url = "https://files.pythonhosted.org/packages/94/e7/b2c673351809dca68a0e064b6af791aa332cf192da575fd474ed7d6f16a2/six-1.17.0.tar.gz", hash = "sha256:ff70335d468e7eb6ec65b95b99d3a2836546063f63acc5171de367e834932a81", size = 34031, upload-time = "2024-12-04T17:35:28.174Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b7/ce/149a00dd41f10bc29e5921b496af8b574d8413afcd5e30dfa0ed46c2cc5e/six-1.17.0-py2.py3-none-any.whl", hash = "sha256:4721f391ed90541fddacab5acf947aa0d3dc7d27b2e1e8eda2be8970586c3274", size = 11050 }, + { url = "https://files.pythonhosted.org/packages/b7/ce/149a00dd41f10bc29e5921b496af8b574d8413afcd5e30dfa0ed46c2cc5e/six-1.17.0-py2.py3-none-any.whl", hash = "sha256:4721f391ed90541fddacab5acf947aa0d3dc7d27b2e1e8eda2be8970586c3274", size = 11050, upload-time = "2024-12-04T17:35:26.475Z" }, ] [[package]] name = "smbus2" version = "0.5.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/10/c9/6d85aa809e107adf85303010a59b340be109c8f815cbedc5c08c73bcffef/smbus2-0.5.0.tar.gz", hash = "sha256:4a5946fd82277870c2878befdb1a29bb28d15cda14ea4d8d2d54cf3d4bdcb035", size = 16950 } +sdist = { url = "https://files.pythonhosted.org/packages/10/c9/6d85aa809e107adf85303010a59b340be109c8f815cbedc5c08c73bcffef/smbus2-0.5.0.tar.gz", hash = "sha256:4a5946fd82277870c2878befdb1a29bb28d15cda14ea4d8d2d54cf3d4bdcb035", size = 16950, upload-time = "2024-10-19T09:20:56.746Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/85/9f/2235ba9001e3c29fc342eeb222104420bcb7bac51555f0c034376a744075/smbus2-0.5.0-py2.py3-none-any.whl", hash = "sha256:1a15c3b9fa69357beb038cc0b5d37939702f8bfde1ddc89ca9f17d8461dbe949", size = 11527 }, + { url = "https://files.pythonhosted.org/packages/85/9f/2235ba9001e3c29fc342eeb222104420bcb7bac51555f0c034376a744075/smbus2-0.5.0-py2.py3-none-any.whl", hash = "sha256:1a15c3b9fa69357beb038cc0b5d37939702f8bfde1ddc89ca9f17d8461dbe949", size = 11527, upload-time = "2024-10-19T09:20:55.202Z" }, ] [[package]] name = "sortedcontainers" version = "2.4.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e8/c4/ba2f8066cceb6f23394729afe52f3bf7adec04bf9ed2c820b39e19299111/sortedcontainers-2.4.0.tar.gz", hash = "sha256:25caa5a06cc30b6b83d11423433f65d1f9d76c4c6a0c90e3379eaa43b9bfdb88", size = 30594 } +sdist = { url = "https://files.pythonhosted.org/packages/e8/c4/ba2f8066cceb6f23394729afe52f3bf7adec04bf9ed2c820b39e19299111/sortedcontainers-2.4.0.tar.gz", hash = "sha256:25caa5a06cc30b6b83d11423433f65d1f9d76c4c6a0c90e3379eaa43b9bfdb88", size = 30594, upload-time = "2021-05-16T22:03:42.897Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/32/46/9cb0e58b2deb7f82b84065f37f3bffeb12413f947f9388e4cac22c4621ce/sortedcontainers-2.4.0-py2.py3-none-any.whl", hash = "sha256:a163dcaede0f1c021485e957a39245190e74249897e2ae4b2aa38595db237ee0", size = 29575 }, + { url = "https://files.pythonhosted.org/packages/32/46/9cb0e58b2deb7f82b84065f37f3bffeb12413f947f9388e4cac22c4621ce/sortedcontainers-2.4.0-py2.py3-none-any.whl", hash = "sha256:a163dcaede0f1c021485e957a39245190e74249897e2ae4b2aa38595db237ee0", size = 29575, upload-time = "2021-05-16T22:03:41.177Z" }, ] [[package]] name = "sounddevice" -version = "0.5.1" +version = "0.5.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/80/2d/b04ae180312b81dbb694504bee170eada5372242e186f6298139fd3a0513/sounddevice-0.5.1.tar.gz", hash = "sha256:09ca991daeda8ce4be9ac91e15a9a81c8f81efa6b695a348c9171ea0c16cb041", size = 52896 } +sdist = { url = "https://files.pythonhosted.org/packages/91/a6/91e9f08ed37c7c9f56b5227c6aea7f2ae63ba2d59520eefb24e82cbdd589/sounddevice-0.5.2.tar.gz", hash = "sha256:c634d51bd4e922d6f0fa5e1a975cc897c947f61d31da9f79ba7ea34dff448b49", size = 53150, upload-time = "2025-05-16T18:12:27.339Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/06/d1/464b5fca3decdd0cfec8c47f7b4161a0b12972453201c1bf03811f367c5e/sounddevice-0.5.1-py3-none-any.whl", hash = "sha256:e2017f182888c3f3c280d9fbac92e5dbddac024a7e3442f6e6116bd79dab8a9c", size = 32276 }, - { url = "https://files.pythonhosted.org/packages/6f/f6/6703fe7cf3d7b7279040c792aeec6334e7305956aba4a80f23e62c8fdc44/sounddevice-0.5.1-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:d16cb23d92322526a86a9490c427bf8d49e273d9ccc0bd096feecd229cde6031", size = 107916 }, - { url = "https://files.pythonhosted.org/packages/57/a5/78a5e71f5ec0faedc54f4053775d61407bfbd7d0c18228c7f3d4252fd276/sounddevice-0.5.1-py3-none-win32.whl", hash = "sha256:d84cc6231526e7a08e89beff229c37f762baefe5e0cc2747cbe8e3a565470055", size = 312494 }, - { url = "https://files.pythonhosted.org/packages/af/9b/15217b04f3b36d30de55fef542389d722de63f1ad81f9c72d8afc98cb6ab/sounddevice-0.5.1-py3-none-win_amd64.whl", hash = "sha256:4313b63f2076552b23ac3e0abd3bcfc0c1c6a696fc356759a13bd113c9df90f1", size = 363634 }, + { url = "https://files.pythonhosted.org/packages/75/2d/582738fc01352a5bc20acac9221e58538365cecb3bb264838f66419df219/sounddevice-0.5.2-py3-none-any.whl", hash = "sha256:82375859fac2e73295a4ab3fc60bd4782743157adc339561c1f1142af472f505", size = 32450, upload-time = "2025-05-16T18:12:21.919Z" }, + { url = "https://files.pythonhosted.org/packages/3f/6f/e3dd751face4fcb5be25e8abba22f25d8e6457ebd7e9ed79068b768dc0e5/sounddevice-0.5.2-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:943f27e66037d41435bdd0293454072cdf657b594c9cde63cd01ee3daaac7ab3", size = 108088, upload-time = "2025-05-16T18:12:23.146Z" }, + { url = "https://files.pythonhosted.org/packages/45/0b/bfad79af0b380aa7c0bfe73e4b03e0af45354a48ad62549489bd7696c5b0/sounddevice-0.5.2-py3-none-win32.whl", hash = "sha256:3a113ce614a2c557f14737cb20123ae6298c91fc9301eb014ada0cba6d248c5f", size = 312665, upload-time = "2025-05-16T18:12:24.726Z" }, + { url = "https://files.pythonhosted.org/packages/e1/3e/61d88e6b0a7383127cdc779195cb9d83ebcf11d39bc961de5777e457075e/sounddevice-0.5.2-py3-none-win_amd64.whl", hash = "sha256:e18944b767d2dac3771a7771bdd7ff7d3acd7d334e72c4bedab17d1aed5dbc22", size = 363808, upload-time = "2025-05-16T18:12:26Z" }, ] [[package]] name = "spidev" -version = "3.6" +version = "3.7" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/c7/d9/401c0a7be089e02826cf2c201f489876b601f15be100fe391ef9c2faed83/spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b", size = 11917 } +sdist = { url = "https://files.pythonhosted.org/packages/b5/99/dd50af8200e224ce9412ad01cdbeeb5b39b2d61acd72138f2b92c4a6d619/spidev-3.7.tar.gz", hash = "sha256:ce628a5ff489f45132679879bff5f455a66abf9751af01843850155b06ae92f0", size = 11616, upload-time = "2025-05-06T14:23:30.783Z" } [[package]] name = "sympy" -version = "1.13.3" +version = "1.14.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "mpmath" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/11/8a/5a7fd6284fa8caac23a26c9ddf9c30485a48169344b4bd3b0f02fef1890f/sympy-1.13.3.tar.gz", hash = "sha256:b27fd2c6530e0ab39e275fc9b683895367e51d5da91baa8d3d64db2565fec4d9", size = 7533196 } +sdist = { url = "https://files.pythonhosted.org/packages/83/d3/803453b36afefb7c2bb238361cd4ae6125a569b4db67cd9e79846ba2d68c/sympy-1.14.0.tar.gz", hash = "sha256:d3d3fe8df1e5a0b42f0e7bdf50541697dbe7d23746e894990c030e2b05e72517", size = 7793921, upload-time = "2025-04-27T18:05:01.611Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/99/ff/c87e0622b1dadea79d2fb0b25ade9ed98954c9033722eb707053d310d4f3/sympy-1.13.3-py3-none-any.whl", hash = "sha256:54612cf55a62755ee71824ce692986f23c88ffa77207b30c1368eda4a7060f73", size = 6189483 }, + { url = "https://files.pythonhosted.org/packages/a2/09/77d55d46fd61b4a135c444fc97158ef34a095e5681d0a6c10b75bf356191/sympy-1.14.0-py3-none-any.whl", hash = "sha256:e091cc3e99d2141a0ba2847328f5479b05d94a6635cb96148ccb3f34671bd8f5", size = 6299353, upload-time = "2025-04-27T18:04:59.103Z" }, ] [[package]] name = "tabulate" version = "0.9.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ec/fe/802052aecb21e3797b8f7902564ab6ea0d60ff8ca23952079064155d1ae1/tabulate-0.9.0.tar.gz", hash = "sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c", size = 81090 } +sdist = { url = "https://files.pythonhosted.org/packages/ec/fe/802052aecb21e3797b8f7902564ab6ea0d60ff8ca23952079064155d1ae1/tabulate-0.9.0.tar.gz", hash = "sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c", size = 81090, upload-time = "2022-10-06T17:21:48.54Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/40/44/4a5f08c96eb108af5cb50b41f76142f0afa346dfa99d5296fe7202a11854/tabulate-0.9.0-py3-none-any.whl", hash = "sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f", size = 35252 }, + { url = "https://files.pythonhosted.org/packages/40/44/4a5f08c96eb108af5cb50b41f76142f0afa346dfa99d5296fe7202a11854/tabulate-0.9.0-py3-none-any.whl", hash = "sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f", size = 35252, upload-time = "2022-10-06T17:21:44.262Z" }, ] [[package]] name = "tomli" version = "2.2.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/18/87/302344fed471e44a87289cf4967697d07e532f2421fdaf868a303cbae4ff/tomli-2.2.1.tar.gz", hash = "sha256:cd45e1dc79c835ce60f7404ec8119f2eb06d38b1deba146f07ced3bbc44505ff", size = 17175 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/43/ca/75707e6efa2b37c77dadb324ae7d9571cb424e61ea73fad7c56c2d14527f/tomli-2.2.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:678e4fa69e4575eb77d103de3df8a895e1591b48e740211bd1067378c69e8249", size = 131077 }, - { url = "https://files.pythonhosted.org/packages/c7/16/51ae563a8615d472fdbffc43a3f3d46588c264ac4f024f63f01283becfbb/tomli-2.2.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:023aa114dd824ade0100497eb2318602af309e5a55595f76b626d6d9f3b7b0a6", size = 123429 }, - { url = "https://files.pythonhosted.org/packages/f1/dd/4f6cd1e7b160041db83c694abc78e100473c15d54620083dbd5aae7b990e/tomli-2.2.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ece47d672db52ac607a3d9599a9d48dcb2f2f735c6c2d1f34130085bb12b112a", size = 226067 }, - { url = "https://files.pythonhosted.org/packages/a9/6b/c54ede5dc70d648cc6361eaf429304b02f2871a345bbdd51e993d6cdf550/tomli-2.2.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6972ca9c9cc9f0acaa56a8ca1ff51e7af152a9f87fb64623e31d5c83700080ee", size = 236030 }, - { url = "https://files.pythonhosted.org/packages/1f/47/999514fa49cfaf7a92c805a86c3c43f4215621855d151b61c602abb38091/tomli-2.2.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c954d2250168d28797dd4e3ac5cf812a406cd5a92674ee4c8f123c889786aa8e", size = 240898 }, - { url = "https://files.pythonhosted.org/packages/73/41/0a01279a7ae09ee1573b423318e7934674ce06eb33f50936655071d81a24/tomli-2.2.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8dd28b3e155b80f4d54beb40a441d366adcfe740969820caf156c019fb5c7ec4", size = 229894 }, - { url = "https://files.pythonhosted.org/packages/55/18/5d8bc5b0a0362311ce4d18830a5d28943667599a60d20118074ea1b01bb7/tomli-2.2.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:e59e304978767a54663af13c07b3d1af22ddee3bb2fb0618ca1593e4f593a106", size = 245319 }, - { url = "https://files.pythonhosted.org/packages/92/a3/7ade0576d17f3cdf5ff44d61390d4b3febb8a9fc2b480c75c47ea048c646/tomli-2.2.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:33580bccab0338d00994d7f16f4c4ec25b776af3ffaac1ed74e0b3fc95e885a8", size = 238273 }, - { url = "https://files.pythonhosted.org/packages/72/6f/fa64ef058ac1446a1e51110c375339b3ec6be245af9d14c87c4a6412dd32/tomli-2.2.1-cp311-cp311-win32.whl", hash = "sha256:465af0e0875402f1d226519c9904f37254b3045fc5084697cefb9bdde1ff99ff", size = 98310 }, - { url = "https://files.pythonhosted.org/packages/6a/1c/4a2dcde4a51b81be3530565e92eda625d94dafb46dbeb15069df4caffc34/tomli-2.2.1-cp311-cp311-win_amd64.whl", hash = "sha256:2d0f2fdd22b02c6d81637a3c95f8cd77f995846af7414c5c4b8d0545afa1bc4b", size = 108309 }, - { url = "https://files.pythonhosted.org/packages/52/e1/f8af4c2fcde17500422858155aeb0d7e93477a0d59a98e56cbfe75070fd0/tomli-2.2.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4a8f6e44de52d5e6c657c9fe83b562f5f4256d8ebbfe4ff922c495620a7f6cea", size = 132762 }, - { url = "https://files.pythonhosted.org/packages/03/b8/152c68bb84fc00396b83e7bbddd5ec0bd3dd409db4195e2a9b3e398ad2e3/tomli-2.2.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8d57ca8095a641b8237d5b079147646153d22552f1c637fd3ba7f4b0b29167a8", size = 123453 }, - { url = "https://files.pythonhosted.org/packages/c8/d6/fc9267af9166f79ac528ff7e8c55c8181ded34eb4b0e93daa767b8841573/tomli-2.2.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4e340144ad7ae1533cb897d406382b4b6fede8890a03738ff1683af800d54192", size = 233486 }, - { url = "https://files.pythonhosted.org/packages/5c/51/51c3f2884d7bab89af25f678447ea7d297b53b5a3b5730a7cb2ef6069f07/tomli-2.2.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:db2b95f9de79181805df90bedc5a5ab4c165e6ec3fe99f970d0e302f384ad222", size = 242349 }, - { url = "https://files.pythonhosted.org/packages/ab/df/bfa89627d13a5cc22402e441e8a931ef2108403db390ff3345c05253935e/tomli-2.2.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:40741994320b232529c802f8bc86da4e1aa9f413db394617b9a256ae0f9a7f77", size = 252159 }, - { url = "https://files.pythonhosted.org/packages/9e/6e/fa2b916dced65763a5168c6ccb91066f7639bdc88b48adda990db10c8c0b/tomli-2.2.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:400e720fe168c0f8521520190686ef8ef033fb19fc493da09779e592861b78c6", size = 237243 }, - { url = "https://files.pythonhosted.org/packages/b4/04/885d3b1f650e1153cbb93a6a9782c58a972b94ea4483ae4ac5cedd5e4a09/tomli-2.2.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:02abe224de6ae62c19f090f68da4e27b10af2b93213d36cf44e6e1c5abd19fdd", size = 259645 }, - { url = "https://files.pythonhosted.org/packages/9c/de/6b432d66e986e501586da298e28ebeefd3edc2c780f3ad73d22566034239/tomli-2.2.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:b82ebccc8c8a36f2094e969560a1b836758481f3dc360ce9a3277c65f374285e", size = 244584 }, - { url = "https://files.pythonhosted.org/packages/1c/9a/47c0449b98e6e7d1be6cbac02f93dd79003234ddc4aaab6ba07a9a7482e2/tomli-2.2.1-cp312-cp312-win32.whl", hash = "sha256:889f80ef92701b9dbb224e49ec87c645ce5df3fa2cc548664eb8a25e03127a98", size = 98875 }, - { url = "https://files.pythonhosted.org/packages/ef/60/9b9638f081c6f1261e2688bd487625cd1e660d0a85bd469e91d8db969734/tomli-2.2.1-cp312-cp312-win_amd64.whl", hash = "sha256:7fc04e92e1d624a4a63c76474610238576942d6b8950a2d7f908a340494e67e4", size = 109418 }, - { url = "https://files.pythonhosted.org/packages/6e/c2/61d3e0f47e2b74ef40a68b9e6ad5984f6241a942f7cd3bbfbdbd03861ea9/tomli-2.2.1-py3-none-any.whl", hash = "sha256:cb55c73c5f4408779d0cf3eef9f762b9c9f147a77de7b258bef0a5628adc85cc", size = 14257 }, +sdist = { url = "https://files.pythonhosted.org/packages/18/87/302344fed471e44a87289cf4967697d07e532f2421fdaf868a303cbae4ff/tomli-2.2.1.tar.gz", hash = "sha256:cd45e1dc79c835ce60f7404ec8119f2eb06d38b1deba146f07ced3bbc44505ff", size = 17175, upload-time = "2024-11-27T22:38:36.873Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/43/ca/75707e6efa2b37c77dadb324ae7d9571cb424e61ea73fad7c56c2d14527f/tomli-2.2.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:678e4fa69e4575eb77d103de3df8a895e1591b48e740211bd1067378c69e8249", size = 131077, upload-time = "2024-11-27T22:37:54.956Z" }, + { url = "https://files.pythonhosted.org/packages/c7/16/51ae563a8615d472fdbffc43a3f3d46588c264ac4f024f63f01283becfbb/tomli-2.2.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:023aa114dd824ade0100497eb2318602af309e5a55595f76b626d6d9f3b7b0a6", size = 123429, upload-time = "2024-11-27T22:37:56.698Z" }, + { url = "https://files.pythonhosted.org/packages/f1/dd/4f6cd1e7b160041db83c694abc78e100473c15d54620083dbd5aae7b990e/tomli-2.2.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ece47d672db52ac607a3d9599a9d48dcb2f2f735c6c2d1f34130085bb12b112a", size = 226067, upload-time = "2024-11-27T22:37:57.63Z" }, + { url = "https://files.pythonhosted.org/packages/a9/6b/c54ede5dc70d648cc6361eaf429304b02f2871a345bbdd51e993d6cdf550/tomli-2.2.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6972ca9c9cc9f0acaa56a8ca1ff51e7af152a9f87fb64623e31d5c83700080ee", size = 236030, upload-time = "2024-11-27T22:37:59.344Z" }, + { url = "https://files.pythonhosted.org/packages/1f/47/999514fa49cfaf7a92c805a86c3c43f4215621855d151b61c602abb38091/tomli-2.2.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c954d2250168d28797dd4e3ac5cf812a406cd5a92674ee4c8f123c889786aa8e", size = 240898, upload-time = "2024-11-27T22:38:00.429Z" }, + { url = "https://files.pythonhosted.org/packages/73/41/0a01279a7ae09ee1573b423318e7934674ce06eb33f50936655071d81a24/tomli-2.2.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8dd28b3e155b80f4d54beb40a441d366adcfe740969820caf156c019fb5c7ec4", size = 229894, upload-time = "2024-11-27T22:38:02.094Z" }, + { url = "https://files.pythonhosted.org/packages/55/18/5d8bc5b0a0362311ce4d18830a5d28943667599a60d20118074ea1b01bb7/tomli-2.2.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:e59e304978767a54663af13c07b3d1af22ddee3bb2fb0618ca1593e4f593a106", size = 245319, upload-time = "2024-11-27T22:38:03.206Z" }, + { url = "https://files.pythonhosted.org/packages/92/a3/7ade0576d17f3cdf5ff44d61390d4b3febb8a9fc2b480c75c47ea048c646/tomli-2.2.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:33580bccab0338d00994d7f16f4c4ec25b776af3ffaac1ed74e0b3fc95e885a8", size = 238273, upload-time = "2024-11-27T22:38:04.217Z" }, + { url = "https://files.pythonhosted.org/packages/72/6f/fa64ef058ac1446a1e51110c375339b3ec6be245af9d14c87c4a6412dd32/tomli-2.2.1-cp311-cp311-win32.whl", hash = "sha256:465af0e0875402f1d226519c9904f37254b3045fc5084697cefb9bdde1ff99ff", size = 98310, upload-time = "2024-11-27T22:38:05.908Z" }, + { url = "https://files.pythonhosted.org/packages/6a/1c/4a2dcde4a51b81be3530565e92eda625d94dafb46dbeb15069df4caffc34/tomli-2.2.1-cp311-cp311-win_amd64.whl", hash = "sha256:2d0f2fdd22b02c6d81637a3c95f8cd77f995846af7414c5c4b8d0545afa1bc4b", size = 108309, upload-time = "2024-11-27T22:38:06.812Z" }, + { url = "https://files.pythonhosted.org/packages/52/e1/f8af4c2fcde17500422858155aeb0d7e93477a0d59a98e56cbfe75070fd0/tomli-2.2.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4a8f6e44de52d5e6c657c9fe83b562f5f4256d8ebbfe4ff922c495620a7f6cea", size = 132762, upload-time = "2024-11-27T22:38:07.731Z" }, + { url = "https://files.pythonhosted.org/packages/03/b8/152c68bb84fc00396b83e7bbddd5ec0bd3dd409db4195e2a9b3e398ad2e3/tomli-2.2.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8d57ca8095a641b8237d5b079147646153d22552f1c637fd3ba7f4b0b29167a8", size = 123453, upload-time = "2024-11-27T22:38:09.384Z" }, + { url = "https://files.pythonhosted.org/packages/c8/d6/fc9267af9166f79ac528ff7e8c55c8181ded34eb4b0e93daa767b8841573/tomli-2.2.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4e340144ad7ae1533cb897d406382b4b6fede8890a03738ff1683af800d54192", size = 233486, upload-time = "2024-11-27T22:38:10.329Z" }, + { url = "https://files.pythonhosted.org/packages/5c/51/51c3f2884d7bab89af25f678447ea7d297b53b5a3b5730a7cb2ef6069f07/tomli-2.2.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:db2b95f9de79181805df90bedc5a5ab4c165e6ec3fe99f970d0e302f384ad222", size = 242349, upload-time = "2024-11-27T22:38:11.443Z" }, + { url = "https://files.pythonhosted.org/packages/ab/df/bfa89627d13a5cc22402e441e8a931ef2108403db390ff3345c05253935e/tomli-2.2.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:40741994320b232529c802f8bc86da4e1aa9f413db394617b9a256ae0f9a7f77", size = 252159, upload-time = "2024-11-27T22:38:13.099Z" }, + { url = "https://files.pythonhosted.org/packages/9e/6e/fa2b916dced65763a5168c6ccb91066f7639bdc88b48adda990db10c8c0b/tomli-2.2.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:400e720fe168c0f8521520190686ef8ef033fb19fc493da09779e592861b78c6", size = 237243, upload-time = "2024-11-27T22:38:14.766Z" }, + { url = "https://files.pythonhosted.org/packages/b4/04/885d3b1f650e1153cbb93a6a9782c58a972b94ea4483ae4ac5cedd5e4a09/tomli-2.2.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:02abe224de6ae62c19f090f68da4e27b10af2b93213d36cf44e6e1c5abd19fdd", size = 259645, upload-time = "2024-11-27T22:38:15.843Z" }, + { url = "https://files.pythonhosted.org/packages/9c/de/6b432d66e986e501586da298e28ebeefd3edc2c780f3ad73d22566034239/tomli-2.2.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:b82ebccc8c8a36f2094e969560a1b836758481f3dc360ce9a3277c65f374285e", size = 244584, upload-time = "2024-11-27T22:38:17.645Z" }, + { url = "https://files.pythonhosted.org/packages/1c/9a/47c0449b98e6e7d1be6cbac02f93dd79003234ddc4aaab6ba07a9a7482e2/tomli-2.2.1-cp312-cp312-win32.whl", hash = "sha256:889f80ef92701b9dbb224e49ec87c645ce5df3fa2cc548664eb8a25e03127a98", size = 98875, upload-time = "2024-11-27T22:38:19.159Z" }, + { url = "https://files.pythonhosted.org/packages/ef/60/9b9638f081c6f1261e2688bd487625cd1e660d0a85bd469e91d8db969734/tomli-2.2.1-cp312-cp312-win_amd64.whl", hash = "sha256:7fc04e92e1d624a4a63c76474610238576942d6b8950a2d7f908a340494e67e4", size = 109418, upload-time = "2024-11-27T22:38:20.064Z" }, + { url = "https://files.pythonhosted.org/packages/6e/c2/61d3e0f47e2b74ef40a68b9e6ad5984f6241a942f7cd3bbfbdbd03861ea9/tomli-2.2.1-py3-none-any.whl", hash = "sha256:cb55c73c5f4408779d0cf3eef9f762b9c9f147a77de7b258bef0a5628adc85cc", size = 14257, upload-time = "2024-11-27T22:38:35.385Z" }, ] [[package]] @@ -4947,81 +4983,110 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "sys_platform == 'win32'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a8/4b/29b4ef32e036bb34e4ab51796dd745cdba7ed47ad142a9f4a1eb8e0c744d/tqdm-4.67.1.tar.gz", hash = "sha256:f8aef9c52c08c13a65f30ea34f4e5aac3fd1a34959879d7e59e63027286627f2", size = 169737 } +sdist = { url = "https://files.pythonhosted.org/packages/a8/4b/29b4ef32e036bb34e4ab51796dd745cdba7ed47ad142a9f4a1eb8e0c744d/tqdm-4.67.1.tar.gz", hash = "sha256:f8aef9c52c08c13a65f30ea34f4e5aac3fd1a34959879d7e59e63027286627f2", size = 169737, upload-time = "2024-11-24T20:12:22.481Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d0/30/dc54f88dd4a2b5dc8a0279bdd7270e735851848b762aeb1c1184ed1f6b14/tqdm-4.67.1-py3-none-any.whl", hash = "sha256:26445eca388f82e72884e0d580d5464cd801a3ea01e63e5601bdff9ba6a48de2", size = 78540 }, + { url = "https://files.pythonhosted.org/packages/d0/30/dc54f88dd4a2b5dc8a0279bdd7270e735851848b762aeb1c1184ed1f6b14/tqdm-4.67.1-py3-none-any.whl", hash = "sha256:26445eca388f82e72884e0d580d5464cd801a3ea01e63e5601bdff9ba6a48de2", size = 78540, upload-time = "2024-11-24T20:12:19.698Z" }, ] [[package]] name = "types-requests" -version = "2.32.0.20250306" +version = "2.32.0.20250515" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/09/1a/beaeff79ef9efd186566ba5f0d95b44ae21f6d31e9413bcfbef3489b6ae3/types_requests-2.32.0.20250306.tar.gz", hash = "sha256:0962352694ec5b2f95fda877ee60a159abdf84a0fc6fdace599f20acb41a03d1", size = 23012 } +sdist = { url = "https://files.pythonhosted.org/packages/06/c1/cdc4f9b8cfd9130fbe6276db574f114541f4231fcc6fb29648289e6e3390/types_requests-2.32.0.20250515.tar.gz", hash = "sha256:09c8b63c11318cb2460813871aaa48b671002e59fda67ca909e9883777787581", size = 23012, upload-time = "2025-05-15T03:04:31.817Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/99/26/645d89f56004aa0ba3b96fec27793e3c7e62b40982ee069e52568922b6db/types_requests-2.32.0.20250306-py3-none-any.whl", hash = "sha256:25f2cbb5c8710b2022f8bbee7b2b66f319ef14aeea2f35d80f18c9dbf3b60a0b", size = 20673 }, + { url = "https://files.pythonhosted.org/packages/fe/0f/68a997c73a129287785f418c1ebb6004f81e46b53b3caba88c0e03fcd04a/types_requests-2.32.0.20250515-py3-none-any.whl", hash = "sha256:f8eba93b3a892beee32643ff836993f15a785816acca21ea0ffa006f05ef0fb2", size = 20635, upload-time = "2025-05-15T03:04:30.5Z" }, ] [[package]] name = "types-tabulate" version = "0.9.0.20241207" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3f/43/16030404a327e4ff8c692f2273854019ed36718667b2993609dc37d14dd4/types_tabulate-0.9.0.20241207.tar.gz", hash = "sha256:ac1ac174750c0a385dfd248edc6279fa328aaf4ea317915ab879a2ec47833230", size = 8195 } +sdist = { url = "https://files.pythonhosted.org/packages/3f/43/16030404a327e4ff8c692f2273854019ed36718667b2993609dc37d14dd4/types_tabulate-0.9.0.20241207.tar.gz", hash = "sha256:ac1ac174750c0a385dfd248edc6279fa328aaf4ea317915ab879a2ec47833230", size = 8195, upload-time = "2024-12-07T02:54:42.554Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5e/86/a9ebfd509cbe74471106dffed320e208c72537f9aeb0a55eaa6b1b5e4d17/types_tabulate-0.9.0.20241207-py3-none-any.whl", hash = "sha256:b8dad1343c2a8ba5861c5441370c3e35908edd234ff036d4298708a1d4cf8a85", size = 8307 }, + { url = "https://files.pythonhosted.org/packages/5e/86/a9ebfd509cbe74471106dffed320e208c72537f9aeb0a55eaa6b1b5e4d17/types_tabulate-0.9.0.20241207-py3-none-any.whl", hash = "sha256:b8dad1343c2a8ba5861c5441370c3e35908edd234ff036d4298708a1d4cf8a85", size = 8307, upload-time = "2024-12-07T02:54:41.031Z" }, ] [[package]] name = "typing-extensions" -version = "4.12.2" +version = "4.13.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/df/db/f35a00659bc03fec321ba8bce9420de607a1d37f8342eee1863174c69557/typing_extensions-4.12.2.tar.gz", hash = "sha256:1a7ead55c7e559dd4dee8856e3a88b41225abfe1ce8df57b7c13915fe121ffb8", size = 85321 } +sdist = { url = "https://files.pythonhosted.org/packages/f6/37/23083fcd6e35492953e8d2aaaa68b860eb422b34627b13f2ce3eb6106061/typing_extensions-4.13.2.tar.gz", hash = "sha256:e6c81219bd689f51865d9e372991c540bda33a0379d5573cddb9a3a23f7caaef", size = 106967, upload-time = "2025-04-10T14:19:05.416Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/26/9f/ad63fc0248c5379346306f8668cda6e2e2e9c95e01216d2b8ffd9ff037d0/typing_extensions-4.12.2-py3-none-any.whl", hash = "sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d", size = 37438 }, + { url = "https://files.pythonhosted.org/packages/8b/54/b1ae86c0973cc6f0210b53d508ca3641fb6d0c56823f288d108bc7ab3cc8/typing_extensions-4.13.2-py3-none-any.whl", hash = "sha256:a439e7c04b49fec3e5d3e2beaa21755cadbbdc391694e28ccdd36ca4a1408f8c", size = 45806, upload-time = "2025-04-10T14:19:03.967Z" }, ] [[package]] name = "urllib3" -version = "2.3.0" +version = "2.4.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/aa/63/e53da845320b757bf29ef6a9062f5c669fe997973f966045cb019c3f4b66/urllib3-2.3.0.tar.gz", hash = "sha256:f8c5449b3cf0861679ce7e0503c7b44b5ec981bec0d1d3795a07f1ba96f0204d", size = 307268 } +sdist = { url = "https://files.pythonhosted.org/packages/8a/78/16493d9c386d8e60e442a35feac5e00f0913c0f4b7c217c11e8ec2ff53e0/urllib3-2.4.0.tar.gz", hash = "sha256:414bc6535b787febd7567804cc015fee39daab8ad86268f1310a9250697de466", size = 390672, upload-time = "2025-04-10T15:23:39.232Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c8/19/4ec628951a74043532ca2cf5d97b7b14863931476d117c471e8e2b1eb39f/urllib3-2.3.0-py3-none-any.whl", hash = "sha256:1cee9ad369867bfdbbb48b7dd50374c0967a0bb7710050facf0dd6911440e3df", size = 128369 }, + { url = "https://files.pythonhosted.org/packages/6b/11/cc635220681e93a0183390e26485430ca2c7b5f9d33b15c74c2861cb8091/urllib3-2.4.0-py3-none-any.whl", hash = "sha256:4e16665048960a0900c702d4a66415956a584919c03361cac9f1df5c5dd7e813", size = 128680, upload-time = "2025-04-10T15:23:37.377Z" }, ] [[package]] name = "watchdog" version = "6.0.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/db/7d/7f3d619e951c88ed75c6037b246ddcf2d322812ee8ea189be89511721d54/watchdog-6.0.0.tar.gz", hash = "sha256:9ddf7c82fda3ae8e24decda1338ede66e1c99883db93711d8fb941eaa2d8c282", size = 131220 } +sdist = { url = "https://files.pythonhosted.org/packages/db/7d/7f3d619e951c88ed75c6037b246ddcf2d322812ee8ea189be89511721d54/watchdog-6.0.0.tar.gz", hash = "sha256:9ddf7c82fda3ae8e24decda1338ede66e1c99883db93711d8fb941eaa2d8c282", size = 131220, upload-time = "2024-11-01T14:07:13.037Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e0/24/d9be5cd6642a6aa68352ded4b4b10fb0d7889cb7f45814fb92cecd35f101/watchdog-6.0.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6eb11feb5a0d452ee41f824e271ca311a09e250441c262ca2fd7ebcf2461a06c", size = 96393 }, - { url = "https://files.pythonhosted.org/packages/63/7a/6013b0d8dbc56adca7fdd4f0beed381c59f6752341b12fa0886fa7afc78b/watchdog-6.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ef810fbf7b781a5a593894e4f439773830bdecb885e6880d957d5b9382a960d2", size = 88392 }, - { url = "https://files.pythonhosted.org/packages/d1/40/b75381494851556de56281e053700e46bff5b37bf4c7267e858640af5a7f/watchdog-6.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:afd0fe1b2270917c5e23c2a65ce50c2a4abb63daafb0d419fde368e272a76b7c", size = 89019 }, - { url = "https://files.pythonhosted.org/packages/39/ea/3930d07dafc9e286ed356a679aa02d777c06e9bfd1164fa7c19c288a5483/watchdog-6.0.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:bdd4e6f14b8b18c334febb9c4425a878a2ac20efd1e0b231978e7b150f92a948", size = 96471 }, - { url = "https://files.pythonhosted.org/packages/12/87/48361531f70b1f87928b045df868a9fd4e253d9ae087fa4cf3f7113be363/watchdog-6.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:c7c15dda13c4eb00d6fb6fc508b3c0ed88b9d5d374056b239c4ad1611125c860", size = 88449 }, - { url = "https://files.pythonhosted.org/packages/5b/7e/8f322f5e600812e6f9a31b75d242631068ca8f4ef0582dd3ae6e72daecc8/watchdog-6.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6f10cb2d5902447c7d0da897e2c6768bca89174d0c6e1e30abec5421af97a5b0", size = 89054 }, - { url = "https://files.pythonhosted.org/packages/a9/c7/ca4bf3e518cb57a686b2feb4f55a1892fd9a3dd13f470fca14e00f80ea36/watchdog-6.0.0-py3-none-manylinux2014_aarch64.whl", hash = "sha256:7607498efa04a3542ae3e05e64da8202e58159aa1fa4acddf7678d34a35d4f13", size = 79079 }, - { url = "https://files.pythonhosted.org/packages/5c/51/d46dc9332f9a647593c947b4b88e2381c8dfc0942d15b8edc0310fa4abb1/watchdog-6.0.0-py3-none-manylinux2014_armv7l.whl", hash = "sha256:9041567ee8953024c83343288ccc458fd0a2d811d6a0fd68c4c22609e3490379", size = 79078 }, - { url = "https://files.pythonhosted.org/packages/d4/57/04edbf5e169cd318d5f07b4766fee38e825d64b6913ca157ca32d1a42267/watchdog-6.0.0-py3-none-manylinux2014_i686.whl", hash = "sha256:82dc3e3143c7e38ec49d61af98d6558288c415eac98486a5c581726e0737c00e", size = 79076 }, - { url = "https://files.pythonhosted.org/packages/ab/cc/da8422b300e13cb187d2203f20b9253e91058aaf7db65b74142013478e66/watchdog-6.0.0-py3-none-manylinux2014_ppc64.whl", hash = "sha256:212ac9b8bf1161dc91bd09c048048a95ca3a4c4f5e5d4a7d1b1a7d5752a7f96f", size = 79077 }, - { url = "https://files.pythonhosted.org/packages/2c/3b/b8964e04ae1a025c44ba8e4291f86e97fac443bca31de8bd98d3263d2fcf/watchdog-6.0.0-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:e3df4cbb9a450c6d49318f6d14f4bbc80d763fa587ba46ec86f99f9e6876bb26", size = 79078 }, - { url = "https://files.pythonhosted.org/packages/62/ae/a696eb424bedff7407801c257d4b1afda455fe40821a2be430e173660e81/watchdog-6.0.0-py3-none-manylinux2014_s390x.whl", hash = "sha256:2cce7cfc2008eb51feb6aab51251fd79b85d9894e98ba847408f662b3395ca3c", size = 79077 }, - { url = "https://files.pythonhosted.org/packages/b5/e8/dbf020b4d98251a9860752a094d09a65e1b436ad181faf929983f697048f/watchdog-6.0.0-py3-none-manylinux2014_x86_64.whl", hash = "sha256:20ffe5b202af80ab4266dcd3e91aae72bf2da48c0d33bdb15c66658e685e94e2", size = 79078 }, - { url = "https://files.pythonhosted.org/packages/07/f6/d0e5b343768e8bcb4cda79f0f2f55051bf26177ecd5651f84c07567461cf/watchdog-6.0.0-py3-none-win32.whl", hash = "sha256:07df1fdd701c5d4c8e55ef6cf55b8f0120fe1aef7ef39a1c6fc6bc2e606d517a", size = 79065 }, - { url = "https://files.pythonhosted.org/packages/db/d9/c495884c6e548fce18a8f40568ff120bc3a4b7b99813081c8ac0c936fa64/watchdog-6.0.0-py3-none-win_amd64.whl", hash = "sha256:cbafb470cf848d93b5d013e2ecb245d4aa1c8fd0504e863ccefa32445359d680", size = 79070 }, - { url = "https://files.pythonhosted.org/packages/33/e8/e40370e6d74ddba47f002a32919d91310d6074130fe4e17dabcafc15cbf1/watchdog-6.0.0-py3-none-win_ia64.whl", hash = "sha256:a1914259fa9e1454315171103c6a30961236f508b9b623eae470268bbcc6a22f", size = 79067 }, + { url = "https://files.pythonhosted.org/packages/e0/24/d9be5cd6642a6aa68352ded4b4b10fb0d7889cb7f45814fb92cecd35f101/watchdog-6.0.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6eb11feb5a0d452ee41f824e271ca311a09e250441c262ca2fd7ebcf2461a06c", size = 96393, upload-time = "2024-11-01T14:06:31.756Z" }, + { url = "https://files.pythonhosted.org/packages/63/7a/6013b0d8dbc56adca7fdd4f0beed381c59f6752341b12fa0886fa7afc78b/watchdog-6.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ef810fbf7b781a5a593894e4f439773830bdecb885e6880d957d5b9382a960d2", size = 88392, upload-time = "2024-11-01T14:06:32.99Z" }, + { url = "https://files.pythonhosted.org/packages/d1/40/b75381494851556de56281e053700e46bff5b37bf4c7267e858640af5a7f/watchdog-6.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:afd0fe1b2270917c5e23c2a65ce50c2a4abb63daafb0d419fde368e272a76b7c", size = 89019, upload-time = "2024-11-01T14:06:34.963Z" }, + { url = "https://files.pythonhosted.org/packages/39/ea/3930d07dafc9e286ed356a679aa02d777c06e9bfd1164fa7c19c288a5483/watchdog-6.0.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:bdd4e6f14b8b18c334febb9c4425a878a2ac20efd1e0b231978e7b150f92a948", size = 96471, upload-time = "2024-11-01T14:06:37.745Z" }, + { url = "https://files.pythonhosted.org/packages/12/87/48361531f70b1f87928b045df868a9fd4e253d9ae087fa4cf3f7113be363/watchdog-6.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:c7c15dda13c4eb00d6fb6fc508b3c0ed88b9d5d374056b239c4ad1611125c860", size = 88449, upload-time = "2024-11-01T14:06:39.748Z" }, + { url = "https://files.pythonhosted.org/packages/5b/7e/8f322f5e600812e6f9a31b75d242631068ca8f4ef0582dd3ae6e72daecc8/watchdog-6.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6f10cb2d5902447c7d0da897e2c6768bca89174d0c6e1e30abec5421af97a5b0", size = 89054, upload-time = "2024-11-01T14:06:41.009Z" }, + { url = "https://files.pythonhosted.org/packages/a9/c7/ca4bf3e518cb57a686b2feb4f55a1892fd9a3dd13f470fca14e00f80ea36/watchdog-6.0.0-py3-none-manylinux2014_aarch64.whl", hash = "sha256:7607498efa04a3542ae3e05e64da8202e58159aa1fa4acddf7678d34a35d4f13", size = 79079, upload-time = "2024-11-01T14:06:59.472Z" }, + { url = "https://files.pythonhosted.org/packages/5c/51/d46dc9332f9a647593c947b4b88e2381c8dfc0942d15b8edc0310fa4abb1/watchdog-6.0.0-py3-none-manylinux2014_armv7l.whl", hash = "sha256:9041567ee8953024c83343288ccc458fd0a2d811d6a0fd68c4c22609e3490379", size = 79078, upload-time = "2024-11-01T14:07:01.431Z" }, + { url = "https://files.pythonhosted.org/packages/d4/57/04edbf5e169cd318d5f07b4766fee38e825d64b6913ca157ca32d1a42267/watchdog-6.0.0-py3-none-manylinux2014_i686.whl", hash = "sha256:82dc3e3143c7e38ec49d61af98d6558288c415eac98486a5c581726e0737c00e", size = 79076, upload-time = "2024-11-01T14:07:02.568Z" }, + { url = "https://files.pythonhosted.org/packages/ab/cc/da8422b300e13cb187d2203f20b9253e91058aaf7db65b74142013478e66/watchdog-6.0.0-py3-none-manylinux2014_ppc64.whl", hash = "sha256:212ac9b8bf1161dc91bd09c048048a95ca3a4c4f5e5d4a7d1b1a7d5752a7f96f", size = 79077, upload-time = "2024-11-01T14:07:03.893Z" }, + { url = "https://files.pythonhosted.org/packages/2c/3b/b8964e04ae1a025c44ba8e4291f86e97fac443bca31de8bd98d3263d2fcf/watchdog-6.0.0-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:e3df4cbb9a450c6d49318f6d14f4bbc80d763fa587ba46ec86f99f9e6876bb26", size = 79078, upload-time = "2024-11-01T14:07:05.189Z" }, + { url = "https://files.pythonhosted.org/packages/62/ae/a696eb424bedff7407801c257d4b1afda455fe40821a2be430e173660e81/watchdog-6.0.0-py3-none-manylinux2014_s390x.whl", hash = "sha256:2cce7cfc2008eb51feb6aab51251fd79b85d9894e98ba847408f662b3395ca3c", size = 79077, upload-time = "2024-11-01T14:07:06.376Z" }, + { url = "https://files.pythonhosted.org/packages/b5/e8/dbf020b4d98251a9860752a094d09a65e1b436ad181faf929983f697048f/watchdog-6.0.0-py3-none-manylinux2014_x86_64.whl", hash = "sha256:20ffe5b202af80ab4266dcd3e91aae72bf2da48c0d33bdb15c66658e685e94e2", size = 79078, upload-time = "2024-11-01T14:07:07.547Z" }, + { url = "https://files.pythonhosted.org/packages/07/f6/d0e5b343768e8bcb4cda79f0f2f55051bf26177ecd5651f84c07567461cf/watchdog-6.0.0-py3-none-win32.whl", hash = "sha256:07df1fdd701c5d4c8e55ef6cf55b8f0120fe1aef7ef39a1c6fc6bc2e606d517a", size = 79065, upload-time = "2024-11-01T14:07:09.525Z" }, + { url = "https://files.pythonhosted.org/packages/db/d9/c495884c6e548fce18a8f40568ff120bc3a4b7b99813081c8ac0c936fa64/watchdog-6.0.0-py3-none-win_amd64.whl", hash = "sha256:cbafb470cf848d93b5d013e2ecb245d4aa1c8fd0504e863ccefa32445359d680", size = 79070, upload-time = "2024-11-01T14:07:10.686Z" }, + { url = "https://files.pythonhosted.org/packages/33/e8/e40370e6d74ddba47f002a32919d91310d6074130fe4e17dabcafc15cbf1/watchdog-6.0.0-py3-none-win_ia64.whl", hash = "sha256:a1914259fa9e1454315171103c6a30961236f508b9b623eae470268bbcc6a22f", size = 79067, upload-time = "2024-11-01T14:07:11.845Z" }, ] [[package]] name = "websocket-client" version = "1.8.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e6/30/fba0d96b4b5fbf5948ed3f4681f7da2f9f64512e1d303f94b4cc174c24a5/websocket_client-1.8.0.tar.gz", hash = "sha256:3239df9f44da632f96012472805d40a23281a991027ce11d2f45a6f24ac4c3da", size = 54648 } +sdist = { url = "https://files.pythonhosted.org/packages/e6/30/fba0d96b4b5fbf5948ed3f4681f7da2f9f64512e1d303f94b4cc174c24a5/websocket_client-1.8.0.tar.gz", hash = "sha256:3239df9f44da632f96012472805d40a23281a991027ce11d2f45a6f24ac4c3da", size = 54648, upload-time = "2024-04-23T22:16:16.976Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/5a/84/44687a29792a70e111c5c477230a72c4b957d88d16141199bf9acb7537a3/websocket_client-1.8.0-py3-none-any.whl", hash = "sha256:17b44cc997f5c498e809b22cdf2d9c7a9e71c02c8cc2b6c56e7c2d1239bfa526", size = 58826 }, + { url = "https://files.pythonhosted.org/packages/5a/84/44687a29792a70e111c5c477230a72c4b957d88d16141199bf9acb7537a3/websocket_client-1.8.0-py3-none-any.whl", hash = "sha256:17b44cc997f5c498e809b22cdf2d9c7a9e71c02c8cc2b6c56e7c2d1239bfa526", size = 58826, upload-time = "2024-04-23T22:16:14.422Z" }, +] + +[[package]] +name = "xattr" +version = "1.1.4" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cffi" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/62/bf/8b98081f9f8fd56d67b9478ff1e0f8c337cde08bcb92f0d592f0a7958983/xattr-1.1.4.tar.gz", hash = "sha256:b7b02ecb2270da5b7e7deaeea8f8b528c17368401c2b9d5f63e91f545b45d372", size = 16729, upload-time = "2025-01-06T19:19:32.557Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/78/5b/f64ba0f93e6447e1997068959f22ff99e08d77dd88d9edcf97ddcb9e9016/xattr-1.1.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:bb4bbe37ba95542081890dd34fa5347bef4651e276647adaa802d5d0d7d86452", size = 23920, upload-time = "2025-01-06T19:17:48.234Z" }, + { url = "https://files.pythonhosted.org/packages/c8/54/ad66655f0b1317b0a297aa2d6ed7d6e5d5343495841fad535bee37a56471/xattr-1.1.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3da489ecef798705f9a39ea8cea4ead0d1eeed55f92c345add89740bd930bab6", size = 18883, upload-time = "2025-01-06T19:17:49.46Z" }, + { url = "https://files.pythonhosted.org/packages/4d/5d/7d5154570bbcb898e6123c292f697c87c33e12258a1a8b9741539f952681/xattr-1.1.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:798dd0cbe696635a6f74b06fc430818bf9c3b24314e1502eadf67027ab60c9b0", size = 19221, upload-time = "2025-01-06T19:17:51.654Z" }, + { url = "https://files.pythonhosted.org/packages/b9/b7/135cf3018278051f57bb5dde944cb1ca4f7ad4ec383465a08c6a5c7f7152/xattr-1.1.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7b2b6361626efad5eb5a6bf8172c6c67339e09397ee8140ec41258737bea9681", size = 39098, upload-time = "2025-01-06T19:17:53.099Z" }, + { url = "https://files.pythonhosted.org/packages/a5/62/577e2eb0108158b78cd93ea3782c7a8d464693f1338a5350a1db16f69a89/xattr-1.1.4-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6e7fa20a0c9ce022d19123b1c5b848d00a68b837251835a7929fe041ee81dcd0", size = 36982, upload-time = "2025-01-06T19:17:54.493Z" }, + { url = "https://files.pythonhosted.org/packages/59/cc/ab3bd7a4bedf445be4b35de4a4627ef2944786724d18eaf28d05c1238c7c/xattr-1.1.4-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6e20eeb08e2c57fc7e71f050b1cfae35cbb46105449853a582bf53fd23c5379e", size = 38891, upload-time = "2025-01-06T19:17:55.853Z" }, + { url = "https://files.pythonhosted.org/packages/45/e8/2285651d92f1460159753fe6628af259c943fcc5071e48a0540fa11dc34d/xattr-1.1.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:477370e75821bded901487e5e752cffe554d1bd3bd4839b627d4d1ee8c95a093", size = 38362, upload-time = "2025-01-06T19:17:57.078Z" }, + { url = "https://files.pythonhosted.org/packages/5f/af/7856c0b1970272a53a428bb20dc125f9fd350fb1b40ebca4e54610af1b79/xattr-1.1.4-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:a8682091cd34a9f4a93c8aaea4101aae99f1506e24da00a3cc3dd2eca9566f21", size = 36724, upload-time = "2025-01-06T19:17:58.534Z" }, + { url = "https://files.pythonhosted.org/packages/5d/34/087e02b32d6288a40b7f6573e97a119016e6c3713d4f4b866bbf56cfb803/xattr-1.1.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:2e079b3b1a274ba2121cf0da38bbe5c8d2fb1cc49ecbceb395ce20eb7d69556d", size = 37945, upload-time = "2025-01-06T19:17:59.764Z" }, + { url = "https://files.pythonhosted.org/packages/f0/2a/d0f9e46de4cec5e4aa45fd939549b977c49dd68202fa844d07cb24ce5f17/xattr-1.1.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ae6579dea05bf9f335a082f711d5924a98da563cac72a2d550f5b940c401c0e9", size = 23917, upload-time = "2025-01-06T19:18:00.868Z" }, + { url = "https://files.pythonhosted.org/packages/83/e0/a5764257cd9c9eb598f4648a3658d915dd3520ec111ecbd251b685de6546/xattr-1.1.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:cd6038ec9df2e67af23c212693751481d5f7e858156924f14340376c48ed9ac7", size = 18891, upload-time = "2025-01-06T19:18:02.029Z" }, + { url = "https://files.pythonhosted.org/packages/8b/83/a81a147987387fd2841a28f767efedb099cf90e23553ead458f2330e47c5/xattr-1.1.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:608b2877526674eb15df4150ef4b70b7b292ae00e65aecaae2f192af224be200", size = 19213, upload-time = "2025-01-06T19:18:03.303Z" }, + { url = "https://files.pythonhosted.org/packages/4b/52/bf093b4eb9873ffc9e9373dcb38ec8a9b5cd4e6a9f681c4c5cf6bf067a42/xattr-1.1.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c54dad1a6a998c6a23edfd25e99f4d38e9b942d54e518570044edf8c767687ea", size = 39302, upload-time = "2025-01-06T19:18:05.846Z" }, + { url = "https://files.pythonhosted.org/packages/2d/d8/9d7315ebae76a7f48bc5e1aecc7e592eb43376a0f6cf470a854d895d2093/xattr-1.1.4-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c0dab6ff72bb2b508f3850c368f8e53bd706585012676e1f71debba3310acde8", size = 37224, upload-time = "2025-01-06T19:18:07.226Z" }, + { url = "https://files.pythonhosted.org/packages/c8/b2/10eb17bea7e378b2bcd76fc8c2e5158318e2c08e774b13f548f333d7318a/xattr-1.1.4-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7a3c54c6af7cf09432b2c461af257d5f4b1cb2d59eee045f91bacef44421a46d", size = 39145, upload-time = "2025-01-06T19:18:08.403Z" }, + { url = "https://files.pythonhosted.org/packages/74/fb/95bbc28116b3c19a21acc34ec0a5973e9cc97fe49d3f47a65775af3760a8/xattr-1.1.4-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e346e05a158d554639fbf7a0db169dc693c2d2260c7acb3239448f1ff4a9d67f", size = 38469, upload-time = "2025-01-06T19:18:09.602Z" }, + { url = "https://files.pythonhosted.org/packages/af/03/23db582cb271ed47f2d62956e112501d998b5493f892a77104b5795ae2fc/xattr-1.1.4-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:3ff6d9e2103d0d6e5fcd65b85a2005b66ea81c0720a37036445faadc5bbfa424", size = 36797, upload-time = "2025-01-06T19:18:10.709Z" }, + { url = "https://files.pythonhosted.org/packages/90/c4/b631d0174e097cf8c44d4f70c66545d91dc8ba15bbfa5054dd7da8371461/xattr-1.1.4-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7a2ee4563c6414dfec0d1ac610f59d39d5220531ae06373eeb1a06ee37cd193f", size = 38128, upload-time = "2025-01-06T19:18:11.884Z" }, ] [[package]] @@ -5029,57 +5094,59 @@ name = "yapf" version = "0.43.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "platformdirs", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, + { name = "platformdirs" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/23/97/b6f296d1e9cc1ec25c7604178b48532fa5901f721bcf1b8d8148b13e5588/yapf-0.43.0.tar.gz", hash = "sha256:00d3aa24bfedff9420b2e0d5d9f5ab6d9d4268e72afbf59bb3fa542781d5218e", size = 254907 } +sdist = { url = "https://files.pythonhosted.org/packages/23/97/b6f296d1e9cc1ec25c7604178b48532fa5901f721bcf1b8d8148b13e5588/yapf-0.43.0.tar.gz", hash = "sha256:00d3aa24bfedff9420b2e0d5d9f5ab6d9d4268e72afbf59bb3fa542781d5218e", size = 254907, upload-time = "2024-11-14T00:11:41.584Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/37/81/6acd6601f61e31cfb8729d3da6d5df966f80f374b78eff83760714487338/yapf-0.43.0-py3-none-any.whl", hash = "sha256:224faffbc39c428cb095818cf6ef5511fdab6f7430a10783fdfb292ccf2852ca", size = 256158 }, + { url = "https://files.pythonhosted.org/packages/37/81/6acd6601f61e31cfb8729d3da6d5df966f80f374b78eff83760714487338/yapf-0.43.0-py3-none-any.whl", hash = "sha256:224faffbc39c428cb095818cf6ef5511fdab6f7430a10783fdfb292ccf2852ca", size = 256158, upload-time = "2024-11-14T00:11:39.37Z" }, ] [[package]] name = "yarl" -version = "1.18.3" +version = "1.20.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "idna" }, { name = "multidict" }, { name = "propcache" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b7/9d/4b94a8e6d2b51b599516a5cb88e5bc99b4d8d4583e468057eaa29d5f0918/yarl-1.18.3.tar.gz", hash = "sha256:ac1801c45cbf77b6c99242eeff4fffb5e4e73a800b5c4ad4fc0be5def634d2e1", size = 181062 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/40/93/282b5f4898d8e8efaf0790ba6d10e2245d2c9f30e199d1a85cae9356098c/yarl-1.18.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8503ad47387b8ebd39cbbbdf0bf113e17330ffd339ba1144074da24c545f0069", size = 141555 }, - { url = "https://files.pythonhosted.org/packages/6d/9c/0a49af78df099c283ca3444560f10718fadb8a18dc8b3edf8c7bd9fd7d89/yarl-1.18.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:02ddb6756f8f4517a2d5e99d8b2f272488e18dd0bfbc802f31c16c6c20f22193", size = 94351 }, - { url = "https://files.pythonhosted.org/packages/5a/a1/205ab51e148fdcedad189ca8dd587794c6f119882437d04c33c01a75dece/yarl-1.18.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:67a283dd2882ac98cc6318384f565bffc751ab564605959df4752d42483ad889", size = 92286 }, - { url = "https://files.pythonhosted.org/packages/ed/fe/88b690b30f3f59275fb674f5f93ddd4a3ae796c2b62e5bb9ece8a4914b83/yarl-1.18.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d980e0325b6eddc81331d3f4551e2a333999fb176fd153e075c6d1c2530aa8a8", size = 340649 }, - { url = "https://files.pythonhosted.org/packages/07/eb/3b65499b568e01f36e847cebdc8d7ccb51fff716dbda1ae83c3cbb8ca1c9/yarl-1.18.3-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b643562c12680b01e17239be267bc306bbc6aac1f34f6444d1bded0c5ce438ca", size = 356623 }, - { url = "https://files.pythonhosted.org/packages/33/46/f559dc184280b745fc76ec6b1954de2c55595f0ec0a7614238b9ebf69618/yarl-1.18.3-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c017a3b6df3a1bd45b9fa49a0f54005e53fbcad16633870104b66fa1a30a29d8", size = 354007 }, - { url = "https://files.pythonhosted.org/packages/af/ba/1865d85212351ad160f19fb99808acf23aab9a0f8ff31c8c9f1b4d671fc9/yarl-1.18.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75674776d96d7b851b6498f17824ba17849d790a44d282929c42dbb77d4f17ae", size = 344145 }, - { url = "https://files.pythonhosted.org/packages/94/cb/5c3e975d77755d7b3d5193e92056b19d83752ea2da7ab394e22260a7b824/yarl-1.18.3-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ccaa3a4b521b780a7e771cc336a2dba389a0861592bbce09a476190bb0c8b4b3", size = 336133 }, - { url = "https://files.pythonhosted.org/packages/19/89/b77d3fd249ab52a5c40859815765d35c91425b6bb82e7427ab2f78f5ff55/yarl-1.18.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2d06d3005e668744e11ed80812e61efd77d70bb7f03e33c1598c301eea20efbb", size = 347967 }, - { url = "https://files.pythonhosted.org/packages/35/bd/f6b7630ba2cc06c319c3235634c582a6ab014d52311e7d7c22f9518189b5/yarl-1.18.3-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:9d41beda9dc97ca9ab0b9888cb71f7539124bc05df02c0cff6e5acc5a19dcc6e", size = 346397 }, - { url = "https://files.pythonhosted.org/packages/18/1a/0b4e367d5a72d1f095318344848e93ea70da728118221f84f1bf6c1e39e7/yarl-1.18.3-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:ba23302c0c61a9999784e73809427c9dbedd79f66a13d84ad1b1943802eaaf59", size = 350206 }, - { url = "https://files.pythonhosted.org/packages/b5/cf/320fff4367341fb77809a2d8d7fe75b5d323a8e1b35710aafe41fdbf327b/yarl-1.18.3-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:6748dbf9bfa5ba1afcc7556b71cda0d7ce5f24768043a02a58846e4a443d808d", size = 362089 }, - { url = "https://files.pythonhosted.org/packages/57/cf/aadba261d8b920253204085268bad5e8cdd86b50162fcb1b10c10834885a/yarl-1.18.3-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:0b0cad37311123211dc91eadcb322ef4d4a66008d3e1bdc404808992260e1a0e", size = 366267 }, - { url = "https://files.pythonhosted.org/packages/54/58/fb4cadd81acdee6dafe14abeb258f876e4dd410518099ae9a35c88d8097c/yarl-1.18.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0fb2171a4486bb075316ee754c6d8382ea6eb8b399d4ec62fde2b591f879778a", size = 359141 }, - { url = "https://files.pythonhosted.org/packages/9a/7a/4c571597589da4cd5c14ed2a0b17ac56ec9ee7ee615013f74653169e702d/yarl-1.18.3-cp311-cp311-win32.whl", hash = "sha256:61b1a825a13bef4a5f10b1885245377d3cd0bf87cba068e1d9a88c2ae36880e1", size = 84402 }, - { url = "https://files.pythonhosted.org/packages/ae/7b/8600250b3d89b625f1121d897062f629883c2f45339623b69b1747ec65fa/yarl-1.18.3-cp311-cp311-win_amd64.whl", hash = "sha256:b9d60031cf568c627d028239693fd718025719c02c9f55df0a53e587aab951b5", size = 91030 }, - { url = "https://files.pythonhosted.org/packages/33/85/bd2e2729752ff4c77338e0102914897512e92496375e079ce0150a6dc306/yarl-1.18.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1dd4bdd05407ced96fed3d7f25dbbf88d2ffb045a0db60dbc247f5b3c5c25d50", size = 142644 }, - { url = "https://files.pythonhosted.org/packages/ff/74/1178322cc0f10288d7eefa6e4a85d8d2e28187ccab13d5b844e8b5d7c88d/yarl-1.18.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7c33dd1931a95e5d9a772d0ac5e44cac8957eaf58e3c8da8c1414de7dd27c576", size = 94962 }, - { url = "https://files.pythonhosted.org/packages/be/75/79c6acc0261e2c2ae8a1c41cf12265e91628c8c58ae91f5ff59e29c0787f/yarl-1.18.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:25b411eddcfd56a2f0cd6a384e9f4f7aa3efee14b188de13048c25b5e91f1640", size = 92795 }, - { url = "https://files.pythonhosted.org/packages/6b/32/927b2d67a412c31199e83fefdce6e645247b4fb164aa1ecb35a0f9eb2058/yarl-1.18.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:436c4fc0a4d66b2badc6c5fc5ef4e47bb10e4fd9bf0c79524ac719a01f3607c2", size = 332368 }, - { url = "https://files.pythonhosted.org/packages/19/e5/859fca07169d6eceeaa4fde1997c91d8abde4e9a7c018e371640c2da2b71/yarl-1.18.3-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e35ef8683211db69ffe129a25d5634319a677570ab6b2eba4afa860f54eeaf75", size = 342314 }, - { url = "https://files.pythonhosted.org/packages/08/75/76b63ccd91c9e03ab213ef27ae6add2e3400e77e5cdddf8ed2dbc36e3f21/yarl-1.18.3-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:84b2deecba4a3f1a398df819151eb72d29bfeb3b69abb145a00ddc8d30094512", size = 341987 }, - { url = "https://files.pythonhosted.org/packages/1a/e1/a097d5755d3ea8479a42856f51d97eeff7a3a7160593332d98f2709b3580/yarl-1.18.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:00e5a1fea0fd4f5bfa7440a47eff01d9822a65b4488f7cff83155a0f31a2ecba", size = 336914 }, - { url = "https://files.pythonhosted.org/packages/0b/42/e1b4d0e396b7987feceebe565286c27bc085bf07d61a59508cdaf2d45e63/yarl-1.18.3-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d0e883008013c0e4aef84dcfe2a0b172c4d23c2669412cf5b3371003941f72bb", size = 325765 }, - { url = "https://files.pythonhosted.org/packages/7e/18/03a5834ccc9177f97ca1bbb245b93c13e58e8225276f01eedc4cc98ab820/yarl-1.18.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5a3f356548e34a70b0172d8890006c37be92995f62d95a07b4a42e90fba54272", size = 344444 }, - { url = "https://files.pythonhosted.org/packages/c8/03/a713633bdde0640b0472aa197b5b86e90fbc4c5bc05b727b714cd8a40e6d/yarl-1.18.3-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:ccd17349166b1bee6e529b4add61727d3f55edb7babbe4069b5764c9587a8cc6", size = 340760 }, - { url = "https://files.pythonhosted.org/packages/eb/99/f6567e3f3bbad8fd101886ea0276c68ecb86a2b58be0f64077396cd4b95e/yarl-1.18.3-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:b958ddd075ddba5b09bb0be8a6d9906d2ce933aee81100db289badbeb966f54e", size = 346484 }, - { url = "https://files.pythonhosted.org/packages/8e/a9/84717c896b2fc6cb15bd4eecd64e34a2f0a9fd6669e69170c73a8b46795a/yarl-1.18.3-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:c7d79f7d9aabd6011004e33b22bc13056a3e3fb54794d138af57f5ee9d9032cb", size = 359864 }, - { url = "https://files.pythonhosted.org/packages/1e/2e/d0f5f1bef7ee93ed17e739ec8dbcb47794af891f7d165fa6014517b48169/yarl-1.18.3-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:4891ed92157e5430874dad17b15eb1fda57627710756c27422200c52d8a4e393", size = 364537 }, - { url = "https://files.pythonhosted.org/packages/97/8a/568d07c5d4964da5b02621a517532adb8ec5ba181ad1687191fffeda0ab6/yarl-1.18.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ce1af883b94304f493698b00d0f006d56aea98aeb49d75ec7d98cd4a777e9285", size = 357861 }, - { url = "https://files.pythonhosted.org/packages/7d/e3/924c3f64b6b3077889df9a1ece1ed8947e7b61b0a933f2ec93041990a677/yarl-1.18.3-cp312-cp312-win32.whl", hash = "sha256:f91c4803173928a25e1a55b943c81f55b8872f0018be83e3ad4938adffb77dd2", size = 84097 }, - { url = "https://files.pythonhosted.org/packages/34/45/0e055320daaabfc169b21ff6174567b2c910c45617b0d79c68d7ab349b02/yarl-1.18.3-cp312-cp312-win_amd64.whl", hash = "sha256:7e2ee16578af3b52ac2f334c3b1f92262f47e02cc6193c598502bd46f5cd1477", size = 90399 }, - { url = "https://files.pythonhosted.org/packages/f5/4b/a06e0ec3d155924f77835ed2d167ebd3b211a7b0853da1cf8d8414d784ef/yarl-1.18.3-py3-none-any.whl", hash = "sha256:b57f4f58099328dfb26c6a771d09fb20dbbae81d20cfb66141251ea063bd101b", size = 45109 }, +sdist = { url = "https://files.pythonhosted.org/packages/62/51/c0edba5219027f6eab262e139f73e2417b0f4efffa23bf562f6e18f76ca5/yarl-1.20.0.tar.gz", hash = "sha256:686d51e51ee5dfe62dec86e4866ee0e9ed66df700d55c828a615640adc885307", size = 185258, upload-time = "2025-04-17T00:45:14.661Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/60/82/a59d8e21b20ffc836775fa7daedac51d16bb8f3010c4fcb495c4496aa922/yarl-1.20.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:fdb5204d17cb32b2de2d1e21c7461cabfacf17f3645e4b9039f210c5d3378bf3", size = 145178, upload-time = "2025-04-17T00:42:04.511Z" }, + { url = "https://files.pythonhosted.org/packages/ba/81/315a3f6f95947cfbf37c92d6fbce42a1a6207b6c38e8c2b452499ec7d449/yarl-1.20.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:eaddd7804d8e77d67c28d154ae5fab203163bd0998769569861258e525039d2a", size = 96859, upload-time = "2025-04-17T00:42:06.43Z" }, + { url = "https://files.pythonhosted.org/packages/ad/17/9b64e575583158551b72272a1023cdbd65af54fe13421d856b2850a6ddb7/yarl-1.20.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:634b7ba6b4a85cf67e9df7c13a7fb2e44fa37b5d34501038d174a63eaac25ee2", size = 94647, upload-time = "2025-04-17T00:42:07.976Z" }, + { url = "https://files.pythonhosted.org/packages/2c/29/8f291e7922a58a21349683f6120a85701aeefaa02e9f7c8a2dc24fe3f431/yarl-1.20.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6d409e321e4addf7d97ee84162538c7258e53792eb7c6defd0c33647d754172e", size = 355788, upload-time = "2025-04-17T00:42:09.902Z" }, + { url = "https://files.pythonhosted.org/packages/26/6d/b4892c80b805c42c228c6d11e03cafabf81662d371b0853e7f0f513837d5/yarl-1.20.0-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:ea52f7328a36960ba3231c6677380fa67811b414798a6e071c7085c57b6d20a9", size = 344613, upload-time = "2025-04-17T00:42:11.768Z" }, + { url = "https://files.pythonhosted.org/packages/d7/0e/517aa28d3f848589bae9593717b063a544b86ba0a807d943c70f48fcf3bb/yarl-1.20.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c8703517b924463994c344dcdf99a2d5ce9eca2b6882bb640aa555fb5efc706a", size = 370953, upload-time = "2025-04-17T00:42:13.983Z" }, + { url = "https://files.pythonhosted.org/packages/5f/9b/5bd09d2f1ad6e6f7c2beae9e50db78edd2cca4d194d227b958955573e240/yarl-1.20.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:077989b09ffd2f48fb2d8f6a86c5fef02f63ffe6b1dd4824c76de7bb01e4f2e2", size = 369204, upload-time = "2025-04-17T00:42:16.386Z" }, + { url = "https://files.pythonhosted.org/packages/9c/85/d793a703cf4bd0d4cd04e4b13cc3d44149470f790230430331a0c1f52df5/yarl-1.20.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0acfaf1da020253f3533526e8b7dd212838fdc4109959a2c53cafc6db611bff2", size = 358108, upload-time = "2025-04-17T00:42:18.622Z" }, + { url = "https://files.pythonhosted.org/packages/6f/54/b6c71e13549c1f6048fbc14ce8d930ac5fb8bafe4f1a252e621a24f3f1f9/yarl-1.20.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b4230ac0b97ec5eeb91d96b324d66060a43fd0d2a9b603e3327ed65f084e41f8", size = 346610, upload-time = "2025-04-17T00:42:20.9Z" }, + { url = "https://files.pythonhosted.org/packages/a0/1a/d6087d58bdd0d8a2a37bbcdffac9d9721af6ebe50d85304d9f9b57dfd862/yarl-1.20.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0a6a1e6ae21cdd84011c24c78d7a126425148b24d437b5702328e4ba640a8902", size = 365378, upload-time = "2025-04-17T00:42:22.926Z" }, + { url = "https://files.pythonhosted.org/packages/02/84/e25ddff4cbc001dbc4af76f8d41a3e23818212dd1f0a52044cbc60568872/yarl-1.20.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:86de313371ec04dd2531f30bc41a5a1a96f25a02823558ee0f2af0beaa7ca791", size = 356919, upload-time = "2025-04-17T00:42:25.145Z" }, + { url = "https://files.pythonhosted.org/packages/04/76/898ae362353bf8f64636495d222c8014c8e5267df39b1a9fe1e1572fb7d0/yarl-1.20.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:dd59c9dd58ae16eaa0f48c3d0cbe6be8ab4dc7247c3ff7db678edecbaf59327f", size = 364248, upload-time = "2025-04-17T00:42:27.475Z" }, + { url = "https://files.pythonhosted.org/packages/1b/b0/9d9198d83a622f1c40fdbf7bd13b224a6979f2e1fc2cf50bfb1d8773c495/yarl-1.20.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a0bc5e05f457b7c1994cc29e83b58f540b76234ba6b9648a4971ddc7f6aa52da", size = 378418, upload-time = "2025-04-17T00:42:29.333Z" }, + { url = "https://files.pythonhosted.org/packages/c7/ce/1f50c1cc594cf5d3f5bf4a9b616fca68680deaec8ad349d928445ac52eb8/yarl-1.20.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:c9471ca18e6aeb0e03276b5e9b27b14a54c052d370a9c0c04a68cefbd1455eb4", size = 383850, upload-time = "2025-04-17T00:42:31.668Z" }, + { url = "https://files.pythonhosted.org/packages/89/1e/a59253a87b35bfec1a25bb5801fb69943330b67cfd266278eb07e0609012/yarl-1.20.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:40ed574b4df723583a26c04b298b283ff171bcc387bc34c2683235e2487a65a5", size = 381218, upload-time = "2025-04-17T00:42:33.523Z" }, + { url = "https://files.pythonhosted.org/packages/85/b0/26f87df2b3044b0ef1a7cf66d321102bdca091db64c5ae853fcb2171c031/yarl-1.20.0-cp311-cp311-win32.whl", hash = "sha256:db243357c6c2bf3cd7e17080034ade668d54ce304d820c2a58514a4e51d0cfd6", size = 86606, upload-time = "2025-04-17T00:42:35.873Z" }, + { url = "https://files.pythonhosted.org/packages/33/46/ca335c2e1f90446a77640a45eeb1cd8f6934f2c6e4df7db0f0f36ef9f025/yarl-1.20.0-cp311-cp311-win_amd64.whl", hash = "sha256:8c12cd754d9dbd14204c328915e23b0c361b88f3cffd124129955e60a4fbfcfb", size = 93374, upload-time = "2025-04-17T00:42:37.586Z" }, + { url = "https://files.pythonhosted.org/packages/c3/e8/3efdcb83073df978bb5b1a9cc0360ce596680e6c3fac01f2a994ccbb8939/yarl-1.20.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e06b9f6cdd772f9b665e5ba8161968e11e403774114420737f7884b5bd7bdf6f", size = 147089, upload-time = "2025-04-17T00:42:39.602Z" }, + { url = "https://files.pythonhosted.org/packages/60/c3/9e776e98ea350f76f94dd80b408eaa54e5092643dbf65fd9babcffb60509/yarl-1.20.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:b9ae2fbe54d859b3ade40290f60fe40e7f969d83d482e84d2c31b9bff03e359e", size = 97706, upload-time = "2025-04-17T00:42:41.469Z" }, + { url = "https://files.pythonhosted.org/packages/0c/5b/45cdfb64a3b855ce074ae607b9fc40bc82e7613b94e7612b030255c93a09/yarl-1.20.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6d12b8945250d80c67688602c891237994d203d42427cb14e36d1a732eda480e", size = 95719, upload-time = "2025-04-17T00:42:43.666Z" }, + { url = "https://files.pythonhosted.org/packages/2d/4e/929633b249611eeed04e2f861a14ed001acca3ef9ec2a984a757b1515889/yarl-1.20.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:087e9731884621b162a3e06dc0d2d626e1542a617f65ba7cc7aeab279d55ad33", size = 343972, upload-time = "2025-04-17T00:42:45.391Z" }, + { url = "https://files.pythonhosted.org/packages/49/fd/047535d326c913f1a90407a3baf7ff535b10098611eaef2c527e32e81ca1/yarl-1.20.0-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:69df35468b66c1a6e6556248e6443ef0ec5f11a7a4428cf1f6281f1879220f58", size = 339639, upload-time = "2025-04-17T00:42:47.552Z" }, + { url = "https://files.pythonhosted.org/packages/48/2f/11566f1176a78f4bafb0937c0072410b1b0d3640b297944a6a7a556e1d0b/yarl-1.20.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3b2992fe29002fd0d4cbaea9428b09af9b8686a9024c840b8a2b8f4ea4abc16f", size = 353745, upload-time = "2025-04-17T00:42:49.406Z" }, + { url = "https://files.pythonhosted.org/packages/26/17/07dfcf034d6ae8837b33988be66045dd52f878dfb1c4e8f80a7343f677be/yarl-1.20.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4c903e0b42aab48abfbac668b5a9d7b6938e721a6341751331bcd7553de2dcae", size = 354178, upload-time = "2025-04-17T00:42:51.588Z" }, + { url = "https://files.pythonhosted.org/packages/15/45/212604d3142d84b4065d5f8cab6582ed3d78e4cc250568ef2a36fe1cf0a5/yarl-1.20.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bf099e2432131093cc611623e0b0bcc399b8cddd9a91eded8bfb50402ec35018", size = 349219, upload-time = "2025-04-17T00:42:53.674Z" }, + { url = "https://files.pythonhosted.org/packages/e6/e0/a10b30f294111c5f1c682461e9459935c17d467a760c21e1f7db400ff499/yarl-1.20.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8a7f62f5dc70a6c763bec9ebf922be52aa22863d9496a9a30124d65b489ea672", size = 337266, upload-time = "2025-04-17T00:42:55.49Z" }, + { url = "https://files.pythonhosted.org/packages/33/a6/6efa1d85a675d25a46a167f9f3e80104cde317dfdf7f53f112ae6b16a60a/yarl-1.20.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:54ac15a8b60382b2bcefd9a289ee26dc0920cf59b05368c9b2b72450751c6eb8", size = 360873, upload-time = "2025-04-17T00:42:57.895Z" }, + { url = "https://files.pythonhosted.org/packages/77/67/c8ab718cb98dfa2ae9ba0f97bf3cbb7d45d37f13fe1fbad25ac92940954e/yarl-1.20.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:25b3bc0763a7aca16a0f1b5e8ef0f23829df11fb539a1b70476dcab28bd83da7", size = 360524, upload-time = "2025-04-17T00:43:00.094Z" }, + { url = "https://files.pythonhosted.org/packages/bd/e8/c3f18660cea1bc73d9f8a2b3ef423def8dadbbae6c4afabdb920b73e0ead/yarl-1.20.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:b2586e36dc070fc8fad6270f93242124df68b379c3a251af534030a4a33ef594", size = 365370, upload-time = "2025-04-17T00:43:02.242Z" }, + { url = "https://files.pythonhosted.org/packages/c9/99/33f3b97b065e62ff2d52817155a89cfa030a1a9b43fee7843ef560ad9603/yarl-1.20.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:866349da9d8c5290cfefb7fcc47721e94de3f315433613e01b435473be63daa6", size = 373297, upload-time = "2025-04-17T00:43:04.189Z" }, + { url = "https://files.pythonhosted.org/packages/3d/89/7519e79e264a5f08653d2446b26d4724b01198a93a74d2e259291d538ab1/yarl-1.20.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:33bb660b390a0554d41f8ebec5cd4475502d84104b27e9b42f5321c5192bfcd1", size = 378771, upload-time = "2025-04-17T00:43:06.609Z" }, + { url = "https://files.pythonhosted.org/packages/3a/58/6c460bbb884abd2917c3eef6f663a4a873f8dc6f498561fc0ad92231c113/yarl-1.20.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:737e9f171e5a07031cbee5e9180f6ce21a6c599b9d4b2c24d35df20a52fabf4b", size = 375000, upload-time = "2025-04-17T00:43:09.01Z" }, + { url = "https://files.pythonhosted.org/packages/3b/2a/dd7ed1aa23fea996834278d7ff178f215b24324ee527df53d45e34d21d28/yarl-1.20.0-cp312-cp312-win32.whl", hash = "sha256:839de4c574169b6598d47ad61534e6981979ca2c820ccb77bf70f4311dd2cc64", size = 86355, upload-time = "2025-04-17T00:43:11.311Z" }, + { url = "https://files.pythonhosted.org/packages/ca/c6/333fe0338305c0ac1c16d5aa7cc4841208d3252bbe62172e0051006b5445/yarl-1.20.0-cp312-cp312-win_amd64.whl", hash = "sha256:3d7dbbe44b443b0c4aa0971cb07dcb2c2060e4a9bf8d1301140a33a93c98e18c", size = 92904, upload-time = "2025-04-17T00:43:13.087Z" }, + { url = "https://files.pythonhosted.org/packages/ea/1f/70c57b3d7278e94ed22d85e09685d3f0a38ebdd8c5c73b65ba4c0d0fe002/yarl-1.20.0-py3-none-any.whl", hash = "sha256:5d0fe6af927a47a230f31e6004621fd0959eaa915fc62acfafa67ff7229a3124", size = 46124, upload-time = "2025-04-17T00:45:12.199Z" }, ] [[package]] @@ -5089,38 +5156,38 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi", marker = "platform_python_implementation == 'PyPy'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ed/f6/2ac0287b442160a89d726b17a9184a4c615bb5237db763791a7fd16d9df1/zstandard-0.23.0.tar.gz", hash = "sha256:b2d8c62d08e7255f68f7a740bae85b3c9b8e5466baa9cbf7f57f1cde0ac6bc09", size = 681701 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/9e/40/f67e7d2c25a0e2dc1744dd781110b0b60306657f8696cafb7ad7579469bd/zstandard-0.23.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:34895a41273ad33347b2fc70e1bff4240556de3c46c6ea430a7ed91f9042aa4e", size = 788699 }, - { url = "https://files.pythonhosted.org/packages/e8/46/66d5b55f4d737dd6ab75851b224abf0afe5774976fe511a54d2eb9063a41/zstandard-0.23.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:77ea385f7dd5b5676d7fd943292ffa18fbf5c72ba98f7d09fc1fb9e819b34c23", size = 633681 }, - { url = "https://files.pythonhosted.org/packages/63/b6/677e65c095d8e12b66b8f862b069bcf1f1d781b9c9c6f12eb55000d57583/zstandard-0.23.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:983b6efd649723474f29ed42e1467f90a35a74793437d0bc64a5bf482bedfa0a", size = 4944328 }, - { url = "https://files.pythonhosted.org/packages/59/cc/e76acb4c42afa05a9d20827116d1f9287e9c32b7ad58cc3af0721ce2b481/zstandard-0.23.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:80a539906390591dd39ebb8d773771dc4db82ace6372c4d41e2d293f8e32b8db", size = 5311955 }, - { url = "https://files.pythonhosted.org/packages/78/e4/644b8075f18fc7f632130c32e8f36f6dc1b93065bf2dd87f03223b187f26/zstandard-0.23.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:445e4cb5048b04e90ce96a79b4b63140e3f4ab5f662321975679b5f6360b90e2", size = 5344944 }, - { url = "https://files.pythonhosted.org/packages/76/3f/dbafccf19cfeca25bbabf6f2dd81796b7218f768ec400f043edc767015a6/zstandard-0.23.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd30d9c67d13d891f2360b2a120186729c111238ac63b43dbd37a5a40670b8ca", size = 5442927 }, - { url = "https://files.pythonhosted.org/packages/0c/c3/d24a01a19b6733b9f218e94d1a87c477d523237e07f94899e1c10f6fd06c/zstandard-0.23.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d20fd853fbb5807c8e84c136c278827b6167ded66c72ec6f9a14b863d809211c", size = 4864910 }, - { url = "https://files.pythonhosted.org/packages/1c/a9/cf8f78ead4597264f7618d0875be01f9bc23c9d1d11afb6d225b867cb423/zstandard-0.23.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ed1708dbf4d2e3a1c5c69110ba2b4eb6678262028afd6c6fbcc5a8dac9cda68e", size = 4935544 }, - { url = "https://files.pythonhosted.org/packages/2c/96/8af1e3731b67965fb995a940c04a2c20997a7b3b14826b9d1301cf160879/zstandard-0.23.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:be9b5b8659dff1f913039c2feee1aca499cfbc19e98fa12bc85e037c17ec6ca5", size = 5467094 }, - { url = "https://files.pythonhosted.org/packages/ff/57/43ea9df642c636cb79f88a13ab07d92d88d3bfe3e550b55a25a07a26d878/zstandard-0.23.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:65308f4b4890aa12d9b6ad9f2844b7ee42c7f7a4fd3390425b242ffc57498f48", size = 4860440 }, - { url = "https://files.pythonhosted.org/packages/46/37/edb78f33c7f44f806525f27baa300341918fd4c4af9472fbc2c3094be2e8/zstandard-0.23.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:98da17ce9cbf3bfe4617e836d561e433f871129e3a7ac16d6ef4c680f13a839c", size = 4700091 }, - { url = "https://files.pythonhosted.org/packages/c1/f1/454ac3962671a754f3cb49242472df5c2cced4eb959ae203a377b45b1a3c/zstandard-0.23.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:8ed7d27cb56b3e058d3cf684d7200703bcae623e1dcc06ed1e18ecda39fee003", size = 5208682 }, - { url = "https://files.pythonhosted.org/packages/85/b2/1734b0fff1634390b1b887202d557d2dd542de84a4c155c258cf75da4773/zstandard-0.23.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:b69bb4f51daf461b15e7b3db033160937d3ff88303a7bc808c67bbc1eaf98c78", size = 5669707 }, - { url = "https://files.pythonhosted.org/packages/52/5a/87d6971f0997c4b9b09c495bf92189fb63de86a83cadc4977dc19735f652/zstandard-0.23.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:034b88913ecc1b097f528e42b539453fa82c3557e414b3de9d5632c80439a473", size = 5201792 }, - { url = "https://files.pythonhosted.org/packages/79/02/6f6a42cc84459d399bd1a4e1adfc78d4dfe45e56d05b072008d10040e13b/zstandard-0.23.0-cp311-cp311-win32.whl", hash = "sha256:f2d4380bf5f62daabd7b751ea2339c1a21d1c9463f1feb7fc2bdcea2c29c3160", size = 430586 }, - { url = "https://files.pythonhosted.org/packages/be/a2/4272175d47c623ff78196f3c10e9dc7045c1b9caf3735bf041e65271eca4/zstandard-0.23.0-cp311-cp311-win_amd64.whl", hash = "sha256:62136da96a973bd2557f06ddd4e8e807f9e13cbb0bfb9cc06cfe6d98ea90dfe0", size = 495420 }, - { url = "https://files.pythonhosted.org/packages/7b/83/f23338c963bd9de687d47bf32efe9fd30164e722ba27fb59df33e6b1719b/zstandard-0.23.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b4567955a6bc1b20e9c31612e615af6b53733491aeaa19a6b3b37f3b65477094", size = 788713 }, - { url = "https://files.pythonhosted.org/packages/5b/b3/1a028f6750fd9227ee0b937a278a434ab7f7fdc3066c3173f64366fe2466/zstandard-0.23.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1e172f57cd78c20f13a3415cc8dfe24bf388614324d25539146594c16d78fcc8", size = 633459 }, - { url = "https://files.pythonhosted.org/packages/26/af/36d89aae0c1f95a0a98e50711bc5d92c144939efc1f81a2fcd3e78d7f4c1/zstandard-0.23.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b0e166f698c5a3e914947388c162be2583e0c638a4703fc6a543e23a88dea3c1", size = 4945707 }, - { url = "https://files.pythonhosted.org/packages/cd/2e/2051f5c772f4dfc0aae3741d5fc72c3dcfe3aaeb461cc231668a4db1ce14/zstandard-0.23.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:12a289832e520c6bd4dcaad68e944b86da3bad0d339ef7989fb7e88f92e96072", size = 5306545 }, - { url = "https://files.pythonhosted.org/packages/0a/9e/a11c97b087f89cab030fa71206963090d2fecd8eb83e67bb8f3ffb84c024/zstandard-0.23.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d50d31bfedd53a928fed6707b15a8dbeef011bb6366297cc435accc888b27c20", size = 5337533 }, - { url = "https://files.pythonhosted.org/packages/fc/79/edeb217c57fe1bf16d890aa91a1c2c96b28c07b46afed54a5dcf310c3f6f/zstandard-0.23.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:72c68dda124a1a138340fb62fa21b9bf4848437d9ca60bd35db36f2d3345f373", size = 5436510 }, - { url = "https://files.pythonhosted.org/packages/81/4f/c21383d97cb7a422ddf1ae824b53ce4b51063d0eeb2afa757eb40804a8ef/zstandard-0.23.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:53dd9d5e3d29f95acd5de6802e909ada8d8d8cfa37a3ac64836f3bc4bc5512db", size = 4859973 }, - { url = "https://files.pythonhosted.org/packages/ab/15/08d22e87753304405ccac8be2493a495f529edd81d39a0870621462276ef/zstandard-0.23.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:6a41c120c3dbc0d81a8e8adc73312d668cd34acd7725f036992b1b72d22c1772", size = 4936968 }, - { url = "https://files.pythonhosted.org/packages/eb/fa/f3670a597949fe7dcf38119a39f7da49a8a84a6f0b1a2e46b2f71a0ab83f/zstandard-0.23.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:40b33d93c6eddf02d2c19f5773196068d875c41ca25730e8288e9b672897c105", size = 5467179 }, - { url = "https://files.pythonhosted.org/packages/4e/a9/dad2ab22020211e380adc477a1dbf9f109b1f8d94c614944843e20dc2a99/zstandard-0.23.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9206649ec587e6b02bd124fb7799b86cddec350f6f6c14bc82a2b70183e708ba", size = 4848577 }, - { url = "https://files.pythonhosted.org/packages/08/03/dd28b4484b0770f1e23478413e01bee476ae8227bbc81561f9c329e12564/zstandard-0.23.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76e79bc28a65f467e0409098fa2c4376931fd3207fbeb6b956c7c476d53746dd", size = 4693899 }, - { url = "https://files.pythonhosted.org/packages/2b/64/3da7497eb635d025841e958bcd66a86117ae320c3b14b0ae86e9e8627518/zstandard-0.23.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:66b689c107857eceabf2cf3d3fc699c3c0fe8ccd18df2219d978c0283e4c508a", size = 5199964 }, - { url = "https://files.pythonhosted.org/packages/43/a4/d82decbab158a0e8a6ebb7fc98bc4d903266bce85b6e9aaedea1d288338c/zstandard-0.23.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9c236e635582742fee16603042553d276cca506e824fa2e6489db04039521e90", size = 5655398 }, - { url = "https://files.pythonhosted.org/packages/f2/61/ac78a1263bc83a5cf29e7458b77a568eda5a8f81980691bbc6eb6a0d45cc/zstandard-0.23.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a8fffdbd9d1408006baaf02f1068d7dd1f016c6bcb7538682622c556e7b68e35", size = 5191313 }, - { url = "https://files.pythonhosted.org/packages/e7/54/967c478314e16af5baf849b6ee9d6ea724ae5b100eb506011f045d3d4e16/zstandard-0.23.0-cp312-cp312-win32.whl", hash = "sha256:dc1d33abb8a0d754ea4763bad944fd965d3d95b5baef6b121c0c9013eaf1907d", size = 430877 }, - { url = "https://files.pythonhosted.org/packages/75/37/872d74bd7739639c4553bf94c84af7d54d8211b626b352bc57f0fd8d1e3f/zstandard-0.23.0-cp312-cp312-win_amd64.whl", hash = "sha256:64585e1dba664dc67c7cdabd56c1e5685233fbb1fc1966cfba2a340ec0dfff7b", size = 495595 }, +sdist = { url = "https://files.pythonhosted.org/packages/ed/f6/2ac0287b442160a89d726b17a9184a4c615bb5237db763791a7fd16d9df1/zstandard-0.23.0.tar.gz", hash = "sha256:b2d8c62d08e7255f68f7a740bae85b3c9b8e5466baa9cbf7f57f1cde0ac6bc09", size = 681701, upload-time = "2024-07-15T00:18:06.141Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/9e/40/f67e7d2c25a0e2dc1744dd781110b0b60306657f8696cafb7ad7579469bd/zstandard-0.23.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:34895a41273ad33347b2fc70e1bff4240556de3c46c6ea430a7ed91f9042aa4e", size = 788699, upload-time = "2024-07-15T00:14:04.909Z" }, + { url = "https://files.pythonhosted.org/packages/e8/46/66d5b55f4d737dd6ab75851b224abf0afe5774976fe511a54d2eb9063a41/zstandard-0.23.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:77ea385f7dd5b5676d7fd943292ffa18fbf5c72ba98f7d09fc1fb9e819b34c23", size = 633681, upload-time = "2024-07-15T00:14:13.99Z" }, + { url = "https://files.pythonhosted.org/packages/63/b6/677e65c095d8e12b66b8f862b069bcf1f1d781b9c9c6f12eb55000d57583/zstandard-0.23.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:983b6efd649723474f29ed42e1467f90a35a74793437d0bc64a5bf482bedfa0a", size = 4944328, upload-time = "2024-07-15T00:14:16.588Z" }, + { url = "https://files.pythonhosted.org/packages/59/cc/e76acb4c42afa05a9d20827116d1f9287e9c32b7ad58cc3af0721ce2b481/zstandard-0.23.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:80a539906390591dd39ebb8d773771dc4db82ace6372c4d41e2d293f8e32b8db", size = 5311955, upload-time = "2024-07-15T00:14:19.389Z" }, + { url = "https://files.pythonhosted.org/packages/78/e4/644b8075f18fc7f632130c32e8f36f6dc1b93065bf2dd87f03223b187f26/zstandard-0.23.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:445e4cb5048b04e90ce96a79b4b63140e3f4ab5f662321975679b5f6360b90e2", size = 5344944, upload-time = "2024-07-15T00:14:22.173Z" }, + { url = "https://files.pythonhosted.org/packages/76/3f/dbafccf19cfeca25bbabf6f2dd81796b7218f768ec400f043edc767015a6/zstandard-0.23.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd30d9c67d13d891f2360b2a120186729c111238ac63b43dbd37a5a40670b8ca", size = 5442927, upload-time = "2024-07-15T00:14:24.825Z" }, + { url = "https://files.pythonhosted.org/packages/0c/c3/d24a01a19b6733b9f218e94d1a87c477d523237e07f94899e1c10f6fd06c/zstandard-0.23.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d20fd853fbb5807c8e84c136c278827b6167ded66c72ec6f9a14b863d809211c", size = 4864910, upload-time = "2024-07-15T00:14:26.982Z" }, + { url = "https://files.pythonhosted.org/packages/1c/a9/cf8f78ead4597264f7618d0875be01f9bc23c9d1d11afb6d225b867cb423/zstandard-0.23.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ed1708dbf4d2e3a1c5c69110ba2b4eb6678262028afd6c6fbcc5a8dac9cda68e", size = 4935544, upload-time = "2024-07-15T00:14:29.582Z" }, + { url = "https://files.pythonhosted.org/packages/2c/96/8af1e3731b67965fb995a940c04a2c20997a7b3b14826b9d1301cf160879/zstandard-0.23.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:be9b5b8659dff1f913039c2feee1aca499cfbc19e98fa12bc85e037c17ec6ca5", size = 5467094, upload-time = "2024-07-15T00:14:40.126Z" }, + { url = "https://files.pythonhosted.org/packages/ff/57/43ea9df642c636cb79f88a13ab07d92d88d3bfe3e550b55a25a07a26d878/zstandard-0.23.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:65308f4b4890aa12d9b6ad9f2844b7ee42c7f7a4fd3390425b242ffc57498f48", size = 4860440, upload-time = "2024-07-15T00:14:42.786Z" }, + { url = "https://files.pythonhosted.org/packages/46/37/edb78f33c7f44f806525f27baa300341918fd4c4af9472fbc2c3094be2e8/zstandard-0.23.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:98da17ce9cbf3bfe4617e836d561e433f871129e3a7ac16d6ef4c680f13a839c", size = 4700091, upload-time = "2024-07-15T00:14:45.184Z" }, + { url = "https://files.pythonhosted.org/packages/c1/f1/454ac3962671a754f3cb49242472df5c2cced4eb959ae203a377b45b1a3c/zstandard-0.23.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:8ed7d27cb56b3e058d3cf684d7200703bcae623e1dcc06ed1e18ecda39fee003", size = 5208682, upload-time = "2024-07-15T00:14:47.407Z" }, + { url = "https://files.pythonhosted.org/packages/85/b2/1734b0fff1634390b1b887202d557d2dd542de84a4c155c258cf75da4773/zstandard-0.23.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:b69bb4f51daf461b15e7b3db033160937d3ff88303a7bc808c67bbc1eaf98c78", size = 5669707, upload-time = "2024-07-15T00:15:03.529Z" }, + { url = "https://files.pythonhosted.org/packages/52/5a/87d6971f0997c4b9b09c495bf92189fb63de86a83cadc4977dc19735f652/zstandard-0.23.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:034b88913ecc1b097f528e42b539453fa82c3557e414b3de9d5632c80439a473", size = 5201792, upload-time = "2024-07-15T00:15:28.372Z" }, + { url = "https://files.pythonhosted.org/packages/79/02/6f6a42cc84459d399bd1a4e1adfc78d4dfe45e56d05b072008d10040e13b/zstandard-0.23.0-cp311-cp311-win32.whl", hash = "sha256:f2d4380bf5f62daabd7b751ea2339c1a21d1c9463f1feb7fc2bdcea2c29c3160", size = 430586, upload-time = "2024-07-15T00:15:32.26Z" }, + { url = "https://files.pythonhosted.org/packages/be/a2/4272175d47c623ff78196f3c10e9dc7045c1b9caf3735bf041e65271eca4/zstandard-0.23.0-cp311-cp311-win_amd64.whl", hash = "sha256:62136da96a973bd2557f06ddd4e8e807f9e13cbb0bfb9cc06cfe6d98ea90dfe0", size = 495420, upload-time = "2024-07-15T00:15:34.004Z" }, + { url = "https://files.pythonhosted.org/packages/7b/83/f23338c963bd9de687d47bf32efe9fd30164e722ba27fb59df33e6b1719b/zstandard-0.23.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b4567955a6bc1b20e9c31612e615af6b53733491aeaa19a6b3b37f3b65477094", size = 788713, upload-time = "2024-07-15T00:15:35.815Z" }, + { url = "https://files.pythonhosted.org/packages/5b/b3/1a028f6750fd9227ee0b937a278a434ab7f7fdc3066c3173f64366fe2466/zstandard-0.23.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1e172f57cd78c20f13a3415cc8dfe24bf388614324d25539146594c16d78fcc8", size = 633459, upload-time = "2024-07-15T00:15:37.995Z" }, + { url = "https://files.pythonhosted.org/packages/26/af/36d89aae0c1f95a0a98e50711bc5d92c144939efc1f81a2fcd3e78d7f4c1/zstandard-0.23.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b0e166f698c5a3e914947388c162be2583e0c638a4703fc6a543e23a88dea3c1", size = 4945707, upload-time = "2024-07-15T00:15:39.872Z" }, + { url = "https://files.pythonhosted.org/packages/cd/2e/2051f5c772f4dfc0aae3741d5fc72c3dcfe3aaeb461cc231668a4db1ce14/zstandard-0.23.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:12a289832e520c6bd4dcaad68e944b86da3bad0d339ef7989fb7e88f92e96072", size = 5306545, upload-time = "2024-07-15T00:15:41.75Z" }, + { url = "https://files.pythonhosted.org/packages/0a/9e/a11c97b087f89cab030fa71206963090d2fecd8eb83e67bb8f3ffb84c024/zstandard-0.23.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d50d31bfedd53a928fed6707b15a8dbeef011bb6366297cc435accc888b27c20", size = 5337533, upload-time = "2024-07-15T00:15:44.114Z" }, + { url = "https://files.pythonhosted.org/packages/fc/79/edeb217c57fe1bf16d890aa91a1c2c96b28c07b46afed54a5dcf310c3f6f/zstandard-0.23.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:72c68dda124a1a138340fb62fa21b9bf4848437d9ca60bd35db36f2d3345f373", size = 5436510, upload-time = "2024-07-15T00:15:46.509Z" }, + { url = "https://files.pythonhosted.org/packages/81/4f/c21383d97cb7a422ddf1ae824b53ce4b51063d0eeb2afa757eb40804a8ef/zstandard-0.23.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:53dd9d5e3d29f95acd5de6802e909ada8d8d8cfa37a3ac64836f3bc4bc5512db", size = 4859973, upload-time = "2024-07-15T00:15:49.939Z" }, + { url = "https://files.pythonhosted.org/packages/ab/15/08d22e87753304405ccac8be2493a495f529edd81d39a0870621462276ef/zstandard-0.23.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:6a41c120c3dbc0d81a8e8adc73312d668cd34acd7725f036992b1b72d22c1772", size = 4936968, upload-time = "2024-07-15T00:15:52.025Z" }, + { url = "https://files.pythonhosted.org/packages/eb/fa/f3670a597949fe7dcf38119a39f7da49a8a84a6f0b1a2e46b2f71a0ab83f/zstandard-0.23.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:40b33d93c6eddf02d2c19f5773196068d875c41ca25730e8288e9b672897c105", size = 5467179, upload-time = "2024-07-15T00:15:54.971Z" }, + { url = "https://files.pythonhosted.org/packages/4e/a9/dad2ab22020211e380adc477a1dbf9f109b1f8d94c614944843e20dc2a99/zstandard-0.23.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9206649ec587e6b02bd124fb7799b86cddec350f6f6c14bc82a2b70183e708ba", size = 4848577, upload-time = "2024-07-15T00:15:57.634Z" }, + { url = "https://files.pythonhosted.org/packages/08/03/dd28b4484b0770f1e23478413e01bee476ae8227bbc81561f9c329e12564/zstandard-0.23.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76e79bc28a65f467e0409098fa2c4376931fd3207fbeb6b956c7c476d53746dd", size = 4693899, upload-time = "2024-07-15T00:16:00.811Z" }, + { url = "https://files.pythonhosted.org/packages/2b/64/3da7497eb635d025841e958bcd66a86117ae320c3b14b0ae86e9e8627518/zstandard-0.23.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:66b689c107857eceabf2cf3d3fc699c3c0fe8ccd18df2219d978c0283e4c508a", size = 5199964, upload-time = "2024-07-15T00:16:03.669Z" }, + { url = "https://files.pythonhosted.org/packages/43/a4/d82decbab158a0e8a6ebb7fc98bc4d903266bce85b6e9aaedea1d288338c/zstandard-0.23.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9c236e635582742fee16603042553d276cca506e824fa2e6489db04039521e90", size = 5655398, upload-time = "2024-07-15T00:16:06.694Z" }, + { url = "https://files.pythonhosted.org/packages/f2/61/ac78a1263bc83a5cf29e7458b77a568eda5a8f81980691bbc6eb6a0d45cc/zstandard-0.23.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a8fffdbd9d1408006baaf02f1068d7dd1f016c6bcb7538682622c556e7b68e35", size = 5191313, upload-time = "2024-07-15T00:16:09.758Z" }, + { url = "https://files.pythonhosted.org/packages/e7/54/967c478314e16af5baf849b6ee9d6ea724ae5b100eb506011f045d3d4e16/zstandard-0.23.0-cp312-cp312-win32.whl", hash = "sha256:dc1d33abb8a0d754ea4763bad944fd965d3d95b5baef6b121c0c9013eaf1907d", size = 430877, upload-time = "2024-07-15T00:16:11.758Z" }, + { url = "https://files.pythonhosted.org/packages/75/37/872d74bd7739639c4553bf94c84af7d54d8211b626b352bc57f0fd8d1e3f/zstandard-0.23.0-cp312-cp312-win_amd64.whl", hash = "sha256:64585e1dba664dc67c7cdabd56c1e5685233fbb1fc1966cfba2a340ec0dfff7b", size = 495595, upload-time = "2024-07-15T00:16:13.731Z" }, ]